From 668d7fd496bd98cc35154bf101054f8973d4a525 Mon Sep 17 00:00:00 2001 From: doterop Date: Mon, 11 Jan 2021 17:48:19 +0100 Subject: [PATCH 001/569] Added exception to register crosswalks --- .../Carla/Util/BoundingBoxCalculator.cpp | 19 ++++++++++++------- 1 file changed, 12 insertions(+), 7 deletions(-) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/BoundingBoxCalculator.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/BoundingBoxCalculator.cpp index e7bd62932..452e2ad27 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/BoundingBoxCalculator.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/BoundingBoxCalculator.cpp @@ -319,7 +319,7 @@ void UBoundingBoxCalculator::GetISMBoundingBox( const UStaticMesh *Mesh = ISMComp->GetStaticMesh(); const FBoundingBox SMBoundingBox = GetStaticMeshBoundingBox(Mesh); - if(SMBoundingBox.Extent.IsZero()) + if(!Mesh) { UE_LOG(LogCarla, Error, TEXT("%s has no SM assigned to the ISM"), *ISMComp->GetOwner()->GetName()); return; @@ -351,8 +351,13 @@ void UBoundingBoxCalculator::GetBBsOfStaticMeshComponents( for(UStaticMeshComponent* Comp : StaticMeshComps) { + bool isCrosswalk = Comp->GetOwner()->GetName().Contains("crosswalk"); + // Avoid duplication with SMComp and not visible meshes - if(!Comp->IsVisible() || Cast(Comp)) continue; + if( (!Comp->IsVisible() && !isCrosswalk) || Cast(Comp)) + { + continue; + } // Filter by tag crp::CityObjectLabel Tag = ATagger::GetTagOfTaggedComponent(*Comp); @@ -361,11 +366,7 @@ void UBoundingBoxCalculator::GetBBsOfStaticMeshComponents( UStaticMesh* StaticMesh = Comp->GetStaticMesh(); FBoundingBox BoundingBox = GetStaticMeshBoundingBox(StaticMesh); - if(BoundingBox.Extent.IsZero()) - { - // UE_LOG(LogCarla, Error, TEXT("%s has no SM assigned"), *Comp->GetOwner()->GetName()); - } - else + if(StaticMesh) { // Component-to-world transform for this component const FTransform& CompToWorldTransform = Comp->GetComponentTransform(); @@ -373,6 +374,10 @@ void UBoundingBoxCalculator::GetBBsOfStaticMeshComponents( OutBB.Emplace(BoundingBox); OutTag.Emplace(static_cast(Tag)); } + else + { + // UE_LOG(LogCarla, Error, TEXT("%s has no SM assigned"), *Comp->GetOwner()->GetName()); + } } } From 704c710f3ed4233f243727ef0c6c97e0bd7033fa Mon Sep 17 00:00:00 2001 From: doterop Date: Mon, 11 Jan 2021 18:02:10 +0100 Subject: [PATCH 002/569] Removed comment --- .../Plugins/Carla/Source/Carla/Util/BoundingBoxCalculator.cpp | 4 ---- 1 file changed, 4 deletions(-) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/BoundingBoxCalculator.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/BoundingBoxCalculator.cpp index 452e2ad27..9efc22fd8 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/BoundingBoxCalculator.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/BoundingBoxCalculator.cpp @@ -374,10 +374,6 @@ void UBoundingBoxCalculator::GetBBsOfStaticMeshComponents( OutBB.Emplace(BoundingBox); OutTag.Emplace(static_cast(Tag)); } - else - { - // UE_LOG(LogCarla, Error, TEXT("%s has no SM assigned"), *Comp->GetOwner()->GetName()); - } } } From ee77b3afa683a4366d84e788afb9c76bf7b71642 Mon Sep 17 00:00:00 2001 From: corkyw10 Date: Mon, 11 Jan 2021 17:08:30 +0100 Subject: [PATCH 003/569] CarSim tutorial refactoring and name change to bring in line with other tutorials --- Docs/carsim_integration.md | 129 --------------------------- Docs/tuto_G_carsim_integration.md | 143 ++++++++++++++++++++++++++++++ mkdocs.yml | 2 +- 3 files changed, 144 insertions(+), 130 deletions(-) delete mode 100644 Docs/carsim_integration.md create mode 100644 Docs/tuto_G_carsim_integration.md diff --git a/Docs/carsim_integration.md b/Docs/carsim_integration.md deleted file mode 100644 index 0bdd0c998..000000000 --- a/Docs/carsim_integration.md +++ /dev/null @@ -1,129 +0,0 @@ -# CARSIM Integration (Beta) - -This integration allows CARLA to forward all vehicle controls to CarSim in order to make all -the physics calculations of the vehicle and send back the new state of the vehicle to CARLA. - -* [__Requisites__](#requisites) -* [__Setup Carsim__](#set-up-carsim) - * [__SIM file__](#sim-file) - * [__On Windows__](#on-windows) - * [__On Ubuntu__](#on-ubuntu) - * [__Vehicle Sizes__](#vehicle-sizes) -* [__Run Simulation__](#run-simulation) - ---- -## Requisites - -* [CarSim](https://www.carsim.com/products/carsim/index.php) software + licence -* Unreal 4.24 plugin (version 2020.0): [Vehicle dynamics](https://www.unrealengine.com/marketplace/en-US/product/carsim-vehicle-dynamics) -* CARLA compiled with flag **--carsim** (CARLA packages are CarSim ready) - -It is necessary to have a licence for CarSim software set up and running. - -For the communication with Unreal it is necessary to install the free plugin in UE called [**vehicle -dynamics**](https://www.unrealengine.com/marketplace/en-US/product/carsim-vehicle-dynamics). -* **For Ubuntu** only: - 1) Download the plugin version 2020.0 from [here](https://www.carsim.com/users/unreal_plugin/unreal_plugin_2020_0.php) - 2) After downloading the plugin replace the file **CarSim.Build.cs** with the one [here](https://carla-releases.s3.eu-west-3.amazonaws.com/Backup/CarSim.Build.cs). We added the proper solver to use. - -If you use CARLA from source, then you need to compile the server with the **--carsim** flag: -```sh -make CarlaUE4Editor ARGS="--carsim" -``` -All packages are already compiled with the **--carsim** flag, so they are ready to use with CarSim. - -## Set Up CarSim -#### SIM File - -You need to generate the .sim file that describes the simulation to run in both CARLA and -CarSim. The CarSim plugin needs this file to know about the simulation to run. - -##### On Windows - -You can use the GUI to generate the file once you have all the parameters configured. - -![generate .sim file](img/carsim_generate.jpg) - -For Windows systems, a **.sim** file looks like this: - -``` -SIMFILE - -SET_MACRO $(ROOT_FILE_NAME)$ Run_dd7a828d-4b14-4c77-9d09-1974401d6b25 -SET_MACRO $(OUTPUT_PATH)$ D:\carsim\Data\Results -SET_MACRO $(WORK_DIR)$ D:\carsim\Data\ -SET_MACRO $(OUTPUT_FILE_PREFIX)$ $(WORK_DIR)$Results\Run_dd7a828d-4b14-4c77-9d09-1974401d6b25\LastRun - -FILEBASE $(OUTPUT_FILE_PREFIX)$ -INPUT $(WORK_DIR)$Results\$(ROOT_FILE_NAME)$\Run_all.par -INPUTARCHIVE $(OUTPUT_FILE_PREFIX)$_all.par -ECHO $(OUTPUT_FILE_PREFIX)$_echo.par -FINAL $(OUTPUT_FILE_PREFIX)$_end.par -LOGFILE $(OUTPUT_FILE_PREFIX)$_log.txt -ERDFILE $(OUTPUT_FILE_PREFIX)$.vs -PROGDIR D:\carsim\ -DATADIR D:\carsim\Data\ -GUI_REFRESH_V CarSim_RefreshEvent_7760 -RESOURCEDIR D:\carsim\\Resources\ -PRODUCT_ID CarSim -PRODUCT_VER 2020.0 -ANIFILE D:\carsim\Data\runs\animator.par -VEHICLE_CODE i_i -EXT_MODEL_STEP 0.00050000 -PORTS_IMP 0 -PORTS_EXP 0 - -DLLFILE D:\carsim\Programs\solvers\carsim_64.dll -END -``` -##### On Ubuntu -For Ubuntu there is no way to create these files via GUI. You need to generate them in Windows and -move the related .par, .txt, .vs files to Ubuntu. You then need to modify the .sim file so that the -variables `INPUT`, `INPUTARCHIVE`, `LOGFILE`, etc point towards the same files in your Ubuntu -system. Finally, you need to replace the `DLLFILE` line to point towards the CarSim solver which -in the default installation will be `SOFILE /opt/carsim_2020.0/lib64/libcarsim.so.2020.0`. Your .sim -file should be similar to this: - -``` -SIMFILE - -FILEBASE /path/to/LastRun -INPUT /path/to/Run_all.par -INPUTARCHIVE /path/to/LastRun_all.par -ECHO /path/to/LastRun_echo.par -FINAL /path/to/LastRun_end.par -LOGFILE /path/to/LastRun_log.txt -ERDFILE /path/to/LastRun.vs -PROGDIR /opt/carsim_2020.0/lib64/ -DATADIR . -PRODUCT_ID CarSim -PRODUCT_VER 2020.0 -VEHICLE_CODE i_i - -SOFILE /opt/carsim_2020.0/lib64/libcarsim.so.2020.0 -END -``` -#### Vehicle Sizes - -Care needs to be taken regarding the sizes of vehicles. CarSim lets you specify the dimensions of -the vehicle to use, but currently there is no correlation between a CarSim vehicle and a CARLA -vehicle. That means that the vehicles in both parts have different dimensions, and the CARLA vehicle is only used as a placeholder in the simulation. - -![carsim vehicle sizes](img/carsim_vehicle_sizes.jpg) - -## Run Simulation - -You only need to spawn a CARLA vehicle and enable CarSim on it with the Python API function - -```sh -vehicle.enable_carsim() -``` - -Now all input controls sent to the vehicle will be forwarded to CarSim, which will update the -physics and send back the status of the vehicle (the transform) to the CARLA vehicle. - -Once the simulation has finished you can analyze all the data in CarSim as usual. - -![carsim analysis](img/carsim_analysis.jpg) - - diff --git a/Docs/tuto_G_carsim_integration.md b/Docs/tuto_G_carsim_integration.md new file mode 100644 index 000000000..f2d35bde8 --- /dev/null +++ b/Docs/tuto_G_carsim_integration.md @@ -0,0 +1,143 @@ +# CarSim Integration (Beta) + +CARLA's integration with CarSim allows vehicle controls in CARLA to be forwarded to CarSim. CarSim will do all required physics calculations of the vehicle and return the new state to CARLA. + +This page shows you how to generate a `.sim` file, explains how vehicle dimensions relate between CARLA and CarSim and how to run a simulation on CARLA using the CarSim integration. + +!!! Warning + This feature is in beta release. This means that development of the feature is ongoing and some aspects of the feature may not work as expected. If you come across any problems feel free to open an issue on [GitHub](https://github.com/carla-simulator/carla). + +* [__Before you begin__](#before-you-begin) +* [__Set up CarSim__](#set-up-carsim) + * [__Generate the .sim file__](#generate-the-sim-file) + * [__On Windows__](#on-windows) + * [__On Ubuntu__](#on-ubuntu) + * [__Vehicle sizes__](#vehicle-sizes) +* [__Run the simulation__](#run-the-simulation) + +--- +## Before you begin + +1. You will need a license for CarSim and to have the software up and running. If you don't currently have a license for CarSim, you can contact the team [here](https://www.carsim.com/forms/additional_information.php) for information. +2. To allow communication with Unreal Engine you will need to install the VehicleSim Dynamics plugin (version 2020.0) for Unreal Engine 4.24. For information on finding specific versions of the plugin, check this [link](https://www.carsim.com/products/supporting/unreal/index.php). Installation of the plugin will depend on your operating system: + + __For Windows__: + + Get the plugin [here](https://www.unrealengine.com/marketplace/en-US/product/carsim-vehicle-dynamics). + + __For Ubuntu__: + + 1. Download the plugin [here](https://www.carsim.com/users/unreal_plugin/unreal_plugin_2020_0.php). + 2. Replace the file `CarSim.Build.cs` with the file found [here](https://carla-releases.s3.eu-west-3.amazonaws.com/Backup/CarSim.Build.cs) in order to use the correct solver for Ubuntu. + +3. If you have built CARLA from source then you will need to compile the server with the `--carsim` flag. This step can be skipped if you are using the packaged version of CARLA. The packaged version has already been compiled using this flag. + + To compile the server with the `--carsim` flag in the source version of CARLA, run the following command: + +```sh + make launch ARGS="--carsim" +``` + +## Set up CarSim + +The following section details how to generate the `.sim` file which is required to run the simulation. There is also important information detailed regarding the relationship of vehicle sizes between CARLA and CarSim. + +#### Generate the .sim file + +The `.sim` file describes the simulation to be run in both CARLA and CarSim. This file is required by the plugin to run the simulation. There is currently no way to generate this file on Ubuntu, however we will describe below how to use a previously generated file to run the simulation on Ubuntu. + +##### On Windows + +After you have configured all the parameters on CarSim, use the GUI to generate the `.sim` file as highlighted below: + +![generate .sim file](img/carsim_generate.jpg) + +The resulting `.sim` file should look something like this: + +``` +SIMFILE + +SET_MACRO $(ROOT_FILE_NAME)$ Run_dd7a828d-4b14-4c77-9d09-1974401d6b25 +SET_MACRO $(OUTPUT_PATH)$ D:\carsim\Data\Results +SET_MACRO $(WORK_DIR)$ D:\carsim\Data\ +SET_MACRO $(OUTPUT_FILE_PREFIX)$ $(WORK_DIR)$Results\Run_dd7a828d-4b14-4c77-9d09-1974401d6b25\LastRun + +FILEBASE $(OUTPUT_FILE_PREFIX)$ +INPUT $(WORK_DIR)$Results\$(ROOT_FILE_NAME)$\Run_all.par +INPUTARCHIVE $(OUTPUT_FILE_PREFIX)$_all.par +ECHO $(OUTPUT_FILE_PREFIX)$_echo.par +FINAL $(OUTPUT_FILE_PREFIX)$_end.par +LOGFILE $(OUTPUT_FILE_PREFIX)$_log.txt +ERDFILE $(OUTPUT_FILE_PREFIX)$.vs +PROGDIR D:\carsim\ +DATADIR D:\carsim\Data\ +GUI_REFRESH_V CarSim_RefreshEvent_7760 +RESOURCEDIR D:\carsim\\Resources\ +PRODUCT_ID CarSim +PRODUCT_VER 2020.0 +ANIFILE D:\carsim\Data\runs\animator.par +VEHICLE_CODE i_i +EXT_MODEL_STEP 0.00050000 +PORTS_IMP 0 +PORTS_EXP 0 + +DLLFILE D:\carsim\Programs\solvers\carsim_64.dll +END +``` +##### On Ubuntu + +There is no way to create the `.sim` file via GUI on Ubuntu. In order to proceed you will need to follow these steps: + +1. Generate the `.sim` file in Windows +2. Move the related `.par`, `.txt` and `.vs` files to Ubuntu. +3. Modify the `.sim` file so the variables `INPUT`, `INPUTARCHIVE`, `LOGFILE` and so on point towards the corresponding files in your Ubuntu +system. +4. Replace the `DLLFILE` line to point towards the CarSim solver which, in the default installation, will be `SOFILE /opt/carsim_2020.0/lib64/libcarsim.so.2020.0`. + +The resulting file should be similar to this: + +``` +SIMFILE + +FILEBASE /path/to/LastRun +INPUT /path/to/Run_all.par +INPUTARCHIVE /path/to/LastRun_all.par +ECHO /path/to/LastRun_echo.par +FINAL /path/to/LastRun_end.par +LOGFILE /path/to/LastRun_log.txt +ERDFILE /path/to/LastRun.vs +PROGDIR /opt/carsim_2020.0/lib64/ +DATADIR . +PRODUCT_ID CarSim +PRODUCT_VER 2020.0 +VEHICLE_CODE i_i + +SOFILE /opt/carsim_2020.0/lib64/libcarsim.so.2020.0 +END +``` +#### Vehicle sizes + +Although CarSim lets you specify the dimensions of the vehicle to use in the simulation, there is currently no correlation between a CarSim vehicle and a CARLA +vehicle. This means that the vehicles in both programmes will have different dimensions. The role of the CARLA vehicle is only to act as a placeholder during the simulation. + +![carsim vehicle sizes](img/carsim_vehicle_sizes.jpg) + +!!! Note + There is no correlation between vehicle size in CARLA and CarSim. The CARLA vehicle is only a simulation placeholder. + +## Run the simulation + +All that is needed when running the simulation is to enable CarSim when you spawn a vehicle. This can be done by passing the path to the `.sim` file to the following [method](https://carla.readthedocs.io/en/latest/python_api/#carla.Vehicle.enable_carsim) of the Python API: + +```sh +vehicle.enable_carsim() +``` + +All input controls sent to the vehicle will be forwarded to CarSim. CarSim will update the +physics and send back the status of the vehicle (the transform) to the CARLA vehicle. + +Once the simulation has finished you can analyze all the data in CarSim as usual. + +![carsim analysis](img/carsim_analysis.jpg) + + diff --git a/mkdocs.yml b/mkdocs.yml index 8dd37b5c9..59d3f69cc 100644 --- a/mkdocs.yml +++ b/mkdocs.yml @@ -50,7 +50,7 @@ nav: - 'Control walker skeletons': "tuto_G_control_walker_skeletons.md" - 'Generate maps with OpenStreetMap': 'tuto_G_openstreetmap.md' - 'Retrieve simulation data': "tuto_G_retrieve_data.md" - - 'CarSim Integration (Beta)': "carsim_integration.md" + - 'CarSim Integration (Beta)': "tuto_G_carsim_integration.md" - Tutorials (assets): - 'Add a new map': 'tuto_A_add_map.md' - 'Add a new vehicle': 'tuto_A_add_vehicle.md' From 812d888faf5e892993b917e2fc3bf245c7d90a1f Mon Sep 17 00:00:00 2001 From: corkyw10 Date: Tue, 12 Jan 2021 09:46:45 +0100 Subject: [PATCH 004/569] Removed reference to .par files etc on Ubuntu and instructed users to use the .sim template provided. Clarified where to run the make launch command --- Docs/tuto_G_carsim_integration.md | 9 ++++----- 1 file changed, 4 insertions(+), 5 deletions(-) diff --git a/Docs/tuto_G_carsim_integration.md b/Docs/tuto_G_carsim_integration.md index f2d35bde8..158fc23b6 100644 --- a/Docs/tuto_G_carsim_integration.md +++ b/Docs/tuto_G_carsim_integration.md @@ -32,7 +32,7 @@ This page shows you how to generate a `.sim` file, explains how vehicle dimensio 3. If you have built CARLA from source then you will need to compile the server with the `--carsim` flag. This step can be skipped if you are using the packaged version of CARLA. The packaged version has already been compiled using this flag. - To compile the server with the `--carsim` flag in the source version of CARLA, run the following command: + To compile the server with the `--carsim` flag in the source build version of CARLA, run the following command in the root folder of CARLA: ```sh make launch ARGS="--carsim" @@ -88,11 +88,10 @@ END There is no way to create the `.sim` file via GUI on Ubuntu. In order to proceed you will need to follow these steps: -1. Generate the `.sim` file in Windows -2. Move the related `.par`, `.txt` and `.vs` files to Ubuntu. -3. Modify the `.sim` file so the variables `INPUT`, `INPUTARCHIVE`, `LOGFILE` and so on point towards the corresponding files in your Ubuntu +1. Generate the `.sim` file in Windows or use the file template below. +2. Modify the `.sim` file so the variables `INPUT`, `INPUTARCHIVE`, `LOGFILE` and so on point towards the corresponding files in your Ubuntu system. -4. Replace the `DLLFILE` line to point towards the CarSim solver which, in the default installation, will be `SOFILE /opt/carsim_2020.0/lib64/libcarsim.so.2020.0`. +3. Replace the `DLLFILE` line to point towards the CarSim solver which, in the default installation, will be `SOFILE /opt/carsim_2020.0/lib64/libcarsim.so.2020.0`. The resulting file should be similar to this: From 0d0ef5a907cb3a10b238bed0b2523e9730d49976 Mon Sep 17 00:00:00 2001 From: corkyw10 Date: Tue, 12 Jan 2021 10:52:49 +0100 Subject: [PATCH 005/569] Changed the CARLA compile with flag wording to be clearer --- Docs/tuto_G_carsim_integration.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Docs/tuto_G_carsim_integration.md b/Docs/tuto_G_carsim_integration.md index 158fc23b6..78625e7a0 100644 --- a/Docs/tuto_G_carsim_integration.md +++ b/Docs/tuto_G_carsim_integration.md @@ -30,9 +30,9 @@ This page shows you how to generate a `.sim` file, explains how vehicle dimensio 1. Download the plugin [here](https://www.carsim.com/users/unreal_plugin/unreal_plugin_2020_0.php). 2. Replace the file `CarSim.Build.cs` with the file found [here](https://carla-releases.s3.eu-west-3.amazonaws.com/Backup/CarSim.Build.cs) in order to use the correct solver for Ubuntu. -3. If you have built CARLA from source then you will need to compile the server with the `--carsim` flag. This step can be skipped if you are using the packaged version of CARLA. The packaged version has already been compiled using this flag. +3. This step can be skipped if you are using the packaged version of CARLA. The packaged version has already been compiled using this flag but if you are building CARLA from source then you will need to compile the server with the `--carsim` flag. - To compile the server with the `--carsim` flag in the source build version of CARLA, run the following command in the root folder of CARLA: + If you are building CARLA from source, run the following command in the root folder to compile the server with the `--carsim` flag: ```sh make launch ARGS="--carsim" From 458761605eab3ae3817747ec4746f9353fb03d77 Mon Sep 17 00:00:00 2001 From: bernat Date: Tue, 15 Dec 2020 17:04:37 +0100 Subject: [PATCH 006/569] Upgrade UE4 API function to get the project directory --- .../Carla/Commandlet/PrepareAssetsForCookingCommandlet.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Commandlet/PrepareAssetsForCookingCommandlet.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Commandlet/PrepareAssetsForCookingCommandlet.cpp index e7be88015..a8b2e6dbe 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Commandlet/PrepareAssetsForCookingCommandlet.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Commandlet/PrepareAssetsForCookingCommandlet.cpp @@ -379,7 +379,7 @@ void UPrepareAssetsForCookingCommandlet::GenerateMapPathsFile( if (Map.Path.StartsWith(TEXT("/Game/"))) { // replacing relative /Game/... address by absolute address to be able to parse files - FString FullPath(FPaths::GameDir() + TEXT("/Content/") + Map.Path.Mid(6, Map.Path.Len() - 6) + TEXT("/Sublevels/") + Map.Name); + FString FullPath(FPaths::ProjectDir() + TEXT("/Content/") + Map.Path.Mid(6, Map.Path.Len() - 6) + TEXT("/Sublevels/") + Map.Name); TArray Sublevels; FileManager.FindFiles(Sublevels, *FullPath, TEXT("*.umap")); for (auto Sublevel : Sublevels) From f9ca7b55772d7218c4eab8f14629e51ea0c5fa29 Mon Sep 17 00:00:00 2001 From: bernat Date: Fri, 8 Jan 2021 17:54:14 +0100 Subject: [PATCH 007/569] Make /Plugins/ folder optional when packaging --- Util/BuildTools/Package.bat | 6 ++++-- Util/BuildTools/Package.sh | 4 +++- 2 files changed, 7 insertions(+), 3 deletions(-) diff --git a/Util/BuildTools/Package.bat b/Util/BuildTools/Package.bat index 5d34f3682..190d25ff0 100644 --- a/Util/BuildTools/Package.bat +++ b/Util/BuildTools/Package.bat @@ -173,9 +173,8 @@ if %DO_COPY_FILES%==true ( echo f | xcopy /y "!XCOPY_FROM!Docs\release_readme.md" "!XCOPY_TO!README" echo f | xcopy /y "!XCOPY_FROM!Util\Docker\Release.Dockerfile" "!XCOPY_TO!Dockerfile" echo f | xcopy /y "!XCOPY_FROM!PythonAPI\carla\dist\*.egg" "!XCOPY_TO!PythonAPI\carla\dist\" - echo f | xcopy /y /s "!XCOPY_FROM!PythonAPI\carla\data\*" "!XCOPY_TO!PythonAPI\carla\data\" + echo f | xcopy /y /s "!XCOPY_FROM!PythonAPI\carla\data\*" "!XCOPY_TO!PythonAPI\carla\data\" echo d | xcopy /y /s "!XCOPY_FROM!Co-Simulation" "!XCOPY_TO!Co-Simulation" - echo d | xcopy /y /s "!XCOPY_FROM!Plugins" "!XCOPY_TO!Plugins" echo d | xcopy /y /s "!XCOPY_FROM!PythonAPI\carla\agents" "!XCOPY_TO!PythonAPI\carla\agents" echo f | xcopy /y "!XCOPY_FROM!PythonAPI\carla\scene_layout.py" "!XCOPY_TO!PythonAPI\carla\" echo f | xcopy /y "!XCOPY_FROM!PythonAPI\carla\requirements.txt" "!XCOPY_TO!PythonAPI\carla\" @@ -186,6 +185,9 @@ if %DO_COPY_FILES%==true ( echo f | xcopy /y "!XCOPY_FROM!PythonAPI\util\requirements.txt" "!XCOPY_TO!PythonAPI\util\" echo f | xcopy /y "!XCOPY_FROM!Unreal\CarlaUE4\Content\Carla\HDMaps\*.pcd" "!XCOPY_TO!HDMaps\" echo f | xcopy /y "!XCOPY_FROM!Unreal\CarlaUE4\Content\Carla\HDMaps\Readme.md" "!XCOPY_TO!HDMaps\README" + if exist "!XCOPY_FROM!Plugins" ( + echo d | xcopy /y /s "!XCOPY_FROM!Plugins" "!XCOPY_TO!Plugins" + ) ) rem ============================================================================== diff --git a/Util/BuildTools/Package.sh b/Util/BuildTools/Package.sh index b25b22225..78321db40 100755 --- a/Util/BuildTools/Package.sh +++ b/Util/BuildTools/Package.sh @@ -163,7 +163,9 @@ if ${DO_CARLA_RELEASE} ; then copy_if_changed "./Co-Simulation/" "${DESTINATION}/Co-Simulation/" - copy_if_changed "./Plugins/" "${DESTINATION}/Plugins/" + if [ -d "./Plugins/" ] ; then + copy_if_changed "./Plugins/" "${DESTINATION}/Plugins/" + fi copy_if_changed "./Unreal/CarlaUE4/Content/Carla/HDMaps/*.pcd" "${DESTINATION}/HDMaps/" copy_if_changed "./Unreal/CarlaUE4/Content/Carla/HDMaps/Readme.md" "${DESTINATION}/HDMaps/README" From 3e3b7fcb2033f0a210cad0f6efe8d38712a774d1 Mon Sep 17 00:00:00 2001 From: Daniel Santos-Olivan Date: Wed, 13 Jan 2021 13:01:38 +0100 Subject: [PATCH 008/569] Disable PhysXVehicleManager when physics are off --- .../Carla/Source/Carla/Server/CarlaServer.cpp | 31 +++++++------------ .../Carla/Vehicle/CarlaWheeledVehicle.cpp | 28 +++++++++++++++++ .../Carla/Vehicle/CarlaWheeledVehicle.h | 5 +++ 3 files changed, 44 insertions(+), 20 deletions(-) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp index deba250aa..ae07bfcba 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp @@ -915,10 +915,15 @@ void FCarlaServer::FPimpl::BindActions() RESPOND_ERROR("unable to set actor simulate physics: actor not found"); } - auto Character = Cast(ActorView.GetActor()); - // The physics in the walkers works in a different way so to disable them, + auto* Character = Cast(ActorView.GetActor()); + auto* CarlaVehicle = Cast(ActorView.GetActor()); + // The physics in the vehicles works in a different way so to disable them. + if (CarlaVehicle != nullptr){ + CarlaVehicle->SetSimulatePhysics(bEnabled); + } + // The physics in the walkers also works in a different way so to disable them, // we need to do it in the UCharacterMovementComponent. - if (Character != nullptr) + else if (Character != nullptr) { auto CharacterMovement = Cast(Character->GetCharacterMovement()); @@ -938,23 +943,9 @@ void FCarlaServer::FPimpl::BindActions() { RESPOND_ERROR("unable to set actor simulate physics: not supported by actor"); } - auto Vehicle = Cast(ActorView.GetActor()); - if(Vehicle) - { - Vehicle->SetActorEnableCollision(true); - #ifdef WITH_CARSIM - if(!Vehicle->IsCarSimEnabled()) - #endif - { - RootComponent->SetSimulatePhysics(bEnabled); - RootComponent->SetCollisionEnabled(ECollisionEnabled::QueryAndPhysics); - } - } - else - { - RootComponent->SetSimulatePhysics(bEnabled); - RootComponent->SetCollisionEnabled(ECollisionEnabled::QueryAndPhysics); - } + + RootComponent->SetSimulatePhysics(bEnabled); + RootComponent->SetCollisionEnabled(ECollisionEnabled::QueryAndPhysics); } return R::Success(); diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.cpp index 3860f032e..7ecbe845a 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.cpp @@ -635,6 +635,34 @@ void ACarlaWheeledVehicle::EnableCarSim(FString SimfilePath) #endif } +void ACarlaWheeledVehicle::SetSimulatePhysics(bool enabled) { + UWheeledVehicleMovementComponent4W *Vehicle4W = Cast( + GetVehicleMovement()); + check(Vehicle4W != nullptr); + + if(bPhysicsEnabled == enabled) + return; + + SetActorEnableCollision(true); + #ifdef WITH_CARSIM + if(!IsCarSimEnabled()) + #endif + { + auto RootComponent = Cast(GetRootComponent()); + RootComponent->SetSimulatePhysics(enabled); + RootComponent->SetCollisionEnabled(ECollisionEnabled::QueryAndPhysics); + + GetWorld()->GetPhysicsScene()->GetPxScene()->lockWrite(); + if(enabled) + Vehicle4W->RecreatePhysicsState(); + else + Vehicle4W->DestroyPhysicsState(); + GetWorld()->GetPhysicsScene()->GetPxScene()->unlockWrite(); + } + + bPhysicsEnabled = enabled; +} + void ACarlaWheeledVehicle::UseCarSimRoad(bool bEnabled) { #ifdef WITH_CARSIM diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.h index 5fd2c0139..8bf7a7b3f 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.h @@ -124,6 +124,8 @@ public: void ApplyVehiclePhysicsControl(const FVehiclePhysicsControl &PhysicsControl); + void SetSimulatePhysics(bool enabled); + void SetWheelCollision(UWheeledVehicleMovementComponent4W *Vehicle4W, const FVehiclePhysicsControl &PhysicsControl); void SetVehicleLightState(const FVehicleLightState &LightState); @@ -295,6 +297,9 @@ private: UPROPERTY(Category="CARLA Wheeled Vehicle", EditAnywhere) float CarSimOriginOffset = 150.f; + UPROPERTY(Category="CARLA Wheeled Vehicle", VisibleAnywhere) + bool bPhysicsEnabled = true; + // Small workarround to allow optional CarSim plugin usage UPROPERTY(Category="CARLA Wheeled Vehicle", VisibleAnywhere, BlueprintReadOnly, meta = (AllowPrivateAccess = "true")) UMovementComponent * ExternalMovementComponent; From c0986a07fc59f496f46866f0c2b5f0764632482a Mon Sep 17 00:00:00 2001 From: Axel Date: Wed, 20 Jan 2021 13:31:53 +0100 Subject: [PATCH 009/569] Improved movement components vehicle interface. --- .../Carla/Source/Carla/Server/CarlaServer.cpp | 34 +-- .../Source/Carla/Util/EnvironmentObject.h | 2 + .../Carla/Vehicle/CarlaWheeledVehicle.cpp | 247 +----------------- .../Carla/Vehicle/CarlaWheeledVehicle.h | 67 +---- .../BaseCarlaMovementComponent.cpp | 47 ++++ .../BaseCarlaMovementComponent.h | 36 +++ .../CarSimManagerComponent.cpp | 171 ++++++++++++ .../CarSimManagerComponent.h | 72 +++++ .../DefaultMovementComponent.cpp | 55 ++++ .../DefaultMovementComponent.h | 34 +++ 10 files changed, 462 insertions(+), 303 deletions(-) create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/BaseCarlaMovementComponent.cpp create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/BaseCarlaMovementComponent.h create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/CarSimManagerComponent.cpp create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/CarSimManagerComponent.h create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/DefaultMovementComponent.cpp create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/DefaultMovementComponent.h diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp index ae07bfcba..5de6e6164 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp @@ -16,6 +16,7 @@ #include "Carla/Walker/WalkerBase.h" #include "GameFramework/CharacterMovementComponent.h" #include "Carla/Game/Tagger.h" +#include "Carla/Vehicle/MovementComponents/CarSimManagerComponent.h" #include #include @@ -919,7 +920,11 @@ void FCarlaServer::FPimpl::BindActions() auto* CarlaVehicle = Cast(ActorView.GetActor()); // The physics in the vehicles works in a different way so to disable them. if (CarlaVehicle != nullptr){ - CarlaVehicle->SetSimulatePhysics(bEnabled); + // Ignore the call for carsim + if (!CarlaVehicle->GetCarlaMovementComponent()) + { + CarlaVehicle->SetSimulatePhysics(bEnabled); + } } // The physics in the walkers also works in a different way so to disable them, // we need to do it in the UCharacterMovementComponent. @@ -1085,12 +1090,10 @@ void FCarlaServer::FPimpl::BindActions() return R::Success(); }; -//-----CARSIM-------------------------------- BIND_SYNC(enable_carsim) << [this]( cr::ActorId ActorId, std::string SimfilePath) -> R { - #ifdef WITH_CARSIM REQUIRE_CARLA_EPISODE(); auto ActorView = Episode->FindActor(ActorId); if (!ActorView.IsValid()) @@ -1102,22 +1105,14 @@ void FCarlaServer::FPimpl::BindActions() { RESPOND_ERROR("unable to set carsim: not actor is not a vehicle"); } - if (Vehicle->IsCarSimEnabled()) - { - RESPOND_ERROR("unable to set carsim: carsim is already enabled"); - } - Vehicle->EnableCarSim(carla::rpc::ToFString(SimfilePath)); + UCarSimManagerComponent::CreateCarsimComponent(Vehicle, carla::rpc::ToFString(SimfilePath)); return R::Success(); - #else - RESPOND_ERROR("CarSim plugin is not enabled"); - #endif }; BIND_SYNC(use_carsim_road) << [this]( cr::ActorId ActorId, bool bEnabled) -> R { - #ifdef WITH_CARSIM REQUIRE_CARLA_EPISODE(); auto ActorView = Episode->FindActor(ActorId); if (!ActorView.IsValid()) @@ -1129,13 +1124,18 @@ void FCarlaServer::FPimpl::BindActions() { RESPOND_ERROR("unable to set carsim road: not actor is not a vehicle"); } - Vehicle->UseCarSimRoad(bEnabled); + auto* CarSimComponent = Vehicle->GetCarlaMovementComponent(); + if(CarSimComponent) + { + CarSimComponent->UseCarSimRoad(bEnabled); + } + else + { + RESPOND_ERROR("UCarSimManagerComponent plugin is not activated"); + } return R::Success(); - #else - RESPOND_ERROR("CarSim plugin is not enabled"); - #endif }; -//-----CARSIM-------------------------------- + // ~~ Traffic lights ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ BIND_SYNC(set_traffic_light_state) << [this]( diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/EnvironmentObject.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/EnvironmentObject.h index b5a79dfcd..25bf1708c 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/EnvironmentObject.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/EnvironmentObject.h @@ -9,6 +9,8 @@ #include #include +#include "BoundingBox.h" + #include "EnvironmentObject.generated.h" namespace crp = carla::rpc; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.cpp index 7ecbe845a..d7367be64 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.cpp @@ -17,6 +17,7 @@ #include "VehicleWheel.h" #include "Carla/Util/ActorAttacher.h" #include "Carla/Util/EmptyActor.h" +#include "MovementComponents/DefaultMovementComponent.h" #include "Rendering/SkeletalMeshRenderData.h" @@ -35,13 +36,9 @@ ACarlaWheeledVehicle::ACarlaWheeledVehicle(const FObjectInitializer& ObjectIniti VelocityControl = CreateDefaultSubobject(TEXT("VelocityControl")); VelocityControl->Deactivate(); - #ifdef WITH_CARSIM - // ExternalMovementComponent = CreateDefaultSubobject(TEXT("CarSimMovement")); - // CarSimMovementComponent = Cast(ExternalMovementComponent); - // CarSimMovementComponent->DisableVehicle = true; - #endif - GetVehicleMovementComponent()->bReverseAsBrake = false; + + BaseMovementComponent = CreateDefaultSubobject(TEXT("BaseMovementComponent")); } ACarlaWheeledVehicle::~ACarlaWheeledVehicle() {} @@ -76,6 +73,8 @@ void ACarlaWheeledVehicle::BeginPlay() { Super::BeginPlay(); + UDefaultMovementComponent::CreateDefaultMovementComponent(this); + float FrictionScale = 3.5f; UWheeledVehicleMovementComponent4W *Vehicle4W = Cast( @@ -148,13 +147,7 @@ void ACarlaWheeledVehicle::AdjustVehicleBounds() float ACarlaWheeledVehicle::GetVehicleForwardSpeed() const { - #ifdef WITH_CARSIM - if (bCarSimEnabled) - { - return CarSimMovementComponent->GetForwardSpeed(); - } - #endif - return GetVehicleMovementComponent()->GetForwardSpeed(); + return BaseMovementComponent->GetVehicleForwardSpeed(); } FVector ACarlaWheeledVehicle::GetVehicleOrientation() const @@ -164,13 +157,7 @@ FVector ACarlaWheeledVehicle::GetVehicleOrientation() const int32 ACarlaWheeledVehicle::GetVehicleCurrentGear() const { - #ifdef WITH_CARSIM - if (bCarSimEnabled) - { - return CarSimMovementComponent->GetCurrentGear(); - } - #endif - return GetVehicleMovementComponent()->GetCurrentGear(); + return BaseMovementComponent->GetVehicleCurrentGear(); } FTransform ACarlaWheeledVehicle::GetVehicleBoundingBoxTransform() const @@ -198,57 +185,7 @@ float ACarlaWheeledVehicle::GetMaximumSteerAngle() const void ACarlaWheeledVehicle::FlushVehicleControl() { - #ifdef WITH_CARSIM - if (bCarSimEnabled) - { - //-----CARSIM-------------------------------- - CarSimMovementComponent->SetThrottleInput(InputControl.Control.Throttle); - CarSimMovementComponent->SetSteeringInput(InputControl.Control.Steer); - CarSimMovementComponent->SetBrakeInput(InputControl.Control.Brake); - if (InputControl.Control.bHandBrake) - { - CarSimMovementComponent->SetBrakeInput(InputControl.Control.Brake + 1.0); - } - // CarSimMovementComponent->SetHandbrakeInput(InputControl.Control.bHandBrake); - // if (LastAppliedControl.bReverse != InputControl.Control.bReverse) - // { - // CarSimMovementComponent->SetUseAutoGears(!InputControl.Control.bReverse); - // CarSimMovementComponent->SetTargetGear(InputControl.Control.bReverse ? -1 : 1, true); - // } - // else - // { - // CarSimMovementComponent->SetUseAutoGears(!InputControl.Control.bManualGearShift); - // if (InputControl.Control.bManualGearShift) - // { - // CarSimMovementComponent->SetTargetGear(InputControl.Control.Gear, true); - // } - // } - InputControl.Control.Gear = CarSimMovementComponent->GetCurrentGear(); - //----------------------------------------- - } - else - #endif - { - auto *MovementComponent = GetVehicleMovementComponent(); - MovementComponent->SetThrottleInput(InputControl.Control.Throttle); - MovementComponent->SetSteeringInput(InputControl.Control.Steer); - MovementComponent->SetBrakeInput(InputControl.Control.Brake); - MovementComponent->SetHandbrakeInput(InputControl.Control.bHandBrake); - if (LastAppliedControl.bReverse != InputControl.Control.bReverse) - { - MovementComponent->SetUseAutoGears(!InputControl.Control.bReverse); - MovementComponent->SetTargetGear(InputControl.Control.bReverse ? -1 : 1, true); - } - else - { - MovementComponent->SetUseAutoGears(!InputControl.Control.bManualGearShift); - if (InputControl.Control.bManualGearShift) - { - MovementComponent->SetTargetGear(InputControl.Control.Gear, true); - } - } - InputControl.Control.Gear = MovementComponent->GetCurrentGear(); - } + BaseMovementComponent->ProcessControl(InputControl.Control); InputControl.Control.bReverse = InputControl.Control.Gear < 0; LastAppliedControl = InputControl.Control; InputControl.Priority = EVehicleInputPriority::INVALID; @@ -507,132 +444,13 @@ void ACarlaWheeledVehicle::SetVehicleLightState(const FVehicleLightState &LightS RefreshLightState(LightState); } -//-----CARSIM-------------------------------- -void ACarlaWheeledVehicle::OnCarSimHit(AActor *Actor, - AActor *OtherActor, - FVector NormalImpulse, - const FHitResult &Hit) +void ACarlaWheeledVehicle::SetCarlaMovementComponent(UBaseCarlaMovementComponent* MovementComponent) { - // handle collision forces here -} - - -void ACarlaWheeledVehicle::OnCarSimOverlap(UPrimitiveComponent* OverlappedComponent, - AActor* OtherActor, - UPrimitiveComponent* OtherComp, - int32 OtherBodyIndex, - bool bFromSweep, - const FHitResult & SweepResult) -{ - if (OtherComp->GetCollisionResponseToChannel( - ECollisionChannel::ECC_WorldDynamic) == - ECollisionResponse::ECR_Block) + if (BaseMovementComponent) { - // handle collision forces here + BaseMovementComponent->DestroyComponent(); } -} - -void ACarlaWheeledVehicle::SwitchToUE4Physics() -{ - #ifdef WITH_CARSIM - GetMesh()->SetPhysicsLinearVelocity(FVector(0,0,0), false, "Vehicle_Base"); - GetVehicleMovementComponent()->SetComponentTickEnabled(true); - GetVehicleMovementComponent()->Activate(); - CarSimMovementComponent->DisableVehicle = true; - CarSimMovementComponent->SetComponentTickEnabled(false); - CarSimMovementComponent->Deactivate(); - CarSimMovementComponent->VsConfigFile = ""; - GetMesh()->PhysicsTransformUpdateMode = EPhysicsTransformUpdateMode::SimulationUpatesComponentTransform; - auto * Bone = GetMesh()->GetBodyInstance(NAME_None); - if (Bone) - { - Bone->SetInstanceSimulatePhysics(true); - } - else - { - carla::log_warning("No bone with name"); - } - OnActorHit.RemoveDynamic(this, &ACarlaWheeledVehicle::OnCarSimHit); - GetMesh()->OnComponentBeginOverlap.RemoveDynamic(this, &ACarlaWheeledVehicle::OnCarSimOverlap); - GetMesh()->SetCollisionResponseToChannel(ECollisionChannel::ECC_WorldStatic, ECollisionResponse::ECR_Block); - GetMesh()->SetCollisionProfileName("Vehicle"); - carla::log_warning("There was a hit"); - #endif -} - -void ACarlaWheeledVehicle::RevertToCarSimPhysics() -{ - #ifdef WITH_CARSIM - GetVehicleMovementComponent()->SetComponentTickEnabled(false); - GetVehicleMovementComponent()->Deactivate(); - CarSimMovementComponent->DisableVehicle = false; - CarSimMovementComponent->Activate(); - // CarSimMovementComponent->ResetVsVehicle(false); - // set carsim position to actor's - CarSimMovementComponent->SyncVsVehicleLocOri(); - CarSimMovementComponent->SetComponentTickEnabled(true); - // set kinematic mode for root component and bones - GetMesh()->PhysicsTransformUpdateMode = EPhysicsTransformUpdateMode::ComponentTransformIsKinematic; - auto * Bone = GetMesh()->GetBodyInstance(NAME_None); - if (Bone) - { - Bone->SetInstanceSimulatePhysics(false); - } - // set callbacks to react to collisions - OnActorHit.AddDynamic(this, &ACarlaWheeledVehicle::OnCarSimHit); - GetMesh()->OnComponentBeginOverlap.AddDynamic(this, &ACarlaWheeledVehicle::OnCarSimOverlap); - GetMesh()->SetCollisionResponseToChannel(ECollisionChannel::ECC_WorldStatic, ECollisionResponse::ECR_Overlap); - carla::log_warning("Collision: giving control to carsim"); - #endif -} - -void ACarlaWheeledVehicle::EnableCarSim(FString SimfilePath) -{ - #ifdef WITH_CARSIM - // workarround to compensate carsim coordinate origin offset - FActorSpawnParameters SpawnParams; - SpawnParams.SpawnCollisionHandlingOverride = - ESpawnActorCollisionHandlingMethod::AlwaysSpawn; - OffsetActor = GetWorld()->SpawnActor( - GetActorLocation() + GetActorForwardVector() * CarSimOriginOffset, - GetActorRotation(), - SpawnParams); - CarSimMovementComponent = NewObject(OffsetActor); - - // CarSimMovementComponent = NewObject(this); - // ExternalMovementComponent = CarSimMovementComponent; - carla::log_warning("Loading simfile:", carla::rpc::FromFString(SimfilePath)); - GetVehicleMovementComponent()->SetComponentTickEnabled(false); - GetVehicleMovementComponent()->Deactivate(); - CarSimMovementComponent->DisableVehicle = false; - CarSimMovementComponent->VsConfigFile = SimfilePath; - CarSimMovementComponent->Activate(); - CarSimMovementComponent->RegisterComponent(); - - CarSimMovementComponent->ResetVsVehicle(false); - // set carsim position to actor's - CarSimMovementComponent->SyncVsVehicleLocOri(); - CarSimMovementComponent->SetComponentTickEnabled(true); - // set kinematic mode for root component and bones - GetMesh()->PhysicsTransformUpdateMode = EPhysicsTransformUpdateMode::ComponentTransformIsKinematic; - auto * Bone = GetMesh()->GetBodyInstance(NAME_None); - if (Bone) - { - Bone->SetInstanceSimulatePhysics(false); - } - // set callbacks to react to collisions - OnActorHit.AddDynamic(this, &ACarlaWheeledVehicle::OnCarSimHit); - GetMesh()->OnComponentBeginOverlap.AddDynamic(this, &ACarlaWheeledVehicle::OnCarSimOverlap); - GetMesh()->SetCollisionResponseToChannel(ECollisionChannel::ECC_WorldStatic, ECollisionResponse::ECR_Overlap); - - // workaround to prevent carsim from interacting with its own car - GetMesh()->SetCollisionResponseToChannel(ECollisionChannel::ECC_Visibility, ECollisionResponse::ECR_Overlap); - - // attach to actor with an offset - AttachToActor(OffsetActor, FAttachmentTransformRules::KeepWorldTransform); - - bCarSimEnabled = true; - #endif + BaseMovementComponent = MovementComponent; } void ACarlaWheeledVehicle::SetSimulatePhysics(bool enabled) { @@ -644,9 +462,7 @@ void ACarlaWheeledVehicle::SetSimulatePhysics(bool enabled) { return; SetActorEnableCollision(true); - #ifdef WITH_CARSIM - if(!IsCarSimEnabled()) - #endif + if(!GetCarlaMovementComponent()) { auto RootComponent = Cast(GetRootComponent()); RootComponent->SetSimulatePhysics(enabled); @@ -663,42 +479,7 @@ void ACarlaWheeledVehicle::SetSimulatePhysics(bool enabled) { bPhysicsEnabled = enabled; } -void ACarlaWheeledVehicle::UseCarSimRoad(bool bEnabled) -{ - #ifdef WITH_CARSIM - carla::log_warning("Enabling CarSim Road", bEnabled); - CarSimMovementComponent->UseVehicleSimRoad = bEnabled; - CarSimMovementComponent->ResetVsVehicle(false); - CarSimMovementComponent->SyncVsVehicleLocOri(); - #endif -} - -#ifdef WITH_CARSIM FVector ACarlaWheeledVehicle::GetVelocity() const { - if (bCarSimEnabled) - { - return GetActorForwardVector() * CarSimMovementComponent->GetForwardSpeed(); - } - else - { - return Super::GetVelocity(); - } + return BaseMovementComponent->GetVelocity(); } -#endif - -bool ACarlaWheeledVehicle::IsCarSimEnabled() const -{ - return bCarSimEnabled; -} - -void ACarlaWheeledVehicle::EndPlay(const EEndPlayReason::Type EndPlayReason) -{ - #ifdef WITH_CARSIM - if (OffsetActor) - { - OffsetActor->Destroy(); - } - #endif -} -//------------------------------------------- diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.h index 8bf7a7b3f..c07e6742e 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.h @@ -15,6 +15,7 @@ #include "Vehicle/VehiclePhysicsControl.h" #include "VehicleVelocityControl.h" #include "WheeledVehicleMovementComponent4W.h" +#include "MovementComponents/BaseCarlaMovementComponent.h" #include "CoreMinimal.h" @@ -206,6 +207,14 @@ public: void SetWheelsFrictionScale(TArray &WheelsFrictionScale); + void SetCarlaMovementComponent(UBaseCarlaMovementComponent* MoementComponent); + + template + T* GetCarlaMovementComponent() const + { + return Cast(BaseMovementComponent); + } + /// @} // =========================================================================== /// @name Overriden from AActor @@ -244,70 +253,22 @@ private: FVehicleControl LastAppliedControl; - -//-----CARSIM-------------------------------- public: - // Enables carsim once enabled it won't turn back to UE4 physics simulation - // (for some reason the UE4 physics get meesed up after enabling carsim) - UFUNCTION(Category="CARLA Wheeled Vehicle", BlueprintCallable) - void EnableCarSim(FString SimfilePath = ""); - - // Enables usage of carsim terrain - UFUNCTION(Category="CARLA Wheeled Vehicle", BlueprintCallable) - void UseCarSimRoad(bool bEnabled); - - #ifdef WITH_CARSIM virtual FVector GetVelocity() const override; - #endif - - UFUNCTION(Category="CARLA Wheeled Vehicle", BlueprintPure) - bool IsCarSimEnabled() const; - - virtual void EndPlay(const EEndPlayReason::Type EndPlayReason); - -private: - - // On car mesh hit, only works when carsim is enabled - UFUNCTION() - void OnCarSimHit(AActor *Actor, - AActor *OtherActor, - FVector NormalImpulse, - const FHitResult &Hit); - - // On car mesh overlap, only works when carsim is enabled - // (this event triggers when overlapping with static environment) - UFUNCTION() - void OnCarSimOverlap(UPrimitiveComponent* OverlappedComponent, - AActor* OtherActor, - UPrimitiveComponent* OtherComp, - int32 OtherBodyIndex, - bool bFromSweep, - const FHitResult & SweepResult); - - UFUNCTION() - void SwitchToUE4Physics(); - - UFUNCTION() - void RevertToCarSimPhysics(); - - UPROPERTY(Category="CARLA Wheeled Vehicle", VisibleAnywhere) - bool bCarSimEnabled = false; +//-----CARSIM-------------------------------- UPROPERTY(Category="CARLA Wheeled Vehicle", EditAnywhere) float CarSimOriginOffset = 150.f; +//------------------------------------------- +private: UPROPERTY(Category="CARLA Wheeled Vehicle", VisibleAnywhere) bool bPhysicsEnabled = true; // Small workarround to allow optional CarSim plugin usage UPROPERTY(Category="CARLA Wheeled Vehicle", VisibleAnywhere, BlueprintReadOnly, meta = (AllowPrivateAccess = "true")) - UMovementComponent * ExternalMovementComponent; + UBaseCarlaMovementComponent * BaseMovementComponent = nullptr; + - #ifdef WITH_CARSIM - AActor* OffsetActor; - // Casted version of ExternalMovementComponent - UCarSimMovementComponent * CarSimMovementComponent; - #endif - //------------------------------------------- }; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/BaseCarlaMovementComponent.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/BaseCarlaMovementComponent.cpp new file mode 100644 index 000000000..ca949adc9 --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/BaseCarlaMovementComponent.cpp @@ -0,0 +1,47 @@ +// Copyright (c) 2021 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// Copyright (c) 2019 Intel Corporation +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "BaseCarlaMovementComponent.h" +#include "Carla/Vehicle/CarlaWheeledVehicle.h" + +void UBaseCarlaMovementComponent::BeginPlay() +{ + Super::BeginPlay(); + ACarlaWheeledVehicle* Vehicle = Cast(GetOwner()); + if (Vehicle) + { + CarlaVehicle = Vehicle; + } + else + { + UE_LOG(LogCarla, Warning, TEXT("Error: Owner is not properly set for UBaseCarlaMovementComponent") ); + } +} + +void UBaseCarlaMovementComponent::ProcessControl(FVehicleControl &Control) +{ + +} + +FVector UBaseCarlaMovementComponent::GetVelocity() const +{ + if (CarlaVehicle) + { + return CarlaVehicle->AWheeledVehicle::GetVelocity(); + } + return FVector(); +} + +int32 UBaseCarlaMovementComponent::GetVehicleCurrentGear() const +{ + return 0; +} + +float UBaseCarlaMovementComponent::GetVehicleForwardSpeed() const +{ + return 0.f; +} diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/BaseCarlaMovementComponent.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/BaseCarlaMovementComponent.h new file mode 100644 index 000000000..5077061b7 --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/BaseCarlaMovementComponent.h @@ -0,0 +1,36 @@ +// Copyright (c) 2021 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// Copyright (c) 2019 Intel Corporation +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "GameFramework/MovementComponent.h" +#include "Carla/Vehicle/VehicleControl.h" +#include "BaseCarlaMovementComponent.generated.h" + +class ACarlaWheeledVehicle; + +UCLASS(Blueprintable, meta=(BlueprintSpawnableComponent)) +class CARLA_API UBaseCarlaMovementComponent : public UMovementComponent +{ + GENERATED_BODY() + +protected: + + ACarlaWheeledVehicle* CarlaVehicle; + +public: + + virtual void BeginPlay() override; + + virtual void ProcessControl(FVehicleControl &Control); + + virtual FVector GetVelocity() const; + + virtual int32 GetVehicleCurrentGear() const; + + virtual float GetVehicleForwardSpeed() const; +}; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/CarSimManagerComponent.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/CarSimManagerComponent.cpp new file mode 100644 index 000000000..8b4025068 --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/CarSimManagerComponent.cpp @@ -0,0 +1,171 @@ +// Copyright (c) 2021 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// Copyright (c) 2019 Intel Corporation +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "CarSimManagerComponent.h" +#include "Carla/Vehicle/CarlaWheeledVehicle.h" +#include "Carla/Util/EmptyActor.h" + + +void UCarSimManagerComponent::CreateCarsimComponent( + ACarlaWheeledVehicle* Vehicle, FString Simfile) +{ + #ifdef WITH_CARSIM + UCarSimManagerComponent* CarSimManagerComponent = NewObject(Vehicle); + CarSimManagerComponent->SimfilePath = Simfile; + CarSimManagerComponent->RegisterComponent(); + Vehicle->SetCarlaMovementComponent(CarSimManagerComponent); + #else + UE_LOG(LogCarla, Warning, TEXT("Error: CarSim plugin is not enabled") ); + #endif +} + +void UCarSimManagerComponent::BeginPlay() +{ + Super::BeginPlay(); + #ifdef WITH_CARSIM + + if(!CarlaVehicle) + { + UE_LOG(LogCarla, Warning, TEXT("Error: Owner is not properly set for UCarSimManagerComponent") ); + return; + } + + // workarround to compensate carsim coordinate origin offset + FActorSpawnParameters SpawnParams; + SpawnParams.SpawnCollisionHandlingOverride = + ESpawnActorCollisionHandlingMethod::AlwaysSpawn; + OffsetActor = GetWorld()->SpawnActor( + CarlaVehicle->GetActorLocation() + CarlaVehicle->GetActorForwardVector() * CarlaVehicle->CarSimOriginOffset, + CarlaVehicle->GetActorRotation(), + SpawnParams); + CarSimMovementComponent = NewObject(OffsetActor); + + // CarSimMovementComponent = NewObject(this); + // BaseMovementComponent = CarSimMovementComponent; + carla::log_warning("Loading simfile:", carla::rpc::FromFString(SimfilePath)); + CarlaVehicle->GetVehicleMovementComponent()->SetComponentTickEnabled(false); + CarlaVehicle->GetVehicleMovementComponent()->Deactivate(); + CarSimMovementComponent->DisableVehicle = false; + CarSimMovementComponent->VsConfigFile = SimfilePath; + CarSimMovementComponent->Activate(); + CarSimMovementComponent->RegisterComponent(); + + CarSimMovementComponent->ResetVsVehicle(false); + // set carsim position to actor's + CarSimMovementComponent->SyncVsVehicleLocOri(); + CarSimMovementComponent->SetComponentTickEnabled(true); + // set kinematic mode for root component and bones + CarlaVehicle->GetMesh()->PhysicsTransformUpdateMode = EPhysicsTransformUpdateMode::ComponentTransformIsKinematic; + auto * Bone = CarlaVehicle->GetMesh()->GetBodyInstance(NAME_None); + if (Bone) + { + Bone->SetInstanceSimulatePhysics(false); + } + // set callbacks to react to collisions + CarlaVehicle->OnActorHit.AddDynamic(this, &UCarSimManagerComponent::OnCarSimHit); + CarlaVehicle->GetMesh()->OnComponentBeginOverlap.AddDynamic(this, &UCarSimManagerComponent::OnCarSimOverlap); + CarlaVehicle->GetMesh()->SetCollisionResponseToChannel(ECollisionChannel::ECC_WorldStatic, ECollisionResponse::ECR_Overlap); + + // workaround to prevent carsim from interacting with its own car + CarlaVehicle->GetMesh()->SetCollisionResponseToChannel(ECollisionChannel::ECC_Visibility, ECollisionResponse::ECR_Overlap); + + // attach to actor with an offset + CarlaVehicle->AttachToActor(OffsetActor, FAttachmentTransformRules::KeepWorldTransform); + #else + UE_LOG(LogCarla, Warning, TEXT("Error: CarSim plugin is not enabled") ); + return; + #endif +} + +void UCarSimManagerComponent::ProcessControl(FVehicleControl &Control) +{ + #ifdef WITH_CARSIM + CarSimMovementComponent->SetThrottleInput(Control.Throttle); + CarSimMovementComponent->SetSteeringInput(Control.Steer); + CarSimMovementComponent->SetBrakeInput(Control.Brake); + if (Control.bHandBrake) + { + CarSimMovementComponent->SetBrakeInput(Control.Brake + 1.0); + } + Control.Gear = CarSimMovementComponent->GetCurrentGear(); + #endif +} + +void UCarSimManagerComponent::OnCarSimHit(AActor *Actor, + AActor *OtherActor, + FVector NormalImpulse, + const FHitResult &Hit) +{ + #ifdef WITH_CARSIM + // handle collision forces here + #endif +} + + +void UCarSimManagerComponent::OnCarSimOverlap(UPrimitiveComponent* OverlappedComponent, + AActor* OtherActor, + UPrimitiveComponent* OtherComp, + int32 OtherBodyIndex, + bool bFromSweep, + const FHitResult & SweepResult) +{ + if (OtherComp->GetCollisionResponseToChannel( + ECollisionChannel::ECC_WorldDynamic) == + ECollisionResponse::ECR_Block) + { + #ifdef WITH_CARSIM + // handle collision forces here + #endif + } +} + +void UCarSimManagerComponent::UseCarSimRoad(bool bEnabled) +{ + #ifdef WITH_CARSIM + CarSimMovementComponent->UseVehicleSimRoad = bEnabled; + CarSimMovementComponent->ResetVsVehicle(false); + CarSimMovementComponent->SyncVsVehicleLocOri(); + #endif +} + + +void UCarSimManagerComponent::EndPlay(const EEndPlayReason::Type EndPlayReason) +{ + #ifdef WITH_CARSIM + if (OffsetActor) + { + OffsetActor->Destroy(); + } + #endif +} + +FVector UCarSimManagerComponent::GetVelocity() const +{ + #ifdef WITH_CARSIM + return GetOwner()->GetActorForwardVector() * CarSimMovementComponent->GetForwardSpeed(); + #else + return FVector(); + #endif +} + +int32 UCarSimManagerComponent::GetVehicleCurrentGear() const +{ + #ifdef WITH_CARSIM + return CarSimMovementComponent->GetCurrentGear(); + #else + return 0; + #endif +} + +float UCarSimManagerComponent::GetVehicleForwardSpeed() const +{ + #ifdef WITH_CARSIM + return CarSimMovementComponent->GetForwardSpeed(); + #else + return 0.0; + #endif +} diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/CarSimManagerComponent.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/CarSimManagerComponent.h new file mode 100644 index 000000000..7fa2a60b5 --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/CarSimManagerComponent.h @@ -0,0 +1,72 @@ +// Copyright (c) 2021 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// Copyright (c) 2019 Intel Corporation +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "BaseCarlaMovementComponent.h" +#include "Carla/Vehicle/VehicleControl.h" + +#ifdef WITH_CARSIM +#include "CarSimMovementComponent.h" +#endif + +#include "CarSimManagerComponent.generated.h" + +class ACarlaWheeledVehicle; + +UCLASS(Blueprintable, meta=(BlueprintSpawnableComponent) ) +class CARLA_API UCarSimManagerComponent : public UBaseCarlaMovementComponent +{ + GENERATED_BODY() + + #ifdef WITH_CARSIM + AActor* OffsetActor; + + UCarSimMovementComponent * CarSimMovementComponent; + #endif + +public: + + static void CreateCarsimComponent( + ACarlaWheeledVehicle* Vehicle, FString Simfile); + + FString SimfilePath = ""; + + virtual void BeginPlay() override; + + void ProcessControl(FVehicleControl &Control) override; + + FVector GetVelocity() const override; + + virtual void EndPlay(const EEndPlayReason::Type EndPlayReason) override; + + void UseCarSimRoad(bool bEnabled); + + int32 GetVehicleCurrentGear() const override; + + float GetVehicleForwardSpeed() const override; + +private: + + // On car mesh hit, only works when carsim is enabled + UFUNCTION() + void OnCarSimHit(AActor *Actor, + AActor *OtherActor, + FVector NormalImpulse, + const FHitResult &Hit); + + // On car mesh overlap, only works when carsim is enabled + // (this event triggers when overlapping with static environment) + UFUNCTION() + void OnCarSimOverlap(UPrimitiveComponent* OverlappedComponent, + AActor* OtherActor, + UPrimitiveComponent* OtherComp, + int32 OtherBodyIndex, + bool bFromSweep, + const FHitResult & SweepResult); + +}; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/DefaultMovementComponent.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/DefaultMovementComponent.cpp new file mode 100644 index 000000000..fea2eb3a9 --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/DefaultMovementComponent.cpp @@ -0,0 +1,55 @@ +// Copyright (c) 2021 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// Copyright (c) 2019 Intel Corporation +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "DefaultMovementComponent.h" + +void UDefaultMovementComponent::CreateDefaultMovementComponent(ACarlaWheeledVehicle* Vehicle) +{ + UDefaultMovementComponent* DefaultMovementComponent = NewObject(Vehicle); + DefaultMovementComponent->RegisterComponent(); + Vehicle->SetCarlaMovementComponent(DefaultMovementComponent); +} + +void UDefaultMovementComponent::BeginPlay() +{ + Super::BeginPlay(); +} + +void UDefaultMovementComponent::ProcessControl(FVehicleControl &Control) +{ + auto *MovementComponent = CarlaVehicle->GetVehicleMovementComponent(); + MovementComponent->SetThrottleInput(Control.Throttle); + MovementComponent->SetSteeringInput(Control.Steer); + MovementComponent->SetBrakeInput(Control.Brake); + MovementComponent->SetHandbrakeInput(Control.bHandBrake); + if (CarlaVehicle->GetVehicleControl().bReverse != Control.bReverse) + { + MovementComponent->SetUseAutoGears(!Control.bReverse); + MovementComponent->SetTargetGear(Control.bReverse ? -1 : 1, true); + } + else + { + MovementComponent->SetUseAutoGears(!Control.bManualGearShift); + if (Control.bManualGearShift) + { + MovementComponent->SetTargetGear(Control.Gear, true); + } + } + Control.Gear = MovementComponent->GetCurrentGear(); +} + +// FVector GetVelocity() const override; + +int32 UDefaultMovementComponent::GetVehicleCurrentGear() const +{ + return CarlaVehicle->GetVehicleMovementComponent()->GetCurrentGear(); +} + +float UDefaultMovementComponent::GetVehicleForwardSpeed() const +{ + return CarlaVehicle->GetVehicleMovementComponent()->GetForwardSpeed(); +} diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/DefaultMovementComponent.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/DefaultMovementComponent.h new file mode 100644 index 000000000..21a762dbc --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/DefaultMovementComponent.h @@ -0,0 +1,34 @@ +// Copyright (c) 2021 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// Copyright (c) 2019 Intel Corporation +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "BaseCarlaMovementComponent.h" +#include "DefaultMovementComponent.generated.h" + + +UCLASS(Blueprintable, meta=(BlueprintSpawnableComponent) ) +class CARLA_API UDefaultMovementComponent : public UBaseCarlaMovementComponent +{ + GENERATED_BODY() + +public: + + static void CreateDefaultMovementComponent(ACarlaWheeledVehicle* Vehicle); + + virtual void BeginPlay() override; + + void ProcessControl(FVehicleControl &Control) override; + + // FVector GetVelocity() const override; + + int32 GetVehicleCurrentGear() const override; + + float GetVehicleForwardSpeed() const override; + +}; + From 5b59d9ad14ddd68951b335a7b1cf4d8204b7bf15 Mon Sep 17 00:00:00 2001 From: Axel Date: Wed, 20 Jan 2021 17:54:43 +0100 Subject: [PATCH 010/569] Removed double check for carsim mode. --- .../Carla/Source/Carla/Server/CarlaServer.cpp | 6 +---- .../Carla/Vehicle/CarlaWheeledVehicle.cpp | 26 ++++++++++--------- 2 files changed, 15 insertions(+), 17 deletions(-) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp index 5de6e6164..871ad6763 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp @@ -920,11 +920,7 @@ void FCarlaServer::FPimpl::BindActions() auto* CarlaVehicle = Cast(ActorView.GetActor()); // The physics in the vehicles works in a different way so to disable them. if (CarlaVehicle != nullptr){ - // Ignore the call for carsim - if (!CarlaVehicle->GetCarlaMovementComponent()) - { - CarlaVehicle->SetSimulatePhysics(bEnabled); - } + CarlaVehicle->SetSimulatePhysics(bEnabled); } // The physics in the walkers also works in a different way so to disable them, // we need to do it in the UCharacterMovementComponent. diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.cpp index d7367be64..f231f523a 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.cpp @@ -454,6 +454,11 @@ void ACarlaWheeledVehicle::SetCarlaMovementComponent(UBaseCarlaMovementComponent } void ACarlaWheeledVehicle::SetSimulatePhysics(bool enabled) { + if(!GetCarlaMovementComponent()) + { + return; + } + UWheeledVehicleMovementComponent4W *Vehicle4W = Cast( GetVehicleMovement()); check(Vehicle4W != nullptr); @@ -462,19 +467,16 @@ void ACarlaWheeledVehicle::SetSimulatePhysics(bool enabled) { return; SetActorEnableCollision(true); - if(!GetCarlaMovementComponent()) - { - auto RootComponent = Cast(GetRootComponent()); - RootComponent->SetSimulatePhysics(enabled); - RootComponent->SetCollisionEnabled(ECollisionEnabled::QueryAndPhysics); + auto RootComponent = Cast(GetRootComponent()); + RootComponent->SetSimulatePhysics(enabled); + RootComponent->SetCollisionEnabled(ECollisionEnabled::QueryAndPhysics); - GetWorld()->GetPhysicsScene()->GetPxScene()->lockWrite(); - if(enabled) - Vehicle4W->RecreatePhysicsState(); - else - Vehicle4W->DestroyPhysicsState(); - GetWorld()->GetPhysicsScene()->GetPxScene()->unlockWrite(); - } + GetWorld()->GetPhysicsScene()->GetPxScene()->lockWrite(); + if(enabled) + Vehicle4W->RecreatePhysicsState(); + else + Vehicle4W->DestroyPhysicsState(); + GetWorld()->GetPhysicsScene()->GetPxScene()->unlockWrite(); bPhysicsEnabled = enabled; } From fa2cde9ace4c85080034216771641e2fe5d086fa Mon Sep 17 00:00:00 2001 From: doterop Date: Wed, 20 Jan 2021 19:12:19 +0100 Subject: [PATCH 011/569] Added smoke test for sensor_tick check --- PythonAPI/test/smoke/test_sensor_tick_time.py | 64 +++++++++++++++++++ 1 file changed, 64 insertions(+) create mode 100644 PythonAPI/test/smoke/test_sensor_tick_time.py diff --git a/PythonAPI/test/smoke/test_sensor_tick_time.py b/PythonAPI/test/smoke/test_sensor_tick_time.py new file mode 100644 index 000000000..7b5531edd --- /dev/null +++ b/PythonAPI/test/smoke/test_sensor_tick_time.py @@ -0,0 +1,64 @@ +# Copyright (c) 2020 Computer Vision Center (CVC) at the Universitat Autonoma de +# Barcelona (UAB). +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . + +from . import SyncSmokeTest + +import carla +import time + +class Sensor(): + def __init__(self, world, bp_sensor, sensor_tick): + self.bp_sensor = bp_sensor + bp_sensor.set_attribute("sensor_tick", str(sensor_tick)) + self.sensor = world.spawn_actor(bp_sensor, carla.Transform()) + self.sensor.listen(lambda sensor_data: self.listen(sensor_data)) + self.num_ticks = 0 + + def destroy(self): + self.sensor.destroy() + + def listen(self, sensor_data): + self.num_ticks += 1 + +class TestSensorTickTime(SyncSmokeTest): + def test_sensor_tick_time(self): + print("TestSensorTickTime.test_sensor_tick_time") + + bp_lib = self.world.get_blueprint_library() + + sensor_exception = { + "sensor.camera.dvs", + "sensor.other.obstacle" + } + spawned_sensors = [] + sensor_tick = 1.0 + + for bp_sensor in bp_lib.filter("sensor.*"): + + if bp_sensor.id in sensor_exception: + continue + + if bp_sensor.has_attribute("sensor_tick"): + spawned_sensors.append(Sensor(self.world, bp_sensor, sensor_tick)) + + num_ticks = 10 + for _ in range(0, num_ticks): + self.world.tick() + time.sleep(1.0) + + dt = 0.05 # self.settings.fixed_delta_seconds + total_time = num_ticks * dt + num_sensor_ticks = total_time/sensor_tick + + print("Total time: {} = {} x {}".format(total_time, num_ticks, self.settings.fixed_delta_seconds)) + print("Expected sensor ticks: {}".format(num_sensor_ticks)) + for sensor in spawned_sensors: + print("{} ticks {} _".format(sensor.bp_sensor.id, sensor.num_ticks)) + self.assertEqual(sensor.num_ticks, num_sensor_ticks, + "\n\n {} does not match tick count".format(sensor.bp_sensor.id)) + sensor.destroy() + + From 2317e35f98470f98a05697b0729b206e6edb7bdb Mon Sep 17 00:00:00 2001 From: doterop Date: Wed, 20 Jan 2021 19:26:25 +0100 Subject: [PATCH 012/569] Added tick control on sensor for sensor_tick attribute --- .../Plugins/Carla/Source/Carla/Sensor/Sensor.cpp | 12 +++++++++++- .../Plugins/Carla/Source/Carla/Sensor/Sensor.h | 5 +++++ 2 files changed, 16 insertions(+), 1 deletion(-) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/Sensor.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/Sensor.cpp index d2d067352..ae2332996 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/Sensor.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/Sensor.cpp @@ -24,7 +24,7 @@ void ASensor::BeginPlay() { Super::BeginPlay(); OnPostTickDelegate = FWorldDelegates::OnWorldPostActorTick.AddUObject( - this, &ASensor::PostPhysTick); + this, &ASensor::PostPhysTickInternal); } void ASensor::Set(const FActorDescription &Description) @@ -41,6 +41,7 @@ void ASensor::Set(const FActorDescription &Description) void ASensor::Tick(const float DeltaTime) { Super::Tick(DeltaTime); + ReadyToTick = true; PrePhysTick(DeltaTime); } @@ -77,3 +78,12 @@ void ASensor::EndPlay(EEndPlayReason::Type EndPlayReason) FWorldDelegates::OnWorldPostActorTick.Remove(OnPostTickDelegate); } + +void ASensor::PostPhysTickInternal(UWorld *World, ELevelTick TickType, float DeltaSeconds) +{ + if(ReadyToTick) + { + PostPhysTick(World, TickType, DeltaSeconds); + ReadyToTick = false; + } +} \ No newline at end of file diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/Sensor.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/Sensor.h index 7e0f0a349..7803e512b 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/Sensor.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/Sensor.h @@ -101,9 +101,14 @@ protected: private: + void PostPhysTickInternal(UWorld *World, ELevelTick TickType, float DeltaSeconds); + FDataStream Stream; FDelegateHandle OnPostTickDelegate; const UCarlaEpisode *Episode = nullptr; + + /// Allows the sensor to tick with the tick rate from UE4. + bool ReadyToTick = false; }; From ac621539f09e78b13468013bc6c290b97a021f7a Mon Sep 17 00:00:00 2001 From: doterop Date: Wed, 20 Jan 2021 19:26:47 +0100 Subject: [PATCH 013/569] Removed previous ReadyToCapture --- .../Plugins/Carla/Source/Carla/Sensor/DepthCamera.cpp | 6 +----- .../Carla/Source/Carla/Sensor/SceneCaptureCamera.cpp | 6 +----- .../Carla/Source/Carla/Sensor/SceneCaptureSensor.cpp | 4 ---- .../Plugins/Carla/Source/Carla/Sensor/SceneCaptureSensor.h | 2 -- .../Source/Carla/Sensor/SemanticSegmentationCamera.cpp | 6 +----- 5 files changed, 3 insertions(+), 21 deletions(-) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/DepthCamera.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/DepthCamera.cpp index 085f5c864..014d9ce5e 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/DepthCamera.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/DepthCamera.cpp @@ -30,9 +30,5 @@ ADepthCamera::ADepthCamera(const FObjectInitializer &ObjectInitializer) void ADepthCamera::PostPhysTick(UWorld *World, ELevelTick TickType, float DeltaSeconds) { - if(ReadyToCapture) - { - FPixelReader::SendPixelsInRenderThread(*this); - ReadyToCapture = false; - } + FPixelReader::SendPixelsInRenderThread(*this); } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SceneCaptureCamera.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SceneCaptureCamera.cpp index c65878d7f..251d1982f 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SceneCaptureCamera.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SceneCaptureCamera.cpp @@ -26,9 +26,5 @@ ASceneCaptureCamera::ASceneCaptureCamera(const FObjectInitializer &ObjectInitial void ASceneCaptureCamera::PostPhysTick(UWorld *World, ELevelTick TickType, float DeltaSeconds) { - if(ReadyToCapture) - { - ReadyToCapture = false; - FPixelReader::SendPixelsInRenderThread(*this); - } + FPixelReader::SendPixelsInRenderThread(*this); } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SceneCaptureSensor.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SceneCaptureSensor.cpp index 3d912405c..c4b322d9f 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SceneCaptureSensor.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SceneCaptureSensor.cpp @@ -511,15 +511,11 @@ void ASceneCaptureSensor::PrePhysTick(float DeltaSeconds) CaptureComponent2D->GetComponentLocation(), ImageWidth, ImageWidth / FMath::Tan(CaptureComponent2D->FOVAngle)); - - // Allows the sensor to tick with the tick rate from UE4. - ReadyToCapture = true; } void ASceneCaptureSensor::PostPhysTick(UWorld *World, ELevelTick TickType, float DeltaTime) { Super::PostPhysTick(World, TickType, DeltaTime); - ReadyToCapture = true; } void ASceneCaptureSensor::EndPlay(const EEndPlayReason::Type EndPlayReason) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SceneCaptureSensor.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SceneCaptureSensor.h index 94b1566b0..297f03767 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SceneCaptureSensor.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SceneCaptureSensor.h @@ -321,6 +321,4 @@ protected: FRenderCommandFence RenderFence; - bool ReadyToCapture = false; - }; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SemanticSegmentationCamera.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SemanticSegmentationCamera.cpp index 56b209c2d..4e85534d8 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SemanticSegmentationCamera.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SemanticSegmentationCamera.cpp @@ -26,9 +26,5 @@ ASemanticSegmentationCamera::ASemanticSegmentationCamera( void ASemanticSegmentationCamera::PostPhysTick(UWorld *World, ELevelTick TickType, float DeltaSeconds) { - if(ReadyToCapture) - { - FPixelReader::SendPixelsInRenderThread(*this); - ReadyToCapture = false; - } + FPixelReader::SendPixelsInRenderThread(*this); } From 23bf0fb16a940babd861aaa734b6e02569e3ce77 Mon Sep 17 00:00:00 2001 From: doterop Date: Wed, 20 Jan 2021 23:43:02 +0100 Subject: [PATCH 014/569] Removed comments --- PythonAPI/test/smoke/test_sensor_tick_time.py | 10 ++++------ 1 file changed, 4 insertions(+), 6 deletions(-) diff --git a/PythonAPI/test/smoke/test_sensor_tick_time.py b/PythonAPI/test/smoke/test_sensor_tick_time.py index 7b5531edd..df019f86f 100644 --- a/PythonAPI/test/smoke/test_sensor_tick_time.py +++ b/PythonAPI/test/smoke/test_sensor_tick_time.py @@ -8,6 +8,7 @@ from . import SyncSmokeTest import carla import time +import math class Sensor(): def __init__(self, world, bp_sensor, sensor_tick): @@ -44,19 +45,16 @@ class TestSensorTickTime(SyncSmokeTest): if bp_sensor.has_attribute("sensor_tick"): spawned_sensors.append(Sensor(self.world, bp_sensor, sensor_tick)) - num_ticks = 10 + num_ticks = 50 for _ in range(0, num_ticks): self.world.tick() time.sleep(1.0) - dt = 0.05 # self.settings.fixed_delta_seconds + dt = self.settings.fixed_delta_seconds total_time = num_ticks * dt - num_sensor_ticks = total_time/sensor_tick + num_sensor_ticks = int(math.ceil(total_time/sensor_tick)) - print("Total time: {} = {} x {}".format(total_time, num_ticks, self.settings.fixed_delta_seconds)) - print("Expected sensor ticks: {}".format(num_sensor_ticks)) for sensor in spawned_sensors: - print("{} ticks {} _".format(sensor.bp_sensor.id, sensor.num_ticks)) self.assertEqual(sensor.num_ticks, num_sensor_ticks, "\n\n {} does not match tick count".format(sensor.bp_sensor.id)) sensor.destroy() From 35c35c00555fb7692c7874e564588d7f6cf96097 Mon Sep 17 00:00:00 2001 From: doterop Date: Thu, 21 Jan 2021 16:59:16 +0100 Subject: [PATCH 015/569] Fixed how fixed_delta_seconds is obtained --- PythonAPI/test/smoke/test_sensor_tick_time.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/PythonAPI/test/smoke/test_sensor_tick_time.py b/PythonAPI/test/smoke/test_sensor_tick_time.py index df019f86f..5d9c600d3 100644 --- a/PythonAPI/test/smoke/test_sensor_tick_time.py +++ b/PythonAPI/test/smoke/test_sensor_tick_time.py @@ -50,7 +50,7 @@ class TestSensorTickTime(SyncSmokeTest): self.world.tick() time.sleep(1.0) - dt = self.settings.fixed_delta_seconds + dt = self.world.get_settings().fixed_delta_seconds total_time = num_ticks * dt num_sensor_ticks = int(math.ceil(total_time/sensor_tick)) From 18f255822305b82aeb61251551a97a1e2f448747 Mon Sep 17 00:00:00 2001 From: Guillermo Date: Wed, 27 Jan 2021 11:09:17 +0100 Subject: [PATCH 016/569] Fixed bug related to RoadOptions --- CHANGELOG.md | 5 +++++ .../carla/agents/navigation/behavior_agent.py | 3 ++- .../agents/navigation/local_planner_behavior.py | 15 +-------------- 3 files changed, 8 insertions(+), 15 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 4ddf6458c..5da3904ab 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,3 +1,8 @@ +## Latest + + * Fixed bug causing the RoadOptions at the BehaviorAgent to not work as intended + + ## CARLA 0.9.11 * Improved the documentation for use with pandoc tool by converting html tags to their markdown equivalent diff --git a/PythonAPI/carla/agents/navigation/behavior_agent.py b/PythonAPI/carla/agents/navigation/behavior_agent.py index 9ce07201c..ea3cc60c5 100644 --- a/PythonAPI/carla/agents/navigation/behavior_agent.py +++ b/PythonAPI/carla/agents/navigation/behavior_agent.py @@ -12,7 +12,8 @@ import random import numpy as np import carla from agents.navigation.agent import Agent -from agents.navigation.local_planner_behavior import LocalPlanner, RoadOption +from agents.navigation.local_planner_behavior import LocalPlanner +from agents.navigation.local_planner import RoadOption from agents.navigation.global_route_planner import GlobalRoutePlanner from agents.navigation.global_route_planner_dao import GlobalRoutePlannerDAO from agents.navigation.types_behavior import Cautious, Aggressive, Normal diff --git a/PythonAPI/carla/agents/navigation/local_planner_behavior.py b/PythonAPI/carla/agents/navigation/local_planner_behavior.py index 86a6d6b78..03a777b86 100644 --- a/PythonAPI/carla/agents/navigation/local_planner_behavior.py +++ b/PythonAPI/carla/agents/navigation/local_planner_behavior.py @@ -14,23 +14,10 @@ from enum import Enum import carla from agents.navigation.controller import VehiclePIDController +from agents.navigation.local_planner import RoadOption from agents.tools.misc import distance_vehicle, draw_waypoints -class RoadOption(Enum): - """ - RoadOption represents the possible topological configurations - when moving from a segment of lane to other. - """ - VOID = -1 - LEFT = 1 - RIGHT = 2 - STRAIGHT = 3 - LANEFOLLOW = 4 - CHANGELANELEFT = 5 - CHANGELANERIGHT = 6 - - class LocalPlanner(object): """ LocalPlanner implements the basic behavior of following a trajectory From 198fa38c9b1317c114ac15dff130766253c02832 Mon Sep 17 00:00:00 2001 From: Daniel Santos-Olivan Date: Tue, 26 Jan 2021 15:51:56 +0100 Subject: [PATCH 017/569] Improve benchmark script: - Added option for sync mode (on by default) - Added a warm-up time after spawning actors to not contaminate the results - Added option for no rendering mode (on by default) - Added two new cases for Lidar (100k and 1M points) - Allow to cancel the execution like other scripts - Added the option to benchmark only a sublist of maps, sensors and types of weather - Added a parameter to show all the maps, sensors and types of weather possible --- PythonAPI/util/performance_benchmark.py | 197 +++++++++++++++++------- 1 file changed, 145 insertions(+), 52 deletions(-) diff --git a/PythonAPI/util/performance_benchmark.py b/PythonAPI/util/performance_benchmark.py index c407d3c34..b9a0a2fae 100755 --- a/PythonAPI/util/performance_benchmark.py +++ b/PythonAPI/util/performance_benchmark.py @@ -75,6 +75,13 @@ def define_weather(): list_weather.append(weather01) list_weather.append(weather02) + if args.weather is not None: + try: + new_list = [list_weather[int(i)] for i in args.weather] + list_weather = new_list + except IndexError as error: + print("Warning!! The list of types of weather introduced is not valid. Using all available.") + return list_weather @@ -83,34 +90,48 @@ def define_sensors(): if args.tm: sensors00 = [{'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, - 'width': 300, 'height': 200, 'fov': 100, 'label': '1. cam-300x200'}] + 'width': 300, 'height': 200, 'fov': 100, 'label': '0. cam-300x200'}] list_sensor_specs.append(sensors00) else: sensors00 = [{'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, - 'width': 300, 'height': 200, 'fov': 100, 'label': '1. cam-300x200'}] + 'width': 300, 'height': 200, 'fov': 100, 'label': '0. cam-300x200'}] sensors01 = [{'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, - 'width': 800, 'height': 600, 'fov': 100, 'label': '2. cam-800x600'}] + 'width': 800, 'height': 600, 'fov': 100, 'label': '1. cam-800x600'}] sensors02 = [{'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, - 'width': 1900, 'height': 1080, 'fov': 100, 'label': '3. cam-1900x1080'}] + 'width': 1900, 'height': 1080, 'fov': 100, 'label': '2. cam-1900x1080'}] sensors03 = [{'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, - 'width': 300, 'height': 200, 'fov': 100, 'label': '4. cam-300x200'}, + 'width': 300, 'height': 200, 'fov': 100, 'label': '3. cam-300x200'}, {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, - 'width': 300, 'height': 200, 'fov': 100, 'label': 'cam-300x200'}, - ] + 'width': 300, 'height': 200, 'fov': 100, 'label': 'cam-300x200'}] sensors04 = [{'type': 'sensor.lidar.ray_cast', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'yaw': 0.0, 'pitch': 0.0, 'roll': 0.0, - 'label': '5. LIDAR'}] + 'pts_per_sec': '100000', 'label': '4. LIDAR: 100k'}] + + sensors05 = [{'type': 'sensor.lidar.ray_cast', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'yaw': 0.0, 'pitch': 0.0, 'roll': 0.0, + 'pts_per_sec': '500000', 'label': '5. LIDAR: 500k'}] + + sensors06 = [{'type': 'sensor.lidar.ray_cast', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'yaw': 0.0, 'pitch': 0.0, 'roll': 0.0, + 'pts_per_sec': '1000000', 'label': '6. LIDAR: 1M'}] list_sensor_specs.append(sensors00) list_sensor_specs.append(sensors01) list_sensor_specs.append(sensors02) list_sensor_specs.append(sensors03) list_sensor_specs.append(sensors04) + list_sensor_specs.append(sensors05) + list_sensor_specs.append(sensors06) + + if args.sensors is not None: + try: + new_list = [list_sensor_specs[int(i)] for i in args.sensors] + list_sensor_specs = new_list + except IndexError as error: + print("Warning!! The list of sensors introduced is not valid. Using all available.") return list_sensor_specs @@ -135,7 +156,18 @@ def define_environments(): return list_env_specs +def define_maps(client): + maps = [m.replace('/Game/Carla/Maps/', '') for m in client.get_available_maps()] + maps = sorted(maps) + if args.maps is not None: + all_good = all(elem in maps for elem in args.maps) + if all_good: + maps = sorted(args.maps) + else: + print("Warning!! The list of maps introduced is not valid. Using all available.") + + return maps class CallBack(object): def __init__(self): self._lock = threading.Lock() @@ -179,7 +211,7 @@ def create_environment(world, sensors, n_vehicles, n_walkers, spawn_points, clie bp.set_attribute('channels', '32') bp.set_attribute('upper_fov', '15') bp.set_attribute('lower_fov', '-30') - bp.set_attribute('points_per_second', '500000') + bp.set_attribute('points_per_second', str(sensor_spec['pts_per_sec'])) sensor_location = carla.Location( x=sensor_spec['x'], y=sensor_spec['y'], @@ -311,6 +343,21 @@ def create_environment(world, sensors, n_vehicles, n_walkers, spawn_points, clie # -- Benchmarking functions -------------------------------------------------------------------------------------------- # ====================================================================================================================== +def set_world_settings(world, args = None): + + if args == None: + settings = world.get_settings() + settings.synchronous_mode = False + settings.fixed_delta_seconds = 0.0 + settings.no_rendering_mode = False + world.apply_settings(settings) + else: + settings = world.get_settings() + settings.synchronous_mode = args.sync + settings.fixed_delta_seconds = args.fixed_dt if args.sync else 0.0 + settings.no_rendering_mode = args.no_render_mode + world.apply_settings(settings) + def run_benchmark(world, sensors, n_vehicles, n_walkers, client, debug=False): global sensors_callback @@ -319,14 +366,21 @@ def run_benchmark(world, sensors, n_vehicles, n_walkers, client, debug=False): list_fps = [] sensor_list = None + tick = world.tick if args.sync else world.wait_for_tick + set_world_settings(world, args) + vehicles_list, walkers_list, all_id, all_actors, sensors_ret = create_environment(world, sensors, n, n_walkers, spawn_points, client) if sensors_ret: sensor_list = sensors_ret + # Allow some time for the server to finish the initialization + for _i in range(0, 50): + tick() + ticks = 0 while ticks < int(args.ticks): - _ = world.wait_for_tick() + _ = tick() if debug: print("== Samples {} / {}".format(ticks + 1, args.ticks)) @@ -356,6 +410,8 @@ def run_benchmark(world, sensors, n_vehicles, n_walkers, client, debug=False): print('\ndestroying %d walkers' % len(walkers_list)) client.apply_batch([carla.command.DestroyActor(x) for x in all_id]) + set_world_settings(world) + return list_fps @@ -419,58 +475,86 @@ def get_system_specs(): return str_system +def show_benchmark_scenarios(maps): + print("Available maps") + for map in sorted(maps): + print(" - %s" % map) + print("Available sensors") + for i,sensors in enumerate(define_sensors()): + sensor_str = "" + for sensor in sensors: + sensor_str += (sensor['label'] + " ") + print(' - %s' % (sensor_str)) + print("Available types of weather") + for i,weather in enumerate(define_weather()): + print(' - %i: %s' % (i, weather['name'])) + print("Available Enviroments") + for i,env in enumerate(define_environments()): + print(' - %i: %s' % (i, str(env))) + + def main(args): - client = carla.Client(args.host, int(args.port)) - client.set_timeout(60.0) - pygame.init() - records = {} - maps = [m.replace('/Game/Carla/Maps/', '') for m in client.get_available_maps()] + try: + client = carla.Client(args.host, int(args.port)) + client.set_timeout(60.0) + pygame.init() - for town in sorted(maps): - world = client.load_world(town) + records = {} + maps = define_maps(client) - # set to async mode - settings = world.get_settings() - settings.synchronous_mode = False - settings.fixed_delta_seconds = None - world.apply_settings(settings) + if args.show_scenarios: + show_benchmark_scenarios(maps) + return - # spectator pointing to the sky to reduce rendering impact - spectator = world.get_spectator() - spectator.set_transform(carla.Transform(carla.Location(z=500), carla.Rotation(pitch=90))) + #maps = ["Town04_Opt"] - for weather in define_weather(): - world.set_weather(weather["parameter"]) - for env in define_environments(): - for sensors in define_sensors(): - list_fps = run_benchmark(world, sensors, env["vehicles"], env["walkers"], client) - mean, std = compute_mean_std(list_fps) - sensor_str = "" - for sensor in sensors: - sensor_str += (sensor['label'] + " ") + for town in maps: + world = client.load_world(town) - record = { - 'town': town, - 'sensors': sensor_str, - 'weather': weather["name"], - 'n_vehicles': env["vehicles"], - 'n_walkers': env["walkers"], - 'samples': args.ticks, - 'fps_mean': mean, - 'fps_std': std - } + # set to async mode + set_world_settings(world) - env_str = str(env["vehicles"]) + str(env["walkers"]) + # spectator pointing to the sky to reduce rendering impact + spectator = world.get_spectator() + spectator.set_transform(carla.Transform(carla.Location(z=500), carla.Rotation(pitch=90))) - if env_str not in records: - records[env_str] = [] - records[env_str].append(record) - print(record) + for weather in define_weather(): + world.set_weather(weather["parameter"]) + for env in define_environments(): + for sensors in define_sensors(): + list_fps = run_benchmark(world, sensors, env["vehicles"], env["walkers"], client) + mean, std = compute_mean_std(list_fps) + sensor_str = "" + for sensor in sensors: + sensor_str += (sensor['label'] + " ") - system_specs = get_system_specs() - serialize_records(records, system_specs, args.file) - pygame.quit() + record = { + 'town': town, + 'sensors': sensor_str, + 'weather': weather["name"], + 'n_vehicles': env["vehicles"], + 'n_walkers': env["walkers"], + 'samples': args.ticks, + 'fps_mean': mean, + 'fps_std': std + } + + env_str = str(env["vehicles"]) + str(env["walkers"]) + + if env_str not in records: + records[env_str] = [] + records[env_str].append(record) + print(record) + + system_specs = get_system_specs() + serialize_records(records, system_specs, args.file) + pygame.quit() + + except KeyboardInterrupt: + set_world_settings(world) + client.reload_world() + print('\nCancelled by user. Bye!') if __name__ == '__main__': @@ -482,6 +566,15 @@ if __name__ == '__main__': parser.add_argument('--file', type=str, help='Write results into a txt file', default="benchmark.md") parser.add_argument('--tm', action='store_true', help='Switch to traffic manager benchmark') parser.add_argument('--ticks', default=100, help='Number of ticks for each scenario (default: 100)') + parser.add_argument('--sync', default=True, action='store_true', help='Synchronous mode execution (default)') + parser.add_argument('--async', dest='sync', action='store_false', help='Asynchronous mode execution') + parser.add_argument('--fixed_dt', type=float, default=0.05, help='Time interval for the simulator in synchronous mode (default: 0.05)') + parser.add_argument('--render_mode', dest='no_render_mode', action='store_false', help='Execute with spectator') + parser.add_argument('--no_render_mode', default=True, action='store_true', help='Execute in no rendering mode (default)') + parser.add_argument('--show_scenarios', default=False, action='store_true', help='Show the scenarios to benchmark and return (default=False)') + parser.add_argument('--sensors', nargs="+", default=None, help='List of sensors to benchmark, by default all defined ones') + parser.add_argument('--maps', nargs="+", default=None, help='List of maps to benchmark, by default all defined ones') + parser.add_argument('--weather', nargs="+", default=None, help='List of weather types to benchmark, by default all defined ones') args = parser.parse_args() From c83f8dd12731b0d2998b1aed49914cfc4656b499 Mon Sep 17 00:00:00 2001 From: corkyw10 Date: Thu, 28 Jan 2021 11:06:14 +0100 Subject: [PATCH 018/569] Added section explaining layered and non-layered maps. Moved map images to hyperlinks accessible from the map table --- Docs/core_map.md | 74 ++++++++++++++++++++++++----------------- Docs/img/sublevels.gif | Bin 0 -> 3460915 bytes 2 files changed, 43 insertions(+), 31 deletions(-) create mode 100644 Docs/img/sublevels.gif diff --git a/Docs/core_map.md b/Docs/core_map.md index 67b1d09a3..95c5d1da2 100644 --- a/Docs/core_map.md +++ b/Docs/core_map.md @@ -12,6 +12,8 @@ After discussing about the world and its actors, it is time to put everything in * [Navigating through waypoints](#navigating-through-waypoints) * [Generating a map navigation](#generating-a-map-navigation) * [__CARLA maps__](#carla-maps) + * [Non-layered maps](#non-layered-maps) + * [Layered maps](#layered-maps) --- ## The map @@ -175,49 +177,59 @@ info_map = map.to_opendrive() --- ## CARLA maps -So far there are seven different maps available. Each one has unique features and is useful for different purposes. Hereunder is a brief sum up on them. +There are seven towns in the CARLA ecosystem and each of those towns have two kinds of map, non-layered and layered. [Layers][layer_api] refer to the grouped objects within a map and consist of the following: + +- NONE +- Buildings +- Decals +- Foliage +- Ground +- ParkedVehicles +- Particles +- Props +- StreetLights +- Walls +- All + +[layer_api]: https://carla.readthedocs.io/en/latest/python_api/#carlamaplayer + +### Non-layered maps + +Non-layered maps are shown in the table below (click the town name to see an overhead image of the layout). All of the layers are present at all times and cannot be toggled on or off in these maps. Up until CARLA 0.9.11, these were the only kinds of map available. !!! Note Users can [customize a map](tuto_A_map_customization.md) or even [create a new map](tuto_A_add_map.md) to be used in CARLA. -| Town | Summary | -| -------------------------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------- | -| **Town01** | A basic town layout with all "T junctions". | -| **Town02** | Similar to **Town01**, but smaller. | -| **Town03** | The most complex town, with a 5-lane junction, a roundabout, unevenness, a tunnel, and much more. Essentially a medley. | -| **Town04** | An infinite loop with a highway and a small town. | -| **Town05** | Squared-grid town with cross junctions and a bridge. It has multiple lanes per direction. Useful to perform lane changes. | -| **Town06** | Long highways with many highway entrances and exits. It also has a [**Michigan left**](). | -| **Town07** | A rural environment with narrow roads, barely non traffic lights and barns. | -| **Town10** | A city environment with with different environments such as an avenue or a promenade, and more realistic textures. | +| Town | Summary | +| -----------| ------ | +| **[Town01](img/Town01.jpg)** | A basic town layout consisting of "T junctions".| +| **[Town02](img/Town02.jpg)** | Similar to **Town01**, but smaller.| +| **[Town03](img/Town03.jpg)** | The most complex town, with a 5-lane junction, a roundabout, unevenness, a tunnel, and more.| +| **[Town04](img/Town04.jpg)** | An infinite loop with a highway and a small town.| +| **[Town05](img/Town05.jpg)** | Squared-grid town with cross junctions and a bridge. It has multiple lanes per direction. Useful to perform lane changes. | +| **[Town06](img/Town06.jpg)** | Long highways with many highway entrances and exits. It also has a [**Michigan left**](). | +| **[Town07](img/Town07.jpg)** | A rural environment with narrow roads, barns and hardly any traffic lights. | +| **[Town10](img/Town10.jpg)** | A city environment with different environments such as an avenue or promenade, and more realistic textures.| -
+### Layered maps +The layout of layered maps is the same as non-layered maps but it is possible to toggle off and on the layers of the map. Layered maps can be idenitified by the suffix `_Opt`, for example, `Town01_Opt`. With these maps it is possible to [load][load_layer] and [unload][unload_layer] layers via the Python API: -![Town01](img/Town01.jpg) -*Above: Town01* + # Load layered map for Town 01 + world = client.load_world('Town01_Opt') -![Town02](img/Town02.jpg) -*Above: Town02* + # Toggle all buildings off + world.unload_map_layer(carla.MapLayer.Buildings) -![Town03](img/Town03.jpg) -*Above: Town03* + # Toggle all buildings on + world.load_map_layer(carla.MapLayer.Buildings) -![Town04](img/Town04.jpg) -*Above: Town04* +[load_layer]: https://carla.readthedocs.io/en/latest/python_api/#carla.World.load_map_layer +[unload_layer]: https://carla.readthedocs.io/en/latest/python_api/#carla.World.unload_map_layer -![Town05](img/Town05.jpg) -*Above: Town05* - -![Town06](img/Town06.jpg) -*Above: Town06* - -![Town07](img/Town07.jpg) -*Above: Town07* - -![Town10](img/Town10.jpg) -*Above: Town10* +See an example of all layers being loaded and unloaded in sequence: +![map-layers](img/sublevels.gif)
diff --git a/Docs/img/sublevels.gif b/Docs/img/sublevels.gif new file mode 100644 index 0000000000000000000000000000000000000000..c81cab7bc7d4ed820174ece0dc5b254b5c6596ed GIT binary patch literal 3460915 zcmaI7cUTk6+dn#+P6~vY&_Y5DJqaB}6Pk2GFM^~1q7*|Ftf5yG5CMBYx-B3mVhdI5 zpomzXpeR_LN3iRoa`?XI_rB-+ao)4nUf1r--fed7nZ5Tj_pI^ubadihf|WzB0pLYP ztqZW*TzZT`(R)AlWO8b}r>$0Y<91!?mh$?x!c0NOfwH>l^6Be+y=OMx=}i0aVODy1 zWVNlq<=*B)E#1F={m9u`P*=3}=H=eYr;h&q_AV@?@Irq-({@E?TXXxl%h%2wczQ?N zQN#TyA86da^`9$cPp;HGIahM}RK&weCoT?Vx_SDxo;>$_?)lK@xv9&&Vxg>7-WI_LdxWDdo`ueF> z$)V#>Ki$5?8Vg3hYzzKp5GB>RL)IJefaQU^z!kAWxD6j zMH$;ZOx?LVAesB{;cjo++=n?~M!|>Y&;OaZ1OQlCTB0rC0z5*3-8ftimK6gIE!Qqr zMfh{6?)*&t@^$6v91&lb6rV{I#BbP`>Z1SQ;#Ga>#yA)Ka65m7zsM~EXKW?)i-g)`{Kh@Uy)c+#MOmflZ z{O1AnKRVqur^i$6tr(U<2E&Hx;AF+Lx3yzASWsCE7Q>pkeA-zu9h_|)oo!gu|8wXs zYfFzya1L_!{6D&uOD_6}nVBMIYwImrwpeYkvD%!z!J6sh!5JaBqIm0|_>9e2>B9JBa)bY<5;?o2 z$MZ8cr-y9boc!N!k(;M>ls54@XCPTMwqIn}Z|czj@s^3$s$XhltIf_E|94v$|Es+J!yEU%+rs=`d99a? zvHnlb{=a(qzpIwr=RddqCf+9|Ni{({oB_spFe$ET=?+M z-|yeOeKSAz`qk{q7c=s|od9mwbqSr-5 zMudljh6D!%a@Pj<`}z8Kd#&;GaCdX%uvf2gS-Ha5$TOsGZ`9dB-fs<0dgQc;=1LLAIo z8@srt;<@kh$|_AP!Cr{v*=J95<#9MtkBH64Tc9aO$R8ZW? zb-eE#FH|%^dvVKDS`fB8dY%Hj^|haEBE9U#y_R}NDa4U&%H!qZNCYh1vZ@D-qPs}g z@6y!DaVNr*`Wz+d*b*aqjW{o(1VspwXjiycl^#!|>Mn(!j_7U<(8bx4@d|I(G#|S< z54-k-Y&d%Z+M)b!HISbX?uS%Pe6Ap;RizvJ+f=YpB6@wJJoNM=-s#zqzBh)o=Hq-1 zU45t097n(_Ri1Xjo}`bva&V}x7zUl!+PC;}Y@hj>fNOo~=F#)Eq5%n1udoIG^o_yG z!6I#Et1$-YrDtj8+#T;K+Rx~!Oj3>`aq;CS5>2Pb_vYyrU!bza7APy;j7ce2_)!~* z^Q*(E^-g)rF?oE4$M?VZ@X8GVu`m5!^PN`@%O?b^Qqbr`ZzT_HgCpd}3ZO*#9>Ja& zSb?=&4y?fVQt2Yhr77qBb=dRFnKGEYT6*P@aiJ~S%dBDkQ?vH*$#FIab1kT_vZHd{ z>VHm3#SNIxuC6FUiz-(V_3#f5il&9A!agIR07ow>bt|WRo@QfAd$!-_5!<|^ibM!N z2-8=E@I8i!p9|O=_}?m?Y%IQTK!s0bjHXcrbyn^(yZz=&---gGQ>Ar4A=nVbZ zc~z-yIATq`rtzcLrJu^|r44xygOUK+!vdUcsid)!ou;{L;>8q?VHI62gw*yF@!fle zEjN6+ef{>tVa>bB4xVsTHP=BT_7>X>K0lnp0s08C7!Ea+P*%`4eSb#yH6tp(&jFX#*7tFG~{=jB8H%)lM2Q3&Vqu8x)$_SF_z%hnP>BI=#x(~v_ zTB+mzgq(N(ggt1Qvk@rd=9r>kv2>mh?2PK(ONPR?XT|lgac&hyzvbNDZTP^Z+xO^H z8@GTq^{GR=bg7N4;;Hn$oEe4^kfGwk_Ts=8OAO+fxLw0S488T0l}~t!eqel^LH)jy zokj+ayu6}3RPqiC!*PuKKhxs8e=T{C{TMaob$p(F4g;bj0`&KZYVdV4FmLeHt>YH5 zYG(>OyktZbIR`~-1Q8t?TBB8vExQWR?BVDpGax*Jj~B`mx{A4H@URJ#hg7WgK~NA` zmJp_95V3}C-!#m4Um?-N%TNZ;YUw=x_<;rzvsf$Y>F(6`bTKj?Xww_=ps2_^!Yg^c z5rVeUT?%PyaM4QdZ($vM4b%I$07gcexyuI$J2(g@TiHga55oL`AN{A)WC^7uP~J3U zLsysw=s(JP;Z}?yVj%(fyDaY^6`{%1!ldY9Zaux#b?&3ZKknXeHg!Glvd+Qg#@61izl;df3|0gn6&5EGyep z$Ii=xd=3rBr8AVyCu=T>_$HyBJ-`uZ)&%A$-3_Ro!$EnGDZW^blJY58P!M zn&!Iqm(<#KmAOU;x5+Dp?YtP}uE}ob7r{U=I}aR`6&kxVDEKD?soINZc!7MdUnZ$w zewL8zBaAzPjAS9o;|5wzoq;y2$-0wocj4b_`)D9hjz#8P4md{iv%BbFCYEMRaI z8PuvKgYT=pFfmep>!mF+kR;%aAOfPjY07VZ)s2u?L!v78@{n@(64AaJ@$&w7r;5K2f{Q zIh89}EN$a-YNo`u6z};*;)Ql#=V2)e=W)L*ldV|Bg>eh#sp6n|jeD>DijKSetKX9S zvN{hNLWRzR+H5piT)XMD#&hy-OLya_gG;v85}BX9!VHg=K6NntcH6q}{?K2|2YzcdjKu}x|HW_G#by4UY?3 zHzy4Fom!{L<2RL4`Jq0m;;N}DdyQ1uOQ8eK2bu?ObolpIHrj_g}9}DCi=pSz;>~?MKKCSaU8({NxM4Yv3~QkOz=(y zF5(*%^#{gT5IcX!%U)OO5Xbr4(tPBd+Tn`G&rPzzgO4hh>x`O0_9kNID0_PgFgl3? z@nPc!2GXgzcmR}7G76{FWO3eDvGTn96pX5Jp=>fTt=;z-YHUXF(S-uI&Nv$GC|AVr z?ryCSp%;g}P|hMyeru{}$ZPwHH_}&Ib}j(bzrSr>e>1+4b>--HSNg^c@4U8t^`-P3 zn4hJuU0az$y}9W13$4i-2Y-z7NQ6WqkUgPPRb{V`Gv`id5^W-=lJD(?p&A$&?@sc; z6Q`GlG%;uGM<3l$J%4t{MSg$PL`P_<)^TsAJG$OURe4&OLMVpVeh9ySwA`KW8jYT({@i9^y01(2N&shj-OXWthUmAaELoy&VANJWMA9 z?hHa<0NFo+?12M~M3f5;ako(?L%eyEnLonU;4S3Vea=;+qCM}U9Yo6?D>#%6*(_ic zxl8L=WP^|)%BY$c%u`-VXs-gPwqpfn3-z%YfHtm2zNUFI#NRX>zLFX{(375Q0EL#q zR?5*33@Cin$A;0=&u1_f;QBH+)U9}YKW*x3q$NyKsU)qIn^j$9u%CfF!p$m{f^3oS zom@e4L_r{O!7dZe%LMxxZLh zL|mEOfZjNWOM}54RYBFnZ0v$_Nhz>ja5*jxqU_Il&c+-B+=PUch~A1CUT#SuF~1og zM3r!waKE7PUxU>I2A(VhZ(g&*+*M9L)W9}x=n67_Jf>2v0z3B|4IcY2FDlBgOjv%11U4S&qTF`&!&+am@b zD;Y$QL!MI02ZQc@ahCXTHq_ur$wMXs*gL>fIG)L$4IMBRFX^kaw`fJF(eO>_?}0dB zpCXP8JVom6JXG|8o@KfwB!bjf;1CtQW8OrQhw$Z5-#~puh0#OTW9N8Fkilw`WQJ3rPYyIAv-R9U$x}vjIDpV;T_gPr ztUh^mBE!HWL)f5IHBe-I&35DQ^gQJy{av3L#?-`B8}(T*pI`C2tOh+uZiS*?yVq=m zqHs*JP$5^U8l$fu7&n#3@oy3_D9I|xIP$myR=X72DMLkEU$qy*J)OJakqGBDg-bbK z2J={vdfp)Ip(;l1LIAKZ*p}Fj$dehkSfWCKT17R$8|`)y0Ga=pV)RW>GN~C7Y=Ht+k|Fu%PRi0axVN zt`zA(Y`79n&-arqrwmSF^ZbS=TQWQjhia7;q#Zz{y{0bvh>z%H-MdEk-s?P<5=A)SXh7WUv zy-8eJ!4MsKJZ|*BN%5}*L6MmLvB{*FfqC?)e>h;5iB7kCv~c(N7gg~~fe z!^)B2mbT$-VF=x=U@9+I08l~(G=bp=8G&6Wde3OnSroAPxz~*ixv}^DTd!CYO!q#E z!3Fgw3ROBD6bmMgsk_qJzfc(mwEX*v`&`j(Jk$>us=rWEm({y_u%1P1P3lu<=C&pu zY)#qPn*8s%?XdGnCxUFnaK!~+BlS^Y`1#+bJ!{lzELZd`V0HwaP`*d$pIxdCP_;iC z)d909T-Z-RPgO_UjCK3&*)apUCvAxz9nvueT+kO(NrjhY{Sx=tFWN=g1bNa+C=FCp zZWY=e<#buZsb$03$`mv`a_)+h%I1$W@f3c{9(o7|7v3H$;2DjG4lVUK$A3honj98% z?Y{zG!QNZWzg&BJBR-2IFfvkn>4teNO8CfDdbN-GageM=2DtIlDMBS?nw2Si`Gtbx z=nW1nI2XD3? z0Fgn|mdL1lh+Ox@%tfpBrlF6yw^r0}k4cG^abR9gUxw)Mu9MtXmWiSS8z zljkjRi(M^)^M(4n`+7G$n~z+N4K#=fxJdo%5u5*rmQIFs+iH#u+xHkYn05D*zjLVe ziEYQG{kwr2s7mWP;nej6)a(<~*q9_d1iQR$?wd#bWs8cHD?}UPv)R~}{pJ!e-cJRe z_;_coQeZsHIR0Mw>x%d~0H1ZjI?9c5g32|C zD?KAI(N5S`6)sp_%qi8aUy{0htO$1S7@DsM4jln>DAZ&oyl)MA7ite&&HPlGnQxX% zIR^LUqubQDGm#H{Vp-c)RbTDhj+CKpriXl;R?ZxV_%+S>;{`1_sx8dJA~ymuk06j$ zUA+f*z;^Wj;)y_eO2wVq)2Q3Cx5(W*b;$SlK<1I&8bSzp?|_H57Rfn$efNzTP}(3ht$4tT%oMH5EDh zbYLa=0u)(MLwwjd_UndTS9QDf?Nrhb+?jox86L@6;L9@u4!SA4n&lsnp)TwWIP?}bMcnpY&ZF+Oh zIbdRSZ@mqzxB^1ilIvz0za|NYsZk9vPl&WI9E`~5~HYB zz@hfbF2CidnWp&z-K_ZXu^9(GPg5bCb?`c+wK8Jrfh#@vkZtMx>TIE+7`7_&@@TU2 zdH2&(={s7p?=&%kR-E!X zXag>R=@&g;pw1={Y7GcoyqmPI_`hbi7*6>=`sp9yiu=1JVCwHJm!2v#vv0;!1zdPp zdW(B1wQ8yKnhdq0gwQ#T90A-+6YimD5JN>@^$r@48x@H;l~s2t<>e!8N;u+QpRlm? zuLBiAaqvxWz7!##ES3q@uFIVRRH4~Jk~ckr%EkN;iwO;n{bo<6H=q%F*kWit z|Edi?m^p$%zqiQAGY?`yv=E>wvG_**gzJnj^9^50L|JVEjV#FJ^Ny=EI2ID(w@q32 zkgTIN<_-W0>1V5Prk_r-LjI$r7dua#WazqS`aJchq^)=B>nkx!e$S(Zll^?yc`9;~ zrjW6IL;hA4MJ}64QM&eNVJh`zQ`YaV8H8_+0BqYa^}G?j4L5x_;O&Vha#7L}HGb$( zU|$r;05Sv_k(;RcMEieU`As1@xI2rExTMS)Wgzuo7?s%cm!kN$B6_+96BG+i``TdM zg-S94e6=WzH$p!sI};TuClpT469jV9ISjDoZT)MZWatCxV?e2)%;3z0Q_pwY-d*~1 z>NhNE z&Mf|M{(bbrVs64`%gSGh7!20MS76V_Cfg&h(G|-GDi6!Y5O!ny>@^edzCZ=ubiBEx zwXLbKO}AA=SGV!x=`$*L7eXHek3zY);3Yr<@8(7k60B4y1jx4v{rZo;nz~Kq1o+wp6o$pp$0{S=d70h);mak9?I$V)lbstxv z0w(l_vR#^ZI8gm};>r1{QE?e(m7s^tQSYc>QtP72U;?0N45#8hidqy4aeAmeG20U$ zval9@`!~(_l!CY$AyflXa10#vOfj?Td~m}5tWV302XB4bSPeJG6>#)!oO908KBn8X z+g+ZPR-a7==8zW%9@p`q!T$_i^%0JJHgzkML)QCW<7SWO;Sf0dPfd4*4D89WJWLM%` z?~ICJNT5}EU8ZkTT{v=T#-&3Ce%&N9m>bVE$D!|j~1c{gE1eUX5iGuMoaF- z%V}jXw;V9qd|NgfZh0>cMHUiyY_jS&-<|CFnYTRj{KPUQ-hww|;Wa3jsOgrbmwUIn zn;My4mQ27=sun!4vhZmW8_hl`9k#W%T}IJ0`$P#4L4Ix)fRg~&KdudQhdn9W$5wWi zK3WTpE`>bF1^G}hSx~qH>5(;D6Nip#Omj=@YJGxBTJ~AZ3}AOkVZ${_mz{3-sHKGX zc%C+LukkcE5;W1yp{GT}l$J@VeCRG}kNj5s{iTNLIdD3)wbl?ecr7# zycW}Q;duWJM8uV|1TowlXn#39NKn=&z%<5)I2e7I;lR+Uz{2T>-2KC+6|vDo?1|QN z!{AQ%`zluzY~^yiY+uUMFUDSy7elrWxjJRZeKZX0)))D)RQ@dUFswA}p-0I1OXGT( zn7+lLV(9ad^qFN$+``B<#e8WNDpFfE3d`+-$8G)~C#_d9eEQH{VfsJ=v_08Yas)O> z@E3&KOvODb60iQIU50yqO1vWfyGk(`f!FeU$zQoXah50IB$Deg22i8|#hDx6q^DZwMs!c=aK3 zTkG9Nvj537aqz%%);J~fkGr8R$5lZrvTWL|$u(%ysQtECQdx~?W!344KAAo88#ZjmiB-1t)__7oH5+jmtS+QxtPf$uQm!0Hgdwg_ zmkRU8YRZBe_LEOW7)6D4gkgJG>i^`lL_R&p8HgS5u3h`a`h_#5?9 z3bd!c947JRk5W9)%lMCRj5IZ?Ns|a5LMVN-WSQm_pAV`saeG1sh%iKjIYo7CO6$%R8Uv#?L{Bb8V(t! zg~U|`s=#@L*Go_10>yJsn#^K_<6A zGkLCcr+BTgNA3|)Ga#|x?bLT)kEmTjlLFj~v>6BT)wa)RpypjE=REV5KFg8FpM<7g zaNsv}5{ku4;B+RBVQFH-aPyjD{nPhdhX4BEoo52qVj62f31YRddF!x+=V#}JPS^MGG7 z{D8{?p6ca!&v$29D~iYPsUo!2xE!)&OpFE^6K)8eylgSgYtiC+FcuZF0 zb<1DF+uMyenlO36ol)cx7W+Kftmelno8wfQrDFfl^IBi%2|X{?UU)fbOng6ZaX6?7__4Tx$ zVxwGkAZ}g-TNA6ss_lq-@6q|z{FSX8&>Z`iem{_Eb`hVx{BI&La(Mb47x~F&3@Lv6 z6&WiDd|n)FEvBOyV3i?Js8YJ(cim*7y7U3amg%0C(Zck_?S;5DyLA_lu=f)b%_>-< zT2|csH8_bkPU_NcYoEUW)2e}rg3}g?(qJ`E>H>}2wEp5}nsI{Tmq02KX2@SKz%dl` z*Py)$KmZwqm!%10Kqyr>LdC2wF^Zlpat+6xu`xUAMt?F1S2Lo2tu;EvAaEH=(DITT z+8(lov%jjU2+ps%HzdT%h4E{U?h@mKd-&pyjx0C&0)lRb27B|j*60%qLJ@d|i(x!u z#XxCLO)%9=42@+nu=?ajW%6)Ry@?jo%xqcUw1^U#77ZUdXo34XEgleSN3@ib6Nv+w zS}a$U@s)xSg6`x>`*8?}xtGX%IFB1nGvS#Shc^cBRn(`5CO6svRi?U_4sS5t?HABFs4?tLkKN9x02ax`oMV)rXt` zc6&lX!nvJ{cxC;JT+C=t`lc=lz&F0&j zHfF&m@+`GfP=L*+8%-kxMD?~Wx&lewzt!tLFm?4J9HRH>P)u#k%qMHHqb<3c`a2IL4)Wi(Z-oFrmG|L9U?8sXCuiX! zU|F4?j8nXG*JC`=ymQH76m1H8p2ZQWAex4{DGG%Fh+{m&Wh4Sm#g>>>Ue|ZA5SgGE z2sJKHs{%SzU`KcM?{T;%SAc$$2JC)YfNllE+|W@SNp{;1+Op({_2{Gw#AlIhnx-5IycJD-A6WDP}PL#Uh0F{ za}oAZSO^3&ml8a9Tyr9Vf2|^r!wsY@WB(>Rmh%m-tiCkASFiLO8B80V+rigBNMj~J zOr}Wnccc}$r+mfd2oi9&o?s1!q)a~CNwsBsR#BmgHQffnehCtf^+jYd!6J-ZW1?ct zIc(OrQ?Ez4`JNVXU!=~!)-$Y{d?`p3Q*I8RvZ=J?H3D@7U2A8@Ga>K`i8Z>WsLM#* z9dcAr0nLTI?=ExSzeT!s61$%psQw$Nv0U08nht|U#jMfAH5nOlDTCE9F;t)1fp9F( z0V}UnZqvTxzNG(DwJ`ssw#i2w<5rs9$LKnVb|RHtZ{uGm@ZT-;KkVjI3rAOF7_M$} z_IZKrVgww!Z@2+f+@iWI0OtI8E<=TyPLUp1NW)PU@~=orhlyO9Fh@_hA|B`#8Jn1c zvL`YyM1(A4FtiM&CjxjL>W}!qu+7?1L9yQy;7VPp^FfOf!jl~oMk;%Ff$+`^>B&Qc zO}K+hc)~eDz-1|25Bm0!RZx`RKEZroT)%eKtd$*ETa>G=Mrw~xQMTQC<0H+NYVmdm zC`f1|fM=gYJSVDaOJS$Ega--;em6oIeB?IV_?4*%|DeU|q2v|H*2{Q?$1t2&u;g|^ zLrch)1Qb>^$~Q`tLr!HUb;^TGW)5dDHFxmUyhgNgUaM?LYrK|VVe+%_&R5RrQ00B< zM(fDI4MuBzpH(i+x5>AO*3;M3(8tU%^>21n4??>4W^~y1LC{$p`^P91%zw|3=h~lwph<^{<)}#`WW*slWN?m7gH|EHt_l|(UZQ=q8gr79NhMKBFz<( zj#;o3-(P1J?kJRj@^OW$)Pp>c0cE^z_f4dx45=#8-C71ARs@uqWxADExRP+MGoAff z+TRtnm;dyK`J(k2_RTR+)(izxK+vxEbyn=NpXLN1q*<=f}ebTxM2H^WN z%FCI1ZDd^=zmhh`g(LQbIA0<)pC$EgX;PjEs-8h-)#j#iBJD)*$68trS;~LDpEc=M zHacr)G$elG(P|y#I8%)ljO$T_x-Q?fSDCd9EYe81OA3}|sG_r8sZ|B_02tRn5L?$y ztA_T1no7+7P>pV?g(dUEdACrEaUb#Fb+HTwV}aOy8qR;a&*O2Lt$}Opu&%a!tRl|V zYF6sax&HWt+OD$zR6(m@0I>#>CQ*NqGNp zMrO%D=jZPI^(Xr;`^4Qvpw7!NcsYa=YZsqG7%rSd0TW+_a^D0rEk&sDOwb||JsCkq zW|B+_v;tWa;FDeg;dqGKP!`)ph-Dk&7wByr0^@kR!G7tkuf`lX`b6SL#Vg|Ju1zJ( zHL7n;bvQQW@WUH6tcaP;FdSGSA0eOhn6cjcT|2klA`mK@6bnP@1q#HVnMcr+6m~an zJ>i#3p~B(;a7avp>s7*LJ_3CS!hr}gCc?IecF(IYiK<$V3@%dFQUZ)$Fa}u-zW6c1 zYuLk+x%WvY_S|4@R!@~QQMtlSt1cwIcz{gq<8i$I%yOKRCF4yd|1~6_waXp zrdiCd#Tv60a4nnkX&M5&7)W;|cRF4S+TRH1M)5ie2l0x?Khou#f>W=`luvC)6l5Q+xi)B3WEOJL4ExL@ z@in_ybzJn!>_>38@`0h@*E?^uwq|ZsA7T^6=_bDHGc+Vt=Q4sCPS9OLxD7`t%|$++CIAxzIz7PR-fe0HnHJ?lyY0-6eh1}>nbe%jn+%I)N@~a1iW>B zEjCRjteeSx*iabtuq*J*Yu$#~UDL(h6>e|#=*-p`QnK($e-`r>^1v^CS{>uuoBg%^ zD_SlW0fzkTn-xTWcnY4QDUHvJzDnRXj zVsJB67sp2X_JKVBg%d-E7^rLgAj8RM;1RZK4R$7=pU8Jee`YOJf5{2IHnEofxLp$AR(8iyly9cw44?q)l!)UtfCJ!wXj?+455 ztQ6=Iv@G!B-|5u918uLY(hEXA<*#!4>+)+iLNXEN!-lV7!0npv(-`nE6E`e7OrEo` z^=s&J4AWs@QW(f&iec(e5k5!At7V7xb-61u=l*(JF8XM^|MBY+0s`iClGmjOjm~jY z21)5zgzBT2?nL&fHFJwzQN8t8*)ViV6=hdmPyeQoF5foi_+pUzE;gset zx;0j+S4VVF0P%s^({u-Ak5MYWtoI6XFcjw-%1|-=pzD}@n-VoHX=#h%JuuO7{@h=+ zTYdE}Wa*RjF|kzi*5le&{z}W2j2fd*{rB6}Uq|y9=)IpDqe1&4r8E`TIfuucWdb)dd4xK*V zb^crzTz2E~ZI!`0w>cwcR36?{VVz+qvLMbmA4jYs3-ij*5DS^Nn;YUBFotb_YL996 z#bQsM08cM$BN0Ofc4DlaO46=Ddx{hjEt;7I`bx?UOYYHq)cg`W#n#G^=)@W&X#S-p zsZ}-*-%R3U@A&ui$0xlp%z?ktBX3673z?@DKVG;weH!uw?(bf;Jw2E7B=h!Qw#9+o z_}g^^?XcQTR>H05kzZOo1#Nq~pQaJiVuCXg43};kR{}7m%cPme;B^XcNS%Zw%25OB zn5lSKC}=(Nm|}KSEztyl@vsEMMwv%2}r~dqb2Ub;|kbRHUG@pO98Rv0g3J?AJh<7Jpya~nIN}OlbuT^pu42Gx- z6>a-U@iokxrzTxq8~zXfS^w0`+h1SdZ_ln?LM^HPdx%Zv>aKU;i3f11Unz7b0#>Zn|P!R7D*#Ln|90hPsd14`& zB4Q&|{X{ZIO@|R!g#@P-2zC#ni4|7Y)s8>#hjU-z*8UVF%f4qX`Ux@6FnvZfVw3b!sCX^g1}ZQWnjVqaa=ZxFqtS4k|lc; zRi4SK;QFP+d^g9$S+Sx+G`9n<=|t>w&?fv$z%!+vRrYfq)x171T~+2E5UDG?9V*yg zrXKpx@a(V(e5z}4#tnvo<-sw0}Doo)C~De=Y^0EjhEUNHiDX`C%OJF%ZbL2c)=QKs7$Jy7T^ ziyqh*+oy+XEch5`>LUx^++Z| z*zakS?atku2T04Qs68qkfUvF-2QoIhp}xb!X7BGi}QzU`fVOz$=} z-u}t*pyJ73xBM48g#1#7O(gj+&L?ad=yoUS#wF&Jc!-EtoEw8ZKtwh`BV|@(0m6{{ z8FbAq-Qx4uO8z$Tfjt!NfWcmNw;WQnz)*-Ll`zH^OS_!N7K=}d_wKWvGBjJvqi(E; z@BaEM++vqtt4F0BXH0U@m*Y(wLbB*0$k{NOCvH~+L_mZb83iyDSXc>g?=``S51@K> z#gau7k<*^&nXjVlM7@exRjKCM-qBhPZ`ZnhL1l$LhV2_R*cujD(g?qXQuSlD}bj^=1k<2) zlPd9$T_S*el!&#)IKmCran9$Eo|4f(U3zud(D|P+@DxE_h!A zkTgjiCa%i#J9D#9`ioLm_N(#TUesXQ-0MhUDZXL5L4Hqp=t@iMiY^&e(;B)~^h;L3 zaH;S=BgC%VwZSsQRw?526CW`6k+R`ryw%p3fN$e`aA7{)Huh9~)Rijor3XB#RKFSA z!a27r1&n%o&r#Tox)M|$0{G8P>u9rK%o=f=>9hdVP|&TFm~3N5P9}Rxr*3oSEbd17 ziC6{?`?=ZOpnV|z9qWpVW*qb7x?6(mY%ez}P>mHquz49^G624EV++ifk#|3gwYu-O z;luWX%C0g((haiqWOsJOX^4jLOH^K}jJ72`u59%1Jlm|7deP%qVR!zv1+Mk#VGzrb z;S-Oa$}y1vc>Fc?gNelNieg!NsE)6tbKg7vxGY@4 zY@BR#U(BIIBV#1&TLc`Fr)1G-arB02lJw);p+uHR<`^3-d3?!kFWxhaNxLf1p2Oz)hjf zE{?jtb5tMmP@hqJ_p>oMJSj)BH@%^jHql^sruH`QbQ}z_;K#|4Dc9kc!YXLo7NBD0 zVTVTmv$Ttbw=9_6_;cwO%)yolXN-Z!XI1lN`kpB&Hnw;k4>&~ZbxKFVhz%JJ@y)IF zsqKWZPMf#ZA`832-o05*soM6X2MHBhBmX@)r!t;hr2FFRA?}=~gT+;ZdYqP?j3q?; zLoZbvwOX4yb@M$Xu8q^vxEuX_$XgzBO7r1PsqvX-y~4gVFgzKqEpf?XN@#G@L3Tx{ zab6g4zedeHf@S*zgiG{Ni~lY&p%e8t_X97@?}z8C9u_eAoL8K6S_^G&wL#1$W*jj% zQq{iTFD?uYyo>q!aAEo#;jm%r_37fCmD7u6MIB1C_TrFE*lt_lq^92u^+k8`o-n(+ zxtKAGg2p}NrC__B;oJAopg8opB8ZD{{~&%FCjQ)<{BhoQoV!A%}4P#!pF#EK1EhB#8e2s>C|AHU^xYWHFC?*3x{Bq%yFJHSf6v%uk-+5Q9KIX-1sVSx zj=!P;R1*SY1c9DuE4~lMGXhuMxxX^LEl9f&;lOiYiD7mcCZaTl?HQ~7snYY6QQn=! zvd1Bg6hYxBwKITU_)3K|I9&o)62o*jX6Y(C zAK@7z1^3Q_AK}}u_mO3GYvR>xV&t2W7qoX2Dc+&6k|rv%7BvipT=Kg#MxZ^viJtI+ z9hnoWC{>Vy>pF-0RE!+LEd!YHsF#DNSD}?C9zw+TjtVw^p5T43d7a{LN*%)PSdZRP z9My$O*~_K&JOHQNZQB>@&Og|75K7jqQuCGhtI2(Tc|wJ52+i&qO_qh96nKv7;KZot z9v}p}<0JehGZi$X3JdX&n%JPA*%{2!BOz|`J*D8RrCJ$W@$4XOEM4tqT-Di6E3T^S zVm}CeSW`B_R{cw=tZlEVod&n+QYLfa+NCB3&mpv_#Llynm_AActT$&YcHUIZ)}LYZ{SOVo6Nv5_T-D@eBt zQP?%g+Wf`ca>sciN2cCGuJ`7A@USNEEZ6lY8TXq_PEE7fGokbp^7<`ZKign6IqTLH zPI6gJD}U%3K99(QNFmMc)*=@?74oHe9yF$IsD>WVnd4)q`XT#dwhgYpsV3uyHSb8w zI8Yiw=>;EokhxZS#`6ss5@8(1QkS1XZ5GcnF1*eQo#)m(q| zsD_!b0|(WGKLzUs4c$3QoF8h3qL_FNckP|QEq5fiAcbWAAh-iJbh0VLkB0wUwL4qx z={{+7pvtnjQRm&Ou+qE}2FtOzGDVI7J9y}8o6toAZMU7sRmz|i0%Oc09gy~h85C7a zzV36V2Cdc1A*WYsH8V*m10<>edY*VVHx5qa`j-ci9+a@?A;)6b9$TxA&E@R&QCQ{V zwD0398z&eFqlNMk!tv#M+t^i?iW1&Ulp+tTBb@Wr>9iB5+Q+?sP+}h;(MHH-&9tVv z@RTA{5gLqDhCIZ-1DU>3+HsjbHE0$9okpu5qEkct(&P38q{2eLn@jTEf3 zQf8-rRN;)9iMsf8Eh_Os;`v4;Z%E)WOuuHAS?p@%(u0_AgV}K5Tgad>z0c+W*KR71 zDT1+hFdB_r@ut0@A7|5R*d;R_$hXj=!A=S~ER{ohT4G}GPGNbWaX<9dG$Ch(|P!Ja>nsn8k)g_C>re8JlUfRIDU<6RV@la3IC z!u9wWF_HUH_y#`Y@~#L2pNFA(%e$vgvgKs)t{MXtL5}ehz=s4%tkFo1Co$UHo2eh6 z!VKUhLs&5o@lu%6wzJE7T!lm@Z~SsDG|FXsI9Uwgr3gIR-*O`~B!He3L2cu7`)#X2 zvI0LUD@Ge1xC|6W^h*!?Q04g+c3rFuJ~Zlx>}-iM=j3%H>%+FZ-*47+Y&OHCoti%{ zfoJ=A6&_ab1;rWb(8Yl!*@tu#C14Aq2is+atqu~LFCp<@tE5Z+7enX4kmTBc;rC_B zP{f5B+$#gOrUkBC8P3!k;I_5 zoZZJHc_c4H55`_}{jiU6YUIt}T;RdJCYCQWM4)U($=t7ncwQTT5I9Ns#KiPoGmzQc zl6TCc>LT=5-tV&t5Bp*8New0qIs4`q)*fI1niPU25c*N{yURBHOpJ0GT75+$WuA;$5u_ z?AsSk#zT}X2s6pvw_fX1+|fB=WO)98L4zT!`ie}g#PpS9upt)5_QI-ErNzY?$|@C& zH=c#E$<=i_8Eaadb#)W3C>LVW`MVqRSJJNDecCbdw1m@i{cifHM`@5T)deu!j)~;) zAtjW7&he~wj@jQq*dUe4V;<;RrS8d1=g|(l{-X4)0dn!7;%V)DpRem4Xg+wvY17gs z(e9ND42_qp%X^s|VcGwVpgK)`m@}T7Q~qfJQ6@-eiUx@6gkS6`Vo;K89v_D|*M4vm z=!?UyjH)p6Gy110qR3<3$S4MqimAk%zi8b04|`sRIHc3L!5gc84vm# zZET#p0hbCbL(v4h7Yu!H#GQq;9F}RlJblrSKGI$n+EC}rVrdPWq)F2QehhW!8wQ-0 zF=cga_Un=gTCJ|kB|qMoO2K}!n2+m&rV)?Ci;@b{z2Lp-dd=TRq@U`jVCH9k?ACA zx*&Gj96X7ma{E6>2!}$LgOh|7B%vG6$@EmON^!aT&p=_-8R%M^=wLJOuR+kw5TPml zVutsA=N?$B$P6t8ZIdaN>aiflGpq_g|0b^88n4qhFdzN?W&I%Ik2dG-yRsGia& z|1W5&obEs2-`U6Vno{2thu28oM}K@>UG>)X2nS*&wj&G0x*jrx+|F5 zyl96k0n%hD$``ktO0&*mw$B({(V$nU>8!)fI#SbiH0#)Kpi0lD{XS)l0VS=g#r=Be z?_AUEC?(}F8xy$nv&IVPf~QH%#l6JX5c~mN6!7Hn(MHtg2# z|1z&NdGYj4DK2{F9_8naAC+F4Fnom$RR9TBM^^Jo zF&jU>82-E%36z5>ou$&^QMjU!L(}@?#h@LE-~ZfRRB+7it9=nJG}<`cXd3;#OeZ4x zc%4uD-lt&s`}1|zkN!cxY7<-YH@N_MvB*!!Qw0J8)`q2dw4D7G;Wvii0^wcEB{aVK z&^dskI%M(d!uKbaP7tAK6T?gAgpv(IfVUaYA{cqoMKC}vlgQA9`{wdycvYJ*h=n

hdi`l*K*Z090(_pBO#I zS@^tL67TN81pXN%de7zpi+%R0`LbTS6(wvRG;2A@3SqJ`rBg7to(=^DWpqB|NMjWY``JnnXF1~$;TITwD)Oz} z3dv{hju55P8P~U+b0_SAKKOXsZeT^z0qin48XhsVHGWV}Y=gRLNk>-Ly~&j0NP*7) zz-22B@ZDp^f_qxe&1*qx-^9jwyHLjko)(R6t`9An>@So2?lQGOd_%ppZh%c=8<6vw z1jU_PCJA^D^I_Ix;IY38O_C{jBl2Mhxg&-^{IC}^GJ6~FI4ERAJD;d!JMAAv>7jc- zws)+(tq}#sd z*KCJ4%ar%+^fdHyj7QeytZmsbxc^5G5>BBqa-E#DnvE3EYpB9XS$Y9d&4>v@oDL3m zBf>Bo1qm&HZdet`+}chyEK31uUL;x;{8e|LW? z^?7tc)3XMx^k13HjA&i%TUcMj^#B)Y<-XA3!PHL*;T}fkiMPu~1ElU)#1tqicE3a) zKIWRE{IG))`4|Ym;GrR*qHVdEpWyC-y-|xII5e{v3_*D!uJQ|rBkepA=WeMl4(m*$d-k*p z8mVVHNesWDxCeTGsZ5L%AoTG#i331GRve}P<-WP~8FUi9A;lQqZpJt!4s(HZ4!AWS zMaWY?cqx6SMF4=n7I7$xTO|V@qsoKBI>8B%PU2uLw9F zqwW31RXeLi%5(9X@}76|r9B>+C=b@NllE)ZLzDWe?xLFNU$|aN%RFe{w&MX%Ex6sb z+5%nGdw^E+!nW%JNULEGm&t@E6^ap(fW()FZD-yrw5b?@vfmupp#irYyvj8y@AidX z%bp*+-D8Ig6=&C++F zFFq6I-@YM+&-Kkj&N^MZZNc1zt2O%X89#h__|w=kbZ>FUY&i7|6!)qEfLc|8&`e2G z2NQG9jmJ@&7n*gG>1cb+{HKx35CvEcQOjYw?z&LoF9ZXSc+O_`-o}dWJlpYC|D8je z7V452D#X~NQ4L_4#R7m5wg=VgxfMO%O@>yBpvsSFXTnNP>UL3M|4Dlg71a2+Mc6iB zk}5wbVJ>RwbL(r&sfA)mwBgmsk>La zkAFPBqp9=k5or0unG@@m-7X%lco8&$umCu)MOtkhZAvwk##OG}+W8K1pedZr6Oona zj~zQKv#(ZiGv|_K8{S$ZbFqdWO!u5DPP5dnxf{X1%)n)z;kMG5&~4hvtwtr5k9rMI zG6_wKQ!5HYy?n{B+Gd=~NI?evrqte{5Vf7X#CXr-tBbbd`dK*_Liw!vBUTgMuu-@) zKDRnG+C-!Z4PIkk$SOM2*S}$ph?@uSRr7#;rij-RQ7@OJLqYK|7wU_7A6ymyiV%!k zsX#VtI(LH#4BCt5gl!jtb0wTY?G;KXh<`lt*{C?&pDNgsgL2+_SY; z4*g^-V<=Fv$mLi2I zJeVij_DD}3GiE=6C<>*&_pagJ2wmQ@-r!`#^h&pj9Ffv|$=9_3BCrp$4nK z!W==b*LFFe{g3=3a{}ON2Xy!(Hk`Ysk-O>M zw2tkt_hhtK0R>6T8jRbtlrWNF@v4%Eu91ek1-YGdUW~X{j?@<=h46F3dgKuzxXEZP zWkqFl)E6O2%A~3gR@5*6Y-+dhtI>#d2Bor3+$W|Lc_mUYYt1q&NLcZ{980zS}v(f}FO1_vnZ4L>8B80H25q6)}Xt zFA-2+7Gg*-3h~U|QRTJc)(twwS1YwAz){S+#lhbKO5MlF{$iM#n}F zETJ#ZBahT1KB`a{g(%t~U@c1#SityFGoC<$oSud2zz!!(*@Qk;I!lclphIlr4u|wa z%C5uPg@}n&NGRDM?|&*8iv@t0AJNQje(QD|uxXDLTN6zkZw*t`Dye7vOJPj3G@2lv>7fUDCmh@@ zdMn;ANj9z6HVD%%$x!K%ti{hw*=4rfEBv+@6QcxbuI=T@Oi*F^fxKDFk(1I0>RSc* z??zBZBRU!g-y9cCS2OY)S3~7ZE{n0mcyTW+Sjn7aYUf)(wbi1Cj+w zXpRBcXGQJDJs*pIw=Xs+O78wrv}{h?sF_VGPkKZI$_p$cgg`I@`Q8~ztN;e4U^0BL z;u2t`?H{}lf#^xwX_Dm5vQlDWxdylN!W$(-wx0qNKr>uiF3_KP6P&-tjXBIoQOm`)Lpu5bWgLo>YD z3X~mxXi%eOeW@+wh7d~SUo@rYOCPo3dxt7m+r9f4R;OuL;$H@%%a{)1B;}JzhRUnf zOkV7h{I4g7@>BA>w)QlC|00z7&k{ll04{mwp~nrs@D$GD)eezUjx5Pz#E7NDsy|Rg z)P%zCF+(S3#cH~wfgG?U6+*MoQc3iSv$-MSRE#*4vYsD#G!o5J#sJV)t15qA)nu}2 z$Z~_I2x$9K4Rc98N!*@Re)!>RRoF-jYD=h5N3-C7TH`RH2w--ov6yNoAtEhTzFcXu z>&}%^&-Lp%YC$y)=#B@f>xVDrAG}jgf7u^)g%fSTgdIb}8Cx?ZnnaYD%T3Em?LFv; zVJe&LXB!S)#?$ZpEOp0+$k9qI{#}%b4iCM4MmAZaT;-_xF|M_qb>&M`k}6ubWag$+mk4Xf330?{ zjs-EulJ`lf``fohP+qjhj3RQsw2G?LE4f%PTJm`fi}=FIMToYC3C|xJA!fJxPMh@K zo|QMtRq#GDo+1sna}Wp50mmm1{~QE3HDL07^I*Q3v%t#^A9t^%JK6jiYuz*`GM3_y z-nv^dJmQ=@+2gi$h(zLrRQ|ysCZZ&=BX;YXJg=z^Y+;Q~;hGklam1GQsyOysdNazH zf=f7wlUNFrPQ2h+Z_)A1`ZtxS8Y6pIZn9xM>Tm9_wNLP#*-Q8I&QhUAL0Bncvv z0nBLlKcbNHgo|IEo|X>M|4nPI;-0%YW+m>qHmO4hqThJI@4cs2$?L~ne51EE-ZFYn z<`9JIU*5Z&*M0UoHk^;#sZHG$lWV9DesLAT_DaUCD_UCx(%y%!Mkt==&l*338d~Ot zM<`mz1C?@m2cYVW(lBRT?;Y@QJFL$zE0U_EobnV(5vpAqQCm+M^h%xB*C>?+&eZYn z@fvz@7I->emC3>SZdipIRAH-18>!xu$7>&e7a_ zQyT}TfZW))J?h7`5b%`*$F;!Ppt!?d&J#5re;Sa57VY!N|1Fw={z9RWDL)5wR^#$ zcc?MF#9J2ot2^w04%^$kaxARVL=NbZp0?KNEW)3(xcFgv+6p@??y+jH?vG0C0(2q#q(L}`N`_%i59!hgmDnpq<1lEXyUDg z4v+aJ4a3g65NOG(t;E}X;VS;ArxQ2PN}sqzf87Lia+AHH+CSyyh*p_{y5>?fT7eT?Wv}LAt6kFr=G9A|H2!LS z+gxx51%cxj$m{%rMZW_hB}-}he4Jjq+7>h$i?KJ2X_9WBWBpq!Zg9HK{=Jj$qy6Sc{G~>N zPnI(Oip#*Ai_n)zANy_DPIz+p!9`9shu>TnsKu6 z5mx&-vPztbuZPFK=Ps>a_QKJtLK|+7;;srL}$*J+Mf}u%{x0l1R`_ zTHepzDH2>g*-OD2r^LZ1N>qb`#V_u$_N*NnU}Cd^s&=Fajm70Ke`)cak7xLg_c3 z09dpBov~-Avj)h6I(N#>ojm>Jj**FrHDd@pa;=? zmo|IjhXAxzNX0N36Nb2i25huYw+sQhEvW(w%e08cM4)43?3^)7EDIYyi%^>)@Km9M zFaLhwefbenWC$ z!1>UAHrWVA>|Y$(KZGs0dKf z+^6j}(lT~8Kt}NL$ zX4a$oQ=c;ay)t$|%H<{L-T6zJ!I#pLKhJ$1+PD4s&djUf?z1e6gf z6-Z@cMGBc4w$49IjA!cI!t7`YpW4+|~I97)eE)Cs|n)|6XnU4difXj+MaQ{3*5s;Uq-*Uvsil9UmN6ERfgOeiz+Toc1)R#8P-v`j( z03;$!B!oqn37tHHYu%7hUV-LvjQ@>m)&<~t9jZ-h5JI`AMQhDE(|j*~)ufCl<*?8o zSAdqmxDH(euHzIG!sjJA_Feki*RU6#kox0U6f|@4Vf38+8-8>@!m9*pIVIpp^;k3Q z50I^BJgCAm##6WnR)@&Ck?s_LH5nHR|CyLzE>0Gvzpn|n8)&JzQ~l>9*k(u_Gr4Y8WNK>Sm`HwsZfnn?6Ry{&=gvzU zDz1ckR%B8_X;!4%zDbfC^QgoG5QAdxMKbO-X!|?N5l<8FAD0DOvNJI_w;Y@)_+afa zqd(bNX7_zYt;X)taD*Q+@G|Kej#8we}TUV_Uw)_ zIw}8+p_Bay1-bV^MqOgrXfqnh;6V28Q@8u8pZ!hfmU0Cybp(Ypj2=Nd$TE4_rELnj z10GQ?@Z~o1;d=Y~^Pn_*&rYkYlt%y_iWTx6F+C6=5YI#-9jFp)#?p3JC>32v9mOM} zl5#v*SI$%)Do5(cU32$O$v4e7*Mj#FuHwqtvS^D zUF$?%rv+`39M3nVv?6G0K?){};hl$(| zfUP71?C5;@Nd7JitGe<`E%mZ{%gS03j(+PL zbAm{cL?*>dDg)9_T+tytoPQt zq&+r+5i1JucgHw`3@N*rWvTcj?Og-8Ac~`vFZ+fbAKz27c!M;k7H{FyB)6YD>1;t= zT!Kfo7G=YV$(QBs;W|&g(WcTAmD4^+pMF!GrRBwwrM$*qR$8^r`tmjzqteV6Or}ueK+uL^(CErnmdRyW?8hy_*_vGS&>Aa{O~k3?Lw6uK$m_j} zicehv5?PnI>C&YYOT5OfRz0ChBXf|yD_-k8>$9YT$c{KzcOe@yIf%K#gjc9Lw2|Op zV(Db3gN64G_{R&*nMXSq4*f|1aob$AO4f7+f>3nqgH&Gs8+mzUUmcl`4B*7T4~cv2 z0G<75R{y{j{+1h%5E7f95bS$K_S9%6n(3WaO~$mu>DPA76C_gb!JDi|(zD6M*RS>R z@+sH5l+eW8QbS7w7!g!v0cUWd%v`cjR72KB9V=vTL}qEf`sU!fY;aVn3`$D(3Ctn2 zaPetfK3*fdM=rxX+;6lfRd+W1%$vu1b!KvL5mQ2rrq4)|y(s3hYoIdKMfLEu zXsV1CUsA6x7d+pBiUQWq_2EYzqy-Ys3HJaVD?KlkMV5to2Lhrf)R9R+w~2TJtMLz& zO!%?=PWkJMs+p0ymB^UG-yKwKFX~>5(CsnvIU(6Jb?STPrkT-bo45i#icmWSK8zL3 zMqd>N^+pMwRq`XH3@%l@&(El!!f4q*E?_y#k^?9lRhWXn___djFNhXEp@8T0Zk}jM zX?(rre8)@BSA}x1H(FzAL&Z!2pCT+ha02j?<;ggf!#RfoOFScK?zd=IPQgC~uhHjw zj`Y%iQ!qB91F(BUcILzfi*+cktjfdXyl;j5o(Rhbk5t*M+drubBZFH+DE0^b7LO~@ zte8uHZRHeOe{a8vqSRP08~{JX-3y5JGPYLlEy*|$K99F$1W0jC%l+2@Fq5HqOr~&q zc6=2jeP=Tf7LgSu#4NyQ?^3MhaOz&_rkXWWO;96OZXdTsSJj+Kyt71C&84r;9)3?& z)E-n!A$kzK3Q{}qTNXW=6s49~ZMiw^aBY7ZIsIWT1T<+)<mZ1f}(YVV+AE=Gijq7y_IB4_u>9JOcc$PTe@c7$8i3Zzve z(SUbP=Sy_)A#GL2i!ew}KIzvICSHK*u6Y`e-z#fSb>`3K?^*t(^{%ew~`_ts0O{S3#N>zK%6| zdpLw#kT$GnxMeC^QT#_y8WaOZdMG!RC_!*)(GQik_Kpe2*ezME8KBZXLLJUYYp}?O zh&3%-rOz}M9U0xXBO>2Nm$=rGJI$)BdbKC3FYjMr6>%}_X-d5+>Ci8bM6M8vc~N^S`?7kh!p8D(mnCut7~PE3!nI=yWK zqwu$9Jj{wbT4fM+6q|-z@1$H~kX-aNJo1&JuIj$}Ka6@h)3+L8J8Gh*mhOr3Lf(CC zQ1u{*MVBjk1!^xF{B?vu;5$`%Y_$M`=>ZRW6N3a2atl?AptM>%DY@_G(yoCZX(hE? zt~#XePyZ;lE#{(Rg?qgQ%UcD>WDnRvTT&{KiZ*^0a7Ogl^ zX^-;4NP#s9Pw*%j^cG18u>xRUQ*1;ICOv+6)`gB*Dx7x;L3y##t+8284kr!JzRsra z@`_TaI-G2NbeCyS^sq|Z<896d)b91!uB^#!gBzj6t$U|-1dvgCe|D`$>}YJ$oa#Z_ zGb-f>8eM}Wo#Mc&dYO>ChCEG85>uvLTkHBFz!H*8ml|k7neqn~79xO40&O(3u9&+H zUOKydB_qPY{i%%AGhPYT0b&kB+X|sl6u1u?vaVx2BecrULKZSG<*zXx<&|!c5Vv|2-`rHqjq5XOX^+k$jPJ^ojHaAu$t zrQte!*k!rd`^-k`XQABvoDkZMlcY$wDmv|Aa-7k3+0fpokF%(p{KBngNboJ1ad#;nwdfE*d@g%CF!pzo|mG&<$VJ}7X31bKO%RV(~uqyl{!T!`yxyC16 z)R^XM&=p+l8(s4lgr zX6nVYAP&1TkijYHsqvHXZ;Xtbe_Lx zFVNL2&Oo&~&^k%R^mnBN8L7y384*g5D(or_YAB?m-|Dz^`%0W+Tst9jQxij?nFu@u zIh9|Mqlw*;sA~()`!FDmyzBB~nDjsW@~?+q?8j6HwhnVG91Fm_NBuWc_K=MVXF_u$ z`ELXOV#Lm!(Y-Mk@QJC`*}fxiS|E4iCUvYBaVIfWC|6{khbFhjwKvz@f$M&NkoFrI zW%zF0RnbCeq-gI}BcLeU@?Sk*wVL!B)ryHdbnL0P@MJC=Jz8ySR&=CF&a+>0DWK4rv zajv`MN>5<_*{5hgoLTK-hNI5bNdUN&s#xZ!*ADJ;t`@tx_Uj89;rMAoXV;-jt1Tt1 zJ^(?pVJ@O+$8VdbF7-6kRJtu1THlMpxX;3&HUIPr7XgwLiveZ!VTe5~TkL%p<6`R^ zE1a)kI(si{(fGC2J;^|$W84SlmvcIc5dW4YMXo0O<>7S(_G)YARg~KsuSjEQEe};R zKf@dB3c!=T2DjgcuzS4F*Uu%a$o%*EriX%*N6nD^)zvm|4`G zv|f2MLp}J>cygk##xh;WG0Gh?=QWcy&Wfa8Q;etfro>&wdcn5#pZ=?=gmQq)(tnD9 zn9{bmpu$i%m8hw#!HzK#JKm%p9xhLx?#+*BgT%KD?m0Vnx_z9roSytAHEvJb5tdx` zpJB)Sn|UKziu=1#iatehKkoB9Fv(7~oQ^`}9&>3hUo?pC@7E7N8T^Mgp+a? z|98%JL@SV7a%>=Dl_*gbk=5o1N$LS$B1AL|8O$IlQlQLR=mI7XMgdLPpo z^(&8E=F7zFP~jwbgK}Tj@pqc=3~2x^(q>T!prbujT%p3=8_eE|qr%!{E=t6Gs(S{N z=|MHG;wpLwciTJ?dd{^!P!K*SR?<#Y3HjIj&#d375i+vN{F_WwQvQK~ZTz9lqJUdA z7PyJ2*{7~< z0U$Z#hBS2lALYKp5N<~;N17U(uj1gS|LD`3s11cZJKoMUH|Ks&|KF@+as7c8eGfm3 z?20S*ZBgVN-$)NZu4hqXjD;=(fZJxT`f2mUX%F|Csg`{PpGw7jqDR_amz&1KuupYt zkbSJY4+xqCumamoA*z87Ddj*Bg8!wjV8kwvU?F@v0>lc_co}Mnvk0 zhZfv>x`D#Z=-Gvcibw~lU@cc3*luJs{Q_XkdfoR8~ zl(F^`L`x17qlOKbc}dBBzW%{mv#L|+hYC~>C1_Ws6jOPRXVUvwtw5AzPI z6C2KL2W!=s!+jshNAhuQ7Ms{o@UAm9qqX5NyZWVdmXx)aQ|LCCO|q3R{7hh)z%=#@c_qfG%S9=L=MM@!~ejetCw?xlcKWz&8 zFG2{}${T>R$0}I{JIyL>E z?Ni&ZAUzOL(xcbN1_GEoXwyoXLBemRz-r&CsBqPQ(&s=Pciob5kA-1zc9w=wZo$MKxMRxW$Z8T*dkKPb|A zjxCU|J~UF3V-T!SAAA6MyfCn2&wX@*3Sk_5vknna+91rkonEnRRb|Uu_C*socK>?W zCRZyM@2+jK*u%M@fe;rO(@DG;oMmbH+uBPDl^(^9J%(6#?A+M>ojl*wl!7^YWLe#O z_iInue>hpoT}S!~j|%w0cTaD!9=*$W9JL>|(C4;bl+P$OG0Rt>hpjuQg=JP1xQ`qj zsOYq>L_7RwDV9B^kUzq9gF5)-=g0ktT;c8ltG>en!boRmKISRSG+cpO)kui>;_>C+ z*`yO*#s2EGw=wBy zc|1g7t8!{L;q*$mA>L8K@=%MFz(X6a(+4Pz$I4rfK=HHo%iG|zt%D`X>|-w~bdhlA zQg1FPvaVh&TobSnIBRNc=%&3HgY4{LoJ#qh(o5!Dvu5FLD|EQ>;x!%1<9ygb$oCxy zoz51^Rh%_juR5Q>4rG{1j+;^6wUb6dU@a4L_kF;#Wxw&oEpLtzDn{```1vd?my-}I zj{q0s;2N2QSv@%%Rmm2kcoHa~#JTyq7X z7lTF-`I^>HOM%}^Wa{~IIZ}&sg0~(%GfdyrnDtV z?g6e$np{EX_2zwh84#7PLfFopP7P&ijReo*9(moj{((>mtP8tw9?y#9`>p!A3ui8B zv_fIE0gtXHl$XG^)EC7`{q;0iAhOg&Z)P-q0s#cX(1i*~8s5;@yA99hPno}*8nCaXC+F$#HVh3 zBi0MsW_xaWJCKF7p2xQ9o;2ogy7;MMgC?Z>+p&(rgwC8k1Xy1g@0h7rSg0&~4-@`8 zD}{}WyOzQZ1?FkI`sS{RLpJ9jS9Wuj)>c(rI6Q;MRHW4+C{^h3rp;bQ(NzhPQ<1`j z>x^{k)aLl@6+_M6vk@VxpCqq++~i$&_!t@M`RNM*GW4vf(*n7n^Dutwgm%E{#r(XM zkoPp?cyJV!8psVG_He56mWs5dQ`-ASos6$69Sivkp5xOw#++tdkkOrCzZz$f4*^Jl z90-v<`H<@`T2c|Bha~WlA2h8}K1b^AuCd6xHX6rNp0vI(kc-RPmOPw%_@TjkDS)>m zfG3BjHjKCSw?H{T!tI)Zv zJ&pl>8C=|@lM^cUcUsDj$T5_|p3t5;LO;H;J!`WqEYpZPxcTMog|Pl7o(~T})HS%ar-`rpyVaMU{VqQddocosOBW&rdjn%WT!8XiJ5s7?-3H`4LC`NE{Ep4KkUs_^^g62jH zDNgoHNGJkhs`g8{+Y6hey6@R3^Lsf``FRgV)V5vFynuSB;d1@ih1>UPcumhZZ6ZGc9-Z1Nw|@G*g+i zNY=eMK%bWSEpnIn3Vb_0PXK`$y+hcE4I*+$gbDYad<2gI?wyoHEU@Y)i1CcP!V07n z6XM134~z1*@`WGcxl^>zi*iS9GecnEzT0HCZ%ctlzDeB)Ktp37+ADsgx-rT5{vl4A z1!)NXBNk9we$=P6Xq&d^6w8?WWxq<4zpcOlsiSODyMz1Ap{|3{-AW-)a+kcE_Lv2n zsfi7SAy^`)F-dMqHsFBA$Z!y9G*$#dzA@)$RL;?t&C&-tq;Vo-L{Evcv0`Yy`L>yqu|$`^9N^gE?W*S8mnIrXnm#G>-2(LgHypY&!8 z3+AChjs!t?m@u^;O#w$h-a`ajo|1USU-^lagkGXltY-Y^5cv0zE2?=@s@v4D`E87Z zg?Ud-vSkNBZwYajB5iMx>UIppWqUiEfBU$EDw2BNeI`NBft z5>v2rw?Yy0k_PCxPk!J3WXy$eCK0t_TR!t}9t2RhEb%E^5_D}AaIKPd%ME~uVZ6b(wj(8b+Dc$T_;pKAhQ?aW zF-1|p&PloJHHJTOz^?yoImTHs;?gxL_%es^2M%zfH<=5L#}MI~?}srj5WLZ$vZD3f zzkAKZXYe4a=}z_jj3Ivqv;7+38l|M{bJFowhe%^yh)*X zwgLaMHIg>?pX^=&xGhBgOo6w)A{h}aVTaF4A;V#c0PxSoPS5vhQL75hOA$8h(kioX z1V8%JMvY)9ItE@_as=YVC}7IP91HZ1p4g1eD)LLNf#j$8(HA+&HaQC(_2e5d&APCg_y4;~;$lXt4ZzITwY)+ifOiX>Pkt*Bo4soLqy z+E(BdPHLRGye~ztFKD*=a^can5yXJ7w9E3;I%w)yaMWT+^)k2gnuO`XB3#kN8 zEQItvpzI>TEoc1L$285_Bc#@F<&WjbXl_{* zV=Mni=wfTSGhh40Lau=-$-88k(1#S!8X>;1pVT_}n|yswuQrSsHfznCGvl=pSrXy^`3 zeO6pSRv@J8eSPz<+5k2r0N65moD0Z{syJ7F+U-bIAiPDdU?;`@Y#c;qzK)(6Rccuj zFY+s~@vlhpKU1QE?7c|ah>7fLFrnz0xN2WRnkrBcg;RlOM`xxs5g@?oRFHRVD@9WfUuQEePo8=?g17+R4>&Wo;PpXy=1*o>*8ofc z;<6%QshqdbO8sm%Wm2!qxk^=)gfXuK;%_vM2BGu&-t}g80c2PKU;;o~ z377#c%Ggcmw;wZQO-5dXJMX1S{b_O5N&5FmW%vJ6bRK?5uJ0dz9v=2kKop#T;$FB% zYT#Ze&a`6*ZcPhUYN_F#C7PNxag|ybn%XYZvSo#4W*cqUI2~=*>3se1`y=kxec#vh z`Mlpx{4^!Q7&?$3h1sL8u|11IZJIkqMuhLp2;gX(I9R=dq^&6UW*b>CT9N{AmU0~{ z4%bqmhh<++b0+cS$YCMi4vhZY5ylg&sxB|Yt+{rVTtW%xutCyM>O9ntNmWW>U)}Wx z1LC=4yQ;zW`!m&Q_Poy*)p|Hf@-iwTnw^q|G>#wdKW`}9f5N0@;1M8s++LdoqY7Z% z?{c&3YYx;-6`z|r^)Et(bTQOrq26@0G4&B1%8l9J!gT7ne4AIdku(+I;88EYy6?r8#^&0_{12h@=BIs* z?TFq7n|q1$e@uMU+w530UMiVU-W}MjuNff8D9kdLRMpy&>-*GG*Fhu5{4;i9CC#xD zGiJm*z|+CA;A(>LQ;}L;S*tpF{aZ~>((^&AV#uX`0@EWLU;Hi^FCmCk;2$DSD}SIF zU4rEbz}&=-|^KFY4jaI$ysN#9gV zjUy8l!Rr_I_u9yz5J6&gYh>d-SP}O;|JwN;&GWQogm`99VxRtWwX_AJZw zI@nrw%>Kr$v+D8Odl!=}W7;n7t59GE)2=<*KxB!3TMaLrAG&aKKz-?o(k2Xgoc<4X zy6Zmc(=VUvo<65BcAume%#A;!=-RCvV~uYUR7H%_Vvmu#RomT_%&2 zI;4niFM_8S>F&jPJ44q)hGmDCxF5@wlPzy!3-#hIBG$J$P56? z5N?1AR@N&T2QFSyH9Nckz)|HgmJOUkAq!Tt6&BBHGfvoH6EciD@_ ztQY;Ma?H9?Aax%rzPb9&6#!XL7j1SJC$G1BDC)r+H)J}O5 z-(kLY4A48TOfgd1VxIc(7KkTqbyzeI=#6OQ%}tE{Aap9{&VoBHgWDvCAk&dTvL^iH zdel1&#IN;Lcac?bu9s_&@lv?mqF(I3ItqZVrO318b4W`oWs48D+g(Gw!|3xYu`kH` zH^qV=B!Bu7@;wgKOeFoMhx)m9U4$PCNj=|g)bqsPDYf_2;oPc$>!WJ4C?bwGas6P_z7xccR@Gw_*vZn@ zX&xm3{){~SR!jH` z&ZO%B--3I3cc~-ZA3MA9@Q)g{viO-so_rRH;En=(v2 zYiI&P{UktFR>{D1&VU zs-|bLN=WIfg@AB!jG#mjP5q&xi8JF)9KxCj=me_m^3-L^)KO(M>7(BB`Bty$4;eOV3bmQ4-Yt~k zfX&HxjYC6>N=MS=8KJe^EUQurX0hy*&olxyE343DWu^OE^Xp;iXQzQ8r8yx0xaLg* zfWlnny@oKqppACPYjh_dg}^w2ZdS^ur4}za?6#c}#Xn!;R&(QdQ_4@>JqA3|P5fGX zpMzeAAjO^Rvh=e9y$OXHM*1dP^U9(x0_e!;yp zh9ZCck50ns%@UmXSr!sR41?a_@j!Wr5u7Hk^B_MJBp;riCq9SG#Y==B_J#s0s$Mu< zM!ThDes>yaCR7M~3rogkt6@3s{%a}a7u$E7hwk<(cB&rs>^3C&iNlkcNR{EQ zBe9&DfEiCE{SaKw7c(A_Mi%xy#R11d)JAv2fyw+jTfM&d^umxPU9^E=09Q&@3RP(^ zN?=8u+jmZ4)6}q>XsgpVp}aa|QLz4mlA4GS`_!vVWSjXHlT^?9^IF|xBVFM<$B#)z z8p{BlG207uh=b9x zM-TC$((}>dnRV>Oimb1loHjbvMtYPPgVNtxs^qaI?U1rS1Xs_$>!rD0rk5t}y3j+% zLJERbEup09>`mlxbp~{?a%=^L~(>Xu|QkoQ67W64?`wUQB5S7O{ zkPC9Dmz83tqa7o5P3KDU=GkSMHvsnjrV?}{7WO_yj__r@IHIesO0@mzeQ4G~cBG8y#K#N{ z#ElJXhevCf*7&DOt@a;WHpsE9>34^z8B9v-*5Jp<>3SO3ph4-w%!enhYN(xf>Sb08 zuTL0@*f+{ej|-YQp5oqQ8A}Jy6lNXFOm5Lne^s|(>H%?w6jaU^f`K%55G@8_PZ#)y z)uq(Mo<|QpF4UQZMeAgIQM+%@W3N3wu9klqv=0A}cx7d`AhML$1J`eOIFgXLBZaU_ zm<(cc6RAS^E##DPi+8|lm*_{*7N;u2MAOYwvL$w8YlsRsy`7@`dJ^cx8yF8|yCTrEd0c2Qp z*0HKd8n7SL~c5_ zqihzca}!{X=8TRTq#)+L4h)@Iz1zIq)-UzW=G=&f#JO^VG72UudavnzQRKrleV_Q* z5vUCX<&v=J+Gvl?#^$KyO8v~CDBJHM$ql>8j1b`^17x|r{MEo$n0s>Bax?-MGkpT1 zdgXg<1n?c8mJ~p>0o$BY#G}A6h@l_-%cOjesVTUV_8$H8qkkT7W8-eC^q-TDPw;S> z)%mf7(55c*vBdL8|1{gf&l+fD$vz&Mn)UWgNHHIlBG5Nhyv}#wcN13h63Z{DOrajd zr^J6cl_%2-4|nSYjRg%4H3VWLT-xF;!xAq89sdXop)6pV5nBOfmW7puA_A{OB zzefMLS7mkb379Xd_E=59lubin`T6@VJ{5A5?uAITvD!u|f8;RW=iNii^eW60KfHN- zwpSyuTmchaTdnqYBpIfUWvLixZKt%3F=3gfx+{c%i4!SHy z;xo^l3_Ceju603IWl+h__Gr^zDo^^!>C80pXO%G{ePI6iKAPqem8Pkw|3(^HZ){(` z`ukL6v~}A8$RW7*%!0Qf7U*)p&$?<1o3ML1vY0a$i8@ zEs&Nf?1LWw&+XTBCAi%Z2HqkD#>oJ0bke-gZOJD4(+VP1gi@CwSn@=d`;aS2M;QiF z=R%w4$WIUu8DHtj0}eAltc3T;14idU>N5Y^(~1P;_S`d26ab4x>F1}wPIdutdCrEy zxV&r!hau)68Q?5e$I=~R_ElLNbts1utNvImz$3C&gd0mXsD!8zO7^Hv7c%*#HT*O? zt0Mc3wB8w#`ZPH5nW~v>e$vXrioq#h7GK>^d~HMIyuIe5heU`K^}~=VWeBIO&1d6w zeLF*aqH9jF((oUvv>G-=m*7lRRHP%;3AsX!kha+B)yof5K19pWe1^v#-Dt4J~{~|j!ZW*?ZkJ`$H#fL$0 z65gZ~nKEyaKEH_{6-eL#=tcjoY_zR3*MBD0qbaxkWtFoW?LgKI4vpWf$G2a^sVkhL zd--d0gPHC%2jk;ShxA(MprZtHv@d~6)-93+zbr@O0Z?Zu!5-Kg%dQg{7Bo>SDkBft zR@ITl%m2rUwCD&;p38C+8d{5?^T#$9e^!l);2m!)!y%3mw6F7jkvO}g~t~){w;4C&Yh=2Qsvd!uRJI^3{`ICQa3Ua!~e2 zy`s|?|17jG3E1JlaGpe0=YuhM&U7(g5W4+cb1<2kPOC zb8!6E@k%7Jh*+ltTSeX~P!D)dR*t7#CIZexqyrJMc@5;bL;0WaU0JEmK%M0;JHCf0 zKb0QeKW>az#>PmLWa8a#+fOc?Bfz^&EH>_;t{kpdh=`j_aLv)~L2kf2+>-j>2xf4r z#rr~gO2grWB5eu$YG=Cdv_$FOKFtyeJUhRJPt)t8SibV1X_zPKM~{8y{BBd{gRJjV z;qr{y!p|c|eoK5wgIfSA(yS$}TEkgR!R+)7lq%GND930}g9Q(e9wrNH-F|Dj`|X0b z@M9gBm#t`dv%5ZQP;F?WG}>9iWSZFXjZz_Ql+?t6v^XU9kQCd5IwZ;lP&CK`X-1Z^ ztal-+^x8*&%QtMiCbWHB-1p;ks85F}69%Qq_ELLC5uE<;!fcY;!zE!8+s zhA03w-(#X;Dgn9}%G1-$gPgR6Y7U%56J!pJ(ss-UW=O@kJDcJt$~zd%c)?WgJsc~H z;{U+omuL4!h@H1@$a5UxS7qxp3LuLP&i}ITU9XZaVh@fuX7iD2(8~!R3qN@PM`f!5 zbOmiXxu;))}S9k!to3cBvu% zzVG%Tn;x8P=boJ!Lqzs92^k zgA&_?4D}N^v5$^yp_v`+A-bI>y-TJkg^=ftZsCW+uOQ7mDAdBn411Bc2iLvyHOWiv zer`sEk*T&qRjWQzo4!ONObuO@Q$l3w>LG=k05yBj7JDItYV*#O!gB-&r)V&_%v9_I z%ac>qWezJ*$q>&c|COe~?V0Fv){?Y8iI2yW(W`8MLq!F{72{te*JGHD*41vt!PP4-Amn zP~TQxny+(|_14cL905q>C_@(p$vqjHe&|XsoP)Pi(@Iy*>s0m`0QBlonhlizHKa#;)+Z}u3hN4-hfESH z^}uZXQXu4v+nhAZvFk4S5<&NC#MB(|PqK&SN1t_HIdLtDS~~}MoA^A`EB9mPx9Gx< z60@RVku6764}Y5QCxS8<88k?$e%oU>3=do=?ihq8k4<6@Or-Ha{u+n5Z3t$3kEcS*}7=zu>vx%*}xwTE+(hFqa|0ns& zp1Zyb7YYy`gN62`S+?0rw)CF1ENM&3xkn=pEB+PU`rgr+_662>Ah3pyC-ZoD0+a*$ zqQ4lwU5pXt!|3!r-NoDWVzkOrok=bi5JLYTAQ*_zLQi_qzBTl`9)MN(AC;Z9@z4vU2ofk)C*odqvoiT9p; z;A^_;+R$MSRos4?gU&)k2yNBqslY88?YqQ~`qKj2sz8JcM#(_N$)O;DDV2)|k+~h) z#QO>YEUrm)$e5ClpY5?hob-JT_z$V?I#zJswOW0iIIyuADb+ z30wUgMj|<8b~^)cgL8&XWYhPg=YFcDQbeX4bb1Hce{Hy*3xkE3Yy7nfSD?TbX}H<~ z7`A2o-xS+$D}WBH5sqwgd2g4Wc?q_O7_Dg?ruqH^Fw=VwCk>NN@9Ry#BTMa#MMuq( z9n!Hm{{gxC3|F7XLu@v;9u3^P*&RA&Nknc}*c{#=6VK9jKY?s!B_IG(lH%v|ARD0~ zdIVjWcb;0$*gfH_q!jdWkHeRfdhDb9b<56frFwscfyUX}oxgSa^@1$t92?vFPG(P? zYQLbp=&UoubZo-72@zJ?_1p}&Zj+D;7vap3N0RnT2FRCBKwl5Sv0LvME(48a=mT6> zt={Lc6TrV(3X91lYca=Kgz#a({(DW^{ZiMNb!Y&By=;6GIAw=*hXrzhO!oA1IiyF_ zzPlB#$j)z|*-a8Z#JyA&Et*>FFZ_a47$0Z`gCf>d3tih+_nJ(IYt2-~INzOSL{^c( z|65gKvu_j&i);9P?knVZlG^)ylr;=b_AC_;0m&uZxb_JQG=>&E@Mo(1FjUL9{6laU zD9k*SV-dLj+Z6 z#w;MOT)z*GPLrgv_#nl|d`ZTTcPple3%+tL>$N8VV&Tnt2c^Ii-bj_jhT!NkfLjS1 zBXRGY?ojYlX~gd2DiCNjI;6qtpE(>gsP?Qjq8Wa~^U8oo0%L~)-X$j#Jx{NyA#EWt z<-8{cwXPT`*B0;F78|PV{PkczkU_+h-1g469rcck^jd93ev)|hhiZnJ+VDithC*oz zNa1t6`xf=p90QcNQK?(5=XQ-2|9yU757oa+9z}$k6PqCuy|dDjW@V0C^gL@zq=btp z)R%Ly%kKb`sqXT~!1vTc`cI&LAK>Kw3Z2!==8a-nG>IVvFD`3yw@=hA@4cp+k3AHg z^WUytEwQ{6yOD7!eRh_uOfUlgB}=oP6-IWpGAVUaPNO>#S2!l8B89vKs@i6BX(geX z?t^4*ZYu#}ulj~zUFkx$o944#Ky&MSFB`eFF!Lph4+z=HDS%iA&-E1pFeXi04*ACj zCOjO3Ja=sWeAiv)qd!HZOyi%z+t#b?Ih}8;2H^1l`aq4Y2jz5*x|g+^Eqjk?n-O;$ zb9&a=w>HoBZLQ@MUQ;!uXm-fxK#CikU_a%OJr3RTbyiZ=KUfyzBD*-Qq&CXytY)lz z+Bl9m7H$nGmEGWC7zUKld+U-`THvMywvrI?=Oy}G4`rF4$^pj`@FR+%hK0DCDG~|} zm+)bDYr1$AVV%Ui_&=qHmF#~ID{2?Fely)j3az2; zj}Lp02&S8s%|%^dna)`fSEv4ChDTf)te`mfo}@<*=xwi=N}O+n?GDLzLWIZwbi~{S z=m!;0{`;GQ5DRbzwXd;VBGilLR#a8L9=VEKIA<4~)BQF1OmP8b zoQ-Df>QVEE8du@jUpPzQ&-_~J z9?>{8_!osR2&us{j{CJ8xmDP=9|kjqB9J)9Uh%}r1SmP#9FKRsa} zP55sR9qCYBLTHnZAu20~Bne;BpVWv?k_p$c_i&Ijs75d?^m)~RjUcuvr6=q~h~(aA z7F(xWB0P@{++>#mTY3HEU!AE!nZ%~} zD6c^CUjCvUcp0Rl^H03w9`=wpZx=i5wBeF;_0D{Ws&w-2^SH%TYa5lCnTF(O=&U%N z@_WC+(zx)FX;pJwAI{cy4+E6uK1w(=6U#9-xb*WfP=Fm9h~D3_zyQ?I^! z+C6lr^w%}zmOc;Et-1Z*0ff~GsHFf6R_Xs-h|f~NKl}4?&5~F@JraH}^^e>Vh%xfE z`khp1_7z5i(X;6iKde@GndQNtEYX%}>g0pt6rmWoi6_HxI~lXaVjMv_hEEZc=|~vL zm*OTc0SUxPwIpzpWPdDE4yg7@!7CTW2+edZ@##(Y!6+S*<|<6MOu1|%3U0obS+`|n zV5{;nLQT96L*%)m8t6#u_2E5hzmB2SiaGEe=!A!Ua7c!AiIQg`tn@v*c^DY8q|lB3 zv_nz5(whDCJB<9o-BB&lF@)F(^7jPc*V;JVNi5}othgPUFHNjl{hC?gQYpdu_?FVf zfy%XVdiAd*u}9AGd7PP)peJ=-qxQs9b0Zp;z62#4xQ6lLagcoW z5!Y=bgh`&-f3hig^@P5UcxUfOkI5jv&amjijgkD!%|4Hqk^8e~r+DP@x8MA=U2j%u z2s~hUy(JrOm{LC9<<-@t-sYzy1*P3(qc#j`swx0dP6MshM;_gK`X^MqZ(crDQPQzf zJaI?g_KRC$AKu|vs8{Nap8cyU=GT^c?_?ZJ$52Z-$j|Im-CeM+?vMNZq0b_*BDSFa ziP8k~9CpfzgL`GM*+|-~5P$LK0n#nu;3qlKN_3h|$S-+kmf(E<0UI>ia|;+H3139a zg5j{|%j1TaB$n>_f6k&z!W+Y2hi~bGM3kF`>Z1{!$0!wSWM|Nbk-b<3r_<$~Xe)y? zz9`vk-h)FL!gZ0C{815YAl~G?xaR5pR|;1w!AhYK0ejsYEw~6BdZ&tBRQfRW zNov|(2ZoyNd>=XR?W~JJV5WB71DQ^z+OBp6m@la*rv)EaGeW62_qO!!bCjf(f(KUS zIv)gEU${R1{k>Z$J0xoCllu`s%euTERa0m6>`mtZ{TDhO_+5s5YWH8g6=ifhnpZm4 zIvORdi#2n&e9!Tp-*YRk@@Eq!KA;7LSEFEte(^;sG~q)q(Fkw|yp^hE7t+Raekutf zHnS^WVK!%)GjTlcG5M`|AxJ!mHU4)Z5H|}>)D|QaQvzAUFq>zYFEyvkkdqWmUbgkd zQqY?ckLVUoGO|RlEPNT_tG|-DKZn{J)p?zC&I=#fsFj9x(favb=~MS-YECI%ltC~|N@Sh^!y49j3|XuAtXOa6lW9fFG; zE+#gxb&g;hk5YWa*c(q~FxGXD)+~V9`>BM3haq(aIr!o|myaBHBE#wQOV8QPrNZB>EY0-|-IP7;r)e8x8oc2_Y7*tyyruKrr=_tqdZ!6W!p8o4s zgbohb&9;6f$^NF|RlpPgp8$#-E^IX`TSEmP$O%E&xt@(a9V9jSEQ;+wo#w;CMZo=> zOwzuM^TV`UiFzml`t9zuV-UWSnR|OyE#}Ocz`-?ZklN+GYy8h>Z}{r_V{HANSL0pMDk%Zp>!lGfxJ3ABe7HpxvoF^-k`uul-(hDE4?A@o5h z)IG7VuF)R#f+0<7X36-f2?#0EYa_>4vt=BD#_=|AUJ z3ug?A4vk_&6UcYr2DhluFC8F<@5(DjMK6fJG=QxGT!)v7^Iz4Oh~e3pG+zcAPSOyl2XY+u^@2bUw*nG?+`atJ6>UHcebT3PSQQLdsdfsX zAfjy&zao$Wv*6`CpwI#z*>w{$VPsXeGT;M8Rq{Y(#~|w6N+x%36%1WK{jyj8!6>bW zTAyO2(`@Xw34-TmZb~F2B8BAqDu(}%qdISW0~AD?iKl*MGOhC+ujZ+J*0q$<74o-s zD4w|tn_F}iebH+OODzBt4tuUC19X-F5RVbi==Ilkrsd~sN9h*2(0x(@u>{z(B$Emm z>J~bsjn2Ld#ryxnHGkn>wCK2qL7(F#Ski3p_Ci)@etfieU=9 zqwTRhh>p}cmVv=?V_i>_?_-p1s?g|N@*(-EsZl}3`Z)wo2)>RiUutDhsy7yXp}=j_ zG|&>8yKaIH>m;9vFo$9eJBl7%o`8>+I;aeb<0?5a8+wtqfbT%O2`-3 z3tP+2TW`(u&TUkwJ>ToZ*`&bLHk?;)a_;LYX>G=;w>kT^Vb%Kv)yr=kOZBVB9Ad6t zR4H@rE8+pWZ+e$9z@)Bz@1LqfIXsW8y+<96W+QNdWQb1LHVFUwjaB=v%%w5FpI(a@-*c?A#dzZ_mY*PVkPd)Z`L7KCi~@>W@B*43W@BGc3^=`tOctCM{a zjXG+9YxHBiPOMHRdkKJ>0qi?hYyEowqUuiiD^p2N?T>33=~4~DMin#*_)tPd6S;W; z=u|22OmEL{C$>VA{GFXNAvt1lEwo&?DI(F2?WE*ONq|Y)>YAn`PRtHQnqpCV8z?;|r^?i4F}AaZ_zB z2J|gxIiNO!ua(Y+@AMnAMN%(pHYmACP*^wCyC|_2JY?ySE95eEty|N z${hVlpfHEvVJ{wu5@p4YUQi9UqCa?i++fL1@LO15rEz;q$87%i>-mGYeXm3Ijpg)nuOn$GFeHk` z8;0x2fa6%5$SCzZfuIxw^+c%I={0A6o8*?!*egELjjaCH)Jq|7w*36#&l=aj{fZ6M z9c*t%M{87`W%XL@b`LDS&mm}G>(j?o{?qvjzZvF3!AT(3eF!k-spyW=9g|2$Q&jZb zgV%g!_Wy*v{egfPLsvSOw;v$RUm(o3!wy$K2%I8-Z;sn}7?9VZm&28;AZro)@IHgO zIILQoLEp0Lx$UqCiIVjn%qYu1g{-aY=@Ao=6z4wDnz&n@hd;QIXOz_y>U-?CjU!?S#xn%iPA=0gWxnq7F|~@ zl!h#EZyLcI5H-08x^K^C%pFbLVtO6nn*q^oJeXJD%ZtKm*P^>v8yAl6ZQSdW>h))E z%>~4^b?s_PZ&+IQHD?(ox7=FOaA>6D+i!0*-d9zgS=Suv9|GW|a5E{~lLhB4=cG&npd17`Zbo*bPHbt})&XSk zHVrw$Sh9=LnV_u@>gH7>`d`{?Lfdpk8{k3OqSnypz!#=qG5xX{p!0fXu8g^=gF~@4 zqg40QRPVGou=M0)*dVBvMKTXfV1(*^hgz z|K(Q#@ns=;Atn002XsCXSN~?`?{=5uME1N0F)x8`eOFP(0^i>!6J!VnwQU+VH2h4J z-f>+AM5uKxXk#JqW-Gc^4UuT(DvH222~fpvkZ`%F>yyGDInr$za1a@KVe1-u42;T! z*?|wM*9&8cu1`v8@5Fhyjnqy8TYe=p*m>NP!4*~`-pQqdjR3VeXhep2;}WqE4D5C+gLfg zXxUOR7&+sonfnT^$I{-du8kGBEZ|kY`KUk8y!-Z|{rjh$r$O(aOr1Oa_Xv}e|7LP` z?mauVqxye=?QzGbnH}rHM**CCQWU0QuA7IHkT%JJaI_+7Rvj*GaXMP}oi!dM|Jm7%#vE%<6kD1k(tZk?`EBAJN1W!tBCYgm!rwpS{|NqA=FR+4ik+| zm)1{89djYm8t+-k+R4B4janr2@<%v(eS^&r587tl_=(^eXaMi09jC37VBXa+W01lE z)rknRWzcLHwwQm0N;FEJ#2l8Rw(Qxlk3Q$x%Hh0`b*g+;GW^9 zICkBe;!m$EJ{52O^zr$p;a;Zi49SBBx6EI)(U@P1TmHN8TYH8r5F?mIq1=}@1@3vr zJhA-3@2gJBLXS6iz?26;EKrzQ^&Gdq7`RZ&ywVio_3wh!KhwD<{cQLXxe-jS9hv2( zY?)eCam)Mz>jg$}l9~qpQ_Ea~)!~M)z|NLPcRh{kMy?9@y9!f6-*)}t6vEwRobLI? zbo;V0W083qBo3Zr4n#%T@PPN#_zIEulq_P14UHWedXYbA7PI?73Jmc<)sd~V*}5=2 zDXcUJHab^OBc4sWr0;$4+lRctC172`$T~kUWG#5GK!^SJGAYTmv4b3nV}pBMATT0; zA^~oH*?bGB>|hct6&wBU<`%cttMKcUom*unXCh=eizy?(>hvQBJQu((Dd_^K>X{k) z((g~HM|3~$+Ieuacn(q6GG-rEo}%Z~e@Ih%bR+b3&574K7lUF|Y;@K%G*_2gKGw2# z0Hbs1vF7GXD{hGR>(G;n=6~PUf#ap11%N=X6W#~csm(y|g6pi>JKwkseBE{G`wM`} zV_1m4+A5>dUCRg+1lKBiY&;GNAwAg8UNVFwH$h}_9PzM5Q4zrAaB>ma5H}#!9ykSX z*u)|%0D|r00M?!Z5E~$C2Lx!7CE(t@9MfD#1$}CC^b}~?o~yRg6f&KIv==9)*z5x> z@AjW!_wBv@QhT+BQ(Vk8?RinT+paPe$-MlP*v;lZ_GprlKN?xzR!P)0F#D>YwU?~= zn%xjBz9@Cq=G2c5D-bFrD3bd5VfsBFW(g(@m7y!^O_=PT%i#FcdX=?-a995L^?OJ+ zjW&A!YR_i& zA2RGbsH2(xF-k{QAUm6FxTV+4(c*?|Y|`hS7cR-RXG^+*LkEr1;;rt!kyj&~HNWz0 zy3Vcs{iGxPw0eo8MAJTg+!oOLvT@+E^#-}MA&xrm*BM`e3hJME>-E|)RNIEyS?hJT z|75KxT7;7tiWcz8SRn)_3D>?4CyNb!fGHj2Ki1Rs!0hLF91tM@btwdjI22Oo<;Up! z?tFAD+^kzyyMoBNu0_z20q~5r`7%RO1-lcxW5=p8td=eKG4N(3l`wq1qJ+Tf2)hLU zM~7+%>U0rIGhi6HYJ9K0L%R1GKuiLHcnoN5JACiWBB1)T=OOI4gB%;62+YGqZ*U1_ zZv%%swF7cak2{$DaF-}E^pZ~d_iv1{ehhe29D^gV$00}&Lpc;j#L!3NAm z&$!@2LJ0DjXO+R;!r7nj5zX!cR|fi2A4GB5#ru^V9R-lGt)sLI@_)fARRXJpUXkea zRibUagCz(8?4I7U+!HB5ZnM% zkhVe)$(07hDaTcl;=s`^?AQrhCWxd;p>;Rt2BRV98Vg&|#m_i11porCz%7uvzP5`i z_rn$Of>_F6pmy3VI2$=@CcO$nJ5Ec@Kdk>O|90EfNqXo9$aihkerh8n4g~I<^4-e| z@A}M9mZ`pq+TSHxdPCX6Pe`KyCKZlf$1b@uuM%iEWi(qOWW)m{M%>aE?z}D5YaRw# z`f~`@JhVMsjH@6UHZ<{f+z5wWu!pBPZ%&l8jPtI&JExAW!rTZ?6Ge-aE$ZP^5#2vzzT zB)K?&gwiJ=3P`Mbfk?i?~vd5j*2j%k3E?k0Aj9)WuS&p=6yQ95dtqk~RfOK32GYUNd zPw`JGZ@92Oamf0_iIacZZ!>Lr@)3ZQR*b`A*#}gJjB3_JL+Tsf#6>~J;frG^wVV0e zBCTq1lCQ6pw9RL=g0?|9&?^Y`v&{#kv5ze)ve3Tu8?kP+#%$XBeNf%`>+jU|8z7_P zs@EKw5iYM7im_CPL^KKGh15IeEOqIGNjphcUYZT_K$2227K-zOzAE6h&3 zkuNoppYG0FrRF9L`pdvdsWExFj>z=r;4&-jQo}V}km5 zRaDy9d_3mlqqwxnQdZ~uT*BzJD4NH8)f+}0D%MfhapXBKa)LBG+K%n@KI+cnH?4L# znRBT-#;tdx2JU6-1RnGg+q$0~2SZb(25TfODogSf+ok!N<<>V>Wg|I%2_^ke`paxRm)*kqA^6d6V%>mZfa1iDHzHcvG31->j|Lk$Sh)l zJq=m3G=~2yx3`xA@W1|)YAI!*ztxvgkUI_*4Df?;9{*HB?!OnN_fQJ=6K^|sTGVx8 zFcP(0PyA!$=`Kn6rGE>1+*i{lO_iJ@hTm-Kz#)W)Ak=hS+C(RH{r$l1vFTL?{XO@w zq@-=Sz1M5-kt&TRHDw0q6CTOko{9X(9{_~gf5S@JTp=n&*JSHA9v+;(t9_z`oxeF3 z;YAniM<>*+w!NfzbK$`AaGfmxBVh4oj-z^82UBe6jx~!3d*Z)`5xl5M$@ zz=n7tBk=AQYy#Xq_HNdn#r9gyFYvAz(=w<;JWTiKxav zLit8k@BN4dQ1~X7p`0gufE!AM-Rjk^(+{Xmn~9*Dt?xnVOL6KdUCnFhMD+yQx?n+8 z6*6iyn@17Br<6r{z-A1oZS7UcR($ziPQ+CR0_2-3A#I{%g_xa(oTMYdf zST!lGnOToVJ%V|2^69EarmQznQI836f)dpOoqy8e7scyI*omNiUKIrAP0_byL#>CwXPYXMLX0KrKLz3b-EAw5G!pqE$N)SKh6^OgA3l8vU<%OkC`OE z)S!{I;1LnJN*))x+8Kcn0`OP75?<+%@t*VWnBFxSbQJ6+0@8U|oSgX;6)>Q81 zA8{}{LFRHChoMJ)x9s~qj%scLxv&uW0JI4(!g4({NoB~rih`x~0t|L{2K8bA3X%Eb z^QpDn(9vV0pr7 zj2d7i&88AHACZH4=nN%K>}Mb!>`eQ`DL6+|ZgBX7MwhGF(BrchW7+LC+~CTIyj z`A3c7QVW+u@)n5rUnPJ&%Y1#LMu9l`KW5SW)I-=|*d}h1vD{q$7ve#6)HMSPsZ`0j z3Wt~`naz>teFCbLSpjeNI%A8m)aXaw<6kuUZxUmgRD=GX(+L>RW$;kLSi%}0S+1Sl$PH1A9k<#M9!aJ{eo~FqxK-+ACn%n1W|?vn9)=EKYr(RK z=nno?b?o{U}8U6A8i!z@%OXU5VSWWLL@4QWP(ptf2eTsFSIc+Q_D@U-U08wmQl) zn)|iI#<6<$13dDoU8{C~G4riq=+a^HPYF(h4u9}UB(umD#X5)L4763noC&u0@tV?6##o6%Pi z{GWZ;=7-=6Yu&N04G-DM6Lg#Vd$ z5`E~KU+1w1TM!C^MbAVw<<555=8zP9slK+J{V#p9?R`eYJ#U0ii@^W;eFRO2JW&Dp zaiOg8t&W1t#2?=Ao@$&B+rDWP0~U;3rs}oOOj9&km%Y}t;5x4Yx z&LrUw*~IN4B7V?B!vJ}IK_&ftnT@=kN(87P^L0mofeuge@S0f0mpGvHFW~;*ur=e!oy^orCf2k2;;TW63U0cJ|7~IQW-} zbPViqqpHT7_EW2B51$jyOrT5eu25NNuO8Ev*-FSxM*kba9kIh?bkX52yPv!ZE|%xP ztPd&sjs3JuoEID5C{9t6wOuM32P6(!ElKnTjO0q@bvyL(y$?sH0Jg5fUmoKok{qgoq6YiuoB~#{<@b z@yK`IzhFO{*Uq``>%Ok{MGaAp@6#v&@Bpa1<-o=@-D3Wzjlk#n_u%0-PN9oPfC%=8 z5jglUCkE=8j)rvW*Z&cJ_GaS2czei!$@m@2oC0#BS+PY>+W(mQdXq^3j{cqwh^5q6 zmg*%u?+9$FmT|6GtE0PpVTE9oPE_yX&}8 z!(Jwsn@4EYeG4@uSmCoBFa%Yoisg|Zvw>IN5%M2xB5JEAxg=`Z|wCF++g=FxQv;f8*Z9Wq{1 zX8hRIaQYe%|Gw|MMsF_CuJG6Ub%D3i$lt`udN#}L?g;2`sQh1o5>d~C50-F%a-stT zI53e?-E$fE=6#~I7A#~SQh?dhDDBh#&T?1)0hs;oQqVaFjF;Fu#-KHyU9`ENx$6}H zKShv_#t=mDECDu?NdKp2n-Uj@7HAWtS2`n2Uol( zV-s&AhRQJb1~*h^5dlv^*wuUF_}T4kvcqeKVZZaKQ|+e|Z=D{DAaIczKd*%w{wPr{X4YTEtb&GU7HuYPM+_Iel3_hnGj*oH z)y>jMN2uafv`*X5uA+b@PdHvW*0PZbaNmg__L${`7iwLh5PC{>Btu&Cu_t?u`9I#h z0hmj0uAhm4LP&eb|I&!=;8tcG*Ak8fmI)c@k%YXIZ#(9BKQCr5cOAzfIogC=Ctk z+=38eMZ^JZlRhPv$A6eGyBBz*?lGE@I%`Vl8Yx%tit>eO*o& zK8Yq#rRx++jCyNjkYHZd{ezxYeM5B3z=XQBWXW(;{uur?Zvpr7rSMHTd;e43sR+u=S;Vg`!yoT!t zT+@E>z`D$W+0TMFcbP7;rsdCXGE~yIJ4tMF1|8bXce%%OPWXwaP`f9|AoedJ*(>T< zdRH)k_b}iQhEXBSFeP|^44+gV=5M` zt>9;xmz=H6fU4UY-=t>K$~Eb;0xkzC6tbWLCQ9fLm5HoRvY%9?Os?~BpQVW)eM6WF zif(I`jv9k@$shvS%z}8;=@jr+c(O*yZSM9Pv_mO#KJYiO58ed!R){$pa1U9+*aRG zt59QNY@SB=gba{0Du;c#evJ8epDkm`^k()4gSk&J0F=u{9e)qKmdRe+^w+0mt2CIZ zZ>eYCOtsQ?Cg|%^Evu*owY5^EL*IxHkrvUQ9~hXXV@=1>2?mxlZ?G3MiXjlF%2+fG z7lXvcr0rrCvf0;1N7K^cZ{EJfzByoxb@V=iHR$%H>l-vb)hE|h8&%}y96PQb7f(o| z8c`kWfwQD34F!Ex-f4>^G5&6@N>GrYTN?xczpt8dq zC;UW0NZqa!$7XP0tfY)`Ysymwq{-_KHRDfa6hTe}3RBSxzc=>|Klzp-xWq%EsWFCL zbO3!-xHa|=!e=v|fQDzd&ij|)K(lspKiVjD3{KR^I$uj1hee2diLCr9O1qBf<^BWX zwF-Do?fryjks{(wAm5}q;1l3xDsPy%21_YW^sO}>JXx@F`}h2aP2nZ4PH3Kf1=fN{ z?ut8hqancM5%$UfPBFuR(GsQgebRC(wX^!Z8`_fu%ngKL>Y}~jfvK{}UEdZas?09W zYge2801tpEd#4d9G2hB3C>hNpl0iiA>{#WlYMM*!$MW`j7>AB{mwJ8nNV#monmk6Q znjI&jBjK|38VnRFia={G01iA!2`(}D0A%jO&l?+&eZ zA_3aUi0JCVnB+c0IF3{6e66@#2tz(FjwH~Biii)CW& z#SJz=??T%WvL zeRh5S$P#%dg>qT`{h6iBHH8X2URa-l61NqdyZv4YtW(&7x|Yk9wI?f5ekC#jhHoli*2{5{jd5JLiH&FfeR7wqs|)XPEJ04~(vgX(@^Ls} zj57EoA{>Gjlbly(FkfhJtOy`r$|Xbv4i8Wp*}|9#Q}E+d`dG>OzL^J`{1}2Lc$GKP(G9y%@~vv@kSf?A;Q#O=b+_ufATPP3L_Sjox_wI>@+ zYHXsRr9B(6`y*Gkp8FXd`sL&~)BC55bG`43!t`mIKphJm7yt;++&*Usx5RKod9*mxX=&UhROoc1BVQmPkymjklt%JS$bWG9oMoQr1Y zZ+2G|MVB~wnyc1O#qa8oFGu>YHsePm(FvP_m#HuW*J1K41z{Yts zJPh{Debg=`K+gquyLF|$a1N&02P)Fvu(Q)d_26x<}T^Wj%@zdV^l>nmtlroXbh0P&l>Di)~B95?#Ec z1&l(T>`{RG;Mnagbn%Q#4)vPK>&;*+Czj%&Qu>?@;tAb1wy#%r3u4|$Kua<2FBdRN zSLitrd&I3C-^}t@b|ulg00c<@B6TH+Sg%pJ9N{KR2oqJ2!l<(9JK&bKbPCohVYrE* zinrJbrH%?Wc804wK2_6phznyd#&F#%q_)5d@5Xg?E$)c4Fk0{zAGuyMUfQ_k;}iT_ z4~)6NK3m?v9Hw}mGuv0wcSz6oYCUD*Jieql#k@UvdR}B*&~;$%nFzK2EN(iT<$`EH zc`MB~ic$NcW^W+QKU@Mj1)Yigfj!E7i{}3Lc2Wk*g{e2&*b@_HQ1&Zf`#Sppz)Oe= z^(qhNvU&Ev!ey&aE}SU7{SqmJu<3$lFKyPf#7G2?l6Qy_PNb?2Q!&W39oOLo7f0mk zQi>9y=~oZaBU8$)jNGeW&LKs33KzcMSZZ;{4ml%Qz}<$gz!<0ObFS?=CQ6907-wyM zpoNx(72a#RXp?H*KFri1y01j%YSE5ykrHB@b~IkbLw6zcVUZ!)u?=!DazoKl06e8H z@Sy$zDBC0b;OsR>+BdtmcZi|*d3EZ5#UaOCJDOmQ>2pv{!bClA6Ti!`NLv8}Eh88O zFfLai%?j9Y1pE^8rql-xKc$xD<}O;PrL2fc?1^A+B?TBf^F`aIETtm8+op#;PP~NWQ;NzT0?aJ> zKgRn;spy}$ccjlrb}4)ODHK&%@nf*##e5VX_CRbHIiT=WM{VPeD3{B9;Ql}^!O_U? zg+|H6lr42^3a!jW_*zD}JOd#mn7R4fz|0)D$EHd6=E4Qfr{7%nC5_c zO7W%*?pJ-@a@X^%Y)<$6Vh3!rE0UWu$`ah?_wUL|no6cWx)k3br6lZ|0+(r35>>b4I=X$u9Y)?T;Vn z9;E(Ug47H6rN0>E;{A0c+;)oTH<+CwC-{C^@@u<)vW4PnH8;57%KHqC>c)qU$4y{u zH)-2m%$q(cSX{4VqQ&DnuJAYsbn8=*`C<-`ZRKpG4dE~+G0@kbXfH&hv26CcEB?slOQ#fr=Af3PSQC_% zem_8L^Uu)6={H%absBshN3w+mH`w@Hw4jZ!Obdfd%QyA`?2I8X{Z=CGg0MiVCh&0` z%=RSOGDO$t(Pr;jU7uRmA&IOdRi=sx&5oh%MS+Snn{#NemMMoSq3#hX)+NzY)!JEq zB?kyBTMR~|W|!IzI)bgN&{t64;(i0-_D()@WHhM~klAm5Sr?!JSEBIgfi6&BYG!Cbsk^*&Yxtl6xND9mDw7}gR4oa0FCN%feR7LJm*UrwjlZT<`sO14 zXGr!0$?8jB9SE5qYnv6Xwonvb*Yl*F<_;;1LKgxD(k40!F$w$n z^vvfjTBLm?e|?*#(7qGT#StrT-R?YWkDraiS%n4uM1eRqv@}B29#G59(pX)j?u|Rd zjRQ@-#-!>fXks|MMBD0DPSUpeXrbpig^D90bc8W4(0dK&=?dHEZtqY=0??9ee^E-T zpcauX=sR)n4nugSwW3jB(aF{f94o+$lG)oX{bTb9+;yr{_RwX(s=ku!g?`te%J`so ztv>CEeoU@NH>XFpa0<#5BXc==`T!8xwU3OAotL9+e^oiOy>7a;gnw z?u~GI7K7K#;{0p)WG2U(CMT5!Km6FApIf=efi>D;$WlbxoL-x_=pGv-+W=qIGKp9+ z)m~0nm*`b75+p1)DYLd#Ngi1PZ|O3ftUynMZmP?PI1dZYYzT)|iT`tvZ|i|#22F28 z5J&UOu09U`D%jG!Xu72@;`QKxS4NR;!HUf#Hd|diaP4kObaG)UB?UlGXh<~)=t`sP z9D!e$^L&~N*I-j@STXw*y#Adp{AIXK%kOZ}6_J}21(@4~bDe2B(qjNI_($KOkjZ;m z3dr7q$Iy@oY=;Z-4bo9=Xd0qS0W#(L*^)MQJ)uI1#+qyJ{a1?mKRu?EINh`0U!__Q zwe6j2S+dM-Z^Z}q6y0D1sUeZd zBD%>f30Y=^R{;>F0~1CkZ9AEjdn-Ga zO}*A`?}0LPWc+`ow1N{{$O&j6b~gh}oBIQg8@gnpb1jj{dQ{vqA$m7Tk4D7=(&Pdc zyRw@Rw*v{?!gWYhSFcuZWPyzekid^h@BuVKBnSVl1Zl(p7lTxLMFiJI*Ak)8x%gZI zp-H{c_S4-}HA=vKefh-iq=VYcPiL@a4Z<9$um>*C<^Hoz-}j~tp53dL8hbJ#ktypC z7!kOtB6su5XOE4~Q(_0ZHioDuIZq##Op+Jh?wGx)k;9A08v)g*6y-5%<4g+;_U;sx z5PgI;r$o#RV}SQBZcM)iEp>SXXTLT&J4G z1=+;*D{|+D`>doOfWaFG)|Ap2rmU(f>XSUu>^8h~!N#?6(?Y5B$YZjukn$^UqY*Lj z?DYBpsFt5-QqMLwTu{)q5oFR`Gj2}d?}_k^^N^u6(swBHi5m>@$nJ9p^dK>g>#O7b zHlsSY3r)=kxX?8nni4`Mg^@5)dHWbuzlw@I?2|=cHRV3hz9}xnEbE0^K=T!ltYkx5 z3%Y!JSj$s~Tq?=6%&|hkT!Ns$pv1^US*`S3onkD@MNT%95SSsS$b=q|;HO5BPx_gB zYN>W#Pqm1sy$lr!;Bx|SgBX@T0~JJ9HwqJbr* z_FA`A?Ry=1wtO2E*ke{>Xf=hJsnUDRf$@G+!sX;|O$ODI_dN1a_3c|Xd#MfiPHVoY z*g~TD6}6xHd&+twR{?ov$3lt^c8ABT))sd*I3AW(7zerjKaB<9CPqZF0EE=x$c9(8 zT99|NJ-GsurVnXJYOJQ(_kG(!`5NVl-%{LBOWk9oU0~rmoB=O8NZ}4#SPD>S8@M!W zW%d+;3-`O+;Swn4RRpRoVsF(VBt@W%5Xl4{#yd?RZWn8~SH?Vkg=(wcc`U<%bbBi! z4)%UvyKMM{#1{TxAYhk@R=*JcPGS&dgmmH}UA~eXPU(LU?tN7sgcg9io=#u|m<;|b-R}Gc5Um9E zZ+9d`2VFCmVkk&J7Z%)e5b$0h?uNmwfl$nHsWka%)|Ydt&CxK+twgEnH2vJ=aOP>P zYn1@(c5A_-Mc^5i)KN~Fdp_*UO|+U0%}+A+%!;6=L>5KPnsVG>im*>F@GqzA91^ z`ZQJj(iG}M9P<;JcWEZet=_oOiXcm+Uk2Rs zAwEz?TY06;iM1)*a!bKZ1zD8=T}ci7(vE-m7{a#g&y^<2cgDuj>?g$r%;utam8^F2 zxKtg@+bAHYPhTDe5Pq;jkKMW=zQw^hwC{}DU7eJF88|!zeVT&4P_Le<3!MBQt5)27 zOw@Au45mki^np?N-*`4Ko!?h}?B}!4`1m_BAD;cv#RdYzLys`8Rj-`5e7Av!IFv%z zmyg0ImK|q=o|!WH)eiLHrZpFk0YZX%GVJEvT=ZN|ARCYy2WYgx4x*mz6gFlBQ^=p;m3cDRUZ|>N>4y2JH*fpFE}8P3OK%IU&VN_>h7qgeB6+Y z3)7zS?zEAiQ`0&TE5el9-)Wo-TVz3+yl!VILpyHsZ!6b>j{q473HnGnlMDX26IOWG zbc+(nn7=K!KPQE9Rij?&PzORwFjt)zlfTQ7NTip5?LrCbe!+{-poEWR7%WXMmuNtE zV`|AkA;m@-|+0fhny&fblDYayBfNxGMJmt?*Z( zhn!Ah14@*nvvm2%2*dfWYSZ+(5ET(L>IV0{iMhKo*t~Uj>xio3K`ZBn+Z0AWpIJKX z-nwUMnWgdSYJ<(Wyngv#9-9JoI>ib;1&*2o7w&BZ^eidjlLFayATrFKiVR5MS|TJ| zB6mHAB1XFWwt`PNAJ@Xg3lKZ6dM2wQng6zl>^8}`1b>=-Gk>Ffv4kp5wfF&}mhD3A z3h)g(GC!_BjR9bDiH$0?og2Dvle56|xA4Mi5#1yp=2xuh7o+v>oyR^l7=pJ?$IT%} z8`9V)C&q_cNgw*T!H0Z5J99v{i#@IuSsHR>ma|Pcou(Jsfa_k&O^=RPiP|gCj)m+V zzVL2AxLgjq+3gLqu-wC=!yZB|5+Y)E+q7~>ZgfAS5~}~O4kqCwe3sD*6cY8gdb^NG zE!{+K;uT=HvLc5l%Yv1EAzteb|70>{`t91apnMvLwl}b{lC{#;(y!FdJ&?OzS!PAZ zw+6tb=4LElaTqjjB3Y$5L;IlaZW5`7)YWrN)H%@E)z{y*?^16!!^9UbF;O2^2X2ns z7>91(yZ_)G#&vXdc4SgDd&WKcMYfXrg1dr(tNTsyO_RruY(7{3*XAbQ`u=$N@5}5T zeyBN&NrD!FoQYuBd!q{jcU^!9ZPNPf+7X-Wt9!9=c4I|oK zXAfk)CIVAa$a|$NHV6z%S6oRw&4srj#1k-xpkn4-@?HT@E99P05n~(Ao{rd=G#C0| zdl5MwpSTtjco2je8RtZb#PLO#pq{fwQ~^NxW>%P`t>|rDzk!Uk$m(f^mB!i>dVEVC z7&1?=6=?l?*zpNLRn5qYB6tWemz&*?{Lqof{R(4jM=43rpjWyn&yU*h0rqNh0x0 zi@jc0^YKT7IJT*838s(1CXfHy=UOAHIgjag&8xgib5)QW2KZ@uhVfAffggcmFsb9D z9u69^_-PJA16RDoyum1960x#?5IO?d<#$@W7OOO6$Ux=KRYp;+tggkRR#h_tLes6X zz<}(y_zDB}Bi)IBzQE;9h+klKm2qH(yW+a(u&8Zr!-eh{Ch;%cwVD=ZJchSQakjjR zRidptaKxF$jT~Lz>Kr7v-%TBH20Fe5Su?}~d_4Bi8?6-7rP6pXgM2OkY1Chy@aYa2x^M40FX6%c z0NMy8TIx<$y(!WKHwR?{uR2LIQIA{-jXf6Bj~9}ag8PCLo1(WjgqkiFSbHOBf*TWL zq~S`F8g>IiiJjriy&GetEN~$s-#%lIQ$d?BF^xL~s8*WWj3ykko1i4=aJgI=^xN+U z)tX5C^ceDT`qPm#pyI|lg0#lHv8(UJLJ`cn`J=0*b9Ga5{KdlnRfe7wubE*_e0oby zYmwusc>D9~BkDSTP_Ud2NllU*=>C-Yo{*NkqujsgWn%@FDb3?@jv`%Gl7U13mwl#8 zXA?dg7L;k@o_;PcOW&f>lQ z``x19m)YZ37O?-j@|s~gO`L<$~q88tgBijL};B&)QYMS4|Ra_xM`X2{XY z9m3eOcYGL8Le4pWpnZ)e$4>H_s`Qf0@jK?n4(6#g|92DaJ%qzBxP8v$ttf&Nl>mDL zkl8{MQOv_+F|>l#P)^jzdw34jazk_{GH4H6_G1xUS*?uaYcZWp-NrX&ccTg!e(?;V z#^0kZK#vPi?&A({?&YeE>Nc)Ydn9QFgTt!6i2iAGZe7m^&!1 zqx0BQwHPky42%a(#sMmVyKatEOp-9=mftv_V4^Lz03#0FdIw|(GR1hAIO?R`eU8jt zU|D-x`F0gPQAPsFn9o3V&z3Ux3I)m=|RvG@>jC?KuOB}VT1_hYB zJH)N1Z{Ch6f7;MZ{S&Q#2=praNBGY0?TOb~MfPwIB(I_VV56LiU%D0?jw+|kdlHbd zBUCiA97b@N;eV9T8l#tgr&m_nm)}Na(~(d!8}fY8u4NU;-#njQ4X*KxO^9)ylDFYh z@qls^)pxT9j^^9sU_E5We|JBWMMVE{DDjs5a;T1?O$K}es14jVz(C+^{~8E+i7hcj283k7+jzt=3d%g zpUS2uey9O&e3r#5fLM^wT~%h1H?{(=>GuylRRBv0Xs}|_*Sk>`1Wuz;tNMHn%BVat zFGxUr>EVxh^29W+P2}r-^lq(pGniG~-UgJj-K&>)w}>`_AFI9Kb(TkEwu@)s%X(LC z_UPnJ4cLyV?{Ys;K2n}Yys$##duICcbUw3%llK4xGUuN?ni8&Rx%kMR7lHfJ8GIGV zNhJE3@7Bt1*Nph=)Z4o7;Fp&Ia`&C~6fozJ4y3PA4!7qNtIK{|ZhBTu$<{jX% z!T@?-2@>|UxB0&HXj4FNk`7kSx!jj^LIByz|;r$jFNs``lt9^=}D{@YZ#!Vy1<- z;McU+1F?mr= zK|95L05}sVeGYYHtckZN(Y{1VV>*%?hrGb>EcYF}9qr9Y5lax^=mx z=Y}A8dd%d=V8U|d+8pIX-9K}u6D)qBh zaS>_Uj`dm?(dx^b&7L2p!5v2{m>o!E+5vUHhfwIhT!2X7scu^jZ#HU^jlt1(zxzEf zHsa;|<2We0OY{PmWt*3$4{q-$Es>i4YA#uiaGxJIE^jDtq7Q7`Gp#gGA`8R4*bJ+k z*;CPgkA6`zHi*%n^6#D6lW}`wE0(tVrks8881!_OKGla6d(h2kc4O1~seGFfR=U%u z7ru#S$${>!su!=Q_iK45MxbZipd(+mQboY?2KHR8eRdqC2!L(+!bWmj!sX0{bVB|q zRyo)0m9lZ8f&;a0U*5X;zoyW z80jRA@-$9nNCW(rZ?^fw~s%r+Wak2fiF)M0hWT)&OTM~ zLe=q7gw>SA|FjfAt_Dp)*SFw8bR8#oAlFSBnDRw)X~Q5An_=zedeDK0c&nwM2x>gC zSx4IoEIYGdj(~;(V0Yn$jzRF&rYWv)CHnd|?V5)gUnul)NV_d@Yx!57V?s4cer%S4 z_Lu@hvCt+Q_SO8t(^=bk+!c~40*O}k3Nv&WqQ-4&NXZuMY{740p{W8mj+JK3$e7~c zH@*b~Y#5Hk*2}_0wFRVKR2*C}jdhWAqw7PV_4yw0UUbJXKxP)m+Tg*8_)+{HH!H>f zvT1b+y+~9TED6cS2T@p?F~A#<{5(h`hp;>bUGhgvz_LLnrrw|{ zQ~puFSxN9!TEo76qkK9sciLzmgVbr8*VPzNL`KFF4fack<*`ol)7CkK%t}7z@QUSHK1Y)Tyq`EBXXp8Q$o7~R z`V)$lS>fTL(q(Ac^wpZg5OV_4!=3}($%1LIcuKiC`W(z-E6BKIf>c^*4bHw8KxmjhHJVWV>L-DOADKr_ygXNEhu}J zV9Kc^t?9_6aFGWOM>J0&%jSUC#Jqh4scgN}#gHl^mbs->!E;4gEEk{J%FiAI1UV`= z066td>41lv6Bq5wf|0vgkB7AkD@U|Po!X}t(@gb>5c%T{tAQ&(t^#L6E&Rp>*G67- zF30Of9_;`2K#&^<0TQI;&Zm zdE(l*wxNa2SCpS#2K~7B#5}@}Flk3gUFX+i>KLTJW-rF%uKHi_+)nX9zkd&{74VB` z5K_oTc(k>w@ICnu_Gyi^z(L2#!Stf&9IgHxqj+0J{kERXp3Uvk#Nc3+tgB-UzQ2m$ ziV1g%QZ|+++#5^!-&exI!;b%iEEg1UhsEX%0!QcDNh91+$_HGbg>%wHhp@0kWK%`v5ahs)6ZoF6Q1jU6puh@3V{CIaDjx>S!qxO7**sI6F~; zX@Fo(a&Q~~g-YwDg%&Sz*SE~P*|pFIJ*lYuGUD?iJ?hD%+Wl;GG}=0@i0dih{`V8J zTuBEn?I&|%_Q-R7fQ8QsG$+%+H_2O%GkV_^_>zoZil~yvNO5<`sVI!>$g-K}so#tFY*ff~|W}TUN1Vdr>(y(#XghXrav0{_vzLD{Vo%+lK0wdPHL;SMFIDO+a7TGd?QiMMST-GtS`7xU*GHB zRj)s$8tOlb{~>X7zuEu!t3hbEBVJUzlCkG%o_+%x0e}|(kNMY}afz9H8IPL=F~)b@ zx8yiDJlSG%K7HN@FFEfjIe#*P93y$4yyAN5BKg;uN?lF`0RVKldGMWi-AE+nUUSJ~ zAVJVAf9zu3>HW(8y%>I{f}KL;Qmr26?dr1R9u=#>*8p*z`mB|wJvV0LJMcnZ<4Y^x zW~sA61Z3Er$2cb{i=fL&^mXt3FMN6rbG6J|gaf|hV+`_d%B;@|Za>zl_%7YPD8@Qghh`TR zMSLmpGPo1B_E_tNynbiU<&QZf_p&{H_kFE854s!Ph&KG~z>4`9fA{Eo$iMmqp^le_ z;X4dV$Cq%4Dd4*e#H$CMx{FWtni@Q(j!Zvva8NQJE8->cqibB2dKK%1u>4p?b}}M- z)AE?Z`6JSp02;993Y_Y0G)9{u()y+aDf$2huQ%Xa-2 z;i+kAho0Ymsft_cs=4OB%d(cKoP|L|T$weX`&w{@?|(SXAd8cSU|5A_*6euekkh9t z!xv6mo86%uk3N3;mLg@Tl)6~S@O#|xNc&=pHCKp@@;B%{`_K0|y9&0YcpZ6`X?fzS zx)z`-pQyKT7JG(Kwzs#wmr$t}7N!hTP$Y8ue!=R0CgZrky^pfa%*5o+fhKy5jwN@8 zVpdSPMiyKkPZ^FC_PwyYQ+8lJ*mLu`INOAi?ap4l&uHA@CC=;8&kUw6oEP*X1xH!*gH1d?EMOD|H2?)Rz`?2Ih55Om)_P+26^Coa$SXEyw@9 z3t3NHvFEyG=-#S*N#%ckkPBLJY$`M93*WUoiK>9M-MpaOQmM!D{~^u1*Du_xU8+??jzW)H+*N(E8DbuW++Q z=gB!b8$d2n%UdZqY?P6x=Tr?pf`oIbz&4I1kxU#JDf+*&oa9-le4oP#QS!$}jU2|4 zWA6cNi(i2MXB(izyPpgkkj?qKqUBp3`mekX8}2a2Qfnyj`S2!t>yvvYf{v+wQII^* zy$;K>NR->ZIdb9)hWc!GD*gxYY1HNZ3&&&&W(a#&sIUK&EEj#*EAvY3nZb4xI-Bpy z*HtDs5pdWTLKCQrZVSC5P&aQT?lc&0S&z=+YS%4q_3|s(B z2G5^22Q3D~_GEi)`vG(8ZSnw_PPZJnPC8Grz>4QV@;XSG8@sx=G`je|YoPha%l}Cv z%i`6AM@#>_x5v?9W2Chc)ZFB$ycO<51<%TFibB^JXYw(w<(Cu0i~|VV_E~BmRK}Fo zQZh?i8b6>))Rs3M*6Dk2%$fGPd|{Toa1a4y$gC_GbZKJj9I^mWVnwf_i9Ou?@~9Hf z;es-3u%AU1X({WcShG9Yz-pugg~At?@&{6O8b$O!>Vc^ypzp2<0q$8v#u0n#?Nz;V zTJC8PBG!4)!dPjAan7%AMh|cLih9v)jESY22b6cets2UFbHh_T_A^%jojRjL(Iwu# zJow?UDALw6YMW?ITPaO)zc9O;ea+jzws$?a7+if(WIB6x>3mMcD}I}UW^~uv=_ikR zEni-H{4TBS{0BoCw|m6dGtM})4eo(&(Wnzw-&#TJgP^v(%ZF}UzrMZ>wDpf!Fy0Cw z;-}%F0Q)E7;xPpIPn#d$nf1^gk6h&XTYSFT@4xXACllxN(Qt@ean-HapT8QCu()yQ zTmM13)wgVh24%ThMgn5sdugyfg@Z53_cu{iax#o6>^Q^FZ{v4A^H0T z0T@oedbB0!iByBdWhKF---~rlBO#U{9HCHXBizWGR|xTzFy)bPxKsw@?VjVkd9rP9 zdTwOu6~j1qka%7YzO`BF#*5^0$Q`rE)%UQWoUT`)ZgTnkN^WUW6OAFL{6OE{)TWZh z#?nr&CY8*x&~3-Ip4UTu$ni5*GRb|JWYZNFI}Dtl>^i^gAHTHfbScGcgAhZJrwCu^ zDc==oa?czcy*&cjd|WZ|4AElRK-E5N_v9pZ|~UQfu`!DZfu+A ze`Opz$zpc(G9F#tcy?>%S<%_R(X-di=1yq%ss!DEX?$9pyl!K%vv}IhG4PJ@#WSZL zHH57i(5y7-FQw3I}~>hwFyRMsWXFPnCd95i@9?75F22PgJtr`i(Zi(F#z7UIZ^bg5; zQ_+?#>!q|uTCm*Wlw?{~4L;HeN1Wgm8-JkE*a}6ucg1BcUcBiHg$e~R6+;_xg*>Lp zG@8X_ZH(I40G2@DX9~|1@**yjLI-9g$Z6uFOAx@%A2g=c$gmm&Q7Yz;d`46E>*XEtWSF2yu=)S($Q{ z`d(KgsZLzZ4^)nd7A3y&D)aD0;|UpKiNt=x^7C?ldc=~NsdgYgD9loMMmq`gI((P) zo=~+<(7D7agB@HM)BPweqj8zU5?Yb24a5JFud#C6%E=8f;~>JEH>)&L(rXH!bf-WW zh7{P+%tpFfiz#O~T-cP9sB2vm{d#HwIo>Ciwl?~^jRt93ON#SO)dl^Tpv=R0hP$;C z+pf774ZtPYeff>uj`<9^*<9nHUg)`(~9+Rf(AUCnVpCC1l$c1r4J>K`jT z3M~Hu9QsTz#i$vp=DiaSL}z+Y=OZ@`$H5eY?4qlAW>93DrAk<+(oVi7cSnuiH-)aDE^>Ih;F;~GuaCyP3ORiF z0-|n>m7A9SWPDxmT@0+5hd_8)L_Mf{WZ-LuccQ5X2>^8D`5~i1Xy9DurEq7n{+c$+ zJ15l;jeSRzLk=F!JP)uHeV1-19V8ulH0WXo?XBE+uyKPt9ViKXBH1&%_27H7Rx>l& zpn0h6Mev^v?v{mDheaN5M1SVr&K;AD8CfzVHr@cjRsYU)Df?L82vwnx_3Wzt9XxsZ zo&P8An=MJKgO~ez{AWCZiBxn|!DVsd*9l+Ju0Jk?5@_ej4*>WOx_i^J(<08ZtuNjr zzb#Z&;iJxzTPbHtWsTdp$%!lt+WHYWnpg`$)h#LI^x;e|#|7^!XTjwxoLLbHkbJ|E zsy!wU&mrofo^zG3Vz96@!fM}ih&pYNC%eCUT*o5)uXj0B>6c{egohU5p%NFI2Xa|b z%%-faISkoKvU`Lwvc))i$|n<12pVs*5-OR2+NOxw;RaYTQSl5TJbUX=mTA7cmz!;J zPJej0u5n9~&xs&%?i>ElfXO)}%JYnE!$JNX@`gwWC{Oc=^^6i)A$u0V6Qe05fvB(r zFx3*2lFUkxDkDo#7HqIB161OWU2_8-SZ^O&%pd#VaCp^c)Xi_K4mcH;$4yX4LuXZn z2OMIm^tme(jjV6D*0>|5d`D_-{$P%MpNrYKesTs&PCZv+C2$jgikh83QbfSAIcCZR zY!b#`iHP@uTT%7cqj`Idm$NSCvM%3b{Zg!SBzicrsg^9|S1UL&OY5tLw!8~R`G;kF zqs1GPl_NVy(@OiBIL=X5%XYT#jmUi2b6=DPRFH)_m22fWAR9_0I;;RAVu+0h^Cl+J z0K&8g+7yDY2Vj{A>F(KEoj5>Eu!b=RlTPRXV-P(j!&ySwgyj9Z8YM5aq;V6Ixu|3z zO4%zjON`(M(9sMVVIBDCAz)I@=X8g2za0oO0d19}Np<$k+-u{x?MO!ss!VF1 z6PNgvHP!d7nu&R2_78*UVE-bz+9@6NSH;fr=W_~2innzYUl7SUw{5o6!mNNPzn05A zIOrZ!$`LVgupL4+u#QA9{&`i=3sk<%*@bOjw4}furOr6`~*X1Q6m68eBQXx_?#|Yu7Enur;!Ywlh>{kFAL8J<;q&+f*(;=?KAdBHvBR=S- zh;ZP5S%|Q|p5ZZBpmROk?F-CW2;F#dz+o!0VhZYwv^px(?e<=WeJ&@tEka0+b)6`~ zDjjt+7(hs1Zh}NN2FjFydXb7uF4>yqiV9-^adC&3eMOI_ZQX4ZH_++RK`KnnHuF@K zyfSj%AUs82d@#^-SNRFMOX~coVhuJtFa_?xEjIIxs*+1pwlg`K4PNfYec+NWE}5y= zZ+ZJQ^~p%;{x?3udXAGpa0M~UtEb-EE~{c>`%4R_=OGRE&GSnF^Y(o!&?VTx$ezj45NE!qfR!@IeVS+lFFPHRjMjkT4fSuZ40lnv|4&x zEZE#GZ*J!;jE|LPfGdSnuS3PWf5$Pljampn=Mu*7?;GwkrmMi-`D-lL3uA7RH z6=Do)1(tdQ<}-TmF8~WA!L(@52?4Pi6XpZwWe@>rd?)}Z@bQ5EuZOqj4cDO|f~D0h zTwaVg)M~oqp_^BpP7UFSVC+VXYdETQu2!1oMA1OMd1FR+bkhRm*=l~6@`j^fF%{F4 zK@sfScj)MnT&}=JNo;npQ*COs?2fj-lU)?^mi=S7yp;JZ#Z7I-@3)UI&1S}JZ+$Pj z_*yNj;%rSBrHC4kPYc79q79mO?2!rG|d-k_O?pNBZrp=~Nhrckz$}StqnQ$^}4b zShOT@b0g1G04Y;4Z=E{hOhaW-Y0d^-{oo0ch%28jwOtA>b+`?%7D|1U^Ln9}D`Tln zm-5SNQaUWx;Ygy-R+KR=4xYw@b^S!>5{uxfJ9?n{Pp2s7lWOfAM^=nyUZEV%e#>6n7drTO{u_f{ft;%2VZk7B|&;!RWxI9c`F~ z6$DziIp96Ikc)5-3?%&@Mduxt^xDSZ-(V^rpyF2Cnwq#rYT!0UXj;y~k(ybdX=-JG zD>XITR@T97X@z?<4vt*a2}flc&C0fx?auM#{hz;{4-e1HeSh!kief(frV&2KT&7g7 z?XKpFF+@5xo-FHAfwt!W`r${*Qz$3jFjQQ%-w`#R5s%qLDkuP_H&|pIA8fI}9b2zt z;i8WIErhpOSsCo;GprtMDF_l4z)lF_VQ*}J1IJVxNabHhKMTca!Wp!F3#K}c13EG< z^1Y=oD>Blc)vpC$nyF;H2^$O$_v@~s3oSO_0Mz9pTya7B)L^@$tu8GJsuepNcJ|!x z=tMomZh3xs@HmfYwN;3np`HIzH-nVM@-+f*tWwSxRN z3;ZyRj4RELA_h8=ckGD8PF@3~1~wBhvcYs6T+Tjf(ojU9)Hkbc#MdsVwXF+dsC_!9 zCqBax0I~n3yT(OYpQ#`crDc>uHF-IrU%}|2o|ey@Aqb^aS(sfd) zD&$1f9)tFv$R&(d&t_;osU>7xS08{3Vj)AI7G$1np2C(=$A}_02!Og-((4>D&J&i* z5%D}IG_l9}9E4sj(GmFdxIpnDfDM32bad3UpZw`%DK&rIe(XL+`=;Q>oAj|PhJU(V1zi`{>uMbu09fV zi~d01HULFTCTxG2@T&0oI1+Kxd9ND}`1$rk)oVqwgpGYYSN=_B+2D!o~oSWT{UK+NZl)n{}?r z`EIJe#UVWln=k8(lY8#=8Gw${0g#D^I);ynl#biW>SiN;`VbibqcZfisrhC(wI2QU zAh(-ApZsebnE>2Mw&cJHB9fPQv~J6e&0k%@euc4$$8Zi6C7YN5$Uud z<1fTo062#a1C|{!I0rBDy(nyByEYy8wRq5xY8y~|sc+N#c41Cgbd0;IQy0RlfodI3N_HafHY_S?@dMxQKR*qt}B_P_`T_om*UeoT0e z{ky(n$H|<~Ey~S;EVRd3Oxw+VX_B|)Mstq9sI1}3|GkYLYWCFO z)Ur#|6rOx(ho|$C^tYEVg1j+22>Xv+9~<0Wp8SkDqc3bGr4&$E(~f<5F*&n4JAim5 z>?MwJq=6Ab*mA+b(Qf^13k%+UJ|`m(-L-p$t}6JSik*>&Ic z?wlg`Yr8JXw(oc~*NdHhq8>%10IHPC`@$6v0^xYCFkQSD4yHlce2q(Y9&I{OorG9gWV1FZM{LAuYGy8hH3e`9MqF9MlI0{yhdEdhAf*R^#X=#c>Qj25Nw&?TY; ziM4lP$p-SBA#U0osnMaFSp`WUUO3nAY@FXGjU0O%pjj_6m-Vzkv!}rh1=jBn%9!%=8I^|t~9+wyi;bdww}JOzFx7erjxEyrJmC%T^R?N zBHh0<|Eh1`H`dh^RadsPUur9Bsc5MCOA5csFfUX4YG$I9Jw|Fo%3KN<2aImf0gyqa zlV`zu0Quh7J#fxeXa4c*A{i!&mX_eR@5J}!KbV<=X14m8dX{?M@se=wzw4iWhS3Fi z46+qPObc#uFEe%2vgTwh+&_sz$ziVY=^h?Y3Msa=r8<-AMe3%kl%F#~ze2gmB`{qq z%)zQ!Hb1mX;^h$341Jbs7PJ+rHc<~f$}xjox5-M5{ZwXO&pY6X+F;(l zzpUCHcE-+L^u1dDPnoXK{KW|OzKtARN+ONL8gW(wIL|i@NY@A?R+{JcL*DnUNC{6> z8@AnQho1r%PlMoQdI4EGl{??`zF+WW_Qba5zQvMM_C&eit(~!U`=1Dm3e$h^#NQr0 z7iLRq>2z(!)6}9xpftZ(F}Z6sT=_ z9C(n6GrQeYi~|?SPswQJiDl^j2JRVFQ!-|25yCeH!qv1jCS6970P&PUS@Ngz6SY># z&uRsgjt1nWRL3$iCd4=v(w>PWq_MhYw_5#h9rmVi00Qm+Esp2n07@48M6t?_uuZI+xZk?A-npl0R)kyC?l7HiSI~p8#+{x43p%C^ z;aP+qcGCdCVy!MxBeOqbktQ7@W-Ca~1Hph(w*sYzvC~3mXR!qk;-rc!qU{#h+Ku)J z5At=&ZWQS zFNxv1O~~!)!Tq7>j1!MTdxN%~NgDIoaqhac?KtNkCFXb4PIVueJ4)7v z1<3lO3jyf(&9S2R`Uj*-@fbzz58Z#ljGpd&JXi&2cKw~CL=18B6z>y#y@qOTi^wKD zXH{gY2rc!w*^||%)u5d4)ps;Nx<>d%0Hq2d(?f^1NSJ2isx|%w<4G5HqOcw?5UNNm z|AVo9g>apqlC)W{)=^1x^1T@0x=sBC$!bw$~^R)g?-0Y?tsl#PgJNAdD3em2qT{?u)iCax<~aT*I`@(csWSh z5oLsbzO&-zrm`O&bqx)+Z1iE)0Kize9-IDFhYh+g3thZ^1V|jLStWm5(YE;zE-|Y> zX&C@qxa7cCUY4sR9~Ca^9a^D(v9n?-6R8@S;qMMZFG3uUprNDtAhVz_5idDSZ^BLz7V+qi;9p2Vm67=mt+SY-qPt zL7@eLkHjI=UD>cYy)7A za=a{>a6hTU(b+}WO==&`-6&g{9d+QZCueof$w7vzCIF!Z41n~fhLjNKpm@6L&J`pg zhYJ`^m_WcmoQVk)+j~xxwxn|bYWs>o=##GT$?h;O` zOvk~-faVEdj%4gv-Bv#2--ibf&qY$=q?F!=b2{l!N z%MJNMmN?67l_wHtr+`6DXF)hRD0Pq{tdSCN%%&HlZ~Pve)X{nUR{<0s-uU)S3Tr|H zQ8g2Tfr5NS*3dUOxPOAK-Y^}U{9_&Hj2!U?*kZdfCax=Y)Lmi#MBE+AkGiLLsZ7f* zl*Il#m)5|A-K}*qpS;l9wjtTb<8*j#3@bgNl_8m*<)L)yKxfY}8f4QSup!OBkPRc` z>NrZano>vKHjOuq7C-i#@-H6Q?O$&|etGeMp7%#jcR6vs(t87}qbCShhxz$)-Hg9~ zxUy^5=JNCYuHlXu!CrG?vGCeUR&&AjZXE{|iXm6qHWcI%dh6Lw&khUBi}QB5B#m~v zKUYbQ<6wVm*rO>OqAJNHCv;sTpS>3J!5(k17(khH{dD9@-l~tj;9%vib?=wmxJ)!YsegBrX8bK93agiyBa#RJ|g%EHN= zt+;6|Tq!%vjpSSgP3fql1>625^HCkskfUV-zS(0PWbr=TBLH0L&}Z;|ybJw`sP&%72Hl4s<}l{)V~4%+2H5RAwa9RLKTD+HK4|18wyU z4D!iFx~yt$a@9D^Ha{<<+B5MpLcm3ch@znpOyK;iqzfz|Z-ObJy}KbKLIj^5!5q}H z46kr4rD5%PI_6@S>5)?qlXj14XA}vXVc>EDIF4C(7oJwe9GXi;+@;~~#9}J*U_4zr zUKVjJN1HC%vrGf5U7=cq1T%4l0#irg<35`%$vPaaTmmZB01K+_cM&pV=E!yZb#GEB zq7?%X%cUipfQAOiS$gk`BI=exO$f-JiKK~PSy}esVfZIscER0ZgbFjJ4XVnZ5ry69 z&en-K$80&?UUUcp!e4WbEjJ!}AF$Dwmi$JJ`=^sLU3cJTm7^d_0V706DyaYFoQ@79 zDdj6|rbD?&V2x$?w|*vZ{(!=X$on9doPR1`+nfk(pu!d+tuHhi&C&w5 zWSwR=+1l;|C^?}`&!?6Z>LfbcmwxifiT~#oGXOJ3am2M?#dnOv&Xh3E7xpg{kY4=s z?syjm9#lvrW<^0>qJ8QNvui2P^!H#USxd5C{HzikBa16PSls^tAD)a}%ArjB+%ImW z&~~8J-ID*iw^@~vgg9NIQ4>XYdEl!Yb3uFa1R3!&8a4-vBo^dfKTfUpB+X48SY1+n z;+)i(d``ZXh5i|NQ(_(F(_d?q{weSm_^%&CAP~D2*lGSo8}COQV{9v2P?(}BN0Jz+ zVrMFAx1KO8#9YhR3pW8kBNjV#I53r^Q66AO{p@mH+qEbTYhe*8#oyfnA|$W{N1(zv z#IS-)qI&@n@WNXQR1_016{7xIa7(eqZW6)|==j)d{3fBLa=kr+jF->G1uh_nd_6!E zLhEdrC2GGG;iPHu>AG^{23=!Gd=B!J1d1tL2tN!$Uks0atz~9)g^} z3BfmydHn|j5kxf#R7i_Xl_APBTfjz*y7i63>}Wt?6q=F!+r;;$fgQxkr@Vh-r` z`v3G&MHe_ev^%bH$nkj=58pyE7XoRT@I`m%zaQ;yLQI|%Dic~w^6N@Apjne!RFryf zsX#81So*JFX#;~!ok;#KL&1$-ikwpXkziUp&A+okIn)nWu&4(uapxy5O!7P^+q5uZ zlv`I~I?`OzB_yvku#yc;^uU{Vh=t_ME3IMSqSPo_o@7FUpk+s~JNHvjreaj!j=XKD z@O+Q!5ls49Hn@MnQj)$dRm4van|G{2@lAlK7C}VR4wFisZ-jM(+o~=~Fa+`$Ectll zb&X^I(ilwBUj#=|UD`I_FvR8(8nLv7wXMlgz0?PtInVT z(j6e~c1U&JG@)xR=@cvx3!0S*xb z-WFuY!MujLB#7eQ-HHAhr`-2A61kT2-#zey2Pn5v`yn(++BK4zf2;~r{83HUnNa>U zXj&a+EnE;?&g>$L@5wzNI=&lKsSVz+Jc=$ zD&&hWEY|>=#}J2UduCmW-FD0RB^6t+fJ$?Rl5ESBrtHxd@W|W!gg_%4prGyU`0|Y7 ziringny5#i>{o-6w*&~3n}QTu2eWcqW(QAkeEooquHy4h-tDl<|NK@oac8tgMcw=D zu;xX7bn^1oGr*OrCgQMw&lb3&K^WA^#JosdnoYp|whV0nB>T^jHrDE67YjS60!pQs z!S3lA25-maIeTOvFS-Z#Avd)qUSl2yp$Vc%=C5ucOsPVytWRv?M4FQ^psPmyf;!G&7# zt??&BojPVr>kl03#H36|fE{(DeOjuqKETbrUaH7^1`m%mBIBKsf`c%!ImQ zw+5g>f5hEM`gj0+%INs*!gJV(&6lBbRV3hiJHVhTDDV*k+Ej1H1H+bUHm_8=zm_j}TM+JbN7bHHLlQr zz~AlS%SBq3UVK7_o_6f`<|8s_2XaS(Y-#4@Gtx@ga9~|n{9)3_7iY(t(J2+W`kgz7 z+47fKi1YTi-R}rn3fHakTQW>$bUz|%Dh&=xUl+Am!%~reg?PGJAiG^zi%vwQ@gCP+ zJklE<9??11k0|yRM`%+gu5$X-GIi&7`|dU(sF9G*J;+b>%r>v?^<|I;G7MK<=IMpV zjSNn_K&Te|oArKp!|#J7l}9J5+e^Uv8&l5BUmDK*K9187D-oDVMt#hCdnPT>WjBns zRy~>Wy1eu%;eip8OE}Fvg?~s0+)z<_{Z_XBbUA&sVJh^P@~99X5>Ys`f<-4H;j^W` z1ul__Q=*TL2p_3uVaP`?%2`M$VuZH9vfwc~B^*wqqLhaPN-q$fu4yOtN6OMwQhG*JW3oL797n}p%e5rF+deM`VB0Y$VAtgEg z?dS0}TPx5El}w#EJ9s0fVkokl@avL}C2PN2gRy6s&iQe8a}r!D(y8HWD%vX>34n%d zCL1)b*;9)8i-JJp}rT0yByAwkochlJNQf+`MOo&Mq#7@*VA;){zzux3W{oQWzDd1|(xprL}uH0sX;*XbIiLc^H{O3Z}jItulXJG z!ym(pC^&lqk6~%Jdm3IBN*~R`kF4};ga1B6FRxtDWbUw*67C3&-0!sozqiothDAMn zNm%ihnQ9#=_HeUPD#_sh_@@zn^f{1U44ZT4BXrAkW=(KK_rk%n8MGmMfAUju=*oQ z`j4DJ-0kOb_RfUtX2xK6(lHj}ztUQOa2lBS_4%?nf+X?w(a&`Spyh<1W))rY)Vkts ziL?&DV1ewM-0a=PBoZ2J{C~y)ue4N6t)f)Nd<&+!%$#3QWpuu@ysQjR$!+Cb^geRx z^5s*V?RhzE{Vg@uuU82x&#Sq)Q7Da*m6JjV6hSmSQw86-Cw$PLcJ)Gw+QV$`RBLND zYv2XWMg9GI+$S=F{3Sa6lax2c-kyp#G{n=X)H=QxLMqV>TDbtDSVf1vHZ;TEszEdt ztR)SXYL_T0n|$kto_76?F%1;S6C~4u^ z`n+9k*%g@2c490DU}H^i@dMsXkG*b9eF?-dFa zV8Y*)`G*D6f{jR0dl0~Xc`XAzW4+H%JNAWQ@h+z-(hKKXiuSJg>GWt+2~qE;AoHnAJ&MF37dxBH1<3{HksY$I(b zG(}1=D0XQztvjzo`C00phX2$qyiI)AjC{v_uV@(e>Fm$XNdANtp>unpfipLE9f8F$ z7!XcJ(j=hFMRLtjR&d^Pkt)}TGvo2@il}Y-%6deIdIWYh; z4c)G5oe1M2#-5Q%QX7Md%xpKrk7R8wYv7yY+-_OFMZH1upEA`fsmC3`-mkl(8|ZZ5 zS!J+O`7@il2HKM-3uUb-;6bC7pB;|o`Olf9YcK-H0a-!_7lDK@tx2gKQfYEAbcG`q zdbZN*U@h-{0TBODelbL8mUv zPurNSN^o>VQdD}}aK61{T z!s)4=qz)gPGasAj0rUCUI2l_`Hm)&O+#a7MSVjJ&S5%cn=(zM~&p!JcJ>@-VOCXF3 zZ{kn;YR9{t#iE{2xzM#YVxr4G3&1-4MmxBa4cZ#>PRPt=z9wP`r&&p1R_uF#)jWHk z>8Q6)@F+R>#4zFix~$Ptt2Tr+!ff!NGN?ou6EPR`a`3k=sp~AY z-D2Bllh%pwf(p~^4;#(VuE9Cgp>c*8Rc|g`>oja_FZ+uY?!Ks%^{LUW0h#z;{?*f@E=FR77E&U5_?S7W9 ziq+R7wD;6z1wdxds&G9U@$dVasF1r~E*kxeDW(Pn`!xdZFwd+k-~Y*Sl6RL;vINF< zIs$uz{iUVAX+n9;9wayHWKsccBXD{o-V~_v7x%l0fhsvu1eNOR_5?s(v82biaGzm$ zY3P)Pd8o$7Y}t8%S_zlM%3J{n#?Tq%2|Dz%Fbn$)R7Z5XqHh-{eEKNqvyHye`0tS< zWpogINK@AkU~HYL@5s_^ynx|xWGtOy`Y$pT;GFccoWij>t-ucebAm*>(8SQXvo#|%EFD)m&{i3Y?5?Z9eLe=B+90H%|F0n zykA9o-GtUpD|kb?ju{3BqvMhJ%VeduGJ1Jt1KS5@lxJwjGWO8G-ar>JeyS0#-r*%J z#DePpgB;5nJg!7VCfAgQs`4TEc|WE-Rmy`(yy{LuN-G5We$q?6#w%JPNJXBvg^4CD zPlnPa-ktL=V;Lexg#jn+hS&IMB&_N|Q#@Vc%I!3=O`vNg3tYzF=vniI{>Ro-s_@EL z?X;9g9DbRhFe=JLQiZO$jN3rOB7Oh$n6QV3y|zX1>60r&OUqVY%p9 zB%5tZoYPa1Fg^{mqgx9lI^7WDY zsHZeZJR{hT7S#Ec`v{`drtR}1Mtha9na(CEA zF%od@AP`#q74@2!)@)-&q?`Fyh*IBzbI zHOt4vpvh3a55oHcN_kB)Mse?^Zbg1f1c2Q~J2kP0;s(Xk2@`E>HvG7TDl_rbLrSuq zZaPml(PDy9fyAuHJHj*CLeQ64e-&jww}fvM*tlh#QToBIr5WOCJy)QkACdZHgA8wg zK7&SyG0zP>10>QQtWYcsJmde&nQ85`)ilnWfC>9k#ZK#%EEGsA#_p$^p0FAn&c8zw z2C+a{YiO%f_58RvuabwPG2LeZ@Gx}W-4z^}7m*rt~(f;r!TYPY~2UV1R*jkGJ z@UL-ZI3!QBF5c7G&j&cO#Lh)gYZw)ov}`pU#$+1rbMj$y4B3-z@3hR22>>9~A53%* zu!#HSFM4BOD`S!G46}3>PH_NgnmXQ1nOQvL246aU^7Q=}Yj@*jEl|T2Kpv6+#_3$o z9toZ77d#e`D1_oHEz7oZ;{As2D|kb>I3m4(YA^(Dp)%A^;uAYL-?}np6U{EC_vv1X zlBSDb_&9{#wXehLG7ZMYd)?}AcsCAmcXV&!9`6r(Jk1C6W#iWC*>ny_6TxP507?<+e?4zs`h39lhzG|fF(#Uv(#Zg6%i!0!xT=mKYCtTw zTx(-R@v;K!8tcptk~bLGK78_O@APv;90z6QdQ%K4irsbT2To~;ZY~tEyb}`@p}`-Z zZ9iC)G-6t6r<5Z<1PXn5If}_m>5kuuWLPXEWH@zGFfe47+IiOCIc=xdEied2{|9(a z*C6~P;6CyY@Wg4Y-|J^eCO2f|zRAhh9dU6{r`EE`M48-oG9N$(bb!@A%l3S;ql1)l zVOpRtLG%m>I57ctPNyI*Y)rpOth^<0u^va{YsxS6y1n|a@1}_KaS!5=AZlj+4Z@9; z**SIhL&@$fy4xVKP5dr_@Fa!yGPun*bH}s$J_8XBQ~SN72Xy0+S%U}U|8!SxRDJtG zN_1Z)iU`YbvX+O;85fMn=W1rQp=harEr@3)-sosjQT&}>tT+Ilt)*b}BM^{GaiYWr z%OOW?v8rzpV$Z5iE(rh2LH14?WJ*L<)2yq>POhs-Zp}vephT$!z0r0w^H2_ELw74E zdgjKL{nxYEWfY7EmX%m{tB#SEQ%;(hoMf1|&dY(_^b?>fK?ioALN-F!k_{OKsgxv# zOWHvc4_tmYMg`^3RVHZRm2NIb+U#37VvaAD1;jCLy-h!AQ(He6RzE zkkriS;ATMT$}~A=LHR*F;30+$801X8-HtqAmBY(-rX`vUu4@lxa|;|SMLNg839d1Te{p;EqPfB%2jja zH{^qxx+AST_GeSeZCfbPLX*nq#KXkk=3DRUk4q||)r*c6y&Vik0SE?FJgWXdh3#KA4kVNAkCE7A@fTqEK7W~aU z>fpU&_CL+l)`_ug3?DB#X{S66qeTdjvxp0#u6L~GLu9a*ZG{zs=O5%_C1oA;@b4i_ z95KB9dreuNWjW`tRwu5B1*cNCWcK1CToUdHrITlmlvwWRIYjLsO511c?Qf=91)xq_ zS`PM~ysCF}@DR={z#3+Twy#Mviu+n}?9Sdl+9WEvyrjja;OFzg&b4GtPh?uuQ=fDe zd+=h}iot&~fcdja zK~bQ9q@jtDOgS|+Y7Chq=1JmRBOn(ql3N?LS7HGfD;w9DF@*cByCUT*gs_7E{;W{; zx?vlhC~+wmXe$AZRLVIBVy3ObGJI2ha^RP2|1TC8E21LM3(#pYj)p0)oD8Isa)MNm zKOL2y)aX10 zFdgOg!lHhMh8)xCv?nH&qp2abP)^Ql>#m&?CN#g*x-5X;6~c3|G=&=S*pRS!)^m}4 z^oZEH&oD%gXEXS4@73nLsV>yN3q#x>EG&T30pL>AzV^JtJ~_Ls&KL8f&UIT|8e(TI z2&JCn?Hky=4l)j_N&vfyp+s2=P?`m}E=3nd9<&z&epBafubw;pM&3FJq^)obhG?>@ zoMDpue@x`REIyIL!7~BWUcRyjMuiEYMErd#d~Uw1**&?(rO>#RQ)5<4M4d{o5Y}Tt zW)HT$I>@@73CUI^<0olb0scA8?doIO<5l`DylQXAd+qugqu zd>{Ekjf&2m-OlNtVUx;$zpJh+(uxi3Op^UGs1nZACmS>e=$Qwz8x(k|#b(Ez#TyoM zH2<@z2d`5>ggOMBJ<=zSq6$;Kf;$k6wo#|Mp9@{5o=iVn z{u8Y1mGby}bgS&?_-Mfy4;_!r?c^wro01mFh+XH)_L5Qehp*A^#lbU5SPOD!=LN6Q zdq=tk5HU<#cywOsR0m(oiiiJWa2#`#Hqlo|Ob80 zssXYbl7KUGISAbq`F-(#-fPtJMRM%;kS+~&OzE;z&=;(#SrgX*!$qxJS9(kou({12 z8A#t~-EHkaN2kC89SV~j3cahc5p{CsvXG9u1HCl4UPHe-QdPEf*s6H-dszFip)uG?)|NNpq}$F!wdoM*tj_j?wcYqSSe9z@mu?78b^pML ztAk-v_3zbb&U$nqIIc`6K}=p846Rqv7$%`8>%%m9Zgu&!HfC{feTCoR4ypS*Nxbrf!0axd=}h67dRFU`OmO zz2f#BU;C->7=zFd8>a z%yAwAxN!0X`(3fX=ekxfDw9Ifbg{62KDWldyij%vQl%kq)Pak1uqh2VpD~fmKeC5R zJ+vnMPE+a_p!152JKvbzx0G;U(|RI~y!~Vi(0kEqJZ>`kMP~P-`DWF8Wzsbchuf?cudrTc}q?tcq9apvN#&VBRjGw^B3zR)zGF-WIvbW;Y*sF#1pcU5)J zTo`ipEZ-YXZ`hb^X!n0Io5D&2>UN3XpVH_kYAoIpE%W*y9zcF{6MUF)Y!7fKCOhb{ zq7|rJy7aDppWH=QuvlUkr6&6Ra!7R|XoC{hIb)ZM5LR@bmir)ak(_`1*2Q3PU#=Vi zokC}Pzr5AH(Gj=NC4R=!5!M8hdl>Ltizj%Vvi?FK;_0kANg2la%M;vc;xIMZQ<1Mh9@3bs#BQDRY7^ix4 zQ!`B}k`NBm%M#%EmOdGW6;)fRobN-laQ3mEkVaD@*ROJYGgvGU$B_;s5z(bL-oyf@yHFuy!IZahXlM zw7n?kQ+f}s*wydR;BDQ6<7ciWN}bEmxzFiReA$@0H2ta1Q6e>aQMTdxPNeIJ4|`&p z@84cO08ozy)RF#hZdfx&%>>Yo{ttecjrsWmD%`5bR{$t1#D1B3r(CyL9Y0H0;3Lhrzux_^qY%W zTrr%{!fmG83xIcr=2nF-q&RZpUoZKtranSoKr1TBBF#G$3#b(pmz*j#a&yZ!s;aKS z;!@ox)c^@iVtND3Eh?!lBod|NN{buTShY#e2N<4gbB(!< zyOBCPJ2GBHzdu$qesjc|B2H~d?d?+mUcYI6)AXUaYO0+Gt++eJF+%X3W%8_vCiZWG#F#~nvwJZwEe~Kexlfuqb612 zU_0Ef1z>3ZT2o4LMp3Noe+#g*=uwQm-ER)9bhcPlpIA#Ix&+~BP{F%c@hix8)mL_L zm95^6wf-ZQDR?hAhn!P=|M!kU^1n;FMEFYDI-G*trNT zb7)1xfWQJ=r95^1_5kWN3S*h}5pwpc##wWKJr1m-@%xw7mHMiZEI98UljCo(_8dvt zuPodu5}LuIMLJ%GT_hH|hhD5iXv(w9)WJ zqdT^_J9>`WfEpi@@_Dj4lvj+MvK0fvYJW>g1f4TFJixIkm`B%dTJ9Vo$_20pz{R6% zK(4>GjGkK&-Y;#j=FmDx{&KsaSa)$kNZ(i;Q*lyy_D2U~{Seo9%l09>G9FKFgrz-_Fm_Of$Z6;ORZlIrojPtFxLd6scm49!HR0b85|#kZr`- zHcA{=at6^P2h6P!4Lzo`@$2<=i_vVil;E|J9bbmE;4WOp-OUdssJ&#&oc1>|$QE+O zUq4O1ZNEI4Nl;Sh-gW|6ZXD^oVX3Aw<|)TwGUn-Fh0EVn%5|9OPu<7VG#$kufBx{%yv_fsgd4yBJ zG%(QruXZa->RhCunD)ir<7He`=pHU7u!YH>x+@Zitb`qj^Skc{SD^aK2*}x&l*>u0 zkJ^5*SEUkn?*8y{L~x*TrK*$g<)tIx%T%B<##Y3Q6ErEMCY?m+q(|&dUnC_uM<^XgVyL!$BFB3gLKSo06-h6t$)%^e7#EjO5$f zh=vY*9O+o$dF*wO4jh%0(3Fg~2roO?LcX(+UZg}+OR~1Q#$^!jpbTW|$+yf#HnGqS? zN7sdvO5hVlv91^@qrr-_E8xr<7f#Vh^84CIRzRgt1uD`UVf4Xw5dNTslCBa zgCj;A7~ou&6Hc>tGa+x{U71PPd`zO?Dgq&i-IS!F$N;TdUC297DyyTHH$Bzl#vv?W z^jy0wl|Q7mL`8>fj7*UGjBqp-X2~#xvbR|v(mqnN{oEp;62(wU>fo;52oNi5FVD$x z;A1XDI9C*YA)5gMSyTf$mY?fBAKne^n!~7!2&WDITATD5JVX|!XTMmgYV@J_QRL2q zk~Um;ylu*)Qo;(@gzcmYrVc)4zWuUdFueZ4iQS8fZ;OC|a97~wzh4tR%X;-*&rL3aX zmV0jfAzsFhmBqQZbqA;$&(ObpqmTM(ID=7moHNtj$r>`%{c$UDB?^!kUfT>6*7x*x~JeKME?E<6aMU3)_2HnG=-{3!^PD`_Rql3oWs20|8Cnu|2f?RU zX`ugIw)+LG+mYIUHSsKtMgqv~$^gz2lc5??)UQ;)RuP`vYh-xx+P}T!rIut{2#-S= zdQzm6A>@>ZkSbTAzQ07c+_`k>PH5OcqkxY_XI1Pi7(1$G&wt!FJtE_Lb{Mbsxw~SdYT)2{z+#r;7 zA-0SSs(ogmb@Nwp&|4M;0{eG-%1#g2cyu9BQ&U=ZJ}~47kk$Uo8`Kv<*!pz0f2g!E z@l;0t_C%$9kvSKxSO6IH8m{wge(Y51ssauGWVXx4fIJ22<@_fyT3a@QH2Z)P?|078ni@1j4~2#O5h4x`}IPQMp=-)HjW3M^og zsHD4FEhiqYP`10i@0I1=w}SJnOEi5X-=`&x0rA#Pya@%U`DCQDS?C_h6n-`)=H~jD z?J;nr3tR+r!+}@a2NqOn_~5!LG2nX6?%OV?B@DzHdx1_Khxhjpfd@r*jz%9pHanRA z-@QWjyiu!tKe6V$`*;5ivyFgd)wi|RT>SUctNmvm7h}?X9U1t~y65>|ZSf7=`g+bS zS6Z}JJ01u(IglYkN8j#yNQk`9odZzE0``jJp&mh4z0=APW&Gse*%QgBpIHmTk043@nJljo)iVoI9zpq!;(2QY>xq>1JURw_3q7o$7l?WIH1AqlH z$aG}4RdU|T)pZh?t$neMgrld0-vlZn5#hOM!Z=u*>iWJ(BJ+ZoXavYi{h2I#rVfDV zs@AeQlBqkaTvZ&p!lbmeT(641s%u%p16oeRx7b*nd61z>2U9s#S6;if=m%?%k4(MV z(SnxdyLzO!YECpKN)LzcD8t_kR8rso40eP99~fc5R*PsIS?o}+_Q1E$%U`J~0_awM z(aEtQ(T}3xK%1+%I|eI@0%f(haQFk=y)X}W8%Jf$>YidATSnXWy6T0LioKcPzq{92 z=Vs6ZeK}jAvVxeaq@Q&yDoZ;*OSLaa>4eku;VdD9O?Cvefd|dU zvoSPkW3F^SM}8UA(HE zy4@nQF)mbxs!XyMF5%O%ZDhy<3JtM;4m;C_Xz?seTsqtaAen5y81SgE^+?anP!)p5 zUdGo=LWRBYF0(tfeUaYwMN?e}k;GtQbod`O%k~d z67Cpee%3$k)`j?M&a%Z8Yfba=W}+x7sJw%On;h+NK>Y{cb2fKhaGCc0fRd$*k`HM6 zx8ujIA@(mn#5~$VGNS7<#w$J^GKKkO({jFKUgeV%*>4oUi!Ga#j0h3$Qpw+yDe|i{ zhl9;1j7T|(?XF*QihmYani+M2pGy@6>#oi?t(Pb1EGH!;G4CXAHLFQ7h@)U~6*D;5 zPwTQ1ddh1xsTQxx>xatS@_`5r$%>g0EkdGL%I*af#JLLJydY}nHmyc|b7p$CzpAkG zQ2CIGO$T5JDCY&|s=EZOn!9dqBBh^5L&U(z4}uPkuLB#)65utaG~{fP|efP@G4@eF~IQAfhycLJSG7`3ry%UUf9paWD(j&<#2V)5POB2i7- zbRRlR_T=sHy{1`G94VcZ)1jTQXJ)=ytuosm>z$uEOx;_5zAsSkWBU0U-9+)Kcd3x7 zyr8DE(x4;&Y(>#K{K=tKm0JA3B8lFG$T#7V`n3%_sRlJO0VR-{6$g$6LDB36YzFHj z2%IWSVn^0#Z77rdR;G43SuG>$04VnsvA%f)W;)SK4sZ?Arz7`^>MwPuUnL>^N0q`; z^{vJwYdT6BE7P1O1Dzf;pojsaIiQ7`BfYY_UlY9X#q9f}uW`2-nGMT-O@>(jONiPa zL~S9Odk1bSo(4f7!nY;p(0EX6GsB#hP_GH^RZ4Sb_tZsJ9}bo}9AaLy(5>60uD}8a zOiVH_Zr@(B9&X9$7kK(iTSWy>sFyjwPQ2xzS(tF4g}CM9K-hs+>=b27_!oB?l;F+F zIEO}_IU{|#L1uh6*1r#TONf~V^ffvl;j-CpqSaer5kNmjp`$wO69=~=b_;Ri8CJJi zYX^Rz3f^eniA!vSf&6Xj=*}M9sudR(-lbzz+Pebwz1Va9-J5;0TP{7?AVEEpypO}0 z2Sm#tARV^UUt0NQblD&xY%WrE62M-fO&kRicng0MX}9Nn;7hce1lK}1O!2Sc`PcE@ zO~G?ey{2NB(gr5s*53m&f?vPusG-cY+{hKlD{z)aHtJBUf;y*D*8WG)z5g@$xPJh@ z@7+7ufjOU<^D)i&RN9=6H6nz}DaxUdLx?u#oEkYsnp1>o6rt3d52;2f9X~@yog}4H zZ{L0Yf;}GlVfVf3dR@<#k!*5Gb8;J`uP&Dxm9nF+NAKfthbgNBo}`-&DvadpA+^J& z8g4@lH{w9JiOTDZIA*`$_7ecr4l`%NOxQARcaz;%O0o;k#Vlm97BqCDDyr|$fxA9_ zAAP(DDd96d13dYx>-KL~&2MY0GgNY+qYoqf25y>2fbFkI zF=xptMY1Y48TEsJ@C(1Azsa$WxMSS5^D`_$6%~Fv)w1tx$7~dMv2&1hW6&qN^TtvC z?oQM0j=|Ev7$Gw97#X>59TSv=HyweE+zfnnpy4{Yp}INn!?eSLq|1MZL36!sxH79$ z=_`UB6G7q*&r#ZRWbYz)^ie$YM6KU09m-lK{T)VHaf5{{VE{kaMP={h^}VQMLsBsb z9?elSFaI#gQSaw0zo5NRkWOywzN1P*zu~Su)ISqi5RxiBB-4{RDJv5XPKe5>1q@@T zUJk#)_GqD$X03D{N&3wJJKcH@N&<0n?)y>O0QRla)U$ralVy5lrNgm-kUy^pLkjnpc%yvM)ar{sfIb9*7i+1JR~O$U>RVI z-2mAx$~x39578eNW9oLgLYULN zTSC@)>1rU$f)Uw=h718RQF}n`SRWI@kPP*pf_Lfgr3KVR_f<8T^}{YHV*$(|D(N|l z)SN5A2^zXw0x64(d?xVZ9zdzz~J!t=aT5l$RE-Y=Wn>)V8CtA)t z_}ewS=LT@hpNwRIZ6iqCALLapC{U=vnAhingjq07eMW|N53_&x+WLuJSF`Jj{OH4w zfy&Z1T%wdH2ww&_x-T4fxK`9#%FON;AM_F=Pno^0MVpQRkAZfqQG%(%ydyyvVp| z*+)yiO(9YEM538-37*UVTnQr4*OtdogwuaJlFrt21fUk4em!vwb&OzoaR0RDklOXT zoqrqFvXD`Qzqg6uWMl+yx_%btX^VSEf}hxpAJ@aB-TU_C^q0JQ#t)vy&SDoI%{1Vc zgjZ#6{zzXDgqv@a-OXwO)K!#z3@dgv`e4r@4C2MV@84^q5^K_Z|}0j{g(Yy}17EH)-ixl)ucC`m0|* z_gtN@ZCL8s-agOtZis_`8!iX`vEgnU*9P**AHt7^&CIhdeqDIFVx$z6{dTa5wKA9A z8BP{PKUmq-@E3b54urKU>ID80s*d&KUH9vy4`$ET8s1$UI79#MzTA5D?l&ua zw>(SN3Ei3VtpG+CjR62FELMkPEGFP-EqtV%JpCXssJb!>LndRQZAqS(Vi2RIws)@@ z#xEo0il&8{fKX`5NbR_!meHpsfE2iz8a65uHq%oxDjN4S?%6!JcaQh@!F}$-$1~Fz zasP{3UU~iI?TVU+QB9>4og>!!4uxzDKRyW=?@cymsqC|rUVaToZx-Ws{J!3>+*9+ z!Ne8;RDZz?CVzW1-kHLCbvqq`-df+d5;$<|d5_PnPu1-;RD`H->-c%E$RHDh}8;D#eif{qZGuu$JmtYTqC!ioQ8jOKja@@E+RQo zBZU}74uyX7SN%I!ZWmCb#gmsH!dwEAboftDcgRP+gH~pj&Boi_FE4NS>TUnq{_|^f z>GCE@whCUGjAQ(eJD2PkO0H*H=e5X$|BXNQ$x_d&dQQNr?c6-AR0{j-{U6uVz zxJdbSGCxP?_KO6J6n9L<-EdlA)ZIumaE&Xp5V+!Q`T+RO5YDa_1Xzr#$i+ri8OQIR zrIre8+)vH`9Ke1`e6tHV7iL#2Z9*C)2O(QnHc_klv-dz{EKeo;*l!0BJcEQp2PF;@ zoSI2uXCMvYH$aWpKkO)BY(gJ_Eck4Odlk>yMZ*ddEf*x>5fZy?RcLTKad$Ql2u2}& zJSs^V`#VZ_VfOXefwF**F^>fKos;2>+7V1!9;Y1J(YLrAlJvVbAa3$mZcK0{KKWDd zpi0qV$kCGO;4m_roddm)i(h2CNaEx~W}d842HI--;Iea)W#pS{BhO!mt(8-rAocj^ z$8P`bkw13x>%?;fV9m;WO00b;`qjY;l>uX!tCgEwC-kU+hUxWzf}iW}v7f$8{x|nz z@zm0mlMw?vVl?F^JIorpYq0=O1@jL;r9&*aM-#VebJ`iNc1uhZhQFRrB-B>FoKvX7 zUL39YHMPbt)vDpVE*Y~>vjq&@UxuA|F-sc7w`wz}(kbDe!;Cb4@xm>r6D9XqJ_cy+ z-gAVU2i2G$dVVuPr-cDx|DM$(%TE72qY^}xh}?#Dy0e%K>3Qnq3)x6|exsK9xiKhZ zN(BwHI$Aw)_f8^k#h|BLhA4SB4uD#!tIoDYe+zf{@J*%w5F*x0IZC4eq8>vrHJlAQ zk*wm>kRZcS>dv?9jOiIS>#X~k_pNpJv9V{8pC%rUL|hWx6VsV2 zufsUoGDdDVGzqD|{m+80`Te^}ml0Zs=^NENQ8YCkJNX&nL zdzCd6w!(Pz-Bhm#;_yok_K0{b;d_M}V@b4>m7iJD4hmp#O*zj(M+QGNm^BK&O+rGz zUF*@NL%+%qHen&hvKhll$F6AY6+5W6d!*+AZbB78j%fsx3q3*HeUpE@^`qsVKNrZT ztve?^d^A8I76yV}FDtts0ToLp~kl!o;40g7uY+0lW!3A*VK{`e| zkKE$I&=nU|(PV*yuH%5Gvx*hR+U2G>j%QAg9MvO6J&m--VLSk3!}|anlgO6k@tv)n z&BdnAuAGe-hW0#G2c8ZNBckX`3VI#3XMl@`rw|zG_MkbZQWcSPF>9&|S!WA;LzkBs z6sy$Xo=!Pt@z364g=!TE_BJ$Xt{fbw!qdl3+nb^T8@`B5n7mpK+-#SWdFW+oeAru6 zGUw*DgafEVvlHu}BJwJ7@c^0Jsp^A)j)cP!3JMgiTQY-ljq8{7XRp;b-2WQ8kHp9B z3||hN`#Ev#aat-Pr33ZmMuIV&t@pg)fK=%DkpihBf9|^j=a1!ypTsx zi`g}*E>=K!2g1rmW;sfm8e^!|ki_XXo(- zqCiiXs^CSl3TGhbPa{i#`D2raL_SfqjD0N2P5h#8+Zi|c7Gzye;2xtjm)#$xU1b2k z2MEx0dwCh@)D8mfK-)DFHp)ZtJkd4jMxf)2<}DMYd&Sc3znE~{j%*Bp*3R%{E8x-mX^zFRuEnhOhN3Sk@#~rSD?>u1SpwtVn&# z6#pNXg{vSgfPR2A{=3#7vO9lUsEykbfA6T&f9D{lcX*jYq$5(RdoXS?mc5h{up;^w zil4Wks2mw)c5e97)A7*xQ03EZ4a-%XzYZF_J>%y4!t4B}aIj=s8;=)Z?uS~~^o^R+ z_%C!&bd88K;=l<6y0;9Pg4S{FaHbkM6uuad%IMEF@M=`mdO<-2k-Xg;`Ps7c0msk` z(!5hnM7w*JckCTyU{LU{l5H0{rBhEOaM@D069&|tPvRhDOwqhbo!E;aS!co6{L z8;k5fKlB;rPCgM6)qw@Xf&vc;B@JGiPDxNbTmN3TAbqIIdSIFaAk?ZF+3`?|F?K@gryal;e&Cz=*+VHBSHg*}6~W z(LPywPk>7AWh%(DF%Sn7L?jd=XmS#7?FhIT%ie0zV%J&Fh3lL*o}rhJ zD8LCkJfRCjcq$=R04F@{A!@R*YIJaa?uiT<%2zwW=MnI76XWKcylXyUPZqwIreVes z4HO*q15QIgB!Y$%q(JCN0Cmk#5UYVxBgbg!AsYBeJ~Ag#m~lY3k72ck2%WAvkX0Ea zOonC9Az=dSdyb|w17^bCmJBhpIAkkw(;jx_lJqwCm&8gDRp{zQA!b;zmI`u5z;HSXWl8T2X_9eil68?sE}mH_Q+!zl{P|W+ zv{%xqb$4TA8T?kX$tl;+&fb~gwd26qSi`gCLdq#+h6}CYmXSf&HH1((D425=w;0Ee z1sjV*HvuWbt#Ch$5Mv1BaE{1Si< zh|?h>2F#TkgK03w$dlik;`I@kB=HETa({?0P^lB6gqR<5pn zY$QQu83a0(6zb{LS`&t!m@Qg}<0elHtqN=(M2g#TjF4hMvQ#LTpSWw~U=BwU&xfn> zZa7D3xS=3-Aq>c{S6veJeTvOktGvp=rtrh5xtO8=ll=>LS1;IpTVvlQ@vJS!L_$7- z(Wbe!Yc~> zT76z0KW0_T-Yze*bq4?#T#R7G)D>}TP@K! zZV2D#GG`ca>-p)@BUAwp^*JA9FU*BNLR|88?S<9a z2H0J2>*|P*!fTax9F%JhVIy># z5YMjr;Ce?J_e{eT%oHnjN`>^ zl@{w}fo6D$~D(gUnf5fbIx(pu{%1il|E>S(rRWx_SK%{uWO{utm@&K!a`_#g;&^?BOCUzv6+YS)Yhb@%p>pZ*5TZ(!Zzv zW_1=v0LAtMc~A@gNi%^3eg}YqeB?4x^uAid$3HP!(Na&M{iad&>?pGlXMhF(crpr3 zMwMfb*Z0fWH9|flirCv!URRru`xz>D zS?rS-6ION3+BpEbPf;{P>lcUUNZL&*g@=lcH7kyWS{IyEF;-spbhVna%6)hr%mQ=> zTBZ`lmwN#h9&nt8q9lWJ#a+=rh2z_Us%0?h0xHo8=KBVIu>=!Cwm3(FSrH;`aqimC zU_NYUmjKR=>5N-6}jb($! zBW_|jjHwRJbjt1UhnvwrarvH4sSWzCx{;k1cF&IBTK0(JXxa@AH>b(^mlZUldlWN9 zL^~gfl3%0l!a6D7XCVafWrOj*71OvCA(s0?itEK5nIu-$S5H)o`yP0^5_MKOD3(pe zw2TZt3cSZU#+GaEhIbD)9Z`H28rwukSNJpEr1ZP&6BpbzD^CfWT(DDm6|v{7#IeRk z8SeT!-Re-+wCt!NTer0L&+EIgjQrvz)UYD^GzSvPh$(=t`kf!gAN*4ZSeIdCPZ#);eO#J#156H-k|pp2>T% znIE&3T^LjxAr7SSmcDGkM48~Nrj%6rC(WBzwUuZNtR5T}hPvBL+BdIqbK=i5b%p{e z)8{2#T>Vyim4ai>3~zVuy4Rqt)Bu+upj|{y#^k>e_!tIGP^#0-g@_2Wd z7!@0(X4zBsJy+r%=~Q?bTQ1%S4cs7oh_@y>$D>o})6Z+*c>+p?58uVVAx%3DtUa~Z z_)TQ2wlJLhPPgUtCv}jGApxAjhOVxy0;CzWtfY)JZR8qac?#L~083dBRrSnm|KfU` zz1qQr%tF;#_I%ENf{MO@ejFrwTMvAC1>PhqX7bQ_zlutPo#tm7f}-Kj=iOhIZvEO| z!HXVf_2G4N6v zD}=V2h8HAR^v>x4I4lNhif_gTUu+W(3dYM~&_PyU4@j=-tFJv*bF+SEpq9%W9O)nJ z9~d9Gb3;#YcJk(&8`sTE3g;l@mgIKtz9N4K%H)%AnJX*rmp;|Ve*wOxKib&%?)H82 z$FHRH^rU0_p`sg?FHlY;Z7l`V98qW2an?>F8xWyxy~7UaQxiD$gyA+!s$y#US22RJ9Ny1KNHai8^R^Oa+WrHq0$D z2->EhnISZ=6mdZI8-a2lFXx&WPTi0OAdA(-fGL=&+i-zsvg1ZbcIz2IG8eE0SnK`WY*67beeqUmb6xIYQ=Voc<=A&C1F0zi#`mRnN^S`{p^PSzcopQc6E&W3bla zW?$^{j2G_0B(g0|!qwY?+W5LD2WxJ?5EfHszz*$v zjCR?4FE*Z?Qdf5~ehJ_2q9}Fr?? z8aiDPe%Y8{b;@yrEMlvBs({`&x+tUm$ zq)}n7g7EQnd&I54t@c);4#W+;c?83Y@tkm~V|1oJ1b{OKyJlce6u7{yR%DG|tflSU z0PUpXICDJ?=e{m_2CTu7@4`7^;hPB-cwm@p_f9Iep?~?Yjjd*%PdZhrq58N{iSrwi!U1oJiu*mL3kAEjhAzS9wCtZ7x{S#q36oghlty(rCY&tGj4l6Sefx7pn# zrd%YzVTz*FQDy}cvR1Rd$OIz~TS9Rljpcxv45sR#_E5ZbS!5Qm;MFcCgCB0J9chWz z15EB6q1J^;rEi#!J?xeHg$+-Gw z^N-EBC9y(bosjI-uN$^oczUXP3q@hON2HwaMm5t9B*`^}*Oi+#7NMqHVA9B52pAipJ@zewZ)p2G`B zNgzAVz&+Q*ZCN;Y4bfNAq>Gfv&Kx9xqL?YM|I(;<^8-y18A}DNTp;sc2*hDGf{ymt zr_#u5qzqZe6-^vGw{k_`A4(kcy%j25GJIYCExKsW`ts69d)p<~(qi9x=afl?jPdSo z(RS-%m9O5Lom%uLO=346{9Mpy|5mgt&LhB9pK%~(p;A6q{-b(A~`v+U~w;6Zj|L)vRj#4dI_P)4jSq5^9#yVyvB_z@s^CVcH*{{jNyS0~c!wawN zoQ;%N`<-*@*LPTbIZV)N2T*~IiCkDk z?2CnypQcz6W}ccL1EGM0za3+N6&c^(I7f;<{9#$ytWY?q=|g?&;H}H1i};oUx{3-E z@RmJ8B$=3vRiMB>?ZOhI*p)BRtVE`cy9Cas=xN1>n2!8&Q}*IkA6{+U*`^bTId|7% zZtMsa`yLEd`p#nP`pI9D9G7O=ez0q zB+NZUl)*Sil%c0d$vwlD1E}?J3}Y?KcH5n?1KB=vlY*E}k!RL@*F+G1Ax7i@BG;=_~u2gbD%oDO*$t*f7Qs^UykVRhtoJ_)Cr95D7}ggYGH z=HPcnYHZLojHQpmJvELS`?MJY)#E_Hy6DDcqMw7~k4s((3YfP%itC?m=g=`#FcX*1aKbN@0HMtq^6_-@YrvG39MJP8t6)8)TDF;^Zvj{var{ie+}W1*?l@1j!)KUx9E3Go;RX&cZ{1S`n&JX_2i}X5PQJn-CGtvtSlnSVEA`!s+rt%+3h94;P zL&a;$@FbeQFRu}^v7{UX6gCzZH?vj$cApgJczUl%vVhdmJ1e2=;Fa$9>&_;Ywz%E` ztzW3Dbtj*j?TJ!LsK4*joqi^YHEJFgXNbo$gxh^Z`tg}(w>6Nz9Peo#H`+{?wm9sa zFRDiu1*oVq-lu}cGBs{QHhNp#vM@EFh@FxwRhbf33WHv7ja^{E|9&K0HX(5&Bu!c1 zQ}CFJ;Lj-sa-s_Ev*ChUO&4PcG&DD0Gb?$*Io+JA+X)GDO|g> z#j=zus9frt1OPyPeF~m;?}R^!ePRfitdW7dGrzooMc|$TC=52www36Wz{a$ZjFj{C zUzU+H)j$cQU}|eHZB%9CCSoU}P_8m04A_?X`$z)o17%N59!j$umqMR_hoK7zS_ zlx59#hZR5n749iki*R!ymYiPwgxA)uOJ(!?k#2_q{zL8-e1!-F~Fp&!V_TmZU6ChxtU2%(<(mASfs?w@6MNuqw zCvvUgmn4-b*z3?yL~i5t{OvQs8x@z=D%tBw!q@f-?>7`DAq`lxjd=HPZB&@Q@|u}_ z)Q8h**`CR%_UQw_kU34P60SFul|2xD`jYqFE$`Rw)z(qPA7sRRR+!;=!cxCX4;j0X z%e|+k&ecwzJ0`){STkQ_2y_|WaLJ3H_Qe?vc$)*39??Dq6Lw=IR6VNc<1uR%u%_Ml zwIs3qsK}gh*F00)u>(ntOn=F4i7UbN$yginahKy~ad zSf$$%-A||zO@=Bc!TXOWqI}YE@Pc=9l7IY-O;)PDbsL%Q$JnZ$-0<|0n#@o{oL0gxiXdw&E}nBfE0i!3ua#nY#zdI%q~y9wR(i6}$t3kbqJQ<8ONMI_C8S;X zm$q_zyIbTL;`J*?02xQDR8qf$HB*+QCEt=DIq@Z}2v9W=Q0hMPV_6JC1K5wx1hE1< z>DzG5jGGJXM1Q&Uyc#=$1_NlYnK#jJBf+-?xKI%mYbRXGK!MdwU{wp6kN#Z(L#aR| zU$0Nh0GYN|Xv=01v+EAzBF2TpSOp3RJ6#*0AE62>s#r8zQn1YWBX%$dpx|G}22Z*U z1t`6Yhln&l^7YPN2h(Srs9RP_ItO){fehp3!bJZn4Y+a`4cJkO{^MzD?+W9mpY#h+ zZsAEvJqh*z!{93zzo|3(^#MWptN3C?N>K~>rqiPQsn~HbC5(-Vs zyc{kI;eq$UNjxVr&P9VPp<`S;GLQ@3)mBezlXDlf-PDxshNbD2o?PE9+Ko(l!Hzt9 zv986W*Ve0D107k^g#Ez0BG6mmTvu#i6tP#piAWta-{HdnKsCt4vvFuiL2*q1O)MKR zaZhF4I6CQ;vE-f=Vuz=r7Mg8#0YFCguG$de7;c8Z9--j$YItW{;2?nwRzIJp!GiZ@ z5P_WC3u8Ox)6O=@?@{AHk&Te>mbwwEpaL{m`03kL*O1xpA_m5`0+(3JjXOVW~$c#vOn%Y25Z_Hvm#IRC_T&v>EObNkWmb z-C$!&QdE9pK}AQm&4|O-HZ|oU2M_VqkLITari)zLwr5NHYcJWl(8eR-vskIFVd<0i zP%pgW3$gf5=28U092t3}ocrw4wK07{%mJn#Grd8cBmVogcz9da0G1@b41cc)2bI*pH4 zj%S3xZaxMklggjC5_bbIE80OUAc>@_%shjdabTUBYK=Tfj*B=;&wJ83`S9GN%reSa5@GW6nf*1oloMNF7Xvcp=;`o7yap5pyIQ^-rB>bwCO*4){?^Txn(4&w z(NJ=7F>N}=P+7+qqYz=M?ht~Ql!~a`#%vpc1o@#nPu|Tg3F!gKi=UOmfJH^Uo{F(1q5kr--Xu-L&gTq-D9?E z^Cx8h9R@;PalC!5to>(-e^<`Q;iIjOQKr}CyO>}MdxAhl3AmMJDsUD%8OWQczKejf zU!h2tyUo(b!pZ8$%XhpMrkVh20z#7kfp+}fNAeTQiWtG|giwGX`4N!?)1gbQ&QxHC zD7~rR^PhGO2c#nbm~`Z}()p83c>8H}GO(8n{1^Z#KVk$MvX`J?-^tJ&m9}PK7;`n{ zKPpwt0>ioSj94qhwX7g3*7GJqNwIU$;&73#N$XUxx@&r!%g4n7M@t0_E=g;?!L1KY zK7KRsZ-mlw|HIUqjB)XUTlalt?znXNomUJ0+CF0c?GD4Sv~;=k@Y^JTAS`+P_Hn&r zA*iZORoP!uQj9g`;x0Y8V104K{sAb3;fs-ZP)8mjy)*f#hkh!td?2A=c5F98R7U0} ztceFz2ySw?uU2;;KjT3YdcDzLe`;^8y z9z1$|%vm_|Z9B!#s(ocx;(w7k1rKhWa6OmXd+GACYzM#Mmy14eZ*m=;7g#+gb$z}! zr8h5EXzPSx+U<7-Qx#J=r^^dtWf^5X$9L^iyul{`cp6HY^9kfzM}9NBjDqjwBTt2( zD(}1bu;lo7Pxi3D0!xXZdtCbVVaS$fVT_8UttRLr4FD9K`ta=9V=B$=im?1cb@`NC z3y;&bKNiRXK0H8^CY!PZVd$c6;I21mV?VPteK>v6oD-^??2B0tFAlSl^tsUodX(w* z=hbJ$xW^(Iv=z_b$01NK2OTQdhy!2@S0G{wg||(>S&yy&nY1!6f%62BjA`K_SIzG3 zDQ)x=;ypK`d4&AViCz3+9=2NTfZ2B^U*GEWZ@1Q-`fy z-1+x=HfixpZ`IJZeaoW3;)!AR|2p)D0r%O(tj|GO(0QLy{1GT+s z{TVTu8T|w`!d^mLOibwR-Ny;>$LVw$H53s@py8h^;zK86;s&1#WxP_0d)?f;{OYm;%lO7l$dPQsnnDolU@qex4$rhXxY z$IqA3;VEA0 z-Fcye*Y32V{PxKz2gyo$C7@-4_vbAW~E0>-)C;7^~YD%i-~VW#17=#k|9svHOvnlB9lj$PFJzWX_@eN zCQ~B#oYBGWQTNWtnbLB))w4oydlkt~+f~L+x9_rY|K!}t7uOOp3cT0!XmZHfI)lL| z+VMpQax{$D5IkQAv%}+Nc;eZ6Id}_!qb0LC;;6iIVr41+LkqNQp*BU!60w+SD%6sG z&)*j+t*A1($7vyD4Dxhlj|%%tad?o(EX!F*r-kK&-;w%=>m*SEpLb(bGLGB4MHL1+9>e+1K~G(L!EV`jXFwzl3f3#^+XoL4gr~d~9;Wy94Ch z#3w=V_@mkZxm&I6hoT-;)&;h{nRp*u{^~$&^y$m|bJ6V%6Sb}Eye(-$NuiuB;MVn6 z&BjeynZHZ~W=YOK z)`497j1DQ+)N2jffD7CTRs2Q>N=jN&Wd!m45PcZ8xy8?hjlwFh z`57i8C|`|0EGCVqqmkLi73@OHmG!S9h7SZ_hTI zFe>Vz@NM7S?Ru`Ay3;2D_tww%M0K?y>PDIGHv07?F3f8}*2_5K3sRLCqV<8XuUo3rIo}>Wh}stFgJmh5(+8~D~O{v~uc1Y^wpdWbZvP(uXajJeU#C&Z}9 zI}+xMQ7&9OzrgmoaB>b>T6bn-YTH|-N4-7u93{I*X2|V)5nLyN#$_t12{3(BEpM}J2F!tiPfLlzBRu@wR@}Hk~dH=IbRZdh} zwfo@vjfur*XuB@UTKe3$FAf!^M)b;T1Q1;^;LlMZfEBTHcV2R0^->;wPPFw z%qxC5hTXCOgo?I=x9PYERrd|@AoMRF$BM;8C=fwJS0mQ;1O;Odo*&8+r0(e4;!N%g zz@{OsNdMC(aJC!qAPy;Ey+{&UfDAcI+wnE(PHi)oSqo9DXN>|(Q-onhV;JvcnEF)1 z9)D*(n#7ph)5FeAPRNS*+GPuzkQP#+e?^I~X?QvVLUD=Ef}7m4oOQ8^DIq9|DCaA~ zIxp=`29f;}Zmezwu0REcFIX0hWoI`jertA^o%bn4R+Op>Q5{acc-1xKHH60`p0aLk z3f;Ov8a#{$xm6hiSn8R~EbKUYydr8@dvctUXLxyC;mF^`iJJf7eQV1kkE$j~`QbmB zWGlP`3M{N8sjRH2qg7%R#O!}?2FP)i-GK{X;KJL$J^qZo6ICd~+2KRiSWJj0qh!BL zR23Oq1M#+uELj(UYWfR>`6A9B&Nd-qsLI?$o=xDbeKPmefovADn3Pyd>yrW9KJ7=u z<~7$LHZ&(EJWJ!NzT0fq3=gOSIT^qBaB%wFo|vC!bXyX{Rnbg{x&}#((frfSQ@m(& zTk~!mC^1x}CXK`-W`4$oIJ2BuCd5n_AvjD804~yi@-BQ!Jf_a+aKS6}E7b*GB~QEh zh4xVvr*C8Zj<{v?{!iZuvvco{4@%gx@^xm&wxmzb^6PCz0HHeKp}PI=Yu=-gb<7Ry+&fl8L_0ALl5oWPA5isVm2 zijec#c~cA*Z%cdOq42m`8{p!rqJa-8{6KmK#YuC`-H^o19rbj{QL+j;ORWHDXgldH zxA~ugW9)u2A+h8CUa8zC!1aGSLu9(W>;f6d=?|6qlU{v(-j!aYd%jiaFMsa3=5gm< z_vR)KzWJc%7=HqPXk*z5_XHfR!dA7-%m^J0T)zA5NP=O*{{@IV|X`QWarKkMGSM`%q= z3)%hY;}y=$84Gz{I6iY++>lrr>O-y1h>}Ir^;7WWg2?N8hIqEbG^_)8x^^}eGz%Z) zr7^&>GyuX8hh@Y}K%~svpr2*old-;6Ba=s-6g)9aKNH1}#wiKXOx&n|A6{|WDK8!< zDZI_y`gF8;?t6L1Wu|ZLrJ4QmMdHFYwpW*ivJ&e4ypa8QcS-5^og}e0OV~lLwRt;$Jgo8N(!nDU%ENYAf^x00UXM4l zLy>rMjjWvN7)zctvgqhde&(F ze?M~4q1gLoAr0^1u2IrT4Yy^Jyi?CbI&@0s-3pPqk`i~gAkLvT#Erk71q;nIJk}KA zXw~XH*l5+_6)*^%zkFRW~+@8bUXpK+DtGNp4eiqx{9b*~I&NXoU?(EhZ` z@2nzD?7(<1g%4QJD-NkhodET4E_$<%V^n^YK?g#c zHyzG2m!0g+DH{z=Ela)9#M=EPr({$rej`miH7@}!n@ROHt##7O(`(E=w&56Bv269o zRx!bw)+R2uS*s)vAvXDbhHN;<3CTS{7exb6oPvdTQQK~GArDcHj%biAtuH`(3YC)R znMJKxo1*ZO2mnpq0j>(2Wk3q$@Q2<+0U5%0Bm89;8B8s?zUYGGArd%+&u^UiGLQ0O zoXYrJly2#vMpxD3?Gk`@a6|QI0`Lq4DRfw>ONj3~K&aS zVefpYI%p6OvY;Ho(ut{?rDipt3#(unqbB_yxn8%Q*7Xl$8__`|1DcKx zE{Aewl2h-><~|jQi}Q|^I6{-LJU?qGpK6S@j{vLEF0HsUd`On6uqw|Dzr@LJ_~7W> zavD9aSgyq4Tt?}0*VR# zHgvewmW`mfK7)nXMKAWf;{HckfOW8OhF4o;+B4NMUnfE>~KD|5mY@;cNAZQGsObYQVu9qQYzKc6t)`-AoMaeZTG zL!DPyLD_Z5i>X^l=a0poAI@Ua7nG?TFQ>hcNUH6{r)ZeT>>u1bR10X+9p(d6WCIb!Kq}$2U)>SwqSdQPXm=;9hyp= zxGXXQNi%9!TU0UTXe*lHN($1Jh~Bc@>qk32!rexi60kxY&>uMLx17p9Pmk^btbmhd z)~d|6RO4%GjOnV}g}v7FWHI_J@fN_E9R&~&BpM7H^m%dvAhD>Dh=`ui-HP%s54o;w zBH^u3B;T`AWDptYYj&On#T^x+(Zo@q+3Smk9t>Wys=MZNy6r~aiEEea@3=rFobK-@ z%>HOxx@XpY@^~sHPc})9cF?c4b_Ip?*WDMTedzxfIt#z1-aZVU?Tj(TfQ=qGy1UcS zjUy#xbgH9M9i75PgTZJJRFDu5bu=O#D z(I(4uYw$#Hn$nA=lmp$uRLppP-tu9^i$kX4@$zzm`r3_K)vCwf6LoJsyl6?d9~=h@ zBcD7KfhG*l8t-UBtYmf(MVDjph^7|KV*iU~UCLq#m0^{^c_zb$VG^PzflOUG+F%rv zAxW@w08%G4I1^LpE`CljklzJptO6y!m=eh#9~%60#z!8F)emr&H)~~dpDyzNZT5l3 z{4Bjp6e1mf?>|IJ`TkAq{cdq>-n4aGua1A@0{O5buQrkoTwo}EUI6^el#-mrc7E+9^&2&|FKVU0uP4t zuV~~tXXo8F6)1muuS|@!Sr@#=4K23}cVA(7ZFfwYoykLz9QqZ9^6*ej|G^6HiH+Z_ z#-k>GsPT66KvsHZQYm3a9wOC+_aw3Y{>d5>3IyPRwXRct^>I$5DO8g~B77LkV8W4^ zr1t@ReDleAnE?UHL4Mpxg8rm3{Q$1W;VX)LKyz`p3I)c7V;=hs2F3e8Zf3lkZq7

ge+5Y5b$3!Y9$6&VJmkPbOvU z_Sw=cAMtJW=44pp)~0CA5+B>I_Ku7->7=?xQqKgnC6&#UzM8|L^vXZYRbP=8SG2P0 zg1j+&+IF)&ejeMgE^zapW1yg{=kPekZNjqsoI-ti>JLi+6F^U`b3F&rhQs$JQVeYI zfwuc~H9M8EnSt~7cFN{J z$ltElr~F# z?!GX%`e?@Y1x4qP2i3{Aqg6az5gHYVz%eWK^%~rur;g8h49s$*om-ftJb&5uGHT7{ z^N2v&8jEbr4dv;8$Q$NlqGk{GVL9}ekaWWd2C3#eE`I!KOsnrMwpk@A{MN19Rp zo+vLo`f>kL%Jr+s`cJwWcP53d8Y^g8-L~ji_v^78!#~y4&8A4@$X&TYO)2{vskY|$ zFmHW$&Q_#f%>KAtyeOcKZC%{vX4q~Aaa{gG`%}c@FK>RV_nHLMLFz)Bo?YC4$U)nB z%)%%6Ld92EekYS6gJlf-{VY9&U&Kf`c9)C1h_)6t!c4%?dCCvRsK6Wt?hA_+LG8^g zWJhEy>WxUPqnZcFLEc)OH4B+EJf!ax+Hyl&D;6q4n#sQQ*no1H+XK3g1Vflq^KxI| zR0V$nz^V+)27sTKv2GC3$V~m0MCENYFy^$$rXb)*(>g5;GcRS9iD7R4n26RgI|qF` ze2vG`*^fTRd-iOs8Rw&y?t%5a>5ZSy>$*JKqo+v9d3mf~ zxlUd3Jf0(Nd^x(k)pFp1OY%7DYbP)4TQ zii5*S&CrIUR9!z?AA;uu^C31G2u?uN)He(*fQBW?va8+XREL;=O_qbRs+*pac~}7mL=v%#WZPRteEztP+&uu0-vRZXM?aRo?`eNN-kER# z0&YBtgT7s$MZbd@2%@*;y41QvCgSk!VK1kh0&{tUO>;h4mu^j$;ZEJ;t|{HNrK$$b zT&uY&HC+k*{q^{Kq_Hq+a_*h;v59#E~2CrjDg4tO;aZzFui z<5A8lBwmt2F^c^xsm%y^QlpkR%7c6g9hcJD%qUkVy}hx{ zA<729sQYFX2p)Om>0NRd4+Yq|&7O5;U*usbl9wM*ecO^Pu8sYV83i(41mqznbk#lG z)XX_`73j~IS$R#fkrr6BQI@aoBvxk$1ZDi8$!Z--Db6$-#VAPHpFfTk%g@7>j_3yDv03n9s2zEdO&_6%W-0hmwBl&mc73ws6th@4L0{{~7<=RaP8DRsBC-Jd zA?m24@FQx1dRCCft+Xr|vyE|5eX#x9$75y-V;}WtYx^|u_d>M|A*R>WHLL~8?i^*? zyyWUOvbKCJaA9z{Iu+AX=~!^Re7jEZT+M=~A_nPVc`>@C+0UdXY|JS~nb*TQH-6s( zko~J_kA}GNjt1KzGGF^QWoWOPXay0U<+XeV$8WBzW**OUwgV769~=L?pBNuwl2>h8 zC<9?4@ofRm{X*`YP;68Y#q{!ulsAI&6#C7RO!1dAVez-0NHZyvfyDe|-D;9;nrB>t z8PCAc4^}m{G@VQc1gA<&PgbOiN3#E(w zjPKQ|lVE!0vQz%#($-?$;j*l`wg=&jeM~Uy_^GNIZ1V(90%wpptJ)d(``5%q_e{)h zyez)0@rG-|KVRq@w*9EPv=+*@Pa2oI&f`+7G2%l5QL0<@7QBz)VLT@Tp2Je7@6x zB0qqr=aEM>I>rH0ext2=5};4Wv?cSjk|$YBJN?0(M{QHk-wZG}4rQZ}IW0F=+u%6|Eg3HJ+jNOwhI`dtq>*)!fI zP36C+B#NwpfWLRMERz5+US54$!4j?72$e!*D%o|p6`zlzRM$wKx?y5&Wcv;4s#zTS ziv`aU2NY`7o`yX|;86j%4C1&cb0k?<|Vf1aW4VcBjOoyCGYNimC%s8P?@8&+CJT%DX0>aqfiK)ui>TF3@KXcy`}VD{@mECk z8_`pFlWP*^ZqJl%vr6j1C$K~DEkpn}!iUGJB`R@JGYwve3%VorU9BkwvgsaF@-S@IjLGO^9qsIV zra-UbrR27Zp!RyQ%vvt}ib?^yjet=pU zQi*POc{ZkuU%WiW=8rOA{AwB1CRrCFy3-5ME6Ws^l7 z+q9W-{%BrH{84ZbLdxJrc3d$ejCI4SJq*U9<_y#Ph5ypu0vWWst~TSi#=&zwRh8t& ztsl;2J{~q3MxqBNwfzLW!w;|f-^JYIRaWlK?z<6wN}^A;_u9FYSTUa0Kc1kj{SOEK zcW{O|V_zQ7#f^zfI)MxRr%#rt0V}t-qo)~l+-7}RFXpSzXXnZAVFvplW`rT%c+0#1 zPlce95JI>ht6ww@wCIRrU4(%~@pBU!2PjJpAI%R&=Kc~>rH{@*L@^Znz9$`z_-nA{ z>J9i)IPt)T5V5QptIfMIbO`(T`RPG%ai-M&nIa$VGo5M;*@+D6IT@gvHT6DAv`1tJa|1@yw;+V(C&|hz6PqM9vI4@N)dnDaXri$6Fl`U`| z+O8fU`TQb>GY0|>?N~VfK^xs!pRx?ZYmJJ3+Xql4P$Tuzpg(v=?DRx%!ZIzw&QwaI zB0|l>bZy&IlqWJJk#o}`$#6B(_*Z7u6#o)0pLvq+@2#^+6FTJjHlL8mfxN|Cpf5DF*GlbV79kdZ45HyD z`rTTCTR{+(HP>1{!R?v_Xsnv&!2odp=!CZWHv)p0SarrR_KvzRQWfBTtMUi}WNNY| zGu)%d`7G7UpYH)o8SwqZ3un>r??kVfW|aO51-2OXye_vdi(ukOev-z91E6;{gX`J^ zaVge35OwZ&;f@BzV6x*Wph;W|Aqj*+4oY4CL%^M2fE^{;9}-^CTe;*Tkir%Z`| znoKo!Wj5T3lXDX_O$c{#H1Vs&pMMqadzfkICYQ(%a1gD?L(@gKtf#y>ftrz*%6OK^ zJR4aEcUiFRopq)4`8{{X5?)M4hF%3T5aK~~*ycFDo5QLaaT5Zn;DJHalcg|FmJU9t zvaaqXdE}9dCP6)3pTVR&FQ7ml4_1vB6b2sapOl=xdhA}-Z^5h2;5;5+n>Wy;**`&p zb)3-QSW@BE<)SU1AQNlea*X<^lYnWs{z%+f4gihw)wn%T041)j8agMAtMgD>Bg0MS z!P6`dWJ7G;)@4I!DC9RVOHWG#AVwqy9J(?Q4NX)9S?QN#n4xB8JOuNB@(T9LHtdhk zIEfhOG{57=$@6Rc9IW%e4|7RkE1*sS#qgkHnA1;PlN#P*a&$+f5SYt&cy)nuK` z7E5YaWDRzidFjAkFR=N?9WQ^55jlvXSJ$Pg))iuez|5T!lOub|uS$*(8q2#Yo9v!a zyxL-(I0m@?lpUQH48Msh7&FetVXN}c+d*oqEdeUQIVF@HU;O-_Bp5{_-B|kRPV6M+W)wJSYUZ98)|+VTFC2*2x9p%{Uw3C~XB?*=b^-0=oc!)#-o2Ew z3e^6Fdi7Q^ZT%XXKB&V$>oWj$5~!VH#7ZoSVt@tf%sROCI#Vz)gk)4{tr%`glYwZj z&>y}LRPX9L`YF-pRq_3ar#McO{=JmB)>>unGRht~&(i6r%KUr{;5V-jT)W0GgVtt& zrdM|6^xN?!iO;7%D~R8xKuShAo_erV z4xTREi*Rlj`Yzk;yFQ^huBo63`>PKNx<*~X3AhnKE8+|`+J)&@9sH!?&C}47?eKXx|a+QOHEN+KhMBJDV_X8 zuWMgCQR8$y8dY4C2sm%s&4mLv9JAHQgp(jx?+ohh(~KEVD?zc!Xy%KgT>1q4RSn`* zxNU5_e*b%G8!3nhqjX4KWR8ZzrO}(l>CB1ldEEEvP7Yw8a}a(4R$h}$}GKCsh4i}wVpd zfi{Lfu>JkNHy7d=TpT~@OhAHA%b@W1?UqsT37&^{y3ZRzIkb+{%O*4ab^&4JD?{JqbVdQr zUe(19762O7VsL`W%XECMamK6rU24)1&souQo#TRxfARv;*C(}Hm@)jEQvZsBwzM() zf}|l=EjqB_aC+m_aTi2YJH(}1M>g`d_kTGkv%kNVj+YiKkS8ERVDnZ$6%5cJj;FAU z$KK>_qdhK)ewbLrFTWy-eyh9aouL#3V7u&)XCH~?f=zg26v@*P)n~g8+7ic6khJ&@ z@QWnqf{!X&lmUI%Ej&(NE5SXqBCseGJI_^VX&X0C=#_IEJbq|x+RaFQddd0fzObK!Fe9zO0m+{brA^AJR8IZ+G(6TnIfj zjhlKe+V}p*qShy^8=@^sSo#2Ty$Twh3YyI^+kaIgf>xQE5@A5hPESs=@y6bj&NVS^ ziqZ0^2mI=R1nORI$3kK8%Yc%XY>}W}w-whyfER}vw6a8LS*B~!)V}H6)-6se*twhk zTaxZi4$VX0Z@KC15SqXy%1=mUFlOCgq`R$ zLjn_NurbsPR%+o_D2S!l`KvO=;zMji!f-h63xA^ZCQ&iI*)CTD)2;`;6%)}Xfl0|w z)kS7$hR~XQ?qta*?8FNgrt0p$ojHj>r$4&6*;`Qdi10@)k&v#s&&1z*yopW$-!a&w zRMv$T6U0>3pURJKKRO6zhgyDYh%LvLma$8co-Gp|UKWEq9ROa#5C$g!+moCvBtQ2= zw^7eQYAckLD+pIqR8^M?U%zp^tgcEJtgCElX>O>y*>U|=!_BTv@FpIAwQK;NYX{hA zYio^0nwhaqKAw4kGDAIkri~a`e7=O3pPE5wX+3?Wg&JL19@%-fvpE0Z>FW>LIrs38 z2X+I4Ww}6EUk~l}?Y|EM5M9JJuQo>(R35Uv)A=8|^rlpOLl#!|ys$I9TLLK737a1n ziC#b^7oZ)==hK77tFC9fEFFX{*wl#f6}2yP2U%hHxOWE*-cBAfVL74J1Yne2B#5U@ z{;D_420>kt>SyLI^^{DrEGZ;0^vn)qtz`N$f$WHHxl|1SfJ;!aLEaD zg_AApt5wkmwDqjVfe?a%H6wAhOcff!hf}t1>e+bktD4^=#F*t5pxsr-h)vpQgcJ%* z0XA{w2muG1vu)ipbjE80H^8i%HgND}Y@5Oe`tJq6`57NAxz6 zT#D30P?*gu5dvaUonN}gQiIhzvzTp7vj?Rvc^r{>f~?ixHHxp&>R z4cCM-@NC$k?iJ6lYBvz7l6SBwbj=u^-g+($x#k~`w_pac4U;@YOyi>6Lu%u*#{}R@ z5kS~Lh-zjS{(1}4Rq{kBtt*B@hYH=70qXnzU|w4ahI^a#)swS;mQ z<^X7kBw>b(niTLY(B{&qV`iMZ`C>yO-h`cvSn@kvuSrpv2||YHq}|6@X_)Dal^6bJ z$dRNNy|-O;W4iar@TA#V#PX4;t!xoX*0LC29PKDl4%RcA~$c&$fK|*_R7%Ax4*F{Q_5#oDb{ZN$HDl~FG5txNF&0BcB^;7xxwPq!G9^_e3`Fvtv2%}qMfHoEYv?1%>PMVC5QED z08j}34th#&9C8KToh|s0v8q;JVp1U-Xd!DinNN#W3pcdoALF;2<<-=PU5(=TW9{!C zDNQ}X*jt-<^P52>>0&%rE@`JRE#62NOV4YS;yFS9Xhu_U(3KD)%nDlwC6B)^i0?YZ zstT9Ugmc}>S9dxs*^iK7%7Z1`aT;a1)TP@D!@=3n=^zPBh8UVAjw7K0{)r#}GlBR& zo)zGZKYplmU@BMqhy9Jv)QzUuLLHlFln05ac14X-6I;!?>r9vL@+fsL8F%9oS{r&! zrD@9k8o^#x?cCPI!6ExRY(ia1u(T0fk-rXKdnbh6P#COHVmH1{XOo$I=*7D?9b>yd zm_o>%RCCS8FT6O(a#?_bHh%+ztV;gUW_8g-O$1tmzFPKOf!Ii@FF6cVh3H-Jw_$x= zh1?wl!h=}sJSb3Xk~-QmN@xY`ulfy(s-cbvh$6%A_dIgVrX}qCM{8v0nT2MZglssJ zOV0v=7nGj!*K=L9DC{>Y`mafRI1K;xc8=C3M6`p3E|THlJX;y|hWD=+K{y9}!v97c zMvsay4-QDx-qQn^dNZ#gmC>23e{G;q>LX5!rcU2i>2TXHb58vl$Q^!1xi?1wDp5OA z-^9dKOg%*!cg9|b6^O**U%%oxjFrQ2JcEU@U8|i~AQr%-n62BJw`B z-v8#f3d1w^{W{Tvw=Gl88o}|&i(a?kM$h0TF!K!}ZfK{=#l3iPR`&Lr<9haqlCdBQjeUL`gAL9WE1CeUPnGs}P~nPpzhhw8#s zCZ%f$d)!IVrlg-1-Up>%Zf)@j^3DNQZF%zOvV0`GOF7;hJ{6? zN3cQZ7>=(w3VwrIw^VI9%x0E#Du= zP5Jlk)IQ-2@A0xZ^2OKrwAp8&U$Xrz_};u0#Z+Au-VQVSM&)F(rWY9RJx-a=HP+T@ z5dTMRml64EmV9l?#v|a{Y*DPiV0NjjbHj+sElydrb&On-IU8ZZqn7FKXQw<{7oCBr zWp=~c(cS?q;?R92@z^GKty7SQNzag#vEGbpOC(bFXSU$$O>NDtIr)oHI=cA`sNJ>n z>0ni!1|Qtb{Jc*Rt;?vdeA86k!6<~LDZBKBZPSA>47G=dO zLrbrl3#Q`4Z`vxLXOaNIS=eWZd%xbAH-DE=JzhrV48psPTZDHgGvBphQ{$q% zHw5Zs24VJZZ-4)DPJAUWqpyRjpxO508%c6W>h0!@4@c)4#C$Jrw(yl`O7t}x{EJm) ztK5{d8<^$0PzgCE%bP3V8#v6S=!;fQJdjr z;^{^*;R!(j8HF8xv`#J%Y%m)3YA;(dD&llea$+qS7U3BA*MaXW_Uju(@^SHZ#aSm$ z4HC1ys?mq%Q7f8UBmSUGhSVqj*p($t1qwG8T1bE8I5v-RPBa}7NCO;Uu&7><1s;op zd)_=1r+9)B3PYpV7B%anllvIVS@%pMnEe!%e3%xbxK^a*EfP&!a7;0$U_qk8JdT^+ z624Kh2AM35gEO@oIJ6N?e*sJlA#r!hhrcho*HV*pEa73LsN^8I$iWA44s8R&taV z;&fsygmzLa`hg`rWnXkOrw*U4d$bDr(qP(?AmM&Pw8TQM2sSR0TU?0a0pI|-H2h}EPoGO?27M*p%d3ji&YX3EUq&aiEUlh5JF_rD3 zUzUJuA+mKl*|lYynf4wcCZ7CXS<6yn5J{Iqi#az5E*@ONAxR2o%o+YD2sbO|f|Gi$ zrpl^WNo%IpD$65MeCTtoXZ_qFYF=L3&M)09$XvN^Agqdgp+z~li)Bhe{;tsywzl;K z7CbP-Nw_RmpgSHU_2{(l5 zqI8lcvseeXgwOQ%Ncz*p@iR}gGlAk!MS*!r^oLU(HW&BlB{ngb>!q_fuznA;Sw@o+ zfZhyxcI~x<+C6SFtj(!tEC1)q7QE5UkHZ`k013lyQal(~^sck-sPoB23bw^UyIq^j z!|;;q1sw|ar*~&A-vtthPiYn>i1&i1&h_4e1JB(3{+*a1j1NXVoh2(asUpvPN}mQhLZr8>z*RiCe0qH9vu|_ z$g6#49=WK8>)fl=Y4hn$M)<5}L)){4Yp(u)_%@O?`UYD_p;yy%FrzgZNXsNlc;@4y zto%^q>|-f@WdC;Fs6I2S87^2^{yCGB3s18kDmG~LkP7m?r5rEGmp`-aOgW}ijgRgqmqVj$JW+x!M)Z41d;1;QbnTA zEj=IsN%bEpp`M8(StZ{0JT+8vXOuVU{d5agde@(@*2MK@&Iy)B6-oYyXjA7X=o3+7 zCRNBr@>`dws#~d1y`IvxyRo``|AXt1T*Hh%B8 zj1LX1W^(Q2x)&eVWaLydDj9p;-OwYNS(hmEilMkRq$E9Y>jjrXF7AdAq-Iw7_InAz zJWiBEI|fOF0XSgHO4Bh!N zlqrw9(cv8-kc441Lw=8t{>7mid!I(>n#5+u4?&q&)ovV}ni~vn{nN@ZmN2F@B%JRP z{j*QV1VbS4ynfp^~ z9*NUHJ*Kb~V{4PjT|yI<6(Bzn(-l8sco94B=_+w{nsuLqI0?3Lk~rTuA-HhNI|arr zW2|>a)S?!|9ucMD3c)pugHB=c4+)BhV6E5tI}NEU-a}nS7T4WtuidJd&;zfsu-?ZS z+<&&+qB|Y|7oYSE3m=jm27vo_!mqVdPMj&s3RLV4EegLO?eqA@gTN}YI>Ar<;hP#a=W+Z08XsPb0JeIh#nC!_Q$oD&rLEPpkYo@?=--K9%?nh% zuyrf2QIe7DQnc8&zBWVb5PpFc)FQ(J_baT;tG~4CD7cNNRYu|OT|o$Sau!dS0E?8q}FU6;3Kq6)uy<&)%oNUJQ(v%20xAc;_q*a8;` z`T)6@=W+3|+Wo)5wO^}i$AY6&#IF59O~Dn0&kEi5A8Iv#P6mBUwDOobKKaG1JrhWc zCtaI(=bHE=KkD;z(#(%L$-_yf$%qH0GJL?f#4I3@a2x!o1oqOnUOB0dLDl2Nfr)nZYX5DI~Qq|!XH(H7P5kbmB3X=d{qntZ~g|7NC+ zUe0?Jb$?iR7Ws1R+PQ1+2grVS^EJWsp_aAZj0xnc$?5#HDQ{N7Zw?IGM#2Ve!am$W_duxj8AFdohhB4r);zEbK6zGpd>h_3ZKuX$NSXVSs+&V9@MFn% zt!8c>1U^JZa?-#rH$9Q_Oqw69Vn23&%2OThYfiSec(!&*+Zc&iKv#WQ_Y!KUyS_f^ z-F((#s`*v6Bk0HSV9oS1{6cAgFHto>O5x%| zn^$znzyHl0oL=$oA4t!ENlV1t)nR9VO-;~qLC1qCK^lJ$r|HXwZcgmyo3*x4GFDqp~1*>}k&Z#wcpM&(#=Cc0&^G*BfgV>Vl5SMC z*VZ@ti67NbU@~Gm0#SDx2>NXFa`jUsz{L)^QP`+xLgh41kY<|>u`#!`f=He7<|!CM z_%#C;_eG?aFXXx0Xrfq{U(0#7c>R6NZoz-=w-|=gc|e+}RH63`0H@Qv%p5i@zzFYe z!t~45mSuJ+@cSEHxMFz0;r3H?Mv|TKf3@7h6v@|4tX8T_(j?EKKW^C>vLp2(8Fm_8 z>RfJkMwm0g1`6d(O)?$(=xO|=M*D~M|Bj1&ZoK{X3&|Au`Sz8rt`Dp+$E>&S!{SeU z9!|)_UYUOD`5buGs=GR2_j#z}(~oK;C)%3#+aUBsIF zjVEbm+=wbMH|*JrK++V+x}$#@v`gb-UcKQ84G?h780q#%%_eIXGPM5Sz5D~DkvV6> zv=61+4y6r+rt`Fpz5n>AbKpXGy0^i>uLAMDDMf@d+biU3@jx7oENW>uQth(#$mNPM zd7+bI*@x9dmC29%!EgHomJCM`L%-5bR(zq|)KVP~&?PH{A2RvPbLRmF4!lBEmasyu za6ukeP+UT}az(g|QVv!W*IX^BJ}$4Ut0<*aS6{jWw%+XMymd(dumie#@Alp673{e` z+|%_C=o)>Ho%L{Ra)kb178n}pdG>ViZa*M=d#$q>%+Alro7gO*ZSNG^sIA{E%&9DW zxqIbJPG;_`sxIEG{ffKDYO)M1Tid)D|H@VhRoAmaT`^Ke9wQp-9sXiIS zNkbMHGx0_J>KrO#7DMJ*f{IRi%}<4Nu4pdWzmSVt_*5#S*#z&)kh`Kib48~!g-fLF zBJX;uY=69Jp20h*pf+iRmjWoXFs%DY8Zr$cdFd!#og#YwdoD#hti7+$p7)h%Cdjo% zpk~xm>?-9;FU$j!ua4jG-VjlC#QJ;b9sC{Ty(%cC@YGo{CR4Tpo7M83%&j2Rvr0tXRfp z97ANjWMCW#`dQ6qB?n-xJgPyscl34YhRdw)(+5_Kn@p8pQi^7Q)%E~ksdnRo~4DLC+Vwb33dos_- z2BY|SZB>ls^)Tx}#V@K9?4sEdiIJmhh#8zK8$9Y-)wERiK{oVQ_w#_;#dq8UIi0yx zO6@_h?1e|SbC>vBrA)Q{z$BMm&Zp`BnkT~${3J6`K2^;X>q}>}acmZg_%qgE%7<>h zlq0P}OPf~}RcBSKf0cOR`UT1CkhpRPi#pUzI-m2usd;0OWg?8F;((HS-M4(j;uwsX zhJuA*$@=7x13G-nXj0Y!rJ*SW|d-@EL0K% zxODQ$b}k3}oP~Ae402B|P}VEjt&$bNbltpE%2(z3)VpmUV?TtZR{B z>MYi$vZMxZ()9&!0P-(FU5-f=ZyObrmp9(qbY+ts%7$M2pXFlaab5S$iQ-7yIQvxw zI|?@%RD;!rfMchLb6L~&((;_kioyC{Bccj7Ht6ZS%ZBF+TQe9@JC?KYMKW9yZ78ZX zH>{Tg;vVP=Z*Z>Gjj}a?i?vmT76DDl>R;GNGcw2OU1a&bZFZtLAgF4?Q?Q-o`#&-h zVg2xK`ZlE4wMN(#AuSEs<0|Fv2D*G^x_>dcT#0W0gl6DofR{vTooG5+i2q>bCYgC< zbmV&uR7xIFbkU(<#&xUBXkDxsJ~@-82#YDZ_zgr@k<*2S@TaD#n^pdqzt}C(;2rW#-xzn! zUhvde_wcwnQ!oepK3PniL*Rfldo=%(EJx|W>&F&bmc6_M-m?XcCtT=EAwyOfffu?e zzWi80bqePF8z<`uHq5=>@bUs$cyZU5lEdkx#peAFcEG?GRFa&z#KeHgP_0MNP2@^} zyD2NN(ce*Mu6|%AMW`KO#fx5owexZz+DwjcTx9Mg?Tfgf8pYiz8p;V1_VbF%2{8k5 zaLIr2#`2dlBglKcKXf`b_7s*1jz$IbKc)Y6T1jo&VK}A^EzWXVZM>vvKCA`ZR}9Nf z;M5(2d8EkipL<8154?qX^x)!u=;u=BlS}h~)dghu?Z+y{~Xxo1{Dwu?HUT zh64z%L@z!)Wt{J-hqY^l_1Ul#1H&m|eZ4Go^ll zt9JMxv+WF|snN(}GKT~TeV1@-tRemFB&KTi5-aG}JIBob^`ZWi=QSar zsL+zpQxz|{rQ!xZCmu7Bi@eC1t)zC7=&wvSDsrSnk0i+Px@S0Wv46iII9|k~>lpw0 z{Vb!;aG<`npzqtkVQFdgt$XDEEmuz_>eltn{h7@8-&WV}2I2B3wT8hBh14I<9-X7! z6_*d*g6iT7*=S12(FF4b&%@9Qi&9b%(jg+tII+!B2FtqknkRi})gO>#D`r5ho8v{J zbTtg?#pD+)E@QF?yvc_2am)A;{MxG^qEji15r+?1ENO2<#^b^ztHQP8bf%{8oV{$r zI$3p>_w%AA~5Jw_x#V_7fUWGH(b_NQ^7*ilg*#WdVxs zU@El}`XN7pinq=xR>wcL)I`NXc>JxSBwZWx~EUp7v z5|)GMM1M`y`I$BTj`i-{aJDA@J5>(NXzcznQy|5{(Uc2@InzF`Fuz%TV}kuofN{0#d)EtYIF$`R{1lbd@`c-*-2X5dS}{^M2w8cWNqZA7`$?MT^q(oaS}H=+7rIH8>l^Ky1mN4oxX`8ufaL zGR)#l8pqUiQ%{;^mwJI#3|1sP2eZB>B4=Y^7~}sV8B6Lq*##$q4C@p5yq7 z2RiRcr7HV)*;+BCjefDFK5(3-?-{$WuCVpN>%kW8`ae@#2mPG~G%su2SQ}s=X_Z^xH$mVKeWG65cICZ@fokppoDdfsG{{Hj z=vxm);x6!}@bhbm{fEk7i1YuoNFQ2@+Ra}&VVlI@2@<19oJ1hG z5+fs@t4r)OW`K#R6i&5H(g?^7xbOik&K)q-c%?D@&WC}}_7rBRf|FzOR$pvA?TBKz zseuc?V5`qo24B$ZxbQz6tD_xV^EX`L5b4r%_%msK2;pq}RjH&fNoCLtLGsgF0snFf z%pNh3Ez9@&?i>}|`7=`)=}8p%aGlxGPeO>&hFUw7stLUhc}= zu?^Y|i>qhy0^A#0P!BloZrlqmr-e|d&4Ys2;Ye^TokqWk{0E$l(m;%c^iaRuihwq8 z^Cw-R#v6Xn|M`E4&cdz9w++MZl5Nyr)W|VHQbvcwMyHH!7~MKjK*Z4?Afr63k{Y9qPjf;%qXf(AT$p+x>0*g&WeF||%mB<%aZj{%csZ*;e-$a-_#>yn>o zhetaS(W4(~WZETic8#L?2B?YMZhwNzNMVIuF<26&?I!)l)ut7LiH#pL=M5Jd9Y;1r zBP#R0P$2MC@J`_KIw$^PI_v%s%tEq`6ontVst>Y6b47&+>;6iKPCP2E9{fv7tM03p z{7Rde2;;oiu*AnviD&MroViJgV|Q}`YZ`_jOem57HKPNZ@2jL(AQcK{5(^MwLY4W) zmB}1J6c9V@-`YsBXMqETp36$sSYn$RN<8ipS%9ugX^3xw_BCEp>_ zC8mr6M|PD=DPR2c)Xp`w5`lfa*-alZtA$h=2TN5-Pu`#byFP+p;5NZMtfW&$9G+uS z8-C5xE~hB#*PASvlqW#ixL{kgLE{|rZT4p5uu%+U$Q~p~1hvM1l*z?rEU>{7uoP>) zwfHd?dZE>D!Hfk6u%J@R$Lw(7{Rof+0V;r-Z}sKS{}>UfuX_#OKFP(rV1H|;(r%QX zsP2K1@o{=pJ6>nT@uv9^Ks3;84N{1Ztl;UY{6o1G;R`xCUIGwl`TN{D9G3Z;m zP&?K6W8L$TEU+0FD!>BUIlRzt02w*Fcy#A91OO(C9<>_In=zp}-HW?FJ35uqS#JZB zVk5=jx_9VDYM6lW>d{h5(3 zF|n?lr?ox8`{MKwuKe8vBzn6|{6!MwW-@G1(_tRTdaf_=;;#L?lfr3<%nCF<- zL9ohbFc5*OR8TI=e_eBH&lA>z7XR{uN17v;)j~1cP*1%dZGNM$_5DG#2x)=0N|@7f z?7@E@>ujW)DieKPhl6Da-LUhmuWYBqNR^todEq1^?}c0T=QR!=tG<7PSkt>*OFyCm z;!M>LS)>7$RG%cYoXERx6^76HRk1D?t6k53uJ%>V{_^tZg>2?-O}F7AttY^*Yx4qR zs4`)DnF)rOK*5d(Y6kcEClGQsQiyQ)97%!b{LTHB@hrn2YN_?6uvE4rujk!Q9(o+S zf7d`ajIs(;tPC>Eoy?HRdx0{MmZ_ECOD*&Td_(_mT`>flE+GPumbT=VHQDnX`~1h? z?!LX6OA}{ep6K1S>>LrIjMDLNmUzdR~O1Xg?mlfLQ_>jp%owz9Or3Hne%4m zRvy_qyT4ebmnU#MPq`3w2u@Bo99vL`h3B%@{#a#+ii+~en%cVhhQ=C5<)up(nwu}w zS4*@tL9Sj>?z(0tWFe6;FgP@P^VaPFGZjfm3jk?`1p1H}ka1;YfeB?HJF`WuJ1eWV zpK{p&<(FPbT&|n0*{Yf@uReVL`oi|R%kSP+HA24DUg_-mU0G68Dug4FgELEj-_@$w z_eEh~bZ&U*rIaiqv# zHEB;vj<}%uky>p}YODj+aKn9_F7zDq3jGRY$F5Kwz2K|g8)bJ@xn|eUw%4u{7VP*4 z{k~@tKuTm0C^FmUGu0wA2$Mt2`1uMQ9q^8>;zAov8QyX3)}}N%DLWHd7PE&3OxeDK z^l@x?kPAb%3dOB7|8A~`v&Fc(Fd%C2Hbm)JCUPCAJ{5g;(EhoIB^ zgv$w~p8WPO%7PZ|&Ro}Iv%#mH^9k6FtILi$1=};(biON* zVx@=7`GrMS>5H;WHk7|fi{#)k0!i2pCWx`sp!5ma2+Fk+Au(FJuzWYVDm)(?PHm;}2*8<3>~-%DOBll%uXeKTFIbS^F0SH7>-)WH z@)QA$29+p|EZi@~+EYFW2T*|6zN4!%n+3Ah`kFl?`0vkwxkJ`Jr|6ppfw(3ek(ca)}nYP(oL3rS`HPc&YgdiB_}W~#8g zD(tPqu`<*8NP~*=9;J%1S0A=Vo@~EuTYEv(xg1Kh!FA;3_#uhhMp|siou9y=^Sx(% z1IoIY*n&*PFi{nO2jghF6uTfzDAZB$rz@XjaAD{PJ68PTPlK{)#}-{(xwZHK*;bm~ zYg9qiDQ^T6E0Swjb%NhgnC?m^Ml42~ae!24d2|tIGM}xjk_{dp7Q9fGJIB2wF(&D_ z34-%l8BT~i41S#cCCpOo&LU$#zBfX4a3}6jPG&Po(G1f~pW$5P|JS_ic)e%AwnoO$ zu-f$f@j0oJQHe21Z~Hv&2o5g8M1xoC{==J=f4TF9_BCzN?C3mAa)lP8R!ftHYLxd= z$K4ZT$lR=%?7qrt0fe6@8zQc$T1DCm*!9ig(Pbce9$Ox@FWaq5&LB4|$f?R*-1Aj36lC%WyIrD0T6M0-pvphAuW{W%moY{?au|RQga-~4UUFjStEaYXfss8mm{p)A{Le{@l3zzGkCzaCD zxs#{++CQDKZI$E`G8jp4P=2U5@C-G)>IxkNVeSvEL?M|_J#BBGFsA+1)B@-hr+s$99Qlr2G`f&A&2 zqI#DV+JDo*)+sZ0`_5rKeipv|Uf(SCo*FMNT1F9rf-%ph&E!b{Pr40wE_FOh>L<Q&CsRAe5CT>WYS#8Z5oqE(Au7p&7H~~wQGOQ9 zv>aVXO@#;#kI8kRNsoQ-Tq*|LbL;RrC{&ZqIv+)UEHm)9hyHi6D=`AEzxAcpB&s0~ z%{nHZ`yI^5n&cnHS3iquBl9tliZ)XUJ7gv-ol)|E`ESS9t?C}l9>gu<HYq>j#Q#tNlXbmOS_L%cm z@)eV7<+gkYTQQgKRVmaq%8Mvjury@<2(X(qf;@qlD40R9%o z6Dk_S=ClHb+pdu6jE_I`QTkn$=4<@4=7CJ_nPbAopMFz3mG(%>QTkK+H~+6E71ing z5(j0wOTtkF+5XJ9!uuKnHisV1mZHjG!#n$dpW+dgYh3i%dRFy6sH8d(iwx#z0|m7%4qdWn$0R z4K?SkCG(ePy%$5(X7U&w2@Wc+<%^QY237CUZ9-xwe%D^gdOth|ER2ddd7lgzahj65 z{QJMA(a**PKh;eo-G*ZRE!?uQ6g>!3>3CafB`Xo&=Tx4*8=6t?_`uv`GQTgX?A0Ik zS<$(<-`i#bYMM&;%(9`R-fWs<`dUK4%D~%H3M}=$_yEF`4uC@aoX_W+UE&f#KoyzV zH)JaLd$3G-F)u(p`;fsm;{7U47mw5{x#p;4&Fs-G>_0C+Ebz@ekOj?THj7CI^mn=$ zPr1muEH80iN|CWc-A8bx?C%$QUbADvNoAP=(BRZkb@@(bFv5>&Bp*!4S|;rsOY~ouP5lp^ zaJb~x-B4YHta#nDS2GgT(n6R_m3w?@njK`)t`68qa5pH1P8a?y8~+KUKBA>`OE!Kd z2yxd6-KnX2|5U)%511waQtd8n(Gtjx&)PZjnJIXw?Kucl3&mUH|F?kCp@RZuAn^?Q zF)a@q<1i1PLH@NyON>UN$S3B%`%hJXWO@L3c_sNhSlz7hFL2cD1U@|)1+|N*QAf+- zICgp?IBI#ug0nQfAvKplT$D_G3P^|!;h+NMG!Ax}FpW|a$1HMS7D=z1@JS9;@XT5d zMiyDw`YdHl9%Spk3y#Zo5p&7DF?&+~vP5N#BFT+6%$?`S(1{bv3hM zUPWM>MIJVvAQSNIeCnP_PP-FM_w*hp9!|8X{swC{wRqoQ4)Es*hXhDAK{V0Ia)EY1 z^T!S2^o5%8{(TEHD~rZ-I;?r*kH!ldvEW8TnTr*qog*1yAjsY2yyLAA+RThn+@Yfc zmLEG4E4%CON92by95Ga-rYcW%ul(3U=`%frc0n?=nwT?}185_AEMMiODQTK zJPEd=0x$rUg643hSH)4_Vay^AX3@w&(Sx=y&m}8$x05WvlhVPiv98t-2|Hpo3WCnIJXNf4%n|GGzyd4O{049sRBK2BA&Ytdb^L#0M zkY#wxifN3gDG4zUjeDp|z!k{-)a}&d-wi@wn5AMiF~z%%Ah!@d{2^K#uYg~QMU>0# z^8s!QNb0-+0texok>n}#UK^-XU=v{wfN(9)H+cj`gnB8$9CxA4%qsJls$13^ab%mg zPUDz56WOGb9s9@b4HchQt(JddG%8~BYbiTLvFVt$-(r8s^GU543%}=+HulMWotfSs zBBj8ld0ImR{l>B+3oyfxN-3&94*W_^?&Ivb5iQkkwZaR%cDktuW^UcMyi`EB8A;tf zmJcVy_Q}zJ>B0J}A--LHy_7b`EBmn2b;52^u77V^-5!A(0H+<;SrTX|GG+e+g9frl zJGu}~T*1yMowjAf?wbZ9y3U43RLIK@6^Mv7zOFj72-KaT=EA}z$cQP}Ac1vo_w zXkuR#5atv@uX;kw2}O29s0u?Yg?dSNsFU)rDvX&Kwwro(*gDIKG5+Snm9*+pi`9-3 z-ruQ=$y^2{uez?)CN;I`sh;i9kc8=CQ_T@uk#jb}H?3edjo{wCHN@J-IFQRXA?NqW zofLkqT{$|AgvBd;i%>tjQFrtvV%}K^tS;!a>Gs#9C14jEOv8fr(neQ>gj)H8DS6ri zogaHrVzZ8uy5nG_40^ts#DGa@TK%*N_m}q(d=bCzv(>!Lj7tEJ?bJ%BKFfEbc8oqNx@) z2QniA|9Js0B8Y>=!KO|4JglM=a&RkDf6La^eA9Ql{7P5o)nFTK9IB~m#&`8V;+A(R z=3MIOLdBO(s5|ddXTPB`9x`02kyDSZYv9^`s-MpycNa6U|1GxN{NZoWn!MYT+#e3u zQy@ZU?ALNxGXM?hckLCHvXE^#Vd-92&yx7VupW0;t!43ExW zd@x58d4@#*-Cl@!cXLvZIedl~gO(jzQeIpm#smXIGGb{H^P!)Qt4deDHBk8~gcATi za#eF0J!WwEhT2Nsy&g5@`XML<2UDd2eAG;{Xm~?C%vg&k@jHFD#ykZpsu=RyCREI1?%l|@uLF?^b{v%$sQES8 zgvt69r@p}<)AuYm3n-tdWQ*!wv`HI`18GAD{)#pktHKg8;yp(?p@}^OXCsDn+`a|g z3D#+gPS3y0)U>}j*sFJ^JtFW34Mhi)MF8fJJ@IH+KfinH0jtd3TFV~$OJ%-)jzH2987lhA~0l5(inj#RvG*FbTLbV2A zs2>_k2FwWDoq(_>mLr7LhkUrs39QBeQ8FXi;sO5_Mwlw3*cAo+)?HcOt zne;;w$E645ebsW>j8CT@$_Pr9iPwCh-@U8!@W0@PjSHzw%eOn2*$z5{r*=sF&DQDs za1a`zPVhgK?Ekd)35Ev$v*K2S4#6=2bsR*WAL6~i=wSHQO$7e?=%+bWTCA)t-f#FH zsQ}b|OQ@ModZKlqV|Z4aUhcD;pm{U?hETeL5Npujab$NPB}k|!QExY52MibTX^GT~ zc`01M1Gx~6so)4+I&zx@L#*CR^L z*I;K}1KB?ZNH~ZI03Z)!4;X=5Gu<_j>h+z29tG<+!h=E%95rc5N#T&Y!fTx^5H2cT zlVIbi*n2mZHV)k|ykBsIYtbxS^oJEc%zmwDZ@$=Y&r%j(Yd||aS$cvPqh=fvso66= zVHhzhm&Xu{G7nZaWni``w|nVBHV>xku+OBbw-$lByM~mX9y-GcVQ2J8uO2|6~Gx)lUmSz&yJU?^tCv zI7eX@;;D@skpU%96uuJl;Ja@8E``-UP0|WV|J-og%e)OIvVphA8g&tS#j)6WY3iTSkfan`F2No1-L}caRm<_ z*STdGvxFN2jE`s7E*?KB&(|nfc>#0Tz!~F`AIDFJj_for!BQQ~R)ss35)_CLJ0wN~ zygq|&W1ysU(0Bdkf(#CQ7RZda?SK4via3Wmg?B3Sg>v^{ibwF5Rx1_P|L3rUo3qmn2`+{pD0?TR}QS)U{YWdc5zJyGcb z0wDlZKK_&dJezWDX;W_PrJM3}t=ymi9Dt};EfUk$6V2m;0dm?wg|6k`S@v& z8_za(zJN`GMsFAz@q&bjG&q#NA!W@0Wvm3RA9BYz0jxW-=43z|4HEuzCyeLHz?0cN z)LjR=lUGp29Q9W&OgSTMohP`96R$BS?tTjeU&~dxs)SudZrUVxO&pgo(Lo?2va)k> zbCvT7a|(!skWxA%qm-Y&QeC(fua2)%Z^Q#tL;!_Cz-_gZq?JrS8YBq_zlH_~q+Z?E zmj%h=w?kmZIk^xBF29KJarl#`Q`6X|a85W5j_MIBWN5k zDY)$vfBhhN|VTMFD`GY*j)R2nVM zWaDiGq>n=NjO|Q|r6#kX)+z`(goX*F5L3x(bv+F5#(4km$jT zW}d#E{Y>tF1)|&nMB1`D%8c}#xRN*pq!E`2iB?O z2db6?$?EU^okOXXpPKU?Z{7B!gjP3{_d#-I0zf0_caMmLGsH-_$n zE|CUc?{@l^eeGF92Y}0oeF-I|0h}DWRreVBwInN^MD)hH7Wz`yWO%ci0rqrbSejDA z#3ydA%elvzlOnS6y`y5f-`8J#IlOUGl-ki|`Rw}0&9I-8t}9obbv1ri`>@4yFjeU} zB<%*hPzM71w3T4Cd|hA=4Xf2#EiY;W>X^C z2h=fc%_&-TDsLqb0nVnZJ*UHd0}6Z3Ve+v_ zI4pu>y1NS|3W?VX-SNg_0f59_1I z6F*xxYQI9Y^k7OWIb6R)h*G3kXT{=XQx}ycyLN=_?D_cS;w?mG0R0{pHvoxnjmST? z)5Occ2bG`MXfj`zM~_n2xd9g2xfmh-oS#F{b+5&3>ax`(pzHpb!@X8{hvJT{acBE8 zdDOEqz8m1>PSv#860gA5p__;{8f$U(`F3@xN8Yo-<;m*> z>n^k7rb)~L(5dOyKxEUp{(L;^Q@qDRch{@l*BMY*A+Ij)h$11-?v`tVZdru=<){rb zhXZw{1ydOUU(hEZC4nre$U5wg9{G%CArWfX62cjsm-j`wBxDYf|DOOt6#d_&NT)TVP7{6TYgGKA67<{e?^*e!Kn2ydh4?U*(F78IN{-yfq&dWA# zu^OlRj@6$Zb$U~BMIk}-s=pwA#^h4!m2VPJNpm2-ztgbxs#}p~-j-`jE&((E8SRGG z_j1dU=a`wat&B&1_M)NJtER;JubM8fGQnx%EQzUg=QjGmqS9Fc?XOj^?^w{?%Otx= zbMAKN8{5yIYgJk66}U^}94i|XviX@7RaB)1{^HQfP%ujD9>C&36N0?P(D2=~!CN6n zhzJV@FPxR;B5az9AZSPKPD$SmLfVPp&>a2=Wtv8RwZp*0opyDPTq5?>Hdi7nugvY2 zTnub<{!kR?jdUIxS$o|VnRJ!&cb>;xYo98JxFm>Cg0>iM_+g?rCfN3 z#uG+^bv`FWR_FjqDz#774JzFdZMBF+h0mJWmmLu?le9JbfgC3_!14pS>{pm2KT#1 zYp+kca!he84vL~f(<$(l?@^QWFmD;S{aycRP^wM8E5~=s zjy=w6Zv)F2)}-~IfNv*w)=?(3(=YIjyWVZ*+;A3#?j~u`V ztNqpC2Y|-xh6>>2CW(GO zcfnr)G{+_nc;oP>eHPlLS?$Os&yy;IYnY^NoZlvttj*Eiq9`;W-me70ky25Y zQnB7s5$o98AHi}k%MR0=$@YNPc#3Lh&H>EzoNnrK%Tyl`*DJ#MZX#*klayK+>-ry7 zj2p^9wXuz6xriOCd#Lp%q0{sHk}~oqW!&?xQ8+KLZ0fXtq1|#^n4}gO;up%fwwX4( zZhh7o=|9VkC_u+(AxUy^b`>Btfb+x*hrK?S4KJ3ba-1QD3Y2?%)#U!DDJ^Wu^9{qz zJ9lU|LxI>ap-HTCJ2GUN;Ps2fBQsXLwg6cZ5S+6x0cP=N40`s+87>M+n+fa_Z0X)R0`oGDoJXmsrc2O*UR``n(`adChvIPsrMA9+k_XPC8)aN|R(=Qi z)fnZf2dS+Uu1%VGgMnpLnt>VF6oi*jIl8=pVg0tJ0=jH-WI|QmGJnMEoXgq2UH za?Y8atlK&Xp@Jc}g7@kw6C8k82-MsLv*0E@>w+iX;V$mHMRNG}M6QPZL!LQpz8bj< zO0owxzwgv#jA;Stv~ZX{xb7d3Ye_(Gd)`-g&jGcTAl1zKlo2^ems-87#fB%I`BAYm zS9^RGQ?h-K%EBbcJc!5;g47)Tx{`z9Y<$}lpXO;i2C>T ztO(kq8{6;&ZK6hZ{#F%pd$_bggTA6j&*Dfe(v8W@HyF1$fA6PQKfl36UDwy!^tSv) z9{7dU;0t_t6hV0Gi3PHqh6+=Wac-)0A)KrF zfIJ#04Zm~`4>IT>vGLTJBrq2d!*5j?9!8GcG`tHf`b8#u!5s2@oWtptpWCEo%%P9s z1dfs@kXQRnd5bL~V>}}3Xz}{9zjk@mdI$t*bo{P-+j=wGuC|~phjc?~{gNAEIA**R zd_h6M(cL>=i^7HccCvZ*@N%Kpqt@?IER}3IgzNW}>Opj92eOTC(NDwkRBLkz=-eNagFJA}vj{dxvh$^)x9MnbivyeL z-Bn2t9jkvz8^A)2Uv2gNV`UHDrCDThRSs+E-Rl;jK=LEcvx}uK)&(}cL?Fn;zlj*$ z!7HyWo2iUP((+TRqS7;j>z6g^4c6fwhOP(CCLh)(Qy5W4FCR%U6&g%+?)=>m8j^By zyp;cH%)f690ir!3(G7B^Z!He=v~McKEw~zt7bt z%p`}YN4K(h)8Y3VZH4U7u__-M!uzP_P6ezi20W5)%*HfYMbJ$wtfOysB(*kj+Vs}k zi1ic~Bi&byyLoHks_q$siBMle_h4Q*t@c}KZMGP2x3Nx5m>r zAu|RS4S-8Cs%I}t4AYJ==*X33iBHe^TGlSn4~jBuxW$@z!60>}p4UK{^lLf~`iis; zLtOO{5PX^^_O~5}IU$&l@#EduIo8>qZx7GD(Y?ktZP}5L9ZbHT3;cHXy16>UOU+J`$hp>&pRJ+Lqr7#T8ofH4W=uyoLUHuN_===gT_;ye4n+1lh8PH4RjH*&KuC_5jgO5Es{ZKlnGUwQ! zjHKR@sY2^0s#n_c8a)o2i2~ukSk7;Txd)0~71TpKc%6)CR z`X|nhfnL($`UuDv;qd+Mjt0!s7_1)(DkdhiQ@M_&nffHu0zidA$PhpU*%AdEUUN%z zOhI2?ia#@G_HKIK_sOC!(ux6#qM9~EURS4}Y<62aem}XaA9aZG-~4l(SbTGC!a~wV z94th){MGQD>pBE!$$yM(JBXn{R)dOTCA|!wFX(T#W4Yaxd2H4&I%T(_(;TbPyb^jw zm~3`_`RyZ+mwdCE$cv>~$7bwK{t!xkE3L}UI>Ar$G2EV=;_I7ud#p;!y^)4gpcd+` zp9=PAX#@KI?Znx&^ryf~WK2Un_2)5}xDFUIW5?H$sMf=tL#R!|i#$89EsONalr2{sYj{4C(4D9hv;5^IGes3dVDcz3 z;AcxXzlpB2MXtym7uryXe%-ifJ`SI(XfK{0AB)Tx&GsW0-xB^DqvqB?NE%namXl#% z{fnzNEMC-k+Euo;=!UV9#y{q@51V}tZw~WsmBu#S0CjX5^~T-YYCqHApEC3NcAD0R zF6W)z#x3hPjT^(d+XJj)1`ThHen0WD2X#S!J#8}>VnS>HB%?C@stjbI>A{n+peJBd zoTLq&A#M@KH`n3W^~mmJt4vK2Ulo=|&z0-8oM}Yoyv~JC*F4;IHfRp|N^RF9y!TP$ z08g76mmX`UBw0XZe6q{{u;A-#F@CSwwBCA76GaZ)z>y_?>~+1rL;|^Pk)HIOfQ+@O z$D?6x>&xG553jS!Psdptawj%l3i`j){!Xanw;TtrzMeionbJ9O%IImPX3Eg5 zn9xVDkt?6lynnbf#)gP1U%Atf9QFC#^!*o>w;wdPpt>*A86Y3vN1z>0WgFF(po`46 zL0(7aUW}ro(ZSsv5<``$4VT=nVuHSH1GcnZx;XGvUWrQto7qn)!E#_jG?z9VC&Yh- zH$Q{}FZ~XEmRI9da+~pIKMek4_nCjv=XmfaQ!nu>I0P!QKI8kIm|*=74red+GdbUE zVjhhahu!IZ-z)SU3^;3E>A*!y&zHy-N8Xa6AqY8@AI3)K$2g8O4~`h`qhU?}0%Vm1 z%0XG74v#|f-wIwTCZWPhXpa zWPHf@{2zp*p<$w~pk%@WQs7ZgP&dgqaN#qvq)G9IJa=ir=b+9)uoH;6^A|1w28nuf zzHI4xz#Vg&l^-*i4=etr6b#|;c?C7$A zJ6Ujr`U|GF^xWzfj)*p4ssVtu9^uq#pM4(r%e7-w%_cQtbcR7Hg=6JKYG(%QYSfYs zHPZv<*QYO-0yG5#*xWR~EO!u&1mmoM2j>Sj2@GOhR*Ttd+meRi8)OK>3=;}aYOc>q zyX0%hH%-j-hSk7fd~%O)rg>oBl+nv&tv00!PLE`f#f<`~lyuV?l?&?Ij|*Nr3Kd;e zTWBvHJ=brv{N8oGko0=QzTSYc`7jPMSR!yb_P>tK!LV!3^?!fud>j7#lh2KJLftaB zV>0*AfRO@X{Hd9e9%G!y*+eCi(Ary$#2+~{Q#3zfWg5n#Rm&hAkQW|XlZYz}8(Ze( z9E8bpCco9uhx>CdJsa&zvhBABVQ1SNt%+!coVKN7FlDCF)sM0s0zZ}1bO->b#QQQX z#;e-!QnSES3rP6hLZ!EPT`tI}=^Hg4OzcCN1AvHpCe#g1SZSmiZLe6P*lUrh+N6oC zFm?~kHKO3?%u2!)?KMs{30n#cogAs}-d2@GAqu!D5DPN16&OVRbJlZWpmb0CLz#}e zSu;uI_Qu1rJ5Bi)6CN;~Ul5uo9UnC2VLpDzEFrUxXE)S40=j?i4W2v8*cT2+SiQ{= zdt=uBcTE2eqoUa4Ptp|*gwaGQ+8WfGKsMTkviU84h+8aPUYG!sD1+KUn?wHM%<}Ir zTV_VSJ;&T@yu&8noBm<6(u;Hz;xb8w3nJOJ_+0`dJoSm-p+IGPW~i`Zpla?S)KPoK zrCg0dAqrb5QSR|)Hj8h$dHz}mbrk8+mYov8{Zx;LZ^Eu|8T36AK`T#UbGUW1CN_dy z)r7DB=Q=st$vl+}&~7-B9ueX1dL*@I3*BeLMdAEuCdwU-hRuPj|nfmI*NN9Nd8u6c@ir5BBMt0_|)kJA5Dk;m*z#U z^qxO@8$0-%i*>PYBjVQ0)6ET%zx(d@^3%B>*Is)Xq1;!fCbla#(6@F)7iLHJRDBD$ z4Cw0|NG+{>a@M~;MMtbm6q+a|@=Y_%#{7;d*|ypvIfr0g(Qx=eHIZZ^PuAmDHA zus;8YBvm&GMz9Jmi!fDu%^1n|&=Y>dK*?q%#7S_B zn9Fp*i;N;Rh-13-2=6W;TG@wC6jyZBqNjZE!pw!R_-9TW!y_xo0p{ni-nW~37ce)& z93Epk8~g@dDp)1PA0ho~ig!$)clr=arK1`z7S_gvwR2nAUBqo*3d!i*IS zB?ms+r+KZHJI7*_Rzpwu25Z6|6EhDrtm!mV29oe3BVNh)XKW{ov4@$_!ZUZ1fu^i+|rJx{*cp)D9xcIqOOUBWf3BuB@p;x+V zN{XDy!&OvC%tEkKfPqxx->UolVYRN@)C76XAqLU44YsD2 zxyKM1B@JgA$9~pcTgOEU3zURw6bTAlt58sTt^!6AQ5y4y@?QTm+bbnx^YX-JM(JX?e!pT$18J*wXJ~zXQ>f?fQDy?2)T%-rQ+9=eOFzhjRbIUtDqk(o_(GWse1EmE|f;_M>%n#5j?LRFfIH4B9qUxE99~qq=%3A_0)_V@0B&#$rHxB=J5(D-DI5EXIrD2P zw72e&2-`Nc%+gay^@?|D-|9$m#cGs&2{XJFQyKFW1I>T`CF*KnC31v56?%R?Hctdt#{$o}II?9^Y=>?3T?L=dC~1*vFc)`ol3Hj(d;3xGp|?}j z<2jt)K2Oko<+synbV{NuV}JIX+5X`4eB@#wBzc<) z6hgakijecHO9QYbkKrRz^CfQF8N2o8_=>S%Uape^_U(QzCOL1g>emtfGzAmMF9SCT zD`8=^?({|rejG8Ga&k8W`+@ufQWREDMQ>q)?_kVI8G=$MOx#_Jx5Xq@Q^Re zh5@ljEU;~bB*4QTj-Gi|!?B(Z`|5OdPy>~on4nmd5P|X6gz68Mi+(*t8@}Q9VBNyA z($Dfo+P1&ZP^u&0O%&fE&6zU=aky#L= ztO&}75W|N~`{oJsScKikWzT;ViDduICZICcbU{$iXv^^sDw>o>J&%B7c?f8ukGO?} zqUhjcsww@TKqK7GHPNzN&soWWwqK=e@<2g8$+;vi(RkI0RerWuN7BCI+)k2#c0Ze` zz@Dfk1&?OTg7I z+k7!F!|yZvI?fo)IBzew4T{*vwsV@2m0Q{2|N;2men59<-}&H;X}r z08ew^Kr6sSIG@T#whfA{)COJAcL=i<=zAcY&w?Bw!+LbRo1Nt-B0irNsNJb~+{>X@ zeIE%MA1SQm)gExg7;miei!3JbGKavWDk{ zqxz6XApaqavm?!_#|!m8x8W#C~ zD~PD6xrHK)8odO z)`u_wIN@MKi}0eHQB++uRv<ZiJ&zvP4>4je9K%uDK#oiIU@!>vj-?TLt z6=GhCPjF+Dx$ukRW)dKD4xYu{1QyILQyfRRxb@Tjqj0rFN5WA#iLv!Uo1c|Gwk{rf z+zFfXhuJc&OrA6Ua8Bo2Rp&|oqyEZMnh~!?wFVl@GXum>ulm?E@em;?!@Q2)0+I1( zyk7NWHAPP06xUZskR7j3u&t^mhCKz9Wi`|~RX{|1Va!RtG(k^9ev$@!S#6D zzg+M4^?E&@8)Oz0F-(^X15Ino!+N+#Wummo^EZbOP;j-LhAtN1Iy?P%dTJBz*f} z_o|@ePjLb@JmBaDJ15nW4x=k?md<#eJJDfO9b8*;S>a0esL9W_S|=0p=I2Uur?sV9 zGQ)-t$&_YW29Air5-Ow6RfLRC`HwA`*|kw>Ham3BW}1s}RuxX>WZ0dLtn03R`7PHS z^OcQ*d>W*q{jtvOu7NKm0mA0mZOCrdD5oL&z@wuY7OFl;yz^3r>!;;NZF z3$BlWIsu&oA}XkRgC4*_h9B$r)?k|0De7uh_qwq+(G|z)1t=+(uRy7i8}9y6uYU-h z8uGN0ZlUlR~%`0vWH_o_v z1-$CJG__Q<*Hxw}Lhiq<#mMYC9^p0LUz|8!64;n5x000bKb(WgxFgHw+)pyhiUmRb zk(V3y?5ojA*yjp^#-y@ajF&A$Uj5+{YvwN)-gw|!`+*>5qk)mCSDFpyJ20p z-l)PT*qyG4O|tR(#{udS!CkD>M-{fvd-oHe`*+)t!@gTSoU(D;b7lZHrqOodc;RiN zJ?Hnq%K<%)>Ay`6vrK^ehAOU=#wHqs zLxSSe6K?d(3=;eFT0#}W=5HWG-g399Fz0WU%TOL2v{@U3-!`|?_`Hd+B;``A-b7EY z&OKpdigp@F_fZ&}yTea!`}N#j9=Sb1$=IpS`J<$9^5*3e5r^l_zd9!* zoN_Q%S-iUU9m8u%o^WmI;;`s1uB@CNtd-NzcPaRlB^H>N%0FXHrYJ?_8-%Al-BVWo z2fcmmc<2HD)-QwBxEN~a)3DvbXSOe4O=lGLbSslx_HY~{zU}wTX{H7E!#;hzsKT~UhXJ;Dr9xSHKCyuW7hJDiC8v=tLYB-B6PaW^HN#v2-+PP>mBsb`b<2}^{@lL7#Wu58x6Hr_6 z#?eh_hcZmToCT|2ktDn_e-e|Eoz#9W*T8Hr+K1lhF)K+3dG@86H5K&GPCduGaN5mZ zSuZ+=*_RDbQad`S01Dv_EVxfDRH*T(B4DQ0pC$5}4^eIp==k*A_qp2GJbdpB=!o3@ zY(@Mz>*)grE%cv0`IeTU92XnBJ`yO0g3y6Hg-FiPFCUwXG?96NOB#lUcCCa~e>nJG z!k2}})ya#A)fMe|)~^;~zMQQ=?|%L2@_H!e+ic!W75f~yqen{Ro=NOq+(O+qaN_QBRgUY)@*k-77V`?< ztK~bGM{uDOFPoF=k9*x(>J{JHJie^rh!Gws_^QdX2<7&FwSVZ+tneTRHu>&h>y1J0 zPcVPUoGvLYR$;pg@HyuDOhd+_M=6i?n9WaIsKDrd-W%V0N=Cl@?J1+)&*8z5Bvn_E zv}=?*G#>>RliwCX0NJ50A0OI&xw8zO39$1QRsS3@sVh0NRxDTTkf-&{Epc-REh*jE z>#l{;*>8tAc7IDw-Fa23p157+wFmfQ|1av;+bm*Ewu1j|=dbGDUm{ zlg~{lXD5SPlx$Io42qX*%{7ZGtgYaYWe98pKbc*YoP42^o9xJzHM_z+TT$FvPN@I@ z@ojzsd&Gz9Gs2JH!LPD&*?9JTUfEeyo^gf7(Cplt2968kF0jS;h>I1B=*p<6c?eYsj&{w&KeCp#?2;CS;52&aRD*h2d1nW1l&<9=FM!vng`+7z$@bM1@7*k*k| zJlt_XR?kyQ(H(v6Ga3he=&G ztKyfd2jBOx%CIW8FE+Q4^DdUfwdi;$xhWptIRtW)2-W~1?*=8xEqgBFTaoG$*>6Y< z#Ol)j;@B@IigWd8FtJ;$jTq1ZJp(#wt{Xh#tKyPdix6rz4OmLpUNwp*iCXP{UFn5*=!lN zt%9LC7NxAr+s5a{Ui0sDgb?0(ldP5a<@PiP1!|<$MhX07+BaC*Q}}p_u%BTJX1L`S z!kX<~E)_+T3#w<=r9LnY^hsIbe~PP*Diz^~DvPnWVMo&~IOg1w*v&DT#Y+|ptBBqoGzmD0$5sak%5w|GF>m<#?bCY--Do**w&d|ZFB&y*y6;!q`}-=Mv~Nbu}y zf=VXKo2~IM=~(5Q>JH|pi>K8m4Np(J=gv#7weDu`^gaJ(MI)uavJN)Vcium1k}&+Q z?-f-PDoDm21OtW%ifeNsJ4=sl57pRYr=MC-dPwOO)g#+dvS2q?_g5B~4F_z?3tI4r zEQAyAfTqD(k*o&&GPj&-_01#Tk=sg8U%A6KMHQBU_DJ883C!40Vv$1CCl!{>Xf*ew z$gu!&j32XZ7k4&eWy8s1ahq`HLHSdy;BCq6pLi_NP$e41u2+Y9MQe1~NnyV#CuDDT3D|z&jmd&=~ z5DG&sjEz6S#**i>aOCT&V;l$pLi6?HmaH5w#7XXIUGv^)Zq+oPP8H1pB+5lMvdA!9 z(g3xW*xdLNW#Af54df&F#5ZDC*1#;G{D;tUTyD>El_F_TL`c5`Y}iD3n<5Gb%3_p_D_K37{3s^}a@BJ*N}aGOg;*K@ zTB87K$HgdlF{_cvAvRSk1#fYEr@Ig`T4QP0q=Odo&8@`#%n)_rioeDIvO$ITwD0S) za~(XzM2s0r=oQT14KnB$gg;X$weq2NE0Axu?B-`zdHd{OOvbJIs(UC<08T#LL|vk2 za7Cp}Kh2TrXY`HjD4i_zi(5U)+)Z;>NSpBi$Z3!YtCrOG*cZq8tander^M6^;tjzO z5c~cgx%Pg%9=QKL@xHf(_J4I2ZMVg5WJQV=%gdJf#TB~p-rZf774^#;&5O?945a(* zx$rMr6v+pNtZ3;`b`@*f$J6wyjUjt&x#IR2?d6GGLCW-~uW)D*hm#hdTQIZ~oSBG4 zNU8g#?DO%rc0cR+CW9j4(~l6wJDa2>MVN&NCiV?PYPe*em@C}Ah|2;Llq9Mt_c#zt zz6Kw|MGf5BOjNAD6Y-0t(HnJwY0+-~_h*eFxlQ^giBtZa)?O};67OpskI)wHB^fl& z^GjV?r12b4ufegnNAKHJ9SRXarqaMdi)wg@XLW)(e4V0WUfbuJ-1(}CS`bZunO$hx z>}WaCFxViMar14pnR$_ko1*qEC@^5vNB`_PR=3%J;j`;rxnsWceSoC{dw}7k%6ybL zaP6#?U@a&^yE&9PB|gSIJEY?M8!G$#EaVt>Y8Bx>8RU8CUcgpamRn8z%;A0Zrj z`*Fywr{AfnN$#d$`=t+LyJp@Ez!Mc)w^Bb5)5dh&)p+6L@yQpu86qA+@3%39)-f|t>hwAw~e8!d; z{H6ASM8^$Hxvx7~I{M;dhh}j&QuVw2cI<7DrY<0!R#X3kN1)nubMr6Xz?@9(5ZB|w zESDgK4|Z&G8Gtgs7O|cWck;=D9vWTn$CdrzTvoVzUU;1Q6$HdFg!ZI#7LpH_6snz7 z@`_taP|KgUCi6`*5aaI*^}>=B9_)^FsY+ z&&z!!ckZQ#uWbec0)RaixRK;19WQUQ$ScW_ajEeOcw3>S?CUww?tPUJTdP!Wym%97 zGIha@QA8GAGfh0&bwoR7cgyP2zfS8k5y$dk)0iMnJX;wOKc!qrP5QFBiJVK^D?|1( zy{Y{6mHBz)i&RsyKL*8dFNZH3&(6PT@K#3l-*8>!BE;x*h3TYO^u2w0Qr}uC_E9;_ z))|}JOkWQ3!~dPX!TAll8~EYN+4U%h*Tgcx&Ix?qQAAbm1cnEQ5x}pervI(~eNxH* z|B^Xd|HRuNOSTGGl8ZW~&&I==H?KFee)-q8wE2`FE$gOxKXfw%o=#Ui#>fBhK~u5K<=FDl&+tJJW0)p_gCFXfO*(}gDYf>q*#mbPB;~%Z>l&PfJlypVA$D8N@p15x=?w+z{kJq3s=L)v?FPK0B47=PVt&e1sM5AKi#qV(xnY{eh6k zwbne>pZs6O&YrbuON=?6&MEK+CRkNtXsDf2n~x7?&+GVn{puL4l!v)ew-pd$4)P^+JzU{_gQCY#GM+t});+dH->P4G z6q(z~yF=uR8Q>jjl;b4ep(n>tmfjWw(CI*}ShhGQgaO#T@W|nYz=!)aG=+Kp)oyXJ zJ~}JGeVD_o>1VtXk?f=7N--GoP`^^-9Q~bitgiM}@qp*h5atW3bI(9rES`btr zm~tM=$1nPT^wR)LJ8T@5C7c#_=jEEMY-tSDb5pK)iMDRr>5tMlC zg1B`lH3m-rp8$|7=_I4$l7eHPV;tD$(Q(6-={Tml(C5cMFK{egI zeBgLc;%;2^N9hI!37}8TKlm1~B0!rMU~BYddrs3SgYq4r;W3p5bDA9o;!Z!vFO8AP zJk<(wpd3zU!{>%M<#D{)&4Ig1zMbzt)#oTxa%x>AWFURh10YoAvTx)(m}?OhbjGi6 z3VoD`o)?8CjK*|yQCG)l{7%zif)I*rD)Ux4D_r+PNL25dgNAjHj%0`))a>AR+e-^j zJHzU`l}yXKb9|0T)g`3zQiDYoF7O?94uEgXZY&pj*GK6p_NgKhqsFnou9LfQoyRFG z6~!p<^{?|o80Ui-JN)nfF8cJMNc96DYD;m^gINntT;jeV?_)WQJC$I=J&E%Z43Yt~ zK_s{6p8eS?^J)OvO9;Jp7dt{oEvq@g?9^odYC0ay;T9;vCI1o85t#~zp%?-EDIkr* zdh!8q92l(kn?w}^Q5{u$K>j3n@f-R{7cD|`)kLv1)dl(Fos92u4eyeYw;Z`VUi{}} zW%w^)2P)Np3MNI`ltV_o~0_Mzl)r4Pk+Lv#mHJ`r}fb}@F>mx2=i5oHUC z!2=JhJ;a9PD$0aJwWk%~w{DHpgNkkP?KrS!A(yrX)YLaCvspL6KIp;tQQkUGxK4|`sXv?FS@UKNsTPAAG(xmOLQfCXNnbvvTIYAj!gQWs zFgv6_JHFi4M54XMSCi5X&->W3I^OWz zs^=X|33zLpkz`NkL)5bBTobXrnWpLXKtWC=n+|{X0W@8zoAw4bN)GXaLqkh_JPzdK zQe$vYt#aD+r?5`PzV(_16*f2)3^g4PlD79#jSBNywH3eh+FKd=+}{0tu>H$jam&bq zZ^6s)Dns{zb&0)pUh0GpbB*BcU9`qLYuw!zt*sQS?@P34l6mxj=+thWt~Yq&324TW z&ee_?Vo8^c16lobC+U<*=`h)6K;Q(h8g8|1KtYvGF(jCgMZkc$p&d(}Pv3N7TxvcM z@OH18`<>fJyAAVFTA+5#3T;;<1}VqtXYO9NcCGlxaezu~Fkk4h9LS70s`zC38S&Wd zPQefb?ogo^&C<`zHG%_(EFJl13E|MHj#x@+h0<*~TNUxgbT6r7Ck?k`t$NjSbLjDn z%0NDqyl&Kd+NZOmQNp~Qk}H>M|4^eM_}(uhF6740_cA^O_Nb857f&KoJMNg}_MT&> z#FU!lRw;%$O$KM*r{e5cJ1qT2E62eTZH2eeM%a>;p`eQJDC=D?*c#YEAgd!-E&RzA z*)Uid2k;wJP|h;kenzWX$FBoG0OKIrxEb=To;Mzs6=G~~N?{`vJ96ERKLYf=cVBqB zNAMAJ18fIFfpaZXcacG|SayT~@e%I#VYpUUR`Nxm$N9Xt7^6P?t<$G_Rl6^VzOEHl z+b`t1)QR&lwFE2U8RPfqSKJO$e_x$id;_A;@-%M{%}P7>@sa$^);Mhh<+<7&B@?*- z2OEa_T}c~TgynLy9!^E@EsC%|(G3`r@I=UP0Mfm+Uzs4!9j);&lryW?RtYh)@U=W) zKkQK~rxlDQBgQp}C+F$N*Yv#eUP=`{pl2lpW1n+#CzYiyMWXLA)_va=0$$@%9{XGV zarE6@_>otyb?#7VAdhYdlOCajSy?=vNhibUG6u&(eJM%%GJ7^vrd}$jpn@+UA^@2p z;da_hAG-U-KS(%6D5j)qGDZXWspneg?@!&|09~X6@^B)kU3GQJ%h`&feIFyd|0ksw z4aa>7ke+pc0xa}D(|V(uf&t1Y-#0S73LcH-AWAlQXGSgN;h^1k8QfkaHouTvqOf1_ z;Rn6FMbCUbNJ2Tm%$-21&q$95lI?ov7SKgg?;y2-4;gR=*6NX{pemn!Yi-st(fha)4n zXzhW^ns0`d{P^QCBZRj)IpE!Kyo`KYW_4`sdx zhQj=kK+Ga%TNYB|xXd5_bCvFp*buA`k6aCk6Vyb_FSgDa?54|v%v*(2A(?cWoj&y> zIJmK}<@2cpdm2fZ@nx zvXj}&s3`Uo-gP#>Mxog<&FD>BH|6!R;oC^Alq?q!&6^sPL1?z2UEH}Y=+_%y1U~K} zSH#AZUo>wk`;^E2^m(nVwC#uBrvzf6=!$5L;wFQYI})X>_~%iE1_evoF<$I1f36c2 z-HGbFcs_>u-w__|s~wIRgLyOTyjd27^ORRKlrDneT$Rq2i`c)@CwWCDhY3fhJ_|5= z!I|49wgtAX!QAOr5({=+Q>{k&t85XZ{2k+T`187Xo_|nEzH}A*ZX3Twqwi9icLzUv z-F-Mq=ucHDu5pEn{zoV*P%P*-i0>Djg)1ihaw(!07W{sqlqhv1j`&ER{ZO&mtlB1( z-&xj2zst#|4}7Rr)n25mS2$yFAorzZR)180FV?y=7bWOv0#wiKf#xB%0vGLOQ7atDe)!Lyymr zelpwy_#H#B_q5EGt`wK?-+0y#45xSO(8-;8doQ+H^zAtb{9|3?6DVsjwVPb(`N&Mc z&u*HrJATV(n6F$dWK*r_^62uin} zHQAym%Oe;q_4UMI!tKA^Z;~84^+xd(+ve_Tq27P@z{dWW&EI}Pc2a(8+jW;cC58(z zQQ9UcGfYRG7vZBZB!YfUZnL4N7y=pu3ATd~SDRdUr)@tGYH^bs9Dh*-y2)~!0hKj# zWL0_z{uBv(k=8g48hgQBZEMq*{aB_!nAN+Z>2kxLucrq0Fp13Tx}M}MCH@x)QLEy4 zl2d^0@SWA+ViNJlzbHL5nd%`OY4rNSTXToZt}!il)Az>5**NAhlkFQU1Cv=5BOor_ zV{Z7G9a0F5TOBXc$hQV}2HaRqDdw<_$ae3O*R;zzhP~)F3I-~FN{v5N08$3`@WMR~}F7kAZYC|lks{+3zyCsqelZ9Tj@|1abzDNY-`__M&%+tbYD z^$Qg|^9`e07eBF4M-_lU5~Mgn#B8vS7U} zT7?8xLi9nr49lsXFKIZ6sx+KA3tI1g(F4MJ z3pn(?I_PQJ?SIw{l|wJvJlKZ36LJ`$*UC|2&C5p%B@EIrS65#+lB*9V2ccd z9IlWy(FG@TP;yqO@BVzc1pkj9L7Y&?hiNVqIia;n`PU%w_9IO)gjOoqJHZQmsr+K& zyB(JKNP{PfHn~p&ivdni)~6Z4nFpRG^=tTBdKOwVF2uB#GMU@*L~s`1m{FD{!}vc6 z)SigEchSU27ULY}{MK_-qSh1t#tQ-pKbb8X!$b9=s-4@EguY6yuva9(SZAT%z59iy zwO4!seYNx3JNNAV8+NDjzIDsuViA)xD%c&j7c)s&=Wn<6MAm*gqjH7uAUBze-84-I z9ZS1U9t{QEDb)@iJ^dHeh%iy9Q7}cKACRo3kwZtOv{v*H3#mZ`@5MUal1E-aEycsP zNI_c~o&m>|pw#>G@|xF=dOs1s>ITIroSAppqDz}ys^b7E$lUZlL;XhgD$Nq2+lOGO zKyzRil(ir~Q=fBDx}lCvnKhq=9-U)c zojy#s4Lm{5Fqr()E>il`e5%z_XJ#_z=ela8G)3BD`Uc zxQTUGNx{Ppp*OH1=5TY#21n}e z<3KjX1G09Ck{5X&QAPB)T{X52*O_0vZ~UOnx98-p<2yFF2mtRZ{uKlJ8o%@wyb;Jb z^~4D!oWq0HI5aYM@$s+LSGu8nI4cK%>LBoDJd&Q@kAGLcOJAT(*_axoQGtD_$9@^? zc>f^+mz@*Z)}~}R(a`c*UG}|{;pt)1-Fqcanf{y*X&CEQ5UI@V43nvDb-23K;{X0g7Xf@=K)5ZLV*mRPnL(R0C<-i#R9V<5z;pNgV@T;O zC8+ZmH1c=3x^VA)Rdjsp?JXNY-jk_%MQbNN?docQFmiEUPTQQ3q{{Q~j&sq6|6W`8 zXu7_%w4Gs93_eHi_E?`5TLP3VC5v9-cFj?Fzhg8t|^*1PRQR1lj0va``9iLd3K{m~(kTMl3;`8N7m& zxtesF1KTkd6%YXK)CG5}Fz`H3bt$@l0RTll0tRQ02D1C23OeCFTtMp7P8p$If2s^~ z)>uYjy!Y|WR0S==epLPy)z2JA_#PFrCG*`IF%Ay!u>uv_qieFH`CK`M$ACKugHxmQ zQ2t1e0a?Ckhwd5daPb^D^dDpMtCo1FZW;st?tYan=|sDb z3UtlaO*Dx)o6N(FsHPT65$KhOyaiXZg<5NL!j%CZPCVAa4K-l}=XZilc-&MUQS-Lgf~KMI_~49*G8{DS6ENfMCR>3C-_U@h_`) z4m9unVgnNS-l#r-_XK$MWcro2wE8HF!iZ1ioa+CS^kr1^vHb@%nsx07g~zDUy^}oM zW@!x<)2~F>KPt#>g&8%QKBD5}I>Yt`hgs+czJ_dmM-{Lpi3MPBMhikKB>79 zjEfc{%FV&|PoJqJfMJ!kjy0|6WoOwJ8d z=}g_&d(z%-K@oBk(qJSCl;uf8t!#l1pc^9116Q{YJNHBjge_V2C;iKDVi?D;;tga2 zVP?{rwf&uW?Y8{zyiU!w(D3%Us-!IEyfm4!B!tY8zQz{BQM+}WaGZ(;eeb?DH|H6t zDt}lc&LV6@<-UQ=D3G;j22Aa9{Z7NO#c(|RDC+S6RSaUk5+ZpE-vC;wJArbz=1!^I z7i|t14g$+3ylq$}()r-*cO+g|Rv_|IjL#@wKolnURh1`>*y;IZdiP6?(k>NLau*?2yhI}idfG?8n2}+uZ_81J%>#xhosPQPkAk+~W zo>M4Dr?NF67$hsL2k73RMkTW{nZJ;xhFV7`>qneJD|yXSmKq`gbDU3Cy@5ewdu-1s zsXZq_HTCUdi)CJ{B0UjC%Lol)Q8SMYcjfG>;+)Fw-Mg{jefef%oYk~o##VA{t|=tI zNto|T2j*x8X(|G%K7rGQWJO5(Y(Q)u2x}7oAM>#aQ6~h^TG6Kg3*aPR2t$dtt03d! z-A$F4plD)$;SxdRLqxZZ0_(Er!Lan#+3vZh1WJp}ml2&-J9g^qZgip2H;Ww^{C3|3 z%PS(CNf;4JEqQlWW$-)nI_pAkkJ+wgu!DVxH{0p;w$h1%`|+pgzc{VGW?;GgN>{{s zudnY+zuwuk((ydX@(TwY$wBxd)(eb_&fV#^-WCE%)f%ixi>mrPH(q-v<4$vAnz}?C zDmd5LU*GLzjo57zGcczT>;1&#cz-#ZE@QHsXL7V;}i^ORaAeG?EB#)!p)I z7W+H90>V)=g5YkI5D03A;@}#{;vAxzakT>MZb?MvDS_F+?RGkj6yaf}D@a|@-PtT- zubh16QnaR5vSR?4V1!utg&bZ|yNCtOGZe8CfXz>}3++|br^)tSAoDIK&1YwEvEApu zbL%xqWkN{Nz1`=s(INiQ>sR34EHt@8fg3GRY+r&kd8gks=wE^e2shzUL~JqCO)OPt zfzS#8gF2Ocl+h%Eb$$UI-iXv^!Ovd0UT>4N`7!bA1$y3duZCIw!gFchD9XOj9IZq= z8He{L{>pms8%g9q^*CMQY6ukOn^Ug$rJ!F;{BN*UD2?!?^99F z-N`m1)%?UAI0VH3UkIcz4)@rDv1b66&J+Pd2f;!6{H$h%pFd=z)}>o>MVwY80=z?T z@2tS=9@1t1m;)*ocbs*0JPbzd?BZm*oWs?!?G(d9&VOx*HJFqySB{(eaXTN2&*wFj zanim`tjo)ZbQiwG_nZa4NC1?DJkk(@rRfK+?P8DL&Ozth|1Gx-J8B(NuDq6Wr419$ z@@Z3UL$!_8ya3heDsz&KnvL5fAl6B)z(Y-`5hMKt>nd$O;0t3-^Tr2+u0_knSvXUfFA6v*>Yk`=^o3*7*0a;SO#(HO6CpCe)?cN{tyF6j zX<&1(;}lY)TgP{K;3N>z%xboe&9R z7jDAH)+7LJeZ34_8|C~o-Mk|op}aq)O$6RY?|a);?W^zdIaI;gO0!rZcTs$%&_u8s z%xnEBHz%c5g4kVPzDIfDX_t?G?2RtdJwTf5?bhp9=neNLoAO-G7KpZhU&R40^-msr z8GG-bM%&#(W^)mJc2C_3$S!RJ&CN4!iel@4&5Y8sUNV1SFC7x4 zm{4yS)*q!XT|(_B%{?qD%YbutK5wHd$6kKyXzHBim8-Do+nBb=^|o&BL}U5Ju{(BF zVaiq~P$dfcjF&pf?Ou-^93mf<|HLp_RgY`&I(SCqYT&f$0y9D5@%sNDUyib`s4k8_ zO?+}0wX!+lU-xF^gO>KvN^>_AKRo;A*I=<)|I+X3?mt8v9JrxymK~4Z;Q0DJfk`L# zWMara_p|LRl-7(uGeGZSmbm7ayHpIIDgq&*WGxry^5f&EDw#9_f-xbLyd-r;eikPVv9>dkJ9!z1n?81X>1Xfd-~xymy>;O zgxDO-UAgu-?``65U`jgS-%`Um4$8gkA`l2U>Qa&H7>VVTbx?&I-PRm_xH0g4W_`cp z)wD_+fBNhZyV|juPu=_f`x_CrVa-i%J^zDt%IfDP#NWVWecjw;{W~f&GZ9`H=5R&q z6#yZjM}zE?oteL6ZU@MozNvfu^YbbpWLN}@xPmV@4ar=fhyLkSB)n2b)+-t~QQ!1?h?M{t4 zzyS(fpy!*M6u2bH(Z=ROWdcCi=L<)GF_9hBWYF)!HD>%u%lwMNTPXS(!1qI^@Mk4i zH)IWzx}g5S@UZ!&*!SxH&X`$TMbZ6qT0osB9eXa4AsE&Z{lT zgRvXyPc-nF%V3aFSY=^lqp+>=RADRSEbbKb!cpE8_6109sXZH2*k8M8sJ|Di=UK5W z#tSc$i_3*iPR|^xcvgFg@&fndEHF_B5xzTD-dfdKU4HyQeO*hrj5Uu`#$2^w{!wMl zAHkcuGya*7NlQm`%`@d<*9Ihy2AwJE2y60X);M=_p(p206>YaHUUlv7f##)gZn5mK zF|XyK2hC>p@n>51j3OSn5Vp#BPaE7n!H56DJ1Qd34Q&qdHIq-MQ@UBf^09lZ+AFNx zebBnyq`P%pGlkToaO;l3M$)F-*PR#Ka2Iu%UmcRc~cPR1K%W5P|>wNOW zk-R!Hztz9=B)_FXhKHCAi|3}Di$DCC=reh@NNqi&R+&0mC~$@_hr}k*)4eV;e^P3W zTYv4@*U(c~m1|IQiVnlrzIfodOvDK{nZ`M+2%TI~)HMI@k5t$ug;Kk=1@3+$pq-w? zAg{jN^UawM`tLn<>5)pqzg>dV_4(m#N1XqbWl39FFP`K;2twAlu1aeA7(QNo<$uI@ zUlH9+scyKOR~R&fFXEfiD|8YPm~}eQssT^6_Q+aPLU;_qoV(J$s6m3JIunj`XtOKR zE>`UE+M#b#B_r^ZyQ&m?8k`Bi+_w&Rifj7ouN{qw#|N9BA{YWtrYX%EEPdH|&v2MJ z6S3Qw`P7rOD!z^~^RnMk6Vu?hQk>R=wun5zv3dMT_aC4`a2eQu;`#%N7)|_tveBM+ z`c%-HNb6ZkPsC^QvFwpmg!`TR^vh|N2SIZ{Jw~V(XxUP)w<=c^ zytBU4QQ#kC^5*fWQn%!Y3ktini;Id(=8jz4r8-xq+y40qTthZZ{DWXZ-cjYJP;Txn zAI<4{t+gKQ`(z*Nz`s_XCJnIg9_iH^jaZ<%gOjz$`|EYg?(=w+(ir>drw0U;-7Wj9 z0h7M_Th9NDT1b+MPeWcSvP$m!Z>658WG(2D+w|cz(7EYd-c#9IO|@rCBK2DhmR3$2 z*3dhwlQIrJNsN3$ts<^SulB3R-godsHOgu4Zlme^f?lq%x3GEM6Xq#<;d@c1Mhirz zxcUGow)p-QD2T$KF}HCtNP8xFOPXs0diiJzIodc&6?pwc8&ci44ZA8B(GI@Wp2%p$ z9(eyk%T))YUSmo@z)9Q(;Wa8*tcTz{)f(p%mWlT2;3=CnBWxj6_c--(TfOWVwu#yE;nY zwOe-HH%-vIq-jH<9`+c$5Lrqk&3HnJ9U4DwD-HQy=4RqpLpCz+8&Py<^=pyC8wjFI zG^0h+!h<->j^Vor-&I`?s*w!O7r>oTe#0!k7qos=P0)U#?TX|{BkcLj zn1bvQ-ZsJcEY3Es8@-ySO%kZP2^3hys}PX+9bStqyGt=)@=XC+a+*?T_hrf*T-Q)q z^>V>p+F)?7r2MVjsQlp>?`xH(Hl0uI=bp4vZJ=SzZKk@n9X4o2D@p+D8UtgwPKKjg z30(aB_N=ctua$X1{qm9oa`>wLHJZ2lRC9l8E#dv$@hSV1&UEs8vlnVtC-tcB={z>4 z!h2dIAJn`;=i%kEtF`aCgmB|jG1?@(Zm_254aN%6=Dorwb$&_I*YV0XL(W!xN8i;? zd<-{}@0#K%yJ^eZmVUv}SHogL6h9)GrU&AU!usDfw zT#rIe5D(Iuy!=xLk&sg%NUD^Y9Iboc!;noJgs%F_PxGOxhPOxaq%E~lGfe$|#gh=u zc7C+kDVFh_3)P_XT1HauYJixvq^7teh8R((1GiU;o{?z??Q4*AvXe*I3#;x64`$GJ zq4e!lZM0nW`PX-YdKyfbS-BF~M(@AlGynCWiM(s&bSv|13Dz*+H?<~zm-M*;@_^dG z>tSAr9NtGxH^LDw(nVHS;}ox)KJ{x1>OEA|^$$YurgHEbd#cT@@kD0lMdx@WYCorw zJbwHmV{QDh`)Plbq@Uh=i+Iq;nrW(>D8!df@A62F+3>!K%ZBN5d3#U7dd@2-H=f=c zkV|9M8<<8hA;r3X&J{mc8naN&ERt~;z{;C`NvtM=x`brRpuo+lWndysRLp!K^Ir_? zxwN&K>dtU#!f}Pi=&YC)=TgseMD>@TsMoXh+UMO=#CjBPqUC2I?It+sJ_(pxiI5vU zv`sG=3iS`}8>Xd>(O4e@-I_7lm-$NDODltIIt~E%o^WX>qrPxL3@@eR6G1(m`S1Of??CYujPj-j?^7>N6?`em zW6HaG7j0RvF8!dG5U_PH850i!pn}=LKYRTIwRqkM`6yU}X8`5DDq)YW^@-r&00QCX zb`;uE{%45#_`0}n8!#UFFkRh0*+9E(#anazVYSdNS~0t*#cMMm*>%k28N9n=@;cQd zYI>s|NE>Dli&y_R@auR_*)-|Vn{}3F4>xzz!dW-4b>#HS=1+NYU2cOks7p%M<|n5) zjRXopX49Zc0%pSHW_#2-LE+iuMGmp%ULU6g}%rfH#xxR2$FeSEcX!>Q>utV#lgEt_iT5`-InHKz3-=z&5|Lj3OM zFUcz6@xm(;-d${h-q{)K(h0%{HapPGLGa^~|LvVc`)={2^ynFNfAdjAc&Mpi_th(= z2Qhocf2sciAR}^BVZ*IKTSKO02*=ljF8;kiH~*zSJ4e>D^|_ZaHDA z)@qKg7}4F((#yE$5xUpO@)+2T3=gG1)o^O$$timt$n@z~|52$lTp^uI@%gJ)RF<0k zK#W+SQjQFR6=_;styVYVoeMcO7vF?5n&*F=)Rc3TUNZ;RAqiHOD4CtuWQ?UkEbVv$UF!D~q`B1n)!C)&wC{(Njw=OxM14WD=p)EzE5H7C@VmnULFQsk9@E;rgQ#v?yM0 zpulX?H-`z~J{|%3h+eX{1$CrHP{)uzHs=3ixB`FR$bly)ZWIghtOU(ea4Im`J+8UI ziA4li#ZJMjxEczGxCJ6&s!K7@4vg;vDPp^q%{~hG#}ITJ`>Omb9}tmB9Z#cDoQ)$yy?=Y8IjG)wCZeilsU*~AI!=-_LyKJn9v1r(rW5~Dyf_4Ch@ zzb>-_i;`Be&4TEn31E*>MLh%Fw_y81WaA@||JZy4)rXMAu4A@Iz$l3wTWH<>p?c?C z%+c$GFZJ->7ujuO!NY{@_XB0dh`iSeVG7qx*V1$k&wwOOs|u&po&d9Fkd@qy+%WGj zn(pA>G^V~a;E%}&>D&h@sHQHEs^=Kc3N8!5JM_)C1l42GH4T-9?f%Z=7TX-@XTs|t zkt}TB;^E0Phxr4P7AwsZx^wclCRpgycy!mz1Jb`R!T()P%oZqCX*`Xw5ec%BAHwMtEM9_vJ2V+3CtRi3hFg`H_Zi-4Z>jW0;N)I4>HZ4p2 zms(B0;VZB|r=uG;y1PWwk%FQQkTf<%ZIq)VmC>OhB`BhfQotHuV16SM zL|;Y34nF>g^E=OTKlgPtil6JNtlhXAvLG6{VVuVY+6923p@J>Ne?l05p)20w?>L+h zSO8)9RiT&+Q}=DPUEFgb4`*=I#S#o}r2;2+(1DX4>J=S@a;TTaM+B>R5QLM;HS{^I z<_VDK&F4t_Yyh&}aBHrc!4x&0LXyYKg5HIq{Ium4E8?>N#fX5I6CKa!4i-PX%btpA zJU*GfTJ!i#ieSE=FW1+H?U#>*jK;VCv~d00^2Uv%XzVv@n zyKZA>_CBjf?^{C(SJiU@Y17~Jw|u1BQF~d1f%*)S?ZN(L^%useg%3#uM5pdnk#oG> zlp9g|-QMV5i^fT(L4!8bvG>?lWw=61Gcn*;M}+8Y(>fViR&fW)xl?M+!HHnK>yea} zc6vtu2)Z4KnTV9Ntuy~fGpM2^4rzKMF#|e&RqU{o^~Ww`eo=9MyaG0hz*zQn+gFUQ zcHkJkIvLpAFRxwB$9lT;D((1vUN}qkTOP<9HoYr+SJSlQ0lBs4q^}%;)C>{A;O+d0irbden3rbal>hEb;f*{w&si`m9 zbd@D%iT*6sTF9~R`yqykqwh5P<-Ap9kjQvsYf>i3o$z=0)Wb*DdL1Q+09Y1)Soe}w z=arJNh)luZJV9C!t)D@MGB(Iha1Zi!`Y#zhL>0{9~%9?y!y^&W?8!J z2?=?LFUcND!_C^5-SK+KcO@P82`oRjdPY_+P6Qy!?4QCPa!WZnPiG83`hq??@Yc0=>P&YP{68#U9}VrX#y0ig zOsL?DgGj{$q~iucpVrZ8Vc8rBz2_<+!UNRzHRPnGP+Kj$K=4yNxbM#?MZ%o@wU-0$ zV=t`m5vG8w->p+B_Dv81{mM4lDH3(;o}?`eDx+dzKuJ;R32HM0T~LFc13#^&;@8>L zcsD7nA|}8XX#@r&VMV9KM*^2_acfCcc}@=@~{v|Q+WxYx(vDQ{-SUW z?=`<#nk6Bv<)oI9tFLoZ({7d6d}l`dHr$r0u6Cqoqc_f3-EDb6={q{9{E@Z=o~(+Zdoi=?{X9&M zD)|)x;o)C@QT0gb&Zg|Y8VpYRKy(kODWVwO6_w?`@Kdh#CUl=hgmi?WGv2P^1K&8t zm&GD21drBwh}Y+3M>so7yh3$Yn~B+o#0~vRJekgYCjZMjpt!jG1KAg36qRFED)H)D>GZSL zO0D2W12S(Rsi*|Oe^nW{!ZIihbravqqo!bFSo|Dw?G<(52 zwku=x>Gi&|qp4gbWMV^qNb&lI9>VuI(8jq3x=Nhw4@is0+RrR#rIERPM^0_@+SODgk~dmpY96E7t-9K{ zwyuHK*wkRe0E~ia#jC}Qn;SIiH0tcCC7Kj3Umj{2y4IMSe1vg40y;U&z(Vgbpbw8j zM;|0t&sC2;ZhBaqTW4En1gb7vwv}xtJkSuKHr-5ZhI~@|G7TBI{_Ruq&re^zs9oga z>E$_~&)9!%KeQ>_^gsXfP^RRicIu~uYH(lYqc$plXM&BynzeH4))zJpV#`asu-g}_ z&5tfB?CZq%J*Pgq)3w{$Gy3+$3pp33?WnR+_b)&KTK{PTA2!w_^&i~HaH@qW70(Ypdi_~F zkJH`#>iDT+W%HAPaSax`-*lz_QG5XUL75ay*$UX=No@Y7YGD${JwWXW@PyNxe)`-C z(KD1CUTLUhxUyfYd~EKV{Nf4@DsXEqn*2xElF<5XVkW00cVuif{(i<&kP8-k<$sAc z9S0uh`j+NCR?bN8cS~$ona$0YY4aroe)yXO5VE(h?&7g;=A9BF-bl^FFoch{XQO1( zk<-ehAKD@u8m}(Ri1F_Cpi3GqN_ZGq3;269G$)oEBCdpPMN>6@jti9$=UYNeqw}Pl z6B>B9f&eouVFj+b<0qOx*b*+)CU}=Ee1bCn7%}5GNMmVf zc;@7l?YYeDI;S=&n z-}pdeSM1l6i?fzWE*(&Vv&3H=U7FEAL&>~$M!Fihtl0)Nqc@Dt+g25?NQ?!G@^A|1 zvi%X8ul(%wTi5JeUPbo${Weq|r~P5E?r97}_}4j0vPlYI>1AI6Z=Cqs$R}}VoAx&( zZl%4vIBaBfp2g@`M|gk;>n~H!73AwtAAL5TIqh+)EUAx}NN~@wmlQgVJGjvBl$9+RLgsVW47_0B)&yzKX%IsD~K{5 zWqPWW?YT2B^9_OZf;lv7U;`J%^oq8C5C#PyPv&=f@L_mP_6*p03l*!#p#hS)DCjrD z(=3gGfgjo8$F~sA|D#A6^CGpDAEJ;b{dV0qhik)r> z_{?NG><2meS-|k6jxjxEemP!YIewqh@BPdxtA6>J3C+GLY(6?#Y9+vULO<}+lw!(| zHU&Y0$hVr5Xa~=pMUnYm*&tEM4Ii2TK7*~Hb$jC~vFnZDiv)_PxgkpRm%dSvil^2| zA=&sg>3Baqx8mNKtWM@zDSFOw^i+q4+B+h;4v541&=K800^D5=_7R9bS7duxb04I< zd8!xr=`RQq+xuisIJ7e5xa5f(s9M9|Po(d0Dz21?2C>(S8pv?~cJA4a5i>W+$0+5; zZen&j%!y0q;5BmdFvn_Dv#kgc2-UF-c}e;y0xU!ko%h;nt44NIvs=8lXgQ-8jrnJ_3ez>~yu`I0k&;!QQ2n*9`JuGLbG(ii*~EM`i&|!JgJ7RD z6~wZ>s-G6Kh2k4H@_qInJR01**G`DI={BHeW_$H5mjb`^c zyOc`FGQjYhBpCAIqh~%eL-e>L?33N^{2kjUO>-@naH$Zb{AaemuEYPJEWB{HRtEmc zqkVaEzc}DE!;p`E9YsqfJCD-v8Owj5uZwz7w@jVIl%+NY#`v{nMaNs3c^(H{1=D_C&pPSg^9?^<5<5Aav|Ao77>Q@!bj zI<2-VH;9oeUt&P_z8k*~l5bSR2j{q#{6&24t$oq1rzcfAsXRAg+`bplwgeHI-;?!K zg`_zJ@kn^O!bDvpr!lEEVu>?8>HPb3z*6?jz;dbo;Upz3R-t@hT>*R#m$2=?5*uCJ zEeZi^Jk2u$|3n$ESs1o-n!@jb;)FjR<{KY5=``d`mySdQYfQsH0Vtf?jY<;P)XBy* za(8x7o5nJd1#XMd8d4En;n7lH+dJn)$4pJ6WZ7LNksnsP4j$N9cw9~~%Tf`IT-A6a z#X2yXV6;85D6TbF66Zfsa`Z-ws4Qh1nm{h)6pc>RpHNV}-XwJkmMLoYU~qq0H<-MCGSz^t8_Ne}CGg5z=k&V-$ z^JrpfaRW18Dp~Jpm)_Eb!2(oq%bg|aY-2YY$RhjzgK;NWD@K~pgauO36Iv5SM;vpX z&n&5p0DIGz{FzC9Ze_mxlUCNY)5zevO^s|-Cy!luv&lEBZ=a!9jfzOql$?VkwQ%Cg z5Wv)MKmHp!c~vs(4j}5Rw8s?Po`Va%f{Fz>UUZI{ChDbd5AWVFoL+%_7rG_R8^9^s z;K3%G7#vMhCFE>bs0sAt=DgsPY#vPlO*4t~4apV&BEAsq9$>s*%)i%?K|^6EF&aX2 zuh2U_@x+KGx*H4o&T{I2p?{OeeiM4b4&?e=YZi$tT*esiW%7kdS3aYszax@2^2Wa- zjv!^HxkL<6osA`osUTLP9jl1&87Cn33GtbOOg>NLq3|?=4@;mRu5YARYw1ZD2Cz3p zRY!{vk+TNcz|9;tz9x1r~+@@?zia2|Z3H_V@<= z5G#KS{Am%{yoxf}IEvXRGV!a!ax#&fPPLU`FmrUcAr2{Rf!xqw5Kl^u0`#TWJkz7u zWHA{5;j+3`D*$YN!#rrpdfAlUL`L0!u{CQ%Pr~7I<#8(}`+hzaxjnnTS1S;`#1OyD znHi0j8gy45sK>l@*D%A9+T8EQD}Tt+)o47Y9EX!EBl>9v`(HyDAa*Vj2-we6!e)6!&$hkHWj@q`!IpbU6b(O2~2mA$X7qT-l25kmOh2xRS3NYWB%c~bgJ0IKIJ zDij-&OO^F=B-hq7)<-y}0a6{6q1=zN_WH+~Ydfm=&As$1=`XFV}h(6rd5o zxy4s_%TZbely9shhg#}w$pqB4v_&}?Kq5dJQ6>$cSzo@RQhd?kDu$28Ro~Y`LnR?G^}$bw+4jTJWOc;TA|8tfhtw!LNmp<0BTvjYHp52pEd^R zPrJNiCVq_oe6uuIs;&Np^-E6(B6KQJaCy~Dho07++C@D0{CM2BQu%}q?1h9zV$oW% zNbXR(j4}3ZdE`}z)Ei7)nUFxjs8+VHCnX!@%afKO$ICb#BH((YKc|TLS4iXBKB}H& zI2!0nqgj2(BDmO7na)T7B)|L!k)nkmD(vE068YqurV<`SnluYjBisC1Z~9cxc&)v$ zBkE#|$)3T*m`8i)!A4e{rXu~CWILvstC7J3M9$NU96E&hWl~!3`A9fiZ72LICwAkn zAQQ+IG8@~5N3WOg$o|;_C@53YHw!3j7cp>YRhtAv1q4@)l4t%QOkYq$=DGOV!qz4U zs<7R2&pDOZOE1)Q3_UtUD~sks&)HF#)msE%5)T?9FH80ORX=-X zF5x!^Uynw|PK&1+%MYv`jq>KFLl@Lp%fL&tvP zm8j7xQ{>U(mfdemPCsZt4nM;hJJnSaA;bysA2TkIH1iKxahjYX3agUyrTZ0sw;r?F z9&W;x|K*Axk<1l;Ns$*ydtAi72qbkkL=G%nzZ0R?^*+AcS-aZzn59*K61_BMs$qA( zqK9x-;y09h45Sy``His2fgKnWVlNE_l6<`o;hIBkQsr5gMUrx$eH&tYRhOr z?DfMp|GFSjjz9;GIZp+u_qB)hV@2k}nnKz{ATO(3a!{}2<=lUukCIW_X8remqEun_ z?o3qL235fvb<%KO)CR1anRFuyRd_f&2v^$hK~%q0#OThxbJvr99UQ)}R9_d}R$Hg{ zdenFGdl`O#NC53Vhc_>+bMF<=DE*C)66B3+XkJu6j|Y!{4{LG2XaAB%{3W;1v@76E zkz=fR*iO~^u_5oo7R;0)ZBc&K^g_`G5a8euax&ThwF%CM7LV@DWB?FTU&5i@OiiZR z2|ee)9P3Ew+K^yhcp;gWF%SX<0!>8r%ppR#t_{r0??uPTBF;1lCtXL5e)>)@A|u_f zHL-B;t1|650YT~9IYkLzzn5jmUF|S%sJzq$ zLXIzfv8gX1`H2+1(sQvdNYXso^6(#W$b60$Z$tW+->%eRRM6tK`S`N@Djx0`H=idk zcpE9j09-7H7lD*rA57F;C2|?QC(?+yp})nD{nZVE6E<`kV{4IZI9W{b*v83YyUinS zU*SIunLBK*7_=dw)OF#>cZ4A=KjpBr+?aF)Upik1&jyi99Iq1SEqOf&QB3|cGyb~o zUGffI{=T@=B^^@`-h=GUe=^~3jO#S16yw6{^}la->XfykqaV|59L4 zN0OA7FMm^83>9$D3XfDI}rW;Iy!xH z;>mOpCJD5EYgbscx|s0`BjPgtF+{imFN=@}>Xlj0KuB^=I${wID6Wz!645Ox029El zpWF6>Z&Y(0eiwspp$Ufj_vY#rja|~v!}+|6|H8~_Z|?O3^#yTIL|tPN^}JVvGSeLk zJc?K}HOnSX=FaM~MQtJp}twkze@foWzt*JZEUVwdTemra!Z0r`5KR^IgFP zH|o6pzRA?;SR~u}*fX^{K4j+gV8w3~v0@t;V2m36FE`Kg;;>|eT_kHfB>pF`KA2wZxe;a9>u-*%$mjlw&!*m4DA6m5K{q|+S zE~9K5^yXohF8l}?dZecmj6=I&j~mp-V+q$Ba#1J9vjREud2Ibbo%OxJl2UHu<#%_BoD8RD!hCZ8e;r&4t1{T6Woa+@XldM>>AhF*@eP{eiqSUSm%)#?_mKRx|N z9J3TN;C!Xse(x6klyK|cOZ^|#PG>MN+L;RdX=<)4)t`S5p%ijpwDWAq9)-VqAYb>y z`Pn?tJ4S<(5ilf!VZ@MOP*|J-mNCP{rcj({#ldinMzYSb5|bI)#^@dDK@-Q60cWTc zUSfcByD#+=^fDBiw+C6E!jZm0U26B$q3)ZkmRmE05XM+R3!Am0kz_w)h~8y+yqMxl zcP|JEsCPJX%~Z1s|0|qZ$h*!8Ut>w=f*vz0x^-T&&YMb__;O)%VBb5i7S(UmaWHtn zy^7?M=SYO6yd$kSweH>**cxh*^sEXl?W5!VIkJdoSy1sZzLg(X?Rn`Y^0}saZh`!* zlhJ>oB1^@oegu?N?G!?uYW=U?6`#^Yy1-D9P&^a~pO+}~%-ZPf^l7SL#D3VoJ?^;B z;wbg?_ZOm{M3a-G?N!}1#}~mFbp~T$L!huu1`PA}%kl8xn=JmxNFASv2Kl<^Q`fXy z4+bcE{?xYL{+hql0AsAs9l1RVO{c66=pR4$Dg6D56fAg4a>Hl*M1j(H>XY9ON9lcM zk2hap%Z%(B9sDbHKF;d%{uhz2HYP7nZiHQqtcrZ&4u|a-KQ&~vfCiG1fb_dzY>zSE z{avLYe{X-^^SjThk9j!#NgoK;t=BHgcSo+2%DP_SX&~hzS3m)}N2mHib;T@rV=xmg zu!JGEe070@LI<;hLa7>$X$1q73u4+PbbIr8Q<7A0z)#w9|8ASFE|GyCSptnC05~eL zSK^vTDcYO7K)BLO!|A&V8p0EOCionaku`hI%zUjcuN^$pmR+dSM$##bIQ-5tND-S9fn$lNuzEMx(SUb)h=7i z4sME#(SCjJYg6HGF}LV~h+%uRK+W^a`UVH-nkiHQ_f2#Wt7T(vp{B`PP^86H@-F#w zyU9FmV$D^DNPD-8m4bq5=8|&qKb1Un37yD0Xk=+rj; z&A6h*R`$^&!)NE^%-B%Dmf%s*Jjm_~{%I{3(8BU9K}GX|ghjVLyqDr=3NMKadXJE&I_s9y+h{98jTrbmvT5WP4}m z{hd`_Kh#vNj!9UVRTQfaig8nYrTfMeElSQHIpqS&T;z2EEIdQ;oja#+?cZJgUF^FP zq>J1tB4O&_TCpPT_XVUh5ualJfK~0=yvJb3{xyj)`*Lqh?!rEpT8)-3%#SGl8vU)W z=kk}~W@4=cWqHK?ocXVT$OdTQuKD$o=^hgl*5iV0#Uap-#%;*&J+Qaduw<};opvJt8h){? z)T;-aE{B7HG~z9|&m>DDr#(g=~L4`feUP5A|nMz2EnM zmSm-uu|6d17tUEvS_?UK{|=G0pkZZSS+s~>?9zQ)Y$nlz>5O&ga^h=PUmX?|38j^Z zSOx`F;Y8&1K<7b;EWLCPi#jT(<VS`{bX(9o;|B^+~PHJh#!2-RM5vY zz#t2z+h3C`Nhe}|?j_eOonMUwvV7vMSJ_2D&yA!!PJc-AwagOtW}*+95qD8V+{Y=Y z;B(wI-F-iE!H2k@H#_?^V5c=(+b;^6g6J?*CN{d8*q9i#f^&)4+@31U?~O4rLzb6* z@hSc>zN#uIA`hbQSJIE` z$=awE(DfrsYiuM7h>7obPl9s7I@FM^SH}P(6Gf<~Vv~vD8OnzN1J>C>D$56=>++F4jT+SHExZ zx}>Q3DHE^iGFizUUdOkc(o)u;&Y|q>=j!u7N?DN)D6-(%k5<=!X-J$j6~)uDM87@S z{a_&tVW{;<#6A*IbCAel|8G=63|2OQ7=LlUfW?|f7vZ)T%$9yqra^sQvq|_SK{y^DNx?b zKM*ADhr{CL;d-BTR8@|@22fVH^yX^TJ^mwN!HLD3GF3qDMr2r(=gluLYU8PU>VUJ(`v%^9zAkK$a`c|CGrn1x|mV=RatEKsTI! z+8sx(#8m3(Jlgxc+h4j_X?i;{I@PmAH72XF^bsHWAAD|?V}t0*50b+EZ*V!`&s>3; z>XYDj%K31gp4BjtgZaB`!aeZif-^Z7-L{p4Pb-HEu3e70Wsyolp8K?qG;F%<>3sL^ zQxX3^Nr2AF+Y$v>N_*!SjLk!XDI55aJL5jmFuJ^WS&9P<+7W>UZTR#F(|rt2DZYNAoNiY^bRRDz}%CbcCQz4=rMXOQvCGyz)K+NEuO)SOPTLyrKFnza)U~Z5W7MWr`pY4}EG+ zL(S^dX(*A*(qHpsr=1H-@+8Zs$GzMAodQuZV`$4j-06dCSJ&{(0HQRkuHRrC!r%m`8W77mK0A8M}< zL-ZZ%C=*SpG)477)lrcgI&IxpK`Vn%TopweitnrguQ1T1+q5;WNNlv^M5LHalc+%lU^{ z&f|SZI5t?p0`nvh9~El*+eqs45@17tv?fEi0&b1~@$$RKhbVBif6`Faw(VJF05wQN zz9#5Wpn`9l)@xo|fuOQM4fCoZ^+uIDgA9cWK?xj?fv=`5mRU9mH>j4KeP{Hb8c7qB z!vqiv0IFX=@69hzqlMg_le?QG*Kt*33Ix=iRp9W-aO|`dI`V&NqRM#6r=KG8AoFe@ z@aJ22tTa4(LfprTarOmALnZ?rfo}aZX)8IqU}k(ropiqx8XkD z&2DX+I1B-9ysP`pi?5Yt%vX5V=7m6JMKjmE*y-{g_(~&NjfFgn8DHtfZD?Bu@;Dzb zLHZ_Q;x^JC#{Ms&U zrj$XKs7!2?pOL3Z`9&5N8k$8G29s(=Azc%@F^S+(w~~kRXmcjSXBO~_l#QuHtK&*b zCTdUTT|OmD{H>#2$+u1~!^MH{?)?PJ#x`M&Y1U&D@&Q#3?L90zA^$E$kv)eMS815x zUicVPe|bj_S6x|uR!`Z&omkhAJBM~c^>vJarg-gbe4q;gd{`D)AOpWUMfr20B0V+p z%wFroemCFTK63l0c3UCS+bRq6eHn`>6@|rG@Onnpl(7eLj;>DVH>cq8|s~b%Qfs%ot!G zQZ^LyVOK3KSJw6rDqyWOTh>lj#p%c+^}~?El`HI zxebpeW$jH+{WUGhMO_g)-R*ig4=>fN-kc=j{xmln6qh@Mh4-Wg49zF!L=(uM1A_9= zn(L?Ja==h+IIr>2sEAhl`NxU94%bDI8!&PfdToWMc~)wEcA&er^WF&(dDNTy+2H`C zs*NjlDRr=r@BMNPHh7KPGgQ*4DUyK#%YKfoq~iz9N;_2_J*X{mMHVW9g&CySMMrC* zB&AFQ;#PCm4gtw4vXnk$%fQ06@Ks%XyRRD4z%*i0tXq zs4D9gs_iNvYq+y*huneTeG>Oq_C<*6W>H5*x(|1~3&N(yc)j84Z& zD_F=}%#aE#wRk-)mow?DUzVWFwIj_`pZ1gSvqu|K!S8tLZ9;r?oy>! z(vh8v8RmKpW#O##dJYUFGr zeWS}4x!zp+Jp7t(an0(w&&-2^Q4=@#z%bcT`vMX!40t6qxC=YjxiQiwuy^9>{4oZ- z8{G!RBB2fd7?4-}KQ(ED94rY$Arx zW8zSXc;vx#o{~0U!u)OzsTfNSj$A|~6HYf;zaB23w;*MfcpS}Lu~|0X)M{9U54=|( z#qv=TRtJf+cnA`$08s3cd8W}ZJKtdsYn3Ynop3+lnSEcWd8edj#6FWYi zADI_deudt(0nTX!Jb?Nqj^OpH@e%+)sZ7~zgzpdzZ7gdRGs#vkpdbG_qs$} z?oLJL0#QVv>`1wTtiNWQ{s2eN^1mVuHQ{=IZSo#<<&4Z5*b@^UWS-L3PfJZGjBI#t zUMVb?$fxjvo#H`vOLdZImRdp`}cW>1tWd7srhyr?%ufhA_XcV3d<7Y(DQCOG-(!PnJCGm+6$hpqc@`nb8zArobbciI_Dr&v zAcF{0gb=ruv-G@0dBNp_qF~>86;hNBGs{49Z0t_)#ZtIB6BM-4b!=zkq=g9UR_URH z@e-%cdQ!F%$3~ELbs*4JR7oZ410L!vCSmoUB*h4RzHu8}J1*PAgDld;WN~fRk|sG= zUyKm%6oCleR6R?yJ(4);@ucLI*U?+PFa2;*76QQG-41O1zH<5I328Me<0o8Qk&yd? zo+`%z5<$b|_#Kqr9Y;k90Qh$S^mc%rh&KpVdZT+;TnHEoxPJhdgbHNcZxOP}KFOo4 zmkrltFMRwjhWh!Y=;osE4*1i)Pl!uLF+vcQshF1A+}V^K7hOE^X};hR@*IOwe!@}w zD+LIroFm7gQv5+f)1|kl-})#(nct3t>)Rhg=rphLnp@u`Cg8c}rs$~PGb*RMWJ)s_ zm*J~kuKE6)g&2H8xrL@KOG9M{aT_lnjng_!L@kXv8&-mC&mV} z3V4wHXKUN(XFZ^&yPg0a#{aozUAzU@jk+a-9@zdBCF&#R?QmY|GYSb|Fix|w^V#gY zYza=u8E$D=zAr-*SsKMi$fnT}VD(M5^;ouTWPT(p()QvG?eGkUOJNt6Vt0^d&~l6| zhdM~@~vbaft<9i?GV0KSLlnL^AqZEZHvaZ%hnx2{YZ49Dvka1&Ym+u?gYeI;QvIm{)gZI$*2>87x{Fp(p3W2Xu%O> z2(F$LyP;n`1(R|8%Cy(FEK?<6UTxgL_*=TXCdyn5RVC4>b6LcKzlIc55P<|ToU{PH zQYloEc&jpp(YSjwM()cSBBkQ2tKzk1util5yy3J2SNL-Zt*b?8F3DcAdqDsoTD^njVtv&fq3DHRX>;dNbEshu;%xvE2RQcI+G{Wyqng`FTi{B?wcz1{gz$ zoeNZ!S1tN6CH7J*Qe55=?&q0`QTh6c6QKak8=(pCD=LHb5`4Gp76CAjjST##M)U;^ zfbnYlm5Ty>iug5Um_nI2RBZDgi7|uCF1FerBatMGMUVvezF>vuCTGdB4K?}gTJ=km ztRAsWEpWY9!mppIrCIg8xDXqxO=vKc`O60DE?`?{OOU_r)JCmqaCpZ%zPUUeT^D^t z`l;maqG-EU+pWYyoYb#c>BNGG4g9At{qR0V(cG$>{r!%JESDl?^tyB0Id!z9OKf|d zeRZCqn?I4pR;;_Kx2gKGWk`)Ao_Kc`NzUx+6lX%TkLfD@u3}=k|AE@{N~_NsE;s*2 zf9Ry_l?4*%rCE}mt9mgZ7o~A^Z5B$lnAav&jKPdYpc?EWOpXWOjug$AH zdM)p**-toX+81iLjyI4GlIl(s((F}N-zuXe&$AE2h$ofIZ&~-9UN6Z(rOoriz^TV> z5-B4y*~oJ$V~}(mZ_<()s>zacIwTX?sFcOT^8xs!nTDgc9qn8O5TQyJ?&Okox> zGY6^aloM3+bAJEvx3+s6IS0)pJ!@vvZi<0t;s%kAl|QcDbWk|xT2v1O>Tiq2>5Xcl zL&w^s12k;TEn6^%ltUIEFhGv-Iv~+p`E7|c;~8t5a?Q(VO`^(iArF;?l22DMbPfI4 zXUSsMqOw&~T()@C*H2E2Xq2M=Jo+H=C+>xYxh0WVO$lRfuq9v8⁡-6*a6z-BT$% zU4xv|5{p@++1LCe30F;H9@QS6g^xLYBs`lCYQ3ApZ3Xcn2fl1KPW+?y8mi^S>8j}kuEg^hI?F1PQ-9z2y|?ed{NtL7_vu=jW%xS)6FqZC?az=ApiwQwdy0kY`!s z3?Tw>_lekiD%;4kF!~Ud-sl+ex6z{ii-^&oDUUH(Ap2KnzQnT)lpoPvG~L!QcR~oS zjV>|t4&@td)ARokh3wz)?V*$;T<>vXWrkFl-Kw^aB=fG)>ho1h%tHQ2$4E!b9<+qKv{ZQI}Erf3Zk`bqUgmtS;T@@9Kb`y5giK4)@mpM zRq;HJ9aZuR{<=VE>+4XCCpI$weOwmrFLgYL@B?8&(YT71$!4|&h^n{fmqO^-ex!=@ z9HGb+Y&b|z_)l6%;Ov#27k9jSoiaK}Hs>rH3Bfj!h7&6ylszudka5%tJsQY#gA`PK zkmPa?flDP~U9V=a!t2?pabzKNVw#}z960(!LW@z@Lsx?KrqN)G!>Qg_Xv zsOr3oSzCd|WGqLE4B?LUX3aFVxLhmf*v=LKB7h@{ArbBEK^Fu|kC4tAu^2Y(vZO zF&qWY_`=UiQ*@TeLAJWSw;L*GqRs2yPkoA7(cF{7-i0@wJf}h_@IHzBbp-|t0zkM{ z4I3feG*QZZN7~OF3Vj43tW;LII8Z(EvSq3J@u`U)9 z-8R42c0leR>4JFaWOcp`awW0qjZ`G=v!2;tKZukS!8f==Xy*;;v?@AEDYd%Jd~ON< z9}N?*fQ45nf~&&AAK83=Cz-fyzXUcJ+fs4l`_CPzns#ZrwxRXv>=i-9s?NT6H95bc zA*3qz2uAq_vR5WR_b*P-<$u}U_d%}EblXq+ggL8q$bh#~(;au`m9L%;1Sv9DbS+$!zSh7IQ^S3H0#jVMl|6&BN+DU&+V}=Ltt3P>oS=ATV>Q z-T1W-eAX^91^a%Xro3c(Zv7eNUf+t2!y$5lHv?)gwqo*I_6SUoxSpw=^&f4YJpWIR z8i5H9ae>G@O+ad(oGTBQ(V*-er)nm!5Sy?GpbqaGwo(9$5S&dzb2sFaEReLyc+Sp% z?JC~E46zjeQ9>tOEKme>&+G$yDO&Hph<%JYWTBPmnT6IiLuOQl+|B}OD)zV24%^KF z{ZS^4>Bwpt1T8d>=>_VaT9gt`;EnZVaM5qxLa1=PpamOE$#4QftPOTBo42!}gPh{y zNmCE3gZ zZ`2fFBd@$=a_G_~J;0eh=*`<{UIC0|GZE)F6oU+^rDwg%K}KL%1Z*0cjKFf`J{z%K zs(XHx5Z$2zc=$`uL6}w$a3cbu21uC+82N%IF3q)%p!Yuk)cL4<#aJCib*uKoS= z+xa4U!zd?X%m49C-CuB4fk=S-G7)JwRWdk~3_cPEw(+yoic+)imBy?hPXQ2SdU|kH z%<902^X;WSk0Wmeh}Q{#n?ihWsij7KEQb#e$+VaL;gDta>t@MKe8EwbZQCe|@Bx7u zsmGZElyLa$+paVG6FIIgX9#S;mdtC2ffOZP%}BsAZj6L&?%a`U!~23iprzrp?CTKI5wjU z07ffZIRbM$LB*JgEq;HN?0X2wn#dv_my~# zYWuWcL*Z6$jOsM$U`k^CF^$;yfE|j3?-OPz*0`*MA~ryVOwz^v^qE*=!?BY#Z`DA0 z>Qb-!rIWYROvfNEBf%yV2&wdBcdn(7wM*em#U0^^)vw#OyT{M0NmZUps{E@(_(UN5 zr%Ldk6ctiM()-+4@p7$=KzK+FV?(>Vxlk34`U|R}&h8Yuj~W>6VmI0AYK3E)3^;&0 zk_kv+0T1r3JR11CRKrv$NFThzjujXEg`oBzL1Y=fC@ttCa}34)fg0fmq$cxmIw%vJ zCJ4>u;?zgssw8Z^gg(Rwr;%?Mm~~pG*W??s8uSG#?&r{IjwCa4vF2q9kE~+X)BqyL zigy0GWm$<9svHJ={yn+ejO=P}rKj#9+Z?8s3wfCVw!(qALcH~~ZW)#{k7kkZ(MT>Xs3J`!lbS5%PLxDo-8fH&pL11s3fcY;*t@hWv_#`S7s#>P2TsZ!^6 zFxyRXa8^3~5#;a}#Kd}gU&!9Ka}oa%L8ipyC(rEDTSCs8wpp*7;RHzyUhxUc%;nHY z##lBv3F!?A+ku&uUy)wbgjn&yyuf8;gUNziK_GT5+#jz&ZsjZKN7s3Rm4bsz%v070<6Q&BN_dH;y}hx>ERxvnrOBh*O>D^ciHK){QdXeEN?^DEhM{jr`#Xn;^WyB5!r8b@K5G!% z!p4CjkxDwupuzqV=jeq49|fMP*`zWq#04s2%tevu_D;f+rF;|lN&0tYrM=MfiQ5@2 zA7&?XPGwdCe(d$i#HhNE;5RTYes5k#Wqb%M*n)gH4OHR7{V4g;JMnee1%}^rd{!&% zsIK;u%0VXD9@)XbK{1{5oN#>`Kq^Ow2!r03%x-@hT7ZiW`c%P?eon~=_4=*rbvUOp zVA1g{kee{zX`2J7SO6oa$pb;lb|^Yt?hci$B%4jhp~YETdOE=UKziTaD~KS7sb zk6io((RyB&WU*j+WbHaf2#{8zo?C+MUNFK>Ks&(|WM=(}#iR<-xPt|jOO8i!u&|Ey z-e>V$)K0g^Rv*ny-^UON!NQ5ErGeHzD23czX);)-QxvrcsqR?#cBXUzA})yQ5*+nc zbi4yM(4A3!I;pmoKB5c1)HY*H)>qiuA@Sx^Wlp$()}$hpirgKcyf2BwPuv@)+xM$=dsh&YOkS`pB<-)A_`ekpMA-ELG z?^w&nDmIvepVB+s`!UW%p6Xj3FdG9gm z{+9YL${N|Qvi8_}0!=%<5nG}4=V!bSzl$6Nt?ExICr2^{G3S?J^b>Y9t|Qc%`nEO3 z6zXnmI_4PXw81{N)aJf=Iv-asI<$qzJAFblSVjYWNb&5*L;X&P|D8L-W|?PEs^<1Q z5oW~ym{q3ZyNV_|)5aC9%I#E2e^PfGJd#+bQaE!ZA04l8!|w!ku~sFQ3yBe^AFBaR zJE;ZwTD;F4zB8$&oCK!fj+=CN<*6Ea-<0s015C(*gnpN`><9MuPx#(H0qca_`m9BW z?r>1748-rqUxGtFz_kH_aKHrB2^02^UqooSvF^_VpHlmHrKEd@s#1u2&?I5HVb-~f&TJUPs;&+F%^&I-dztN2 zcqL@xNnP*%M{b)Wf3={Qt+Ii$DxFjWQheC{1SVPzmy_6m(x$bsRtCA;+d^jKkMc9NzTp?+F`v9%xh+2VMeW@4GI=1g6OAGkSjjyqu(?+Yb!FWl|fNQmhR z-1E>vt$ffoX-Cy{fAXk3y>mAKXn7xEYnjosCDGwwVsD)^^3+F-t=IN+r`gwJJuac% zTq`&M*F%S}qfyzUIyCa(X)r};B0k^l=0k-;w~h)UusRuRlp4_KD1J|;^swKc~UPk@~{Z#YDbGU}+$R|*B z?`9qE#%Cj|^iScK4#cdZh@=dUwp_E6PWHN}&=P+39nr#Dv%jdJ^SH*hXiIprv$F1~ zrnL_s!irKRyf7LR6vjox0N$C47eZKTZja?^E$dpEV1Pg~eoZIn`KG8-d6U~Oq8n*v zZZ}jczwG$o&V;_?fV9`3{l>2;n45>2?;Eu}Kg$F$gD};K7M!>Uc)t4cr=}EkU_KYO zT8e|VKe?4XKYjmC)_*oSzvSOO>0jQjw&~Qh$mLJ}*3s{kQ)rbzHfy}%{a%fQz3ua_u&2U}sdmLPwb9mO~$Cy2?GW&)=Moz8D<51N}(m zB4JN$WZ4K?Vcn?w%0tH^<%;%)f+W9K#IfH|(?@1T&SqdfDSBOHLUOZ8d{yH%XXZq% z1C-2E_)K*%md*b8)i+}iWL%m%z7Qo%1Il`PKg`^Ko8!27!%Ra(XN zapS?I8B4H`liURmi`%a;hQStzJk%TQoMXxA%R24F&w%*`U7+Y#gc0_-XcXVgf zd)GA~)rv>%_b@WG`at?mCU}wLVm0$#&&T3aQP0?$#0nR76h%v%LAS-b6V9!Twp_GX zaJf9%dI1fPI+L5S`&VdFp7w-|khTo*hoVsfN!m9=QCe(LrLmcf_x|ikU3wr;w%`-! zUra~_1D!C2>g3Z&Vim2Os$Jf>3~rU0uf$4vKEx^3GVWZ{p!-nhP=6eT#=wx@>%sn* zY20AOz9uj-mzCi5fM zb9@pxjDbxteN?dQsXCu8dl^euqYLPW?D>zx`7a6IUQhK;mFGzp=9~dZtF$v`+eA{G zn8hNQb_~xZXGJgYiM44~;V~)Kw}=B@0*2))$Pn=uUShtAqMbq#tDF#%BYB0o?wPC2 z;+wj`|Cqicl9e}-Mh~(neZTiHUc6}d!il0WA?S+>e~c98N`P+gWYDI58xtPh=~;Iq zGwPkx?Fr8u2ZCDq#kbVY`p&iOJ08c5mkciq^1ivG^cM5bk-@LIK0zQns}t4S#<(umy=gQ zJ$+C+u|HFFQLZh7i?q<TShLHgcN0{Kp_Lp{K=sCVY&qq zz^xA{B-E5d5or+b1-b97$px}6V#Hoip~x&L!(;7|W*bM~VdWvc;h&dE?p4S=tvzs} zLvghYUs0KgA}0V-gOpZsK4Oor-p+JtlRqxC6>=0_ z1T0s2ZMtj}JeSmYv=gSncY%3?yPt)XnC(~dk}ufb6`2u7Tt0k}%n}W$x}+7=kDo89 z_7sySZFSh|w}KWMc%p7W%Rl?qDY;R^SLY#ar8f^+Cd>Huur!<6LmNGp2=x|c+inSlk}d9Hv_GKFlU3ch9bguO^X{yrV}$;ecbCj9-0o3-|X>oy6yyeY-TosB!#_ zV6tn4(x4{1?Z#=XPe5))1`jx%pQ|{5V=w=muW|SdyA~q?cF7@Vv-}3)<+qc8yl@Fd zEnj`a!%;a@c--SFV5K^*G;N=A_GC<3xaPg{zGFitUJFNll@HvB_z>wye*kyjOwUFM zlf0>eo2?{Kj@b9Fcyx~L-ogMUT40b~#HyEj*#NQ>wSA(%qKPlW+J2zQrWm zt9h8Ry_6iP=4+~&Bk_&WHYNr`o;Q(yBb0PqcTtv@ylLqDHnqevXZ%la{pU;KSJ=Wu z(mVPsv6!zoD=Gl3C5vlYyw|zd$-yfK-06l+?v@2XWfW4d3oZFVdR6;TosHc^w^Bxm zM)D)I*KRg%&Cm9RIeZ``>@M7D0W_Akm}Hu#TnQ+O(%FDW#yIS*^3g0fDsRbxJ=Rw=cej$~B^PhC5e)&Q$AO8PbCty?3l#`9h|oX9LJOOSr+Pkr=48K@4&NI$}jl*jct8)(ujs!V$ORo z^uIKl>F(3U`?P}pIETs#Ea4ow>CBh7NK#nQzP0l@LE6&oj3>j)@{u%932BuPk~JIw zy^Aqz$|c!qC?}5DnWakblI9yn_%495xMZVSc!Ij}6T5ZE67bMP#+ z*|V}ACOv}ZdWu#)cv#PmZ?pS_Q_SeqwZsPOr6tJ|(&0fy-x2@Kjo=Kdz8wtNkJ%<> z>3kFOinKt>my?0{h>=-`Don$oa33Y_?{e~=$jFZ_%B4>~U#>_jX@37{i}asJ?F;#R zIiBi`!YR>rOFPOp*}rKeyFc|g6pHq1dWXut<@st}s?u_yZ3tI-#fENo!gCelCve$n zHkuv_S`nzRc`$b#eK)Ym!*4x&J?Tn%G69x3&xZ_3r#U6O0}o--ai-J*CBNz1llP`^ zHY;A|BPYCP$1`OA<-{5JKLE7XKH&_*&XcYSE_tYIo8|C*9t2kvC6QIZ>n5XS3;2^( zb?NG_Ggy`s*xoL?2z9|NGjpieHztHRRJTW-Tx$(qQOJk> z1#n}&Ne<*tUo1Hq77J;uHn9{cO*gzKrM%^7H6_DQLG6&i!Yz4obq^+;!8dIdC5jyb z!F5m%fW=3oX-E2SxbVovJ(66g9vefSLJgU3z$_>zaUk$2-S~Gjs3HP;Q@}k!NtB9mV;Cl z*S5~+q=tM=Zlf#m688mN$1f#Iczgvn&17;phffLs8rhLrj#^8>nWuuM%S}JD$v0XX z_izy`_Y}ppXsJc@HmYr_EF49ENf5wVa_(JRB6dI0a6J%gH&M5S#XGaBg|M-mF2Bm* z+M-0obxp)%+Ep@4|1CK74Y3)f-5J(AP7`PF3OL-H8}y@(<@cT>r&}CA&PD=iOu&T+ zIkV!p%bH#*GRzN7u%Z~9?%Xh3(lQcoG7o=4xKWco=#X}-TfO91g}E1x(Ip=)gNg!F z|2*jb#oPf9FAqs!FkwBoPzDuRBg;{qmn1R8GKDb5jlwH1kL_liVY6m znh5Iz?0YC1=u}*wNebx4EEB2;C-`-3B>(& zM+|~0jbsv0Frs+eTjdf!s_~0dNfh)wLfhX<BO-ldfJwK%LIj zc`=irTzPumInymiQ99LoyvPN2MY46}2;cI^g0W+;aBQ9q${|s&GN-0gWWEOo;wKY1 zl%xxx!LuF`&nf#i-qg(=!v@OKg>q#3I_memHJlaH-3_lBi%S0^jZI&&im~DahZOTG zH;~@rrx*gU+3p}3Uwq~$E`e*%m_r!qJ3B5cuzu={Awhtl*eObQTEniBd`2Eg)_}De zmgXha#@k7T{Yt9jfV-PFJQVjMDDo(rH*ipYb z3iA%ZDc*$v*C>%>K4@ zW|nJe-RotG$+o&eKM75;BLz@%c`g;;X(@3Yt@9<9Gzc~10yzCtR;OgZdkuhjSmRk6 z!HJy!f!EWF@_VWvkaOEbb`SV41AWw^_|PdHaEMvO=2daM+eOTC6ra=Ivl$&`QV|B& z+IMzN$q3Oix#!J0Ct+q|OOjD5Tt1iMTaMQG0T8(cU?^-P_`>=stZ`I4L@0@+nI#FX z9(CI>;nFjR*nfo+40}`ff~Rnjc4$4iN9X6p4$oRv;yq0F)Ghnfk~IQvp1gILj+uQpkb!I$sTJ!wL}d5zx+G0qX_Q zn{~BPoh0)Fm){y?XJ{w~A&i>T$Pplj*Sc04gU8?ouRGxOyR8DX6B!-F(n9;lyJ!Cs z9KA`svGSHN6^wBi9Ec2bA7*)^=@)*u2KDr`d>;@(-i-+bF;r)*8_SYuggbSuFdG4Z z`wqPCLzM*RcZHtEXKNmZN0(Y`cr`lfmt~-~K4z;@!XL;3+60|jUA^ov^;2Z>-?&kf z4@YS=jm>m1_=(ub+nMQOf1ZwEJp)8(DC6%(HILy^X+V-QI^f36LosFwAZ!Z+7W51C zE26aaxk7}z7y4fCp~$gmdSPk8SP1}UuJl#AUvl-Ay#EaIu?LeePs-SIC;4h@o$K!W z0lxcws8r~B^M2+H0-|G-$>1VN(?PO;iKS3g&z)_`5tEw3Xz@!pWTsio;ost7VWQJ# zocwOkZvEVUdDaE0cN$^R3X{TJ{6qs+LN~9^#DC?z_lpiWb@=}Uk@;@}_(EWhVIYTZ zlmS4lFb~h2LzgRTh}}0p_26_R=Oq)z`@6$4YRq6?`r?@ZA@ZrQ* zr}7pixsPX}-4Vo%rJ3sNd?181fU|U6z04aeB_i`)e(&R_#6JaR9~q9d*u7Y>GL3U` zo=Nj!;8fcP*+xN3*8+k;Xic9`i*0~9Zh-RI%sl_3Q2k)qLdmZRjPCB)p1cRfnQ0=U zLNoK%XF3%J?3_r38LVu}nazSY;ZSx6BKZdE%!{*8)B8VO^?2MimzVfD(XvvzsF;!`(H4oO6fTR$b(1RZS ziI}OsK-k~75;9B&FyBidPUfarGGVQ88E)spl5$R<=cYK+&@CO>cHC^c7PLZb>0)Gt zo(L6z&#gIE2Q_l)1C(;`*t#PSGhw>KCk^Fo3S&2xQ!Ms-G>)Hc2ut64n0QLXyGfLwjUWY2yk6Vd9g(NViN-5B>ck}Cbnch6ED!|lv zvasN!T?MEkpWS`&+f~dpw3n}kub1Gv7YUc{g8MLw`ixaX!-oC zt{d#1hkySkQ0r@UHD7f5c**8C&0PCFnzx-5@OgX*oH2tPnM08%Xl>mwSx&O@JUgbp>W zKGfy8nE~(h)wFSwYYQo(`~#Uk-*DoHgHVIx554XE#kxwiBK>>*zbNldJJwj=P8o+QqA))Z;avo&!dK6?D%*-Ien z2qyXD$Yugn$~UtS`Gh4pfCR7y;8)x+=_~y*i*4UFaV>J;;6*E{X$FY%c{1ei zk@WD`1f?AUfj&`}+ZC+@;#9ARjv@X85@;h^v&SKPnAPXN!T^~p1=#(To$iO;%$n&# z5ummmgO$f-+gRE#G9wb$1O|y!!Pc~3l{Q02$bz-4^LlpCL=>o zj-%v^ZdG&1`D58y*l62<2?oHFBYD&Y_n#B}+n zyWFY*ZsS%tep;?|9tU0b)IB+x4AK-byO_ zS(Z2FyXjtRfGjXiN?Y5|uMaFo>9#-Kb`q-GwQ)ny_$U_W8K1xH<;c1~Hac1h3;Xv6 zL2uZLWPkV-(00`_?4kBVg!Y$Um`>QipDo|=@uOQ6QN;rkL~Db6f_B-hp>}^8B#U?0 zDzHXSxYcC1`S0-kSBBD2=u1iXuRDHb%oWSm?Oxk)VQbQ|9s2mwn?_3v{pIC5+(hR^-Vi9+HQP8QieT!=AWoUV|j@mTI1N(uQ%>Q*^<6f;C!~lYh+fkYjPf8N*rCFFBP_ zDW><1n?r||4Ij?Q%Sf{9x$Ut0p3z{Gmr_Jd9ou*4RVr(4Qi{~`0dat6SBn!Px|T5k zXiTy9w9kQ)b1+KocisEsE%&_976vv=7fhBlEeoYi|INN%sz0^v5$$lpbGxbSJ?O5E zUUByib`_uf-h{D3e-=ra6w^HPY7U)HBW6<9cEWx?m8z)PPHWJvxe9NKJ;4r4s;ck* zb3$mi?khY`)V}eIsiOVYk7k0J^BChvVStyO-Frlvd-O3v4#OJ0IDAOE-nwvy^1p#` z(smUEa&j$;;weLL9gsXKWid93+(`Sd+4jj3wYcaLh6jUTPsZD~_qe*CBZ&sgoNl7x zd)*J}kD*k9gl>4+1E~-nm;2NAanB8}xN?F*F6OmMYZBe|#XAvEds6i5DyJg&_TLJW zu{B@qY9P>mvAKRk)qj3(TAV7TM&05HOj`|C<#O)M|5lpe>s>gC|D=%p*eo$tGT?=+ zk&~Fvz(`*Ac>X=sI_`cBXBhjAm%iNfOSp>JX`Ii9a^j(pZ*(E`kcFpO(FCNU2QH>dEb$O&a6@yhUn>=0#zJk7#c zl?9~%o^$wEu%2^=Uk0CE)|uf4Uufu*TMwygcdc#-sTV~0PU0G9qipWB2u1^*K>VkT zKDL*DuN2gYT*Rp4A0jl+RhgK7z}5ITCExiE zOeX$w@!@smhiN*#u zN6dy)Lug+L&7gC{rg!Y>{!*rVkmxF*(ikeE3zzvv4w|X=lT)KN+M^rnT{?s(^Nw9G z+3-gW?-hv>+@kj3^IY#TmCmkywQO-Dzcd;VoY=xID{9?CE`A}O349|tHs^LlP5E6scCK#y|sasK#z$dt=^ zQ{%Ng!l(~#TAatUr7XdF;s+A%1zSb-nRSdVo4LcJd6#kArf?Zws=V|Qx`nnNUv*C~ z=(E{=|sEN)AM1>%OK>_%;1KN;Uzw#x1)Ljtv&B{#l|8jv(t| zqqH6i6<-GJW({pQbLqLpk@|s9du9y>-fF1Zbp^<}i|u>kp99DjH_16;6gvXs1!Qs4 z>ssM?6hF_b$7MC_idF_l!F;bU1u~4IY$La)?;U)_dkIPErtD2VBA)AKq#-Fj_mY^w z!xiO!huVA%#riXI4Wq@-+M7l71LaV|iFNr4*>uTtr)~Q8zR5S8Xbf&Lt-Cd|z(?;n zrT%bE3HjJrH9e-o#*mD?m}b}2D>%wI_-!us$$)s?B_rZ(SG0_XbI@hK*~y^YFm+JT zd?1!74?1zwLIl3w+V8q@wne>GOYf0=l3g)`XMb5^!v##m;T)0e&W-Bl{IgVrqd6Lc zSKp%bdskcxwG&^uIuM-W{P_6uT$XpcS6F2f{G5a;m|TJL?fK`Qx5NU%r{x@Nh{H6Lmusp@W=*4coI+8=M`} zQixgnh?NI}<)n6j&pRlf9=KcX1RGL!py7GGpmDPkJlGe%D!uPrpE~ftE&il8vTU$y zN5*rac)EQ`O`TV`J>8h-+YuGoAG$}ITu^K~P^$Vt2o{`2(_PAPG;7x-wH?JJsnPoN zoi(`UlllIc9R)in^)U~refRWuUlQHB<Evx` zqJKvsAo9P{tT|uN^>-I{hXk4h+g~&S=-BWx{>QI&RH)phG0`3CX-CC&%6jv`ZQCO7 zrQGJ>HVc>vpGUYQ_^EzfxMnj6g`D9#Xi^Y8IB( zmRDjIc}AK*0f3(Kc!Ip6>fL~61s-kghpgP}oD9O2 zwUSI*7?J_rD44>}x2jGZ-rCmao(lXnJX$RpbkE+rV@p}>N1F+VPNH4*$5gt=Fm0}^ zA{6FSM&~enRiqW%yDjx~g2R_`7`ScLp1D1Mm`8qY*b~cfxZ~q8gKiOdnTl{b7W9ma zMePsj!clW~Zto_9T=kC(YgsmniszVe7^BCLjdR|=F zP02BezLQ0PYV!P_gdCag$YEH*&t(@H&ZXTvfL2WfY_I!XOUkqMx7>de>(0YQcNDb+ zgKpR1=Y!#L9aYmEMOQ}9$z0ZC2Q6zU>G@oU$&W3a*W6k@qy43rr*k!02O_nmjD$QJ z2kO@Ep5PuTn2Xf7Mfdc=$-I}cEqRP66e7V8w0Un9c9?xN5-jLC2u6aI9cY6N#kbRj zE8z7~#cnltBCHPH>Dbz53Z|zj>d@>=q42X`^wiRdh^P#9NB+Y8t$F0YOSy7v9=pfY~e#**%A<0K=_^M88+dz-o4g?subaz}qK`uXYx+D#@l zVU@KMSp7B4-OV%nfM)pOxcz%gi7PWZ9)de&))hnM&ZvAZo-{ifXP4MTQ@2mcZ=OcW z_}M%uWB&ko2?QR4jMxJp*c9OS7+U)nzRCuz#m~s@jM9hO=EQ)xID?O^@ppupvt7^@ zxT*z8s`;s{T3ORydB92J|Gjg|PJf#NAaue{^@W=*VI83;ZBu?sW6=zJo=DK1g#BT{ z+NV5_D{>NK`S_-miCFZ-w>vP@<~z8c{t!I`9e65(#dNq9we0)|?C@?R`9jYozH#_H zijH4Z{Lic9nV>j3yUqcM%`Nxd$(2d^h0x$hjp8gG`W>8rBzAdipws8jG?7?V3|i$L zsf7-|-Er_^YfV3n!zLgw@lxfc7k&n#7i^@ycgP&xRy~dQZVPjCt9K*T%dOZp zCSLi*q?@0|X-fg>&RI7*!PWAM^MZ?>(m}3ipm*rDeo>HTTAoYOcA1n`<0R|~Q$zn6 z^x$y?&%&NX6h=x2xoV|6XrBJU`+~;!wkh)?e>~QXO$l=tCV_f8k^+lM;A6SMr2c zR_8h4M6Wmg8vn#`AGIUXM~qS~nEm{P4xssb;X87e=3>$k1M`kCN}cmoZBaTYr~q1` z2e`b%?BdGCCE@)|rR?urwQelyA?(~Q@2!s)OQRlouC*aIkf%5tw;f4EIH!Sk6x<)d z#YXM6(VG=jI}F~m!@JVaOZ=Xz3mR2zS9jmkcuK{*UN2t$J604GCsFcnUniNNJ5|NmA;2ur#^dbfUKP)v>;g*;@ zz(e-~icL=4D}BuaW7`d#9fk-n-m?0(qnpg%yk0W4(_n`(0GO%_RVErfuFL{HCv27bV)byps<*1KefNozGh)C{ErZH9~uPxxNRO(9XX)B9Lll>K-`4*}sHgto@jt)LEu%GK%a0?iYlO-bx79{#ol zq1feI53hehtNd(v$pL&|QlEp64{<;PlkonV0@gwY+>PSqb#q9?t>5>8VYB<#2 z0TCjLy9(XEX@zZ_>d}X?D#VW;LM3px5JUhP?qj+LocrWwBN)}vJ_h1wBhw99&`S6{ zI&6#RwnO9XZUC2|Xf;2m#_~zAJ&yfudclb>{B%ode}J|X8|H-v8duP#zS>sd;e7|t zQB8oDlpH}QEzU$wBHwG*5=x-IaD5idPVMNRG3N&Rb z>w=#&Oy_$&(vL^UNCDRdVB0e5_qSes-N7$gIg;Z7g7m5e8Q`q-r6={AVTPSH*H&JIw5>s z^TX=KnZ|>gL+6>-I*T7|bzA3E?~!4IidT0C_O?k@uH%Kc6ySCY_<0*xbQf~zeb8O= z(+p;@>{|`qr1j90`WiKDBU52dC3=z|{HhsB9>uKRx=(mHRy%)>V_%bZizN3Cv6pha zJX{jQ0k^f$JLzzH?)~k~`;PwY-8(8C*tH-e`-P(^|AZ4PdQ=`6#ltxu+s3X{+G3*t zO#kMhWH>zGP)4^0+x_BMSxhD@96c~y_E?`(5hv8`Fp+<0qZ ze}AO?ZAEs^DTsot#_&Kz2*SvBOVZnCBH^<$A~uDT7z3b`Yr6G2Nr^6c#z-?^T@~F% z+7c?66u9-lr4Khv`Wl>Dw=>M9K6H^kYC)l0lTz6i-mCYKkNrUuM9BP=?jwN?=8w?I z?)-DW5`zy|Jfv1Z0X3y`o?X}9PSE)DD+__umJRGIQ2ohK!9w9ugc`P{dfSif=+m<| zUs9mgFZg-oTC~3iA4yV-cX5Md=DaF-G+>T-DMUQ+z8r(HB0hMaqUv~sM{(%&yW_6A zyoB6BkxLHulG&wo5Av={M8(2QUB6|1EN&<`)prz!Sbgq;!0_i`hL zC)UxS&+E?UzVUxYw504i?egcbRu}oFou>5w1eA7Xu$-h=3|M|41CT6Y+ZVAotU#hZ zqpIkX>M5r}s|to$69X)4FY*D3c}|o~MIPyi4k$c%@wc+YsYzKL5DMz39_oXoJLV25m=|<>J!Jg+jC8 zf6_uT(o?Mac&$N$6;X@fT+5t5#sUPZoH2{5@IxElIv-1K;IG1`o4v7!m|>?y3F5^f zOp&S9y81f?4I%?KxN_^ttL7;UjWVn1xgUjm#*ab~U)$TJb~ zNyJRX8;HxcR)suIR1uIJb^zP+og>|ZhX$$Z7L%cvA`0^{%c6BA#J>EPb**lGl+JVY zKie9g>x%#J(bz# zhx9BkPXU*`6iO}DEUdVk}kq6~R(!ha^{ zVJnyErfJ`?gTM7RryxfH3OdexEB@-y_Uwf~)5;#YZ)Nby#ZoY*M5-~y{P<7xJkXSt zUumMOYVK}G7$szmyKIwG;`-B7i^tu<>4*Cn3fV}% z$5QUKG(BmI5J2>vE3#< zJFHxLt~DJkwyvYz-z`UUly&p*-1}$fp56D`X4OrHpyQ`r^xN2`_dSAqZO>KL2r1D5 zOK>NAz+1=t$YHMMX{mn-2%V;*o%Q$~pbUqm=5g~e?q1f>A$LPuhj`faY;5Pdi4*QX zqgO4{+**_M0p|ym?h(jna4DEK189lKp%ja$*9i*Qz`ik3L7S)2^lcHeK8ksa`71Bc zJ#Ba^(_2Mu;iVqVG=H%Ssa&-la2scu`}#BjKl)2yFR$!&+0wX4y0iK&8q|Yw?jzYG zdzu#YbZh^*soJLy?uMqGR_WJm73A+*gz(98E%7DL+KhzlfQ3JdR|V5TjWwUxvtC$T zFNELwnWyRMbuYk?iBO0b)IbS5M;zXUZeo~>BNy(qXB6W|PqauctRQJ??xfUws4-pO zWxYnxe%1L}imKG!M0=N6#RZ;q;PZ?P58}g=%T$i*j%*Et@B7u?_Hx&Jr-l2MjCU)` zHdpRZB3D4Gx4!p1x7_mpxbs1|zd&?H**R+LyS*R;rz!7z(^&HX&>Z(ry=XLF(>Q{| z@^n&gTP&R9o3Yo(EKeLhXHWR5P}H!D zZb%3wpWSfHS5$$RC6HJ*vVxIRPl`S4m{eAjG(6Seinl#+^x&nO{L}B;k2&CA3Nrkr z3aLi)-u1oWXLfPhdpiy1T2ye&Y4y=^sb_OTUknX<1?7R_k+1s?ElsVDA(u*URexMe zaznuYU?yS?ctAszHM&h}cQ4rtq}QBdD*0C8#a5go6$aRIb}0ejV$%9tm;6T>z$Q*E z+xx!=AT|?{zvHyr;SL=Qg34=jeVAaX#U5 zwy|uaLNJsYZwnF~BsOU-K?L=mlt{<#^>I6if94V{<|Z&=$}`{eNo9Z?{nAaG=#;vb z8({9!s58#n$|}gO4Z}&u&);}@$KACmEv_Fh+vTbt_gR>0)Yzg>3&;P%Asl^kn&9g& z32(}T*IF>qS_#Nf0jibxc(Jd#s~Vb=XMQ&Fc%s_fARM{zd!Pn#O25w}H=5dRy#VE*J^}&nRfv2|l1Ih#0Py?iZfBHPDu?g;!_ z>l$Up*+}-(?njq;uPo?KPD_np4(?6FF}GYe{=zWwtSKkP7yy698p7~3J@RvZRyDyq zn;p4Q8j|N6UhcP8JionQc``plbb+ejl3@Q?Qh^EW|KWhNJGv-o^zo;OrbMjs7y;0| z&X)vD?;IcFJ?>d4o=jl=Bur2oO)qhol=XM|UKDc3U-LBS% z%6U8M`E!{x`U?Q6bzk50Kd{f$BoBZo81k!*r~bM7+7Y!SBPcFG7dytwYXs;&^w{|qBCL2oYd(UdOa6c{CE3RZ@9ekk5uoOwxc|&>dnPyZW-JdK{pN@W)YJo<2|a*< z6hqBaqi#Q{vXkMIEoL8s`uhXjHs$;I8kovtSsn@Lm18;zLKysG$bo{Qj`Z8iYzJqM zG?>r|K&w0yepErwIKa(cb0tMH44|HwL$P_Jxy7`h#UvVC8Y}RB_yf^JLN+W%ZdrpK zp9KzDiN9~iek~?V#c?V+IQRJ2LL7t;jI}p|FRvq3R?z?1Ak{lK6ez4&Nvu9R6!%ZYB4h@<)B$*Hx`0E>_vpC;K;13A`i=0T2bWJXXwD`$ z^BBeA5P3+g+(HX|c*D=I)J9g|Oh)Xatx=p?uYxQBKuoX7mob<$j;YA?+h z3v9Gqu|mp`Wg`Xvb!sSr8j8GEQ^>9Pbqve5Mom-Xr0tMZ=jD%=@rG$7c)p)xT*j=> zW>FLnH;DOe&V{*vZtofxw3Dhk&4Qp-uWV`@}cjD?0XMLJs z|D)(E|C(^$HoO8B#DdOkbUM0WbSd3kQi1}K3T$-CXatlIQUU_fDh`we9Uv-Ll#225 zI}|}t+{5$c{s-}@qv8quE zUaZ_J8h&QOAJEzBKM`P@6=9I}ks}ot?~@pRuu0e%gqnwa^E}4{rkWB-*``9Gsc!J z!_Zt-R`Mgv4%KZuy1A7A z7H|{i_)&NJYqaxGf zlq}i|QY!BLB;-9MnxD&U3|K3f%gt5VKhF%ncJ%_mFoYOU%W@72%POf4mvnre%irmF z+l_N=*!E`V;JK><7l!#QwLm`-fi6I`#fau^Wl)V8Oa%n?L$XS2$=!@WbzqDgBSMu* z2l_LZEH{nn_mM+cR8a3;60rBG5rFSMb??;<-9EF{^POoVy2+Te_b*bW z{Pi~#vdFCbbdz(-cV3?MM zK0z)+94JY^F}13NB)XMgETWufT1eMtrFDHxL`%&L+k0`gHW~v| zb+A4a25vMj8)@YLlaaH@_wcgz3He`S( zfK{JRNuu5N&Pw_>CaR*Gl|}G-G6EGvMB-E899j*<{$Ah+NaGN`H;zQ`enpF1Vak&R zRH^>`?}PYuAd?}_C;p33X$pkfwiL+>=1ce|9ww7~HVa6V5Cb``lcPZrZSbp;_^V^| z85i!NpKL>rvb(<|sQET_dN5p@_VFsqlX$;&vh_5T z^{c>u9GKo|o|5MhD!s7WO|TTM`(^Kok6xVbP3f)nj;1qE6KOwZRXt<8`EAzaiPz)Q zoLZSEIP(fdb7DkAe?B(S0Nn9X^!2KN&*Z-mw%3P^yJw$Ra$uM;6LHyTc#IpuTWjDI zyyNz%#d_cyQLJi7Q8Nnu=nvasDFi<;nDf7ZJC5!NL>*N!!LyKwb|8w^1LtA;_}y1M zq+SIrEcjzIl#>`BsEi+Fq1}BZHFg*6cey#_6C$>kNB6+yg0*1sQQPD1ZW8*eF=eeJ zvhdP_)s*(W?`3gc$gjTYrFQ%e5r`YW7*E`M^-8RK24?k4*qc2&gSU{ZLg zqo$eBa%pLCd;+==W!l#G2A=-ZPKYZyPBB|&bDRwC^X3v~*=#1ax;sexc(d@&dK&>a zD=5Q;>239+n`kaOJ~&_j7aC|^+lu6I`SO}b5`UJZrAvHe3BV4NT%ZJUo=R2_l9^BD zxCa`E-UmD0Ph7x{^Po%l{QMbDlaUb@UsR^Q7uaroP`Ax|um+48ec`IFOB*=%zO#}St%4H9XzC*{IUW~>2t42LDt?b{4E6F{ zOoTZ706Z^Lu0)y%0K{)4ck9qqK6=h4?hlh_4sx8|4(v1k9VNva^T4Ay5y>_ONHZ(; zDf9>Ln45_=9|X#qt^BX<4tdbuhl+XlZ1K;AiO8F2>PooNw=aC+Us5J#*jgId-?97j ze9VlI9U4FLd`(o|KO{7ld!>k9rS^k7${aw{ao=aQEXu;gui1`pMiA1Bvj9LOQt(hd z5%LBwbAsNzCRo(=oamH%tCvyUYf|}b&q7QHij?Xk+th?k{r=w_JC7zy?XQ9-y`kApYGon34{8l#eO~ z0`osSa^D22P`@Xl3ZiLH$j5E(WsDvYQ0SoXBnl2B)!JCuT(|&u_#I)GkqkwWOuoOY zS-K%Wh2J)b-6=C<}i!qVD&|Cfjc-b;tE-1-1BMTXsKuRQ$QVS(W z?xaZZ!pgELm#W%YLAScXn1Nal;NlgqUwq|V2awbNS-eY<@hYDHQF ziPYpi*;ugCkX@*xl(7%1??H((U;o`-rdizLrlb@EHg|a3;v;n`*8YG!5rZQCk+t8O zhR&W_(D+3CZP6-or?Si)B)6EeWIg_mVSPK_+{zA#ZikKj`G{z7%Nqw$$%aNNitpV!7PG7B!DJg(QodNL`o8%E?)lvjLrVCYJf6>RiO#={uC_WjN%vDBEta}v zL_GM(7T=^sFLHd-2x*L4WQH}-!s^(6y~PVhIIc@|&#g@8)WUwe!pru%!y?7TUpy^9 zdpr*;YNE;D-6#EdIo%(QK1;tSAF^9!jLXP+<-rGOw^8+r!@6n<#6olF`Vn@t;uu#FgShdHuB=eNMlVy@y zdc#bBwdyZqZ>I&iszJyoc3_|awL=n;wMCWT`>c{f+8C>{<&XptKLybPxfSln+qAA1 zE6(V3nLfN323s7kKJ@B0fx1%bh54x8D7*g0Lh5zo_W`MMh3IHFar6Ql_LEcGUn}yNwuM@4AYBpoChBa1cG<!gSos+GarVWXsv>{SS3+UcQ4|FaPSI`mNb^vHnicUD;pWw#$7LTZ`h_ZC|6=JKEF79#b|NQFv-dy~m8~O$)=ikKtWCK|M15$a1e=I~-Aw6>-_`?4dJp2?g zpUt(-ih@+65MZRZh|uJ+#=whFQsiVzQ)YdH)J#9WS#Ns(6%p3-)&8eZj1XQABh%f! zEJ?Me=&VxUkAKt*J2kke4gmnN9Rw&Y+VO03BH(fpV}i~d{^6aEQ^KSPjQ|{g&w(ak zZm%v}@d@MUWql=hIrqO?Gd>Pp0_W~;SCUVR6bk7jG6T=rzyEK$D8c~%+HTVH=rz)B zpfGD>>UR-Vs2%d8KSpqZVVtGNX;G%jqKAhfOYCjUNt-iliX)by7klJS7yNsXQkF3I zN+wSvOPJ+;@4*L^hKPHFOV^j+bT-yc8n2)uGx-00syV&fnsnB6*n-1IV9xideo7XGXG zWYS2MrF~g_eB?c=;>;5}Z$=EafP}!2{py z)#-fhpuOmvJsbPGWz$f9>dK8gJixR6De8Pv0VDrhbsgQ)*(SZmFU{e)av=~Mccox^ zq75DR3{w61m@WTbx)g!16U2=y7Ok-;(ZI4hka2uZ0ruh_^rloqLG*KKi??f1iu4w& zUyq9RkIbfWUBLdn{aa>>tHtaMOss{hw3}i5^4P@Z>^k7SP7KP5Kok>1G7Zi>-aIXe zIU1&h=hM;x&t5yp6gdvd|DHB0TxT{l_wsbpLE&hxrLQ2FWZ$PBdbC5q1*Dh$Ylhxm zF_K#qk{7Sqdc27dmR9celg#cmO+4$Bf8Y|Bpb}>56GSXzA@}Lr#=_zwi6TM#*}mKK z5U!E%wO3`>#L6Z@+Bf$AVS&&0hOXT9%EoP5btX}(r7m0o*KQv%Ut3R;D8a@Yatapk z9X8Hr0G#kA7l)R;^F>{dJ>-N9*JZ>mfOr)D_5R|$Z%CHqc)+7gj3S93*g z^TYlo&enEiQGWd0IhQkrR*d@*e)2&xn$a_K{o>+POM;@ti-PIO4z+yi;ej6C>6PXS zn|Y7U30=9=1J+Pd?~uhKR{o5{**K4L_f}c9 zTIcvDL|9`Y2{tx*k@k;!IvLWY$|`l=oa@j5T4T?_Pun%`tjzM#z4v6(C$idD>o5RBJ2`Cdm|T z8iz=#5y`FbWPUC8h&$@IP@8rvM6u#s9A8@Ek8_Er<&h`Okwh0lq#geq{FsSuE?AiQ zXyn^JY%$5qvg?(BuqTu5ZusIlcC`G9RP&gQrHF{=zCQH|$~>WAj_2mpaE^oQ%ZB$? z>fc2`ARL4jih2tV%+$93n*=<>C?2yZw`g4&>Uh<5zU zdGd88L=k^fvovWYP%hd4!B@zQ3br@MmVS6`d zR!I)7B#I1$BnP^QsL&$#*nH=sLnr7QlYPWWs-_Vi=S1k$LU9mC(?ZEo{znygAn|IT zJB+U#b%G7{fnHMkA!-sEs1#!am4xfiQd?PdmiLju##wizAnj{12kKxvHCw$@n1PkW zmHRa@d`^0i>a>9OgEn#jnN^YqAQd2u^ejvCY>mSau(4IqPTt>x&;TVM0Pv~V!WYdM z0ALl&QE8SyOdJ*L(n-6UA<|$@;7g_}d!BgMV0x)W&VLR$yHs%^F_)th?~A%R1_*@3 z+mAU24G;j*2i`6rMI2j*1>%JtZ3xX?=cUG|#drsA&8T|^BCAyh1m5PW3rt6by_gbG z#Q-$^WRnCaxnOxy+F{=5+^3;cA{ENXa4JNCuBjl7Futuw06UR;$Db&;f*h?uimB;R zS`ov87w@eIQWK1Vev&0vbB3jhe(aWV^j!*J(cKD>_`=4inw#9_FQ$JN76S%I_5p&8 zE^M^JTmrcbPbv;K{g1Wi9=@!OYPm~L-GW~I zy=gZYPev^ZbnH~BQT4ur!e)l6OByrG8WHM8JYQ77j|N~L&^*aN)>|qD3n8$1Uh@VT zSeHOhiH5vei`Aof>|i0-O{G_K0p7({^)F>2^%4k=XrRO4^-20QX@;}~!@zMpv(R70zn4S4-@qHst7%VeBBtF3 zfbLWHhh>@ah>19%3O)O9xau=)*HD4z(Hz0j#>G!6?c{3tA6FpCH!^;@R;|{bXR{JW zmlWA6kG*am+G-$BTSCC{UNLQIqn+m{O{=6|Zz4kqH!F)b^R=QwHziA&2o1|1(8Vgm zxevhIXkh$%(~`N=QL5)940`k@g}E=A2?!!tssMX(!( z@izm&8;?(4d$l3XDJa+C2z==>Sdkm#`TNXUS*=M*N!}1NlE&Xf_NaR<>}ISxV-DSz zh*54w{C9L6yn2nwQ~9AaD&#qr3I%r2Tx9(bmOco3tpZSC)OMd~C-ZT7D;9$a z2d?SRW7>*1`yK28mjYeJ%_v7o4H3rh=QC9Pnf9(?D{e6 zRHgdA_M|9t#A)MF=alVd4Ij17=9$%Lpq^#MDr=hg4ftbNHxUxO4M^<(t&BLFa@W*U zQv|<4=!>o=*A=D(x*r}j#;&K=nDiXC=&WdKUkPt(2SD!Jg$&0B&78kTZ0^Czq#H{M zSUhfY*#&EuUaur{Y|-yj5;c6e3E<`^3wsc6AAYq7zG_mxxDo$h=iC^B3EBwc+(bg4 zL=b!v^JA+I@X``()*3FzRr9RMRx^A>PzZg1I^T9fODCs;ue$#9$a^9@+%myOxmyzh z(78t#qwB?+MSQO|-`N!_4JhUSsy)P!iaKDD0i%P?8m~heA|7>|cr>+9fbdO|!9zA# zvf`F3!X?N5#>^Nt5Yu)Uu|$Jcd3pN*>c=)Ke8Wp8H~aWuSK+tn8+ZEKs5bhNAf-k2bOi1 z4uBHV(wf0m6o}O=@Lz{er*!UBd$jiiLdA&p44rmu7yKATjNrDtZtm4@-zLH>GzaP) zPH(%M?RrA#7hWFbcs$XIntWp2om42USSHZMkW)Fl1P)bI0t%(@K_Z5s*3rN{Yu$W7 z&H>t8mqBPC8U5VCQ<)g5mRM7WggLMam+HF9vtxA&N&X;CKuN@b#p+*#j2@T#Mt4tu{p=Wi^RN8# zKk{BLEI;1w_w_21=tugej|lJ1mN@8%(BOs_s6G2g8=30t0ob%XS_ZiIw*aKZ5Uw#h zZK;CPx?uAOp%zUrJ*a|t`cl8Y=vFx3c$>Za2(~-J;~xjiYmzkNg;;NCj9yV&`imRp zVdn_ZQU@*p18epcMjrSB#{b;Br#1fWZ=peP_u_GQ>iUGw@RMc1$?2cy=73qh^k!ir z1aSw@BNruOcJrR`T%#05oIUC-6%LDJ!Xk;H9=iZTS_tT9w6s_0G^GWQJvOGn^UV;| zHi5EOot3<(p{>1t>j%VK=p)6o}VZPOfQDd52Qp1GUW+VNX1p!vWiOakhCU zaK{KVYL%U(eAP%O!mSDkx zQ1!N_g-8~c?_QrbxFm>+X;HAfmvujeg~O#HKraJQvqNoDF;O$N)Sk4on*t3|4E zNKk+a|9iVIA8$4jFwBqMX*rt%YvdffwYB+jxfjwE-E_ddIhVcm=j6SzIEIip(O}=F zkuGMe5%q%?tEjLQZGj&8r1?&g)s{#hmb3TFgG-W)=S{#`G_dytSj%b5fZXe*)eO_w z;FK4iU$6+!Mb^Q9*0oOT#hy4Runze}9kx}AnD!0Cy`4JFwGVG)kp+Bziy68N48**l zaPEn4hAi8^a9~b~?9LRLvfBmC`Cl`F_Cek&TnZeYoO;!-ShcPcvRe08Q7$^=r#$;6 zQsk%Ne6(-N4@^>}J$jGD{Tqu$yB%c;M_=<^PQf3xX}pH%)c<7lB8wgqE>^ut=8A*KAI2q>gill*oeZzz&W^ zqMwd@5{XRkO-t|@HI8I5@C;F8_&P_?$+>>?eGWetQp-&6J;>Sr#R&i-@LyaCzBCc4MWf^4xQF_H~a1hYQZTQo3p>ZF8!@TVO0`SK(CGru6}-@MAmXFGm%05sW;WQ8D+)N*s7*10mw zT=jy)f{Fq@odT6AAgR8#vH-6MRHj~2xtV*jfuy3`lB?Xs*UHyhtH&A%AzgkzIzuYO zaZHl5vRW%MWhn)v1qf&%yi%irnEPUW?R5ndzFPT)q^dd}7)#o%6nG1V>*##lcsrjf zay0*YUjFzm69k8}-=Q{zoA4Li4m2_1xxy-LU2oa9J!TD%lhjjdSwTDf(?Jec_V1D@ zycWFoDGnJO0wqd<5J2AwAfKr6uarQOY>&ucKe5{Cd5!bDVQnS1ca7L!h*iS6NHjXj zx}r0pH#*zfWN+oVOLAQ0u4o1Hc#Eh5K2Yu$2L4m9%sA_ihs1J9=4w-xr$vh((ummEPO#%hwQKIi2y!-|eOhBhh* zjP=o>|4mdF#1`a{e@3OYlj;No^nQh88hIw$ilX|=cA9kADYim&k6C;Q1YCmsH3xz! zTSc3cVeCMSa`xkA&JjmTZvwRQi7c*BslE3;&g4y)plYT+S_Ohf+G@zwboP$bxUgona04W`@}Ri#Z>0R6}&B z-tI83!3Xj3W<{;;O)*e>{7+5WsT9lfGxY)@zz=PME}VSGdScpx2=@FmuL>JfE9$)n;m#` z8Qq-ycxgZ`FtfNI?iuP%B>|vNk_)Ko=oyUKXe?u0uDwuDH)V+{Z?(S%8l<00*cmuy zY@;ue2s1E!IMxzH0Y_dxe{*oEg-<0}G9zCqf0yNvcG{a{OMd;7eRtN+n{{*40)ktC zVg-Zx9QR$OEDtX`vd?y=VgO|!M9Nw=Q>lRdWV9Xs+md0*7E>;@^SOLYF563 zu|hq5xzMi>?mBauorBbu*2u2G&cZKu|3PSx3mDXGXzxwe$7Bxmm%Z+*-2H#pp7Opw zRw&AaatIdexf&~44dDZS=;x+&v8TvYrb5d#Ny?3~Q0&h~je+Tjdty5J-wB*r?X{-3 zOrc&@cGQR4vwS2D8FP3n%^N0UAl&puOn<;^A9tU)S>*+=RXE0l3HQ@JX)UV1*eck) zHHo`gZk9hT^`a}hocquPl@TF!)l!|1hw1kS65P6n{~IZy8Z0kkS6ctz3bo|G=(BrS z-%RM8lWrGBHT1aVDMn%`z_P_-B_EA8kQsPXv&C6ar~n~;nr&S?-^M_{d{K3 z&l!MAM=U=gzwt%YfTyuEqV;1l0b_fl%szf6B0+-3Qb4&cN%!gW+p?&f; zGgu2iY~DnWVQ+(m+hq}Z;!`YNR2ir680G>u1Zn_tHmSyRk*-_+IZs}H$~X|UlN7hQ0)#xN9o*`;&gK5DIZx>KvL{TH`FO-;Kix{RK!%#wH1EcP5PV zROY=pr6sU{ts+*B@^%TD;xZtBW!xp_G9siTYDKl_SpJKF>^@jB1%D>~lkqLfz`;Ue zFx!P+4Zc(fI2C zG*sn_*z0VNClOpWV4rb9E>b9vp|WOpL}qYQv}Zgvf3gS8KD{A-?|-$^^PRtC0oH|{ z!|64TW-9khe@%EQ{0oVc?{QVs>{@t2<_F|Hm%Jsrpf3Vme$^^9_G= zTxDs^%kvq+d|^nqs4`E2_9mOa3dEHBcv@0#1j}9DBEe<#RZlOkw}5{a8}C+R;)q8b z7S74jPHEg(CRs$zzRp90njz%>xldm%zk1S$!%Su_?EV_h-3-S3n}PUY5~Ho@)oU1d zH|t*L{afRui0 zY3EHD^ue$ypMI{^TW=4iFmLIV<4aa}ARx~vm_f>3mdw$aCB~pQAV^vPRxxhHvSOFnKH#UaY@0U@GZAsodCSLdivKg;o5!X zg%3x%pWKkv$mH}`EA3Wjper&NFGx4zr2lZwp$AhYuC~&lN^XV#ilz)9xuI7|0P9|~ zCQ)+U^fg0pjl!X1#0kJEp||{x2u_Wskm*pwil%T)Uj{5OWBX(3(n`v3U-%q2Zy1*< zH<>Xxk!ScaiHQ_W*35%SM_<-RR|GbiZVB&4tA%U%awtN>SV>rD+;iY7ckKAcSWWZFSI+_?}*vD}- z1kTY2Kw1isaOjurG0IhDvU|E_?k;$#z^l-REz8uu8t0yV49^=1zyp~@6%>B4K9{_Y zF|MoX;#+9n@&t|#7g%s?gF$f3&4|+ivmAlce5er`OhNT!z6t`@@EG8TEMbkdz}_oH zlwhmFf*S#VrWF;Ab}m^Bfa0LPQf1*5E5}Q)Q1^=a5jJpXCw2HB57ibuULKA=EM5gA zUJJQ4jLVE-QzU)NQ*D)$wLIr#ibp$?wBgi(@JeEu`5i6BAr3H2BBh%mo!hUPC!O~u zNny5?{mu^^MtZXD7CJJ-5Crph5+;*Jy!6grYJ(#1Dd6~VId5O?iwyHT4}O))dXNCYyuIoh4ka=%%$lz3gmrb1BmboTWMqzz zn0-^&hC>jwS4j7zkd#%DQLHija@G+NaL>r6f^J{S0=LV9Zeufwr`)-AWO(~II>Uv2 zRa`8v*Y@)u+_dB*W(btqo1KvhNV;dk!R65&ov9hZsS5f zl?oKf@tt(BXnLJjGBBT^V^Avmtlf)y3%%|y_e=$-K?g`s6;w=3{i2;?L7Wqx96oY` zSU+KKWNrgW-BB~OpjSx21V7mUR-=zP1W9@zqp} zn#dZtR8C)i{yV(5aDB)_`t`UR*$sm&(T#&;dH>+1 z9;C{iEaVGruCZ!P7EDwv$OwPdq**I#02P0{R{8Ry!2h7JsU4XlteoKQB3OcqSPK^? zU3XK(;n5bR=rHDGZ+*`iQv7}4mwg;H9IiEo&HL^rHplrDQ0H0@n2wg;Owb|4oJw>X ziR-Y0%GRADA$>?*RlvD5mQ2b%N*vu1>}a+n-mLa1mDLUHeB}mOIdC;JGd-{EUA|tw zR&GkIKF79r2Fhce7WJA(6#O$4Nc2{VVRpvdt@=8OYni@C-2{I-ivAi7=LDo*d|t=0 zFNos<`IZ&-r~r)vz>EN}!fM5Qud?5!l@SBrJLSxSO8G-b{E{S`Q-Dbb=?X@7qxQSr zs?FbYfvIDMWO?q}yPTJNn z_2xL_OrO`QHq2HZW{a%}m-*^Cp6u42AA&BP;W~4#{c{Z}-kwdY5&!TOyEQ!GfO285 zQKY-6BCDF?eNd<%sI?$QZp595>M0Xdp@IcsWbXWco$oimtd&w3g82bAeGo$Mt4(BO zCwZ91m)>qiU91|i98=9TzvCR@RTC+MGTs@YZr;21D&tM9H+!36Q~Ei@-)$M~&DYDg zg777g9fgMiu1z0`FN6)0{kfLET%lqQ1~OXi*Hj4(I~d%C#O>=zmHt+& zTRjhzq3J7*P@04~k;%VC2rD(a__EhPA|F4WnIdHFG8I$t_A-~jdYfX)(ER3gVH;Xu zRrk2y&8K}GkG%ZX_RSV<(=0t;I#dsR8<6onACyL_!786hq`RU!>oodLJh>=1xpjh` zCKWW6psM*wc;pHPGW}6w!YrK!Fwhr#{+D>Syz3LxfX7u`USlHxf?g2i;V*jb2{A+U zw@D5>T0L*7C9>aharnkWm!sLao%~FL2w`GVg^%{+j=dDuD&PH2$$Wi|>VUYSQrWrW znL7pcu`zN<&-n%Q2IuYz8raKy;)P^2Qhc&IW&_6=p6EApm3|1nwk1!{sr-@xy7fr2 z6(*q>x5U@PWS{B<{Cfr_@~McY3p~!g*Nk$}uf6xHOVYu6{;zlH#xK=6Af0*p-aLNniAss<3Y>Eq!p*IVoY9 zZUYo8h?eoc5XJLg)yK>8R<_!m37C5~N0~QQSH#76Y(`}U(1mSPi~ngKs75E;$+Ei* z@@7il3-ejU(lfne$q62s+Hc$;(z2`%GK9Zu-dEB}hGq0lgw&UPZ&oyHHO;1#s%)ZRYp3z?GN5Fc<)e;!k79Xo zRLvQ*aFOQq^Q!BWZ{D=)O-l!!dp>^ygA>e};)Hi+c*H2&WP6@6syscz>DOBoac&J& zTE-gV>^a3+`-i|usY*Bt!_ciC_@KgX2`(xF1<0%#6k%-?V4-+ft=U+86I4KBH@Ib35a$&o;|eIWMc)vlF?0S80ibw1+Gb@mHlK?CX!{FJ6o#e_lPe zCCEe}4q2Y)L;dKkZ>WHh&(Bqzp35sN7E*T~2H=p&;M@$DX7pIwpKFCKXB9Z$V~d)2 z*>hW%$Cc3zBwR*p^vmns>^^DIJo$1Dka;WIO zGL@3X_r@xKgo`MKQ5`SvRC}mTz<@q(g3n&br)f!rLO++k-KEtmzEw(jR^M6K%iL&= zRp142GIYLubBDzzfCka|W;Nbyc6>~`R^yN`uQ>i?X7%gaQT^Q3 zFMNN}(oSJ6*O3&J_1muRHfUCo%PvT03{kJ2EoAnXppv{LnNRkZ>jD%6iaST_V~id@ zrLr$7n-L^{MEY3c;DeeTz!@x?K=k8dtck$pe?9fI4|_D}mEuoP4DNthh0ohVaClC0^s6gW0EJYa0q*j=dbQmw!m>(GhJ;$Vqop?@Ho| z_3`!wi(gB&)lUTb?^3P^t#4bVeuGvCLVTXJ-N%_lck@x?ASbcUxipMvEPlMX8_2+2d+HF zE*Herz4>E0;71=_M)OJxKu)kPuEmI~xW7gK4AADPROl_^d@_&BRo0|rJ*#i63e8#5 z1g)Q6w&YnJ7ReHi+bl}XyzM_psR($jSjGZV##mN~>BfKidP@;;3IA$1=e2QW;f1a@ z>HRug{$Uro3!>8NmWGgDzgainwE?BCyYnsL@;-lUrIK~GhhF#?A-D9Ow{QFybdVR2}C4RZ3Q`cj{@3;Kn~ zK||$TF`wF0?iI110oPgh^h*FB2q(f{uUT@R!N&UTED`NKLJQ5inyr`fE^lwMoQ&hH zkl4!W?#>;EPk3NZfwng{}SnJwr}WK zFm|Ti3g+g5%V0IVS)xBa$m@B;E^Pxc*|iM9DYP(?tP>?iXEO?`nk<1yBUEfx&eM2+HG>^OXeK2uLp>ELvikv=PEeAns4)f04 z{u=6N`{Zrxq%OKYi&is)9epJh-TC4voanA8sn}`ySkV0y1tM(Ka-+%X{(J0k)r0>a z)77_=*C&ZBgcbKsvfL8%PYTplenOfC8s8D{UNMhPNo4b~%_{XL*yaq}(_{84tN$f(x2 ze6A`~1V{j9LAL*;U-KJB^;gJ^6)yv1hUb|=a)$Fa*!jkHUnhyTi*x?Xi{~ZyAHF1U z2dw17>_b269{Rp%Cx*S#{ck|TA#w5XaokbM3`5q_ObPf0rCi17i+ zLss}OuC6;^oF^^o&abSX(UtYK#mECbB)%4c-}$&y=@PUYeUbQeI!1ewRk??2w*)9 zBK8xC!y=u)c3-*N(Pf$TfQmk2#x^Nv&v@={U}nVDWXyoP=Nfwep!D>d!ToaT+5yTa zv!*laz{4FUwf)Gr=7M9Im(kB@^P8LcO)d-CW)QQA$$}H37_;jzTtXPvnMsP$hs<~J zP~|R3?`sMri(*g7hj7SiJIWy=J6$K2s-E5}=f^nf6zhlpEGmgC%6PH3g{zmZed7|H zCo5!T-=CotI}jtD@E14VS8fGUmPe`on_Wh!t(*reKo`7UN&=vgL<)cm3X?!bMp&=oXfj zs{|}5-zKlqT;=BEp5=8A9UDmw(I^D`+_v zx^b4;%*nB<9cD1ioQeb7-G7_#<%GDCezh09op^6BKkHd0<&16b{?ceWsNc_F7Z{<4 zyKrV>p%evDAc~(NI1ZWo{V*V_<*vj1>&7I(7pI299o@*Bhw^yV!0ZA&li9Q_;m*}mtMH(L1d18OVP&1u8WSH^}~Y#*4VOx3)~ zN|~)5zx_Xh$>T|n#cul@drq$Y51e7YmU$_<9k@T~uOk#*xL5uDSpN4Q`2n|{H}Cj z=tO9`zKiRSskW~0*yw*2o?4d1^%olk=W^7Zp_1V>Q2JeUt#; z=!p`DS9qI3yKZ6Uv~*ZM`Dra@R>_jFl<=E!S)77X$g=3~p_KG~MC$bt6>HDOL)0jb z&+hL@E#K3hmG^Bn-IXfM<^rgPUBAS{o>LpCHOazu=T;nZYMf@^^0h$aPHvr@am?Am zsK}+J)4EbAOW(#X6PbYjwR%bfNXcuR4FUNFot?hWaK6v(u6<;oAbo7LDNT(Ow1lb8XdHOo=9g=H_=ka?y!0)kj-CWCeldhTK(8z%d0k^k(G^p#p=mkS zqKzYsnXi{i8*mD%&L;k^M75=69D6F>hUwj3u$=qV2mSsQSiZw|Wz|CHU25=PPTR`K z(#&g}+n=PypNkrFCRWB9tSHod4$A&5`|#H1y6r=TNYA%ipsDB$&%C?`PT5J}@O(vf zA&@=7o?O2TZU~?`YRKOC;diM~2>a@~!rk8h6nr8JoP^}M5;h^0M}(*nh2NYHfQkxD zUAEHI3FFYBh&F%LthOOx{f$A*)YS=!=Yuczn2+H^{`X_2-%3)S|PsEs_5L znN|n`%2O`2oJ&elFG^L;KdDb=6}Rm|XR$w;6f|)Pt}*4+A~^pJ0Q|@%#bv9c4v_%MB&{67TQ69MLs2AxG@Rfz zYi5-k2;6XH(J6&y{1lf6w$CA^lTMAVU=cgU>9T}vk}ZWqWy|tU{K)OKXu%Y_|1)tR z=8|JBa@9%r{Vjja5O?+|@o9V4HYDWRDG@q}Lr{R1LE3)NX`~!%7MXnzXLC3q=;)rg zU>5P8ze^h}(i|j-q2%xQb1XN8Y^ix;7@$|t7i82i#fM0aUx?4D=XwLciUT@#-HHE| zryM%~!baFQcXG0c>HO_%aU)k7V{?W1Md)Fisl!+t&qcPw@MUFDZt>Kdw%lwB&2=Jr zox!s6GISz_T^JwhpUxAr2B?4vT$-@8Kv|BGO@76I6F0MxRlHkb9F6yrq2F0teBr`l(3wS!)iwZ)vPa7qOU}je zdBv@jL<#=OhD~MRTM}us^OEa9-oa3bbXMUqAe<d= z_`}OaG-Bemt?ZKER04#KBWCTkYi*oek}p6 zN&(*7vKqWx)lb&arle;PAQz6RV#8Q3g+t>=#cuL?3 z{*R)w@N4Sr!|=v{odqyP_ZXdyZXGZhaUdPijXDr1#f=z@9v#x1G8zdTUFr{16jYQ@ zR4gztd3n#j@SM*%&+~n*`?~$D0C5U;>;&@MV`2Yf?(g9EgSsOZ9qVH&!qq`gdLJo? zy3Bf-S*QEBAl_0Zgi!yM*t%I(c0H{sK0PNyqYBM)EhX%%Ttln)nu$?DVOo!DizR6g z15P1&d7p3_Yrj};dx zNYn@f=lsbRZ=!k!BdjBfgk^FM`0$$e=H?FOXqbRlafoQwIwF%L#sw_$gq07}%7>{e zG^uaZA|lv~rRIHxgRB1fXk(+~KQ>EU+KGCvh|)_?Px39yLqV`aPOasTJPM1(2rEBc z_19)b2uQxrMgFm-x)7bC_N}i*jODJLe_LHgzv7XlxItz$w0$UwPtsJg#SNGa157nI z8_gtTCxl1SpNYBRF{%C`K~xLYN(sQ+ppPF>!wLJ>zwAn#djVwR{R8dbv1o8 zj=A-d&2*NdlqP5UP8%&Z>o3MbFxHVNq(hIFTQHJ3Rh>#~CKHD*f*EAuSu&cmd1!F6U}!Ccr>0mroG=d=glRYNnO6( z;=`ij17KFXt&s8G82pa@sy=4ql@qgW_*KO|I=q#Y3+W z0XH^QR&HoC3OalRcUuH{wZa`5gI{d%e*MV9x@64R!`=U|K48?|-M~UxFf1{tbxjAM z(x}Uc9||{skwM41TBM=u5ShXdISZVkbIml{`F;0j1fRHs=KSs}0qNwN_K`RjpYhry z44;V$%y!2T zlJCi(Af3~OIG6xq{Q6>EhJ1z1EQ+5Q-G}2WEa%YQgj5{=kW3&2w(}wG09a=9TNcJ` zz_By(nm1;Y%wz|fok}BinJO%RU(J!3kfSe9u1!cR#uY&~f%<{_*OfTyK}Z(0&X>yk zljTKfHJ&&g6AXg+SS;%Gm8c&%ZEVhR)6#DrCE;3#0mjoyBB*vGD#0aD>ZYL@W`>HN zxo`#Uc=ZUbzA19Z0A49w`-eYK7d;Uy!1ALhx0i7(yU2-=h7?4*^y2RNYkN~z;5J1j zc*_TXx}z=*vUpV`u=oC3-D3t^&=_OzX3}nY)0A%Ne)FxERU+KTM?&0>U5~L4BgZ!R zw*L~aSbwKfyVBwgO0eg0OUP;LxUEHzb>Oy=L_jcJ~wd{lYOxTLOcB#O<4@nog?46tKSB*kDJ=L(Uq@Gxo!S1#WZAwEZ zG&Kr~^;J0eJR)QNxzH46Dz7t4JxKLD(DoNv8*f#MIZZdc1|9&_xZgh4bJs&>?yAk? zSFPT6SzyM~^=FJZIUF0A0io_szlzA%pR*=SdL64fMocFp{q2sH=7zB41S^SBQTD;# z6RIEA$(ZI|(zD)Lu<$ag-VN}ZirDbG@}emlD^(W13qmED+=U_IKkSVT{RR)=0zWhB zxj3f2O0tM0BEFP!E&B*lKhs)BDw2#RWX6*|0&vMM_ut!iL1JcI_^w)DS6a>y`-#mA zD*fhU&#`o%v3E1r_+6?u&eI_kZL1+zA*p9Oa;}#_PPk?kFo8H>2b>URXC`Bi5(P!=Lu;Ow{^v0h?&W~dy3k%J3Qt_r_e?%ndE@1VnsG7sJg%c|59R1dY6f=@^+pup694*20lW*;LHi zr+eF;``gi^g%%XMAEsHWsin*gkb1T;A8z}NZn0$Ay^q<@xg+|o|0wB)ekd1V12A7{ zFkIaKHFeE2^sXEtkoq`{J}pmKIok=SUj%qXF)5lLBgGfur$gW1083pS&3%xf7hrk> z3 zEt}uTOg1+v-=kBTc?zjs zJVG@z?-Sl+b_Cf!f0+eXiN#8*zFqxOG(X(0 zI+|QP>ZCtwafY8;ring++kLRhxz1$?s}jy+zoSnivnz&eKBVXoypY$tcmqV}O-INe zN;~pNyFaViSAg~{PxNwjs|vO!9L;im?S|LR_YY6+PoCy69?&aLyDRMb)k<~xMDJZS zSf5|?n5xu583#`na@@B1b-aq6hB(PRC~PH%FRAkHNWRHaMX&aA4|y%k%EZD>B>Ws1 zG~DV+HyES5v9LGegty_JT$RTPssAOZOq0CQr!wOQ+yfBhN%jtNN8rJ66r+>MGGtp4xX7SCjU-KkCx^b2oo&|Q~rNY8AvylfqN2hMN%uD4xbP_*3srPV0e^Y_T zcCt`1nd_8~D<8W+1|tb;XasWM32!{lemza(e8{{>?L?4NPS$(Nyu8tsmwt5lo6R0+ zlmm0=Fq_5iD9JUxsEJG2xR&|oY(gmzvl;0!??XG3C7_p z5|&xXl4Weim;73NwDXHVd|`H--IWBaIz~P7sw4;2OTCvDf_5xgD}`f|YaJ^++X2dJ zTV3wlO8enEnOS!Z=0uzSt#D;VqbPu&ukvPU5E1BefHM~pHj*_5@Cn~m1MPycqbD+r1#2ZA>4#uxG!_gv(s?|?Qhq|KP_!Ww`$=7$AM2y8 z4zktOssMmK#e%*0KmB{edA|SpcO*qmJ(ae=ftP4q!-@J`clH6f^Gi#-23--8;!ErI zrqxQ&_qI-ct+W$YN=`;{J;MYR1!n4$^&%nb zWmG-~OE48Y8jk4uek$Rd@{3d5n=lYcs5?bsJRAKTsyWlT1IG%mTlJlOrCI<5w_%g_ zu)fQ_pCx1!(c#@kYO|2OQlrn-T>lYDq`CGqp7wvqJ9Tu&{=7_&`0o$u+s}Eh?old* z$n+2L4<$Cm`3XfCG`tr!NToqGUZH#Z`w6c*M&=`J`@uFl5l8t%c9w)Qw#L$p?~P8F zuTk+e#+t6QiM&5nZ*|b9f9VtP_jngZ9jrRsQTm6b;&!rF^VIiTor@M7ngYFxGZ#!P zA5`6yrq#jS8E&Wr4Ev=isnS2QR;Jgj2!C28mKCtcTA}XPqRlP>!NMkk=>YO$YKgGX zqpRERONi4A8}~tMhJ_~jWzS-54{8AIO61+{=lsy=@*=g;AW#odW~Q|5fCaE}=L zlm?GSk8RMP28>e&J$D(El>!g7!dCSw%gzL7i$wEd-hvB^74J%_m2o~|3?N@e^vYs~ z@yH?F!Hrfwcdt!y#tn?ZM=(&q$ zK{-rI?ONPrCM}!}$t=X;E~{ON57yB>WU1aSV!bDdN}^hBO6-@>a3%;Uz9K*hJFK=* z)T|+_N5m}1j%L4SWaI! z0@);Z;#n7$G5~S@)2;+8@r#12NEaYyE>975eg7OmcLi?zN#XOA^@{-otJwd(~s>MkT zn4uT5paTY(XzyPVH1RYAV|=FN?@Y8!scmPbEy;CJ^3&x*G;d}QDI$Uz9Y?OOz^vY{ zOtRRbPkNx_3%6N#sEhA6P&#%@B!-5ql^XN4;Z79s5>faWWA5 zwEgz2eExU~qhf-|yQ(`t!w_L+(NDI+ix+$^eiwOA z`)wzzxatr_KHT3cc2+*o_-FmZipk-#Ze@ZosQ)F17k^Hc>&FqaoB}w1j$hMu{lbKl z1Sa@Tz&45!M!vGuET4~4|8!l7F?_KGP=R!pb#>6KFI7Kkc{zuw@*H&&C>wl zYgpzVNxh0L<9l16Tf@-(CMhvjO4b(=`)b*NKGQiS(qjskMk;Zhg>M2h zE#SC)wv*;5>nT8%1E67oxv7BpeXs9W4vSC(+LbUk#CrL5E{eai1oi32M zS$ZwrEMP00x~F5jGvjh`CTd_lQ*ZLjft-PDjG%In%G#u;RrXI&4mNnn@Bt*SQUMoB90z2}X{GqJnoc;xatI>@$9KNj6kNj^HVxg9J zB9yM$N2R`2QiXUQvMSpg(pjwNqmo%+ZUF)TS&{@LMx38q`J8(ZU2-?d>d#*J>Leftkcs}zm`S3 zQQ>)YX=)Hz^g5r0N$}tizXLidl(f9^w8VC*2$}?=UP8gOoxXteYqvSLgoRpOYn$^Xq~6 z1)SI0x(e2I+kg8x4o#dNOq!Q45Q}9MT?%O}36!^7`B#$1dm_1jsW76)^>q2FQxUiU ze<2D3Jy!v)cwqknq|JD z?->_Zml=oYFZF0PP)Rvr36F8CSPpvkw(P5!p?QUj*_Oek18-h@+LeRr`K{+a9~241 z>7v4P?jI^rH`zCWD>CFSC^!LHK8P!(F}`q)bd%=QL#V+%H2;^z;HKjh`{HbSQt&#P zg*}p@&vhTfl23tHF)Q^5p{_G6@uU)#{;H-4P)nir`bUV)Hi@lPWm8YIZ7iL2sf))zNxj#oT_2rh|Y-b;_*8|~s{^{4N~8@-&c z;cW#TtlGM(acu~QTa^OV(Vj9Mi08r-&y8n7TaA3y|j)-6d4z%Tkm+UF^ zt?0mHuXRP#Y0sTm)K2b|gFkZIf8=v_8hENJ=Tv8Q8NzWR zeQICbKcg0+!;hERhsuxyU$Hm>^@U>kTml9Dhob=Q(KL;oSxcL;dDo;ZnX1(q`?su{ z9_{>ZF;FW(WOC_@=(8$4>!^&_aK~ohu~s0#=CsyvO01msJ1oc%O~Lv^N68h=4gsyj z3Lour_;_q>nvlNBiQW`UCzEfhu#ayZIL6r$CrytrL_Dlt5U?oOM)_LZe(4J6GLAst z{w^t3+dXIhe2CyB)Ifbi1Fp|Xh?>Yeq^888GXf?~@rXI1K|Y`3X&Ex?^MIJ%`CC(>4?AfYpyBsK9>3S9 zyXAL}^5I9L$jdCrGd{Ff-RTSp8<{kH%)F=~Z!h`aq-(GLyaRlHS3|2ESkwxM$!0Du z`6!yi+4W(U;^{0KJp){tqjizjL|CFY#Vo|{j!xPb?A#O)JKxUlIiy<}!GsKPuE^gR z10-iA7Z?35_Hyn%(A_w$mL4#I=u42t6{31zL`lTDym-Qw7>>;*Pe~|HyO6bi&pDj% z%J<UrQMpqB7EYX>4LjHiQ&5 zvbbrMwohYKgl9@@3RYS`Kb2GSR%RDjhkT06sVh&G=gQbfx&8`5z7AIZL~i~_9r#Lp z+P?8Q<@+dW8xJd9LXr&j8=G>O_wGwa39QmAd+KMh1U14u8~}+eHWGX z3N+iX`Wxh!a7B-b`)!v**>WnElt1NEl zALHrPlsjuOlFo{Bu&r$zeWHNM^msmI3t&%R{m0gXN~jUNoxx;Q16k9@ETXAMbx)j1 z&fYX;>Ws18WRuD7H6Hv?Z-y=(B_h)j1(`*?c6K>M?iBj4Am7rdF6+<6JnwxXE1R}J zcDyQv#bOJp;_yNSmJ-|-`uC8UfP*AgGt4BV=!Uz3sgzDDk3!Gz`GQ>o*yBIB%*zWz z(_TRXMWw;33!qI&d`JnZ^u#5V;7<2$yyou5Dew%Ug`Lv+U?KIx^%YJ$ZR={lq zGwX!sDbXubsjn-X3+Ry_=ltimW@eV_Z(Iq8RgvyYptOJ;=QB&?km#G{nl9fhfNC~l z2j@tx$8f`+nyy(#hIN-DbX+?#zQ-JBJ-&4Q=Pi$i)S3f1=i48%_-(Ha(nEfCtlh5g zLZFQGEbBh%8r+-+)Ylj-m|zz;dr*eyd_8DNquQ7XWdXOa6^ob%6m+^ol6SL1@aB}W z(bD~+e=)cDNA{@=Az~MTehizgrKs*%65q`_(_GkmU>*q~L+8HnD++N$r!P-{_4;X5 zo%Pb3KiAlY4l2@EDYQo>0$fO+-cNic8R|CEi8t(-1ZKDEt#@Fg!Nkq6_^?1bA<=8D zG}@Fgj+EPxC8pvl^IsAJQ?V^3E;277S`^6sZC>3hW#h@0X>Zi|7sA#1Oci+rSI?-$4{F5>{4wDt& zhnr!Yw!tz{&2~>--A8|tF8DU70G2a(gYG?qS-JOEvsAChcCBT=;7Rvt8sD;aSUOLH zH3^%9?Pj=|mKx$Lf#|4EjAuoVOLS2kh;DB;atKs4uG}lopVW~Z_qeR?D`g6x3&5@c zhhe@q%T?=7?ddjEFGi(9%s;8695w*6X%v` zU^$vdXLVS~xt+)gEwv5(Bn!G@{Pk?7?4OPIDvVgr6nB1N}5*##Bd zzw9R89N&w)*6Pe})T?4ziSDTCV|@*GIK7{df_8Gt32VR_?szjok%j=;YkbAd|MBVA2x@zT&Qg@xx3gcefBC*?yx1n*i3cQt zEJZwdd>C>+?WT3@184El+V`J3M^(QnyRWThgy|zV!VMM0Z#Md%)V|)}$L=3V z1}u~)=}*#Vx=$0?Q7Iixvo2UF!}mYG%^mUJanQ%6#gD~)JTrwn22ZQ!m$Uxk-AmIW zfblRWn8H_7ro$C?QF8M8$le7LjX&GPk7^)Q^ z_ACE-(^*;-BBN;fixX|y!y^F+3OzIdJ1TE+{Ba+7Z7jREK|u!mUGm~Do5T{^2`N~!!({$eU+ zqL^*_g?)d?O4@}wJO97@52O8b-xa&N$E>?*whKxz{y>7oh(bI-`8-YVmDK!^OEC4} z)L@>k-(HEx9j-2SndA$P5XoZi%pN>ZSsg1m>b+aZ-d&={s<>bjX50&mQ&1;MqRj>) zld5YUKtC)*OX?SPBBb@o-~EI1s^n{2GAmU%C|8x6|NFt%()9w@MO_6?A#zIl}T0 zwTrBrKEkuf;j|@uv-%rK_Oq^#iKLg-TLB}iRngoLv8-E*)&h}U&F8)zO+w1x#l!I$ zVIg_WPou_010Txf!i7MoQEF@o`7C4Ow5x8d>{UWBYtTB#yTrd?25zft=;kk$1}F1C zUs+$fg~b`SMsmxmOs^bFe|_Tr@>}Nqb9q1hIBe*DPCp|T&O~og?g3>eAcPe*lApQG zH96PqZYzb^0r7f*USte2Ic`KkS`T+j_-rv!e%yylEA zCtb|-SU~tW3tbB6@v_jRU8O>9ll@XaycceEiPv}1?Qg!aAmPfij;pXRBQ|hItv&~@DX-VffEtU5ZF^6r|`?+j_Lfl+6ezc zgYbUPS#7NQ8ddX=L9mP%l_%~o7QAU;Lv8k4;!S>(!eU5K4D3n1@r@Qk1L-g!*yXFM ze3%!c6b^g!4HPK2kGGT*cCWyGKpkYzCoh*|J@nWwYmJJsr>z&5{X45wCK6^|hd`*T7f^uEJCz)-ymllcLkz@>U{pFT7gx(=x#5Ub*plaqz`-< zq`wR|ZpcexM8($Tm|4MpHoEd}7vII@W#Lr}(ybB1sA5KuonGlbQ>g=j@^nKIPW$4o z$EBZ3xb^cRvU&ss&SJDKXMobfu74@~LqCE^YLY7%VGa}4k0;r0enD~UXZ`5Qztk3V z_dv&$#pCzc6r#|TpCGS2ZT>Mv9K9D>2WARUya;l3@Q?0P!TzoHB02TKVGer7MoGgO`r0K^5UvUcc~!k?;JP z`}V?AozFPZgCu>LDN5ocmc!5Uat1YSn!m|S?!grQe?Q%ZS_2m97SzK!@yx~e{zo|1gLmzJAf=eI2_mgud4vX^fZBgsT} zMgQb#j96-_R1sgLasbzRezktzBZ(W^6;}heWK7VXH;d~6Jmgc$5<|qC;^Eg)CA_yq z?HBkV%Z|9|a^d{^D-O;aI#o*TReS>ZDIrCI75e=Cja$JyjQ+%8wPNBd>{^t{Z+tdp zp-hT}wNvuKWC(=xvj(Hi3af1)@0&-gfPZA1ms){U6xZ4xVj6tiWPYOHbW(Rp1U<>A zgW+0VEBa$zV2T?uF7Nd>z3T6m=5GgeyRGGBvB`0JIiUxBj=I7>YcDhrxeaODp8|Qa z*$S4M%ks_&;n9`ayjjc#_Q#nk!d!MH-X}KRCMls^ShDGaBdg+BXx5K*r<*qT^^%GL z2@7pR^BzpaPtU<2-uKc`QaVcEecDwQYF0f1hdXT6-}h1@i0PJ8X5wo@lN{c^xq@JH zjTdUbaKOC^hpEV#)z7HFt!pgyC-tAe?(Mj6oyFWYPnMPShdwSO4x8vUjY1r!1QV zD{O`B1%>T|aoaGgCHrA}@j`HJ?UDyc?!Ve@mDu1d1b&U2)Sn(~`YkD|KUNB2UDeC} ztVrwn1zepNS%Y8X-I9|S;8~~n8c0HNpPX25pf~m-@GQl@gassoMsBUsXT$l~eVWQZ z>~Ys`jq_-H3UGNa3p+>Pj%-ba2XN+XqdxPQT-+VAr;Y4R!5+0B{(J*&{f^rsw9`li zLEiuihp|Tb*#7V2M4(H1qBD_uyp*AcpF@4UF4g#xT;;>Zk3D-WknU38xRY=jmvyBN z6gnw#WJ*DFCzRf*7~=MP0|VC%30%dtfmJa8uV%=>~#ZJC9r zLfjmNF>L=~3bn0e%9Wq1vKQ8F-0-hy&^Y3p=ra=-k<~t&8#f{HWnnDkU8%;qfOGvC zk*?e}xH6^t70I})RGjCpG+%k?v=B%;?O7FdpDkl->|B`xeoQ3bhjQk;T*Bw>4-dh2 z9AUO1y(KmUymdkc&TW%;Tj$=;WE9H_5`B9)M!*JBAIS?hJ-=%+xVX^7sh5jz8F&&u z5^MgZj#skYyTbt4oTEyZUd@cR)| zxY8pzNB|59KEmCb`or(L59O`AC%3bdd8gx2lXt_NE`BTrKu=g@W62^wLLM6)R1&Zx zEzX^YH;bM@Nku2lh9swQO|F!TKtQ=kpbPKr@t=o1kKlH z00VKH)KYz4>k=h&ID5bL8KTN_%EjVA%d*3b%Qp#~UL2(I*3@BvzalS#X3etsWzdmz zDNdg1M9$hceWf@>$w?RXhHb~&tXaJn%+R;OS>q48;uA&fUY*E{NeD-iSO zY>u-P;h~8}xXIP;;r(CVF61%ohPm&jK3bJK`(FxXO;)SeD-+hdC-swl;f)732oJF) zVow(`>{`V`WMLL&|u90Utn7dz8PH2J}md4urP;3rqA)J^Z-8}GX%dQ+JP#HM)N zK?yI7wSor=Hn2qaZ4Y;x)M(<3QeJ)v_o>x-59Q~^;5?XK1+zAFCGTz)^sxQIP}-VHCm%?G%z zbt>Yvk!n(A1unr`2y8E_I>z!xU7awW_E{&pA!XpiH`1G7Qo)6zxZ-NyecfBx0jDY~$o4u@Nn75k7I?=ObI#V+y>awO_JR$nW3%V`R{#r#OE-OZ%Kzj;aALUl;p2Bz1M z(&xB!Y8;MoZg$^0_y{6Dg>{T&uQdw|U#SPlyzX$d6+S+>I$?z`wk}!Je?Cg#54!!8 zboA-`#CL)2v&PHdz8l=%I8YK+T#g^o4OX!iKRHydkJO`%zVQ!9eb@P>E%~EI8`SG~ zz!7W3KPV?Ueh~1kKfa(#XCOYE36j+Z(|lf%y19)!f5lD-ywf@4jm#5&Gfxk`sYLoZ zH(`ee{mi2Yf%YrQcdy;u=K;>eu`@rB$h(SD%_2#M^|*~&q-PVO&pV5rwq-*?x8D`x zzz){GTVGILTs!ru-QigmmrnOzDJ;0kH%+qZgxU z8x`K4S`h$*oRR`2r-9PNQnPb%^XT~ng+;{$06C)ootBeTQfOS8Bht{^(%RPE(b;vQ zn{lJ2R=sC%s8*~#Pl-A{T$`LfS(JRO0i8RVVvIk^tzxdMU{WjY7s4NBFFe_J{$g`$ z1*DeutiXDEZ*;lv-d>LJ?VGzT8LzXKQl5R;`qT|t8((B^uTjFVN_D-l*yTc;*~k80 z#p%IiHOX(=I<9@nk!1`ssExjf;$M!~K z@iPY&?B`bv<=nLdidn>R&nfZ)xVUZH{i?~feIxx2PQZWqbfgix)>%JiT8jRdRo|EY zsy&iTep78n`rjH~_(vPwPiOVK9IlY$cC}yNh|X6il_@&lu{uiGe19@Qz`*$;QS`#X z-v_Y@b(|j0Er(X0{YUYyKNJ4qoa3}JL|Y=C(m#1{zPl!>4^Ff&j;vN0*Ve`T{!i4( zT}~@6`cIx8NCZE#g8myByqWZjxfr=P&e`bg{JCs}z@r}NKd$X?h_b2&jMu*kIy zlOsxTG&*@3^IcebDJ6LBCykwr?Th8Lh6swE;&0<)t6ku^g65Jf=?Pgyo`1%?$Ef5_ zKd8@>P^;9{5QkZbD}Q?$svm1^f+P`yBV&#_95FkznN8-M?7l5@R1!pK#I_8nraRjs zHK1$=aOM+)0w1uAUe&ym1UupgQ$-tW8!KyA@H}Zrj+xJ7u_|azUiDNUQf~}?75vn* zZCgu`9KY=FJSMWRVgd3y++Rp%TDjQdmCX%H^S@vrnv3HE=5S%eSWPLnV)E$S;4}=bczI%K@FRT4FwXr}ZV_9Vi*8 zaH;0eab3d}z<+7v;%zDCKS>i3fMBomU@OB*_YM?x>Q5-I?SiP3rP)dCB;dl2thB9T z6}NUHB|4SvZPv_=4Xrb1x99Gz}>V3u`Qw`P>{pmHFAww_WU06{$BXq>aP~Iq4mT7|GODnbVd& zAU~3qRBnUGc@U={?m@kjupl>TnaX_(St{dbGr4!#M1^?~plgR%)m)aVjlK&4u>9=j zm=(usFXtbu(L2q@meF?7temp0b9pZpc{wdBw=OKxK+iTai#3Vhgk=f~(XYr47f491 zHP7@6LgjrmhyMF)emh(;|1Qg^`|uPNJ=*0 zg?KY3tpC2|5i4mGgZ>G%dL>oxm?qQ6xstPc)jqgX>9tC7e1%__6&MY$7+8FVioN{E zsp)!`O+9UIL57lZhjSy$25U!?~W~5fUt@v**Y~GszeB}qtH=G^6-FCMU|ae z*_EUF7?B=F8vIp98a!)J+DOEg5HMa^6w)Goz`@EzFw^4k3A2 zrdgY+(wMOImo&mmL)pGkHpSI(rHx_$*JwxJyo=6Op3=s*yQmHO<+&w=rEL4 z^eC2E#Kh4Dwr;X~)|L43l__`!)cia-c_fG4dpFKxTtUP___o?EhJasiq!gfxOnMYt zD;;f+Yj>U+vPV1B=~ou7^NHdir4lP3AycVSgv$Rj_KN!SEOTAInoUyLwxe~*6$BsQiXUgOu-HL-ha5Hc|8q3YG^Ijp^2oQc# zOK4nW?`~sP<0wq_UV7cJSzE;qu9(*XSNK50~hX#9@w^jDg%*{ z=^zxV%p3F@iPR{Bv%w^5U`OiZKPW+8QOKjlw$HcfCe!zoq2bZYBX4R!iKXsl zv|IoRWM?`o|A2ix>C8cE>g@FOf1%Tf|L`ESTYg9m(t!kto^B|d&EW;OcPSMZNHCJ7 zMjP!jZn$H`zRH8_E~MTM=^qv^mRh@hPFFh3D+A=6&Ud2gl1`Zs0OB;cdUAsM!NnEu zQ|thr(3>R1A=;-Pm0Gafn;!(>+R&6$p9>PXsW*NueyDlS#~sOzlPp;;Yz+3q@u#I; zsJT(q(e1Z)$KAxrRrIqZq3&Ayn}pC!whp9pzmERl@rQk8K>_Xe%4{Lt?BB1}v<1q? z7Z+IN*u-Jg7kM{(4uhv>9H6#wm`}AKVccZ2w+|kKJYOs8@sIRim` z#(>N|903i|2jB(inw&bYFWUCT0F2k?JasGDDM$_PdUWD@aAFGGf`gPYO!QR4sJk0O zDlFs$@KPngFwOha9AZo-Gc*PoR(A>c_@QwifV})IZDTV+i_e1inL3C{OWpS>j`Ch( zPf20m1TbE7c336B8*3hFm@jMbn09|3adr+68it>k2Sg9Aoi#DZW~Sa)PCF$Tj#pDH zo3Sc8 z$k!G*EezBci1P{nXQ$CV^1;ZFVz9SI90yZ;(LgXgU$<;lc!Afio9VP6a1Gg-D1ZXF z0&tmftUw!m>HwD7VA2!k#rYsN)ZTV{8eqG5RkM}-#8Eh3VXK(9LVyg zh9Ce6WZ(xBVhK}t;1TP?B8N{w&WBezmABO=llRk`egK3i#ohZEE4r|$!x%Lp)|C&D zHYF^HVi8p<#{I+|n~Zg2FdTl5In10n8h-#TO(pGk$da^$E~B6UL+jPEOJ^!`KsAhp zD8~(kPhJ*12Kg6nUca58edRGQG|VSQGGn+2O8JCXG~161!);R%1n8vxO-d)X_57|=ya6f(yPm*B-HNbon*smE>~~e zJblf$+QYa3=FVM#yIdg8X++d6d<%rag+6?XdCCL9{{YFDR^>D8HE^o;%hlu*U;{*% zJL=c-K-I+{x4>TH)-0&l>UATvHuLJOuf|M18hI$JY?YH zjaBNGwVuFXV?wZp{uSd6+*#VNbuD1~kax>nK`Yd>0_9_?9a|M$s!J(a+HXFnJwj$4 z(CaB-YZgV^zPca#%TsDwnWT>4P0#$zCb8j&RJtJ<$0}OJfQt0JK$(qC2u8R7V#1Jc zojQC%VysS5aV^XV?OOHKlaA4KIuOinJC=|F*l;;aa@|Leq}?1)tk~y@;C+Zy*SA63 z9pP9eIhnuX7FmMv|L${7z4TZ(`muoCo;I8dZ*}&GvaUWKf>d4Wb1Y^9#fiWiz1{o@`qQ(jmJ-Se*YD?Aqa@C;A|gmECCyFuSOi9>hOIsjz=zdA zWVji@d0ijb=?-)Hj3z*GshAx6D2ywX(;`2|eh(h~5Rjyt|Cewi%uX6$><_*m4zz@i zv~`5h@oLL^B=uUp&I!XU2T4n%QGe6+8${bt4`C#Q$IfwR8^<~zJTfQJw;+OmxJu@k zpJ@-{tluB=SGvAViAiv}UDc?OF>Svn8wL8QSLq?Bkx$%Ef;AZk9(zSoJZ?cdDhg1N zqJe$~?`nFU4hOgj*60CQX!g?v$&W$0Fhf{R5358c^OcfO7d-ZVgq`(UlW*An@38^f zsBLtQ(IL_$-7Vef2nh)R0V!cHI!8B*PGy7$d_YI13W$`VBUDgCKt)U*p6B@f{{0v3 z$>gvdz zG_)_(IU~Il>6R?qKaYQ6Uj?r>dbY>l7(hq-_TQIVPh|h}xvITTZaCAO@Y&2je!f3rt!fuH>~Mm#v7T{Dt+8g&FDXbj^c6Ul|{@ytg&*UFnKSUPvn z#`bL&G9Y0nZDQBsm*k|pD=j8SCDQQW*t5@nSnnNqMt4lTMNlDl8Rke&QGkdDZv*%5 z;AIBzt3qmH+=&_FlUc}|V@+gVo-$(@ ze%bn{vbYHZXcF#x^%q$w>^7JxPr?PB(=py;TWb0W%Z`O-yo`x^1*N{X6v;rh;X>zs ziII+6`R?a*lVN65pv1AQ%(ZLDP&qziI((!^@je&WspUB{Xf52XsPrDZOLpd2=qd%V znrj7lmc^0pNR_SuQ_q%a)?VL2u-zq;)smqtuP2Hq^z-2$kOned<7V~K^Y;9OS5Nje z61Se`0Cy~ja|AMV{6h9a{N1)-(D1}n9TIfV28}tc(HL1szBfePg#R3bSIxqmfNt+2 zS`FNC9vOTYsbzhS!DZR>O7G)(-0QX@bV%hhQXnjK$zhphBMUpUy2jiz40j@pWXW** ze1zAbwP+Yk-l)K4S()eY9>D7A($Oj%ar51kwQTMC`#2!o>P1u6Y%>)cCb_+`)2r#p zE-Twnto=4=yhTBqh2af!d=AP>u;krjc)ug2^MhPOzW?g4X5w$wf7kBzFKl+A+qAmq z_I4iR5L!z|SU;eh)V0$dj@Ib~Nn$#>Z631KVP3O>ijhyDJ8I{7@uVh;-_*f9IpkQn zYP~R5*ET7S^(pS{4&3$==gIt|P&^^;FbfXm5dQs@Ya#eQ9S6Bq3xQPauHuK*3!D}C zkKYvr>FIxlif=Nbk0@c5lg{2l;Wc6A8GWKc(+3Rs`rZkD(u9^TbO{Y~rEXB1=21GpC-tc1_6on=Qy)3Wx*=D;Dd=^J+*W9U6IF$PVl zHO+%8tQ6iV>&_hWTNO^zukW8fV})7K0+z7HLAFo3=h?;pdFzRn@}eY5=wmTh5b^WJ z2GuiQvLR>moh6q$-;rwFmn=z`>`PkV$bCV=mzG6nckwwFQ|Q6!k?Hj%C`J5Z5Cc=U z>Cpvjx|4MHBueS;%33{{Mwx@;=bru}=!^6=3~@4$nBtdQqrEQBReT z1sABtE+fq8&|h(Sbu!qMpMe2!QG@=_jsLl0@U4hI#l{HJ4yDGE<6@pHHd}om$*40U zfre2ApRI$AV5!VE(BfhU@6}N@LG~E*i8TJaC`rHr__Zv-%b1^^q7y-<*qxZ_!Ivv=gXu8n`TORq-7Ed4Bs> z6Ru#j{)^xOtvCW;{JYSFJ?Zdg1Orf=_=_cM{KXSnJStv9B!iHb0pu4I5bhS2S5#J2 z*AQ##>KpLk@y)5N@obG3iEUSgWOp|@O%AX8aEK66tfT#?UN|l2UcOV_bjJMf^Q<&* z#$pBtFTn7;W_9J&MPR#K*Pb38lWK5(ryAfrI6AH$NPStnf&Z2vGXE?nK46^mv!Ir} z8yW9K27Y|W?a^mKUNhF;cV?h2I_Fr&D+F2rFkbe*ut2_+Y6i)Nm|}HluVgQ7YbWC; z0;-%U7p|m@JPEz>6XJTyT+M>h$Ink~&GqetH%(!FYl;Xdf3d&CyaPYKzMreTapUu7 zp8kK5fB7ycwvBy%n!^b`SI%1IaDItXdLu93cbet>ZmXH7ZqVPY@7l@HPf6+&$cG3$ zoj_IE1>o|g**}Q;n8@OnwO0gaq$sQ5@g#*MF*=Q1yu2vSDCZTFWsB!!1l3ACMy-qO zRnB|sW*9ffJi<6WU*+P1YN)HeO7TeVPcN#_ZZ>wV^HsHEsqFVHfKEs?qxYC4m3e3icMXG|RAh90HgyW=c3nqrCB-YU%aF(=9aR3Q`F3S z7Uo;Dhuw}=W~2hB5;AORs}+9c8C%C#Tg@p*jh~3L8Z)dhVvyNr4EGIOzbAi|wfJn4 zaFCvELwcA3&~#qYu)xn&7Le$uGR=rFR+JdcsA+v0fM^zG_?JgUtfZLDQomZc3$?8d zSYwUz6xbbO!7JQKj0@8l9V?DcQZuG`nd5mCSKYVLDr(3`r9ZOWeUU`fi(ptVFgqI` zQ6|xVF3}%xa-5K+gr%a+G>?HA5i-W+B*%2p6C%oM*Mh{bI!A~2`z%3N#F?LGc~25? zL+SDaKO6e=gRqHDXw12+E`KuP(uDkYzT60^G8_>orqeT4C8B)pjuwP|I#@M}Ry;5n zueZv-BeXdSPO|pS%-#`z#dRMF$Y+VU@&^f3DSCG&2raqh9n_g@D)AMs3V1R9OP!aS zkx;fc4@vEz0(vVGPX(@-b)W7=O*R|P4oOKcF2-l1&2Rp2#*CQB9bnT-cM25)F<{qj zgt9PJM6Z2nM)=oOz?(fuo zx``!cJ2<{EF_D<|#8cS?V2pFN?_PD~%+SC5SF&A(s3FQQSn$`E86TWQVbt{H!f-4K zz8IhikIpnYR7pTyD8FMLKy^oE6?LBIXS?TcLo#X7_`{d=8kMyo%87K9nc{dCP55<&a|rS~GolV? zZQBkEp@UKP5f77)=wm(&9V!fOT}Lh4)%0|)I0tZIyr$M6 zmHK&A3(bB`Hrm!4SSq7|Jo?cURMGtV>}nwWY+E%=d9qcAx5L-Jzr@^W*{49@f~f*eQkaKj zeRvv+phZD-Ag^x{s{aTpmX&pkB@Cw6@eSsg_vsB3?2O+rUT}uD6nOQ>x5dCEc zUlA8Tw*MUq4_~pjf^PG6f^bxWrLJRt`cNN)^R1lHZDsX~djm+#p6@g4`i*rvV?HNv zHkrY*n(l;@N5X_5pp6UgN>A}q+ktIo>9H_$KYNA0=pKNuD2!lEi@hzHHBMvd(w4eS zrTsS`SWu6nG;06vm_ED0bfqFkm{|6>b}gNps3MuR^D~%@r>n%!Va79kdV;AiI9u%B z$W(kVE|)qV6 z#A?lG454Fq(<&Isxv*Zl{n^67$L(DtJ+ZrX`as0yysIzpGlqcVv#PTZ0fj)AY4o}aL!d%yXm{$IhzsjY$~Ir!Pli*zQE>fPugi>o)%rXL ziSf+@v7Pi@Pm5a0Khgn{P0ALI0-1H57PgcGRtpn0){CuNTk-m^`6d;&X!kIoEba$6 zA|7`$)03El=wT#v@QYq5I>tJc-78}UOql+|h(|HdUAfGhDk)_ z%na57E}74esaM{|w5Lnk6A?pJ!{8D}Q{GR%Q&JlA6HnC-V}IMQ zz5P|D-AGfHYNToHuH`>sLHVaWi!Td(l5T%#&w~UFwu^y5A;bdhxyTr+?Q6*Af4Jjo zc3f;%p9MY%OAZY#WtdZRmhEK<%y~0v?%H*x@Z423;wnqiL9e^1kzRh%wH@@Nkro7^ zez>uc?S>Nb<#(&M%xn9-$%=c!_m7g-qm>gbs$ewm+)U?(?{^o}GcmOn40<&$H$NN_ zrVj-+e6Vfjn{hgI`)C(;kb~s*#xX8ZitP(*MR01*2&Cf_7VyI{a^G+~V&#MIaq`(` zKA+A=j(u9a47I)A%XQE{qr$R6&hihoYGn?ukaBo9$it}8)bZ>sfe$_l_%BbGs0)6Z z|8-hW+iJx6U>4j1=ifs%hOqa(UO8rb`RF_j@gUc{xuX?|w~10RTfMiXjN4}sl3|BE zSAd(5Kp!392|lpQAAZk1u-A&fij(3SgF~y)S3byse+A3L6JmOFaW$eWOkzwej&NzC z#BNd;mkn%nit(4OWEaIyDiTj1#2;8iGoUo2TJTZZka}UbEDNLFG%MlAOEZ|3oPvi$ zCMu2KseZs#dJ-Gt66#QlQa3r)o5M)KtZPQso*&z-2{2opB~79@!;hF5^&H3zN`=_? z`?B%49XR+1<=ZTOjf0ME0f;MwKEcAKNU7UOEV7X)r+01|yW=`i%qQ7{Ux4YXrsMqVyryJq|VJbLd z5Ep|<7`$l&H=s6n_t0ZS8t3vo}2`nJfa^+Y3X0oXHIY;aEgf^rha1>p_hE1SKw3c6gI)+i%X zig$@er<*D4TPThZr4fJDWc- zSLI#GkGoK(N3IpbT%Y9RAt3(&K~M^okU2pIT}XO}&RhEiH%fyhM6z8KDbEyklBc*olBh5&_pp=<3Y^HofpC2wHtKLK-Oi9S+r7 z&+5se%}pshTPs8+5|kgIfAvG;)1a(Qa5vSwd=jg+vwL1}=m`hh0TaeIQ~cl?v4RlT0sKmLNQb5hefJgftTwMZQE#U2KDs&)T*4uDr z&&U`hS80r-3Z`~EpUP?=0um>YJHZJ=99M>w_VxU_jNp2E+LoA)No)Y`+`xHjCDF5R z+^$XrSRP@ilJlH~wO!h1K3SFVgICP!wGhzFbaGDRGP&kU%6A9ZC62&hDOADHQXLyU z=PL4uS@p|EAbKM+9tY?msE6S&;SW(y_F3`TrN?NnKWd&u@iQf39VeQ%LED!8x<$0Rh!uzHk! zI$2wTeQ>X&6V=Z4XYI}=-twOsBRi3)JDfor4H35Od}$x>3~i_|4wfv3@IdKwthE1) zd&wf0Q9l0=HmSx{}fqiv3hizm)uUKW_v1Zjk zoTCJ6w_owAagTCKC}f{4=V$gdS)|5F>C2HHxPT6h?qT$XSzf6dHdWJUiyB|L|V|!}JJtq{A0Z>DMK@kFEV|pW92kupL zFsm_o{s-$N-zgqMqlk}+$o9Vk_Qo_JqqCV%w%&r0p{4`M$N%MV z!Hg+E7&69j4ArYQI45b_*(K94m*K5PhyBgYXbO)&o?qP;egMa0*Hbc=^J>*`{~3?C zW*`|-BOj|JUZVTK)f2;a+CGp+E+rtYe)$B4Yv<430i~I7o4L|;7C=F0=qEGshu