From 9a75c167061327cc7f12125fe3eee1cd59fe2e87 Mon Sep 17 00:00:00 2001 From: luhongliang Date: Mon, 29 Apr 2024 12:01:05 +0800 Subject: [PATCH 01/99] Possible null pointer access during master-slave synchronization --- .../Plugins/Carla/Source/Carla/Game/CarlaEngine.cpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEngine.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEngine.cpp index 503942ce5..da793561b 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEngine.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEngine.cpp @@ -136,7 +136,11 @@ void FCarlaEngine::NotifyInitGame(const UCarlaSettings &Settings) case carla::multigpu::MultiGPUCommand::LOAD_MAP: { FString FinalPath((char *) Data.data()); - UGameplayStatics::OpenLevel(CurrentEpisode->GetWorld(), *FinalPath, true); + if(GetCurrentEpisode()) + { + UGameplayStatics::OpenLevel(GetCurrentEpisode()->GetWorld(), *FinalPath, true); + } + break; } case carla::multigpu::MultiGPUCommand::GET_TOKEN: From 1a05f256162c2e58ccc4f685c8ee33246d6b7b5b Mon Sep 17 00:00:00 2001 From: KianBahasadri <101868619+KianBahasadri@users.noreply.github.com> Date: Sat, 27 Apr 2024 01:03:14 -0400 Subject: [PATCH 02/99] Update build_docker_unreal.md Change docs from using Github password to use Github Access Token --- Docs/build_docker_unreal.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Docs/build_docker_unreal.md b/Docs/build_docker_unreal.md index 6a43c1b92..5f06efc60 100644 --- a/Docs/build_docker_unreal.md +++ b/Docs/build_docker_unreal.md @@ -52,10 +52,10 @@ The following steps will each take a long time. __1. Build the CARLA prerequisites image.__ -The following command will build an image called `carla-prerequisites` using `Prerequisites.Dockerfile`. In this build we install the compiler and required tools, download the Unreal Engine 4.26 fork and compile it. You will need to provide your login details as build arguments for the download of Unreal Engine to be successful: +The following command will build an image called `carla-prerequisites` using `Prerequisites.Dockerfile`. In this build we install the compiler and required tools, download the Unreal Engine 4.26 fork and compile it. You will need to provide your login details (use a Github Personal Access Token instead of a password) as build arguments for the download of Unreal Engine to be successful: ```sh -docker build --build-arg EPIC_USER= --build-arg EPIC_PASS= -t carla-prerequisites -f Prerequisites.Dockerfile . +docker build --build-arg EPIC_USER= --build-arg EPIC_PASS= -t carla-prerequisites -f Prerequisites.Dockerfile . ``` __2. Build the final CARLA image.__ From 3547112a44b64abc60e53874f59204241410ef9f Mon Sep 17 00:00:00 2001 From: KianBahasadri <101868619+KianBahasadri@users.noreply.github.com> Date: Sat, 27 Apr 2024 15:31:09 -0400 Subject: [PATCH 03/99] fixed typo --- Docs/build_docker_unreal.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Docs/build_docker_unreal.md b/Docs/build_docker_unreal.md index 5f06efc60..b15f3dc58 100644 --- a/Docs/build_docker_unreal.md +++ b/Docs/build_docker_unreal.md @@ -55,7 +55,7 @@ __1. Build the CARLA prerequisites image.__ The following command will build an image called `carla-prerequisites` using `Prerequisites.Dockerfile`. In this build we install the compiler and required tools, download the Unreal Engine 4.26 fork and compile it. You will need to provide your login details (use a Github Personal Access Token instead of a password) as build arguments for the download of Unreal Engine to be successful: ```sh -docker build --build-arg EPIC_USER= --build-arg EPIC_PASS= -t carla-prerequisites -f Prerequisites.Dockerfile . +docker build --build-arg EPIC_USER= --build-arg EPIC_PASS= -t carla-prerequisites -f Prerequisites.Dockerfile . ``` __2. Build the final CARLA image.__ From e9f6693f1ee64b52b65cf9e3e3e4cda9eabf542d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Xavier=20Sol=C3=A9=20Nogu=C3=A9s?= Date: Mon, 29 Apr 2024 12:11:37 +0200 Subject: [PATCH 04/99] Disable use less CPU in background --- Unreal/CarlaUE4/Config/DefaultEditorSettings.ini | 2 ++ 1 file changed, 2 insertions(+) create mode 100644 Unreal/CarlaUE4/Config/DefaultEditorSettings.ini diff --git a/Unreal/CarlaUE4/Config/DefaultEditorSettings.ini b/Unreal/CarlaUE4/Config/DefaultEditorSettings.ini new file mode 100644 index 000000000..6431ddc1d --- /dev/null +++ b/Unreal/CarlaUE4/Config/DefaultEditorSettings.ini @@ -0,0 +1,2 @@ +[/Script/UnrealEd.EditorPerformanceSettings] +bThrottleCPUWhenNotForeground=False From e351561eeabb8bcffcf832b253d4feff5ff92f7d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Xavier=20Sol=C3=A9=20Nogu=C3=A9s?= Date: Mon, 29 Apr 2024 14:49:38 +0200 Subject: [PATCH 05/99] Retry OSM2ODR download --- Util/BuildTools/BuildOSM2ODR.bat | 11 ++++------- Util/BuildTools/BuildOSM2ODR.sh | 13 ++++--------- 2 files changed, 8 insertions(+), 16 deletions(-) diff --git a/Util/BuildTools/BuildOSM2ODR.bat b/Util/BuildTools/BuildOSM2ODR.bat index 7d2a7df60..140699d21 100644 --- a/Util/BuildTools/BuildOSM2ODR.bat +++ b/Util/BuildTools/BuildOSM2ODR.bat @@ -92,13 +92,10 @@ if %REMOVE_INTERMEDIATE% == true ( rem Build OSM2ODR if %BUILD_OSM2ODR% == true ( - - if %GIT_PULL% == true ( - if not exist "%OSM2ODR_SOURCE_PATH%" git clone -b %OSM2ODR_BRANCH% %OSM2ODR_REPO% %OSM2ODR_SOURCE_PATH% - cd "%OSM2ODR_SOURCE_PATH%" - git fetch - git checkout %CURRENT_OSM2ODR_COMMIT% - ) + cd "%OSM2ODR_SOURCE_PATH%" + curl --retry 5 --retry-max-time 120 -L -o OSM2ODR.zip https://github.com/carla-simulator/sumo/archive/%CURRENT_OSM2ODR_COMMIT%.zip + tar -xf OSM2ODR.zip + cd sumo-%CURRENT_OSM2ODR_COMMIT% if not exist "%OSM2ODR_VSPROJECT_PATH%" mkdir "%OSM2ODR_VSPROJECT_PATH%" cd "%OSM2ODR_VSPROJECT_PATH%" diff --git a/Util/BuildTools/BuildOSM2ODR.sh b/Util/BuildTools/BuildOSM2ODR.sh index 61e7d449f..6f17ebf88 100755 --- a/Util/BuildTools/BuildOSM2ODR.sh +++ b/Util/BuildTools/BuildOSM2ODR.sh @@ -76,15 +76,10 @@ fi if ${BUILD_OSM2ODR} ; then log "Building OSM2ODR." - # [ ! -d ${OSM2ODR_BUILD_FOLDER} ] && mkdir ${OSM2ODR_BUILD_FOLDER} - if ${GIT_PULL} ; then - if [ ! -d ${OSM2ODR_SOURCE_FOLDER} ] ; then - git clone -b ${OSM2ODR_BRANCH} ${OSM2ODR_REPO} ${OSM2ODR_SOURCE_FOLDER} - fi - cd ${OSM2ODR_SOURCE_FOLDER} - git fetch - git checkout ${CURRENT_OSM2ODR_COMMIT} - fi + cd $OSM2ODR_SOURCE_PATH + curl --retry 5 --retry-max-time 120 -L -o OSM2ODR.zip https://github.com/carla-simulator/sumo/archive/$CURRENT_OSM2ODR_COMMIT.zip + tar -xf OSM2ODR.zip + cd sumo-$CURRENT_OSM2ODR_COMMIT mkdir -p ${OSM2ODR_BUILD_FOLDER} cd ${OSM2ODR_BUILD_FOLDER} From a1fb7a95967ccca9a951804e8cffff3fadb18966 Mon Sep 17 00:00:00 2001 From: xavisolesoft Date: Mon, 29 Apr 2024 18:44:06 +0100 Subject: [PATCH 06/99] Implement OSM2ODR download retry for linux --- Util/BuildTools/BuildOSM2ODR.sh | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/Util/BuildTools/BuildOSM2ODR.sh b/Util/BuildTools/BuildOSM2ODR.sh index 6f17ebf88..73f59bf6d 100755 --- a/Util/BuildTools/BuildOSM2ODR.sh +++ b/Util/BuildTools/BuildOSM2ODR.sh @@ -76,14 +76,18 @@ fi if ${BUILD_OSM2ODR} ; then log "Building OSM2ODR." - cd $OSM2ODR_SOURCE_PATH - curl --retry 5 --retry-max-time 120 -L -o OSM2ODR.zip https://github.com/carla-simulator/sumo/archive/$CURRENT_OSM2ODR_COMMIT.zip - tar -xf OSM2ODR.zip - cd sumo-$CURRENT_OSM2ODR_COMMIT + if [ ! -d ${OSM2ODR_SOURCE_FOLDER} ] ; then + cd ${CARLA_BUILD_FOLDER} + curl --retry 5 --retry-max-time 120 -L -o OSM2ODR.zip https://github.com/carla-simulator/sumo/archive/${CURRENT_OSM2ODR_COMMIT}.zip + unzip OSM2ODR.zip + rm -f OSM2ODR.zip + mv sumo-${CURRENT_OSM2ODR_COMMIT} ${OSM2ODR_SOURCE_FOLDER} + fi mkdir -p ${OSM2ODR_BUILD_FOLDER} cd ${OSM2ODR_BUILD_FOLDER} + export CC="$UE4_ROOT/Engine/Extras/ThirdPartyNotUE/SDKs/HostLinux/Linux_x64/v17_clang-10.0.1-centos7/x86_64-unknown-linux-gnu/bin/clang" export CXX="$UE4_ROOT/Engine/Extras/ThirdPartyNotUE/SDKs/HostLinux/Linux_x64/v17_clang-10.0.1-centos7/x86_64-unknown-linux-gnu/bin/clang++" export PATH="$UE4_ROOT/Engine/Extras/ThirdPartyNotUE/SDKs/HostLinux/Linux_x64/v17_clang-10.0.1-centos7/x86_64-unknown-linux-gnu/bin:$PATH" From 1071001114914a83eed4c1d774d5f8ac89465f3e Mon Sep 17 00:00:00 2001 From: xavisolesoft Date: Mon, 29 Apr 2024 18:45:26 +0100 Subject: [PATCH 07/99] Fix windows --- Util/BuildTools/BuildOSM2ODR.bat | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/Util/BuildTools/BuildOSM2ODR.bat b/Util/BuildTools/BuildOSM2ODR.bat index 140699d21..5a4fb36e0 100644 --- a/Util/BuildTools/BuildOSM2ODR.bat +++ b/Util/BuildTools/BuildOSM2ODR.bat @@ -93,9 +93,12 @@ if %REMOVE_INTERMEDIATE% == true ( rem Build OSM2ODR if %BUILD_OSM2ODR% == true ( cd "%OSM2ODR_SOURCE_PATH%" - curl --retry 5 --retry-max-time 120 -L -o OSM2ODR.zip https://github.com/carla-simulator/sumo/archive/%CURRENT_OSM2ODR_COMMIT%.zip - tar -xf OSM2ODR.zip - cd sumo-%CURRENT_OSM2ODR_COMMIT% + if not exist "%OSM2ODR_SOURCE_PATH%" ( + curl --retry 5 --retry-max-time 120 -L -o OSM2ODR.zip https://github.com/carla-simulator/sumo/archive/%CURRENT_OSM2ODR_COMMIT%.zip + tar -xf OSM2ODR.zip + del OSM2ODR.zip + ren sumo-%CURRENT_OSM2ODR_COMMIT% %OSM2ODR_SOURCE_PATH% + ) if not exist "%OSM2ODR_VSPROJECT_PATH%" mkdir "%OSM2ODR_VSPROJECT_PATH%" cd "%OSM2ODR_VSPROJECT_PATH%" From 4da350ab2d5b1c435c4f628b91eee3c502b12236 Mon Sep 17 00:00:00 2001 From: xavisolesoft Date: Mon, 29 Apr 2024 19:00:35 +0100 Subject: [PATCH 08/99] Unzip quiet --- Util/BuildTools/BuildOSM2ODR.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Util/BuildTools/BuildOSM2ODR.sh b/Util/BuildTools/BuildOSM2ODR.sh index 73f59bf6d..6264c9a2f 100755 --- a/Util/BuildTools/BuildOSM2ODR.sh +++ b/Util/BuildTools/BuildOSM2ODR.sh @@ -79,7 +79,7 @@ if ${BUILD_OSM2ODR} ; then if [ ! -d ${OSM2ODR_SOURCE_FOLDER} ] ; then cd ${CARLA_BUILD_FOLDER} curl --retry 5 --retry-max-time 120 -L -o OSM2ODR.zip https://github.com/carla-simulator/sumo/archive/${CURRENT_OSM2ODR_COMMIT}.zip - unzip OSM2ODR.zip + unzip -qq OSM2ODR.zip rm -f OSM2ODR.zip mv sumo-${CURRENT_OSM2ODR_COMMIT} ${OSM2ODR_SOURCE_FOLDER} fi From c7cfdad9a3e14457feacd399e2a13501f0634057 Mon Sep 17 00:00:00 2001 From: Daniel Grimm Date: Tue, 23 Apr 2024 13:06:32 +0200 Subject: [PATCH 09/99] v2x 2nd try --- Docs/python_api.md | 94 ++- Docs/ref_sensors.md | 102 +++ .../source/carla/client/ServerSideSensor.cpp | 10 + .../source/carla/client/ServerSideSensor.h | 3 + .../source/carla/client/detail/Client.cpp | 4 + LibCarla/source/carla/client/detail/Client.h | 2 + .../source/carla/client/detail/Simulator.cpp | 4 + .../source/carla/client/detail/Simulator.h | 2 + LibCarla/source/carla/sensor/SensorRegistry.h | 11 +- LibCarla/source/carla/sensor/data/LibITS.h | 796 ++++++++++++++++++ LibCarla/source/carla/sensor/data/V2XData.h | 107 +++ LibCarla/source/carla/sensor/data/V2XEvent.h | 61 ++ .../carla/sensor/s11n/V2XSerializer.cpp | 25 + .../source/carla/sensor/s11n/V2XSerializer.h | 79 ++ PythonAPI/carla/source/libcarla/Sensor.cpp | 1 + .../carla/source/libcarla/SensorData.cpp | 103 +++ PythonAPI/carla/source/libcarla/V2XData.cpp | 650 ++++++++++++++ PythonAPI/carla/source/libcarla/libcarla.cpp | 1 + Unreal/CarlaUE4/.ignore | 9 + .../Actor/ActorBlueprintFunctionLibrary.cpp | 480 +++++++++++ .../Actor/ActorBlueprintFunctionLibrary.h | 35 + .../Source/Carla/Sensor/CustomV2XSensor.cpp | 225 +++++ .../Source/Carla/Sensor/CustomV2XSensor.h | 73 ++ .../Source/Carla/Sensor/V2X/CaService.cpp | 755 +++++++++++++++++ .../Carla/Source/Carla/Sensor/V2X/CaService.h | 137 +++ .../Source/Carla/Sensor/V2X/PathLossModel.cpp | 563 +++++++++++++ .../Source/Carla/Sensor/V2X/PathLossModel.h | 144 ++++ .../Carla/Sensor/V2X/VehicleObstacle.cpp | 228 +++++ .../Carla/Source/Carla/Sensor/V2XSensor.cpp | 235 ++++++ .../Carla/Source/Carla/Sensor/V2XSensor.h | 77 ++ .../Carla/Source/Carla/Server/CarlaServer.cpp | 36 + 31 files changed, 5050 insertions(+), 2 deletions(-) create mode 100644 LibCarla/source/carla/sensor/data/LibITS.h create mode 100644 LibCarla/source/carla/sensor/data/V2XData.h create mode 100644 LibCarla/source/carla/sensor/data/V2XEvent.h create mode 100644 LibCarla/source/carla/sensor/s11n/V2XSerializer.cpp create mode 100644 LibCarla/source/carla/sensor/s11n/V2XSerializer.h create mode 100644 PythonAPI/carla/source/libcarla/V2XData.cpp create mode 100644 Unreal/CarlaUE4/.ignore create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/CustomV2XSensor.cpp create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/CustomV2XSensor.h create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/CaService.cpp create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/CaService.h create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.cpp create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.h create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/VehicleObstacle.cpp create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2XSensor.cpp create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2XSensor.h diff --git a/Docs/python_api.md b/Docs/python_api.md index 3cf5203b7..e0e0aa72a 100644 --- a/Docs/python_api.md +++ b/Docs/python_api.md @@ -419,6 +419,48 @@ Parses the location and extent of the bounding box to string. --- +## carla.CAMData +Inherited from _[carla.SensorData](#carla.SensorData)_
+This is the data type for cooperative awareness message reception, contained in a [CAMEvent](#carlacamevent) +### Instance Variables +- **power** (_float - dBm_) +Received power. + +### Methods +- **get**(**self**) +Get the CAM data. + - **Return:** _dict_ + + Returns a nested dictionary containing the message following the ETSI standard: + - `"Header"`: _dict_ + - `"Message"`: _dict_ + +##### Dunder methods +- **\__str__**(**self**) + +--- + +## carla.CAMEvent +Inherited from _[carla.SensorData](#carla.SensorData)_
+Class that defines the data provided by a sensor.other.v2x. This is a collection type to combine returning several [CAMData](#carlacamdata). + +### Instance Variables + + +### Methods +- **get_message_count**(**self**) +Get the number of received CAM's. + - **Return:** _int_ + +##### Dunder methods +- **\__getitem__**(**self**, **pos**=int) +- **\__iter__**(**self**) +Iterate over the [carla.CAMData](#carla.CAMData) retrieved as data. +- **\__len__**(**self**) + +--- + + ## carla.CityObjectLabel Enum declaration that contains the different tags available to filter the bounding boxes returned by [carla.World.get_level_bbs](#carla.World.get_level_bbs)(). These values correspond to the [semantic tag](ref_sensors.md#semantic-segmentation-camera) that the elements in the scene have. @@ -668,6 +710,49 @@ Converts the image to a depth map using a logarithmic scale, leading to better p No changes applied to the image. Used by the [RGB camera](ref_sensors.md#rgb-camera). --- +## carla.CustomV2XData +Inherited from _[carla.SensorData](#carla.SensorData)_
+This is the data type defining a custom V2X message. Received as part of a [CustomV2XEvent](#carla.CustomV2XEvent). + +### Instance Variables +- **power** (_float - dBm_) +Received power. + +### Methods +- **get**(**self**) +Get the custom message. + - **Return:** _dict_. + + Returns a nested dictionary containing the message. It has two primary keys: + - `"Header"` : _dict_ + - `"Message"`: _str_ + + +##### Dunder methods +- **\__str__**(**self**) + +--- + +## carla.CustomV2XEvent +Inherited from _[carla.SensorData](#carla.SensorData)_
+Class that defines the data provided by a sensor.other.v2x_custom. This is a collection type to combine returning several [CustomV2XData](#carla.CustomV2XData). + +### Instance Variables + + +### Methods +- **get_message_count**(**self**) +Get the number of received CAM's. + - **Return:** _int_ + +##### Dunder methods +- **\__getitem__**(**self**, **pos**=int) +- **\__iter__**(**self**) +Iterate over the [carla.CustomV2XData](#carla.CustomV2XData) retrieved as data. +- **\__len__**(**self**) + +--- + ## carla.DVSEvent Class that defines a DVS event. An event is a quadruple, so a tuple of 4 elements, with `x`, `y` pixel coordinate location, timestamp `t` and polarity `pol` of the event. Learn more about them [here](ref_sensors.md). @@ -2245,6 +2330,7 @@ Sensors compound a specific family of actors quite diverse and unique. They are - [Collision detector](ref_sensors.md#collision-detector). - [Lane invasion detector](ref_sensors.md#lane-invasion-detector). - [Obstacle detector](ref_sensors.md#obstacle-detector). + - [V2X sensor](ref_sensors.md#v2x-sensor). ### Instance Variables - **is_listening** (_boolean_) @@ -2272,6 +2358,10 @@ The function the sensor will be calling to every time the desired GBuffer textur - **Parameters:** - `gbuffer_id` (_[carla.GBufferTextureID](#carla.GBufferTextureID)_) - The ID of the target Unreal Engine GBuffer texture. - `callback` (_function_) - The called function with one argument containing the received GBuffer texture. +- **send**(**self**, **message**) +Instructs the sensor to send the string given by `message` to all other CustomV2XSensors on the next tick. + - **Parameters:** + - `message` (_string_) - The data to send. *Note*: maximum string length is 100 chars. - **stop**(**self**) Commands the sensor to stop listening for data. - **stop_gbuffer**(**self**, **gbuffer_id**) @@ -2295,7 +2385,9 @@ Base class for all the objects containing data generated by a [carla.Sensor](#ca - Obstacle detector: [carla.ObstacleDetectionEvent](#carla.ObstacleDetectionEvent).
- Radar sensor: [carla.RadarMeasurement](#carla.RadarMeasurement).
- RSS sensor: [carla.RssResponse](#carla.RssResponse).
- - Semantic LIDAR sensor: [carla.SemanticLidarMeasurement](#carla.SemanticLidarMeasurement). + - Semantic LIDAR sensor: [carla.SemanticLidarMeasurement](#carla.SemanticLidarMeasurement). + - Cooperative awareness messages V2X sensor: [carla.CAMEvent](#carla.CAMEvent). + - Custom V2X messages V2X sensor: [carla.CustomV2XEvent](#carla.CustomV2XEvent). ### Instance Variables - **frame** (_int_) diff --git a/Docs/ref_sensors.md b/Docs/ref_sensors.md index 477d16c51..5e1fd5e48 100644 --- a/Docs/ref_sensors.md +++ b/Docs/ref_sensors.md @@ -15,6 +15,9 @@ - [__Instance segmentation camera__](#instance-segmentation-camera) - [__DVS camera__](#dvs-camera) - [__Optical Flow camera__](#optical-flow-camera) +- [__V2X sensor__](#v2x-sensor) + - [Cooperative awareness](#cooperative-awareness-message) + - [Custom message](#custom-v2x-message) !!! Important All the sensors use the UE coordinate system (__x__-*forward*, __y__-*right*, __z__-*up*), and return coordinates in local space. When using any visualization software, pay attention to its coordinate system. Many invert the Y-axis, so visualizing the sensor data directly may result in mirrored outputs. @@ -904,3 +907,102 @@ The Optical Flow camera captures the motion perceived from the point of view of | `raw_data` | bytes | Array of BGRA 64-bit pixels containing two float values. |
+ +--- + +## V2X sensor + +Vehicle-to-everything (V2X) communication is an important aspect for future applications of cooperative intelligent transportation systems. In real vehicles, this requires a dedicated onboard unit (OBU) in each vehicle, that is able to send and receive information over wireless channels. Depending on the region (Europe, China, USA), different physical technologies, protocols and application messaging formats are used. + +CARLA currently supports simulation of a simple broadcast wireless channel and two application messages. Protocols for network access and forwarding are not supported yet. The two implemented messages are the [*Cooperative Awarness Message*](#cooperative-awareness-message) according to the European standard ETSI, and a [*custom message*](#custom-v2x-message) type, that can be used to transmit arbitrary string data (e.g. JSON). There are two distinct sensors for V2X communication, that can be used separately, one for each application message type. + +Basically, the wireless channel incorporates the following calculation for both sensors: + + ReceivedPower = OtherTransmitPower + combined_antenna_gain - loss + + IF (ReceivedPower >= receiver_sensitivity) + THEN message is received + +To simulate V2X communication, at least two V2X sensors of the same type need to be spawned (at least one sender-receiver pair). Because the received power is calculated on the receiver-side V2X sensor, only the antenna gain that is specified on the receiver-side sensor is incorporated in this calculation. Transmission power and receiver sensitivity can be configured (see [Blueprint attributes](#v2x-sensors-blueprint-attributes)). + +The *loss* calculation depends on +- the visbility condition between sender and receiver: line of sight (no obstacles), non-line of sight obstructed by buildings, or non-line of sight obstructed by vehicles, and +- the scenario: highway, rural, or urban environment + +While the visibility is simulated within CARLA, the scenario can be configured by the user (see [Blueprint attributes](#v2x-sensors-blueprint-attributes)), as well as several other attributes of the wireless channel. + +### Sensor (sub)types + +#### Cooperative Awareness Message + +* __Blueprint:__ sensor.other.v2x +* __Output:__ [carla.CAMData](python_api.md#carla.CAMData), triggered according to the ETSI CAM standard, unless configured otherwise + +Triggering conditions according to ETSI standard: +- Heading angle change > $4$° +- Position difference > $4$ m +- Speed change > $5$ m/s +- Time elapsed > CAM Generation time (configurable) +- Low Frequency Container Time Elapsed $> 500$ ms + +For the CAM V2X sensor, additional blueprint attributes apply: + +| Blueprint attribute | Type | Default | Description | +|-------------------------|--------|-------------------------|------------------------------------| +| Message generation | +| gen\_cam\_min | float | $0.1$ | Minimum elapsed time between two successive CAMs in seconds (s) | +| gen\_cam\_max | float | $1.0$ | Maximum elapsed time between two successive CAMs in seconds (s) | +| fixed\_rate | bool | false [true] | Generate a CAM in every CARLA tick (only for debug purposes, will result in slowdown) | +| Data generation | +| `noise_vel_stddev_x` | float | 0\.0 | Standard deviation parameter in the noise model for velocity (X axis). | +| `noise_accel_stddev_x` | float | 0\.0 | Standard deviation parameter in the noise model for acceleration (X axis). | +| `noise_accel_stddev_y` | float | 0\.0 | Standard deviation parameter in the noise model for acceleration (Y axis). | +| `noise_accel_stddev_z` | float | 0\.0 | Standard deviation parameter in the noise model for acceleration (Z axis). | +| `noise_yawrate_bias` | float | 0\.0 | Mean parameter in the noise model for yaw rate. | +| `noise_yawrate_stddev` | float | 0\.0 | Standard deviation parameter in the noise model for yaw rate. | +| `noise_alt_bias` | float | 0\.0 | Mean parameter in the noise model for altitude. | +| `noise_alt_stddev` | float | 0\.0 | Standard deviation parameter in the noise model for altitude. | +| `noise_lat_bias` | float | 0\.0 | Mean parameter in the noise model for latitude. | +| `noise_lat_stddev` | float | 0\.0 | Standard deviation parameter in the noise model for latitude. | +| `noise_lon_bias` | float | 0\.0 | Mean parameter in the noise model for longitude. | +| `noise_lon_stddev` | float | 0\.0 | Standard deviation parameter in the noise model for longitude. | +| `noise_head_bias` | float | 0\.0 | Mean parameter in the noise model for heading. | +| `noise_head_stddev` | float | 0\.0 | Standard deviation parameter in the noise model for heading. | + +#### Custom V2X Message + +* __Blueprint:__ sensor.other.v2x_custom +* __Output:__ [carla.CustomV2XData](python_api.md#carla.CustomV2XData), triggered with next tick after a *send()* was called + +##### Methods +- **send**(**self**, **callback**) +The function the user has to call every time to send a message. This function needs for an argument containing an object type [carla.SensorData](#carla.SensorData) to work with. + - **Parameters:** + - `data` (_function_) - The called function with one argument containing the sensor data. + +The custom V2X message sensor works a little bit different than other sensors, because it has the *send* function in addition to the *listen* function, that needs to be called, before another sensor of this type will receive anything. The transmission of a custom message is only triggered, when *send* is called. Each message given to the *send* function is only transmitted once to all Custom V2X Message sensors currently spawned. + +Example: + + bp = world.get_blueprint_library().find('sensor.other.v2x_custom') + sensor = world.spawn_actor(bp, carla.Transform(), attach_to=parent) + sensor.send("Hello CARLA") + +### V2X sensors blueprint attributes + +| Blueprint attribute | Type | Default | Description | +|-------------------------|--------|-------------------------|------------------------------------| +| transmit\_power | float | $21.5$ | Sender transmission power in dBm | +| receiver\_sensitivity | float | $-99$ | Receiver sensitivity in dBm | +| frequency\_ghz | float | $5.9$ | Transmission frequency in GHz. 5.9 GHz is standard for several physical channels. | +| noise\_seed | int | $0$ | Random parameter for initialization of noise | +| filter\_distance | float | $500$ | Maximum transmission distance in meter, path loss calculations above are skipped for simulation speed | +| __Path loss model parameters__ | +| combined\_antenna\_gain | float | $10.0$ | Combined gain of sender and receiver antennas in dBi, parameter for radiation efficiency and directivity | +| d\_ref | float | $ 1.0 $ | reference distance for Log-distance path loss model in meter | +| path\_loss\_exponent | float | 2.7 | Loss parameter for non-line of sight due to building obstruction | +| scenario | string | urban | Options: [urban, rural, highway], defines the fading noise parameters | +| path\_loss\_model | string | geometric | general path loss model to be used. Options: [geometric, winner] | +| use\_etsi\_fading | bool | true | Use the fading params as mentioned in the ETSI publication (true), or use the custom fading standard deviation | +| custom\_fading\_stddev | float | 0.0 | Custom value for fading standard deviation, only used if `use_etsi_fading` is set to `false` | + diff --git a/LibCarla/source/carla/client/ServerSideSensor.cpp b/LibCarla/source/carla/client/ServerSideSensor.cpp index 19ec11c1a..30803b172 100644 --- a/LibCarla/source/carla/client/ServerSideSensor.cpp +++ b/LibCarla/source/carla/client/ServerSideSensor.cpp @@ -55,6 +55,16 @@ namespace client { listening_mask.reset(0); } + void ServerSideSensor::Send(std::string message) { + log_debug("calling sensor Send() ", GetDisplayId()); + if (GetActorDescription().description.id != "sensor.other.v2x_custom") + { + log_warning("Send methods are not supported on non-V2x sensors (sensor.other.v2x_custom)."); + return; + } + GetEpisode().Lock()->Send(*this,message); + } + void ServerSideSensor::ListenToGBuffer(uint32_t GBufferId, CallbackFunctionType callback) { log_debug(GetDisplayId(), ": subscribing to gbuffer stream"); RELEASE_ASSERT(GBufferId < GBufferTextureCount); diff --git a/LibCarla/source/carla/client/ServerSideSensor.h b/LibCarla/source/carla/client/ServerSideSensor.h index fae320aba..288f0e235 100644 --- a/LibCarla/source/carla/client/ServerSideSensor.h +++ b/LibCarla/source/carla/client/ServerSideSensor.h @@ -56,6 +56,9 @@ namespace client { /// Return if the sensor is publishing for ROS2 bool IsEnabledForROS(); + /// Send data via this sensor + void Send(std::string message); + /// @copydoc Actor::Destroy() /// /// Additionally stop listening. diff --git a/LibCarla/source/carla/client/detail/Client.cpp b/LibCarla/source/carla/client/detail/Client.cpp index fe5c327f0..72b9e705e 100644 --- a/LibCarla/source/carla/client/detail/Client.cpp +++ b/LibCarla/source/carla/client/detail/Client.cpp @@ -670,6 +670,10 @@ namespace detail { return _pimpl->CallAndWait("is_sensor_enabled_for_ros", thisToken.get_stream_id()); } + void Client::Send(rpc::ActorId ActorId, std::string message) { + _pimpl->AsyncCall("send", ActorId, message); + } + void Client::SubscribeToGBuffer( rpc::ActorId ActorId, uint32_t GBufferId, diff --git a/LibCarla/source/carla/client/detail/Client.h b/LibCarla/source/carla/client/detail/Client.h index 73f8cdb85..064cd2c86 100644 --- a/LibCarla/source/carla/client/detail/Client.h +++ b/LibCarla/source/carla/client/detail/Client.h @@ -430,6 +430,8 @@ namespace detail { rpc::ActorId ActorId, uint32_t GBufferId); + void Send(rpc::ActorId ActorId, std::string message); + void DrawDebugShape(const rpc::DebugShape &shape); void ApplyBatch( diff --git a/LibCarla/source/carla/client/detail/Simulator.cpp b/LibCarla/source/carla/client/detail/Simulator.cpp index 28eb8be68..8b4089a88 100644 --- a/LibCarla/source/carla/client/detail/Simulator.cpp +++ b/LibCarla/source/carla/client/detail/Simulator.cpp @@ -441,6 +441,10 @@ EpisodeProxy Simulator::GetCurrentEpisode() { _client.FreezeAllTrafficLights(frozen); } + void Simulator::Send(const Sensor &sensor, std::string message) { + _client.Send(sensor.GetId(), message); + } + // ========================================================================= /// -- Texture updating operations // ========================================================================= diff --git a/LibCarla/source/carla/client/detail/Simulator.h b/LibCarla/source/carla/client/detail/Simulator.h index 6f5d950c3..7dea3ced4 100644 --- a/LibCarla/source/carla/client/detail/Simulator.h +++ b/LibCarla/source/carla/client/detail/Simulator.h @@ -695,6 +695,8 @@ namespace detail { Actor & sensor, uint32_t gbuffer_id); + void Send(const Sensor &sensor, std::string message); + /// @} // ========================================================================= /// @name Operations with traffic lights diff --git a/LibCarla/source/carla/sensor/SensorRegistry.h b/LibCarla/source/carla/sensor/SensorRegistry.h index 901a47dfd..6f7c21745 100644 --- a/LibCarla/source/carla/sensor/SensorRegistry.h +++ b/LibCarla/source/carla/sensor/SensorRegistry.h @@ -29,6 +29,7 @@ #include "carla/sensor/s11n/SemanticLidarSerializer.h" #include "carla/sensor/s11n/GBufferUint8Serializer.h" #include "carla/sensor/s11n/GBufferFloatSerializer.h" +#include "carla/sensor/s11n/V2XSerializer.h" // 2. Add a forward-declaration of the sensor here. class ACollisionSensor; @@ -50,6 +51,8 @@ class ARssSensor; class FWorldObserver; struct FCameraGBufferUint8; struct FCameraGBufferFloat; +class AV2XSensor; +class ACustomV2XSensor; namespace carla { namespace sensor { @@ -80,7 +83,11 @@ namespace sensor { std::pair, std::pair, std::pair, - std::pair + std::pair, + std::pair, + std::pair + + >; } // namespace sensor @@ -108,5 +115,7 @@ namespace sensor { #include "Carla/Sensor/SemanticSegmentationCamera.h" #include "Carla/Sensor/InstanceSegmentationCamera.h" #include "Carla/Sensor/WorldObserver.h" +#include "Carla/Sensor/V2XSensor.h" +#include "Carla/Sensor/CustomV2XSensor.h" #endif // LIBCARLA_SENSOR_REGISTRY_WITH_SENSOR_INCLUDES diff --git a/LibCarla/source/carla/sensor/data/LibITS.h b/LibCarla/source/carla/sensor/data/LibITS.h new file mode 100644 index 000000000..6fbb32bd7 --- /dev/null +++ b/LibCarla/source/carla/sensor/data/LibITS.h @@ -0,0 +1,796 @@ +#pragma once +#include +#include +#include + +class ITSContainer +{ + +public: + + typedef bool OptionalValueAvailable_t; + + /* Latitude Dependencies*/ + typedef enum Latitude + { + Latitude_oneMicroDegreeNorth = 10, + Latitude_oneMicroDegreeSouth = -10, + Latitude_unavailable = 900000001 + } e_Latitude; + + /* Latitude */ + typedef long Latitude_t; + + /* Longitude Dependencies */ + typedef enum Longitude + { + Longitude_oneMicroDegreeEast = 10, + Longitude_oneMicroDegreeWest = -10, + Longitude_unavailable = 1800000001 + } e_Longitude; + + /* Longitude */ + typedef long Longitude_t; + + /* SemiAxisLength Dependencies */ + typedef enum SemiAxisLength + { + SemiAxisLength_oneCentimeter = 1, + SemiAxisLength_outOfRange = 4094, + SemiAxisLength_unavailable = 4095 + } e_SemiAxisLength; + + /* SemiAxisLength*/ + typedef long SemiAxisLength_t; + + /* HeadingValue Dependencies */ + typedef enum HeadingValue + { + HeadingValue_wgs84North = 0, + HeadingValue_wgs84East = 900, + HeadingValue_wgs84South = 1800, + HeadingValue_wgs84West = 2700, + HeadingValue_unavailable = 3601 + } e_HeadingValue; + + /* HeadingValue */ + typedef long HeadingValue_t; + + /* HeadingConfidence Dependencies */ + typedef enum HeadingConfidence { + HeadingConfidence_equalOrWithinZeroPointOneDegree = 1, + HeadingConfidence_equalOrWithinOneDegree = 10, + HeadingConfidence_outOfRange = 126, + HeadingConfidence_unavailable = 127 + } e_HeadingConfidence; + + /* HeadingConfidence */ + typedef long HeadingConfidence_t; + + /* PosConfidenceEllipse*/ + typedef struct PosConfidenceEllipse + { + SemiAxisLength_t semiMajorConfidence; + SemiAxisLength_t semiMinorConfidence; + HeadingValue_t semiMajorOrientation; + } PosConfidenceEllipse_t; + + /* AltitudeValue Dependencies */ + typedef enum AltitudeValue + { + AltitudeValue_referenceEllipsoidSurface = 0, + AltitudeValue_oneCentimeter = 1, + AltitudeValue_unavailable = 800001 + } e_AltitudeValue; + + /* AltitudeValue */ + typedef long AltitudeValue_t; + + /* AltitudeConfidence Dependencies */ + typedef enum AltitudeConfidence + { + AltitudeConfidence_alt_000_01 = 0, + AltitudeConfidence_alt_000_02 = 1, + AltitudeConfidence_alt_000_05 = 2, + AltitudeConfidence_alt_000_10 = 3, + AltitudeConfidence_alt_000_20 = 4, + AltitudeConfidence_alt_000_50 = 5, + AltitudeConfidence_alt_001_00 = 6, + AltitudeConfidence_alt_002_00 = 7, + AltitudeConfidence_alt_005_00 = 8, + AltitudeConfidence_alt_010_00 = 9, + AltitudeConfidence_alt_020_00 = 10, + AltitudeConfidence_alt_050_00 = 11, + AltitudeConfidence_alt_100_00 = 12, + AltitudeConfidence_alt_200_00 = 13, + AltitudeConfidence_outOfRange = 14, + AltitudeConfidence_unavailable = 15 + }e_AltitudeConfidence; + + /* AltitudeConfidence */ + typedef long AltitudeConfidence_t; + + /* Altitude */ + typedef struct Altitude + { + AltitudeValue_t altitudeValue; + AltitudeConfidence_t altitudeConfidence; + }Altitude_t; + + /* ReferencePosition */ + typedef struct ReferencePosition + { + Latitude_t latitude; + Longitude_t longitude; + PosConfidenceEllipse_t positionConfidenceEllipse; + Altitude_t altitude; + } ReferencePosition_t; + + /* StationType Dependencies */ + typedef enum StationType + { + StationType_unknown = 0, + StationType_pedestrian = 1, + StationType_cyclist = 2, + StationType_moped = 3, + StationType_motorcycle = 4, + StationType_passengerCar = 5, + StationType_bus = 6, + StationType_lightTruck = 7, + StationType_heavyTruck = 8, + StationType_trailer = 9, + StationType_specialVehicles = 10, + StationType_tram = 11, + StationType_roadSideUnit = 15 + } e_StationType; + + /* StationType */ + typedef long StationType_t; + + /* StationID*/ + typedef long StationID_t; + // typedef unsigned long StationID_t; + + /* Dependencies */ + typedef enum protocolVersion + { + protocolVersion_currentVersion = 1 + } e_protocolVersion; + + typedef enum messageID + { + messageID_custom = 0, + messageID_denm = 1, + messageID_cam = 2, + messageID_poi = 3, + messageID_spat = 4, + messageID_map = 5, + messageID_ivi = 6, + messageID_ev_rsr = 7 + } e_messageID; + + typedef struct ItsPduHeader + { + long protocolVersion; + long messageID; + StationID_t stationID; + } ItsPduHeader_t; + + /* Heading */ + typedef struct Heading + { + HeadingValue_t headingValue; + HeadingConfidence_t headingConfidence; + } Heading_t; + + /* SpeedValue Dependencies */ + typedef enum SpeedValue + { + SpeedValue_standstill = 0, + SpeedValue_oneCentimeterPerSec = 1, + SpeedValue_unavailable = 16383 + } e_SpeedValue; + + /* SpeedValue */ + typedef long SpeedValue_t; + + /* SpeedConfidence Dependencies */ + typedef enum SpeedConfidence + { + SpeedConfidence_equalOrWithInOneCentimerterPerSec = 1, + SpeedConfidence_equalOrWithinOneMeterPerSec = 100, + SpeedConfidence_outOfRange = 126, + SpeedConfidence_unavailable = 127 + } e_SpeedConfidence; + + /* SpeedConfidence */ + typedef long SpeedConfidence_t; + + /* Speed */ + typedef struct speed + { + SpeedValue_t speedValue; + SpeedConfidence_t speedConfidence; + } Speed_t; + + /* DriveDirection Dependencies */ + typedef enum DriveDirection + { + DriveDirection_forward = 0, + DriveDirection_backward = 1, + DriveDirection_unavailable = 2 + } e_DriveDirection; + + /* DriveDirection */ + typedef long DriveDirection_t; + + /* VehicleLength Dependencies */ + typedef enum VehicleLengthValue + { + VehicleLengthValue_tenCentimeters = 1, + VehicleLengthValue_outOfRange = 1022, + VehicleLengthValue_unavailable = 1023 + } e_VehicleLengthValue; + + /* VehicleLengthValue */ + typedef long VehicleLengthValue_t; + + /* VehicleLengthConfidenceIndication Dependencies */ + typedef enum VehicleLengthConfidenceIndication + { + VehicleLengthConfidenceIndication_noTrailerPresent = 0, + VehicleLengthConfidenceIndication_trailerPresentWithKnownLength = 1, + VehicleLengthConfidenceIndication_trailerPresentWithUnknownLength = 2, + VehicleLengthConfidenceIndication_trailerPresenceIsUnknown = 3, + VehicleLengthConfidenceIndication_unavailable = 4 + } e_VehicleLengthConfidenceIndication; + + /* VehicleLengthConfidenceIndication */ + typedef long VehicleLengthConfidenceIndication_t; + + /* VehicleLength */ + typedef struct VehicleLength + { + VehicleLengthValue_t vehicleLengthValue; + VehicleLengthConfidenceIndication_t vehicleLengthConfidenceIndication; + } VehicleLength_t; + + /* VehicleWidth Dependencies */ + typedef enum VehicleWidth + { + VehicleWidth_tenCentimeters = 1, + VehicleWidth_outOfRange = 61, + VehicleWidth_unavailable = 62 + } e_VehicleWidth; + + /* VehicleWidth */ + typedef long VehicleWidth_t; + + /* LongitudinalAcceleration Dependencies */ + typedef enum LongitudinalAcceletationValue + { + LongitudinalAccelerationValue_pointOneMeterPerSecSquaredForward = 1, + LongitudinalAccelerationValue_pointOneMeterPerSecSquaredBackWard = -1, + LongitudinalAccelerationValue_unavailable = 161 + } e_LongitudinalAccelerationValue; + + /* LongitudinalAcclerationValue */ + typedef long LongitudinalAccelerationValue_t; + + /* AccelerationConfidence Dependencies */ + typedef enum AccelerationConfidence + { + AccelerationConfindence_pointOneMeterPerSecSquared = 1, + AccelerationConfidence_outOfRange = 101, + AccelerationConfidence_unavailable = 102 + } e_AccelerationConfidence; + + /* AccelerationConfidence*/ + typedef long AccelerationConfidence_t; + + /* LongitudinalAcceleration */ + typedef struct LongitudinalAcceleration + { + LongitudinalAccelerationValue_t longitudinalAccelerationValue; + AccelerationConfidence_t longitudinalAccelerationConfidence; + } LongitudinalAcceleration_t; + + /* CurvatureValue Dependencies */ + typedef enum CurvatureValue + { + CurvatureValue_straight = 0, + CurvatureValue_reciprocalOf1MeterRadiusToRight = -30000, + CurvatureValue_reciprocalOf1MeterRadiusToLeft = 30000, + CurvatureValue_unavailable = 30001 + } e_CurvatureValue; + + /* CurvatureValue */ + typedef long CurvatureValue_t; + + /* CurvatureConfidence Dependencies*/ + typedef enum CurvatureConfidence + { + CurvatureConfidence_onePerMeter_0_00002 = 0, + CurvatureConfidence_onePerMeter_0_0001 = 1, + CurvatureConfidence_onePerMeter_0_0005 = 2, + CurvatureConfidence_onePerMeter_0_002 = 3, + CurvatureConfidence_onePerMeter_0_01 = 4, + CurvatureConfidence_onePerMeter_0_1 = 5, + CurvatureConfidence_outOfRange = 6, + CurvatureConfidence_unavailable = 7 + } e_CurvatureConfidence; + + /* CurvatureConfidence */ + typedef long CurvatureConfidence_t; + + /* Curvature */ + typedef struct Curvature + { + CurvatureValue_t curvatureValue; + CurvatureConfidence_t curvatureConfidence; + } Curvature_t; + + /* CurvatureCalculationMode Dependencies */ + typedef enum CurvatureCalculationMode + { + CurvatureCalculationMode_yarRateUsed = 0, + CurvatureCalculationMode_yarRateNotUsed = 1, + CurvatureCalculationMode_unavailable = 2 + } e_CurvatureCalculationMode; + + /* CurvatureCalculationMode */ + typedef long CurvatureCalculationMode_t; + + /* YawRateValue Dependencies */ + typedef enum YawRateValue + { + YawRateValue_straight = 0, + YawRateValue_degSec_000_01ToRight = -1, + YawRateValue_degSec_000_01ToLeft = 1, + YawRateValue_unavailable = 32767 + } e_YawRateValue; + + /* YawRateValue */ + typedef long YawRateValue_t; + + /* YawRateConfidence Dependencies */ + typedef enum YawRateConfidence { + YawRateConfidence_degSec_000_01 = 0, + YawRateConfidence_degSec_000_05 = 1, + YawRateConfidence_degSec_000_10 = 2, + YawRateConfidence_degSec_001_00 = 3, + YawRateConfidence_degSec_005_00 = 4, + YawRateConfidence_degSec_010_00 = 5, + YawRateConfidence_degSec_100_00 = 6, + YawRateConfidence_outOfRange = 7, + YawRateConfidence_unavailable = 8 + } e_YawRateConfidence; + + /* YawRateConfidence */ + typedef long YawRateConfidence_t; + + /* YawRate */ + typedef struct YawRate + { + YawRateValue_t yawRateValue; + YawRateConfidence_t yawRateConfidence; + } YawRate_t; + + /* AccelerationControl Dependencies */ + typedef enum AccelerationControl { + AccelerationControl_brakePedalEngaged = 0, + AccelerationControl_gasPedalEngaged = 1, + AccelerationControl_emergencyBrakeEngaged = 2, + AccelerationControl_collisionWarningEngaged = 3, + AccelerationControl_accEngaged = 4, + AccelerationControl_cruiseControlEngaged = 5, + AccelerationControl_speedLimiterEngaged = 6 + } e_AccelerationControl; + + /* BIT_STRING_s*/ + // struct BIT_STRING_s { + // // uint8_t *buf; /* BIT STRING body */ + // //note: we cant use pointers + // uint8_t buf; /* BIT STRING body */ + // int size; /* Size of the above buffer */ + + // int bits_unused;/* Unused trailing bits in the last octet (0..7) */ + + // }; + + /* AccelerationControl */ + typedef uint8_t AccelerationControl_t; + + /* LanePosition Dependencies */ + typedef enum LanePosition { + LanePosition_offTheRoad = -1, + LanePosition_hardShoulder = 0, + LanePosition_outermostDrivingLane = 1, + LanePosition_secondLaneFromOutside = 2 + } e_LanePosition; + + /* LanePosition */ + typedef long LanePosition_t; + + /* SteeringWheelAngleValue Dependencies */ + typedef enum SteeringWheelAngleValue { + SteeringWheelAngleValue_straight = 0, + SteeringWheelAngleValue_onePointFiveDegreesToRight = -1, + SteeringWheelAngleValue_onePointFiveDegreesToLeft = 1, + SteeringWheelAngleValue_unavailable = 512 + } e_SteeringWheelAngleValue; + + /* SteeringWheelAngleValue */ + typedef long SteeringWheelAngleValue_t; + + /* SteeringWheelAngleConfidence Dependencies */ + typedef enum SteeringWheelAngleConfidence { + SteeringWheelAngleConfidence_equalOrWithinOnePointFiveDegree = 1, + SteeringWheelAngleConfidence_outOfRange = 126, + SteeringWheelAngleConfidence_unavailable = 127 + } e_SteeringWheelAngleConfidence; + + /* SteeringWheelAngleConfidence */ + typedef long SteeringWheelAngleConfidence_t; + + /* SteeringWheelAngle */ + typedef struct SteeringWheelAngle + { + SteeringWheelAngleValue_t steeringWheelAngleValue; + SteeringWheelAngleConfidence_t steeringWheelAngleConfidence; + } SteeringWheelAngle_t; + + /* LateralAccelerationValue Dependencies */ + typedef enum LateralAccelerationValue { + LateralAccelerationValue_pointOneMeterPerSecSquaredToRight = -1, + LateralAccelerationValue_pointOneMeterPerSecSquaredToLeft = 1, + LateralAccelerationValue_unavailable = 161 + } e_LateralAccelerationValue; + + /* LateralAccelerationValue */ + typedef long LateralAccelerationValue_t; + + /* LateralAcceleration */ + typedef struct LateralAcceleration + { + LateralAccelerationValue_t lateralAccelerationValue; + AccelerationConfidence_t lateralAccelerationConfidence; + } LateralAcceleration_t; + + /* VerticalAccelerationValue Dependencies */ + typedef enum VerticalAccelerationValue { + VerticalAccelerationValue_pointOneMeterPerSecSquaredUp = 1, + VerticalAccelerationValue_pointOneMeterPerSecSquaredDown = -1, + VerticalAccelerationValue_unavailable = 161 + } e_VerticalAccelerationValue; + + /* VerticalAccelerationValue */ + typedef long VerticalAccelerationValue_t; + + /* VerticalAcceleration */ + typedef struct VerticalAcceleration + { + VerticalAccelerationValue_t verticalAccelerationValue; + AccelerationConfidence_t verticalAccelerationConfidence; + } VerticalAcceleration_t; + + /* PerformanceClass Dependencies */ + typedef enum PerformanceClass { + PerformanceClass_unavailable = 0, + PerformanceClass_performanceClassA = 1, + PerformanceClass_performanceClassB = 2 + } e_PerformanceClass; + + /* PerformanceClass */ + typedef long PerformanceClass_t; + + /* ProtectedZoneID */ + typedef long ProtectedZoneID_t; + + /* CenDsrcTollingZoneID */ + typedef ProtectedZoneID_t CenDsrcTollingZoneID_t; + + /* CenDsrcTollingZone */ + typedef struct CenDsrcTollingZone { + Latitude_t protectedZoneLatitude; + Longitude_t protectedZoneLongitude; + CenDsrcTollingZoneID_t cenDsrcTollingZoneID; /* OPTIONAL */ + OptionalValueAvailable_t cenDsrcTollingZoneIDAvailable; + } CenDsrcTollingZone_t; + + /* ProtectedZoneType Dependencies */ + typedef enum ProtectedZoneType { + ProtectedZoneType_cenDsrcTolling = 0 + + } e_ProtectedZoneType; + + /* ProtectedZoneType */ + typedef long ProtectedZoneType_t; + + /* TimestampIts Dependencies */ + typedef enum TimestampIts { + TimestampIts_utcStartOf2004 = 0, + TimestampIts_oneMillisecAfterUTCStartOf2004 = 1 + } e_TimestampIts; + + + + /* TimestampIts */ + // typedef BIT_STRING_s TimestampIts_t; + typedef long TimestampIts_t; + + /* ProtectedZoneRadius Dependencies */ + typedef enum ProtectedZoneRadius { + ProtectedZoneRadius_oneMeter = 1 + } e_ProtectedZoneRadius; + + /* ProtectedZoneRadius */ + typedef long ProtectedZoneRadius_t; + + /* ProtectedCommunicationZone */ + typedef struct ProtectedCommunicationZone { + ProtectedZoneType_t protectedZoneType; + TimestampIts_t expiryTime /* OPTIONAL */; + OptionalValueAvailable_t expiryTimeAvailable; + Latitude_t protectedZoneLatitude; + Longitude_t protectedZoneLongitude; + ProtectedZoneRadius_t protectedZoneRadius /* OPTIONAL */; + OptionalValueAvailable_t protectedZoneRadiusAvailable; + ProtectedZoneID_t protectedZoneID /* OPTIONAL */; + OptionalValueAvailable_t protectedZoneIDAvailable; + } ProtectedCommunicationZone_t; + + /* ProtectedCommunicationZonesRSU */ + typedef struct ProtectedCommunicationZonesRSU { + long ProtectedCommunicationZoneCount; + std::vector list; + } ProtectedCommunicationZonesRSU_t; + + /* VehicleRole Dependencies */ + typedef enum VehicleRole { + VehicleRole_default = 0, + VehicleRole_publicTransport = 1, + VehicleRole_specialTransport = 2, + VehicleRole_dangerousGoods = 3, + VehicleRole_roadWork = 4, + VehicleRole_rescue = 5, + VehicleRole_emergency = 6, + VehicleRole_safetyCar = 7, + VehicleRole_agriculture = 8, + VehicleRole_commercial = 9, + VehicleRole_military = 10, + VehicleRole_roadOperator = 11, + VehicleRole_taxi = 12, + VehicleRole_reserved1 = 13, + VehicleRole_reserved2 = 14, + VehicleRole_reserved3 = 15 + } e_VehicleRole; + + /* VehicleRole */ + typedef long VehicleRole_t; + + /* ExteriorLights Dependencies */ + typedef enum ExteriorLights { + ExteriorLights_lowBeamHeadlightsOn = 0, + ExteriorLights_highBeamHeadlightsOn = 1, + ExteriorLights_leftTurnSignalOn = 2, + ExteriorLights_rightTurnSignalOn = 3, + ExteriorLights_daytimeRunningLightsOn = 4, + ExteriorLights_reverseLightOn = 5, + ExteriorLights_fogLightOn = 6, + ExteriorLights_parkingLightsOn = 7 + } e_ExteriorLights; + + /* ExteriorLights */ + // typedef BIT_STRING_s ExteriorLights_t; + typedef uint8_t ExteriorLights_t; + /* DeltaLatitude Dependencies */ + typedef enum DeltaLatitude { + DeltaLatitude_oneMicrodegreeNorth = 10, + DeltaLatitude_oneMicrodegreeSouth = -10, + DeltaLatitude_unavailable = 131072 + } e_DeltaLatitude; + + /* DeltaLatitude */ + typedef long DeltaLatitude_t; + + /* DeltaLongitude Dependencies */ + typedef enum DeltaLongitude { + DeltaLongitude_oneMicrodegreeEast = 10, + DeltaLongitude_oneMicrodegreeWest = -10, + DeltaLongitude_unavailable = 131072 + } e_DeltaLongitude; + + /* DeltaLongitude */ + typedef long DeltaLongitude_t; + + /* DeltaAltitude Dependencies */ + typedef enum DeltaAltitude { + DeltaAltitude_oneCentimeterUp = 1, + DeltaAltitude_oneCentimeterDown = -1, + DeltaAltitude_unavailable = 12800 + } e_DeltaAltitude; + + /* DeltaAltitude */ + typedef long DeltaAltitude_t; + + /* DeltaReferencePosition */ + typedef struct DeltaReferencePosition { + DeltaLatitude_t deltaLatitude; + DeltaLongitude_t deltaLongitude; + DeltaAltitude_t deltaAltitude; + } DeltaReferencePosition_t; + + /* PathDeltaTime Dependencies */ + typedef enum PathDeltaTime { + PathDeltaTime_tenMilliSecondsInPast = 1 + } e_PathDeltaTime; + + /* PathDeltaTime */ + typedef long PathDeltaTime_t; + + /* PathPoint */ + typedef struct PathPoint { + DeltaReferencePosition_t pathPosition; + PathDeltaTime_t *pathDeltaTime /* OPTIONAL */; + + } PathPoint_t; + + /* PathHistory */ + typedef struct PathHistory { + long NumberOfPathPoint; + std::vector data; + } PathHistory_t; +}; + +class CAMContainer +{ +public: + + /* GenerationDeltaTime Dependencies*/ + typedef enum GenerationDeltaTime + { + GenerationDeltaTime_oneMilliSec = 1 + } e_GenerationDeltaTime; + + /* GenerationDeltaTime */ + typedef long GenerationDeltaTime_t; + + /* BasicContainer */ + typedef struct BasicContainer + { + ITSContainer::StationType_t stationType; + ITSContainer::ReferencePosition_t referencePosition; + } BasicContainer_t; + + /* HighFrequencyContainer Dependencies */ + typedef enum HighFrequencyContainer_PR : long + { + HighFrequencyContainer_PR_NOTHING, /* No components present */ + HighFrequencyContainer_PR_basicVehicleContainerHighFrequency, + HighFrequencyContainer_PR_rsuContainerHighFrequency + } HighFrequencyContainer_PR; + + typedef bool OptionalStructAvailable_t; + + /* BasicVehicleContainerHighFrequency*/ + typedef struct BasicVehicleContainerHighFrequency + { + ITSContainer::Heading_t heading; + ITSContainer::Speed_t speed; + ITSContainer::DriveDirection_t driveDirection; + ITSContainer::VehicleLength_t vehicleLength; + ITSContainer::VehicleWidth_t vehicleWidth; + ITSContainer::LongitudinalAcceleration_t longitudinalAcceleration; + ITSContainer::Curvature_t curvature; + ITSContainer::CurvatureCalculationMode_t curvatureCalculationMode; + ITSContainer::YawRate_t yawRate; + + OptionalStructAvailable_t accelerationControlAvailable; + ITSContainer::AccelerationControl_t accelerationControl /* OPTIONAL */; + + OptionalStructAvailable_t lanePositionAvailable; + ITSContainer::LanePosition_t lanePosition /* OPTIONAL */; + + OptionalStructAvailable_t steeringWheelAngleAvailable; + ITSContainer::SteeringWheelAngle_t steeringWheelAngle /* OPTIONAL */; + + OptionalStructAvailable_t lateralAccelerationAvailable; + ITSContainer::LateralAcceleration_t lateralAcceleration /* OPTIONAL */; + + OptionalStructAvailable_t verticalAccelerationAvailable; + ITSContainer::VerticalAcceleration_t verticalAcceleration /* OPTIONAL */; + + OptionalStructAvailable_t performanceClassAvailable; + ITSContainer::PerformanceClass_t performanceClass /* OPTIONAL */; + + OptionalStructAvailable_t cenDsrcTollingZoneAvailable; + ITSContainer::CenDsrcTollingZone_t cenDsrcTollingZone /* OPTIONAL */; + + } BasicVehicleContainerHighFrequency_t; + + /* RsuContainerHighFrequency */ + typedef struct RSUContainerHighFrequency + { + ITSContainer::ProtectedCommunicationZonesRSU_t protectedCommunicationZonesRSU; + } RSUContainerHighFrequency_t; + + /* HighFrequencyContainer */ + typedef struct HighFrequencyContainer + { + // HighFrequencyContainer() {}; + // HighFrequencyContainer(HighFrequencyContainer &hfc) {}; + // ~HighFrequencyContainer() {}; + HighFrequencyContainer_PR present; + // union + // { + BasicVehicleContainerHighFrequency_t basicVehicleContainerHighFrequency; + RSUContainerHighFrequency_t rsuContainerHighFrequency; + // }; + + } HighFrequencyContainer_t; + + /* Dependencies */ + typedef enum LowFrequencyContainer_PR : long + { + LowFrequencyContainer_PR_NOTHING, /* No components present */ + LowFrequencyContainer_PR_basicVehicleContainerLowFrequency, + /* Extensions may appear below */ + + } LowFrequencyContainer_PR; + + /* BasicVehicleContainerLowFrequency */ + typedef struct BasicVehicleContainerLowFrequency { + ITSContainer::VehicleRole_t vehicleRole; + ITSContainer::ExteriorLights_t exteriorLights; + ITSContainer::PathHistory_t pathHistory; + } BasicVehicleContainerLowFrequency_t; + + /* LowFrequencyContainer */ + typedef struct LowFrequencyContainer + { + // LowFrequencyContainer() {}; + // LowFrequencyContainer(LowFrequencyContainer &lfc) {}; + // ~LowFrequencyContainer() {}; + LowFrequencyContainer_PR present; + // union + // { + BasicVehicleContainerLowFrequency_t basicVehicleContainerLowFrequency; + + // }; + //Since only option is available + // BasicVehicleContainerLowFrequency_t basicVehicleContainerLowFrequency; + } LowFrequencyContainer_t; + + /* CamParameters */ + typedef struct CamParameters + { + BasicContainer_t basicContainer; + HighFrequencyContainer_t highFrequencyContainer; + LowFrequencyContainer_t lowFrequencyContainer; /* OPTIONAL */ + // SpecialVehicleContainer *specialVehicleContainer; /* OPTIONAL */ + } CamParameters_t; + + /* CoopAwareness*/ + typedef struct CoopAwareness + { + GenerationDeltaTime_t generationDeltaTime; + CamParameters_t camParameters; + } CoopAwareness_t; + + +}; + + /* CoopAwareness */ + typedef struct CAM + { + ITSContainer::ItsPduHeader_t header; + CAMContainer::CoopAwareness_t cam; + } CAM_t; + + + typedef struct CustomV2XM + { + ITSContainer::ItsPduHeader_t header; + char message[100]; + } CustomV2XM_t; diff --git a/LibCarla/source/carla/sensor/data/V2XData.h b/LibCarla/source/carla/sensor/data/V2XData.h new file mode 100644 index 000000000..18e23e4b1 --- /dev/null +++ b/LibCarla/source/carla/sensor/data/V2XData.h @@ -0,0 +1,107 @@ +// Copyright (c) 2024 Institut fuer Technik der Informationsverarbeitung (ITIV) at the +// Karlsruhe Institute of Technology +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . +#pragma once + +#include +#include +#include +#include "LibITS.h" + +namespace carla +{ + namespace sensor + { + + namespace s11n + { + class CAMDataSerializer; + class CustomV2XDataSerializer; + } + + namespace data + { + class CAMData + { + public: + float Power; + CAM_t Message; + }; + + class CustomV2XData + { + public: + float Power; + CustomV2XM Message; + }; + + class CAMDataS + { + + public: + explicit CAMDataS() = default; + + CAMDataS &operator=(CAMDataS &&) = default; + + // /// Returns the number of current received messages. + size_t GetMessageCount() const + { + return MessageList.size(); + } + + /// Deletes the current messages. + void Reset() + { + MessageList.clear(); + } + + /// Adds a new detection. + void WriteMessage(CAMData message) + { + MessageList.push_back(message); + } + + private: + std::vector MessageList; + + friend class s11n::CAMDataSerializer; + }; + + + class CustomV2XDataS + { + + public: + explicit CustomV2XDataS() = default; + + CustomV2XDataS &operator=(CustomV2XDataS &&) = default; + + // /// Returns the number of current received messages. + size_t GetMessageCount() const + { + return MessageList.size(); + } + + /// Deletes the current messages. + void Reset() + { + MessageList.clear(); + } + + /// Adds a new detection. + void WriteMessage(CustomV2XData message) + { + MessageList.push_back(message); + } + + private: + std::vector MessageList; + + friend class s11n::CustomV2XDataSerializer; + }; + + } // namespace s11n + } // namespace sensor +} // namespace carla diff --git a/LibCarla/source/carla/sensor/data/V2XEvent.h b/LibCarla/source/carla/sensor/data/V2XEvent.h new file mode 100644 index 000000000..f1966a5ad --- /dev/null +++ b/LibCarla/source/carla/sensor/data/V2XEvent.h @@ -0,0 +1,61 @@ +// Copyright (c) 2024 Institut fuer Technik der Informationsverarbeitung (ITIV) at the +// Karlsruhe Institute of Technology +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/Debug.h" +#include "carla/sensor/data/Array.h" +#include "carla/sensor/s11n/V2XSerializer.h" +#include "carla/sensor/data/V2XData.h" + +namespace carla +{ + namespace sensor + { + namespace data + { + + class CAMEvent : public Array + { + using Super = Array; + + protected: + using Serializer = s11n::CAMDataSerializer; + + friend Serializer; + + explicit CAMEvent(RawData &&data) + : Super(0u, std::move(data)) {} + + public: + Super::size_type GetMessageCount() const + { + return Super::size(); + } + }; + + class CustomV2XEvent : public Array + { + using Super = Array; + + protected: + using Serializer = s11n::CustomV2XDataSerializer; + + friend Serializer; + + explicit CustomV2XEvent(RawData &&data) + : Super(0u, std::move(data)) {} + + public: + Super::size_type GetMessageCount() const + { + return Super::size(); + } + }; + + } // namespace data + } // namespace sensor +} // namespace carla \ No newline at end of file diff --git a/LibCarla/source/carla/sensor/s11n/V2XSerializer.cpp b/LibCarla/source/carla/sensor/s11n/V2XSerializer.cpp new file mode 100644 index 000000000..7babb44ef --- /dev/null +++ b/LibCarla/source/carla/sensor/s11n/V2XSerializer.cpp @@ -0,0 +1,25 @@ +// Copyright (c) 2024 Institut fuer Technik der Informationsverarbeitung (ITIV) at the +// Karlsruhe Institute of Technology +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "carla/sensor/s11n/V2XSerializer.h" + +#include "carla/sensor/data/V2XEvent.h" + +namespace carla { +namespace sensor { +namespace s11n { + + SharedPtr CAMDataSerializer::Deserialize(RawData &&data) { + return SharedPtr(new data::CAMEvent(std::move(data))); + } + + SharedPtr CustomV2XDataSerializer::Deserialize(RawData &&data) { + return SharedPtr(new data::CustomV2XEvent(std::move(data))); + } + +} // namespace s11n +} // namespace sensor +} // namespace carla \ No newline at end of file diff --git a/LibCarla/source/carla/sensor/s11n/V2XSerializer.h b/LibCarla/source/carla/sensor/s11n/V2XSerializer.h new file mode 100644 index 000000000..9d6c7e700 --- /dev/null +++ b/LibCarla/source/carla/sensor/s11n/V2XSerializer.h @@ -0,0 +1,79 @@ +// Copyright (c) 2024 Institut fuer Technik der Informationsverarbeitung (ITIV) at the +// Karlsruhe Institute of Technology +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/Memory.h" +#include "carla/sensor/RawData.h" +#include "carla/sensor/data/V2XData.h" + +#include +#include +class CAMContainer; +namespace carla +{ + namespace sensor + { + + class SensorData; + + namespace s11n + { + + // =========================================================================== + // -- V2XSerializer -------------------------------------------------------- + // =========================================================================== + + /// Serializes the data generated by V2X sensors. + // CAM + class CAMDataSerializer + { + public: + template + static Buffer Serialize( + const Sensor &sensor, + const data::CAMDataS &data, + Buffer &&output); + + static SharedPtr Deserialize(RawData &&data); + }; + + template + inline Buffer CAMDataSerializer::Serialize( + const Sensor &, + const data::CAMDataS &data, + Buffer &&output) + { + output.copy_from(data.MessageList); + return std::move(output); + } + + // Custom message + class CustomV2XDataSerializer + { + public: + template + static Buffer Serialize( + const Sensor &sensor, + const data::CustomV2XDataS &data, + Buffer &&output); + + static SharedPtr Deserialize(RawData &&data); + }; + + template + inline Buffer CustomV2XDataSerializer::Serialize( + const Sensor &, + const data::CustomV2XDataS &data, + Buffer &&output) + { + output.copy_from(data.MessageList); + return std::move(output); + } + + } // namespace s11n + } // namespace sensor +} // namespace carla \ No newline at end of file diff --git a/PythonAPI/carla/source/libcarla/Sensor.cpp b/PythonAPI/carla/source/libcarla/Sensor.cpp index 9a8cf5f78..779738788 100644 --- a/PythonAPI/carla/source/libcarla/Sensor.cpp +++ b/PythonAPI/carla/source/libcarla/Sensor.cpp @@ -41,6 +41,7 @@ void export_sensor() { .def("enable_for_ros", &cc::ServerSideSensor::EnableForROS) .def("disable_for_ros", &cc::ServerSideSensor::DisableForROS) .def("is_enabled_for_ros", &cc::ServerSideSensor::IsEnabledForROS) + .def("send", &cc::ServerSideSensor::Send, (arg("message"))) .def(self_ns::str(self_ns::self)) ; diff --git a/PythonAPI/carla/source/libcarla/SensorData.cpp b/PythonAPI/carla/source/libcarla/SensorData.cpp index d235dd6b7..3b8fc8b56 100644 --- a/PythonAPI/carla/source/libcarla/SensorData.cpp +++ b/PythonAPI/carla/source/libcarla/SensorData.cpp @@ -20,6 +20,9 @@ #include #include #include +#include +#include +#include #include @@ -32,6 +35,8 @@ #include #include +// #include "V2XData.cpp" + namespace carla { namespace sensor { namespace data { @@ -166,6 +171,41 @@ namespace data { return out; } + std::ostream &operator<<(std::ostream &out, const CAMEvent &data) { + out << "CAMEvent(frame=" << std::to_string(data.GetFrame()) + << ", timestamp=" << std::to_string(data.GetTimestamp()) + << ", message_count=" << std::to_string(data.GetMessageCount()) + << ')'; + return out; + } + + std::ostream &operator<<(std::ostream &out, const CustomV2XEvent &data) { + out << "CustomV2XEvent(frame=" << std::to_string(data.GetFrame()) + << ", timestamp=" << std::to_string(data.GetTimestamp()) + << ", message_count=" << std::to_string(data.GetMessageCount()) + << ')'; + return out; + } + + std::ostream &operator<<(std::ostream &out, const CAMData &data) { + out << "CAMData(power=" << std::to_string(data.Power) + << ", stationId=" << std::to_string(data.Message.header.stationID) + << ", messageId=" << std::to_string(data.Message.header.messageID) + << ')'; + return out; + } + + std::ostream &operator<<(std::ostream &out, const CustomV2XData &data) { + out << "CustomV2XData(power=" << std::to_string(data.Power) + << ", stationId=" << std::to_string(data.Message.header.stationID) + << ", messageId=" << std::to_string(data.Message.header.messageID) + // << ", message=" << data.Message.message + << ')'; + return out; + } + + + } // namespace s11n } // namespace sensor } // namespace carla @@ -356,6 +396,39 @@ static std::string SavePointCloudToDisk(T &self, std::string path) { return carla::pointcloud::PointCloudIO::SaveToDisk(std::move(path), self.begin(), self.end()); } +static boost::python::dict GetCAMData(const carla::sensor::data::CAMData message) +{ + boost::python::dict myDict; + try + { + myDict["Power"] = message.Power; + myDict["Message"] = GetCAMMessage(message); + } + catch(const std::exception& e) + { + std::cerr << e.what() << '\n'; + } + + return myDict; +} + + +static boost::python::dict GetCustomV2XData(const carla::sensor::data::CustomV2XData message) +{ + boost::python::dict myDict; + try + { + myDict["Power"] = message.Power; + myDict["Message"] = GetCustomV2XMessage(message); + } + catch(const std::exception& e) + { + std::cerr << e.what() << '\n'; + } + + return myDict; +} +/**********************************************************************************************/ void export_sensor_data() { using namespace boost::python; namespace cc = carla::client; @@ -573,4 +646,34 @@ void export_sensor_data() { .def("to_array_pol", CALL_RETURNING_LIST(csd::DVSEventArray, ToArrayPol)) .def(self_ns::str(self_ns::self)) ; + + class_("CAMMessage") + .def_readwrite("power", &csd::CAMData::Power) + .def("get", GetCAMData) + .def(self_ns::str(self_ns::self)) + ; + + class_("CustomV2XData") + .def_readwrite("power", &csd::CustomV2XData::Power) + .def("get", GetCustomV2XData) + .def(self_ns::str(self_ns::self)) + ; + + class_, boost::noncopyable, boost::shared_ptr>("CAMEvent", no_init) + .def("get_message_count", &csd::CAMEvent::GetMessageCount) + .def("__len__", &csd::CAMEvent::size) + .def("__iter__", iterator()) + .def("__getitem__", +[](const csd::CAMEvent &self, size_t pos) -> csd::CAMData { + return self.at(pos); + }) + ; + + class_, boost::noncopyable, boost::shared_ptr>("CustomV2XEvent", no_init) + .def("get_message_count", &csd::CustomV2XEvent::GetMessageCount) + .def("__len__", &csd::CustomV2XEvent::size) + .def("__iter__", iterator()) + .def("__getitem__", +[](const csd::CustomV2XEvent &self, size_t pos) -> csd::CustomV2XData { + return self.at(pos); + }) + ; } diff --git a/PythonAPI/carla/source/libcarla/V2XData.cpp b/PythonAPI/carla/source/libcarla/V2XData.cpp new file mode 100644 index 000000000..a29cf152e --- /dev/null +++ b/PythonAPI/carla/source/libcarla/V2XData.cpp @@ -0,0 +1,650 @@ +// Copyright (c) 2024 Institut fuer Technik der Informationsverarbeitung (ITIV) at the +// Karlsruhe Institute of Technology +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include +#include +#include +#include +#include + +/**********************************************************************************************/ +// Functions to convert CAM message from V2X sensor to python dict +std::string GetStationTypeString(const ITSContainer::StationType_t stationType) +{ + switch (stationType) + { + case ITSContainer::StationType_unknown: + return "Uunknown"; + case ITSContainer::StationType_pedestrian: + return "Pedestrian"; + case ITSContainer::StationType_cyclist: + return "Cyclist"; + case ITSContainer::StationType_moped: + return "Moped"; + case ITSContainer::StationType_motorcycle: + return "Motorcycle"; + case ITSContainer::StationType_passengerCar: + return "Passenger Car"; + case ITSContainer::StationType_bus: + return "Bus"; + case ITSContainer::StationType_lightTruck: + return "Light Truck"; + case ITSContainer::StationType_heavyTruck: + return "HeavyTruck"; + case ITSContainer::StationType_trailer: + return "Trailer"; + case ITSContainer::StationType_specialVehicles: + return "Special Vehicle"; + case ITSContainer::StationType_tram: + return "Tram"; + case ITSContainer::StationType_roadSideUnit: + return "Road Side Unit"; + default: + return "Unknown"; + } +} +std::string GetSemiConfidenceString(const long confidence) +{ + switch(confidence) + { + case ITSContainer::SemiAxisLength_oneCentimeter: + return "Semi Axis Length One Centimeter"; + case ITSContainer::SemiAxisLength_outOfRange: + return "Semi Axis Length Out Of Range"; + default: + return "Semi Axis Length Unavailable"; + } +} + +std::string GetSemiOrientationString(const long orientation) +{ + switch(orientation) + { + case ITSContainer::HeadingValue_wgs84North: + return "Heading wgs84 North"; + case ITSContainer::HeadingValue_wgs84East: + return "Heading wgs84 East"; + case ITSContainer::HeadingValue_wgs84South: + return "Heading wgs84 South"; + case ITSContainer::HeadingValue_wgs84West: + return "Heading wgs84 West"; + default: + return "Heading Unavailable"; + } +} + +std::string GetAltitudeConfidenceString(ITSContainer::AltitudeConfidence_t altitudeConfidence) +{ + switch(altitudeConfidence) + { + case ITSContainer::AltitudeConfidence_alt_000_01: + return "AltitudeConfidence_alt_000_01"; + case ITSContainer::AltitudeConfidence_alt_000_02: + return "AltitudeConfidence_alt_000_02"; + case ITSContainer::AltitudeConfidence_alt_000_05: + return "AltitudeConfidence_alt_000_05"; + case ITSContainer::AltitudeConfidence_alt_000_10: + return "AltitudeConfidence_alt_000_10"; + case ITSContainer::AltitudeConfidence_alt_000_20: + return "AltitudeConfidence_alt_000_20"; + case ITSContainer::AltitudeConfidence_alt_000_50: + return "AltitudeConfidence_alt_000_50"; + case ITSContainer::AltitudeConfidence_alt_001_00: + return "AltitudeConfidence_alt_001_00"; + case ITSContainer::AltitudeConfidence_alt_002_00: + return "AltitudeConfidence_alt_002_00"; + case ITSContainer::AltitudeConfidence_alt_005_00: + return "AltitudeConfidence_alt_005_00"; + case ITSContainer::AltitudeConfidence_alt_010_00: + return "AltitudeConfidence_alt_010_00"; + case ITSContainer::AltitudeConfidence_alt_020_00: + return "AltitudeConfidence_alt_020_00"; + case ITSContainer::AltitudeConfidence_alt_050_00: + return "AltitudeConfidence_alt_050_00"; + case ITSContainer::AltitudeConfidence_alt_100_00: + return "AltitudeConfidence_alt_100_00"; + case ITSContainer::AltitudeConfidence_alt_200_00: + return "AltitudeConfidence_alt_200_00"; + case ITSContainer::AltitudeConfidence_outOfRange: + return "AltitudeConfidence_alt_outOfRange"; + default: + return "AltitudeConfidence_unavailable"; + } +} +static boost::python::dict GetReferenceContainer(const CAM_t message) +{ + boost::python::dict ReferencePosition; + ITSContainer::ReferencePosition_t ref = message.cam.camParameters.basicContainer.referencePosition; + ReferencePosition["Latitude"] = ref.latitude; + ReferencePosition["Longitude"] = ref.longitude; + boost::python::dict PosConfidence; + PosConfidence["Semi Major Confidence"] = GetSemiConfidenceString(ref.positionConfidenceEllipse.semiMajorConfidence); + PosConfidence["Semi Minor Confidence"] = GetSemiConfidenceString(ref.positionConfidenceEllipse.semiMinorConfidence); + PosConfidence["Semi Major Orientation"] = GetSemiOrientationString(ref.positionConfidenceEllipse.semiMajorOrientation); + ReferencePosition["Position Confidence Eliipse"] = PosConfidence; + boost::python::dict Altitude; + Altitude["Altitude Value"] = ref.altitude.altitudeValue; + Altitude["Altitude Confidence"] = GetAltitudeConfidenceString(ref.altitude.altitudeConfidence); + return ReferencePosition; +} +static boost::python::dict GetBasicContainer(const CAM_t message) +{ + boost::python::dict BasicContainer; + BasicContainer["Station Type"] = GetStationTypeString(message.cam.camParameters.basicContainer.stationType); + BasicContainer["Reference Position"] = GetReferenceContainer(message); + return BasicContainer; +} + +std::string GetHeadingConfidenceString(ITSContainer::HeadingConfidence_t confidence) +{ + switch (confidence) + { + case ITSContainer::HeadingConfidence_equalOrWithinZeroPointOneDegree: + return "Equal or With in Zero Point One Degree"; + case ITSContainer::HeadingConfidence_equalOrWithinOneDegree: + return "Equal or With in One Degree"; + case ITSContainer::HeadingConfidence_outOfRange: + return "Out of Range"; + default: + return "Unavailable"; + } +} + +std::string GetSpeedConfidenceString(ITSContainer::SpeedConfidence_t confidence) +{ + switch (confidence) + { + case ITSContainer::SpeedConfidence_equalOrWithInOneCentimerterPerSec: + return "Equal or With in One Centimeter per Sec"; + case ITSContainer::SpeedConfidence_equalOrWithinOneMeterPerSec: + return "Equal or With in One Meter per Sec"; + case ITSContainer::SpeedConfidence_outOfRange: + return "Out of Range"; + default: + return "Unavailable"; + } +} + +std::string GetVehicleLengthConfidenceString(ITSContainer::VehicleLengthConfidenceIndication_t confidence) +{ + switch (confidence) + { + case ITSContainer::VehicleLengthConfidenceIndication_noTrailerPresent: + return "No Trailer Present"; + case ITSContainer::VehicleLengthConfidenceIndication_trailerPresentWithKnownLength: + return "Trailer Present With Known Length"; + case ITSContainer::VehicleLengthConfidenceIndication_trailerPresentWithUnknownLength: + return "Trailer Present With Unknown Length"; + case ITSContainer::VehicleLengthConfidenceIndication_trailerPresenceIsUnknown: + return "Trailer Presence Is Unknown"; + default: + return "Unavailable"; + } +} + +std::string GetAccelerationConfidenceString(ITSContainer::AccelerationConfidence_t confidence) +{ + switch (confidence) + { + case ITSContainer::AccelerationConfindence_pointOneMeterPerSecSquared: + return "Point One Meter Per Sec Squared"; + case ITSContainer::AccelerationConfidence_outOfRange: + return "Out Of Range"; + default: + return "Unavailable"; + } +} + +std::string GetCurvatureConfidenceString(ITSContainer::CurvatureConfidence_t confidence) +{ + switch (confidence) + { + case ITSContainer::CurvatureConfidence_onePerMeter_0_00002: + return "One Per Meter 0_00002"; + case ITSContainer::CurvatureConfidence_onePerMeter_0_0001: + return "One Per Meter 0_0001"; + case ITSContainer::CurvatureConfidence_onePerMeter_0_0005: + return "One Per Meter 0_0005"; + case ITSContainer::CurvatureConfidence_onePerMeter_0_002: + return "One Per Meter 0_002"; + case ITSContainer::CurvatureConfidence_onePerMeter_0_01: + return "One Per Meter 0_01"; + case ITSContainer::CurvatureConfidence_onePerMeter_0_1: + return "One Per Meter 0_1"; + case ITSContainer::CurvatureConfidence_outOfRange: + return "Out Of Range"; + default: + return "Unavailable"; + } +} + +std::string GetYawRateConfidenceString(ITSContainer::YawRateConfidence_t confidence) +{ + switch (confidence) + { + case ITSContainer::YawRateConfidence_degSec_000_01: + return "degSec 000_01"; + case ITSContainer::YawRateConfidence_degSec_000_05: + return "degSec 000_05"; + case ITSContainer::YawRateConfidence_degSec_000_10: + return "degSec 000_10"; + case ITSContainer::YawRateConfidence_degSec_001_00: + return "degSec 001_00"; + case ITSContainer::YawRateConfidence_degSec_005_00: + return "degSec 005_00"; + case ITSContainer::YawRateConfidence_degSec_010_00: + return "degSec 010_00"; + case ITSContainer::YawRateConfidence_degSec_100_00: + return "degSec 100_00"; + case ITSContainer::YawRateConfidence_outOfRange: + return "Out Of Range"; + default: + return "Unavailable"; + } +} + +std::string GetSteeringWheelConfidenceString(ITSContainer::SteeringWheelAngleConfidence_t confidence) +{ + switch (confidence) + { + case ITSContainer::SteeringWheelAngleConfidence_equalOrWithinOnePointFiveDegree: + return "Equal or With in 1.5 degree"; + case ITSContainer::SteeringWheelAngleConfidence_outOfRange: + return "Out of Range"; + default: + return "Unavailable"; + } +} + +static boost::python::dict GetBVCHighFrequency(const CAM_t message) +{ + boost::python::dict BVCHighFrequency; + CAMContainer::BasicVehicleContainerHighFrequency_t bvchf = message.cam.camParameters.highFrequencyContainer.basicVehicleContainerHighFrequency; + boost::python::dict HeadingValueConfidence; + HeadingValueConfidence["Value"] = bvchf.heading.headingValue; + HeadingValueConfidence["Confidence"] = GetHeadingConfidenceString(bvchf.heading.headingConfidence); + BVCHighFrequency["Heading"] = HeadingValueConfidence; + // ValueConfidence.clear(); + boost::python::dict SpeedValueConfidence; + SpeedValueConfidence["Value"] = bvchf.speed.speedValue; + SpeedValueConfidence["Confidence"] = GetSpeedConfidenceString(bvchf.speed.speedConfidence); + BVCHighFrequency["Speed"] = SpeedValueConfidence; + + BVCHighFrequency["Drive Direction"] = bvchf.driveDirection; + + boost::python::dict VehicleLengthValueConfidence; + VehicleLengthValueConfidence["Value"] = bvchf.vehicleLength.vehicleLengthValue; + VehicleLengthValueConfidence["Confidence"] = GetVehicleLengthConfidenceString(bvchf.vehicleLength.vehicleLengthConfidenceIndication); + BVCHighFrequency["Vehicle Length"] = VehicleLengthValueConfidence; + + BVCHighFrequency["Vehicle Width"] = bvchf.vehicleWidth; + + boost::python::dict LongitudinalAccelerationValueConfidence; + LongitudinalAccelerationValueConfidence["Value"] = bvchf.longitudinalAcceleration.longitudinalAccelerationValue; + LongitudinalAccelerationValueConfidence["Confidence"] = GetAccelerationConfidenceString(bvchf.longitudinalAcceleration.longitudinalAccelerationConfidence); + BVCHighFrequency["Longitudinal Acceleration"] = LongitudinalAccelerationValueConfidence; + + boost::python::dict CurvatureValueConfidence; + CurvatureValueConfidence["Value"] = bvchf.curvature.curvatureValue; + CurvatureValueConfidence["Confidence"] = GetCurvatureConfidenceString(bvchf.curvature.curvatureConfidence); + BVCHighFrequency["Curvature"] = CurvatureValueConfidence; + BVCHighFrequency["Curvature Calculation Mode"] = bvchf.curvatureCalculationMode; + + boost::python::dict YawValueConfidence; + YawValueConfidence["Value"] = bvchf.yawRate.yawRateValue; + YawValueConfidence["Confidence"] = GetYawRateConfidenceString(bvchf.yawRate.yawRateConfidence); + BVCHighFrequency["Yaw Rate"] = YawValueConfidence; + + boost::python::dict ValueConfidence; + if (bvchf.accelerationControlAvailable) + { + BVCHighFrequency["Acceleration Control"] = bvchf.accelerationControl; + } + else + { + BVCHighFrequency["Acceleration Control"] = boost::python::object(); + } + + if (bvchf.lanePositionAvailable) + { + BVCHighFrequency["Lane Position"] = bvchf.lanePosition; + } + else + { + BVCHighFrequency["Lane Position"] = boost::python::object(); + } + + if (bvchf.steeringWheelAngleAvailable) + { + boost::python::dict ValueConfidence; + ValueConfidence["Value"] = bvchf.steeringWheelAngle.steeringWheelAngleValue; + ValueConfidence["Confidence"] = GetSteeringWheelConfidenceString(bvchf.steeringWheelAngle.steeringWheelAngleConfidence); + BVCHighFrequency["Steering Wheel Angle"] = ValueConfidence; + } + else + { + BVCHighFrequency["Steering Wheel Angle"] = boost::python::object(); + } + + if (bvchf.lateralAccelerationAvailable) + { + boost::python::dict ValueConfidence; + ValueConfidence["Value"] = bvchf.lateralAcceleration.lateralAccelerationValue; + ValueConfidence["Confidence"] = GetAccelerationConfidenceString(bvchf.lateralAcceleration.lateralAccelerationConfidence); + BVCHighFrequency["Lateral Acceleration"] = ValueConfidence; + // BVCHighFrequency["Lateral Acceleration"] = boost::python::object(); + } + else + { + BVCHighFrequency["Lateral Acceleration"] = boost::python::object(); + } + + if (bvchf.verticalAccelerationAvailable) + { + boost::python::dict ValueConfidence; + ValueConfidence["Value"] = bvchf.verticalAcceleration.verticalAccelerationValue; + ValueConfidence["Confidence"] = GetAccelerationConfidenceString(bvchf.verticalAcceleration.verticalAccelerationConfidence); + BVCHighFrequency["Vertical Acceleration"] = ValueConfidence; + } + else + { + BVCHighFrequency["Vertical Acceleration"] = boost::python::object(); + } + + if (bvchf.performanceClassAvailable) + { + BVCHighFrequency["Performance class"] = bvchf.performanceClass; + } + else + { + BVCHighFrequency["Performance class"] = boost::python::object(); + } + + if (bvchf.cenDsrcTollingZoneAvailable) + { + boost::python::dict ValueConfidence; + ValueConfidence["Protected Zone Latitude"] = bvchf.cenDsrcTollingZone.protectedZoneLatitude; + ValueConfidence["Protected Zone Longitude"] = bvchf.cenDsrcTollingZone.protectedZoneLongitude; + if (bvchf.cenDsrcTollingZone.cenDsrcTollingZoneIDAvailable) + { + ValueConfidence["Cen DSRC Tolling Zone ID"] = bvchf.cenDsrcTollingZone.cenDsrcTollingZoneID; + } + BVCHighFrequency["Cen DSRC Tolling Zone"] = ValueConfidence; + } + else + { + BVCHighFrequency["Cen DSRC Tolling Zone"] = boost::python::object(); + } + + return BVCHighFrequency; +} + +static boost::python::list GetProtectedCommunicationZone(const CAMContainer::RSUContainerHighFrequency_t rsuMessage) +{ + boost::python::list PCZlist; + + for (ITSContainer::ProtectedCommunicationZone_t data : rsuMessage.protectedCommunicationZonesRSU.list) + { + boost::python::dict PCZDict; + PCZDict["Protected Zone Type"] = data.protectedZoneType; + if (data.expiryTimeAvailable) + { + PCZDict["Expiry Time"] = data.expiryTime; + } + + PCZDict["Protected Zone Latitude"] = data.protectedZoneLatitude; + PCZDict["Protected Zone Longitude"] = data.protectedZoneLongitude; + + if (data.protectedZoneIDAvailable) + { + PCZDict["Protected Zone ID"] = data.protectedZoneID; + } + if (data.protectedZoneRadiusAvailable) + { + PCZDict["Protected Zone Radius"] = data.protectedZoneRadius; + } + + PCZlist.append(PCZDict); + } + return PCZlist; +} +static boost::python::dict GetRSUHighFrequency(const CAM_t message) +{ + boost::python::dict RSU; + CAMContainer::RSUContainerHighFrequency_t rsu = message.cam.camParameters.highFrequencyContainer.rsuContainerHighFrequency; + RSU["Protected Communication Zone"] = GetProtectedCommunicationZone(rsu); + return RSU; +} + +static boost::python::dict GetHighFrequencyContainer(const CAM_t message) +{ + boost::python::dict HFC; + CAMContainer::HighFrequencyContainer_t hfc = message.cam.camParameters.highFrequencyContainer; + // HFC["High Frequency Container Present"] = GetHFCPresentString(hfc.present); + switch (hfc.present) + { + case CAMContainer::HighFrequencyContainer_PR_basicVehicleContainerHighFrequency: + HFC["High Frequency Container Present"] = "Basic Vehicle Container High Frequency"; + HFC["Basic Vehicle Container High Frequency"] = GetBVCHighFrequency(message); + break; + case CAMContainer::HighFrequencyContainer_PR_rsuContainerHighFrequency: + HFC["High Frequency Container Present"] = "RSU Container High Frequency"; + HFC["RSU Container High Frequency"] = GetRSUHighFrequency(message); + break; + default: + HFC["High Frequency Container Present"] = "No container present"; + } + return HFC; +} +std::string GetVehicleRoleString(ITSContainer::VehicleRole_t vehicleRole) +{ + switch (vehicleRole) + { + case ITSContainer::VehicleRole_publicTransport: + return "Public Transport"; + case ITSContainer::VehicleRole_specialTransport: + return "Special Transport"; + case ITSContainer::VehicleRole_dangerousGoods: + return "Dangerous Goods"; + case ITSContainer::VehicleRole_roadWork: + return "Road Work"; + case ITSContainer::VehicleRole_rescue: + return "Rescue"; + case ITSContainer::VehicleRole_emergency: + return "Emergency"; + case ITSContainer::VehicleRole_safetyCar: + return "Safety Car"; + case ITSContainer::VehicleRole_agriculture: + return "Agriculture"; + case ITSContainer::VehicleRole_commercial: + return "Commercial"; + case ITSContainer::VehicleRole_military: + return "Military"; + case ITSContainer::VehicleRole_roadOperator: + return "Road Operator"; + case ITSContainer::VehicleRole_taxi: + return "Taxi"; + case ITSContainer::VehicleRole_reserved1: + return "Reserved 1"; + case ITSContainer::VehicleRole_reserved2: + return "Reserved 2"; + case ITSContainer::VehicleRole_reserved3: + return "Reserved 3"; + default: + return "Default"; + } +} +// boost::python::list GetVehicleExteriorLightList(const ITSContainer::ExteriorLights_t exteriorLights) +// { +// boost::python::list ExteriorLightsList; +// uint8_t light = *exteriorLights.buf; +// if(light & 0x80) +// { +// ExteriorLightsList.append("Low Beam Head Lights On"); +// } +// if(light & 0x40) +// { +// ExteriorLightsList.append("High Beam Head Lights On"); +// } +// if(light & 0x20) +// { +// ExteriorLightsList.append("Left turn signal on"); +// } +// if(light & 0x10) +// { +// ExteriorLightsList.append("Right turn signal on"); +// } +// if(light & 0x08) +// { +// ExteriorLightsList.append("Day time running lights on"); +// } +// if(light & 0x04) +// { +// ExteriorLightsList.append("Reverse light on"); +// } +// if(light & 0x02) +// { +// ExteriorLightsList.append("Fog light on"); +// } +// if(light & 0x01) +// { +// ExteriorLightsList.append("Parking Lights on"); +// } +// return ExteriorLightsList; + +// } +boost::python::list GetPathHistory(const ITSContainer::PathHistory_t pathHistory) +{ + + boost::python::list PathHistoryList; + for (ITSContainer::PathPoint_t pathPoint : pathHistory.data) + { + boost::python::dict PathHistory; + PathHistory["Delta Latitude"] = pathPoint.pathPosition.deltaLatitude; + PathHistory["Delta Longitude"] = pathPoint.pathPosition.deltaLongitude; + PathHistory["Delta Altitude"] = pathPoint.pathPosition.deltaAltitude; + if (pathPoint.pathDeltaTime != nullptr) + { + PathHistory["Delta Time"] = *pathPoint.pathDeltaTime; + } + else + { + PathHistory["Delta Time"] = boost::python::object(); + } + PathHistoryList.append(PathHistory); + } + return PathHistoryList; +} +boost::python::dict GetBVCLowFrequency(const CAMContainer::BasicVehicleContainerLowFrequency_t bvc) +{ + boost::python::dict BVC; + BVC["Vehicle Role"] = GetVehicleRoleString(bvc.vehicleRole); + BVC["Exterior Light"] = bvc.exteriorLights; // GetVehicleExteriorLightList(bvc.exteriorLights); + if (bvc.pathHistory.NumberOfPathPoint != 0) + { + BVC["Path History"] = GetPathHistory(bvc.pathHistory); + } + else + { + BVC["Path History"] = boost::python::object(); + } + return BVC; +} + +boost::python::dict GetLowFrequencyContainer(const CAM_t message) +{ + boost::python::dict LFC = boost::python::dict(); + CAMContainer::LowFrequencyContainer_t lfc = message.cam.camParameters.lowFrequencyContainer; + switch (lfc.present) + { + case CAMContainer::LowFrequencyContainer_PR_basicVehicleContainerLowFrequency: + LFC["Low Frequency Container Present"] = "Basic Vehicle Container Low Frequency"; + LFC["Basic Vehicle Low Frequency"] = GetBVCLowFrequency(lfc.basicVehicleContainerLowFrequency); + break; + default: + LFC["Low Frequency Container Present"] = "No Container Present"; + break; + } + return LFC; +} +static boost::python::dict GetCAMParameters(const CAM_t message) +{ + boost::python::dict CAMParams; + try + { + + CAMParams["Basic Container"] = GetBasicContainer(message); + CAMParams["High Frequency Container"] = GetHighFrequencyContainer(message); + CAMParams["Low Frequency Container"] = GetLowFrequencyContainer(message); + } + catch (const std::exception &e) + { + std::cerr << e.what() << '\n'; + } + return CAMParams; +} + +static boost::python::dict GetCoopAwarness(const CAM_t message) +{ + + boost::python::dict Coop; + CAMContainer::CoopAwareness_t coop = message.cam; + Coop["Generation Delta Time"] = coop.generationDeltaTime; + Coop["CAM Parameters"] = GetCAMParameters(message); + return Coop; +} + +std::string GetMessageIDString(const long messageId) +{ + switch (messageId) + { + case ITSContainer::messageID_custom: + return "CUSTOM"; + case ITSContainer::messageID_denm: + return "DENM"; + case ITSContainer::messageID_cam: + return "CAM"; + case ITSContainer::messageID_poi: + return "POI"; + case ITSContainer::messageID_spat: + return "SPAT"; + case ITSContainer::messageID_map: + return "MAP"; + case ITSContainer::messageID_ivi: + return "IVI"; + case ITSContainer::messageID_ev_rsr: + return "EV_RSR"; + default: + return "Not Found"; + } +} + +static boost::python::dict GetMessageHeader(const ITSContainer::ItsPduHeader_t header) +{ + boost::python::dict Header; + Header["Protocol Version"] = header.protocolVersion; + Header["Message ID"] = GetMessageIDString(header.messageID); + Header["Station ID"] = header.stationID; + return Header; +} + +boost::python::dict GetCAMMessage(const carla::sensor::data::CAMData message) +{ + boost::python::dict CAM; + CAM_t CAMMessage = message.Message; + CAM["Header"] = GetMessageHeader(CAMMessage.header); + CAM["Message"] = GetCoopAwarness(CAMMessage); + return CAM; +} + +boost::python::dict GetCustomV2XMessage(const carla::sensor::data::CustomV2XData message) +{ + boost::python::dict CustomV2X; + CustomV2XM V2XMessage = message.Message; + CustomV2X["Header"] = GetMessageHeader(V2XMessage.header); + CustomV2X["Message"] = std::string(V2XMessage.message); + return CustomV2X; +} diff --git a/PythonAPI/carla/source/libcarla/libcarla.cpp b/PythonAPI/carla/source/libcarla/libcarla.cpp index 73998c2eb..9bd3fc83d 100644 --- a/PythonAPI/carla/source/libcarla/libcarla.cpp +++ b/PythonAPI/carla/source/libcarla/libcarla.cpp @@ -216,6 +216,7 @@ static auto MakeCallback(boost::python::object callback) { }; } +#include "V2XData.cpp" #include "Geom.cpp" #include "Actor.cpp" #include "Blueprint.cpp" diff --git a/Unreal/CarlaUE4/.ignore b/Unreal/CarlaUE4/.ignore new file mode 100644 index 000000000..fa98ea662 --- /dev/null +++ b/Unreal/CarlaUE4/.ignore @@ -0,0 +1,9 @@ +.kdev4 +.vscode +Intermediate +Plugins/Carla/CarlaDependencies +Plugins/Carla/Content +Plugins/Carla/Intermediate +Plugins/CarlaExporter/Intermediate +Plugins/CarlaTools/Content +Plugins/CarlaTools/Intermediate diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp index ce637c739..4899c7e29 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp @@ -10,6 +10,7 @@ #include "Carla/Sensor/LidarDescription.h" #include "Carla/Sensor/SceneCaptureSensor.h" #include "Carla/Sensor/ShaderBasedSensor.h" +#include "Carla/Sensor/V2X/PathLossModel.h" #include "Carla/Util/ScopedStack.h" #include @@ -1014,6 +1015,353 @@ void UActorBlueprintFunctionLibrary::MakeLidarDefinition( Success = CheckActorDefinition(Definition); } +FActorDefinition UActorBlueprintFunctionLibrary::MakeV2XDefinition() +{ + FActorDefinition Definition; + bool Success; + MakeV2XDefinition(Success, Definition); + check(Success); + return Definition; +} + +void UActorBlueprintFunctionLibrary::MakeV2XDefinition( + bool &Success, + FActorDefinition &Definition) +{ + FillIdAndTags(Definition, TEXT("sensor"), TEXT("other"), TEXT("v2x")); + // AddRecommendedValuesForSensorRoleNames(Definition); + AddVariationsForSensor(Definition); + + // - Noise seed -------------------------------- + FActorVariation NoiseSeed; + NoiseSeed.Id = TEXT("noise_seed"); + NoiseSeed.Type = EActorAttributeType::Int; + NoiseSeed.RecommendedValues = { TEXT("0") }; + NoiseSeed.bRestrictToRecommended = false; + + //Frequency + FActorVariation Frequency; + Frequency.Id = TEXT("frequency_ghz"); + Frequency.Type = EActorAttributeType::Float; + Frequency.RecommendedValues = { TEXT("5.9")}; + + //TransmitPower + FActorVariation TransmitPower; + TransmitPower.Id = TEXT("transmit_power"); + TransmitPower.Type = EActorAttributeType::Float; + TransmitPower.RecommendedValues = { TEXT("21.5")}; + + //ReceiveSensitivity + FActorVariation ReceiverSensitivity; + ReceiverSensitivity.Id = TEXT("receiver_sensitivity"); + ReceiverSensitivity.Type = EActorAttributeType::Float; + ReceiverSensitivity.RecommendedValues = { TEXT("-99.0")}; + + //Combined Antenna Gain in dBi + FActorVariation CombinedAntennaGain; + CombinedAntennaGain.Id = TEXT("combined_antenna_gain"); + CombinedAntennaGain.Type = EActorAttributeType::Float; + CombinedAntennaGain.RecommendedValues = { TEXT("10.0")}; + + //Scenario + FActorVariation Scenario; + Scenario.Id = TEXT("scenario"); + Scenario.Type = EActorAttributeType::String; + Scenario.RecommendedValues = { TEXT("highway"), TEXT("rural"), TEXT("urban")}; + Scenario.bRestrictToRecommended = true; + + //Path loss exponent + FActorVariation PLE; + PLE.Id = TEXT("path_loss_exponent"); + PLE.Type = EActorAttributeType::Float; + PLE.RecommendedValues = { TEXT("2.7")}; + + + //FSPL reference distance for LDPL calculation + FActorVariation FSPL_RefDistance; + FSPL_RefDistance.Id = TEXT("d_ref"); + FSPL_RefDistance.Type = EActorAttributeType::Float; + FSPL_RefDistance.RecommendedValues = { TEXT("1.0")}; + + //filter distance to speed up calculation + FActorVariation FilterDistance; + FilterDistance.Id = TEXT("filter_distance"); + FilterDistance.Type = EActorAttributeType::Float; + FilterDistance.RecommendedValues = { TEXT("500.0")}; + + //etsi fading + FActorVariation EtsiFading; + EtsiFading.Id = TEXT("use_etsi_fading"); + EtsiFading.Type = EActorAttributeType::Bool; + EtsiFading.RecommendedValues = { TEXT("true")}; + + //custom fading std deviation + FActorVariation CustomFadingStddev; + CustomFadingStddev.Id = TEXT("custom_fading_stddev"); + CustomFadingStddev.Type = EActorAttributeType::Float; + CustomFadingStddev.RecommendedValues = { TEXT("0.0")}; + + // Min Cam Generation + FActorVariation GenCamMin; + GenCamMin.Id = TEXT("gen_cam_min"); + GenCamMin.Type = EActorAttributeType::Float; + GenCamMin.RecommendedValues = { TEXT("0.1")}; + + // Max Cam Generation + FActorVariation GenCamMax; + GenCamMax.Id = TEXT("gen_cam_max"); + GenCamMax.Type = EActorAttributeType::Float; + GenCamMax.RecommendedValues = { TEXT("1.0")}; + + //Fixed Rate + FActorVariation FixedRate; + FixedRate.Id = TEXT("fixed_rate"); + FixedRate.Type = EActorAttributeType::Bool; + FixedRate.RecommendedValues = { TEXT("false")}; + + //path loss model + FActorVariation PLModel; + PLModel.Id = TEXT("path_loss_model"); + PLModel.Type = EActorAttributeType::String; + PLModel.RecommendedValues = { TEXT("winner"), TEXT("geometric")}; + PLModel.bRestrictToRecommended = true; + + //V2x Sensor sends GNSS position in CAM messages + // - Latitude ---------------------------------- + FActorVariation StdDevLat; + StdDevLat.Id = TEXT("noise_lat_stddev"); + StdDevLat.Type = EActorAttributeType::Float; + StdDevLat.RecommendedValues = { TEXT("0.0") }; + StdDevLat.bRestrictToRecommended = false; + FActorVariation BiasLat; + BiasLat.Id = TEXT("noise_lat_bias"); + BiasLat.Type = EActorAttributeType::Float; + BiasLat.RecommendedValues = { TEXT("0.0") }; + BiasLat.bRestrictToRecommended = false; + + // - Longitude --------------------------------- + FActorVariation StdDevLong; + StdDevLong.Id = TEXT("noise_lon_stddev"); + StdDevLong.Type = EActorAttributeType::Float; + StdDevLong.RecommendedValues = { TEXT("0.0") }; + StdDevLong.bRestrictToRecommended = false; + FActorVariation BiasLong; + BiasLong.Id = TEXT("noise_lon_bias"); + BiasLong.Type = EActorAttributeType::Float; + BiasLong.RecommendedValues = { TEXT("0.0") }; + BiasLong.bRestrictToRecommended = false; + + // - Altitude ---------------------------------- + FActorVariation StdDevAlt; + StdDevAlt.Id = TEXT("noise_alt_stddev"); + StdDevAlt.Type = EActorAttributeType::Float; + StdDevAlt.RecommendedValues = { TEXT("0.0") }; + StdDevAlt.bRestrictToRecommended = false; + FActorVariation BiasAlt; + BiasAlt.Id = TEXT("noise_alt_bias"); + BiasAlt.Type = EActorAttributeType::Float; + BiasAlt.RecommendedValues = { TEXT("0.0") }; + BiasAlt.bRestrictToRecommended = false; + + // - Heading ---------------------------------- + FActorVariation StdDevHeading; + StdDevHeading.Id = TEXT("noise_head_stddev"); + StdDevHeading.Type = EActorAttributeType::Float; + StdDevHeading.RecommendedValues = { TEXT("0.0") }; + StdDevHeading.bRestrictToRecommended = false; + FActorVariation BiasHeading; + BiasHeading.Id = TEXT("noise_head_bias"); + BiasHeading.Type = EActorAttributeType::Float; + BiasHeading.RecommendedValues = { TEXT("0.0") }; + BiasHeading.bRestrictToRecommended = false; + + //V2x Sensor sends acceleration in CAM messages + // - Accelerometer Standard Deviation ---------- + // X Component + FActorVariation StdDevAccelX; + StdDevAccelX.Id = TEXT("noise_accel_stddev_x"); + StdDevAccelX.Type = EActorAttributeType::Float; + StdDevAccelX.RecommendedValues = { TEXT("0.0") }; + StdDevAccelX.bRestrictToRecommended = false; + // Y Component + FActorVariation StdDevAccelY; + StdDevAccelY.Id = TEXT("noise_accel_stddev_y"); + StdDevAccelY.Type = EActorAttributeType::Float; + StdDevAccelY.RecommendedValues = { TEXT("0.0") }; + StdDevAccelY.bRestrictToRecommended = false; + // Z Component + FActorVariation StdDevAccelZ; + StdDevAccelZ.Id = TEXT("noise_accel_stddev_z"); + StdDevAccelZ.Type = EActorAttributeType::Float; + StdDevAccelZ.RecommendedValues = { TEXT("0.0") }; + StdDevAccelZ.bRestrictToRecommended = false; + + // Yaw rate + FActorVariation StdDevYawrate; + StdDevYawrate.Id = TEXT("noise_yawrate_stddev"); + StdDevYawrate.Type = EActorAttributeType::Float; + StdDevYawrate.RecommendedValues = { TEXT("0.0") }; + StdDevYawrate.bRestrictToRecommended = false; + FActorVariation BiasYawrate; + BiasYawrate.Id = TEXT("noise_yawrate_bias"); + BiasYawrate.Type = EActorAttributeType::Float; + BiasYawrate.RecommendedValues = { TEXT("0.0") }; + BiasYawrate.bRestrictToRecommended = false; + + //V2x Sensor sends speed in CAM messages + // X Component + FActorVariation StdDevVelX; + StdDevVelX.Id = TEXT("noise_vel_stddev_x"); + StdDevVelX.Type = EActorAttributeType::Float; + StdDevVelX.RecommendedValues = { TEXT("0.0") }; + StdDevVelX.bRestrictToRecommended = false; + + Definition.Variations.Append({ + NoiseSeed, + TransmitPower, + ReceiverSensitivity, + Frequency, + CombinedAntennaGain, + Scenario, + PLModel, + PLE, + FSPL_RefDistance, + FilterDistance, + EtsiFading, + CustomFadingStddev, + GenCamMin, + GenCamMax, + FixedRate, + StdDevLat, + BiasLat, + StdDevLong, + BiasLong, + StdDevAlt, + BiasAlt, + StdDevHeading, + BiasHeading, + StdDevAccelX, + StdDevAccelY, + StdDevAccelZ, + StdDevYawrate, + BiasYawrate, + StdDevVelX}); + Success = CheckActorDefinition(Definition); +} + +FActorDefinition UActorBlueprintFunctionLibrary::MakeCustomV2XDefinition() +{ + FActorDefinition Definition; + bool Success; + MakeCustomV2XDefinition(Success, Definition); + check(Success); + return Definition; +} + +void UActorBlueprintFunctionLibrary::MakeCustomV2XDefinition( + bool &Success, + FActorDefinition &Definition) +{ + FillIdAndTags(Definition, TEXT("sensor"), TEXT("other"), TEXT("v2x_custom")); + // AddRecommendedValuesForSensorRoleNames(Definition); + AddVariationsForSensor(Definition); + + // - Noise seed -------------------------------- + FActorVariation NoiseSeed; + NoiseSeed.Id = TEXT("noise_seed"); + NoiseSeed.Type = EActorAttributeType::Int; + NoiseSeed.RecommendedValues = { TEXT("0") }; + NoiseSeed.bRestrictToRecommended = false; + + //TransmitPower + FActorVariation TransmitPower; + TransmitPower.Id = TEXT("transmit_power"); + TransmitPower.Type = EActorAttributeType::Float; + TransmitPower.RecommendedValues = { TEXT("21.5")}; + + //ReceiveSensitivity + FActorVariation ReceiverSensitivity; + ReceiverSensitivity.Id = TEXT("receiver_sensitivity"); + ReceiverSensitivity.Type = EActorAttributeType::Float; + ReceiverSensitivity.RecommendedValues = { TEXT("-99.0")}; + + //Frequency + FActorVariation Frequency; + Frequency.Id = TEXT("frequency_ghz"); + Frequency.Type = EActorAttributeType::Float; + Frequency.RecommendedValues = { TEXT("5.9")}; + + //Combined Antenna Gain in dBi + FActorVariation CombinedAntennaGain; + CombinedAntennaGain.Id = TEXT("combined_antenna_gain"); + CombinedAntennaGain.Type = EActorAttributeType::Float; + CombinedAntennaGain.RecommendedValues = { TEXT("10.0")}; + + //Scenario + FActorVariation Scenario; + Scenario.Id = TEXT("scenario"); + Scenario.Type = EActorAttributeType::String; + Scenario.RecommendedValues = { TEXT("highway"), TEXT("rural"), TEXT("urban")}; + Scenario.bRestrictToRecommended = true; + + //Path loss exponent + FActorVariation PLE; + PLE.Id = TEXT("path_loss_exponent"); + PLE.Type = EActorAttributeType::Float; + PLE.RecommendedValues = { TEXT("2.7")}; + + + //FSPL reference distance for LDPL calculation + FActorVariation FSPL_RefDistance; + FSPL_RefDistance.Id = TEXT("d_ref"); + FSPL_RefDistance.Type = EActorAttributeType::Float; + FSPL_RefDistance.RecommendedValues = { TEXT("1.0")}; + + //filter distance to speed up calculation + FActorVariation FilterDistance; + FilterDistance.Id = TEXT("filter_distance"); + FilterDistance.Type = EActorAttributeType::Float; + FilterDistance.RecommendedValues = { TEXT("500.0")}; + + //etsi fading + FActorVariation EtsiFading; + EtsiFading.Id = TEXT("use_etsi_fading"); + EtsiFading.Type = EActorAttributeType::Bool; + EtsiFading.RecommendedValues = { TEXT("true")}; + + //custom fading std deviation + FActorVariation CustomFadingStddev; + CustomFadingStddev.Id = TEXT("custom_fading_stddev"); + CustomFadingStddev.Type = EActorAttributeType::Float; + CustomFadingStddev.RecommendedValues = { TEXT("0.0")}; + + //path loss model + FActorVariation PLModel; + PLModel.Id = TEXT("path_loss_model"); + PLModel.Type = EActorAttributeType::String; + PLModel.RecommendedValues = { TEXT("winner"), TEXT("geometric")}; + PLModel.bRestrictToRecommended = true; + + + Definition.Variations.Append({ + NoiseSeed, + TransmitPower, + ReceiverSensitivity, + Frequency, + CombinedAntennaGain, + Scenario, + PLModel, + PLE, + FSPL_RefDistance, + FilterDistance, + EtsiFading, + CustomFadingStddev +}); + + Success = CheckActorDefinition(Definition); +} + + FActorDefinition UActorBlueprintFunctionLibrary::MakeGnssDefinition() { FActorDefinition Definition; @@ -1763,4 +2111,136 @@ void UActorBlueprintFunctionLibrary::SetRadar( RetrieveActorAttributeToInt("points_per_second", Description.Variations, 1500)); } +void UActorBlueprintFunctionLibrary::SetV2X( + const FActorDescription &Description, + AV2XSensor* V2X) +{ + CARLA_ABFL_CHECK_ACTOR(V2X); + if (Description.Variations.Contains("noise_seed")) + { + V2X->SetSeed( + RetrieveActorAttributeToInt("noise_seed", Description.Variations, 0)); + } + else + { + V2X->SetSeed(V2X->GetRandomEngine()->GenerateRandomSeed()); + } + + V2X->SetPropagationParams( + RetrieveActorAttributeToFloat("transmit_power", Description.Variations, 21.5), + RetrieveActorAttributeToFloat("receiver_sensitivity", Description.Variations, -99.0), + RetrieveActorAttributeToFloat("frequency_ghz", Description.Variations, 5.9), + RetrieveActorAttributeToFloat("combined_antenna_gain", Description.Variations, 10.0), + RetrieveActorAttributeToFloat("path_loss_exponent", Description.Variations, 2.7), + RetrieveActorAttributeToFloat("d_ref", Description.Variations, 1.0), + RetrieveActorAttributeToFloat("filter_distance", Description.Variations, 500.0), + RetrieveActorAttributeToBool("use_etsi_fading", Description.Variations, true), + RetrieveActorAttributeToFloat("custom_fading_stddev", Description.Variations, 0.0f) + ); + + if (RetrieveActorAttributeToString("scenario", Description.Variations, "urban") == "urban") + { + V2X->SetScenario(EScenario::Urban); + } + else if (RetrieveActorAttributeToString("scenario", Description.Variations, "urban") == "rural") + { + V2X->SetScenario(EScenario::Rural); + } + else + { + V2X->SetScenario(EScenario::Highway); + } + + V2X->SetCaServiceParams( + RetrieveActorAttributeToFloat("gen_cam_min", Description.Variations, 0.1), + RetrieveActorAttributeToFloat("gen_cam_max", Description.Variations, 1.0), + RetrieveActorAttributeToBool("fixed_rate", Description.Variations, false)); + + V2X->SetAccelerationStandardDeviation({ + RetrieveActorAttributeToFloat("noise_accel_stddev_x", Description.Variations, 0.0f), + RetrieveActorAttributeToFloat("noise_accel_stddev_y", Description.Variations, 0.0f), + RetrieveActorAttributeToFloat("noise_accel_stddev_z", Description.Variations, 0.0f)}); + + V2X->SetGNSSDeviation( + RetrieveActorAttributeToFloat("noise_lat_stddev", Description.Variations, 0.0f), + RetrieveActorAttributeToFloat("noise_lon_stddev", Description.Variations, 0.0f), + RetrieveActorAttributeToFloat("noise_alt_stddev", Description.Variations, 0.0f), + RetrieveActorAttributeToFloat("noise_head_stddev", Description.Variations, 0.0f), + RetrieveActorAttributeToFloat("noise_lat_bias", Description.Variations, 0.0f), + RetrieveActorAttributeToFloat("noise_lon_bias", Description.Variations, 0.0f), + RetrieveActorAttributeToFloat("noise_alt_bias", Description.Variations, 0.0f), + RetrieveActorAttributeToFloat("noise_head_bias", Description.Variations, 0.0f)); + + V2X->SetVelDeviation( + RetrieveActorAttributeToFloat("noise_vel_stddev_x", Description.Variations, 0.0f) + ); + V2X->SetYawrateDeviation( + RetrieveActorAttributeToFloat("noise_yawrate_stddev", Description.Variations, 0.0f), + RetrieveActorAttributeToFloat("noise_yawrate_bias", Description.Variations, 0.0f) + ); + + if (RetrieveActorAttributeToString("path_loss_model", Description.Variations, "geometric") == "winner") + { + V2X->SetPathLossModel(EPathLossModel::Winner); + } + else if(RetrieveActorAttributeToString("path_loss_model", Description.Variations, "geometric") == "geometric") + { + V2X->SetPathLossModel(EPathLossModel::Geometric); + } + + +} + +void UActorBlueprintFunctionLibrary::SetCustomV2X( + const FActorDescription &Description, + ACustomV2XSensor* V2X) +{ + CARLA_ABFL_CHECK_ACTOR(V2X); + if (Description.Variations.Contains("noise_seed")) + { + V2X->SetSeed( + RetrieveActorAttributeToInt("noise_seed", Description.Variations, 0)); + } + else + { + V2X->SetSeed(V2X->GetRandomEngine()->GenerateRandomSeed()); + } + + V2X->SetPropagationParams( + RetrieveActorAttributeToFloat("transmit_power", Description.Variations, 21.5), + RetrieveActorAttributeToFloat("receiver_sensitivity", Description.Variations, -99.0), + RetrieveActorAttributeToFloat("frequency_ghz", Description.Variations, 5.9), + RetrieveActorAttributeToFloat("combined_antenna_gain", Description.Variations, 10.0), + RetrieveActorAttributeToFloat("path_loss_exponent", Description.Variations, 2.7), + RetrieveActorAttributeToFloat("d_ref", Description.Variations, 1.0), + RetrieveActorAttributeToFloat("filter_distance", Description.Variations, 500.0), + RetrieveActorAttributeToBool("use_etsi_fading", Description.Variations, true), + RetrieveActorAttributeToFloat("custom_fading_stddev", Description.Variations, 0.0f) + ); + + if (RetrieveActorAttributeToString("scenario", Description.Variations, "urban") == "urban") + { + V2X->SetScenario(EScenario::Urban); + } + else if (RetrieveActorAttributeToString("scenario", Description.Variations, "urban") == "rural") + { + V2X->SetScenario(EScenario::Rural); + } + else + { + V2X->SetScenario(EScenario::Highway); + } + + + if (RetrieveActorAttributeToString("path_loss_model", Description.Variations, "geometric") == "winner") + { + V2X->SetPathLossModel(EPathLossModel::Winner); + } + else if(RetrieveActorAttributeToString("path_loss_model", Description.Variations, "geometric") == "geometric") + { + V2X->SetPathLossModel(EPathLossModel::Geometric); + } + + +} #undef CARLA_ABFL_CHECK_ACTOR diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.h index 5ae41c795..61ad86586 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.h @@ -14,6 +14,10 @@ #include "Carla/Sensor/GnssSensor.h" #include "Carla/Sensor/Radar.h" #include "Carla/Sensor/InertialMeasurementUnit.h" +#include "Carla/Sensor/V2XSensor.h" +#include "Carla/Sensor/CustomV2XSensor.h" +#include "Carla/Sensor/V2XSensor.h" +#include "Carla/Sensor/CustomV2XSensor.h" #include "Kismet/BlueprintFunctionLibrary.h" @@ -108,6 +112,34 @@ public: bool &Success, FActorDefinition &Definition); + static FActorDefinition MakeV2XDefinition(); + + UFUNCTION(Category = "Carla Actor", BlueprintCallable) + static void MakeV2XDefinition( + bool &Success, + FActorDefinition &Definition); + + static FActorDefinition MakeCustomV2XDefinition(); + + UFUNCTION(Category = "Carla Actor", BlueprintCallable) + static void MakeCustomV2XDefinition( + bool &Success, + FActorDefinition &Definition); + + static FActorDefinition MakeV2XDefinition(); + + UFUNCTION(Category = "Carla Actor", BlueprintCallable) + static void MakeV2XDefinition( + bool &Success, + FActorDefinition &Definition); + + static FActorDefinition MakeCustomV2XDefinition(); + + UFUNCTION(Category = "Carla Actor", BlueprintCallable) + static void MakeCustomV2XDefinition( + bool &Success, + FActorDefinition &Definition); + UFUNCTION(Category = "Carla Actor", BlueprintCallable) static void MakeVehicleDefinition( const FVehicleParameters &Parameters, @@ -226,4 +258,7 @@ public: static void SetIMU(const FActorDescription &Description, AInertialMeasurementUnit *IMU); static void SetRadar(const FActorDescription &Description, ARadar *Radar); + + static void SetV2X(const FActorDescription &Description, AV2XSensor *V2X); + static void SetCustomV2X(const FActorDescription &Description, ACustomV2XSensor *V2X); }; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/CustomV2XSensor.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/CustomV2XSensor.cpp new file mode 100644 index 000000000..60c5aabbb --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/CustomV2XSensor.cpp @@ -0,0 +1,225 @@ +// Copyright (c) 2024 Institut fuer Technik der Informationsverarbeitung (ITIV) at the +// Karlsruhe Institute of Technology +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "Carla.h" +#include "Carla/Actor/ActorBlueprintFunctionLibrary.h" +#include "Carla/Game/CarlaEpisode.h" +#include "Carla/Vehicle/CarlaWheeledVehicle.h" +#include +#include +#include +#include "CustomV2XSensor.h" +#include "V2X/PathLossModel.h" + +std::list ACustomV2XSensor::mV2XActorContainer; +ACustomV2XSensor::ActorV2XDataMap ACustomV2XSensor::mActorV2XDataMap; + +ACustomV2XSensor::ACustomV2XSensor(const FObjectInitializer &ObjectInitializer) + : Super(ObjectInitializer) +{ + PrimaryActorTick.bCanEverTick = true; + RandomEngine = CreateDefaultSubobject(TEXT("RandomEngine")); + + // Init path loss model + PathLossModelObj = new PathLossModel(RandomEngine); +} + +void ACustomV2XSensor::SetOwner(AActor *Owner) +{ + UE_LOG(LogCarla, Warning, TEXT("CustomV2XSensor: called setowner with %p"), Owner); + if (GetOwner() != nullptr) + { + ACustomV2XSensor::mV2XActorContainer.remove(GetOwner()); + UE_LOG(LogCarla, Warning, TEXT("CustomV2XSensor: removed old owner %p"), GetOwner()); + } + + Super::SetOwner(Owner); + + // Store the actor into the static list if the actor details are not available + if(Owner != nullptr) + { + if (std::find(ACustomV2XSensor::mV2XActorContainer.begin(), ACustomV2XSensor::mV2XActorContainer.end(), Owner) == ACustomV2XSensor::mV2XActorContainer.end()) + { + ACustomV2XSensor::mV2XActorContainer.push_back(Owner); + UE_LOG(LogCarla, Warning, TEXT("CustomV2XSensor: added owner, length now %d"), ACustomV2XSensor::mV2XActorContainer.size()); + } + + } + + PathLossModelObj->SetOwner(Owner); + + UCarlaEpisode* CarlaEpisode = UCarlaStatics::GetCurrentEpisode(GetWorld()); + FCarlaActor* CarlaActor = CarlaEpisode->FindCarlaActor(Owner); + if (CarlaActor != nullptr) + { + mStationId = static_cast(CarlaActor->GetActorId()); + } +} + +FActorDefinition ACustomV2XSensor::GetSensorDefinition() +{ + return UActorBlueprintFunctionLibrary::MakeCustomV2XDefinition(); +} + +/* Function to add configurable parameters*/ +void ACustomV2XSensor::Set(const FActorDescription &ActorDescription) +{ + UE_LOG(LogCarla, Warning, TEXT("CustomV2XSensor: Set function called")); + Super::Set(ActorDescription); + UActorBlueprintFunctionLibrary::SetCustomV2X(ActorDescription, this); +} + +void ACustomV2XSensor::SetPropagationParams(const float TransmitPower, + const float ReceiverSensitivity, + const float Frequency, + const float combined_antenna_gain, + const float path_loss_exponent, + const float reference_distance_fspl, + const float filter_distance, + const bool use_etsi_fading, + const float custom_fading_stddev) +{ + // forward parameters to PathLossModel Obj + PathLossModelObj->SetParams(TransmitPower, ReceiverSensitivity, Frequency, combined_antenna_gain, path_loss_exponent, reference_distance_fspl, filter_distance, use_etsi_fading, custom_fading_stddev); +} + +void ACustomV2XSensor::SetPathLossModel(const EPathLossModel path_loss_model){ + PathLossModelObj->SetPathLossModel(path_loss_model); +} + +void ACustomV2XSensor::SetScenario(EScenario scenario) +{ + PathLossModelObj->SetScenario(scenario); +} + +/* + * Function stores the actor details in to the static list. + * Calls the CaService object to generate CAM message + * Stores the message in static map + */ +void ACustomV2XSensor::PrePhysTick(float DeltaSeconds) +{ + Super::PrePhysTick(DeltaSeconds); + // Clear the message created during the last sim cycle + if (GetOwner()) + { + ACustomV2XSensor::mActorV2XDataMap.erase(GetOwner()); + + // Step 0: Create message to send, if triggering conditions fulfilled + // this needs to be done in pre phys tick to enable synchronous reception in all other v2x sensors + // Check whether the message is generated + if (mMessageDataChanged) + { + // If message is generated store it + // make a pair of message and sending power + // if different v2x sensors send with different power, we need to store that + carla::sensor::data::CustomV2XData message_pw; + message_pw.Message = CreateCustomV2XMessage(); + + message_pw.Power = PathLossModelObj->GetTransmitPower(); + ACustomV2XSensor::mActorV2XDataMap.insert({GetOwner(), message_pw}); + } + } +} + +CustomV2XM_t ACustomV2XSensor::CreateCustomV2XMessage() +{ + CustomV2XM_t message = CustomV2XM_t(); + + CreateITSPduHeader(message); + std::strcpy(message.message,mMessageData.c_str()); + mMessageDataChanged = false; + return message; +} + +void ACustomV2XSensor::CreateITSPduHeader(CustomV2XM_t &message) +{ + ITSContainer::ItsPduHeader_t& header = message.header; + header.protocolVersion = mProtocolVersion; + header.messageID = mMessageId; + header.stationID = mStationId; +} + +/* + * Function takes care of sending messages to the current actor. + * First simulates the communication by calling LOSComm object. + * If there is a list present then messages from those list are sent to the current actor + */ +void ACustomV2XSensor::PostPhysTick(UWorld *World, ELevelTick TickType, float DeltaTime) +{ + TRACE_CPUPROFILER_EVENT_SCOPE(ACustomV2XSensor::PostPhysTick); + + // Step 1: Create an actor list which has messages to send targeting this v2x sensor instance + std::vector ActorPowerList; + for (const auto &pair : ACustomV2XSensor::mActorV2XDataMap) + { + if (pair.first != GetOwner()) + { + ActorPowerPair actor_power_pair; + actor_power_pair.first = pair.first; + // actor sending with transmit power + actor_power_pair.second = pair.second.Power; + ActorPowerList.push_back(actor_power_pair); + } + } + + // Step 2: Simulate the communication for the actors in actor list to current actor. + if (!ActorPowerList.empty()) + { + UCarlaEpisode *carla_episode = UCarlaStatics::GetCurrentEpisode(GetWorld()); + PathLossModelObj->Simulate(ActorPowerList, carla_episode, GetWorld()); + // Step 3: Get the list of actors who can send message to current actor, and the receive power of their messages. + ActorPowerMap actor_receivepower_map = PathLossModelObj->GetReceiveActorPowerList(); + // Step 4: Retrieve the messages of the actors that are received + + // get registry to retrieve carla actor IDs + const FActorRegistry &Registry = carla_episode->GetActorRegistry(); + + ACustomV2XSensor::V2XDataList msg_received_power_list; + for (const auto &pair : actor_receivepower_map) + { + carla::sensor::data::CustomV2XData send_msg_and_pw = ACustomV2XSensor::mActorV2XDataMap.at(pair.first); + carla::sensor::data::CustomV2XData received_msg_and_pw; + // sent CAM + received_msg_and_pw.Message = send_msg_and_pw.Message; + // receive power + received_msg_and_pw.Power = pair.second; + + msg_received_power_list.push_back(received_msg_and_pw); + } + + WriteMessageToV2XData(msg_received_power_list); + } + // Step 5: Send message + + if (mV2XData.GetMessageCount() > 0) + { + auto DataStream = GetDataStream(*this); + DataStream.SerializeAndSend(*this, mV2XData, DataStream.PopBufferFromPool()); + } + mV2XData.Reset(); +} + +/* + * Function the store the message into the structure so it can be sent to python client + */ +void ACustomV2XSensor::WriteMessageToV2XData(const ACustomV2XSensor::V2XDataList &msg_received_power_list) +{ + for (const auto &elem : msg_received_power_list) + { + mV2XData.WriteMessage(elem); + } +} + + +void ACustomV2XSensor::Send(const FString message) +{ + //note: this is unsafe! + //should be fixed to limit length somewhere + mMessageData = TCHAR_TO_UTF8(*message); + mMessageDataChanged = true; +} + diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/CustomV2XSensor.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/CustomV2XSensor.h new file mode 100644 index 000000000..2b3557dad --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/CustomV2XSensor.h @@ -0,0 +1,73 @@ +// Copyright (c) 2024 Institut fuer Technik der Informationsverarbeitung (ITIV) at the +// Karlsruhe Institute of Technology +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "Carla/Sensor/Sensor.h" +#include "Carla/Actor/ActorDefinition.h" +#include "Carla/Actor/ActorDescription.h" +#include +#include "V2X/PathLossModel.h" +#include +#include +#include "CustomV2XSensor.generated.h" + + +UCLASS() +class CARLA_API ACustomV2XSensor : public ASensor +{ + GENERATED_BODY() + + using FV2XData = carla::sensor::data::CustomV2XDataS; + using V2XDataList = std::vector; + using ActorV2XDataMap = std::map; + +public: + ACustomV2XSensor(const FObjectInitializer &ObjectInitializer); + + static FActorDefinition GetSensorDefinition(); + + void Set(const FActorDescription &ActorDescription) override; + void SetPropagationParams(const float TransmitPower, + const float ReceiverSensitivity, + const float Frequency, + const float combined_antenna_gain, + const float path_loss_exponent, + const float reference_distance_fspl, + const float filter_distance, + const bool use_etsi_fading, + const float custom_fading_stddev); + void SetScenario(EScenario scenario); + void SetPathLossModel(const EPathLossModel path_loss_model); + + virtual void PrePhysTick(float DeltaSeconds) override; + virtual void PostPhysTick(UWorld *World, ELevelTick TickType, float DeltaTime) override; + void SetOwner(AActor *Owner) override; + + void Send(const FString message); + +private: + static std::list mV2XActorContainer; + PathLossModel *PathLossModelObj; + + //store data + static ACustomV2XSensor::ActorV2XDataMap mActorV2XDataMap; + FV2XData mV2XData; + + //write + void WriteMessageToV2XData(const ACustomV2XSensor::V2XDataList &msg_received_power_list); + + //msg gen + void CreateITSPduHeader(CustomV2XM_t &message); + CustomV2XM_t CreateCustomV2XMessage(); + const long mProtocolVersion = 2; + const long mMessageId = ITSContainer::messageID_custom; + long mStationId; + std::string mMessageData; + bool mMessageDataChanged = false; + constexpr static uint16_t data_size = sizeof(CustomV2XM_t::message); + +}; \ No newline at end of file diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/CaService.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/CaService.cpp new file mode 100644 index 000000000..99d552a43 --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/CaService.cpp @@ -0,0 +1,755 @@ +// Copyright (c) 2024 Institut fuer Technik der Informationsverarbeitung (ITIV) at the +// Karlsruhe Institute of Technology +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "Carla.h" +#include "CaService.h" +#include +#include "carla/rpc/String.h" +#include "Carla/Util/BoundingBoxCalculator.h" +#include +static const float scLowFrequencyContainerInterval = 0.5; + + +ITSContainer::SpeedValue_t CaService::buildSpeedValue(const float vel) +{ + static const float lower = 0.0; // meter_per_second + static const float upper = 163.82; //meter_per_second + + ITSContainer::SpeedValue_t speed = ITSContainer::SpeedValue_unavailable; + if (vel >= upper) { + speed = 16382; // see CDD A.74 (TS 102 894 v1.2.1) + } else if (vel >= lower) { + //to cm per second + speed = std::round(vel * 100.0) * ITSContainer::SpeedValue_oneCentimeterPerSec; + } + return speed; +} + +CaService::CaService(URandomEngine* random_engine) +{ + mRandomEngine = random_engine; + // The starting point now + std::chrono::system_clock::time_point start_Point = std::chrono::system_clock::now(); + //the reference point for ETSI (2004-01-01T00:00:00:000Z) + std::chrono::system_clock::time_point ref_point = std::chrono::system_clock::from_time_t(1072915200); // Unix time for 2004-01-01 + + mGenerationDelta0 = std::chrono::duration_cast(start_Point - ref_point); +} + + +void CaService::SetOwner(UWorld* world, AActor *Owner) +{ + UE_LOG(LogCarla, Warning, TEXT("CaService:SetOwner function called")); + mWorld = world; + mCarlaEpisode = UCarlaStatics::GetCurrentEpisode(world); + + CurrentGeoReference = mCarlaEpisode->GetGeoReference(); + + mActorOwner = Owner; + mCarlaEpisode = UCarlaStatics::GetCurrentEpisode(mWorld); + mCarlaActor = mCarlaEpisode->FindCarlaActor(Owner); + + if (mCarlaActor != nullptr) + { + mVehicle = Cast(Owner); + + if(mCarlaActor->GetActorType() == FCarlaActor::ActorType::Vehicle) + { + UE_LOG(LogCarla, Warning, TEXT("CaService:Initialize Vehicle type")); + + mLastCamTimeStamp = mCarlaEpisode->GetElapsedGameTime() - mGenCamMax; + mLastLowCamTimeStamp = mCarlaEpisode->GetElapsedGameTime() - scLowFrequencyContainerInterval; + //Can add logic for this later + mDccRestriction = false; + + + mElapsedTime = 0; + VehicleSpeed = 0; + VehiclePosition = {0, 0, 0}; + VehicleHeading = {0, 0, 0}; + mLastCamSpeed = 0; + mLastCamPosition = {0, 0, 0}; + mLastCamHeading = {0, 0, 0}; + + } + else if((mCarlaActor->GetActorType() == FCarlaActor::ActorType::TrafficLight)|| + (mCarlaActor->GetActorType() == FCarlaActor::ActorType::TrafficSign)) + { + mGenerationInterval = 0.5; + mLastCamTimeStamp = -mGenerationInterval; + UE_LOG(LogCarla, Warning, TEXT("CaService:Initialize RSU type")); + } + + mStationId = static_cast(mCarlaActor->GetActorId()); + mStationType = GetStationType(); + + } + +} + + +void CaService::SetParams(const float GenCamMin, const float GenCamMax, const bool FixedRate) +{ + UE_LOG(LogCarla, Warning, TEXT("CaService:SetParams function called")); + //Max and Min for generation rate + + mGenCamMin = GenCamMin; //in second + mGenCamMax = GenCamMax; //in second + mGenCam = mGenCamMax; + //If we want set a fix interval make this as true + mFixedRate = FixedRate; + +} + +/* +* Function to check trigger condition for RSU +*/ +bool CaService::Trigger(float DeltaSeconds) +{ + + mElapsedTime = mCarlaEpisode->GetElapsedGameTime(); + bool Trigger = false; + if(mStationType == ITSContainer::StationType_roadSideUnit) + { + if (mElapsedTime - mLastCamTimeStamp >= mGenerationInterval) + { + Trigger = true; + mCAMMessage = CreateCooperativeAwarenessMessage(DeltaSeconds); + mLastCamTimeStamp = mElapsedTime; + } + } + else + { + Trigger = CheckTriggeringConditions(DeltaSeconds); + + } + return Trigger; + +} + +/* +* Function to provide CAM message to other objects if necessary +*/ +CAM_t CaService::GetCamMessage() +{ + return mCAMMessage; +} + +/* +* Check the trigger condition in case of vehicles and if trigger is true request +* to generate CAM message +*/ +bool CaService::CheckTriggeringConditions(float DeltaSeconds) +{ + float &T_GenCam = mGenCam; + const float T_GenCamMin = mGenCamMin; + const float T_GenCamMax = mGenCamMax; + const float T_GenCamDcc = mDccRestriction ? 0 : T_GenCamMin; + const float T_elapsed = mElapsedTime - mLastCamTimeStamp; + if(T_elapsed >= T_GenCamDcc) + { + //If message need to be generated every sim tick then set this to true. + if(mFixedRate) + { + GenerateCamMessage(DeltaSeconds); + return true; + } + + else if (CheckHeadingDelta(DeltaSeconds) || CheckPositionDelta(DeltaSeconds) || CheckSpeedDelta(DeltaSeconds)) + { + GenerateCamMessage(DeltaSeconds); + T_GenCam = std::min(T_elapsed, T_GenCamMax); + mGenCamLowDynamicsCounter = 0; + return true; + } + else if (T_elapsed >= T_GenCam) + { + GenerateCamMessage(DeltaSeconds); + if (++mGenCamLowDynamicsCounter >= mGenCamLowDynamicsLimit) { + T_GenCam = T_GenCamMax; + } + return true; + } + } + return false; +} + +bool CaService::CheckPositionDelta(float DeltaSeconds) +{ + //If position change is more the 4m + VehiclePosition = mVehicle->GetActorLocation(); + double Distance = FVector::Distance(VehiclePosition, mLastCamPosition) / 100.0f; //From cm to m + if(Distance > 4.0f) + { + return true; + } + return false; +} + +bool CaService::CheckSpeedDelta(float DeltaSeconds) +{ + VehicleSpeed = mVehicle->GetVehicleForwardSpeed() / 100.0f; // From cm/s to m/s + float DeltaSpeed = std::abs(VehicleSpeed - mLastCamSpeed); + + //Speed differance is greater than 0.5m/s + if(DeltaSpeed > 0.5) + { + return true; + } + + return false; +} + +double CaService::GetFVectorAngle(const FVector &a, const FVector &b) +{ + double Dot = a.X * b.X + a.Y * b.Y + a.Z * b.Z; + return std::acos(Dot / (a.Size() * b.Size())); +} + +void CaService::GenerateCamMessage(float DeltaTime) +{ + mCAMMessage = CreateCooperativeAwarenessMessage(DeltaTime); + mLastCamPosition = VehiclePosition; + mLastCamSpeed = VehicleSpeed; + mLastCamHeading = VehicleHeading; + mLastCamTimeStamp = mElapsedTime; +} + +//Function to get the station type +ITSContainer::StationType_t CaService::GetStationType() +{ + check(mActorOwner != nullptr); + mCarlaEpisode = UCarlaStatics::GetCurrentEpisode(mWorld); + mCarlaActor = mCarlaEpisode->FindCarlaActor(mActorOwner); + ITSContainer::StationType_t stationType = ITSContainer::StationType_unknown; + //return unknown if carla actor is gone + if(mCarlaActor == nullptr) + { + return static_cast(stationType); + } + auto Tag = ATagger::GetTagOfTaggedComponent(*mVehicle->GetMesh()); + + switch(Tag){ + case crp::CityObjectLabel::None: + stationType = ITSContainer::StationType_unknown; + break; + case crp::CityObjectLabel::Pedestrians: + stationType = ITSContainer::StationType_pedestrian; + break; + case crp::CityObjectLabel::Bicycle: + stationType = ITSContainer::StationType_cyclist; + break; + case crp::CityObjectLabel::Motorcycle: + stationType = ITSContainer::StationType_motorcycle; + break; + case crp::CityObjectLabel::Car: + stationType = ITSContainer::StationType_passengerCar; + break; + case crp::CityObjectLabel::Bus: + stationType = ITSContainer::StationType_bus; + break; + //TODO Modify this in future is CARLA adds difference truck + case crp::CityObjectLabel::Truck: + stationType = ITSContainer::StationType_lightTruck; + break; + case crp::CityObjectLabel::Buildings: + case crp::CityObjectLabel::Walls: + case crp::CityObjectLabel::Fences: + case crp::CityObjectLabel::Poles: + case crp::CityObjectLabel::TrafficLight: + case crp::CityObjectLabel::TrafficSigns: + stationType = ITSContainer::StationType_roadSideUnit; + break; + case crp::CityObjectLabel::Train: + stationType = ITSContainer::StationType_tram; + break; + default: + stationType = ITSContainer::StationType_unknown; + } + + //Can improve this later for different special vehicles once carla implements it + FCarlaActor::ActorType Type = mCarlaActor->GetActorType(); + if (Type == FCarlaActor::ActorType::Vehicle) + { + if(mCarlaActor->GetActorInfo()->Description.Variations.Contains("special_type")) + { + std::string special_type = carla::rpc::FromFString(*mCarlaActor->GetActorInfo()->Description.Variations["special_type"].Value); + if(special_type.compare("emergency") == 0 ) + { + stationType = ITSContainer::StationType_specialVehicles; + } + } + + } + return static_cast(stationType); +} + +FVector CaService::GetReferencePosition() +{ + FVector RefPos; + carla::geom::Location ActorLocation = mActorOwner->GetActorLocation(); + ALargeMapManager * LargeMap = UCarlaStatics::GetLargeMapManager(mWorld); + if (LargeMap) + { + ActorLocation = LargeMap->LocalToGlobalLocation(ActorLocation); + } + carla::geom::Location Location = ActorLocation; + carla::geom::GeoLocation CurrentLocation = CurrentGeoReference.Transform(Location); + + // Compute the noise for the sensor + const float LatError = mRandomEngine->GetNormalDistribution(0.0f, LatitudeDeviation); + const float LonError = mRandomEngine->GetNormalDistribution(0.0f, LongitudeDeviation); + const float AltError = mRandomEngine->GetNormalDistribution(0.0f, AltitudeDeviation); + + // Apply the noise to the sensor + double Latitude = CurrentLocation.latitude + LatitudeBias + LatError; + double Longitude = CurrentLocation.longitude + LongitudeBias + LonError; + double Altitude = CurrentLocation.altitude + AltitudeBias + AltError; + + RefPos.X = Latitude; + RefPos.Y = Longitude; + RefPos.Z = Altitude; + return RefPos; + +} + + +float CaService::GetHeading() +{ + // Magnetometer: orientation with respect to the North in rad + const FVector CarlaNorthVector = FVector(0.0f, -1.0f, 0.0f); + const FVector ForwVect = mActorOwner->GetActorForwardVector().GetSafeNormal2D(); + const float DotProd = FVector::DotProduct(CarlaNorthVector, ForwVect); + + // We check if the dot product is higher than 1.0 due to numerical error + if (DotProd >= 1.00f) + return 0.0f; + + float Heading = std::acos(DotProd); + // Keep the angle between [0, 2pi) + if (FVector::CrossProduct(CarlaNorthVector, ForwVect).Z < 0.0f) + Heading = carla::geom::Math::Pi2() - Heading; + + const double HeadingDegree = carla::geom::Math::ToDegrees(Heading); + + // Compute the noise for the sensor + const float HeadingError = mRandomEngine->GetNormalDistribution(0.0f, HeadingDeviation); + + //add errors + return HeadingDegree + HeadingBias + HeadingError; +} + +//Function to get the vehicle role +long CaService::GetVehicleRole() +{ + long VehicleRole = ITSContainer::VehicleRole_default; + long StationType = GetStationType(); + switch (StationType) + { + case ITSContainer::StationType_cyclist: + case ITSContainer::StationType_moped: + case ITSContainer::StationType_motorcycle: + VehicleRole = ITSContainer::VehicleRole_default; + break; + case ITSContainer::StationType_bus: + case ITSContainer::StationType_tram: + VehicleRole = ITSContainer::VehicleRole_publicTransport; + break; + case ITSContainer::StationType_specialVehicles: + VehicleRole = ITSContainer::VehicleRole_emergency; + break; + default: + VehicleRole = ITSContainer::VehicleRole_default; + break; + } + return VehicleRole; +} + +CAM_t CaService::CreateCooperativeAwarenessMessage(float DeltaTime) +{ + CAM_t message = CAM_t(); + + CreateITSPduHeader(message); + AddCooperativeAwarenessMessage(message.cam, DeltaTime); + + return message; +} + +void CaService::CreateITSPduHeader(CAM_t &message) +{ + ITSContainer::ItsPduHeader_t& header = message.header; + header.protocolVersion = mProtocolVersion; + header.messageID = mMessageId; + header.stationID = mStationId; +} + +void CaService::AddCooperativeAwarenessMessage(CAMContainer::CoopAwareness_t& CoopAwarenessMessage, float DeltaTime) +{ + + /* GenerationDeltaTime */ + auto genDeltaTime = mGenerationDelta0 + std::chrono::milliseconds(static_cast(mCarlaEpisode->GetElapsedGameTime() * 1000)); + CoopAwarenessMessage.generationDeltaTime = genDeltaTime.count() % 65536 * CAMContainer::GenerationDeltaTime_oneMilliSec; //TODOCheck this logic + AddBasicContainer(CoopAwarenessMessage.camParameters.basicContainer); + if(CoopAwarenessMessage.camParameters.basicContainer.stationType == ITSContainer::StationType_roadSideUnit) + { + //TODO Future Implementation + AddRSUContainerHighFrequency(CoopAwarenessMessage.camParameters.highFrequencyContainer); + + } + else if(CoopAwarenessMessage.camParameters.basicContainer.stationType == ITSContainer::StationType_pedestrian) + { + //TODO no container available for Pedestrains + + } + else + { + //BasicVehicleContainer + AddBasicVehicleContainerHighFrequency(CoopAwarenessMessage.camParameters.highFrequencyContainer, DeltaTime); + + if (mElapsedTime - mLastLowCamTimeStamp >= scLowFrequencyContainerInterval) + { + AddLowFrequencyContainer(CoopAwarenessMessage.camParameters.lowFrequencyContainer); + mLastLowCamTimeStamp = mElapsedTime; + } + else + { + //Store nothing if not used + CoopAwarenessMessage.camParameters.lowFrequencyContainer.present = CAMContainer::LowFrequencyContainer_PR_NOTHING; + } + /* + *TODO Add Special container if it a special vehicle + */ + + } + + +} + +void CaService::AddBasicContainer(CAMContainer::BasicContainer_t &BasicContainer) +{ + BasicContainer.stationType = mStationType; + + /* CamParameters ReferencePosition */ + FVector RefPos = GetReferencePosition(); + BasicContainer.referencePosition.latitude = std::round(RefPos.X * 1e6) * ITSContainer::Latitude_oneMicroDegreeNorth; + BasicContainer.referencePosition.longitude = std::round(RefPos.Y * 1e6) * ITSContainer::Longitude_oneMicroDegreeEast; + BasicContainer.referencePosition.positionConfidenceEllipse.semiMajorConfidence = ITSContainer::SemiAxisLength_unavailable; + BasicContainer.referencePosition.positionConfidenceEllipse.semiMinorConfidence = ITSContainer::SemiAxisLength_unavailable; + BasicContainer.referencePosition.positionConfidenceEllipse.semiMajorOrientation = ITSContainer::HeadingValue_unavailable; + BasicContainer.referencePosition.altitude.altitudeValue = std::round(RefPos.Z * 100.0) * ITSContainer::AltitudeValue_oneCentimeter; + BasicContainer.referencePosition.altitude.altitudeConfidence = ITSContainer::AltitudeConfidence_unavailable; +} + +void CaService::SetAccelerationStandardDeviation(const FVector &Vec) +{ + StdDevAccel = Vec; +} + + +void CaService::SetGNSSDeviation(const float noise_lat_stddev, + const float noise_lon_stddev, + const float noise_alt_stddev, + const float noise_head_stddev, + const float noise_lat_bias, + const float noise_lon_bias, + const float noise_alt_bias, + const float noise_head_bias) +{ + LatitudeDeviation = noise_lat_stddev; + LongitudeDeviation = noise_lon_stddev; + AltitudeDeviation = noise_alt_stddev; + HeadingDeviation = noise_head_stddev; + LatitudeBias = noise_lat_bias; + LongitudeBias = noise_lon_bias; + AltitudeBias = noise_alt_bias; + HeadingBias = noise_head_bias; +} + + + void CaService::SetVelDeviation(const float noise_vel_stddev_x) + { + VelocityDeviation = noise_vel_stddev_x; + } + + void CaService::SetYawrateDeviation(const float noise_yawrate_stddev, const float noise_yawrate_bias) + { + YawrateDeviation = noise_yawrate_stddev; + YawrateBias = noise_yawrate_bias; + } + + +void CaService::AddBasicVehicleContainerHighFrequency(CAMContainer::HighFrequencyContainer_t &hfc, float DeltaTime) +{ + hfc.present = CAMContainer::HighFrequencyContainer_PR_basicVehicleContainerHighFrequency; + CAMContainer::BasicVehicleContainerHighFrequency_t& bvc = hfc.basicVehicleContainerHighFrequency; + //heading + bvc.heading.headingValue = std::round(GetHeading() * 10.0); + bvc.heading.headingConfidence = ITSContainer::HeadingConfidence_equalOrWithinOneDegree; //TODO + //speed + //speed with noise + bvc.speed.speedValue = buildSpeedValue(ComputeSpeed()); + bvc.speed.speedConfidence = ITSContainer::SpeedConfidence_equalOrWithInOneCentimerterPerSec * 3; //TODO + //direction + bvc.driveDirection = (mVehicle->GetVehicleForwardSpeed() / 100.0f) >= 0.0 ? ITSContainer::DriveDirection_forward : ITSContainer::DriveDirection_backward; + //length and width + auto bb = UBoundingBoxCalculator::GetActorBoundingBox(mActorOwner); //cm + float length = bb.Extent.X *2.0; //half box + float width = bb.Extent.Y * 2.0; //half box + + bvc.vehicleLength.vehicleLengthValue = std::round(length * 10.0); //0.1 meter + bvc.vehicleLength.vehicleLengthConfidenceIndication = ITSContainer::VehicleLengthConfidenceIndication_unavailable; + bvc.vehicleWidth = std::round(width * 10.0); //0.1 meter + + //acceleration + carla::geom::Vector3D Accel = ComputeAccelerometer(DeltaTime); + + const double lonAccelValue = Accel.x * 10.0; // m/s to 0.1 m/s + // limit changes + if (lonAccelValue >= -160.0 && lonAccelValue <= 161.0) { + bvc.longitudinalAcceleration.longitudinalAccelerationValue = std::round(lonAccelValue) * ITSContainer::LongitudinalAccelerationValue_pointOneMeterPerSecSquaredForward; + } else { + bvc.longitudinalAcceleration.longitudinalAccelerationValue = ITSContainer::LongitudinalAccelerationValue_unavailable; + } + bvc.longitudinalAcceleration.longitudinalAccelerationConfidence = ITSContainer::AccelerationConfidence_unavailable; //TODO + + + //curvature TODO + bvc.curvature.curvatureValue = ITSContainer::CurvatureValue_unavailable; + bvc.curvature.curvatureConfidence = ITSContainer::CurvatureConfidence_unavailable; + bvc.curvatureCalculationMode = ITSContainer::CurvatureCalculationMode_yarRateUsed; + + //yaw rate is in rad/s --> to centidegree per second + bvc.yawRate.yawRateValue = std::round( carla::geom::Math::ToDegrees(ComputeYawRate()) * 100.0) * ITSContainer::YawRateValue_degSec_000_01ToLeft; + if (bvc.yawRate.yawRateValue < -32766 || bvc.yawRate.yawRateValue > 32766) { + bvc.yawRate.yawRateValue = ITSContainer::YawRateValue_unavailable; + } + bvc.yawRate.yawRateConfidence = ITSContainer::YawRateConfidence_unavailable; //TODO + + //optional lat and vertical accelerations + bvc.lateralAccelerationAvailable = true; + const double latAccelValue = Accel.y * 10.0; // m/s to 0.1 m/s + if (latAccelValue >= -160.0 && latAccelValue <= 161.0) { + bvc.lateralAcceleration.lateralAccelerationValue = std::round(latAccelValue) * ITSContainer::LateralAccelerationValue_pointOneMeterPerSecSquaredToLeft; + } else { + bvc.lateralAcceleration.lateralAccelerationValue = ITSContainer::LateralAccelerationValue_unavailable; + } + bvc.lateralAcceleration.lateralAccelerationConfidence = ITSContainer::AccelerationConfidence_unavailable; //TODO + + bvc.verticalAccelerationAvailable = true; + const double vertAccelValue = Accel.z * 10.0; // m/s to 0.1 m/s + if (vertAccelValue >= -160.0 && vertAccelValue <= 161.0) { + bvc.verticalAcceleration.verticalAccelerationValue = std::round(vertAccelValue) * ITSContainer::VerticalAccelerationValue_pointOneMeterPerSecSquaredUp; + } else { + bvc.verticalAcceleration.verticalAccelerationValue = ITSContainer::VerticalAccelerationValue_unavailable; + } + bvc.verticalAcceleration.verticalAccelerationConfidence = ITSContainer::AccelerationConfidence_unavailable; //TODO + + //TODO + bvc.accelerationControlAvailable = false; + bvc.lanePositionAvailable = false; + bvc.steeringWheelAngleAvailable = false; + bvc.performanceClassAvailable = false; + bvc.cenDsrcTollingZoneAvailable = false; +} + +const carla::geom::Vector3D CaService::ComputeAccelerometerNoise( + const FVector &Accelerometer) +{ + // Normal (or Gaussian or Gauss) distribution will be used as noise function. + // A mean of 0.0 is used as a first parameter, the standard deviation is + // determined by the client + constexpr float Mean = 0.0f; + return carla::geom::Vector3D { + Accelerometer.X + mRandomEngine->GetNormalDistribution(Mean, StdDevAccel.X), + Accelerometer.Y + mRandomEngine->GetNormalDistribution(Mean, StdDevAccel.Y), + Accelerometer.Z + mRandomEngine->GetNormalDistribution(Mean, StdDevAccel.Z) + }; +} + +carla::geom::Vector3D CaService::ComputeAccelerometer( + const float DeltaTime) +{ + // Used to convert from UE4's cm to meters + constexpr float TO_METERS = 1e-2; + // Earth's gravitational acceleration is approximately 9.81 m/s^2 + constexpr float GRAVITY = 9.81f; + + // 2nd derivative of the polynomic (quadratic) interpolation + // using the point in current time and two previous steps: + // d2[i] = -2.0*(y1/(h1*h2)-y2/((h2+h1)*h2)-y0/(h1*(h2+h1))) + const FVector CurrentLocation = mVehicle->GetActorLocation(); + + const FVector Y2 = PrevLocation[0]; + const FVector Y1 = PrevLocation[1]; + const FVector Y0 = CurrentLocation; + const float H1 = DeltaTime; + const float H2 = PrevDeltaTime; + + const float H1AndH2 = H2 + H1; + const FVector A = Y1 / ( H1 * H2 ); + const FVector B = Y2 / ( H2 * (H1AndH2) ); + const FVector C = Y0 / ( H1 * (H1AndH2) ); + FVector FVectorAccelerometer = TO_METERS * -2.0f * ( A - B - C ); + + // Update the previous locations + PrevLocation[0] = PrevLocation[1]; + PrevLocation[1] = CurrentLocation; + PrevDeltaTime = DeltaTime; + + // Add gravitational acceleration + FVectorAccelerometer.Z += GRAVITY; + + FQuat ImuRotation = mActorOwner->GetRootComponent()->GetComponentTransform().GetRotation(); + FVectorAccelerometer = ImuRotation.UnrotateVector(FVectorAccelerometer); + + // Cast from FVector to our Vector3D to correctly send the data in m/s^2 + // and apply the desired noise function, in this case a normal distribution + const carla::geom::Vector3D Accelerometer = + ComputeAccelerometerNoise(FVectorAccelerometer); + + return Accelerometer; +} + + +float CaService::ComputeSpeed() +{ + + const float speed = mVehicle->GetVehicleForwardSpeed() / 100.0f; + + // Normal (or Gaussian or Gauss) distribution and a bias will be used as + // noise function. + // A mean of 0.0 is used as a first parameter.The standard deviation and the + // bias are determined by the client + constexpr float Mean = 0.0f; + return boost::algorithm::clamp(speed + mRandomEngine->GetNormalDistribution(Mean, VelocityDeviation),0.0f,std::numeric_limits::max()); +} + +float CaService::ComputeYawRate() +{ + check(mActorOwner != nullptr); + const FVector AngularVelocity = + FIMU_GetActorAngularVelocityInRadians(*mActorOwner); + + const FQuat SensorLocalRotation = + mActorOwner->GetRootComponent()->GetRelativeTransform().GetRotation(); + + const FVector FVectorGyroscope = + SensorLocalRotation.RotateVector(AngularVelocity); + + // Cast from FVector to our Vector3D to correctly send the data in rad/s + // and apply the desired noise function, in this case a normal distribution + float yawrate = + ComputeYawNoise(FVectorGyroscope); + + return yawrate; //rad/s +} + +const float CaService::ComputeYawNoise( + const FVector &Gyroscope) +{ + // Normal (or Gaussian or Gauss) distribution and a bias will be used as + // noise function. + // A mean of 0.0 is used as a first parameter.The standard deviation and the + // bias are determined by the client + constexpr float Mean = 0.0f; + return Gyroscope.Z + YawrateBias + mRandomEngine->GetNormalDistribution(Mean, YawrateDeviation); +} + +long millisecondsSince2004() { + // Define the epoch time (2004-01-01T00:00:00.000Z) + std::tm epoch_time = {}; + epoch_time = {0, 0, 0, 1, 0, 104}; // January 1, 2004 + + // Convert epoch time to a std::chrono::time_point + std::chrono::system_clock::time_point epoch = std::chrono::system_clock::from_time_t(std::mktime(&epoch_time)); + + // Get the current time + std::chrono::system_clock::time_point now = std::chrono::system_clock::now(); + + // Calculate the duration since the epoch in milliseconds + std::chrono::milliseconds duration = std::chrono::duration_cast(now - epoch); + + // Return the number of milliseconds as a long + return duration.count(); +} + +void CaService::AddRSUContainerHighFrequency(CAMContainer::HighFrequencyContainer_t &hfc) +{ + hfc.present = CAMContainer::HighFrequencyContainer_PR_rsuContainerHighFrequency; + CAMContainer::RSUContainerHighFrequency_t& rsu = hfc.rsuContainerHighFrequency; + //TODO For future implementation + // ITSContainer::ProtectedCommunicationZonesRSU_t PCZR; + + uint8_t ProtectedZoneDataLength = 16; //Maximum number of elements in path history + + for (uint8_t i = 0; i <= ProtectedZoneDataLength; ++i) + { + ITSContainer::ProtectedCommunicationZone_t PCZ; + PCZ.protectedZoneType = ITSContainer::ProtectedZoneType_cenDsrcTolling; + PCZ.expiryTimeAvailable = false; + PCZ.protectedZoneLatitude = 50; + PCZ.protectedZoneLongitude = 50; + PCZ.protectedZoneRadiusAvailable = false; + PCZ.protectedZoneIDAvailable = false; + rsu.protectedCommunicationZonesRSU.list.push_back(PCZ); + rsu.protectedCommunicationZonesRSU.ProtectedCommunicationZoneCount += 1; + } +} + +void CaService::AddLowFrequencyContainer(CAMContainer::LowFrequencyContainer_t& lfc) +{ + lfc.present = CAMContainer::LowFrequencyContainer_PR_basicVehicleContainerLowFrequency; + CAMContainer::BasicVehicleContainerLowFrequency_t& bvc = lfc.basicVehicleContainerLowFrequency; + + /*Vehicle Role*/ + bvc.vehicleRole = GetVehicleRole(); + + /*Exterior Lights*/ + uint8_t* buf = &bvc.exteriorLights; + FVehicleLightState LightStateData = mVehicle->GetVehicleLightState(); + if(LightStateData.LowBeam) + { + buf[0] |= 1 << (7 - ITSContainer::ExteriorLights_lowBeamHeadlightsOn); + } + if(LightStateData.HighBeam) + { + buf[0] |= 1 << (7 - ITSContainer::ExteriorLights_highBeamHeadlightsOn); + } + if(LightStateData.LeftBlinker) + { + buf[0] |= 1 << (7 - ITSContainer::ExteriorLights_leftTurnSignalOn); + } + if(LightStateData.RightBlinker) + { + buf[0] |= 1 << (7 - ITSContainer::ExteriorLights_rightTurnSignalOn); + } + if(LightStateData.Reverse) + { + buf[0] |= 1 << (7 - ITSContainer::ExteriorLights_reverseLightOn); + } + if(LightStateData.Fog) + { + buf[0] |= 1 << (7 - ITSContainer::ExteriorLights_fogLightOn); + } + if(LightStateData.Position) + { + buf[0] |= 1 << (7 - ITSContainer::ExteriorLights_parkingLightsOn); + } + bvc.pathHistory.NumberOfPathPoint = 0; +} + +bool CaService::CheckHeadingDelta(float DeltaSeconds) +{ + //if heading diff is more than 4degree + VehicleHeading = mVehicle->GetVehicleOrientation(); + double HeadingDelta = carla::geom::Math::ToDegrees(GetFVectorAngle(mLastCamHeading, VehicleHeading)); + if(HeadingDelta > 4.0) + { + return true; + } + return false; +} + diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/CaService.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/CaService.h new file mode 100644 index 000000000..6147352e4 --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/CaService.h @@ -0,0 +1,137 @@ +// Copyright (c) 2024 Institut fuer Technik der Informationsverarbeitung (ITIV) at the +// Karlsruhe Institute of Technology +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "Carla/Sensor/Sensor.h" + +#include "Carla/Actor/ActorDefinition.h" +#include "Carla/Actor/ActorDescription.h" +#include "Carla/Vehicle/CarlaWheeledVehicle.h" +#include "carla/geom/Math.h" +#include "carla/geom/GeoLocation.h" +#include +#include "carla/sensor/data/LibITS.h" +#include + +class CaService +{ +public: + + CaService(URandomEngine* random_engine); + void SetOwner(UWorld* world, AActor *Owner); + + void SetParams(const float GenCamMin, const float GenCamMax, const bool FixedRate); + void SetVelDeviation(const float noise_vel_stddev_x); + void SetYawrateDeviation(const float noise_yawrate_stddev, const float noise_yawrate_bias); + void SetAccelerationStandardDeviation(const FVector &Vec); + void SetGNSSDeviation(const float noise_lat_stddev, + const float noise_lon_stddev, + const float noise_alt_stddev, + const float noise_head_stddev, + const float noise_lat_bias, + const float noise_lon_bias, + const float noise_alt_bias, + const float noise_head_bias); + bool Trigger(float DeltaSeconds); + CAM_t GetCamMessage(); + +private: + + AActor *mActorOwner; + FCarlaActor* mCarlaActor; + UCarlaEpisode* mCarlaEpisode; + UWorld* mWorld; + ACarlaWheeledVehicle* mVehicle; + float mLastCamTimeStamp; + float mLastLowCamTimeStamp; + float mGenCamMin; + float mGenCamMax; + float mGenCam; + double mElapsedTime; + float mGenDeltaTimeMod; + bool mDccRestriction; + bool mFixedRate; + unsigned int mGenCamLowDynamicsCounter; + unsigned int mGenCamLowDynamicsLimit; + float mGenerationInterval; + + float VehicleSpeed; + FVector VehiclePosition; + FVector VehicleHeading; + + FVector mLastCamPosition; + float mLastCamSpeed; + FVector mLastCamHeading; + std::chrono::milliseconds mGenerationDelta0; + + + bool CheckTriggeringConditions(float DeltaSeconds); + bool CheckHeadingDelta(float DeltaSeconds); + bool CheckPositionDelta(float DeltaSeconds); + bool CheckSpeedDelta(float DeltaSeconds); + double GetFVectorAngle(const FVector &a, const FVector &b); + void GenerateCamMessage(float DeltaTime); + ITSContainer::StationType_t GetStationType(); + + float GetHeading(); + long GetVehicleRole(); + + /* Constant values for message*/ + const long mProtocolVersion = 2; + const long mMessageId = ITSContainer::messageID_cam; + long mStationId; + long mStationType; + + carla::geom::Vector3D ComputeAccelerometer(const float DeltaTime); + const carla::geom::Vector3D ComputeAccelerometerNoise(const FVector &Accelerometer); + /// Standard deviation for acceleration settings. + FVector StdDevAccel; + + /// Used to compute the acceleration + std::array PrevLocation; + + /// Used to compute the acceleration + float PrevDeltaTime; + + //GNSS reference position and heading + FVector GetReferencePosition(); + carla::geom::GeoLocation CurrentGeoReference; + float LatitudeDeviation; + float LongitudeDeviation; + float AltitudeDeviation; + float HeadingDeviation; + + float LatitudeBias; + float LongitudeBias; + float AltitudeBias; + float HeadingBias; + + //Velocity + float ComputeSpeed(); + float VelocityDeviation; + + //Yaw rate + const float ComputeYawNoise(const FVector &Gyroscope); + float ComputeYawRate(); + float YawrateDeviation; + float YawrateBias; + + CAM_t CreateCooperativeAwarenessMessage(float DeltaTime); + void CreateITSPduHeader(CAM_t& message); + void AddCooperativeAwarenessMessage(CAMContainer::CoopAwareness_t& CoopAwarenessMessage, float DeltaTime); + void AddBasicContainer(CAMContainer::BasicContainer_t& BasicContainer); + void AddBasicVehicleContainerHighFrequency(CAMContainer::HighFrequencyContainer_t& hfc, float DeltaTime); + void AddRSUContainerHighFrequency(CAMContainer::HighFrequencyContainer_t& hfc); + void AddLowFrequencyContainer(CAMContainer::LowFrequencyContainer_t& lfc); + CAM_t mCAMMessage; + + //random for noise + URandomEngine* mRandomEngine; + ITSContainer::SpeedValue_t buildSpeedValue(const float vel); + + +}; \ No newline at end of file diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.cpp new file mode 100644 index 000000000..df87f9423 --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.cpp @@ -0,0 +1,563 @@ +// Copyright (c) 2024 Institut fuer Technik der Informationsverarbeitung (ITIV) at the +// Karlsruhe Institute of Technology +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "Carla.h" +#include "Carla/Game/CarlaEpisode.h" +#include "PathLossModel.h" +#include +#include + + +double PathLossModel::Frequency_GHz = 5.9f; +double PathLossModel::Frequency = 5.9f * std::pow(10,9); +double PathLossModel::lambda = PathLossModel::c_speedoflight/(5.9f * std::pow(10,9)); + +PathLossModel::PathLossModel(URandomEngine *random_engine) +{ + mRandomEngine = random_engine; +} + +void PathLossModel::SetOwner(AActor *Owner) +{ + mActorOwner = Owner; +} + +void PathLossModel::SetParams(const float TransmitPower, + const float ReceiverSensitivity, + const float Frequency, + const float combined_antenna_gain, + const float path_loss_exponent, + const float reference_distance_fspl, + const float filter_distance, + const bool use_etsi_fading, + const float custom_fading_stddev) +{ + this->TransmitPower = TransmitPower; + this->ReceiverSensitivity = ReceiverSensitivity; + this->path_loss_exponent = path_loss_exponent; + this->reference_distance_fspl = reference_distance_fspl; + this->filter_distance = filter_distance; + this->use_etsi_fading = use_etsi_fading; + this->custom_fading_stddev = custom_fading_stddev; + this->combined_antenna_gain = combined_antenna_gain; + PathLossModel::Frequency_GHz = Frequency; + PathLossModel::Frequency = PathLossModel::Frequency_GHz * std::pow(10,9); + PathLossModel::lambda = PathLossModel::c_speedoflight/PathLossModel::Frequency; + // when reference distance is set, we prepare the FSPL for the reference distance to be used in LDPL + CalculateFSPL_d0(); +} + +void PathLossModel::SetScenario(EScenario scenario) +{ + this->scenario = scenario; +} + +std::map PathLossModel::GetReceiveActorPowerList() +{ + return mReceiveActorPowerList; +} + +void PathLossModel::Simulate(const std::vector ActorList, UCarlaEpisode *CarlaEpisode, UWorld *World) +{ + // Set current world and episode + mWorld = World; + mCarlaEpisode = CarlaEpisode; + + CurrentActorLocation = mActorOwner->GetTransform().GetLocation(); + FVector OtherActorLocation; + mReceiveActorPowerList.clear(); + float ReceivedPower = 0; + // Logic to get height of the vehicle + // TODO: make that thing use the actual attachment and transform of the sensor + + double tx_height_local = (mActorOwner->GetSimpleCollisionHalfHeight() * 2.0f) + 2.0; + + const FActorRegistry &Registry = mCarlaEpisode->GetActorRegistry(); + + for (auto &actor_power_pair : ActorList) + { + const FCarlaActor *view = Registry.FindCarlaActor(actor_power_pair.first); + // ensure other actor is still alive + if (!view) + { + continue; + } + OtherActorLocation = actor_power_pair.first->GetTransform().GetLocation(); + double rx_height_local = (actor_power_pair.first->GetSimpleCollisionHalfHeight() * 2.0) + 2.0; + + // calculate relative ht and hr respecting slope and elevation + // cm + // if objects are on a slope, minimum Z height of both is the reference to calculate transmitter height + double ref0 = std::min(CurrentActorLocation.Z, OtherActorLocation.Z); + // cm + double ht = CurrentActorLocation.Z + tx_height_local - ref0; + double hr = OtherActorLocation.Z + rx_height_local - ref0; + // localize to common ref0 as ground + FVector source_rel = CurrentActorLocation; + source_rel.Z += tx_height_local; + FVector dest_rel = OtherActorLocation; + dest_rel.Z += rx_height_local; + + double Distance3d = FVector::Distance(source_rel, dest_rel) / 100.0f; // From cm to m + // to meters + ht = ht / 100.0f; + hr = hr / 100.0f; + + if (Distance3d < filter_distance) // maybe change this for highway + { + float OtherTransmitPower = actor_power_pair.second; + ReceivedPower = CalculateReceivedPower(actor_power_pair.first, + OtherTransmitPower, + CurrentActorLocation, + OtherActorLocation, + Distance3d, + ht, + tx_height_local, + hr, + rx_height_local, + ref0); + if (ReceivedPower > -1.0 * std::numeric_limits::max()) + { + mReceiveActorPowerList.insert(std::make_pair(actor_power_pair.first, ReceivedPower)); + } + } + } +} + +float PathLossModel::CalculateReceivedPower(AActor *OtherActor, + const float OtherTransmitPower, + const FVector Source, + const FVector Destination, + const double Distance3d, + const double ht, + const double ht_local, + const double hr, + const double hr_local, + const double reference_z) +{ + // hr in m + // ht in m + // reference_z in cm + // distance3d in m + bool ret = false; + FCollisionObjectQueryParams ObjectParams; + // Channels to check for collision with different object types + ObjectParams.AddObjectTypesToQuery(ECollisionChannel::ECC_WorldStatic); + ObjectParams.AddObjectTypesToQuery(ECollisionChannel::ECC_PhysicsBody); + ObjectParams.AddObjectTypesToQuery(ECollisionChannel::ECC_Vehicle); + ObjectParams.AddObjectTypesToQuery(ECollisionChannel::ECC_WorldDynamic); + HitResult.Reset(); + + FVector tx = Source; + tx.Z += ht_local; + FVector rx = Destination; + rx.Z += hr_local; + mWorld->LineTraceMultiByObjectType(HitResult, tx, rx, ObjectParams); + + // all losses + float loss = ComputeLoss(OtherActor, Source, Destination, Distance3d, ht, hr, reference_z); + + // we incorporate the tx power of the sender (the other actor), not our own + // NOTE: combined antenna gain is parametrized for each sensor. Better solution would be to parametrize individual antenna gain + // and combine at the receiver. This would allow to better account for antenna characteristics. + float ReceivedPower = OtherTransmitPower + combined_antenna_gain - loss; + + if (ReceivedPower >= ReceiverSensitivity) + { + ret = true; + } + float deltaPercentage = loss / (OtherTransmitPower - ReceiverSensitivity); + + // Works only when run in debug mode + DrawDebugLine( + mWorld, + tx, + rx, + FColor::Cyan, + false, 0.05f, 0, + 30); + if (deltaPercentage < 0.65) + { + DrawDebugLine( + mWorld, + tx, + rx, + FColor::Green, + false, 0.1f, 0, + 30); + } + else if (deltaPercentage < 0.8) + { + DrawDebugLine( + mWorld, + tx, + rx, + FColor::Orange, + false, 0.1f, 0, + 30); + } + else if (ReceivedPower >= ReceiverSensitivity) + { + DrawDebugLine( + mWorld, + tx, + rx, + FColor::Red, + false, 0.1f, 0, + 30); + } + + if (ret) + { + return ReceivedPower; + } + else + { + return -1.0 * std::numeric_limits::max(); + } +} + +void PathLossModel::EstimatePathStateAndVehicleObstacles(AActor *OtherActor, + FVector CurrentActorLocation, + double TxHeight, + double RxHeight, + double reference_z, + EPathState &state, + std::vector &vehicle_obstacles) +{ + // CurrentActorLocation in cm original + // TxHeight in m + // RxHeight in m + // reference_z in cm + + // init with LOS + state = EPathState::LOS; + if (HitResult.Num() == 0) + { + // no hits --> LOS + return; + } + + // check all hits + for (const FHitResult &HitInfo : HitResult) + { + + FVector location; + if (HitIsSelfOrOther(HitInfo, OtherActor)) + { + // the current hit is either Tx or Rx, so we can skip it, no obstacle + continue; + } + + // cal by ref + if (GetLocationIfVehicle(CurrentActorLocation, HitInfo, reference_z, location)) + { + // we found a vehicle + // Note: we may set this several times if we have several vehicles in between + state = EPathState::NLOSv; + // z (height) is gonna be in m in relation to reference height + // x,y also in meters + // call by reference + vehicle_obstacles.emplace_back(location); + + // alternative (cf Etsi): statistical model + // vehicle_blockage_loss += MakeVehicleBlockageLoss(TxHeight, RxHeight, obj_height, obj_dist); + } + // but if we hit a building, we stop and switch to NLOSb + else + { + state = EPathState::NLOSb; + break; + } + } +} + +double PathLossModel::CalculateNLOSvLoss(const FVector Source, + const FVector Destination, + const double TxHeight, + const double RxHeight, + const double RxDistance3d, + std::vector &vehicle_obstacles) +{ + double vehicle_blockage_loss = 0.0; + + // convert all positions to meters + FVector pos_tx = Source; + pos_tx.X /= 100.0f; + pos_tx.Y /= 100.0f; + pos_tx.Z = TxHeight; + + FVector pos_rx = Destination; + pos_rx.X /= 100.0f; + pos_rx.Y /= 100.0f; + pos_rx.Z = RxHeight; + const double distTxRx{sqrt(std::pow(pos_rx.X - pos_tx.X, 2) + std::pow(pos_rx.Y - pos_tx.Y, 2))}; /*< ground distance */ + DiffractionObstacle Tx{0.0, pos_tx.Z}; + DiffractionObstacle Rx{distTxRx, pos_rx.Z}; + + auto obsTop = buildTopObstacles(vehicle_obstacles, pos_tx, pos_rx); + + if (!obsTop.empty()) + { + obsTop.push_front(Tx); + obsTop.push_back(Rx); + auto path = computeMultipleKnifeEdge(obsTop); + vehicle_blockage_loss = path.attenuation; + } + + return vehicle_blockage_loss; +} + +void PathLossModel::SetPathLossModel(const EPathLossModel path_loss_model) +{ + model = path_loss_model; +} + + +float PathLossModel::ComputeLoss(AActor *OtherActor, FVector Source, FVector Destination, double Distance3d, double TxHeight, double RxHeight, double reference_z) +{ + // TxHeight in m + // RxHeight in m + // reference_z in cm + // distance3d in m + EPathState state; + + float PathLoss = 0.0; + double VehicleBlockageLoss; + float ShadowFadingLoss = 0.0; + + // state and vehicle obstacles are call-by-reference + std::vector vehicle_obstacles; + EstimatePathStateAndVehicleObstacles(OtherActor, Source, TxHeight, RxHeight, reference_z, state, vehicle_obstacles); + + if (model == EPathLossModel::Winner) + { + // calculate pure path loss depending on state and scenario + PathLoss = CalculatePathLoss_WINNER(state, Distance3d); + // in nlosv case, add multi knife edge + if (state == EPathState::NLOSv) + { + PathLoss = PathLoss + CalculateNLOSvLoss(Source, Destination, TxHeight, RxHeight, Distance3d, vehicle_obstacles); + } + } + else + { + if (state == EPathState::LOS) + { + // full two ray path loss + PathLoss = CalculateTwoRayPathLoss(Distance3d, TxHeight, RxHeight); + } + else if (state == EPathState::NLOSb) + { + // log distance path loss + PathLoss = (m_fspl_d0 + 10.0 * path_loss_exponent * log10(Distance3d / reference_distance_fspl)); + } + else + { + // fspl + multi knife edge + // fspl + double free_space_loss = 20.0 * log10(Distance3d) + 20.0 * log10(4.0 * M_PI / lambda); + // add the knife edge vehicle blockage loss + PathLoss = free_space_loss + CalculateNLOSvLoss(Source, Destination, TxHeight, RxHeight, Distance3d, vehicle_obstacles); + } + } + + // add random shadows + ShadowFadingLoss = CalculateShadowFading(state); + return PathLoss + ShadowFadingLoss; +} + +bool PathLossModel::IsVehicle(const FHitResult &HitInfo) +{ + bool Vehicle = false; + const FActorRegistry &Registry = mCarlaEpisode->GetActorRegistry(); + + const AActor *actor = HitInfo.Actor.Get(); + + if (actor != nullptr) + { + + const FCarlaActor *view = Registry.FindCarlaActor(actor); + if (view) + { + if (view->GetActorType() == FCarlaActor::ActorType::Vehicle) + { + Vehicle = true; + } + } + } + return Vehicle; +} + +bool PathLossModel::HitIsSelfOrOther(const FHitResult &HitInfo, AActor *OtherActor) +{ + const AActor *actor = HitInfo.Actor.Get(); + if (actor != nullptr) + { + if (actor == mActorOwner) + { + return true; + } + else if (actor == OtherActor) + { + return true; + } + } + return false; +} + +bool PathLossModel::GetLocationIfVehicle(const FVector CurrentActorLocation, const FHitResult &HitInfo, const double reference_z, FVector &location) +{ + // reference_z in cm + bool Vehicle = false; + const FActorRegistry &Registry = mCarlaEpisode->GetActorRegistry(); + + const AActor *actor = HitInfo.Actor.Get(); + + if (actor != nullptr) + { + + const FCarlaActor *view = Registry.FindCarlaActor(actor); + if (view) + { + if (view->GetActorType() == FCarlaActor::ActorType::Vehicle) + { + Vehicle = true; + location = actor->GetTransform().GetLocation(); + location.Z = location.Z - reference_z + (actor->GetSimpleCollisionHalfHeight() * 2.0) + 2.0; + location.Z = location.Z / 100.0f; + // cm to m + location.X /= 100.0f; + location.Y /= 100.0f; + } + } + } + return Vehicle; +} + +void PathLossModel::CalculateFSPL_d0() +{ + m_fspl_d0 = 20.0 * log10(reference_distance_fspl) + 20.0 * log10(Frequency) + 20.0 * log10(4.0 * M_PI / c_speedoflight); +} + +// Following ETSI TR 103 257-1 V1.1.1 (2019-05: from WINNER Project Board: "D5.3 - WINNER+ Final Channel Models", 30 06 2010. +float PathLossModel::CalculatePathLoss_WINNER(EPathState state, double Distance) +{ + + if (state == EPathState::NLOSb) + { + // Distance should be euclidean here. + return 36.85f + 30.0f * log10(Distance) + 18.9f * log10(Frequency_GHz); + } + else // LOS, NLOSv + { + if (scenario == EScenario::Highway) + { + return 32.4f + 20.0f * log10(Distance) + 20.0f * log10(Frequency_GHz); + } + else // Rural or Urban + { + return 38.77f + 16.7f * log10(Distance) + 18.2f * log10(Frequency_GHz); + } + } +} + +// Following ETSI TR 103 257-1 V1.1.1 Table 6: Shadow-fading parameter σ for V2V +float PathLossModel::CalculateShadowFading(EPathState state) +{ + const float Mean = 0.0f; + float std_dev_dB; // = 5.2; + if (use_etsi_fading) + { + switch (state) + { + case EPathState::LOS: + switch (scenario) + { + case EScenario::Highway: + std_dev_dB = 3.3f; + break; + case EScenario::Urban: + std_dev_dB = 5.2f; + break; + case EScenario::Rural: + // no known values in ETSI Standard, take middle of Highway and Urban + std_dev_dB = 4.25f; + break; + } + break; + case EPathState::NLOSb: + switch (scenario) + { + // Note: according to ETSI, NLOSb is not applicable in Highway scenario, only Urban + // we use the same std_dev for all three scenarios if in NLOSb + case EScenario::Highway: + std_dev_dB = 6.8f; + break; + case EScenario::Urban: + std_dev_dB = 6.8f; + break; + case EScenario::Rural: + std_dev_dB = 6.8f; + break; + } + break; + case EPathState::NLOSv: + switch (scenario) + { + case EScenario::Highway: + std_dev_dB = 3.8f; + break; + case EScenario::Urban: + std_dev_dB = 5.3f; + break; + case EScenario::Rural: + // no known values in ETSI Standard, take middle of Highway and Urban + std_dev_dB = 4.55f; + break; + } + break; + } + } + else + { + //custom fading param + std_dev_dB = custom_fading_stddev; + } + + // in dB + return mRandomEngine->GetNormalDistribution(Mean, std_dev_dB); +} + +float PathLossModel::CalculateTwoRayPathLossSimple(double Distance3d, double TxHeight, double RxHeight) +{ + // simplified Two Ray Path Loss (https://en.wikipedia.org/wiki/Two-ray_ground-reflection_model) + // is only a valid assumption, if distance >> 4 pi TxHeight * RxHeight / lambda + // with f=5.9 Ghz -> lambda = c/ f = 0.05m + // and with average antenna height 2m: distance >> 1000m + return 40 * log10(Distance3d) - 10 * log10(TxHeight * TxHeight * RxHeight * RxHeight); +} + +double PathLossModel::CalculateTwoRayPathLoss(double Distance3d, double TxHeight, double RxHeight) +{ + // tx and rx height in m + // distance 3d is LOS in m + double d_ground = sqrt(std::pow(Distance3d, 2) - std::pow(TxHeight - RxHeight, 2)); + + // reflected path + // d_reflection = sqrt(d_ground^2+(ht+hr)^2) -> with d_ground = sqrt(d_los^2 - (ht-hr)^2): + double d_refl = sqrt(std::pow(Distance3d, 2) + 4.0 * TxHeight * RxHeight); + + // Sine and cosine of incident angle + double sin_theta = (TxHeight + RxHeight) / d_refl; + double cos_theta = d_ground / d_refl; + + double gamma = (sin_theta - sqrt(epsilon_r - std::pow(cos_theta, 2))) / (sin_theta + sqrt(epsilon_r - std::pow(cos_theta, 2))); + + double phi = (2.0 * M_PI / lambda * (Distance3d - d_refl)); + + return 20 * log10(4.0 * M_PI * d_ground / lambda * 1.0 / sqrt(std::pow(1 + gamma * cos(phi), 2) + std::pow(gamma, 2) * std::pow(sin(phi), 2))); +} diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.h new file mode 100644 index 000000000..04d71fa38 --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.h @@ -0,0 +1,144 @@ +// Copyright (c) 2024 Institut fuer Technik der Informationsverarbeitung (ITIV) at the +// Karlsruhe Institute of Technology +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include +#include + +using ActorPowerMap = std::map; +using ActorPowerPair = std::pair; + +enum EPathState{ + LOS, + NLOSb, + NLOSv +}; + +enum EPathLossModel{ + Winner, + Geometric, +}; + +enum EScenario{ + Highway, + Rural, + Urban +}; + +struct DiffractionObstacle +{ + DiffractionObstacle(double distTx, double height); + //meter + double d; // distance to transmitter + double h; // height of obstacle +}; + +struct DiffractionPath +{ + DiffractionPath(); + + double attenuation; + double d; //meter +}; + + +class PathLossModel +{ +public: + PathLossModel(URandomEngine* random_engine); + void SetOwner(AActor *Owner); + void SetScenario(EScenario scenario); + void Simulate(const std::vector ActorList, UCarlaEpisode *CarlaEpisode, UWorld* World); + ActorPowerMap GetReceiveActorPowerList(); + void SetParams(const float TransmitPower, + const float ReceiverSensitivity, + const float Frequency, + const float combined_antenna_gain, + const float path_loss_exponent, + const float reference_distance_fspl, + const float filter_distance, + const bool use_etsi_fading, + const float custom_fading_stddev); + float GetTransmitPower() { return TransmitPower; } + void SetPathLossModel(const EPathLossModel path_loss_model); + +private: + //multiple knife edge diffraction for NLOSv + double computeVehiclePathLoss(const FVector& pos_tx, const FVector& pos_rx, const double reference_z, std::vector& vehicle_obstacles); + double computeSimpleKnifeEdge(double heightTx, double heightRx,double heightObs, double distTxRx, double distTxObs); + DiffractionPath computeMultipleKnifeEdge(const std::list& obs); + std::list buildTopObstacles(const std::vector& vehicles, const FVector& pos_tx, const FVector& pos_rx); + + //powers + float CalculateReceivedPower(AActor* OtherActor, + const float OtherTransmitPower, + const FVector Source, + const FVector Destination, + const double Distance3d, + const double ht, + const double ht_local, + const double hr, + const double hr_local, + const double reference_z); + void EstimatePathStateAndVehicleObstacles(AActor* OtherActor, FVector Source, double TxHeight, double RxHeight, double reference_z, EPathState& state, std::vector& vehicle_obstacles); + double MakeVehicleBlockageLoss(double TxHeight, double RxHeight, double obj_height, double obj_distance); + //variables + AActor *mActorOwner; + UCarlaEpisode* mCarlaEpisode; + UWorld* mWorld; + URandomEngine* mRandomEngine; + + ActorPowerMap mReceiveActorPowerList; + FVector CurrentActorLocation; + + //constants + constexpr static float c_speedoflight = 299792458.0; //m/s + + //full two ray path loss + const double epsilon_r = 1.02; + + //params + static double Frequency_GHz; // 5.9f;//5.9 GHz + static double Frequency; // Frequency_GHz * std::pow(10,9); + static double lambda; // c_speedoflight/Frequency; + float reference_distance_fspl; //m + float TransmitPower; //dBm + float ReceiverSensitivity; //dBm + EScenario scenario; + float path_loss_exponent; // no unit, default 2.7; + float filter_distance; //in meters default 500.0 + EPathLossModel model; + bool use_etsi_fading; + float custom_fading_stddev; + float combined_antenna_gain; //10.0 dBi + + //dependent params that are precalculated on setting of params + float m_fspl_d0; + +protected: + + /// Method that allow to preprocess if the rays will be traced. + + float ComputeLoss(AActor* OtherActor, FVector Source, FVector Destination, double Distance3d, double TxHeight, double RxHeight, double reference_z); + bool IsVehicle(const FHitResult& HitInfo); + bool GetLocationIfVehicle(const FVector CurrentActorLocation, const FHitResult &HitInfo, const double reference_z, FVector& location); + bool HitIsSelfOrOther(const FHitResult &HitInfo, AActor* OtherActor); + float CalculatePathLoss_WINNER(EPathState state, double Distance); + double CalculateNLOSvLoss( const FVector Source, const FVector Destination, const double TxHeight, const double RxHeight, const double RxDistance3d, std::vector& vehicle_obstacles); + + float CalculateShadowFading(EPathState state); + + //full two ray model + double CalculateTwoRayPathLoss(double Distance3d, double TxHeight, double RxHeight); + //simplified two ray model + float CalculateTwoRayPathLossSimple(double Distance3d, double TxHeight, double RxHeight); + + //functions for precalculation + void CalculateFSPL_d0(); + TArray HitResult; + +}; \ No newline at end of file diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/VehicleObstacle.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/VehicleObstacle.cpp new file mode 100644 index 000000000..0bac279c7 --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/VehicleObstacle.cpp @@ -0,0 +1,228 @@ + +// Copyright (c) 2024 Institut fuer Technik der Informationsverarbeitung (ITIV) at the +// Karlsruhe Institute of Technology +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include +#include +#include +#include + +#include "PathLossModel.h" + + +namespace { +auto compareDistance = [](const DiffractionObstacle& a, const DiffractionObstacle& b) { return a.d < b.d; }; +auto compareHeight = [](const DiffractionObstacle& a, const DiffractionObstacle& b) { return a.h < b.h; }; + +using ObstacleIterator = std::list::const_iterator; +ObstacleIterator findMainObstacle(ObstacleIterator, ObstacleIterator); +ObstacleIterator findSecondaryObstacle(ObstacleIterator, ObstacleIterator); +} // namespace + +DiffractionObstacle::DiffractionObstacle(double distTx, double height) : + d(distTx), h(height) +{ +} + +DiffractionPath::DiffractionPath() : + attenuation(0.0), d(0.0) +{ +} + + + + + + +double PathLossModel::computeSimpleKnifeEdge(double heightTx, double heightRx,double heightObs, double distTxRx, double distTxObs) +{ + // following calculations are similar to equation 29 of ITU-R P.526-13: + // v = sqrt(2d/lambda * alpha1 * alpha2) + // + // with sinus approximation for small angles: + // alpha1 =~ sin alpha1 = h / d1 + // alpha2 =~ sin alpha2 = h / d2 + // + // v = sqrt(2d / lambda * h / d1 * h / d2) = sqrt(2) * h / sqrt(lambda * d1 * d2 / d) + // + // with d1 = distTxObs, d2 = distRxObs, d = distTxRx, + + // distance between Rx and obstacle + const double distRxObs = distTxRx - distTxObs; + // signed height relative to the line connecting Tx and Rx at obstacle position + const double obsHeightTxRxLine = (heightRx - heightTx) / distTxRx * distTxObs + heightTx; + const double h = heightObs - obsHeightTxRxLine; + // calculate the Fresnel ray + const double r = sqrt(lambda * distTxObs * distRxObs / distTxRx); + static const double root_two = sqrt(2.0); + const double v = root_two * h / r; + + double loss = 0.0; + if (v > -0.78) { + // approximation of Fresnel-Kirchoff loss given by ITU-R P.526, equation 31 (result in dB): + // J(v) = 6.9 + 20 log(sqrt((v - 01)^2 + 1) + v - 0.1) + loss = 6.9 + 20.0 * log10(sqrt(std::pow(v - 0.1,2) + 1.0) + v - 0.1); + } + + return loss; +} + +DiffractionPath PathLossModel::computeMultipleKnifeEdge(const std::list& obs) +{ + DiffractionPath path; + + // determine main and secondary obstacles + std::vector mainObs; + mainObs.push_back(obs.begin()); // Tx + for (ObstacleIterator it = obs.begin(); it != obs.end();) { + it = findMainObstacle(it, obs.end()); + if (it != obs.end()) { + mainObs.push_back(it); + } + } + // NOTE: Rx is added by loop as last main obstacle + struct SecondaryObstacle { + SecondaryObstacle(ObstacleIterator tx, ObstacleIterator obs, ObstacleIterator rx) : + tx(tx), obstacle(obs), rx(rx) {} + ObstacleIterator tx; + ObstacleIterator obstacle; + ObstacleIterator rx; + }; + + std::vector secObs; + std::vector mainObsDistances; + for (std::size_t i = 0, j = 1; j < mainObs.size(); ++i, ++j) { + const double d = mainObs[j]->d - mainObs[i]->d; + path.d += sqrt(std::pow(d,2) + std::pow(mainObs[j]->h - mainObs[i]->h,2)); + mainObsDistances.push_back(d); + + const auto delta = std::distance(mainObs[i], mainObs[j]); + if (delta == 2) { + // single other obstacle between two main obstacles + secObs.emplace_back(mainObs[i], std::next(mainObs[i]), mainObs[j]); + } else if (delta > 2) { + secObs.emplace_back(mainObs[i], findSecondaryObstacle(mainObs[i], mainObs[j]), mainObs[j]); + } + } + + // attenuation due to main obstacles + double attMainObs = 0.0; + for (std::size_t i = 0; i < mainObs.size() - 2; ++i) { + const double distTxObs = mainObsDistances[i]; + const double distTxRx = distTxObs + mainObsDistances[i+1]; + attMainObs += computeSimpleKnifeEdge(mainObs[i]->h, mainObs[i+2]->h, mainObs[i+1]->h, distTxRx, distTxObs); + } + + // attenuation due to secondary obstacles + double attSecObs = 0.0; + for (const SecondaryObstacle& sec : secObs) { + const double distTxRx = sec.rx->d - sec.tx->d; + const double distTxObs = sec.obstacle->d - sec.tx->d; + attSecObs += computeSimpleKnifeEdge(sec.tx->h, sec.rx->h, sec.obstacle->h, distTxRx, distTxObs); + } + + // correction factor C (see eq. 46 in ITU-R P.526-13) + double C = mainObs.back()->d - mainObs.front()->d; // distance between Tx and Rx + for (double d : mainObsDistances) { + C *= d; + } + double pairwiseDistProduct = 1.0; + for (std::size_t i = 1; i < mainObsDistances.size(); ++i) { + pairwiseDistProduct *= mainObsDistances[i-1] + mainObsDistances[i]; + } + C /= mainObsDistances.front() * mainObsDistances.back() * pairwiseDistProduct; + + path.attenuation = attMainObs + attSecObs - 10.0* log10(C); + return path; +} + +std::list PathLossModel::buildTopObstacles(const std::vector& vehicles, const FVector& pos_tx, const FVector& pos_rx) +{ + std::list diffTop; + const double vx = pos_rx.X - pos_tx.X; + const double vy = pos_rx.Y - pos_tx.Y; + + for (auto vehicle : vehicles) { + const double midpoint_x = vehicle.X; + const double midpoint_y = vehicle.Y; + const double k = (midpoint_x * vx - vy * pos_tx.Y + vy * midpoint_y - pos_tx.X * vx) / (std::pow(vx,2) + std::pow(vy,2)); + if (k < 0.0 || k > 1.0) continue; /*< skip points beyond the ends of TxRx line segment */ + const double d = k * sqrt(std::pow(vx,2) + std::pow(vy,2)); + diffTop.emplace_back(d, vehicle.Z); + } + + diffTop.sort(compareDistance); + return diffTop; +} + + + +namespace { + +ObstacleIterator findMainObstacle(ObstacleIterator begin, ObstacleIterator end) +{ + ObstacleIterator mainIterator = end; + double mainAngle = -std::numeric_limits::infinity(); + + if (begin != end) { + for (ObstacleIterator it = std::next(begin); it != end; ++it) { + double angle = (it->h - begin->h) / (it->d - begin->d); + if (angle > mainAngle) { + mainIterator = it; + mainAngle = angle; + } + } + } + + return mainIterator; +} + +ObstacleIterator findSecondaryObstacle(ObstacleIterator first, ObstacleIterator last) +{ + ObstacleIterator secIterator = last; + double secHeightGap { std::numeric_limits::infinity() }; + + const double distFirstLast = last->d - first->d; + const double heightFirstLast = last->h - first->h; + const auto offset = first->h * last->d - first->d * last->h; + for (ObstacleIterator it = std::next(first); it != last; ++it) { + const double heightGap = ((it->d * heightFirstLast + offset) / distFirstLast) - it->h; + if (heightGap < secHeightGap) { + secIterator = it; + secHeightGap = heightGap; + } + } + + return secIterator; +} + +} // namespace + + +//statistical model from ETSI TR 103 257-1 V1.1.1 (2019-05) +double PathLossModel::MakeVehicleBlockageLoss(double TxHeight, double RxHeight, double obj_height, double obj_distance) +{ + //according to ETSI, stochastic method + if( TxHeight > obj_height && RxHeight > obj_height) + { + //no blocking if higher than obj + return 0.0; + } + else if(TxHeight < obj_height && RxHeight < obj_height) + { + //worst case: obj is higher than both tx and rx + float mean = 9.0f + fmax(0.0f, 15.0f * log10(obj_distance)-41.0f); + return mRandomEngine->GetNormalDistribution(mean, 4.5f); + } + else + { + //something in between + float mean = 5.0f + fmax(0.0f, 15.0f * log10(obj_distance)-41.0f); + return mRandomEngine->GetNormalDistribution(mean, 4.0f); + } +} \ No newline at end of file diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2XSensor.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2XSensor.cpp new file mode 100644 index 000000000..321b21686 --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2XSensor.cpp @@ -0,0 +1,235 @@ +// Copyright (c) 2024 Institut fuer Technik der Informationsverarbeitung (ITIV) at the +// Karlsruhe Institute of Technology +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "Carla.h" +#include "Carla/Sensor/V2XSensor.h" +#include "Carla/Actor/ActorBlueprintFunctionLibrary.h" +#include "Carla/Game/CarlaEpisode.h" +#include "Carla/Vehicle/CarlaWheeledVehicle.h" +#include +#include +#include "V2X/CaService.h" +#include "V2XSensor.h" +#include "V2X/PathLossModel.h" +std::list AV2XSensor::mV2XActorContainer; +AV2XSensor::ActorV2XDataMap AV2XSensor::mActorV2XDataMap; + +AV2XSensor::AV2XSensor(const FObjectInitializer &ObjectInitializer) + : Super(ObjectInitializer) +{ + PrimaryActorTick.bCanEverTick = true; + RandomEngine = CreateDefaultSubobject(TEXT("RandomEngine")); + + // Init path loss model + PathLossModelObj = new PathLossModel(RandomEngine); + CaServiceObj = new CaService(RandomEngine); +} + +void AV2XSensor::SetOwner(AActor *Owner) +{ + UE_LOG(LogCarla, Warning, TEXT("V2XSensor: called setowner with %p"), Owner); + if (GetOwner() != nullptr) + { + AV2XSensor::mV2XActorContainer.remove(GetOwner()); + UE_LOG(LogCarla, Warning, TEXT("V2XSensor: removed old owner %p"), GetOwner()); + } + + Super::SetOwner(Owner); + + // Store the actor into the static list if the actor details are not available + if(Owner != nullptr) + { + if (std::find(AV2XSensor::mV2XActorContainer.begin(), AV2XSensor::mV2XActorContainer.end(), Owner) == AV2XSensor::mV2XActorContainer.end()) + { + AV2XSensor::mV2XActorContainer.push_back(Owner); + UE_LOG(LogCarla, Warning, TEXT("V2XSensor: added owner, length now %d"), AV2XSensor::mV2XActorContainer.size()); + } + UWorld *world = GetWorld(); + CaServiceObj->SetOwner(world, Owner); + PathLossModelObj->SetOwner(Owner); + } + +} + + +FActorDefinition AV2XSensor::GetSensorDefinition() +{ + return UActorBlueprintFunctionLibrary::MakeV2XDefinition(); +} + +/* Function to add configurable parameters*/ +void AV2XSensor::Set(const FActorDescription &ActorDescription) +{ + UE_LOG(LogCarla, Warning, TEXT("V2XSensor: Set function called")); + Super::Set(ActorDescription); + UActorBlueprintFunctionLibrary::SetV2X(ActorDescription, this); +} + +void AV2XSensor::SetCaServiceParams(const float GenCamMin, const float GenCamMax, const bool FixedRate) +{ + // forward parameters to CaService Obj + CaServiceObj->SetParams(GenCamMin, GenCamMax, FixedRate); +} + +void AV2XSensor::SetPropagationParams(const float TransmitPower, + const float ReceiverSensitivity, + const float Frequency, + const float combined_antenna_gain, + const float path_loss_exponent, + const float reference_distance_fspl, + const float filter_distance, + const bool use_etsi_fading, + const float custom_fading_stddev) +{ + // forward parameters to PathLossModel Obj + PathLossModelObj->SetParams(TransmitPower, ReceiverSensitivity, Frequency, combined_antenna_gain, path_loss_exponent, reference_distance_fspl, filter_distance, use_etsi_fading, custom_fading_stddev); +} + +void AV2XSensor::SetPathLossModel(const EPathLossModel path_loss_model){ + PathLossModelObj->SetPathLossModel(path_loss_model); +} + +void AV2XSensor::SetScenario(EScenario scenario) +{ + PathLossModelObj->SetScenario(scenario); +} + +/* + * Function stores the actor details in to the static list. + * Calls the CaService object to generate CAM message + * Stores the message in static map + */ +void AV2XSensor::PrePhysTick(float DeltaSeconds) +{ + Super::PrePhysTick(DeltaSeconds); + // Clear the message created during the last sim cycle + if (GetOwner()) + { + AV2XSensor::mActorV2XDataMap.erase(GetOwner()); + + // Step 0: Create message to send, if triggering conditions fulfilled + // this needs to be done in pre phys tick to enable synchronous reception in all other v2x sensors + // Check whether the message is generated + if (CaServiceObj->Trigger(DeltaSeconds)) + { + // If message is generated store it + // make a pair of message and sending power + // if different v2x sensors send with different power, we need to store that + carla::sensor::data::CAMData cam_pw; + cam_pw.Message = CaServiceObj->GetCamMessage(); + cam_pw.Power = PathLossModelObj->GetTransmitPower(); + AV2XSensor::mActorV2XDataMap.insert({GetOwner(), cam_pw}); + } + } +} + +void AV2XSensor::SetAccelerationStandardDeviation(const FVector &Vec) +{ + CaServiceObj->SetAccelerationStandardDeviation(Vec); +} + +void AV2XSensor::SetGNSSDeviation(const float noise_lat_stddev, + const float noise_lon_stddev, + const float noise_alt_stddev, + const float noise_head_stddev, + const float noise_lat_bias, + const float noise_lon_bias, + const float noise_alt_bias, + const float noise_head_bias) +{ + CaServiceObj->SetGNSSDeviation(noise_lat_stddev, + noise_lon_stddev, + noise_alt_stddev, + noise_head_stddev, + noise_lat_bias, + noise_lon_bias, + noise_alt_bias, + noise_head_bias); +} + +void AV2XSensor::SetVelDeviation(const float noise_vel_stddev) +{ + CaServiceObj->SetVelDeviation(noise_vel_stddev); +} + +void AV2XSensor::SetYawrateDeviation(const float noise_yawrate_stddev, const float noise_yawrate_bias) +{ + CaServiceObj->SetYawrateDeviation(noise_yawrate_stddev, noise_yawrate_bias); +} + +/* + * Function takes care of sending messages to the current actor. + * First simulates the communication by calling LOSComm object. + * If there is a list present then messages from those list are sent to the current actor + */ +void AV2XSensor::PostPhysTick(UWorld *World, ELevelTick TickType, float DeltaTime) +{ + TRACE_CPUPROFILER_EVENT_SCOPE(AV2XSensor::PostPhysTick); + if (GetOwner()) + { + // Step 1: Create an actor list which has messages to send targeting this v2x sensor instance + std::vector ActorPowerList; + for (const auto &pair : AV2XSensor::mActorV2XDataMap) + { + if (pair.first != GetOwner()) + { + ActorPowerPair actor_power_pair; + actor_power_pair.first = pair.first; + // actor sending with transmit power + actor_power_pair.second = pair.second.Power; + ActorPowerList.push_back(actor_power_pair); + } + } + + // Step 2: Simulate the communication for the actors in actor list to current actor. + if (!ActorPowerList.empty()) + { + UCarlaEpisode *carla_episode = UCarlaStatics::GetCurrentEpisode(GetWorld()); + PathLossModelObj->Simulate(ActorPowerList, carla_episode, GetWorld()); + // Step 3: Get the list of actors who can send message to current actor, and the receive power of their messages. + ActorPowerMap actor_receivepower_map = PathLossModelObj->GetReceiveActorPowerList(); + // Step 4: Retrieve the messages of the actors that are received + + // get registry to retrieve carla actor IDs + const FActorRegistry &Registry = carla_episode->GetActorRegistry(); + + AV2XSensor::V2XDataList msg_received_power_list; + for (const auto &pair : actor_receivepower_map) + { + // Note: AActor* sender_actor = pair.first; + carla::sensor::data::CAMData send_msg_and_pw = AV2XSensor::mActorV2XDataMap.at(pair.first); + carla::sensor::data::CAMData received_msg_and_pw; + // sent CAM + received_msg_and_pw.Message = send_msg_and_pw.Message; + // receive power + received_msg_and_pw.Power = pair.second; + + msg_received_power_list.push_back(received_msg_and_pw); + } + + WriteMessageToV2XData(msg_received_power_list); + } + // Step 5: Send message + + if (mV2XData.GetMessageCount() > 0) + { + auto DataStream = GetDataStream(*this); + DataStream.SerializeAndSend(*this, mV2XData, DataStream.PopBufferFromPool()); + } + mV2XData.Reset(); + } +} + +/* + * Function the store the message into the structure so it can be sent to python client + */ +void AV2XSensor::WriteMessageToV2XData(const AV2XSensor::V2XDataList &msg_received_power_list) +{ + for (const auto &elem : msg_received_power_list) + { + mV2XData.WriteMessage(elem); + } +} \ No newline at end of file diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2XSensor.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2XSensor.h new file mode 100644 index 000000000..940d5eeee --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2XSensor.h @@ -0,0 +1,77 @@ +// Copyright (c) 2024 Institut fuer Technik der Informationsverarbeitung (ITIV) at the +// Karlsruhe Institute of Technology +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "Carla/Sensor/Sensor.h" + +#include "Carla/Actor/ActorDefinition.h" +#include "Carla/Actor/ActorDescription.h" +#include +#include "V2X/CaService.h" +#include "V2X/PathLossModel.h" +#include +#include +#include "V2XSensor.generated.h" + +UCLASS() +class CARLA_API AV2XSensor : public ASensor +{ + GENERATED_BODY() + + using FV2XData = carla::sensor::data::CAMDataS; + using ActorV2XDataMap = std::map; + using V2XDataList = std::vector; + +public: + AV2XSensor(const FObjectInitializer &ObjectInitializer); + + static FActorDefinition GetSensorDefinition(); + + void Set(const FActorDescription &ActorDescription) override; + + void SetCaServiceParams(const float GenCamMin, const float GenCamMax, const bool FixedRate); + void SetPropagationParams(const float TransmitPower, + const float ReceiverSensitivity, + const float Frequency, + const float combined_antenna_gain, + const float path_loss_exponent, + const float reference_distance_fspl, + const float filter_distance, + const bool use_etsi_fading, + const float custom_fading_stddev); + void SetScenario(EScenario scenario); + + //CAM params + void SetAccelerationStandardDeviation(const FVector &Vec); + void SetGNSSDeviation(const float noise_lat_stddev, + const float noise_lon_stddev, + const float noise_alt_stddev, + const float noise_head_stddev, + const float noise_lat_bias, + const float noise_lon_bias, + const float noise_alt_bias, + const float noise_head_bias); + void SetVelDeviation(const float noise_vel_stddev); + void SetYawrateDeviation(const float noise_yawrate_stddev, const float noise_yawrate_bias); + void SetPathLossModel(const EPathLossModel path_loss_model); + + virtual void PrePhysTick(float DeltaSeconds) override; + virtual void PostPhysTick(UWorld *World, ELevelTick TickType, float DeltaTime) override; + void SetOwner(AActor *Owner) override; + +private: + static std::list mV2XActorContainer; + CaService *CaServiceObj; + PathLossModel *PathLossModelObj; + + //store data + static ActorV2XDataMap mActorV2XDataMap; + FV2XData mV2XData; + + //write + void WriteMessageToV2XData(const V2XDataList &msg_received_power_list); +}; \ No newline at end of file diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp index 7824ddfde..b5c20a919 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp @@ -20,6 +20,7 @@ #include "Carla/Util/NavigationMesh.h" #include "Carla/Util/RayTracer.h" #include "Carla/Vehicle/CarlaWheeledVehicle.h" +#include "Carla/Sensor/CustomV2XSensor.h" #include "Carla/Walker/WalkerController.h" #include "Carla/Walker/WalkerBase.h" #include "GameFramework/CharacterMovementComponent.h" @@ -964,6 +965,41 @@ BIND_SYNC(is_sensor_enabled_for_ros) << [this](carla::streaming::detail::stream_ } }; + + BIND_SYNC(send) << [this]( + cr::ActorId ActorId, + std::string message) -> R + { + REQUIRE_CARLA_EPISODE(); + FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId); + if (!CarlaActor) + { + return RespondError( + "send", + ECarlaServerResponse::ActorNotFound, + " Actor Id: " + FString::FromInt(ActorId)); + } + + if (CarlaActor->IsDormant()) + { + return RespondError( + "send", + ECarlaServerResponse::FunctionNotAvailiableWhenDormant, + " Actor Id: " + FString::FromInt(ActorId)); + } + ACustomV2XSensor* Sensor = Cast(CarlaActor->GetActor()); + if (!Sensor) + { + return RespondError( + "send", + ECarlaServerResponse::ActorTypeMismatch, + " Actor Id: " + FString::FromInt(ActorId)); + } + + Sensor->Send(cr::ToFString(message)); + return R::Success(); + }; + // ~~ Actor physics ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ BIND_SYNC(set_actor_location) << [this]( From 079f822911b58b08ca40aab404bbbf8efa1e6f3b Mon Sep 17 00:00:00 2001 From: Daniel Grimm Date: Tue, 23 Apr 2024 13:21:54 +0200 Subject: [PATCH 10/99] remove comment --- PythonAPI/carla/source/libcarla/SensorData.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/PythonAPI/carla/source/libcarla/SensorData.cpp b/PythonAPI/carla/source/libcarla/SensorData.cpp index 3b8fc8b56..73559acee 100644 --- a/PythonAPI/carla/source/libcarla/SensorData.cpp +++ b/PythonAPI/carla/source/libcarla/SensorData.cpp @@ -35,8 +35,6 @@ #include #include -// #include "V2XData.cpp" - namespace carla { namespace sensor { namespace data { From f9a49c50a4eb2db2433fa0232992d2ac7d450971 Mon Sep 17 00:00:00 2001 From: Daniel Grimm Date: Tue, 23 Apr 2024 13:29:39 +0200 Subject: [PATCH 11/99] remove ignore file --- Unreal/CarlaUE4/.ignore | 9 --------- 1 file changed, 9 deletions(-) delete mode 100644 Unreal/CarlaUE4/.ignore diff --git a/Unreal/CarlaUE4/.ignore b/Unreal/CarlaUE4/.ignore deleted file mode 100644 index fa98ea662..000000000 --- a/Unreal/CarlaUE4/.ignore +++ /dev/null @@ -1,9 +0,0 @@ -.kdev4 -.vscode -Intermediate -Plugins/Carla/CarlaDependencies -Plugins/Carla/Content -Plugins/Carla/Intermediate -Plugins/CarlaExporter/Intermediate -Plugins/CarlaTools/Content -Plugins/CarlaTools/Intermediate From 7be2803454aa93df028a9f0971076191baba108a Mon Sep 17 00:00:00 2001 From: Daniel Grimm Date: Tue, 23 Apr 2024 14:34:35 +0200 Subject: [PATCH 12/99] add EOFs --- LibCarla/source/carla/sensor/data/V2XEvent.h | 2 +- .../carla/sensor/s11n/V2XSerializer.cpp | 31 ++++++++------ .../source/carla/sensor/s11n/V2XSerializer.h | 2 +- PythonAPI/carla/source/libcarla/V2XData.cpp | 40 +------------------ .../Carla/Source/Carla/Sensor/V2X/CaService.h | 2 +- .../Source/Carla/Sensor/V2X/PathLossModel.h | 2 +- .../Carla/Sensor/V2X/VehicleObstacle.cpp | 2 +- .../Carla/Source/Carla/Sensor/V2XSensor.cpp | 2 +- .../Carla/Source/Carla/Sensor/V2XSensor.h | 2 +- 9 files changed, 26 insertions(+), 59 deletions(-) diff --git a/LibCarla/source/carla/sensor/data/V2XEvent.h b/LibCarla/source/carla/sensor/data/V2XEvent.h index f1966a5ad..817630fe7 100644 --- a/LibCarla/source/carla/sensor/data/V2XEvent.h +++ b/LibCarla/source/carla/sensor/data/V2XEvent.h @@ -58,4 +58,4 @@ namespace carla } // namespace data } // namespace sensor -} // namespace carla \ No newline at end of file +} // namespace carla diff --git a/LibCarla/source/carla/sensor/s11n/V2XSerializer.cpp b/LibCarla/source/carla/sensor/s11n/V2XSerializer.cpp index 7babb44ef..7853afac7 100644 --- a/LibCarla/source/carla/sensor/s11n/V2XSerializer.cpp +++ b/LibCarla/source/carla/sensor/s11n/V2XSerializer.cpp @@ -1,4 +1,4 @@ -// Copyright (c) 2024 Institut fuer Technik der Informationsverarbeitung (ITIV) at the +// Copyright (c) 2024 Institut fuer Technik der Informationsverarbeitung (ITIV) at the // Karlsruhe Institute of Technology // // This work is licensed under the terms of the MIT license. @@ -8,18 +8,23 @@ #include "carla/sensor/data/V2XEvent.h" -namespace carla { -namespace sensor { -namespace s11n { +namespace carla +{ + namespace sensor + { + namespace s11n + { - SharedPtr CAMDataSerializer::Deserialize(RawData &&data) { - return SharedPtr(new data::CAMEvent(std::move(data))); - } + SharedPtr CAMDataSerializer::Deserialize(RawData &&data) + { + return SharedPtr(new data::CAMEvent(std::move(data))); + } - SharedPtr CustomV2XDataSerializer::Deserialize(RawData &&data) { - return SharedPtr(new data::CustomV2XEvent(std::move(data))); - } + SharedPtr CustomV2XDataSerializer::Deserialize(RawData &&data) + { + return SharedPtr(new data::CustomV2XEvent(std::move(data))); + } -} // namespace s11n -} // namespace sensor -} // namespace carla \ No newline at end of file + } // namespace s11n + } // namespace sensor +} // namespace carla diff --git a/LibCarla/source/carla/sensor/s11n/V2XSerializer.h b/LibCarla/source/carla/sensor/s11n/V2XSerializer.h index 9d6c7e700..4c38aed47 100644 --- a/LibCarla/source/carla/sensor/s11n/V2XSerializer.h +++ b/LibCarla/source/carla/sensor/s11n/V2XSerializer.h @@ -76,4 +76,4 @@ namespace carla } // namespace s11n } // namespace sensor -} // namespace carla \ No newline at end of file +} // namespace carla diff --git a/PythonAPI/carla/source/libcarla/V2XData.cpp b/PythonAPI/carla/source/libcarla/V2XData.cpp index a29cf152e..748e330a9 100644 --- a/PythonAPI/carla/source/libcarla/V2XData.cpp +++ b/PythonAPI/carla/source/libcarla/V2XData.cpp @@ -477,45 +477,7 @@ std::string GetVehicleRoleString(ITSContainer::VehicleRole_t vehicleRole) return "Default"; } } -// boost::python::list GetVehicleExteriorLightList(const ITSContainer::ExteriorLights_t exteriorLights) -// { -// boost::python::list ExteriorLightsList; -// uint8_t light = *exteriorLights.buf; -// if(light & 0x80) -// { -// ExteriorLightsList.append("Low Beam Head Lights On"); -// } -// if(light & 0x40) -// { -// ExteriorLightsList.append("High Beam Head Lights On"); -// } -// if(light & 0x20) -// { -// ExteriorLightsList.append("Left turn signal on"); -// } -// if(light & 0x10) -// { -// ExteriorLightsList.append("Right turn signal on"); -// } -// if(light & 0x08) -// { -// ExteriorLightsList.append("Day time running lights on"); -// } -// if(light & 0x04) -// { -// ExteriorLightsList.append("Reverse light on"); -// } -// if(light & 0x02) -// { -// ExteriorLightsList.append("Fog light on"); -// } -// if(light & 0x01) -// { -// ExteriorLightsList.append("Parking Lights on"); -// } -// return ExteriorLightsList; -// } boost::python::list GetPathHistory(const ITSContainer::PathHistory_t pathHistory) { @@ -542,7 +504,7 @@ boost::python::dict GetBVCLowFrequency(const CAMContainer::BasicVehicleContainer { boost::python::dict BVC; BVC["Vehicle Role"] = GetVehicleRoleString(bvc.vehicleRole); - BVC["Exterior Light"] = bvc.exteriorLights; // GetVehicleExteriorLightList(bvc.exteriorLights); + BVC["Exterior Light"] = bvc.exteriorLights; if (bvc.pathHistory.NumberOfPathPoint != 0) { BVC["Path History"] = GetPathHistory(bvc.pathHistory); diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/CaService.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/CaService.h index 6147352e4..749b54e65 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/CaService.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/CaService.h @@ -134,4 +134,4 @@ private: ITSContainer::SpeedValue_t buildSpeedValue(const float vel); -}; \ No newline at end of file +}; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.h index 04d71fa38..beb37398b 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.h @@ -141,4 +141,4 @@ protected: void CalculateFSPL_d0(); TArray HitResult; -}; \ No newline at end of file +}; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/VehicleObstacle.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/VehicleObstacle.cpp index 0bac279c7..4f44a31d1 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/VehicleObstacle.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/VehicleObstacle.cpp @@ -225,4 +225,4 @@ double PathLossModel::MakeVehicleBlockageLoss(double TxHeight, double RxHeight, float mean = 5.0f + fmax(0.0f, 15.0f * log10(obj_distance)-41.0f); return mRandomEngine->GetNormalDistribution(mean, 4.0f); } -} \ No newline at end of file +} diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2XSensor.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2XSensor.cpp index 321b21686..503f1e923 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2XSensor.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2XSensor.cpp @@ -232,4 +232,4 @@ void AV2XSensor::WriteMessageToV2XData(const AV2XSensor::V2XDataList &msg_receiv { mV2XData.WriteMessage(elem); } -} \ No newline at end of file +} diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2XSensor.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2XSensor.h index 940d5eeee..89b6be27a 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2XSensor.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2XSensor.h @@ -74,4 +74,4 @@ private: //write void WriteMessageToV2XData(const V2XDataList &msg_received_power_list); -}; \ No newline at end of file +}; From 52375d099b16d5e1f48ffa5176942c67998b7827 Mon Sep 17 00:00:00 2001 From: Daniel Grimm Date: Tue, 23 Apr 2024 14:39:18 +0200 Subject: [PATCH 13/99] add changelog --- CHANGELOG.md | 1 + 1 file changed, 1 insertion(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index 0475512ba..ed7c3b58c 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -14,6 +14,7 @@ * Added possibility to change gravity variable in imui sensor for the accelerometer * Fixed ROS2 native extension build error when ROS2 is installed in the system. * ROS2Native: Force fast-dds dependencies download to avoid build crash when boost_asio and tinyxml2 are not installed in Linux. + * Added V2X sensors for cooperative awareness message and custom user-defined messages to support vehicle-to-vehicle communication ## CARLA 0.9.15 From 780234b9a66aeabb987318a748506990748b2d2b Mon Sep 17 00:00:00 2001 From: Daniel Grimm Date: Tue, 23 Apr 2024 14:46:16 +0200 Subject: [PATCH 14/99] add EOF --- .../Plugins/Carla/Source/Carla/Sensor/CustomV2XSensor.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/CustomV2XSensor.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/CustomV2XSensor.h index 2b3557dad..ced0cc287 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/CustomV2XSensor.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/CustomV2XSensor.h @@ -70,4 +70,4 @@ private: bool mMessageDataChanged = false; constexpr static uint16_t data_size = sizeof(CustomV2XM_t::message); -}; \ No newline at end of file +}; From bace2f1aab3dcb729ee8ec2fe68f1fc568e87ce3 Mon Sep 17 00:00:00 2001 From: Daniel Grimm Date: Tue, 23 Apr 2024 15:41:54 +0200 Subject: [PATCH 15/99] comments and formatting --- LibCarla/source/carla/sensor/data/LibITS.h | 37 +- LibCarla/source/carla/sensor/data/V2XData.h | 17 +- LibCarla/source/carla/sensor/data/V2XEvent.h | 4 +- .../carla/source/libcarla/SensorData.cpp | 1 - PythonAPI/carla/source/libcarla/V2XData.cpp | 3 - PythonAPI/examples/V2XDemo.py | 1419 +++++++++++++++++ PythonAPI/examples/test_addsecondvx.py | 95 ++ .../Actor/ActorBlueprintFunctionLibrary.cpp | 2 - .../Source/Carla/Sensor/V2X/CaService.cpp | 612 ++++--- .../Carla/Source/Carla/Sensor/V2X/CaService.h | 73 +- .../Source/Carla/Sensor/V2X/PathLossModel.cpp | 14 +- .../Source/Carla/Sensor/V2X/PathLossModel.h | 142 +- .../Carla/Sensor/V2X/VehicleObstacle.cpp | 179 ++- .../Carla/Source/Carla/Sensor/V2XSensor.cpp | 9 +- .../Carla/Source/Carla/Sensor/V2XSensor.h | 42 +- 15 files changed, 2062 insertions(+), 587 deletions(-) create mode 100644 PythonAPI/examples/V2XDemo.py create mode 100644 PythonAPI/examples/test_addsecondvx.py diff --git a/LibCarla/source/carla/sensor/data/LibITS.h b/LibCarla/source/carla/sensor/data/LibITS.h index 6fbb32bd7..b3f419b6a 100644 --- a/LibCarla/source/carla/sensor/data/LibITS.h +++ b/LibCarla/source/carla/sensor/data/LibITS.h @@ -386,17 +386,6 @@ public: AccelerationControl_cruiseControlEngaged = 5, AccelerationControl_speedLimiterEngaged = 6 } e_AccelerationControl; - - /* BIT_STRING_s*/ - // struct BIT_STRING_s { - // // uint8_t *buf; /* BIT STRING body */ - // //note: we cant use pointers - // uint8_t buf; /* BIT STRING body */ - // int size; /* Size of the above buffer */ - - // int bits_unused;/* Unused trailing bits in the last octet (0..7) */ - - // }; /* AccelerationControl */ typedef uint8_t AccelerationControl_t; @@ -516,7 +505,6 @@ public: /* TimestampIts */ - // typedef BIT_STRING_s TimestampIts_t; typedef long TimestampIts_t; /* ProtectedZoneRadius Dependencies */ @@ -582,7 +570,6 @@ public: } e_ExteriorLights; /* ExteriorLights */ - // typedef BIT_STRING_s ExteriorLights_t; typedef uint8_t ExteriorLights_t; /* DeltaLatitude Dependencies */ typedef enum DeltaLatitude { @@ -718,15 +705,10 @@ public: /* HighFrequencyContainer */ typedef struct HighFrequencyContainer { - // HighFrequencyContainer() {}; - // HighFrequencyContainer(HighFrequencyContainer &hfc) {}; - // ~HighFrequencyContainer() {}; HighFrequencyContainer_PR present; - // union - // { - BasicVehicleContainerHighFrequency_t basicVehicleContainerHighFrequency; - RSUContainerHighFrequency_t rsuContainerHighFrequency; - // }; + + BasicVehicleContainerHighFrequency_t basicVehicleContainerHighFrequency; + RSUContainerHighFrequency_t rsuContainerHighFrequency; } HighFrequencyContainer_t; @@ -749,17 +731,10 @@ public: /* LowFrequencyContainer */ typedef struct LowFrequencyContainer { - // LowFrequencyContainer() {}; - // LowFrequencyContainer(LowFrequencyContainer &lfc) {}; - // ~LowFrequencyContainer() {}; LowFrequencyContainer_PR present; - // union - // { - BasicVehicleContainerLowFrequency_t basicVehicleContainerLowFrequency; + // Since only option is available + BasicVehicleContainerLowFrequency_t basicVehicleContainerLowFrequency; - // }; - //Since only option is available - // BasicVehicleContainerLowFrequency_t basicVehicleContainerLowFrequency; } LowFrequencyContainer_t; /* CamParameters */ @@ -768,7 +743,7 @@ public: BasicContainer_t basicContainer; HighFrequencyContainer_t highFrequencyContainer; LowFrequencyContainer_t lowFrequencyContainer; /* OPTIONAL */ - // SpecialVehicleContainer *specialVehicleContainer; /* OPTIONAL */ + // Optional TODO: SpecialVehicleContainer *specialVehicleContainer } CamParameters_t; /* CoopAwareness*/ diff --git a/LibCarla/source/carla/sensor/data/V2XData.h b/LibCarla/source/carla/sensor/data/V2XData.h index 18e23e4b1..4747b5ef8 100644 --- a/LibCarla/source/carla/sensor/data/V2XData.h +++ b/LibCarla/source/carla/sensor/data/V2XData.h @@ -1,4 +1,4 @@ -// Copyright (c) 2024 Institut fuer Technik der Informationsverarbeitung (ITIV) at the +// Copyright (c) 2024 Institut fuer Technik der Informationsverarbeitung (ITIV) at the // Karlsruhe Institute of Technology // // This work is licensed under the terms of the MIT license. @@ -45,19 +45,19 @@ namespace carla CAMDataS &operator=(CAMDataS &&) = default; - // /// Returns the number of current received messages. + // Returns the number of current received messages. size_t GetMessageCount() const { return MessageList.size(); } - /// Deletes the current messages. + // Deletes the current messages. void Reset() { MessageList.clear(); } - /// Adds a new detection. + // Adds a new detection. void WriteMessage(CAMData message) { MessageList.push_back(message); @@ -69,7 +69,6 @@ namespace carla friend class s11n::CAMDataSerializer; }; - class CustomV2XDataS { @@ -78,19 +77,19 @@ namespace carla CustomV2XDataS &operator=(CustomV2XDataS &&) = default; - // /// Returns the number of current received messages. + // Returns the number of current received messages. size_t GetMessageCount() const { return MessageList.size(); } - /// Deletes the current messages. + // Deletes the current messages. void Reset() { MessageList.clear(); } - /// Adds a new detection. + // Adds a new detection. void WriteMessage(CustomV2XData message) { MessageList.push_back(message); @@ -100,7 +99,7 @@ namespace carla std::vector MessageList; friend class s11n::CustomV2XDataSerializer; - }; + }; } // namespace s11n } // namespace sensor diff --git a/LibCarla/source/carla/sensor/data/V2XEvent.h b/LibCarla/source/carla/sensor/data/V2XEvent.h index 817630fe7..f146bffb1 100644 --- a/LibCarla/source/carla/sensor/data/V2XEvent.h +++ b/LibCarla/source/carla/sensor/data/V2XEvent.h @@ -1,4 +1,4 @@ -// Copyright (c) 2024 Institut fuer Technik der Informationsverarbeitung (ITIV) at the +// Copyright (c) 2024 Institut fuer Technik der Informationsverarbeitung (ITIV) at the // Karlsruhe Institute of Technology // // This work is licensed under the terms of the MIT license. @@ -54,7 +54,7 @@ namespace carla { return Super::size(); } - }; + }; } // namespace data } // namespace sensor diff --git a/PythonAPI/carla/source/libcarla/SensorData.cpp b/PythonAPI/carla/source/libcarla/SensorData.cpp index 73559acee..61c39ab15 100644 --- a/PythonAPI/carla/source/libcarla/SensorData.cpp +++ b/PythonAPI/carla/source/libcarla/SensorData.cpp @@ -197,7 +197,6 @@ namespace data { out << "CustomV2XData(power=" << std::to_string(data.Power) << ", stationId=" << std::to_string(data.Message.header.stationID) << ", messageId=" << std::to_string(data.Message.header.messageID) - // << ", message=" << data.Message.message << ')'; return out; } diff --git a/PythonAPI/carla/source/libcarla/V2XData.cpp b/PythonAPI/carla/source/libcarla/V2XData.cpp index 748e330a9..2be2198ce 100644 --- a/PythonAPI/carla/source/libcarla/V2XData.cpp +++ b/PythonAPI/carla/source/libcarla/V2XData.cpp @@ -267,7 +267,6 @@ static boost::python::dict GetBVCHighFrequency(const CAM_t message) HeadingValueConfidence["Value"] = bvchf.heading.headingValue; HeadingValueConfidence["Confidence"] = GetHeadingConfidenceString(bvchf.heading.headingConfidence); BVCHighFrequency["Heading"] = HeadingValueConfidence; - // ValueConfidence.clear(); boost::python::dict SpeedValueConfidence; SpeedValueConfidence["Value"] = bvchf.speed.speedValue; SpeedValueConfidence["Confidence"] = GetSpeedConfidenceString(bvchf.speed.speedConfidence); @@ -335,7 +334,6 @@ static boost::python::dict GetBVCHighFrequency(const CAM_t message) ValueConfidence["Value"] = bvchf.lateralAcceleration.lateralAccelerationValue; ValueConfidence["Confidence"] = GetAccelerationConfidenceString(bvchf.lateralAcceleration.lateralAccelerationConfidence); BVCHighFrequency["Lateral Acceleration"] = ValueConfidence; - // BVCHighFrequency["Lateral Acceleration"] = boost::python::object(); } else { @@ -423,7 +421,6 @@ static boost::python::dict GetHighFrequencyContainer(const CAM_t message) { boost::python::dict HFC; CAMContainer::HighFrequencyContainer_t hfc = message.cam.camParameters.highFrequencyContainer; - // HFC["High Frequency Container Present"] = GetHFCPresentString(hfc.present); switch (hfc.present) { case CAMContainer::HighFrequencyContainer_PR_basicVehicleContainerHighFrequency: diff --git a/PythonAPI/examples/V2XDemo.py b/PythonAPI/examples/V2XDemo.py new file mode 100644 index 000000000..eedfae968 --- /dev/null +++ b/PythonAPI/examples/V2XDemo.py @@ -0,0 +1,1419 @@ +#!/usr/bin/env python + +# Copyright (c) 2019 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 . + +# Allows controlling a vehicle with a keyboard. For a simpler and more +# documented example, please take a look at tutorial.py. + +""" +Welcome to CARLA manual control. + +Use ARROWS or WASD keys for control. + + W : throttle + S : brake + A/D : steer left/right + Q : toggle reverse + Space : hand-brake + P : toggle autopilot + M : toggle manual transmission + ,/. : gear up/down + CTRL + W : toggle constant velocity mode at 60 km/h + + L : toggle next light type + SHIFT + L : toggle high beam + Z/X : toggle right/left blinker + I : toggle interior light + + TAB : change sensor position + ` or N : next sensor + [1-9] : change to sensor [1-9] + G : toggle radar visualization + C : change weather (Shift+C reverse) + Backspace : change vehicle + + O : open/close all doors of vehicle + T : toggle vehicle's telemetry + + V : Select next map layer (Shift+V reverse) + B : Load current selected map layer (Shift+B to unload) + + R : toggle recording images to disk + + CTRL + R : toggle recording of simulation (replacing any previous) + CTRL + P : start replaying last recorded simulation + CTRL + + : increments the start time of the replay by 1 second (+SHIFT = 10 seconds) + CTRL + - : decrements the start time of the replay by 1 second (+SHIFT = 10 seconds) + + F1 : toggle HUD + H/? : toggle help + ESC : quit +""" + +from __future__ import print_function + + +# ============================================================================== +# -- find carla module --------------------------------------------------------- +# ============================================================================== + + +import glob +import os +import sys + +try: + sys.path.append(glob.glob('../carla/dist/carla-0.9.15-py*%d.%d-%s.egg' % ( + sys.version_info.major, + sys.version_info.minor, + 'win-amd64' if os.name == 'nt' else 'linux-x86_64'))[0]) +except IndexError: + pass + + +# ============================================================================== +# -- imports ------------------------------------------------------------------- +# ============================================================================== + + +import carla + +from carla import ColorConverter as cc + +import argparse +import collections +import datetime +import logging +import math +import random +import re +import weakref + +try: + import pygame + from pygame.locals import KMOD_CTRL + from pygame.locals import KMOD_SHIFT + from pygame.locals import K_0 + from pygame.locals import K_9 + from pygame.locals import K_BACKQUOTE + from pygame.locals import K_BACKSPACE + from pygame.locals import K_COMMA + from pygame.locals import K_DOWN + from pygame.locals import K_ESCAPE + from pygame.locals import K_F1 + from pygame.locals import K_LEFT + from pygame.locals import K_PERIOD + from pygame.locals import K_RIGHT + from pygame.locals import K_SLASH + from pygame.locals import K_SPACE + from pygame.locals import K_TAB + from pygame.locals import K_UP + from pygame.locals import K_a + from pygame.locals import K_b + from pygame.locals import K_c + from pygame.locals import K_d + from pygame.locals import K_f + from pygame.locals import K_g + from pygame.locals import K_h + from pygame.locals import K_i + from pygame.locals import K_l + from pygame.locals import K_m + from pygame.locals import K_n + from pygame.locals import K_o + from pygame.locals import K_p + from pygame.locals import K_q + from pygame.locals import K_r + from pygame.locals import K_s + from pygame.locals import K_t + from pygame.locals import K_v + from pygame.locals import K_w + from pygame.locals import K_x + from pygame.locals import K_z + from pygame.locals import K_MINUS + from pygame.locals import K_EQUALS +except ImportError: + raise RuntimeError('cannot import pygame, make sure pygame package is installed') + +try: + import numpy as np +except ImportError: + raise RuntimeError('cannot import numpy, make sure numpy package is installed') + + +# ============================================================================== +# -- Global functions ---------------------------------------------------------- +# ============================================================================== + + +def find_weather_presets(): + rgx = re.compile('.+?(?:(?<=[a-z])(?=[A-Z])|(?<=[A-Z])(?=[A-Z][a-z])|$)') + name = lambda x: ' '.join(m.group(0) for m in rgx.finditer(x)) + presets = [x for x in dir(carla.WeatherParameters) if re.match('[A-Z].+', x)] + return [(getattr(carla.WeatherParameters, x), name(x)) for x in presets] + + +def get_actor_display_name(actor, truncate=250): + name = ' '.join(actor.type_id.replace('_', '.').title().split('.')[1:]) + return (name[:truncate - 1] + u'\u2026') if len(name) > truncate else name + +def get_actor_blueprints(world, filter, generation): + bps = world.get_blueprint_library().filter(filter) + + if generation.lower() == "all": + return bps + + # If the filter returns only one bp, we assume that this one needed + # and therefore, we ignore the generation + if len(bps) == 1: + return bps + + try: + int_generation = int(generation) + # Check if generation is in available generations + if int_generation in [1, 2]: + bps = [x for x in bps if int(x.get_attribute('generation')) == int_generation] + return bps + else: + print(" Warning! Actor Generation is not valid. No actor will be spawned.") + return [] + except: + print(" Warning! Actor Generation is not valid. No actor will be spawned.") + return [] + + +# ============================================================================== +# -- World --------------------------------------------------------------------- +# ============================================================================== + + +class World(object): + def __init__(self, carla_world, hud, args): + self.world = carla_world + self.sync = args.sync + self.actor_role_name = args.rolename + try: + self.map = self.world.get_map() + except RuntimeError as error: + print('RuntimeError: {}'.format(error)) + print(' The server could not send the OpenDRIVE (.xodr) file:') + print(' Make sure it exists, has the same name of your town, and is correct.') + sys.exit(1) + self.hud = hud + self.player = None + self.collision_sensor = None + # self.lane_invasion_sensor = None + self.gnss_sensor = None + self.imu_sensor = None + self.v2x_sensor = None + self.radar_sensor = None + self.camera_manager = None + self._weather_presets = find_weather_presets() + self._weather_index = 0 + self._actor_filter = args.filter + self._actor_generation = args.generation + self._gamma = args.gamma + self.restart() + self.world.on_tick(hud.on_world_tick) + self.recording_enabled = False + self.recording_start = 0 + self.constant_velocity_enabled = False + self.show_vehicle_telemetry = False + self.doors_are_open = False + self.current_map_layer = 0 + self.map_layer_names = [ + carla.MapLayer.NONE, + carla.MapLayer.Buildings, + carla.MapLayer.Decals, + carla.MapLayer.Foliage, + carla.MapLayer.Ground, + carla.MapLayer.ParkedVehicles, + carla.MapLayer.Particles, + carla.MapLayer.Props, + carla.MapLayer.StreetLights, + carla.MapLayer.Walls, + carla.MapLayer.All + ] + + def restart(self): + self.player_max_speed = 1.589 + self.player_max_speed_fast = 3.713 + # Keep same camera config if the camera manager exists. + cam_index = self.camera_manager.index if self.camera_manager is not None else 0 + cam_pos_index = self.camera_manager.transform_index if self.camera_manager is not None else 0 + # Get a random blueprint. + blueprint = random.choice(get_actor_blueprints(self.world, self._actor_filter, self._actor_generation)) + blueprint.set_attribute('role_name', self.actor_role_name) + if blueprint.has_attribute('terramechanics'): + blueprint.set_attribute('terramechanics', 'true') + if blueprint.has_attribute('color'): + color = random.choice(blueprint.get_attribute('color').recommended_values) + blueprint.set_attribute('color', color) + if blueprint.has_attribute('driver_id'): + driver_id = random.choice(blueprint.get_attribute('driver_id').recommended_values) + blueprint.set_attribute('driver_id', driver_id) + if blueprint.has_attribute('is_invincible'): + blueprint.set_attribute('is_invincible', 'true') + # set the max speed + if blueprint.has_attribute('speed'): + self.player_max_speed = float(blueprint.get_attribute('speed').recommended_values[1]) + self.player_max_speed_fast = float(blueprint.get_attribute('speed').recommended_values[2]) + + # Spawn the player. + if self.player is not None: + spawn_point = self.player.get_transform() + spawn_point.location.z += 2.0 + spawn_point.rotation.roll = 0.0 + spawn_point.rotation.pitch = 0.0 + self.destroy() + self.player = self.world.try_spawn_actor(blueprint, spawn_point) + self.show_vehicle_telemetry = False + self.modify_vehicle_physics(self.player) + while self.player is None: + if not self.map.get_spawn_points(): + print('There are no spawn points available in your map/town.') + print('Please add some Vehicle Spawn Point to your UE4 scene.') + sys.exit(1) + spawn_points = self.map.get_spawn_points() + spawn_point = random.choice(spawn_points) if spawn_points else carla.Transform() + self.player = self.world.try_spawn_actor(blueprint, spawn_point) + self.show_vehicle_telemetry = False + self.modify_vehicle_physics(self.player) + # Set up the sensors. + self.collision_sensor = CollisionSensor(self.player, self.hud) + #self.lane_invasion_sensor = LaneInvasionSensor(self.player, self.hud) + self.gnss_sensor = GnssSensor(self.player) + self.imu_sensor = IMUSensor(self.player) + self.v2x_sensor = V2XSensor(self.player, self.hud) + self.camera_manager = CameraManager(self.player, self.hud, self._gamma) + self.camera_manager.transform_index = cam_pos_index + self.camera_manager.set_sensor(cam_index, notify=False) + actor_type = get_actor_display_name(self.player) + self.hud.notification(actor_type) + + if self.sync: + self.world.tick() + else: + self.world.wait_for_tick() + + def next_weather(self, reverse=False): + self._weather_index += -1 if reverse else 1 + self._weather_index %= len(self._weather_presets) + preset = self._weather_presets[self._weather_index] + self.hud.notification('Weather: %s' % preset[1]) + self.player.get_world().set_weather(preset[0]) + + def next_map_layer(self, reverse=False): + self.current_map_layer += -1 if reverse else 1 + self.current_map_layer %= len(self.map_layer_names) + selected = self.map_layer_names[self.current_map_layer] + self.hud.notification('LayerMap selected: %s' % selected) + + def load_map_layer(self, unload=False): + selected = self.map_layer_names[self.current_map_layer] + if unload: + self.hud.notification('Unloading map layer: %s' % selected) + self.world.unload_map_layer(selected) + else: + self.hud.notification('Loading map layer: %s' % selected) + self.world.load_map_layer(selected) + + def toggle_radar(self): + if self.radar_sensor is None: + self.radar_sensor = RadarSensor(self.player) + elif self.radar_sensor.sensor is not None: + self.radar_sensor.sensor.destroy() + self.radar_sensor = None + + def modify_vehicle_physics(self, actor): + #If actor is not a vehicle, we cannot use the physics control + try: + physics_control = actor.get_physics_control() + physics_control.use_sweep_wheel_collision = True + actor.apply_physics_control(physics_control) + except Exception: + pass + + def tick(self, clock): + self.hud.tick(self, clock) + + def render(self, display): + self.camera_manager.render(display) + self.hud.render(display) + + def destroy_sensors(self): + self.camera_manager.sensor.destroy() + self.camera_manager.sensor = None + self.camera_manager.index = None + + def destroy(self): + if self.radar_sensor is not None: + self.toggle_radar() + sensors = [ + self.camera_manager.sensor, + self.collision_sensor.sensor, + # self.lane_invasion_sensor.sensor, + self.gnss_sensor.sensor, + self.imu_sensor.sensor, + self.v2x_sensor.sensor] + for sensor in sensors: + if sensor is not None: + sensor.stop() + sensor.destroy() + if self.player is not None: + self.player.destroy() + + +# ============================================================================== +# -- KeyboardControl ----------------------------------------------------------- +# ============================================================================== + + +class KeyboardControl(object): + """Class that handles keyboard input.""" + def __init__(self, world, start_in_autopilot): + self._autopilot_enabled = start_in_autopilot + self._ackermann_enabled = False + self._ackermann_reverse = 1 + if isinstance(world.player, carla.Vehicle): + self._control = carla.VehicleControl() + self._ackermann_control = carla.VehicleAckermannControl() + self._lights = carla.VehicleLightState.NONE + world.player.set_autopilot(self._autopilot_enabled) + world.player.set_light_state(self._lights) + elif isinstance(world.player, carla.Walker): + self._control = carla.WalkerControl() + self._autopilot_enabled = False + self._rotation = world.player.get_transform().rotation + else: + raise NotImplementedError("Actor type not supported") + self._steer_cache = 0.0 + world.hud.notification("Press 'H' or '?' for help.", seconds=4.0) + + def parse_events(self, client, world, clock, sync_mode): + if isinstance(self._control, carla.VehicleControl): + current_lights = self._lights + for event in pygame.event.get(): + if event.type == pygame.QUIT: + return True + elif event.type == pygame.KEYUP: + if self._is_quit_shortcut(event.key): + return True + elif event.key == K_BACKSPACE: + if self._autopilot_enabled: + world.player.set_autopilot(False) + world.restart() + world.player.set_autopilot(True) + else: + world.restart() + elif event.key == K_F1: + world.hud.toggle_info() + elif event.key == K_v and pygame.key.get_mods() & KMOD_SHIFT: + world.next_map_layer(reverse=True) + elif event.key == K_v: + world.next_map_layer() + elif event.key == K_b and pygame.key.get_mods() & KMOD_SHIFT: + world.load_map_layer(unload=True) + elif event.key == K_b: + world.load_map_layer() + elif event.key == K_h or (event.key == K_SLASH and pygame.key.get_mods() & KMOD_SHIFT): + world.hud.help.toggle() + elif event.key == K_TAB: + world.camera_manager.toggle_camera() + elif event.key == K_c and pygame.key.get_mods() & KMOD_SHIFT: + world.next_weather(reverse=True) + elif event.key == K_c: + world.next_weather() + elif event.key == K_g: + world.toggle_radar() + elif event.key == K_BACKQUOTE: + world.camera_manager.next_sensor() + elif event.key == K_n: + world.camera_manager.next_sensor() + elif event.key == K_w and (pygame.key.get_mods() & KMOD_CTRL): + if world.constant_velocity_enabled: + world.player.disable_constant_velocity() + world.constant_velocity_enabled = False + world.hud.notification("Disabled Constant Velocity Mode") + else: + world.player.enable_constant_velocity(carla.Vector3D(17, 0, 0)) + world.constant_velocity_enabled = True + world.hud.notification("Enabled Constant Velocity Mode at 60 km/h") + elif event.key == K_o: + try: + if world.doors_are_open: + world.hud.notification("Closing Doors") + world.doors_are_open = False + world.player.close_door(carla.VehicleDoor.All) + else: + world.hud.notification("Opening doors") + world.doors_are_open = True + world.player.open_door(carla.VehicleDoor.All) + except Exception: + pass + elif event.key == K_t: + if world.show_vehicle_telemetry: + world.player.show_debug_telemetry(False) + world.show_vehicle_telemetry = False + world.hud.notification("Disabled Vehicle Telemetry") + else: + try: + world.player.show_debug_telemetry(True) + world.show_vehicle_telemetry = True + world.hud.notification("Enabled Vehicle Telemetry") + except Exception: + pass + elif event.key > K_0 and event.key <= K_9: + index_ctrl = 0 + if pygame.key.get_mods() & KMOD_CTRL: + index_ctrl = 9 + world.camera_manager.set_sensor(event.key - 1 - K_0 + index_ctrl) + elif event.key == K_r and not (pygame.key.get_mods() & KMOD_CTRL): + world.camera_manager.toggle_recording() + elif event.key == K_r and (pygame.key.get_mods() & KMOD_CTRL): + if (world.recording_enabled): + client.stop_recorder() + world.recording_enabled = False + world.hud.notification("Recorder is OFF") + else: + client.start_recorder("manual_recording.rec") + world.recording_enabled = True + world.hud.notification("Recorder is ON") + elif event.key == K_p and (pygame.key.get_mods() & KMOD_CTRL): + # stop recorder + client.stop_recorder() + world.recording_enabled = False + # work around to fix camera at start of replaying + current_index = world.camera_manager.index + world.destroy_sensors() + # disable autopilot + self._autopilot_enabled = False + world.player.set_autopilot(self._autopilot_enabled) + world.hud.notification("Replaying file 'manual_recording.rec'") + # replayer + client.replay_file("manual_recording.rec", world.recording_start, 0, 0) + world.camera_manager.set_sensor(current_index) + elif event.key == K_MINUS and (pygame.key.get_mods() & KMOD_CTRL): + if pygame.key.get_mods() & KMOD_SHIFT: + world.recording_start -= 10 + else: + world.recording_start -= 1 + world.hud.notification("Recording start time is %d" % (world.recording_start)) + elif event.key == K_EQUALS and (pygame.key.get_mods() & KMOD_CTRL): + if pygame.key.get_mods() & KMOD_SHIFT: + world.recording_start += 10 + else: + world.recording_start += 1 + world.hud.notification("Recording start time is %d" % (world.recording_start)) + if isinstance(self._control, carla.VehicleControl): + if event.key == K_f: + # Toggle ackermann controller + self._ackermann_enabled = not self._ackermann_enabled + world.hud.show_ackermann_info(self._ackermann_enabled) + world.hud.notification("Ackermann Controller %s" % + ("Enabled" if self._ackermann_enabled else "Disabled")) + if event.key == K_q: + if not self._ackermann_enabled: + self._control.gear = 1 if self._control.reverse else -1 + else: + self._ackermann_reverse *= -1 + # Reset ackermann control + self._ackermann_control = carla.VehicleAckermannControl() + elif event.key == K_m: + self._control.manual_gear_shift = not self._control.manual_gear_shift + self._control.gear = world.player.get_control().gear + world.hud.notification('%s Transmission' % + ('Manual' if self._control.manual_gear_shift else 'Automatic')) + elif self._control.manual_gear_shift and event.key == K_COMMA: + self._control.gear = max(-1, self._control.gear - 1) + elif self._control.manual_gear_shift and event.key == K_PERIOD: + self._control.gear = self._control.gear + 1 + elif event.key == K_p and not pygame.key.get_mods() & KMOD_CTRL: + if not self._autopilot_enabled and not sync_mode: + print("WARNING: You are currently in asynchronous mode and could " + "experience some issues with the traffic simulation") + self._autopilot_enabled = not self._autopilot_enabled + world.player.set_autopilot(self._autopilot_enabled) + world.hud.notification( + 'Autopilot %s' % ('On' if self._autopilot_enabled else 'Off')) + elif event.key == K_l and pygame.key.get_mods() & KMOD_CTRL: + current_lights ^= carla.VehicleLightState.Special1 + elif event.key == K_l and pygame.key.get_mods() & KMOD_SHIFT: + current_lights ^= carla.VehicleLightState.HighBeam + elif event.key == K_l: + # Use 'L' key to switch between lights: + # closed -> position -> low beam -> fog + if not self._lights & carla.VehicleLightState.Position: + world.hud.notification("Position lights") + current_lights |= carla.VehicleLightState.Position + else: + world.hud.notification("Low beam lights") + current_lights |= carla.VehicleLightState.LowBeam + if self._lights & carla.VehicleLightState.LowBeam: + world.hud.notification("Fog lights") + current_lights |= carla.VehicleLightState.Fog + if self._lights & carla.VehicleLightState.Fog: + world.hud.notification("Lights off") + current_lights ^= carla.VehicleLightState.Position + current_lights ^= carla.VehicleLightState.LowBeam + current_lights ^= carla.VehicleLightState.Fog + elif event.key == K_i: + current_lights ^= carla.VehicleLightState.Interior + elif event.key == K_z: + current_lights ^= carla.VehicleLightState.LeftBlinker + elif event.key == K_x: + current_lights ^= carla.VehicleLightState.RightBlinker + + if not self._autopilot_enabled: + if isinstance(self._control, carla.VehicleControl): + self._parse_vehicle_keys(pygame.key.get_pressed(), clock.get_time()) + self._control.reverse = self._control.gear < 0 + # Set automatic control-related vehicle lights + if self._control.brake: + current_lights |= carla.VehicleLightState.Brake + else: # Remove the Brake flag + current_lights &= ~carla.VehicleLightState.Brake + if self._control.reverse: + current_lights |= carla.VehicleLightState.Reverse + else: # Remove the Reverse flag + current_lights &= ~carla.VehicleLightState.Reverse + if current_lights != self._lights: # Change the light state only if necessary + self._lights = current_lights + world.player.set_light_state(carla.VehicleLightState(self._lights)) + # Apply control + if not self._ackermann_enabled: + world.player.apply_control(self._control) + else: + world.player.apply_ackermann_control(self._ackermann_control) + # Update control to the last one applied by the ackermann controller. + self._control = world.player.get_control() + # Update hud with the newest ackermann control + world.hud.update_ackermann_control(self._ackermann_control) + + elif isinstance(self._control, carla.WalkerControl): + self._parse_walker_keys(pygame.key.get_pressed(), clock.get_time(), world) + world.player.apply_control(self._control) + + def _parse_vehicle_keys(self, keys, milliseconds): + if keys[K_UP] or keys[K_w]: + if not self._ackermann_enabled: + self._control.throttle = min(self._control.throttle + 0.01, 1.00) + else: + self._ackermann_control.speed += round(milliseconds * 0.005, 2) * self._ackermann_reverse + else: + if not self._ackermann_enabled: + self._control.throttle = 0.0 + + if keys[K_DOWN] or keys[K_s]: + if not self._ackermann_enabled: + self._control.brake = min(self._control.brake + 0.2, 1) + else: + self._ackermann_control.speed -= min(abs(self._ackermann_control.speed), round(milliseconds * 0.005, 2)) * self._ackermann_reverse + self._ackermann_control.speed = max(0, abs(self._ackermann_control.speed)) * self._ackermann_reverse + else: + if not self._ackermann_enabled: + self._control.brake = 0 + + steer_increment = 5e-4 * milliseconds + if keys[K_LEFT] or keys[K_a]: + if self._steer_cache > 0: + self._steer_cache = 0 + else: + self._steer_cache -= steer_increment + elif keys[K_RIGHT] or keys[K_d]: + if self._steer_cache < 0: + self._steer_cache = 0 + else: + self._steer_cache += steer_increment + else: + self._steer_cache = 0.0 + self._steer_cache = min(0.7, max(-0.7, self._steer_cache)) + if not self._ackermann_enabled: + self._control.steer = round(self._steer_cache, 1) + self._control.hand_brake = keys[K_SPACE] + else: + self._ackermann_control.steer = round(self._steer_cache, 1) + + def _parse_walker_keys(self, keys, milliseconds, world): + self._control.speed = 0.0 + if keys[K_DOWN] or keys[K_s]: + self._control.speed = 0.0 + if keys[K_LEFT] or keys[K_a]: + self._control.speed = .01 + self._rotation.yaw -= 0.08 * milliseconds + if keys[K_RIGHT] or keys[K_d]: + self._control.speed = .01 + self._rotation.yaw += 0.08 * milliseconds + if keys[K_UP] or keys[K_w]: + self._control.speed = world.player_max_speed_fast if pygame.key.get_mods() & KMOD_SHIFT else world.player_max_speed + self._control.jump = keys[K_SPACE] + self._rotation.yaw = round(self._rotation.yaw, 1) + self._control.direction = self._rotation.get_forward_vector() + + @staticmethod + def _is_quit_shortcut(key): + return (key == K_ESCAPE) or (key == K_q and pygame.key.get_mods() & KMOD_CTRL) + + +# ============================================================================== +# -- HUD ----------------------------------------------------------------------- +# ============================================================================== + + +class HUD(object): + def __init__(self, width, height): + self.dim = (width, height) + font = pygame.font.Font(pygame.font.get_default_font(), 20) + font_name = 'courier' if os.name == 'nt' else 'mono' + fonts = [x for x in pygame.font.get_fonts() if font_name in x] + default_font = 'ubuntumono' + mono = default_font if default_font in fonts else fonts[0] + mono = pygame.font.match_font(mono) + self._font_mono = pygame.font.Font(mono, 12 if os.name == 'nt' else 14) + self._notifications = FadingText(font, (width, 40), (0, height - 40)) + self.help = HelpText(pygame.font.Font(mono, 16), width, height) + self.server_fps = 0 + self.frame = 0 + self.simulation_time = 0 + self._show_info = True + self._info_text = [] + self._server_clock = pygame.time.Clock() + + self._show_ackermann_info = False + self._ackermann_control = carla.VehicleAckermannControl() + + def on_world_tick(self, timestamp): + self._server_clock.tick() + self.server_fps = self._server_clock.get_fps() + self.frame = timestamp.frame + self.simulation_time = timestamp.elapsed_seconds + + def tick(self, world, clock): + self._notifications.tick(world, clock) + if not self._show_info: + return + t = world.player.get_transform() + v = world.player.get_velocity() + c = world.player.get_control() + compass = world.imu_sensor.compass + heading = 'N' if compass > 270.5 or compass < 89.5 else '' + heading += 'S' if 90.5 < compass < 269.5 else '' + heading += 'E' if 0.5 < compass < 179.5 else '' + heading += 'W' if 180.5 < compass < 359.5 else '' + colhist = world.collision_sensor.get_collision_history() + collision = [colhist[x + self.frame - 200] for x in range(0, 200)] + max_col = max(1.0, max(collision)) + collision = [x / max_col for x in collision] + vehicles = world.world.get_actors().filter('vehicle.*') + self._info_text = [ + 'Server: % 16.0f FPS' % self.server_fps, + 'Client: % 16.0f FPS' % clock.get_fps(), + '', + 'Vehicle: % 20s' % get_actor_display_name(world.player, truncate=20), + 'Map: % 20s' % world.map.name.split('/')[-1], + 'Simulation time: % 12s' % datetime.timedelta(seconds=int(self.simulation_time)), + '', + 'Speed: % 15.0f km/h' % (3.6 * math.sqrt(v.x**2 + v.y**2 + v.z**2)), + u'Compass:% 17.0f\N{DEGREE SIGN} % 2s' % (compass, heading), + 'Accelero: (%5.1f,%5.1f,%5.1f)' % (world.imu_sensor.accelerometer), + 'Gyroscop: (%5.1f,%5.1f,%5.1f)' % (world.imu_sensor.gyroscope), + 'Location:% 20s' % ('(% 5.1f, % 5.1f)' % (t.location.x, t.location.y)), + 'GNSS:% 24s' % ('(% 2.6f, % 3.6f)' % (world.gnss_sensor.lat, world.gnss_sensor.lon)), + 'Height: % 18.0f m' % t.location.z, + ''] + if isinstance(c, carla.VehicleControl): + self._info_text += [ + ('Throttle:', c.throttle, 0.0, 1.0), + ('Steer:', c.steer, -1.0, 1.0), + ('Brake:', c.brake, 0.0, 1.0), + ('Reverse:', c.reverse), + ('Hand brake:', c.hand_brake), + ('Manual:', c.manual_gear_shift), + 'Gear: %s' % {-1: 'R', 0: 'N'}.get(c.gear, c.gear)] + if self._show_ackermann_info: + self._info_text += [ + '', + 'Ackermann Controller:', + ' Target speed: % 8.0f km/h' % (3.6*self._ackermann_control.speed), + ] + elif isinstance(c, carla.WalkerControl): + self._info_text += [ + ('Speed:', c.speed, 0.0, 5.556), + ('Jump:', c.jump)] + self._info_text += [ + '', + 'Collision:', + collision, + '', + 'Number of vehicles: % 8d' % len(vehicles)] + if len(vehicles) > 1: + self._info_text += ['Nearby vehicles:'] + distance = lambda l: math.sqrt((l.x - t.location.x)**2 + (l.y - t.location.y)**2 + (l.z - t.location.z)**2) + vehicles = [(distance(x.get_location()), x) for x in vehicles if x.id != world.player.id] + for d, vehicle in sorted(vehicles, key=lambda vehicles: vehicles[0]): + if d > 200.0: + break + vehicle_type = get_actor_display_name(vehicle, truncate=22) + self._info_text.append('% 4dm %s' % (d, vehicle_type)) + + def show_ackermann_info(self, enabled): + self._show_ackermann_info = enabled + + def update_ackermann_control(self, ackermann_control): + self._ackermann_control = ackermann_control + + def toggle_info(self): + self._show_info = not self._show_info + + def notification(self, text, seconds=2.0): + self._notifications.set_text(text, seconds=seconds) + + def error(self, text): + self._notifications.set_text('Error: %s' % text, (255, 0, 0)) + + def render(self, display): + if self._show_info: + info_surface = pygame.Surface((220, self.dim[1])) + info_surface.set_alpha(100) + display.blit(info_surface, (0, 0)) + v_offset = 4 + bar_h_offset = 100 + bar_width = 106 + for item in self._info_text: + if v_offset + 18 > self.dim[1]: + break + if isinstance(item, list): + if len(item) > 1: + points = [(x + 8, v_offset + 8 + (1.0 - y) * 30) for x, y in enumerate(item)] + pygame.draw.lines(display, (255, 136, 0), False, points, 2) + item = None + v_offset += 18 + elif isinstance(item, tuple): + if isinstance(item[1], bool): + rect = pygame.Rect((bar_h_offset, v_offset + 8), (6, 6)) + pygame.draw.rect(display, (255, 255, 255), rect, 0 if item[1] else 1) + else: + rect_border = pygame.Rect((bar_h_offset, v_offset + 8), (bar_width, 6)) + pygame.draw.rect(display, (255, 255, 255), rect_border, 1) + f = (item[1] - item[2]) / (item[3] - item[2]) + if item[2] < 0.0: + rect = pygame.Rect((bar_h_offset + f * (bar_width - 6), v_offset + 8), (6, 6)) + else: + rect = pygame.Rect((bar_h_offset, v_offset + 8), (f * bar_width, 6)) + pygame.draw.rect(display, (255, 255, 255), rect) + item = item[0] + if item: # At this point has to be a str. + surface = self._font_mono.render(item, True, (255, 255, 255)) + display.blit(surface, (8, v_offset)) + v_offset += 18 + self._notifications.render(display) + self.help.render(display) + + +# ============================================================================== +# -- FadingText ---------------------------------------------------------------- +# ============================================================================== + + +class FadingText(object): + def __init__(self, font, dim, pos): + self.font = font + self.dim = dim + self.pos = pos + self.seconds_left = 0 + self.surface = pygame.Surface(self.dim) + + def set_text(self, text, color=(255, 255, 255), seconds=2.0): + text_texture = self.font.render(text, True, color) + self.surface = pygame.Surface(self.dim) + self.seconds_left = seconds + self.surface.fill((0, 0, 0, 0)) + self.surface.blit(text_texture, (10, 11)) + + def tick(self, _, clock): + delta_seconds = 1e-3 * clock.get_time() + self.seconds_left = max(0.0, self.seconds_left - delta_seconds) + self.surface.set_alpha(500.0 * self.seconds_left) + + def render(self, display): + display.blit(self.surface, self.pos) + + +# ============================================================================== +# -- HelpText ------------------------------------------------------------------ +# ============================================================================== + + +class HelpText(object): + """Helper class to handle text output using pygame""" + def __init__(self, font, width, height): + lines = __doc__.split('\n') + self.font = font + self.line_space = 18 + self.dim = (780, len(lines) * self.line_space + 12) + self.pos = (0.5 * width - 0.5 * self.dim[0], 0.5 * height - 0.5 * self.dim[1]) + self.seconds_left = 0 + self.surface = pygame.Surface(self.dim) + self.surface.fill((0, 0, 0, 0)) + for n, line in enumerate(lines): + text_texture = self.font.render(line, True, (255, 255, 255)) + self.surface.blit(text_texture, (22, n * self.line_space)) + self._render = False + self.surface.set_alpha(220) + + def toggle(self): + self._render = not self._render + + def render(self, display): + if self._render: + display.blit(self.surface, self.pos) + + +# ============================================================================== +# -- CollisionSensor ----------------------------------------------------------- +# ============================================================================== + + +class CollisionSensor(object): + def __init__(self, parent_actor, hud): + self.sensor = None + self.history = [] + self._parent = parent_actor + self.hud = hud + world = self._parent.get_world() + bp = world.get_blueprint_library().find('sensor.other.collision') + self.sensor = world.spawn_actor(bp, carla.Transform(), attach_to=self._parent) + # We need to pass the lambda a weak reference to self to avoid circular + # reference. + weak_self = weakref.ref(self) + self.sensor.listen(lambda event: CollisionSensor._on_collision(weak_self, event)) + + def get_collision_history(self): + history = collections.defaultdict(int) + for frame, intensity in self.history: + history[frame] += intensity + return history + + @staticmethod + def _on_collision(weak_self, event): + self = weak_self() + if not self: + return + actor_type = get_actor_display_name(event.other_actor) + self.hud.notification('Collision with %r' % actor_type) + impulse = event.normal_impulse + intensity = math.sqrt(impulse.x**2 + impulse.y**2 + impulse.z**2) + self.history.append((event.frame, intensity)) + if len(self.history) > 4000: + self.history.pop(0) + + +# ============================================================================== +# -- LaneInvasionSensor -------------------------------------------------------- +# ============================================================================== + + +class LaneInvasionSensor(object): + def __init__(self, parent_actor, hud): + self.sensor = None + + # If the spawn object is not a vehicle, we cannot use the Lane Invasion Sensor + if parent_actor.type_id.startswith("vehicle."): + self._parent = parent_actor + self.hud = hud + world = self._parent.get_world() + bp = world.get_blueprint_library().find('sensor.other.lane_invasion') + self.sensor = world.spawn_actor(bp, carla.Transform(), attach_to=self._parent) + # We need to pass the lambda a weak reference to self to avoid circular + # reference. + weak_self = weakref.ref(self) + self.sensor.listen(lambda event: LaneInvasionSensor._on_invasion(weak_self, event)) + + @staticmethod + def _on_invasion(weak_self, event): + self = weak_self() + if not self: + return + lane_types = set(x.type for x in event.crossed_lane_markings) + text = ['%r' % str(x).split()[-1] for x in lane_types] + self.hud.notification('Crossed line %s' % ' and '.join(text)) + + +# ============================================================================== +# -- GnssSensor ---------------------------------------------------------------- +# ============================================================================== + + +class GnssSensor(object): + def __init__(self, parent_actor): + self.sensor = None + self._parent = parent_actor + self.lat = 0.0 + self.lon = 0.0 + world = self._parent.get_world() + bp = world.get_blueprint_library().find('sensor.other.gnss') + self.sensor = world.spawn_actor(bp, carla.Transform(carla.Location(x=1.0, z=2.8)), attach_to=self._parent) + # We need to pass the lambda a weak reference to self to avoid circular + # reference. + weak_self = weakref.ref(self) + self.sensor.listen(lambda event: GnssSensor._on_gnss_event(weak_self, event)) + + @staticmethod + def _on_gnss_event(weak_self, event): + self = weak_self() + if not self: + return + self.lat = event.latitude + self.lon = event.longitude + + +# ============================================================================== +# -- IMUSensor ----------------------------------------------------------------- +# ============================================================================== + + +class IMUSensor(object): + def __init__(self, parent_actor): + self.sensor = None + self._parent = parent_actor + self.accelerometer = (0.0, 0.0, 0.0) + self.gyroscope = (0.0, 0.0, 0.0) + self.compass = 0.0 + world = self._parent.get_world() + bp = world.get_blueprint_library().find('sensor.other.imu') + self.sensor = world.spawn_actor( + bp, carla.Transform(), attach_to=self._parent) + # We need to pass the lambda a weak reference to self to avoid circular + # reference. + weak_self = weakref.ref(self) + self.sensor.listen( + lambda sensor_data: IMUSensor._IMU_callback(weak_self, sensor_data)) + + @staticmethod + def _IMU_callback(weak_self, sensor_data): + self = weak_self() + if not self: + return + limits = (-99.9, 99.9) + self.accelerometer = ( + max(limits[0], min(limits[1], sensor_data.accelerometer.x)), + max(limits[0], min(limits[1], sensor_data.accelerometer.y)), + max(limits[0], min(limits[1], sensor_data.accelerometer.z))) + self.gyroscope = ( + max(limits[0], min(limits[1], math.degrees(sensor_data.gyroscope.x))), + max(limits[0], min(limits[1], math.degrees(sensor_data.gyroscope.y))), + max(limits[0], min(limits[1], math.degrees(sensor_data.gyroscope.z)))) + self.compass = math.degrees(sensor_data.compass) + +# ============================================================================== +# -- V2XSensor ----------------------------------------------------------------- +# ============================================================================== + + +class V2XSensor(object): + def __init__(self, parent_actor, hud): + self.sensor = None + self._parent = parent_actor + world = self._parent.get_world() + #bp = world.get_blueprint_library().find('sensor.other.v2x_custom') + bp = world.get_blueprint_library().find('sensor.other.v2x') + bp.set_attribute("path_loss_model", "geometric") + self.hud = hud + self.sensor = world.spawn_actor( + bp, carla.Transform(), attach_to=self._parent) + # We need to pass the lambda a weak reference to self to avoid circular + # reference. + weak_self = weakref.ref(self) + self.sensor.listen( + lambda sensor_data: V2XSensor._V2X_callback(weak_self, sensor_data)) + + @staticmethod + def _V2X_callback(weak_self, sensor_data): + self = weak_self() + if not self: + return + print(sensor_data.get_message_count()) + for data in sensor_data: + msg = data.get() + # stationId = msg["Header"]["Station ID"] + power = data.power + print(msg) + # self.hud.notification('Cam message received from %s ' % stationId) + self.hud.notification('Cam message received with power %f ' % power) +# ============================================================================== +# -- RadarSensor --------------------------------------------------------------- +# ============================================================================== + + +class RadarSensor(object): + def __init__(self, parent_actor): + self.sensor = None + self._parent = parent_actor + bound_x = 0.5 + self._parent.bounding_box.extent.x + bound_y = 0.5 + self._parent.bounding_box.extent.y + bound_z = 0.5 + self._parent.bounding_box.extent.z + + self.velocity_range = 7.5 # m/s + world = self._parent.get_world() + self.debug = world.debug + bp = world.get_blueprint_library().find('sensor.other.radar') + bp.set_attribute('horizontal_fov', str(35)) + bp.set_attribute('vertical_fov', str(20)) + self.sensor = world.spawn_actor( + bp, + carla.Transform( + carla.Location(x=bound_x + 0.05, z=bound_z+0.05), + carla.Rotation(pitch=5)), + attach_to=self._parent) + # We need a weak reference to self to avoid circular reference. + weak_self = weakref.ref(self) + self.sensor.listen( + lambda radar_data: RadarSensor._Radar_callback(weak_self, radar_data)) + + @staticmethod + def _Radar_callback(weak_self, radar_data): + self = weak_self() + if not self: + return + # To get a numpy [[vel, altitude, azimuth, depth],...[,,,]]: + # points = np.frombuffer(radar_data.raw_data, dtype=np.dtype('f4')) + # points = np.reshape(points, (len(radar_data), 4)) + + current_rot = radar_data.transform.rotation + for detect in radar_data: + azi = math.degrees(detect.azimuth) + alt = math.degrees(detect.altitude) + # The 0.25 adjusts a bit the distance so the dots can + # be properly seen + fw_vec = carla.Vector3D(x=detect.depth - 0.25) + carla.Transform( + carla.Location(), + carla.Rotation( + pitch=current_rot.pitch + alt, + yaw=current_rot.yaw + azi, + roll=current_rot.roll)).transform(fw_vec) + + def clamp(min_v, max_v, value): + return max(min_v, min(value, max_v)) + + norm_velocity = detect.velocity / self.velocity_range # range [-1, 1] + r = int(clamp(0.0, 1.0, 1.0 - norm_velocity) * 255.0) + g = int(clamp(0.0, 1.0, 1.0 - abs(norm_velocity)) * 255.0) + b = int(abs(clamp(- 1.0, 0.0, - 1.0 - norm_velocity)) * 255.0) + self.debug.draw_point( + radar_data.transform.location + fw_vec, + size=0.075, + life_time=0.06, + persistent_lines=False, + color=carla.Color(r, g, b)) + +# ============================================================================== +# -- CameraManager ------------------------------------------------------------- +# ============================================================================== + + +class CameraManager(object): + def __init__(self, parent_actor, hud, gamma_correction): + self.sensor = None + self.surface = None + self._parent = parent_actor + self.hud = hud + self.recording = False + bound_x = 0.5 + self._parent.bounding_box.extent.x + bound_y = 0.5 + self._parent.bounding_box.extent.y + bound_z = 0.5 + self._parent.bounding_box.extent.z + Attachment = carla.AttachmentType + + if not self._parent.type_id.startswith("walker.pedestrian"): + self._camera_transforms = [ + (carla.Transform(carla.Location(x=-2.0*bound_x, y=+0.0*bound_y, z=2.0*bound_z), carla.Rotation(pitch=8.0)), Attachment.SpringArmGhost), + (carla.Transform(carla.Location(x=+0.8*bound_x, y=+0.0*bound_y, z=1.3*bound_z)), Attachment.Rigid), + (carla.Transform(carla.Location(x=+1.9*bound_x, y=+1.0*bound_y, z=1.2*bound_z)), Attachment.SpringArmGhost), + (carla.Transform(carla.Location(x=-2.8*bound_x, y=+0.0*bound_y, z=4.6*bound_z), carla.Rotation(pitch=6.0)), Attachment.SpringArmGhost), + (carla.Transform(carla.Location(x=-1.0, y=-1.0*bound_y, z=0.4*bound_z)), Attachment.Rigid)] + else: + self._camera_transforms = [ + (carla.Transform(carla.Location(x=-2.5, z=0.0), carla.Rotation(pitch=-8.0)), Attachment.SpringArmGhost), + (carla.Transform(carla.Location(x=1.6, z=1.7)), Attachment.Rigid), + (carla.Transform(carla.Location(x=2.5, y=0.5, z=0.0), carla.Rotation(pitch=-8.0)), Attachment.SpringArmGhost), + (carla.Transform(carla.Location(x=-4.0, z=2.0), carla.Rotation(pitch=6.0)), Attachment.SpringArmGhost), + (carla.Transform(carla.Location(x=0, y=-2.5, z=-0.0), carla.Rotation(yaw=90.0)), Attachment.Rigid)] + + self.transform_index = 1 + self.sensors = [ + ['sensor.camera.rgb', cc.Raw, 'Camera RGB', {}], + ['sensor.camera.depth', cc.Raw, 'Camera Depth (Raw)', {}], + ['sensor.camera.depth', cc.Depth, 'Camera Depth (Gray Scale)', {}], + ['sensor.camera.depth', cc.LogarithmicDepth, 'Camera Depth (Logarithmic Gray Scale)', {}], + ['sensor.camera.semantic_segmentation', cc.Raw, 'Camera Semantic Segmentation (Raw)', {}], + ['sensor.camera.semantic_segmentation', cc.CityScapesPalette, 'Camera Semantic Segmentation (CityScapes Palette)', {}], + ['sensor.camera.instance_segmentation', cc.CityScapesPalette, 'Camera Instance Segmentation (CityScapes Palette)', {}], + ['sensor.camera.instance_segmentation', cc.Raw, 'Camera Instance Segmentation (Raw)', {}], + # ['sensor.other.v2x', None, 'Lidar (Ray-Cast)', {'range': '50'}], + ['sensor.camera.dvs', cc.Raw, 'Dynamic Vision Sensor', {}], + ['sensor.camera.rgb', cc.Raw, 'Camera RGB Distorted', + {'lens_circle_multiplier': '3.0', + 'lens_circle_falloff': '3.0', + 'chromatic_aberration_intensity': '0.5', + 'chromatic_aberration_offset': '0'}], + ['sensor.camera.optical_flow', cc.Raw, 'Optical Flow', {}], + ['sensor.camera.normals', cc.Raw, 'Camera Normals', {}], + ] + world = self._parent.get_world() + bp_library = world.get_blueprint_library() + for item in self.sensors: + bp = bp_library.find(item[0]) + if item[0].startswith('sensor.camera'): + bp.set_attribute('image_size_x', str(hud.dim[0])) + bp.set_attribute('image_size_y', str(hud.dim[1])) + if bp.has_attribute('gamma'): + bp.set_attribute('gamma', str(gamma_correction)) + for attr_name, attr_value in item[3].items(): + bp.set_attribute(attr_name, attr_value) + elif item[0].startswith('sensor.lidar'): + self.lidar_range = 50 + + for attr_name, attr_value in item[3].items(): + bp.set_attribute(attr_name, attr_value) + if attr_name == 'range': + self.lidar_range = float(attr_value) + + item.append(bp) + self.index = None + + def toggle_camera(self): + self.transform_index = (self.transform_index + 1) % len(self._camera_transforms) + self.set_sensor(self.index, notify=False, force_respawn=True) + + def set_sensor(self, index, notify=True, force_respawn=False): + index = index % len(self.sensors) + needs_respawn = True if self.index is None else \ + (force_respawn or (self.sensors[index][2] != self.sensors[self.index][2])) + if needs_respawn: + if self.sensor is not None: + self.sensor.destroy() + self.surface = None + self.sensor = self._parent.get_world().spawn_actor( + self.sensors[index][-1], + self._camera_transforms[self.transform_index][0], + attach_to=self._parent, + attachment_type=self._camera_transforms[self.transform_index][1]) + # We need to pass the lambda a weak reference to self to avoid + # circular reference. + weak_self = weakref.ref(self) + self.sensor.listen(lambda image: CameraManager._parse_image(weak_self, image)) + if notify: + self.hud.notification(self.sensors[index][2]) + self.index = index + + def next_sensor(self): + self.set_sensor(self.index + 1) + + def toggle_recording(self): + self.recording = not self.recording + self.hud.notification('Recording %s' % ('On' if self.recording else 'Off')) + + def render(self, display): + if self.surface is not None: + display.blit(self.surface, (0, 0)) + + @staticmethod + def _parse_image(weak_self, image): + self = weak_self() + if not self: + return + if self.sensors[self.index][0].startswith('sensor.lidar'): + points = np.frombuffer(image.raw_data, dtype=np.dtype('f4')) + points = np.reshape(points, (int(points.shape[0] / 4), 4)) + lidar_data = np.array(points[:, :2]) + lidar_data *= min(self.hud.dim) / (2.0 * self.lidar_range) + lidar_data += (0.5 * self.hud.dim[0], 0.5 * self.hud.dim[1]) + lidar_data = np.fabs(lidar_data) # pylint: disable=E1111 + lidar_data = lidar_data.astype(np.int32) + lidar_data = np.reshape(lidar_data, (-1, 2)) + lidar_img_size = (self.hud.dim[0], self.hud.dim[1], 3) + lidar_img = np.zeros((lidar_img_size), dtype=np.uint8) + lidar_img[tuple(lidar_data.T)] = (255, 255, 255) + self.surface = pygame.surfarray.make_surface(lidar_img) + elif self.sensors[self.index][0].startswith('sensor.camera.dvs'): + # Example of converting the raw_data from a carla.DVSEventArray + # sensor into a NumPy array and using it as an image + dvs_events = np.frombuffer(image.raw_data, dtype=np.dtype([ + ('x', np.uint16), ('y', np.uint16), ('t', np.int64), ('pol', np.bool)])) + dvs_img = np.zeros((image.height, image.width, 3), dtype=np.uint8) + # Blue is positive, red is negative + dvs_img[dvs_events[:]['y'], dvs_events[:]['x'], dvs_events[:]['pol'] * 2] = 255 + self.surface = pygame.surfarray.make_surface(dvs_img.swapaxes(0, 1)) + elif self.sensors[self.index][0].startswith('sensor.camera.optical_flow'): + image = image.get_color_coded_flow() + array = np.frombuffer(image.raw_data, dtype=np.dtype("uint8")) + array = np.reshape(array, (image.height, image.width, 4)) + array = array[:, :, :3] + array = array[:, :, ::-1] + self.surface = pygame.surfarray.make_surface(array.swapaxes(0, 1)) + else: + image.convert(self.sensors[self.index][1]) + array = np.frombuffer(image.raw_data, dtype=np.dtype("uint8")) + array = np.reshape(array, (image.height, image.width, 4)) + array = array[:, :, :3] + array = array[:, :, ::-1] + self.surface = pygame.surfarray.make_surface(array.swapaxes(0, 1)) + if self.recording: + image.save_to_disk('_out/%08d' % image.frame) + + +# ============================================================================== +# -- game_loop() --------------------------------------------------------------- +# ============================================================================== + + +def game_loop(args): + pygame.init() + pygame.font.init() + world = None + original_settings = None + + try: + client = carla.Client(args.host, args.port) + client.set_timeout(2000.0) + + sim_world = client.get_world() + if args.sync: + original_settings = sim_world.get_settings() + settings = sim_world.get_settings() + if not settings.synchronous_mode: + settings.synchronous_mode = True + settings.fixed_delta_seconds = 0.05 + sim_world.apply_settings(settings) + + traffic_manager = client.get_trafficmanager() + traffic_manager.set_synchronous_mode(True) + + if args.autopilot and not sim_world.get_settings().synchronous_mode: + print("WARNING: You are currently in asynchronous mode and could " + "experience some issues with the traffic simulation") + + display = pygame.display.set_mode( + (args.width, args.height), + pygame.HWSURFACE | pygame.DOUBLEBUF) + display.fill((0,0,0)) + pygame.display.flip() + # monitors = get_monitors() + # resolutions = [(monitor.name, monitor.width, monitor.height) for monitor in monitors] + # return resolutions + hud = HUD(args.width, args.height) + world = World(sim_world, hud, args) + controller = KeyboardControl(world, args.autopilot) + + if args.sync: + sim_world.tick() + else: + sim_world.wait_for_tick() + + clock = pygame.time.Clock() + while True: + if args.sync: + sim_world.tick() + clock.tick_busy_loop(60) + if controller.parse_events(client, world, clock, args.sync): + return + world.tick(clock) + world.render(display) + pygame.display.flip() + + finally: + + if original_settings: + sim_world.apply_settings(original_settings) + + if (world and world.recording_enabled): + client.stop_recorder() + + if world is not None: + world.destroy() + + pygame.quit() + + +# ============================================================================== +# -- main() -------------------------------------------------------------------- +# ============================================================================== + + +def main(): + argparser = argparse.ArgumentParser( + description='CARLA Manual Control Client') + argparser.add_argument( + '-v', '--verbose', + action='store_true', + dest='debug', + help='print debug information') + argparser.add_argument( + '--host', + metavar='H', + default='127.0.0.1', + help='IP of the host server (default: 127.0.0.1)') + argparser.add_argument( + '-p', '--port', + metavar='P', + default=2000, + type=int, + help='TCP port to listen to (default: 2000)') + argparser.add_argument( + '-a', '--autopilot', + action='store_true', + help='enable autopilot') + argparser.add_argument( + '--res', + metavar='WIDTHxHEIGHT', + default='1280x720', + help='window resolution (default: 1280x720)') + argparser.add_argument( + '--filter', + metavar='PATTERN', + default='vehicle.*', + help='actor filter (default: "vehicle.*")') + argparser.add_argument( + '--generation', + metavar='G', + default='2', + help='restrict to certain actor generation (values: "1","2","All" - default: "2")') + argparser.add_argument( + '--rolename', + metavar='NAME', + default='hero', + help='actor role name (default: "hero")') + argparser.add_argument( + '--gamma', + default=2.2, + type=float, + help='Gamma correction of the camera (default: 2.2)') + argparser.add_argument( + '--sync', + action='store_true', + help='Activate synchronous mode execution') + args = argparser.parse_args() + + args.width, args.height = [int(x) for x in args.res.split('x')] + + log_level = logging.DEBUG if args.debug else logging.INFO + logging.basicConfig(format='%(levelname)s: %(message)s', level=log_level) + + logging.info('listening to server %s:%s', args.host, args.port) + + print(__doc__) + + try: + + game_loop(args) + + except KeyboardInterrupt: + print('\nCancelled by user. Bye!') + + +if __name__ == '__main__': + + main() diff --git a/PythonAPI/examples/test_addsecondvx.py b/PythonAPI/examples/test_addsecondvx.py new file mode 100644 index 000000000..367508b14 --- /dev/null +++ b/PythonAPI/examples/test_addsecondvx.py @@ -0,0 +1,95 @@ +import glob +import os +import sys + +try: + sys.path.append(glob.glob('../carla/dist/carla-0.9.15-py*%d.%d-%s.egg' % ( + sys.version_info.major, + sys.version_info.minor, + 'win-amd64' if os.name == 'nt' else 'linux-x86_64'))[0]) +except IndexError: + pass + +import carla +import random +import weakref + +def get_actor_blueprints(world, filter, generation): + bps = world.get_blueprint_library().filter(filter) + + if generation.lower() == "all": + return bps + + # If the filter returns only one bp, we assume that this one needed + # and therefore, we ignore the generation + if len(bps) == 1: + return bps + + try: + int_generation = int(generation) + # Check if generation is in available generations + if int_generation in [1, 2]: + bps = [x for x in bps if int(x.get_attribute('generation')) == int_generation] + return bps + else: + print(" Warning! Actor Generation is not valid. No actor will be spawned.") + return [] + except: + print(" Warning! Actor Generation is not valid. No actor will be spawned.") + return [] + +class V2XSensor(object): + def __init__(self, parent_actor): + self.sensor = None + self._parent = parent_actor + world = self._parent.get_world() + #bp = world.get_blueprint_library().find('sensor.other.v2x_custom') + bp = world.get_blueprint_library().find('sensor.other.v2x') + self.sensor = world.spawn_actor( + bp, carla.Transform(), attach_to=self._parent) + # We need to pass the lambda a weak reference to self to avoid circular + # reference. + weak_self = weakref.ref(self) + self.sensor.listen( + lambda sensor_data: V2XSensor._V2X_callback(weak_self, sensor_data)) + + def destroy(self): + self.sensor.stop() + self.sensor.destroy() + + @staticmethod + def _V2X_callback(weak_self, sensor_data): + self = weak_self() + if not self: + return + for data in sensor_data: + msg = data.get() + # stationId = msg["Header"]["Station ID"] + power = data.power + print(msg) + # print('Cam message received from %s ' % stationId) + print('Cam message received with power %f ' % power) + +client = carla.Client("localhost",2000) +client.set_timeout(2000.0) + +world = client.get_world() +smap = world.get_map() +# acl = world.get_actor(28) +# acl.send("test") + + +spawn_points = smap.get_spawn_points() +spawn_point = random.choice(spawn_points) if spawn_points else carla.Transform() +blueprint = random.choice(get_actor_blueprints(world, "vehicle.*", "2")) +blueprint.set_attribute('role_name', "test") +player = world.try_spawn_actor(blueprint, spawn_point) +v2x_sensor = V2XSensor(player) + +world.wait_for_tick() +try: + while True: + world.wait_for_tick() +finally: + v2x_sensor.destroy() + player.destroy() \ No newline at end of file diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp index 4899c7e29..2de3050a2 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp @@ -1029,7 +1029,6 @@ void UActorBlueprintFunctionLibrary::MakeV2XDefinition( FActorDefinition &Definition) { FillIdAndTags(Definition, TEXT("sensor"), TEXT("other"), TEXT("v2x")); - // AddRecommendedValuesForSensorRoleNames(Definition); AddVariationsForSensor(Definition); // - Noise seed -------------------------------- @@ -1263,7 +1262,6 @@ void UActorBlueprintFunctionLibrary::MakeCustomV2XDefinition( FActorDefinition &Definition) { FillIdAndTags(Definition, TEXT("sensor"), TEXT("other"), TEXT("v2x_custom")); - // AddRecommendedValuesForSensorRoleNames(Definition); AddVariationsForSensor(Definition); // - Noise seed -------------------------------- diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/CaService.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/CaService.cpp index 99d552a43..0c4ea10ef 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/CaService.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/CaService.cpp @@ -1,4 +1,4 @@ -// Copyright (c) 2024 Institut fuer Technik der Informationsverarbeitung (ITIV) at the +// Copyright (c) 2024 Institut fuer Technik der Informationsverarbeitung (ITIV) at the // Karlsruhe Institute of Technology // // This work is licensed under the terms of the MIT license. @@ -12,42 +12,43 @@ #include static const float scLowFrequencyContainerInterval = 0.5; - ITSContainer::SpeedValue_t CaService::buildSpeedValue(const float vel) { - static const float lower = 0.0; // meter_per_second - static const float upper = 163.82; //meter_per_second + static const float lower = 0.0; // meter_per_second + static const float upper = 163.82; // meter_per_second - ITSContainer::SpeedValue_t speed = ITSContainer::SpeedValue_unavailable; - if (vel >= upper) { - speed = 16382; // see CDD A.74 (TS 102 894 v1.2.1) - } else if (vel >= lower) { - //to cm per second - speed = std::round(vel * 100.0) * ITSContainer::SpeedValue_oneCentimeterPerSec; - } - return speed; + ITSContainer::SpeedValue_t speed = ITSContainer::SpeedValue_unavailable; + if (vel >= upper) + { + speed = 16382; // see CDD A.74 (TS 102 894 v1.2.1) + } + else if (vel >= lower) + { + // to cm per second + speed = std::round(vel * 100.0) * ITSContainer::SpeedValue_oneCentimeterPerSec; + } + return speed; } -CaService::CaService(URandomEngine* random_engine) +CaService::CaService(URandomEngine *random_engine) { mRandomEngine = random_engine; // The starting point now std::chrono::system_clock::time_point start_Point = std::chrono::system_clock::now(); - //the reference point for ETSI (2004-01-01T00:00:00:000Z) + // the reference point for ETSI (2004-01-01T00:00:00:000Z) std::chrono::system_clock::time_point ref_point = std::chrono::system_clock::from_time_t(1072915200); // Unix time for 2004-01-01 - mGenerationDelta0 = std::chrono::duration_cast(start_Point - ref_point); + mGenerationDelta0 = std::chrono::duration_cast(start_Point - ref_point); } - -void CaService::SetOwner(UWorld* world, AActor *Owner) +void CaService::SetOwner(UWorld *world, AActor *Owner) { UE_LOG(LogCarla, Warning, TEXT("CaService:SetOwner function called")); mWorld = world; mCarlaEpisode = UCarlaStatics::GetCurrentEpisode(world); CurrentGeoReference = mCarlaEpisode->GetGeoReference(); - + mActorOwner = Owner; mCarlaEpisode = UCarlaStatics::GetCurrentEpisode(mWorld); mCarlaActor = mCarlaEpisode->FindCarlaActor(Owner); @@ -56,16 +57,15 @@ void CaService::SetOwner(UWorld* world, AActor *Owner) { mVehicle = Cast(Owner); - if(mCarlaActor->GetActorType() == FCarlaActor::ActorType::Vehicle) + if (mCarlaActor->GetActorType() == FCarlaActor::ActorType::Vehicle) { UE_LOG(LogCarla, Warning, TEXT("CaService:Initialize Vehicle type")); - + mLastCamTimeStamp = mCarlaEpisode->GetElapsedGameTime() - mGenCamMax; mLastLowCamTimeStamp = mCarlaEpisode->GetElapsedGameTime() - scLowFrequencyContainerInterval; - //Can add logic for this later + // Can add logic for this later mDccRestriction = false; - mElapsedTime = 0; VehicleSpeed = 0; VehiclePosition = {0, 0, 0}; @@ -73,10 +73,9 @@ void CaService::SetOwner(UWorld* world, AActor *Owner) mLastCamSpeed = 0; mLastCamPosition = {0, 0, 0}; mLastCamHeading = {0, 0, 0}; - } - else if((mCarlaActor->GetActorType() == FCarlaActor::ActorType::TrafficLight)|| - (mCarlaActor->GetActorType() == FCarlaActor::ActorType::TrafficSign)) + else if ((mCarlaActor->GetActorType() == FCarlaActor::ActorType::TrafficLight) || + (mCarlaActor->GetActorType() == FCarlaActor::ActorType::TrafficSign)) { mGenerationInterval = 0.5; mLastCamTimeStamp = -mGenerationInterval; @@ -85,36 +84,32 @@ void CaService::SetOwner(UWorld* world, AActor *Owner) mStationId = static_cast(mCarlaActor->GetActorId()); mStationType = GetStationType(); - } - } - void CaService::SetParams(const float GenCamMin, const float GenCamMax, const bool FixedRate) { UE_LOG(LogCarla, Warning, TEXT("CaService:SetParams function called")); - //Max and Min for generation rate + // Max and Min for generation rate - mGenCamMin = GenCamMin; //in second - mGenCamMax = GenCamMax; //in second + mGenCamMin = GenCamMin; // in second + mGenCamMax = GenCamMax; // in second mGenCam = mGenCamMax; - //If we want set a fix interval make this as true + // If we want set a fix interval make this as true mFixedRate = FixedRate; - } /* -* Function to check trigger condition for RSU -*/ + * Function to check trigger condition for RSU + */ bool CaService::Trigger(float DeltaSeconds) { - + mElapsedTime = mCarlaEpisode->GetElapsedGameTime(); bool Trigger = false; - if(mStationType == ITSContainer::StationType_roadSideUnit) + if (mStationType == ITSContainer::StationType_roadSideUnit) { - if (mElapsedTime - mLastCamTimeStamp >= mGenerationInterval) + if (mElapsedTime - mLastCamTimeStamp >= mGenerationInterval) { Trigger = true; mCAMMessage = CreateCooperativeAwarenessMessage(DeltaSeconds); @@ -124,24 +119,22 @@ bool CaService::Trigger(float DeltaSeconds) else { Trigger = CheckTriggeringConditions(DeltaSeconds); - } return Trigger; - } /* -* Function to provide CAM message to other objects if necessary -*/ + * Function to provide CAM message to other objects if necessary + */ CAM_t CaService::GetCamMessage() { return mCAMMessage; } /* -* Check the trigger condition in case of vehicles and if trigger is true request -* to generate CAM message -*/ + * Check the trigger condition in case of vehicles and if trigger is true request + * to generate CAM message + */ bool CaService::CheckTriggeringConditions(float DeltaSeconds) { float &T_GenCam = mGenCam; @@ -149,10 +142,10 @@ bool CaService::CheckTriggeringConditions(float DeltaSeconds) const float T_GenCamMax = mGenCamMax; const float T_GenCamDcc = mDccRestriction ? 0 : T_GenCamMin; const float T_elapsed = mElapsedTime - mLastCamTimeStamp; - if(T_elapsed >= T_GenCamDcc) + if (T_elapsed >= T_GenCamDcc) { - //If message need to be generated every sim tick then set this to true. - if(mFixedRate) + // If message need to be generated every sim tick then set this to true. + if (mFixedRate) { GenerateCamMessage(DeltaSeconds); return true; @@ -162,15 +155,16 @@ bool CaService::CheckTriggeringConditions(float DeltaSeconds) { GenerateCamMessage(DeltaSeconds); T_GenCam = std::min(T_elapsed, T_GenCamMax); - mGenCamLowDynamicsCounter = 0; + mGenCamLowDynamicsCounter = 0; return true; } else if (T_elapsed >= T_GenCam) { GenerateCamMessage(DeltaSeconds); - if (++mGenCamLowDynamicsCounter >= mGenCamLowDynamicsLimit) { - T_GenCam = T_GenCamMax; - } + if (++mGenCamLowDynamicsCounter >= mGenCamLowDynamicsLimit) + { + T_GenCam = T_GenCamMax; + } return true; } } @@ -179,10 +173,10 @@ bool CaService::CheckTriggeringConditions(float DeltaSeconds) bool CaService::CheckPositionDelta(float DeltaSeconds) { - //If position change is more the 4m + // If position change is more the 4m VehiclePosition = mVehicle->GetActorLocation(); - double Distance = FVector::Distance(VehiclePosition, mLastCamPosition) / 100.0f; //From cm to m - if(Distance > 4.0f) + double Distance = FVector::Distance(VehiclePosition, mLastCamPosition) / 100.0f; // From cm to m + if (Distance > 4.0f) { return true; } @@ -194,8 +188,8 @@ bool CaService::CheckSpeedDelta(float DeltaSeconds) VehicleSpeed = mVehicle->GetVehicleForwardSpeed() / 100.0f; // From cm/s to m/s float DeltaSpeed = std::abs(VehicleSpeed - mLastCamSpeed); - //Speed differance is greater than 0.5m/s - if(DeltaSpeed > 0.5) + // Speed differance is greater than 0.5m/s + if (DeltaSpeed > 0.5) { return true; } @@ -204,7 +198,7 @@ bool CaService::CheckSpeedDelta(float DeltaSeconds) } double CaService::GetFVectorAngle(const FVector &a, const FVector &b) -{ +{ double Dot = a.X * b.X + a.Y * b.Y + a.Z * b.Z; return std::acos(Dot / (a.Size() * b.Size())); } @@ -218,108 +212,106 @@ void CaService::GenerateCamMessage(float DeltaTime) mLastCamTimeStamp = mElapsedTime; } -//Function to get the station type +// Function to get the station type ITSContainer::StationType_t CaService::GetStationType() { check(mActorOwner != nullptr); mCarlaEpisode = UCarlaStatics::GetCurrentEpisode(mWorld); mCarlaActor = mCarlaEpisode->FindCarlaActor(mActorOwner); ITSContainer::StationType_t stationType = ITSContainer::StationType_unknown; - //return unknown if carla actor is gone - if(mCarlaActor == nullptr) + // return unknown if carla actor is gone + if (mCarlaActor == nullptr) { return static_cast(stationType); } auto Tag = ATagger::GetTagOfTaggedComponent(*mVehicle->GetMesh()); - - switch(Tag){ - case crp::CityObjectLabel::None: - stationType = ITSContainer::StationType_unknown; - break; - case crp::CityObjectLabel::Pedestrians: - stationType = ITSContainer::StationType_pedestrian; - break; - case crp::CityObjectLabel::Bicycle: - stationType = ITSContainer::StationType_cyclist; - break; - case crp::CityObjectLabel::Motorcycle: - stationType = ITSContainer::StationType_motorcycle; - break; - case crp::CityObjectLabel::Car: - stationType = ITSContainer::StationType_passengerCar; - break; - case crp::CityObjectLabel::Bus: - stationType = ITSContainer::StationType_bus; - break; - //TODO Modify this in future is CARLA adds difference truck - case crp::CityObjectLabel::Truck: - stationType = ITSContainer::StationType_lightTruck; - break; - case crp::CityObjectLabel::Buildings: - case crp::CityObjectLabel::Walls: - case crp::CityObjectLabel::Fences: - case crp::CityObjectLabel::Poles: - case crp::CityObjectLabel::TrafficLight: - case crp::CityObjectLabel::TrafficSigns: - stationType = ITSContainer::StationType_roadSideUnit; - break; - case crp::CityObjectLabel::Train: - stationType = ITSContainer::StationType_tram; - break; - default: - stationType = ITSContainer::StationType_unknown; + + switch (Tag) + { + case crp::CityObjectLabel::None: + stationType = ITSContainer::StationType_unknown; + break; + case crp::CityObjectLabel::Pedestrians: + stationType = ITSContainer::StationType_pedestrian; + break; + case crp::CityObjectLabel::Bicycle: + stationType = ITSContainer::StationType_cyclist; + break; + case crp::CityObjectLabel::Motorcycle: + stationType = ITSContainer::StationType_motorcycle; + break; + case crp::CityObjectLabel::Car: + stationType = ITSContainer::StationType_passengerCar; + break; + case crp::CityObjectLabel::Bus: + stationType = ITSContainer::StationType_bus; + break; + // TODO Modify this in future is CARLA adds difference truck + case crp::CityObjectLabel::Truck: + stationType = ITSContainer::StationType_lightTruck; + break; + case crp::CityObjectLabel::Buildings: + case crp::CityObjectLabel::Walls: + case crp::CityObjectLabel::Fences: + case crp::CityObjectLabel::Poles: + case crp::CityObjectLabel::TrafficLight: + case crp::CityObjectLabel::TrafficSigns: + stationType = ITSContainer::StationType_roadSideUnit; + break; + case crp::CityObjectLabel::Train: + stationType = ITSContainer::StationType_tram; + break; + default: + stationType = ITSContainer::StationType_unknown; } - //Can improve this later for different special vehicles once carla implements it + // Can improve this later for different special vehicles once carla implements it FCarlaActor::ActorType Type = mCarlaActor->GetActorType(); if (Type == FCarlaActor::ActorType::Vehicle) { - if(mCarlaActor->GetActorInfo()->Description.Variations.Contains("special_type")) + if (mCarlaActor->GetActorInfo()->Description.Variations.Contains("special_type")) { std::string special_type = carla::rpc::FromFString(*mCarlaActor->GetActorInfo()->Description.Variations["special_type"].Value); - if(special_type.compare("emergency") == 0 ) + if (special_type.compare("emergency") == 0) { stationType = ITSContainer::StationType_specialVehicles; } } - } return static_cast(stationType); } FVector CaService::GetReferencePosition() { - FVector RefPos; - carla::geom::Location ActorLocation = mActorOwner->GetActorLocation(); - ALargeMapManager * LargeMap = UCarlaStatics::GetLargeMapManager(mWorld); - if (LargeMap) - { - ActorLocation = LargeMap->LocalToGlobalLocation(ActorLocation); - } - carla::geom::Location Location = ActorLocation; - carla::geom::GeoLocation CurrentLocation = CurrentGeoReference.Transform(Location); + FVector RefPos; + carla::geom::Location ActorLocation = mActorOwner->GetActorLocation(); + ALargeMapManager *LargeMap = UCarlaStatics::GetLargeMapManager(mWorld); + if (LargeMap) + { + ActorLocation = LargeMap->LocalToGlobalLocation(ActorLocation); + } + carla::geom::Location Location = ActorLocation; + carla::geom::GeoLocation CurrentLocation = CurrentGeoReference.Transform(Location); - // Compute the noise for the sensor - const float LatError = mRandomEngine->GetNormalDistribution(0.0f, LatitudeDeviation); - const float LonError = mRandomEngine->GetNormalDistribution(0.0f, LongitudeDeviation); - const float AltError = mRandomEngine->GetNormalDistribution(0.0f, AltitudeDeviation); + // Compute the noise for the sensor + const float LatError = mRandomEngine->GetNormalDistribution(0.0f, LatitudeDeviation); + const float LonError = mRandomEngine->GetNormalDistribution(0.0f, LongitudeDeviation); + const float AltError = mRandomEngine->GetNormalDistribution(0.0f, AltitudeDeviation); - // Apply the noise to the sensor - double Latitude = CurrentLocation.latitude + LatitudeBias + LatError; - double Longitude = CurrentLocation.longitude + LongitudeBias + LonError; - double Altitude = CurrentLocation.altitude + AltitudeBias + AltError; - - RefPos.X = Latitude; - RefPos.Y = Longitude; - RefPos.Z = Altitude; - return RefPos; + // Apply the noise to the sensor + double Latitude = CurrentLocation.latitude + LatitudeBias + LatError; + double Longitude = CurrentLocation.longitude + LongitudeBias + LonError; + double Altitude = CurrentLocation.altitude + AltitudeBias + AltError; + RefPos.X = Latitude; + RefPos.Y = Longitude; + RefPos.Z = Altitude; + return RefPos; } - float CaService::GetHeading() { - // Magnetometer: orientation with respect to the North in rad + // Magnetometer: orientation with respect to the North in rad const FVector CarlaNorthVector = FVector(0.0f, -1.0f, 0.0f); const FVector ForwVect = mActorOwner->GetActorForwardVector().GetSafeNormal2D(); const float DotProd = FVector::DotProduct(CarlaNorthVector, ForwVect); @@ -337,33 +329,33 @@ float CaService::GetHeading() // Compute the noise for the sensor const float HeadingError = mRandomEngine->GetNormalDistribution(0.0f, HeadingDeviation); - - //add errors + + // add errors return HeadingDegree + HeadingBias + HeadingError; } -//Function to get the vehicle role +// Function to get the vehicle role long CaService::GetVehicleRole() { - long VehicleRole = ITSContainer::VehicleRole_default; + long VehicleRole = ITSContainer::VehicleRole_default; long StationType = GetStationType(); switch (StationType) { - case ITSContainer::StationType_cyclist: - case ITSContainer::StationType_moped: - case ITSContainer::StationType_motorcycle: - VehicleRole = ITSContainer::VehicleRole_default; - break; - case ITSContainer::StationType_bus: - case ITSContainer::StationType_tram: - VehicleRole = ITSContainer::VehicleRole_publicTransport; - break; - case ITSContainer::StationType_specialVehicles: - VehicleRole = ITSContainer::VehicleRole_emergency; - break; - default: - VehicleRole = ITSContainer::VehicleRole_default; - break; + case ITSContainer::StationType_cyclist: + case ITSContainer::StationType_moped: + case ITSContainer::StationType_motorcycle: + VehicleRole = ITSContainer::VehicleRole_default; + break; + case ITSContainer::StationType_bus: + case ITSContainer::StationType_tram: + VehicleRole = ITSContainer::VehicleRole_publicTransport; + break; + case ITSContainer::StationType_specialVehicles: + VehicleRole = ITSContainer::VehicleRole_emergency; + break; + default: + VehicleRole = ITSContainer::VehicleRole_default; + break; } return VehicleRole; } @@ -380,33 +372,31 @@ CAM_t CaService::CreateCooperativeAwarenessMessage(float DeltaTime) void CaService::CreateITSPduHeader(CAM_t &message) { - ITSContainer::ItsPduHeader_t& header = message.header; + ITSContainer::ItsPduHeader_t &header = message.header; header.protocolVersion = mProtocolVersion; header.messageID = mMessageId; header.stationID = mStationId; } -void CaService::AddCooperativeAwarenessMessage(CAMContainer::CoopAwareness_t& CoopAwarenessMessage, float DeltaTime) +void CaService::AddCooperativeAwarenessMessage(CAMContainer::CoopAwareness_t &CoopAwarenessMessage, float DeltaTime) { /* GenerationDeltaTime */ auto genDeltaTime = mGenerationDelta0 + std::chrono::milliseconds(static_cast(mCarlaEpisode->GetElapsedGameTime() * 1000)); - CoopAwarenessMessage.generationDeltaTime = genDeltaTime.count() % 65536 * CAMContainer::GenerationDeltaTime_oneMilliSec; //TODOCheck this logic + CoopAwarenessMessage.generationDeltaTime = genDeltaTime.count() % 65536 * CAMContainer::GenerationDeltaTime_oneMilliSec; // TODOCheck this logic AddBasicContainer(CoopAwarenessMessage.camParameters.basicContainer); - if(CoopAwarenessMessage.camParameters.basicContainer.stationType == ITSContainer::StationType_roadSideUnit) + if (CoopAwarenessMessage.camParameters.basicContainer.stationType == ITSContainer::StationType_roadSideUnit) { - //TODO Future Implementation + // TODO Future Implementation AddRSUContainerHighFrequency(CoopAwarenessMessage.camParameters.highFrequencyContainer); - } - else if(CoopAwarenessMessage.camParameters.basicContainer.stationType == ITSContainer::StationType_pedestrian) + else if (CoopAwarenessMessage.camParameters.basicContainer.stationType == ITSContainer::StationType_pedestrian) { - //TODO no container available for Pedestrains - + // TODO no container available for Pedestrains } else { - //BasicVehicleContainer + // BasicVehicleContainer AddBasicVehicleContainerHighFrequency(CoopAwarenessMessage.camParameters.highFrequencyContainer, DeltaTime); if (mElapsedTime - mLastLowCamTimeStamp >= scLowFrequencyContainerInterval) @@ -416,21 +406,18 @@ void CaService::AddCooperativeAwarenessMessage(CAMContainer::CoopAwareness_t& Co } else { - //Store nothing if not used + // Store nothing if not used CoopAwarenessMessage.camParameters.lowFrequencyContainer.present = CAMContainer::LowFrequencyContainer_PR_NOTHING; } /* - *TODO Add Special container if it a special vehicle - */ - + *TODO Add Special container if it a special vehicle + */ } - - } void CaService::AddBasicContainer(CAMContainer::BasicContainer_t &BasicContainer) { - BasicContainer.stationType = mStationType; + BasicContainer.stationType = mStationType; /* CamParameters ReferencePosition */ FVector RefPos = GetReferencePosition(); @@ -448,15 +435,14 @@ void CaService::SetAccelerationStandardDeviation(const FVector &Vec) StdDevAccel = Vec; } - void CaService::SetGNSSDeviation(const float noise_lat_stddev, - const float noise_lon_stddev, - const float noise_alt_stddev, - const float noise_head_stddev, - const float noise_lat_bias, - const float noise_lon_bias, - const float noise_alt_bias, - const float noise_head_bias) + const float noise_lon_stddev, + const float noise_alt_stddev, + const float noise_head_stddev, + const float noise_lat_bias, + const float noise_lon_bias, + const float noise_alt_bias, + const float noise_head_bias) { LatitudeDeviation = noise_lat_stddev; LongitudeDeviation = noise_lon_stddev; @@ -468,86 +454,93 @@ void CaService::SetGNSSDeviation(const float noise_lat_stddev, HeadingBias = noise_head_bias; } - - void CaService::SetVelDeviation(const float noise_vel_stddev_x) - { +void CaService::SetVelDeviation(const float noise_vel_stddev_x) +{ VelocityDeviation = noise_vel_stddev_x; - } +} - void CaService::SetYawrateDeviation(const float noise_yawrate_stddev, const float noise_yawrate_bias) - { +void CaService::SetYawrateDeviation(const float noise_yawrate_stddev, const float noise_yawrate_bias) +{ YawrateDeviation = noise_yawrate_stddev; YawrateBias = noise_yawrate_bias; - } - +} void CaService::AddBasicVehicleContainerHighFrequency(CAMContainer::HighFrequencyContainer_t &hfc, float DeltaTime) { hfc.present = CAMContainer::HighFrequencyContainer_PR_basicVehicleContainerHighFrequency; - CAMContainer::BasicVehicleContainerHighFrequency_t& bvc = hfc.basicVehicleContainerHighFrequency; - //heading - bvc.heading.headingValue = std::round(GetHeading() * 10.0); - bvc.heading.headingConfidence = ITSContainer::HeadingConfidence_equalOrWithinOneDegree; //TODO - //speed - //speed with noise - bvc.speed.speedValue = buildSpeedValue(ComputeSpeed()); - bvc.speed.speedConfidence = ITSContainer::SpeedConfidence_equalOrWithInOneCentimerterPerSec * 3; //TODO - //direction - bvc.driveDirection = (mVehicle->GetVehicleForwardSpeed() / 100.0f) >= 0.0 ? ITSContainer::DriveDirection_forward : ITSContainer::DriveDirection_backward; - //length and width - auto bb = UBoundingBoxCalculator::GetActorBoundingBox(mActorOwner); //cm - float length = bb.Extent.X *2.0; //half box - float width = bb.Extent.Y * 2.0; //half box + CAMContainer::BasicVehicleContainerHighFrequency_t &bvc = hfc.basicVehicleContainerHighFrequency; + // heading + bvc.heading.headingValue = std::round(GetHeading() * 10.0); + bvc.heading.headingConfidence = ITSContainer::HeadingConfidence_equalOrWithinOneDegree; // TODO + // speed + // speed with noise + bvc.speed.speedValue = buildSpeedValue(ComputeSpeed()); + bvc.speed.speedConfidence = ITSContainer::SpeedConfidence_equalOrWithInOneCentimerterPerSec * 3; // TODO + // direction + bvc.driveDirection = (mVehicle->GetVehicleForwardSpeed() / 100.0f) >= 0.0 ? ITSContainer::DriveDirection_forward : ITSContainer::DriveDirection_backward; + // length and width + auto bb = UBoundingBoxCalculator::GetActorBoundingBox(mActorOwner); // cm + float length = bb.Extent.X * 2.0; // half box + float width = bb.Extent.Y * 2.0; // half box - bvc.vehicleLength.vehicleLengthValue = std::round(length * 10.0); //0.1 meter + bvc.vehicleLength.vehicleLengthValue = std::round(length * 10.0); // 0.1 meter bvc.vehicleLength.vehicleLengthConfidenceIndication = ITSContainer::VehicleLengthConfidenceIndication_unavailable; - bvc.vehicleWidth = std::round(width * 10.0); //0.1 meter - - //acceleration - carla::geom::Vector3D Accel = ComputeAccelerometer(DeltaTime); + bvc.vehicleWidth = std::round(width * 10.0); // 0.1 meter + + // acceleration + carla::geom::Vector3D Accel = ComputeAccelerometer(DeltaTime); const double lonAccelValue = Accel.x * 10.0; // m/s to 0.1 m/s - // limit changes - if (lonAccelValue >= -160.0 && lonAccelValue <= 161.0) { - bvc.longitudinalAcceleration.longitudinalAccelerationValue = std::round(lonAccelValue) * ITSContainer::LongitudinalAccelerationValue_pointOneMeterPerSecSquaredForward; - } else { - bvc.longitudinalAcceleration.longitudinalAccelerationValue = ITSContainer::LongitudinalAccelerationValue_unavailable; - } - bvc.longitudinalAcceleration.longitudinalAccelerationConfidence = ITSContainer::AccelerationConfidence_unavailable; //TODO + // limit changes + if (lonAccelValue >= -160.0 && lonAccelValue <= 161.0) + { + bvc.longitudinalAcceleration.longitudinalAccelerationValue = std::round(lonAccelValue) * ITSContainer::LongitudinalAccelerationValue_pointOneMeterPerSecSquaredForward; + } + else + { + bvc.longitudinalAcceleration.longitudinalAccelerationValue = ITSContainer::LongitudinalAccelerationValue_unavailable; + } + bvc.longitudinalAcceleration.longitudinalAccelerationConfidence = ITSContainer::AccelerationConfidence_unavailable; // TODO - - //curvature TODO - bvc.curvature.curvatureValue = ITSContainer::CurvatureValue_unavailable; + // curvature TODO + bvc.curvature.curvatureValue = ITSContainer::CurvatureValue_unavailable; bvc.curvature.curvatureConfidence = ITSContainer::CurvatureConfidence_unavailable; bvc.curvatureCalculationMode = ITSContainer::CurvatureCalculationMode_yarRateUsed; - - //yaw rate is in rad/s --> to centidegree per second - bvc.yawRate.yawRateValue = std::round( carla::geom::Math::ToDegrees(ComputeYawRate()) * 100.0) * ITSContainer::YawRateValue_degSec_000_01ToLeft; - if (bvc.yawRate.yawRateValue < -32766 || bvc.yawRate.yawRateValue > 32766) { - bvc.yawRate.yawRateValue = ITSContainer::YawRateValue_unavailable; - } - bvc.yawRate.yawRateConfidence = ITSContainer::YawRateConfidence_unavailable; //TODO - //optional lat and vertical accelerations + // yaw rate is in rad/s --> to centidegree per second + bvc.yawRate.yawRateValue = std::round(carla::geom::Math::ToDegrees(ComputeYawRate()) * 100.0) * ITSContainer::YawRateValue_degSec_000_01ToLeft; + if (bvc.yawRate.yawRateValue < -32766 || bvc.yawRate.yawRateValue > 32766) + { + bvc.yawRate.yawRateValue = ITSContainer::YawRateValue_unavailable; + } + bvc.yawRate.yawRateConfidence = ITSContainer::YawRateConfidence_unavailable; // TODO + + // optional lat and vertical accelerations bvc.lateralAccelerationAvailable = true; const double latAccelValue = Accel.y * 10.0; // m/s to 0.1 m/s - if (latAccelValue >= -160.0 && latAccelValue <= 161.0) { - bvc.lateralAcceleration.lateralAccelerationValue = std::round(latAccelValue) * ITSContainer::LateralAccelerationValue_pointOneMeterPerSecSquaredToLeft; - } else { - bvc.lateralAcceleration.lateralAccelerationValue = ITSContainer::LateralAccelerationValue_unavailable; - } - bvc.lateralAcceleration.lateralAccelerationConfidence = ITSContainer::AccelerationConfidence_unavailable; //TODO - + if (latAccelValue >= -160.0 && latAccelValue <= 161.0) + { + bvc.lateralAcceleration.lateralAccelerationValue = std::round(latAccelValue) * ITSContainer::LateralAccelerationValue_pointOneMeterPerSecSquaredToLeft; + } + else + { + bvc.lateralAcceleration.lateralAccelerationValue = ITSContainer::LateralAccelerationValue_unavailable; + } + bvc.lateralAcceleration.lateralAccelerationConfidence = ITSContainer::AccelerationConfidence_unavailable; // TODO + bvc.verticalAccelerationAvailable = true; const double vertAccelValue = Accel.z * 10.0; // m/s to 0.1 m/s - if (vertAccelValue >= -160.0 && vertAccelValue <= 161.0) { - bvc.verticalAcceleration.verticalAccelerationValue = std::round(vertAccelValue) * ITSContainer::VerticalAccelerationValue_pointOneMeterPerSecSquaredUp; - } else { - bvc.verticalAcceleration.verticalAccelerationValue = ITSContainer::VerticalAccelerationValue_unavailable; - } - bvc.verticalAcceleration.verticalAccelerationConfidence = ITSContainer::AccelerationConfidence_unavailable; //TODO + if (vertAccelValue >= -160.0 && vertAccelValue <= 161.0) + { + bvc.verticalAcceleration.verticalAccelerationValue = std::round(vertAccelValue) * ITSContainer::VerticalAccelerationValue_pointOneMeterPerSecSquaredUp; + } + else + { + bvc.verticalAcceleration.verticalAccelerationValue = ITSContainer::VerticalAccelerationValue_unavailable; + } + bvc.verticalAcceleration.verticalAccelerationConfidence = ITSContainer::AccelerationConfidence_unavailable; // TODO - //TODO + // TODO bvc.accelerationControlAvailable = false; bvc.lanePositionAvailable = false; bvc.steeringWheelAngleAvailable = false; @@ -558,62 +551,60 @@ void CaService::AddBasicVehicleContainerHighFrequency(CAMContainer::HighFrequenc const carla::geom::Vector3D CaService::ComputeAccelerometerNoise( const FVector &Accelerometer) { - // Normal (or Gaussian or Gauss) distribution will be used as noise function. - // A mean of 0.0 is used as a first parameter, the standard deviation is - // determined by the client - constexpr float Mean = 0.0f; - return carla::geom::Vector3D { - Accelerometer.X + mRandomEngine->GetNormalDistribution(Mean, StdDevAccel.X), - Accelerometer.Y + mRandomEngine->GetNormalDistribution(Mean, StdDevAccel.Y), - Accelerometer.Z + mRandomEngine->GetNormalDistribution(Mean, StdDevAccel.Z) - }; + // Normal (or Gaussian or Gauss) distribution will be used as noise function. + // A mean of 0.0 is used as a first parameter, the standard deviation is + // determined by the client + constexpr float Mean = 0.0f; + return carla::geom::Vector3D{ + Accelerometer.X + mRandomEngine->GetNormalDistribution(Mean, StdDevAccel.X), + Accelerometer.Y + mRandomEngine->GetNormalDistribution(Mean, StdDevAccel.Y), + Accelerometer.Z + mRandomEngine->GetNormalDistribution(Mean, StdDevAccel.Z)}; } carla::geom::Vector3D CaService::ComputeAccelerometer( const float DeltaTime) { - // Used to convert from UE4's cm to meters - constexpr float TO_METERS = 1e-2; - // Earth's gravitational acceleration is approximately 9.81 m/s^2 - constexpr float GRAVITY = 9.81f; + // Used to convert from UE4's cm to meters + constexpr float TO_METERS = 1e-2; + // Earth's gravitational acceleration is approximately 9.81 m/s^2 + constexpr float GRAVITY = 9.81f; - // 2nd derivative of the polynomic (quadratic) interpolation - // using the point in current time and two previous steps: - // d2[i] = -2.0*(y1/(h1*h2)-y2/((h2+h1)*h2)-y0/(h1*(h2+h1))) - const FVector CurrentLocation = mVehicle->GetActorLocation(); + // 2nd derivative of the polynomic (quadratic) interpolation + // using the point in current time and two previous steps: + // d2[i] = -2.0*(y1/(h1*h2)-y2/((h2+h1)*h2)-y0/(h1*(h2+h1))) + const FVector CurrentLocation = mVehicle->GetActorLocation(); - const FVector Y2 = PrevLocation[0]; - const FVector Y1 = PrevLocation[1]; - const FVector Y0 = CurrentLocation; - const float H1 = DeltaTime; - const float H2 = PrevDeltaTime; + const FVector Y2 = PrevLocation[0]; + const FVector Y1 = PrevLocation[1]; + const FVector Y0 = CurrentLocation; + const float H1 = DeltaTime; + const float H2 = PrevDeltaTime; - const float H1AndH2 = H2 + H1; - const FVector A = Y1 / ( H1 * H2 ); - const FVector B = Y2 / ( H2 * (H1AndH2) ); - const FVector C = Y0 / ( H1 * (H1AndH2) ); - FVector FVectorAccelerometer = TO_METERS * -2.0f * ( A - B - C ); + const float H1AndH2 = H2 + H1; + const FVector A = Y1 / (H1 * H2); + const FVector B = Y2 / (H2 * (H1AndH2)); + const FVector C = Y0 / (H1 * (H1AndH2)); + FVector FVectorAccelerometer = TO_METERS * -2.0f * (A - B - C); - // Update the previous locations - PrevLocation[0] = PrevLocation[1]; - PrevLocation[1] = CurrentLocation; - PrevDeltaTime = DeltaTime; + // Update the previous locations + PrevLocation[0] = PrevLocation[1]; + PrevLocation[1] = CurrentLocation; + PrevDeltaTime = DeltaTime; - // Add gravitational acceleration - FVectorAccelerometer.Z += GRAVITY; + // Add gravitational acceleration + FVectorAccelerometer.Z += GRAVITY; - FQuat ImuRotation = mActorOwner->GetRootComponent()->GetComponentTransform().GetRotation(); - FVectorAccelerometer = ImuRotation.UnrotateVector(FVectorAccelerometer); + FQuat ImuRotation = mActorOwner->GetRootComponent()->GetComponentTransform().GetRotation(); + FVectorAccelerometer = ImuRotation.UnrotateVector(FVectorAccelerometer); - // Cast from FVector to our Vector3D to correctly send the data in m/s^2 - // and apply the desired noise function, in this case a normal distribution - const carla::geom::Vector3D Accelerometer = - ComputeAccelerometerNoise(FVectorAccelerometer); + // Cast from FVector to our Vector3D to correctly send the data in m/s^2 + // and apply the desired noise function, in this case a normal distribution + const carla::geom::Vector3D Accelerometer = + ComputeAccelerometerNoise(FVectorAccelerometer); - return Accelerometer; + return Accelerometer; } - float CaService::ComputeSpeed() { @@ -624,44 +615,45 @@ float CaService::ComputeSpeed() // A mean of 0.0 is used as a first parameter.The standard deviation and the // bias are determined by the client constexpr float Mean = 0.0f; - return boost::algorithm::clamp(speed + mRandomEngine->GetNormalDistribution(Mean, VelocityDeviation),0.0f,std::numeric_limits::max()); + return boost::algorithm::clamp(speed + mRandomEngine->GetNormalDistribution(Mean, VelocityDeviation), 0.0f, std::numeric_limits::max()); } float CaService::ComputeYawRate() { - check(mActorOwner != nullptr); - const FVector AngularVelocity = - FIMU_GetActorAngularVelocityInRadians(*mActorOwner); + check(mActorOwner != nullptr); + const FVector AngularVelocity = + FIMU_GetActorAngularVelocityInRadians(*mActorOwner); - const FQuat SensorLocalRotation = - mActorOwner->GetRootComponent()->GetRelativeTransform().GetRotation(); + const FQuat SensorLocalRotation = + mActorOwner->GetRootComponent()->GetRelativeTransform().GetRotation(); - const FVector FVectorGyroscope = - SensorLocalRotation.RotateVector(AngularVelocity); + const FVector FVectorGyroscope = + SensorLocalRotation.RotateVector(AngularVelocity); - // Cast from FVector to our Vector3D to correctly send the data in rad/s - // and apply the desired noise function, in this case a normal distribution - float yawrate = - ComputeYawNoise(FVectorGyroscope); + // Cast from FVector to our Vector3D to correctly send the data in rad/s + // and apply the desired noise function, in this case a normal distribution + float yawrate = + ComputeYawNoise(FVectorGyroscope); - return yawrate; //rad/s + return yawrate; // rad/s } const float CaService::ComputeYawNoise( const FVector &Gyroscope) { - // Normal (or Gaussian or Gauss) distribution and a bias will be used as - // noise function. - // A mean of 0.0 is used as a first parameter.The standard deviation and the - // bias are determined by the client - constexpr float Mean = 0.0f; - return Gyroscope.Z + YawrateBias + mRandomEngine->GetNormalDistribution(Mean, YawrateDeviation); + // Normal (or Gaussian or Gauss) distribution and a bias will be used as + // noise function. + // A mean of 0.0 is used as a first parameter.The standard deviation and the + // bias are determined by the client + constexpr float Mean = 0.0f; + return Gyroscope.Z + YawrateBias + mRandomEngine->GetNormalDistribution(Mean, YawrateDeviation); } -long millisecondsSince2004() { +long millisecondsSince2004() +{ // Define the epoch time (2004-01-01T00:00:00.000Z) std::tm epoch_time = {}; - epoch_time = {0, 0, 0, 1, 0, 104}; // January 1, 2004 + epoch_time = {0, 0, 0, 1, 0, 104}; // January 1, 2004 // Convert epoch time to a std::chrono::time_point std::chrono::system_clock::time_point epoch = std::chrono::system_clock::from_time_t(std::mktime(&epoch_time)); @@ -679,17 +671,16 @@ long millisecondsSince2004() { void CaService::AddRSUContainerHighFrequency(CAMContainer::HighFrequencyContainer_t &hfc) { hfc.present = CAMContainer::HighFrequencyContainer_PR_rsuContainerHighFrequency; - CAMContainer::RSUContainerHighFrequency_t& rsu = hfc.rsuContainerHighFrequency; - //TODO For future implementation - // ITSContainer::ProtectedCommunicationZonesRSU_t PCZR; - - uint8_t ProtectedZoneDataLength = 16; //Maximum number of elements in path history + CAMContainer::RSUContainerHighFrequency_t &rsu = hfc.rsuContainerHighFrequency; + // TODO For future implementation ITSContainer::ProtectedCommunicationZonesRSU_t PCZR + + uint8_t ProtectedZoneDataLength = 16; // Maximum number of elements in path history for (uint8_t i = 0; i <= ProtectedZoneDataLength; ++i) { ITSContainer::ProtectedCommunicationZone_t PCZ; PCZ.protectedZoneType = ITSContainer::ProtectedZoneType_cenDsrcTolling; - PCZ.expiryTimeAvailable = false; + PCZ.expiryTimeAvailable = false; PCZ.protectedZoneLatitude = 50; PCZ.protectedZoneLongitude = 50; PCZ.protectedZoneRadiusAvailable = false; @@ -699,42 +690,42 @@ void CaService::AddRSUContainerHighFrequency(CAMContainer::HighFrequencyContaine } } -void CaService::AddLowFrequencyContainer(CAMContainer::LowFrequencyContainer_t& lfc) +void CaService::AddLowFrequencyContainer(CAMContainer::LowFrequencyContainer_t &lfc) { lfc.present = CAMContainer::LowFrequencyContainer_PR_basicVehicleContainerLowFrequency; - CAMContainer::BasicVehicleContainerLowFrequency_t& bvc = lfc.basicVehicleContainerLowFrequency; + CAMContainer::BasicVehicleContainerLowFrequency_t &bvc = lfc.basicVehicleContainerLowFrequency; /*Vehicle Role*/ bvc.vehicleRole = GetVehicleRole(); /*Exterior Lights*/ - uint8_t* buf = &bvc.exteriorLights; + uint8_t *buf = &bvc.exteriorLights; FVehicleLightState LightStateData = mVehicle->GetVehicleLightState(); - if(LightStateData.LowBeam) - { + if (LightStateData.LowBeam) + { buf[0] |= 1 << (7 - ITSContainer::ExteriorLights_lowBeamHeadlightsOn); } - if(LightStateData.HighBeam) + if (LightStateData.HighBeam) { buf[0] |= 1 << (7 - ITSContainer::ExteriorLights_highBeamHeadlightsOn); } - if(LightStateData.LeftBlinker) + if (LightStateData.LeftBlinker) { buf[0] |= 1 << (7 - ITSContainer::ExteriorLights_leftTurnSignalOn); } - if(LightStateData.RightBlinker) + if (LightStateData.RightBlinker) { buf[0] |= 1 << (7 - ITSContainer::ExteriorLights_rightTurnSignalOn); } - if(LightStateData.Reverse) + if (LightStateData.Reverse) { buf[0] |= 1 << (7 - ITSContainer::ExteriorLights_reverseLightOn); } - if(LightStateData.Fog) + if (LightStateData.Fog) { buf[0] |= 1 << (7 - ITSContainer::ExteriorLights_fogLightOn); } - if(LightStateData.Position) + if (LightStateData.Position) { buf[0] |= 1 << (7 - ITSContainer::ExteriorLights_parkingLightsOn); } @@ -743,13 +734,12 @@ void CaService::AddLowFrequencyContainer(CAMContainer::LowFrequencyContainer_t& bool CaService::CheckHeadingDelta(float DeltaSeconds) { - //if heading diff is more than 4degree + // if heading diff is more than 4degree VehicleHeading = mVehicle->GetVehicleOrientation(); double HeadingDelta = carla::geom::Math::ToDegrees(GetFVectorAngle(mLastCamHeading, VehicleHeading)); - if(HeadingDelta > 4.0) + if (HeadingDelta > 4.0) { return true; } return false; } - diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/CaService.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/CaService.h index 749b54e65..070f185ad 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/CaService.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/CaService.h @@ -1,4 +1,4 @@ -// Copyright (c) 2024 Institut fuer Technik der Informationsverarbeitung (ITIV) at the +// Copyright (c) 2024 Institut fuer Technik der Informationsverarbeitung (ITIV) at the // Karlsruhe Institute of Technology // // This work is licensed under the terms of the MIT license. @@ -20,32 +20,30 @@ class CaService { public: - - CaService(URandomEngine* random_engine); - void SetOwner(UWorld* world, AActor *Owner); + CaService(URandomEngine *random_engine); + void SetOwner(UWorld *world, AActor *Owner); void SetParams(const float GenCamMin, const float GenCamMax, const bool FixedRate); - void SetVelDeviation(const float noise_vel_stddev_x); - void SetYawrateDeviation(const float noise_yawrate_stddev, const float noise_yawrate_bias); + void SetVelDeviation(const float noise_vel_stddev_x); + void SetYawrateDeviation(const float noise_yawrate_stddev, const float noise_yawrate_bias); void SetAccelerationStandardDeviation(const FVector &Vec); void SetGNSSDeviation(const float noise_lat_stddev, - const float noise_lon_stddev, - const float noise_alt_stddev, - const float noise_head_stddev, - const float noise_lat_bias, - const float noise_lon_bias, - const float noise_alt_bias, - const float noise_head_bias); + const float noise_lon_stddev, + const float noise_alt_stddev, + const float noise_head_stddev, + const float noise_lat_bias, + const float noise_lon_bias, + const float noise_alt_bias, + const float noise_head_bias); bool Trigger(float DeltaSeconds); CAM_t GetCamMessage(); private: - AActor *mActorOwner; - FCarlaActor* mCarlaActor; - UCarlaEpisode* mCarlaEpisode; - UWorld* mWorld; - ACarlaWheeledVehicle* mVehicle; + FCarlaActor *mCarlaActor; + UCarlaEpisode *mCarlaEpisode; + UWorld *mWorld; + ACarlaWheeledVehicle *mVehicle; float mLastCamTimeStamp; float mLastLowCamTimeStamp; float mGenCamMin; @@ -68,7 +66,6 @@ private: FVector mLastCamHeading; std::chrono::milliseconds mGenerationDelta0; - bool CheckTriggeringConditions(float DeltaSeconds); bool CheckHeadingDelta(float DeltaSeconds); bool CheckPositionDelta(float DeltaSeconds); @@ -85,21 +82,21 @@ private: const long mMessageId = ITSContainer::messageID_cam; long mStationId; long mStationType; - + carla::geom::Vector3D ComputeAccelerometer(const float DeltaTime); const carla::geom::Vector3D ComputeAccelerometerNoise(const FVector &Accelerometer); /// Standard deviation for acceleration settings. FVector StdDevAccel; - /// Used to compute the acceleration + /// Used to compute the acceleration std::array PrevLocation; /// Used to compute the acceleration float PrevDeltaTime; - //GNSS reference position and heading + // GNSS reference position and heading FVector GetReferencePosition(); - carla::geom::GeoLocation CurrentGeoReference; + carla::geom::GeoLocation CurrentGeoReference; float LatitudeDeviation; float LongitudeDeviation; float AltitudeDeviation; @@ -109,29 +106,27 @@ private: float LongitudeBias; float AltitudeBias; float HeadingBias; - - //Velocity - float ComputeSpeed(); - float VelocityDeviation; - - //Yaw rate + + // Velocity + float ComputeSpeed(); + float VelocityDeviation; + + // Yaw rate const float ComputeYawNoise(const FVector &Gyroscope); float ComputeYawRate(); float YawrateDeviation; float YawrateBias; CAM_t CreateCooperativeAwarenessMessage(float DeltaTime); - void CreateITSPduHeader(CAM_t& message); - void AddCooperativeAwarenessMessage(CAMContainer::CoopAwareness_t& CoopAwarenessMessage, float DeltaTime); - void AddBasicContainer(CAMContainer::BasicContainer_t& BasicContainer); - void AddBasicVehicleContainerHighFrequency(CAMContainer::HighFrequencyContainer_t& hfc, float DeltaTime); - void AddRSUContainerHighFrequency(CAMContainer::HighFrequencyContainer_t& hfc); - void AddLowFrequencyContainer(CAMContainer::LowFrequencyContainer_t& lfc); + void CreateITSPduHeader(CAM_t &message); + void AddCooperativeAwarenessMessage(CAMContainer::CoopAwareness_t &CoopAwarenessMessage, float DeltaTime); + void AddBasicContainer(CAMContainer::BasicContainer_t &BasicContainer); + void AddBasicVehicleContainerHighFrequency(CAMContainer::HighFrequencyContainer_t &hfc, float DeltaTime); + void AddRSUContainerHighFrequency(CAMContainer::HighFrequencyContainer_t &hfc); + void AddLowFrequencyContainer(CAMContainer::LowFrequencyContainer_t &lfc); CAM_t mCAMMessage; - //random for noise - URandomEngine* mRandomEngine; + // random for noise + URandomEngine *mRandomEngine; ITSContainer::SpeedValue_t buildSpeedValue(const float vel); - - }; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.cpp index df87f9423..53e40ee69 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.cpp @@ -1,4 +1,4 @@ -// Copyright (c) 2024 Institut fuer Technik der Informationsverarbeitung (ITIV) at the +// Copyright (c) 2024 Institut fuer Technik der Informationsverarbeitung (ITIV) at the // Karlsruhe Institute of Technology // // This work is licensed under the terms of the MIT license. @@ -10,10 +10,9 @@ #include #include - double PathLossModel::Frequency_GHz = 5.9f; -double PathLossModel::Frequency = 5.9f * std::pow(10,9); -double PathLossModel::lambda = PathLossModel::c_speedoflight/(5.9f * std::pow(10,9)); +double PathLossModel::Frequency = 5.9f * std::pow(10, 9); +double PathLossModel::lambda = PathLossModel::c_speedoflight / (5.9f * std::pow(10, 9)); PathLossModel::PathLossModel(URandomEngine *random_engine) { @@ -44,8 +43,8 @@ void PathLossModel::SetParams(const float TransmitPower, this->custom_fading_stddev = custom_fading_stddev; this->combined_antenna_gain = combined_antenna_gain; PathLossModel::Frequency_GHz = Frequency; - PathLossModel::Frequency = PathLossModel::Frequency_GHz * std::pow(10,9); - PathLossModel::lambda = PathLossModel::c_speedoflight/PathLossModel::Frequency; + PathLossModel::Frequency = PathLossModel::Frequency_GHz * std::pow(10, 9); + PathLossModel::lambda = PathLossModel::c_speedoflight / PathLossModel::Frequency; // when reference distance is set, we prepare the FSPL for the reference distance to be used in LDPL CalculateFSPL_d0(); } @@ -316,7 +315,6 @@ void PathLossModel::SetPathLossModel(const EPathLossModel path_loss_model) model = path_loss_model; } - float PathLossModel::ComputeLoss(AActor *OtherActor, FVector Source, FVector Destination, double Distance3d, double TxHeight, double RxHeight, double reference_z) { // TxHeight in m @@ -524,7 +522,7 @@ float PathLossModel::CalculateShadowFading(EPathState state) } else { - //custom fading param + // custom fading param std_dev_dB = custom_fading_stddev; } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.h index beb37398b..1c43e58bc 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.h @@ -1,4 +1,4 @@ -// Copyright (c) 2024 Institut fuer Technik der Informationsverarbeitung (ITIV) at the +// Copyright (c) 2024 Institut fuer Technik der Informationsverarbeitung (ITIV) at the // Karlsruhe Institute of Technology // // This work is licensed under the terms of the MIT license. @@ -9,21 +9,24 @@ #include #include -using ActorPowerMap = std::map; +using ActorPowerMap = std::map; using ActorPowerPair = std::pair; -enum EPathState{ +enum EPathState +{ LOS, NLOSb, NLOSv }; -enum EPathLossModel{ +enum EPathLossModel +{ Winner, Geometric, }; -enum EScenario{ +enum EScenario +{ Highway, Rural, Urban @@ -32,7 +35,7 @@ enum EScenario{ struct DiffractionObstacle { DiffractionObstacle(double distTx, double height); - //meter + // meter double d; // distance to transmitter double h; // height of obstacle }; @@ -42,103 +45,100 @@ struct DiffractionPath DiffractionPath(); double attenuation; - double d; //meter + double d; // meter }; - class PathLossModel { public: - PathLossModel(URandomEngine* random_engine); + PathLossModel(URandomEngine *random_engine); void SetOwner(AActor *Owner); void SetScenario(EScenario scenario); - void Simulate(const std::vector ActorList, UCarlaEpisode *CarlaEpisode, UWorld* World); + void Simulate(const std::vector ActorList, UCarlaEpisode *CarlaEpisode, UWorld *World); ActorPowerMap GetReceiveActorPowerList(); void SetParams(const float TransmitPower, - const float ReceiverSensitivity, - const float Frequency, - const float combined_antenna_gain, - const float path_loss_exponent, - const float reference_distance_fspl, - const float filter_distance, - const bool use_etsi_fading, - const float custom_fading_stddev); + const float ReceiverSensitivity, + const float Frequency, + const float combined_antenna_gain, + const float path_loss_exponent, + const float reference_distance_fspl, + const float filter_distance, + const bool use_etsi_fading, + const float custom_fading_stddev); float GetTransmitPower() { return TransmitPower; } void SetPathLossModel(const EPathLossModel path_loss_model); private: - //multiple knife edge diffraction for NLOSv - double computeVehiclePathLoss(const FVector& pos_tx, const FVector& pos_rx, const double reference_z, std::vector& vehicle_obstacles); - double computeSimpleKnifeEdge(double heightTx, double heightRx,double heightObs, double distTxRx, double distTxObs); - DiffractionPath computeMultipleKnifeEdge(const std::list& obs); - std::list buildTopObstacles(const std::vector& vehicles, const FVector& pos_tx, const FVector& pos_rx); + // multiple knife edge diffraction for NLOSv + double computeVehiclePathLoss(const FVector &pos_tx, const FVector &pos_rx, const double reference_z, std::vector &vehicle_obstacles); + double computeSimpleKnifeEdge(double heightTx, double heightRx, double heightObs, double distTxRx, double distTxObs); + DiffractionPath computeMultipleKnifeEdge(const std::list &obs); + std::list buildTopObstacles(const std::vector &vehicles, const FVector &pos_tx, const FVector &pos_rx); - //powers - float CalculateReceivedPower(AActor* OtherActor, - const float OtherTransmitPower, - const FVector Source, - const FVector Destination, - const double Distance3d, - const double ht, - const double ht_local, - const double hr, - const double hr_local, - const double reference_z); - void EstimatePathStateAndVehicleObstacles(AActor* OtherActor, FVector Source, double TxHeight, double RxHeight, double reference_z, EPathState& state, std::vector& vehicle_obstacles); + // powers + float CalculateReceivedPower(AActor *OtherActor, + const float OtherTransmitPower, + const FVector Source, + const FVector Destination, + const double Distance3d, + const double ht, + const double ht_local, + const double hr, + const double hr_local, + const double reference_z); + void EstimatePathStateAndVehicleObstacles(AActor *OtherActor, FVector Source, double TxHeight, double RxHeight, double reference_z, EPathState &state, std::vector &vehicle_obstacles); double MakeVehicleBlockageLoss(double TxHeight, double RxHeight, double obj_height, double obj_distance); - //variables + // variables AActor *mActorOwner; - UCarlaEpisode* mCarlaEpisode; - UWorld* mWorld; - URandomEngine* mRandomEngine; - + UCarlaEpisode *mCarlaEpisode; + UWorld *mWorld; + URandomEngine *mRandomEngine; + ActorPowerMap mReceiveActorPowerList; FVector CurrentActorLocation; - //constants - constexpr static float c_speedoflight = 299792458.0; //m/s + // constants + constexpr static float c_speedoflight = 299792458.0; // m/s - //full two ray path loss - const double epsilon_r = 1.02; + // full two ray path loss + const double epsilon_r = 1.02; - //params - static double Frequency_GHz; // 5.9f;//5.9 GHz - static double Frequency; // Frequency_GHz * std::pow(10,9); - static double lambda; // c_speedoflight/Frequency; - float reference_distance_fspl; //m - float TransmitPower; //dBm - float ReceiverSensitivity; //dBm + // params + static double Frequency_GHz; // 5.9f;//5.9 GHz + static double Frequency; // Frequency_GHz * std::pow(10,9); + static double lambda; // c_speedoflight/Frequency; + float reference_distance_fspl; // m + float TransmitPower; // dBm + float ReceiverSensitivity; // dBm EScenario scenario; float path_loss_exponent; // no unit, default 2.7; - float filter_distance; //in meters default 500.0 + float filter_distance; // in meters default 500.0 EPathLossModel model; bool use_etsi_fading; float custom_fading_stddev; - float combined_antenna_gain; //10.0 dBi + float combined_antenna_gain; // 10.0 dBi - //dependent params that are precalculated on setting of params + // dependent params that are precalculated on setting of params float m_fspl_d0; protected: + /// Method that allow to preprocess if the rays will be traced. - /// Method that allow to preprocess if the rays will be traced. + float ComputeLoss(AActor *OtherActor, FVector Source, FVector Destination, double Distance3d, double TxHeight, double RxHeight, double reference_z); + bool IsVehicle(const FHitResult &HitInfo); + bool GetLocationIfVehicle(const FVector CurrentActorLocation, const FHitResult &HitInfo, const double reference_z, FVector &location); + bool HitIsSelfOrOther(const FHitResult &HitInfo, AActor *OtherActor); + float CalculatePathLoss_WINNER(EPathState state, double Distance); + double CalculateNLOSvLoss(const FVector Source, const FVector Destination, const double TxHeight, const double RxHeight, const double RxDistance3d, std::vector &vehicle_obstacles); - float ComputeLoss(AActor* OtherActor, FVector Source, FVector Destination, double Distance3d, double TxHeight, double RxHeight, double reference_z); - bool IsVehicle(const FHitResult& HitInfo); - bool GetLocationIfVehicle(const FVector CurrentActorLocation, const FHitResult &HitInfo, const double reference_z, FVector& location); - bool HitIsSelfOrOther(const FHitResult &HitInfo, AActor* OtherActor); - float CalculatePathLoss_WINNER(EPathState state, double Distance); - double CalculateNLOSvLoss( const FVector Source, const FVector Destination, const double TxHeight, const double RxHeight, const double RxDistance3d, std::vector& vehicle_obstacles); + float CalculateShadowFading(EPathState state); - float CalculateShadowFading(EPathState state); - - //full two ray model - double CalculateTwoRayPathLoss(double Distance3d, double TxHeight, double RxHeight); - //simplified two ray model - float CalculateTwoRayPathLossSimple(double Distance3d, double TxHeight, double RxHeight); - - //functions for precalculation - void CalculateFSPL_d0(); - TArray HitResult; + // full two ray model + double CalculateTwoRayPathLoss(double Distance3d, double TxHeight, double RxHeight); + // simplified two ray model + float CalculateTwoRayPathLossSimple(double Distance3d, double TxHeight, double RxHeight); + // functions for precalculation + void CalculateFSPL_d0(); + TArray HitResult; }; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/VehicleObstacle.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/VehicleObstacle.cpp index 4f44a31d1..fd27ed80e 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/VehicleObstacle.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/VehicleObstacle.cpp @@ -1,5 +1,5 @@ -// Copyright (c) 2024 Institut fuer Technik der Informationsverarbeitung (ITIV) at the +// Copyright (c) 2024 Institut fuer Technik der Informationsverarbeitung (ITIV) at the // Karlsruhe Institute of Technology // // This work is licensed under the terms of the MIT license. @@ -14,32 +14,27 @@ #include "PathLossModel.h" +namespace +{ + auto compareDistance = [](const DiffractionObstacle &a, const DiffractionObstacle &b) + { return a.d < b.d; }; + auto compareHeight = [](const DiffractionObstacle &a, const DiffractionObstacle &b) + { return a.h < b.h; }; -namespace { -auto compareDistance = [](const DiffractionObstacle& a, const DiffractionObstacle& b) { return a.d < b.d; }; -auto compareHeight = [](const DiffractionObstacle& a, const DiffractionObstacle& b) { return a.h < b.h; }; - -using ObstacleIterator = std::list::const_iterator; -ObstacleIterator findMainObstacle(ObstacleIterator, ObstacleIterator); -ObstacleIterator findSecondaryObstacle(ObstacleIterator, ObstacleIterator); + using ObstacleIterator = std::list::const_iterator; + ObstacleIterator findMainObstacle(ObstacleIterator, ObstacleIterator); + ObstacleIterator findSecondaryObstacle(ObstacleIterator, ObstacleIterator); } // namespace -DiffractionObstacle::DiffractionObstacle(double distTx, double height) : - d(distTx), h(height) +DiffractionObstacle::DiffractionObstacle(double distTx, double height) : d(distTx), h(height) { } -DiffractionPath::DiffractionPath() : - attenuation(0.0), d(0.0) +DiffractionPath::DiffractionPath() : attenuation(0.0), d(0.0) { } - - - - - -double PathLossModel::computeSimpleKnifeEdge(double heightTx, double heightRx,double heightObs, double distTxRx, double distTxObs) +double PathLossModel::computeSimpleKnifeEdge(double heightTx, double heightRx, double heightObs, double distTxRx, double distTxObs) { // following calculations are similar to equation 29 of ITU-R P.526-13: // v = sqrt(2d/lambda * alpha1 * alpha2) @@ -63,32 +58,35 @@ double PathLossModel::computeSimpleKnifeEdge(double heightTx, double heightRx,do const double v = root_two * h / r; double loss = 0.0; - if (v > -0.78) { + if (v > -0.78) + { // approximation of Fresnel-Kirchoff loss given by ITU-R P.526, equation 31 (result in dB): // J(v) = 6.9 + 20 log(sqrt((v - 01)^2 + 1) + v - 0.1) - loss = 6.9 + 20.0 * log10(sqrt(std::pow(v - 0.1,2) + 1.0) + v - 0.1); + loss = 6.9 + 20.0 * log10(sqrt(std::pow(v - 0.1, 2) + 1.0) + v - 0.1); } return loss; } -DiffractionPath PathLossModel::computeMultipleKnifeEdge(const std::list& obs) +DiffractionPath PathLossModel::computeMultipleKnifeEdge(const std::list &obs) { DiffractionPath path; // determine main and secondary obstacles std::vector mainObs; mainObs.push_back(obs.begin()); // Tx - for (ObstacleIterator it = obs.begin(); it != obs.end();) { + for (ObstacleIterator it = obs.begin(); it != obs.end();) + { it = findMainObstacle(it, obs.end()); - if (it != obs.end()) { + if (it != obs.end()) + { mainObs.push_back(it); } } // NOTE: Rx is added by loop as last main obstacle - struct SecondaryObstacle { - SecondaryObstacle(ObstacleIterator tx, ObstacleIterator obs, ObstacleIterator rx) : - tx(tx), obstacle(obs), rx(rx) {} + struct SecondaryObstacle + { + SecondaryObstacle(ObstacleIterator tx, ObstacleIterator obs, ObstacleIterator rx) : tx(tx), obstacle(obs), rx(rx) {} ObstacleIterator tx; ObstacleIterator obstacle; ObstacleIterator rx; @@ -96,31 +94,37 @@ DiffractionPath PathLossModel::computeMultipleKnifeEdge(const std::list secObs; std::vector mainObsDistances; - for (std::size_t i = 0, j = 1; j < mainObs.size(); ++i, ++j) { + for (std::size_t i = 0, j = 1; j < mainObs.size(); ++i, ++j) + { const double d = mainObs[j]->d - mainObs[i]->d; - path.d += sqrt(std::pow(d,2) + std::pow(mainObs[j]->h - mainObs[i]->h,2)); + path.d += sqrt(std::pow(d, 2) + std::pow(mainObs[j]->h - mainObs[i]->h, 2)); mainObsDistances.push_back(d); const auto delta = std::distance(mainObs[i], mainObs[j]); - if (delta == 2) { + if (delta == 2) + { // single other obstacle between two main obstacles secObs.emplace_back(mainObs[i], std::next(mainObs[i]), mainObs[j]); - } else if (delta > 2) { + } + else if (delta > 2) + { secObs.emplace_back(mainObs[i], findSecondaryObstacle(mainObs[i], mainObs[j]), mainObs[j]); } } // attenuation due to main obstacles double attMainObs = 0.0; - for (std::size_t i = 0; i < mainObs.size() - 2; ++i) { + for (std::size_t i = 0; i < mainObs.size() - 2; ++i) + { const double distTxObs = mainObsDistances[i]; - const double distTxRx = distTxObs + mainObsDistances[i+1]; - attMainObs += computeSimpleKnifeEdge(mainObs[i]->h, mainObs[i+2]->h, mainObs[i+1]->h, distTxRx, distTxObs); + const double distTxRx = distTxObs + mainObsDistances[i + 1]; + attMainObs += computeSimpleKnifeEdge(mainObs[i]->h, mainObs[i + 2]->h, mainObs[i + 1]->h, distTxRx, distTxObs); } // attenuation due to secondary obstacles double attSecObs = 0.0; - for (const SecondaryObstacle& sec : secObs) { + for (const SecondaryObstacle &sec : secObs) + { const double distTxRx = sec.rx->d - sec.tx->d; const double distTxObs = sec.obstacle->d - sec.tx->d; attSecObs += computeSimpleKnifeEdge(sec.tx->h, sec.rx->h, sec.obstacle->h, distTxRx, distTxObs); @@ -128,31 +132,35 @@ DiffractionPath PathLossModel::computeMultipleKnifeEdge(const std::listd - mainObs.front()->d; // distance between Tx and Rx - for (double d : mainObsDistances) { + for (double d : mainObsDistances) + { C *= d; } double pairwiseDistProduct = 1.0; - for (std::size_t i = 1; i < mainObsDistances.size(); ++i) { - pairwiseDistProduct *= mainObsDistances[i-1] + mainObsDistances[i]; + for (std::size_t i = 1; i < mainObsDistances.size(); ++i) + { + pairwiseDistProduct *= mainObsDistances[i - 1] + mainObsDistances[i]; } C /= mainObsDistances.front() * mainObsDistances.back() * pairwiseDistProduct; - path.attenuation = attMainObs + attSecObs - 10.0* log10(C); + path.attenuation = attMainObs + attSecObs - 10.0 * log10(C); return path; } -std::list PathLossModel::buildTopObstacles(const std::vector& vehicles, const FVector& pos_tx, const FVector& pos_rx) +std::list PathLossModel::buildTopObstacles(const std::vector &vehicles, const FVector &pos_tx, const FVector &pos_rx) { std::list diffTop; const double vx = pos_rx.X - pos_tx.X; const double vy = pos_rx.Y - pos_tx.Y; - for (auto vehicle : vehicles) { + for (auto vehicle : vehicles) + { const double midpoint_x = vehicle.X; const double midpoint_y = vehicle.Y; - const double k = (midpoint_x * vx - vy * pos_tx.Y + vy * midpoint_y - pos_tx.X * vx) / (std::pow(vx,2) + std::pow(vy,2)); - if (k < 0.0 || k > 1.0) continue; /*< skip points beyond the ends of TxRx line segment */ - const double d = k * sqrt(std::pow(vx,2) + std::pow(vy,2)); + const double k = (midpoint_x * vx - vy * pos_tx.Y + vy * midpoint_y - pos_tx.X * vx) / (std::pow(vx, 2) + std::pow(vy, 2)); + if (k < 0.0 || k > 1.0) + continue; /*< skip points beyond the ends of TxRx line segment */ + const double d = k * sqrt(std::pow(vx, 2) + std::pow(vy, 2)); diffTop.emplace_back(d, vehicle.Z); } @@ -160,69 +168,72 @@ std::list PathLossModel::buildTopObstacles(const std::vecto return diffTop; } - - -namespace { - -ObstacleIterator findMainObstacle(ObstacleIterator begin, ObstacleIterator end) +namespace { - ObstacleIterator mainIterator = end; - double mainAngle = -std::numeric_limits::infinity(); - if (begin != end) { - for (ObstacleIterator it = std::next(begin); it != end; ++it) { - double angle = (it->h - begin->h) / (it->d - begin->d); - if (angle > mainAngle) { - mainIterator = it; - mainAngle = angle; + ObstacleIterator findMainObstacle(ObstacleIterator begin, ObstacleIterator end) + { + ObstacleIterator mainIterator = end; + double mainAngle = -std::numeric_limits::infinity(); + + if (begin != end) + { + for (ObstacleIterator it = std::next(begin); it != end; ++it) + { + double angle = (it->h - begin->h) / (it->d - begin->d); + if (angle > mainAngle) + { + mainIterator = it; + mainAngle = angle; + } } } + + return mainIterator; } - return mainIterator; -} + ObstacleIterator findSecondaryObstacle(ObstacleIterator first, ObstacleIterator last) + { + ObstacleIterator secIterator = last; + double secHeightGap{std::numeric_limits::infinity()}; -ObstacleIterator findSecondaryObstacle(ObstacleIterator first, ObstacleIterator last) -{ - ObstacleIterator secIterator = last; - double secHeightGap { std::numeric_limits::infinity() }; - - const double distFirstLast = last->d - first->d; - const double heightFirstLast = last->h - first->h; - const auto offset = first->h * last->d - first->d * last->h; - for (ObstacleIterator it = std::next(first); it != last; ++it) { - const double heightGap = ((it->d * heightFirstLast + offset) / distFirstLast) - it->h; - if (heightGap < secHeightGap) { - secIterator = it; - secHeightGap = heightGap; + const double distFirstLast = last->d - first->d; + const double heightFirstLast = last->h - first->h; + const auto offset = first->h * last->d - first->d * last->h; + for (ObstacleIterator it = std::next(first); it != last; ++it) + { + const double heightGap = ((it->d * heightFirstLast + offset) / distFirstLast) - it->h; + if (heightGap < secHeightGap) + { + secIterator = it; + secHeightGap = heightGap; + } } - } - return secIterator; -} + return secIterator; + } } // namespace - -//statistical model from ETSI TR 103 257-1 V1.1.1 (2019-05) +// statistical model from ETSI TR 103 257-1 V1.1.1 (2019-05) double PathLossModel::MakeVehicleBlockageLoss(double TxHeight, double RxHeight, double obj_height, double obj_distance) { - //according to ETSI, stochastic method - if( TxHeight > obj_height && RxHeight > obj_height) + // according to ETSI, stochastic method + if (TxHeight > obj_height && RxHeight > obj_height) { - //no blocking if higher than obj + // no blocking if higher than obj return 0.0; } - else if(TxHeight < obj_height && RxHeight < obj_height) + else if (TxHeight < obj_height && RxHeight < obj_height) { - //worst case: obj is higher than both tx and rx - float mean = 9.0f + fmax(0.0f, 15.0f * log10(obj_distance)-41.0f); + // worst case: obj is higher than both tx and rx + float mean = 9.0f + fmax(0.0f, 15.0f * log10(obj_distance) - 41.0f); return mRandomEngine->GetNormalDistribution(mean, 4.5f); } else { - //something in between - float mean = 5.0f + fmax(0.0f, 15.0f * log10(obj_distance)-41.0f); + // something in between + float mean = 5.0f + fmax(0.0f, 15.0f * log10(obj_distance) - 41.0f); return mRandomEngine->GetNormalDistribution(mean, 4.0f); } } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2XSensor.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2XSensor.cpp index 503f1e923..2e5c88692 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2XSensor.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2XSensor.cpp @@ -1,4 +1,4 @@ -// Copyright (c) 2024 Institut fuer Technik der Informationsverarbeitung (ITIV) at the +// Copyright (c) 2024 Institut fuer Technik der Informationsverarbeitung (ITIV) at the // Karlsruhe Institute of Technology // // This work is licensed under the terms of the MIT license. @@ -40,7 +40,7 @@ void AV2XSensor::SetOwner(AActor *Owner) Super::SetOwner(Owner); // Store the actor into the static list if the actor details are not available - if(Owner != nullptr) + if (Owner != nullptr) { if (std::find(AV2XSensor::mV2XActorContainer.begin(), AV2XSensor::mV2XActorContainer.end(), Owner) == AV2XSensor::mV2XActorContainer.end()) { @@ -51,10 +51,8 @@ void AV2XSensor::SetOwner(AActor *Owner) CaServiceObj->SetOwner(world, Owner); PathLossModelObj->SetOwner(Owner); } - } - FActorDefinition AV2XSensor::GetSensorDefinition() { return UActorBlueprintFunctionLibrary::MakeV2XDefinition(); @@ -88,7 +86,8 @@ void AV2XSensor::SetPropagationParams(const float TransmitPower, PathLossModelObj->SetParams(TransmitPower, ReceiverSensitivity, Frequency, combined_antenna_gain, path_loss_exponent, reference_distance_fspl, filter_distance, use_etsi_fading, custom_fading_stddev); } -void AV2XSensor::SetPathLossModel(const EPathLossModel path_loss_model){ +void AV2XSensor::SetPathLossModel(const EPathLossModel path_loss_model) +{ PathLossModelObj->SetPathLossModel(path_loss_model); } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2XSensor.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2XSensor.h index 89b6be27a..9ce46dd2a 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2XSensor.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2XSensor.h @@ -1,4 +1,4 @@ -// Copyright (c) 2024 Institut fuer Technik der Informationsverarbeitung (ITIV) at the +// Copyright (c) 2024 Institut fuer Technik der Informationsverarbeitung (ITIV) at the // Karlsruhe Institute of Technology // // This work is licensed under the terms of the MIT license. @@ -35,30 +35,30 @@ public: void SetCaServiceParams(const float GenCamMin, const float GenCamMax, const bool FixedRate); void SetPropagationParams(const float TransmitPower, - const float ReceiverSensitivity, - const float Frequency, - const float combined_antenna_gain, - const float path_loss_exponent, - const float reference_distance_fspl, - const float filter_distance, - const bool use_etsi_fading, - const float custom_fading_stddev); + const float ReceiverSensitivity, + const float Frequency, + const float combined_antenna_gain, + const float path_loss_exponent, + const float reference_distance_fspl, + const float filter_distance, + const bool use_etsi_fading, + const float custom_fading_stddev); void SetScenario(EScenario scenario); - //CAM params + // CAM params void SetAccelerationStandardDeviation(const FVector &Vec); void SetGNSSDeviation(const float noise_lat_stddev, - const float noise_lon_stddev, - const float noise_alt_stddev, - const float noise_head_stddev, - const float noise_lat_bias, - const float noise_lon_bias, - const float noise_alt_bias, - const float noise_head_bias); - void SetVelDeviation(const float noise_vel_stddev); + const float noise_lon_stddev, + const float noise_alt_stddev, + const float noise_head_stddev, + const float noise_lat_bias, + const float noise_lon_bias, + const float noise_alt_bias, + const float noise_head_bias); + void SetVelDeviation(const float noise_vel_stddev); void SetYawrateDeviation(const float noise_yawrate_stddev, const float noise_yawrate_bias); void SetPathLossModel(const EPathLossModel path_loss_model); - + virtual void PrePhysTick(float DeltaSeconds) override; virtual void PostPhysTick(UWorld *World, ELevelTick TickType, float DeltaTime) override; void SetOwner(AActor *Owner) override; @@ -68,10 +68,10 @@ private: CaService *CaServiceObj; PathLossModel *PathLossModelObj; - //store data + // store data static ActorV2XDataMap mActorV2XDataMap; FV2XData mV2XData; - //write + // write void WriteMessageToV2XData(const V2XDataList &msg_received_power_list); }; From b3f0dbea662cd75d04d60d372de05d28b285bb37 Mon Sep 17 00:00:00 2001 From: Daniel Grimm Date: Fri, 26 Apr 2024 16:26:54 +0200 Subject: [PATCH 16/99] remove doubled defs --- .../Carla/Actor/ActorBlueprintFunctionLibrary.h | 14 -------------- 1 file changed, 14 deletions(-) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.h index 61ad86586..e75a3fb25 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.h @@ -121,20 +121,6 @@ public: static FActorDefinition MakeCustomV2XDefinition(); - UFUNCTION(Category = "Carla Actor", BlueprintCallable) - static void MakeCustomV2XDefinition( - bool &Success, - FActorDefinition &Definition); - - static FActorDefinition MakeV2XDefinition(); - - UFUNCTION(Category = "Carla Actor", BlueprintCallable) - static void MakeV2XDefinition( - bool &Success, - FActorDefinition &Definition); - - static FActorDefinition MakeCustomV2XDefinition(); - UFUNCTION(Category = "Carla Actor", BlueprintCallable) static void MakeCustomV2XDefinition( bool &Success, From 441372b36993554c68c07ae61d5c32fb0d0cd67a Mon Sep 17 00:00:00 2001 From: Daniel Grimm Date: Sat, 27 Apr 2024 04:37:27 +0200 Subject: [PATCH 17/99] removed structs, simple calc --- .../Source/Carla/Sensor/V2X/PathLossModel.cpp | 32 ++- .../Source/Carla/Sensor/V2X/PathLossModel.h | 24 +- .../Carla/Sensor/V2X/VehicleObstacle.cpp | 239 ------------------ 3 files changed, 22 insertions(+), 273 deletions(-) delete mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/VehicleObstacle.cpp diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.cpp index 53e40ee69..79046a264 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.cpp @@ -274,6 +274,16 @@ void PathLossModel::EstimatePathStateAndVehicleObstacles(AActor *OtherActor, } } +double PathLossModel::CalcVehicleLoss(const double d1, const double d2, const double h) +{ + double V = h * sqrt(2.0 * (d1 + d2) / (lambda * d1 * d2)); + if (V >= -0.78) { + double T = std::pow(V - 0.1, 2) + 1.0; + return 6.9 + 20.0 * log10(sqrt(T + 1.0) + V - 0.1); + } + return 0.0; +} + double PathLossModel::CalculateNLOSvLoss(const FVector Source, const FVector Destination, const double TxHeight, @@ -281,7 +291,6 @@ double PathLossModel::CalculateNLOSvLoss(const FVector Source, const double RxDistance3d, std::vector &vehicle_obstacles) { - double vehicle_blockage_loss = 0.0; // convert all positions to meters FVector pos_tx = Source; @@ -293,21 +302,20 @@ double PathLossModel::CalculateNLOSvLoss(const FVector Source, pos_rx.X /= 100.0f; pos_rx.Y /= 100.0f; pos_rx.Z = RxHeight; - const double distTxRx{sqrt(std::pow(pos_rx.X - pos_tx.X, 2) + std::pow(pos_rx.Y - pos_tx.Y, 2))}; /*< ground distance */ - DiffractionObstacle Tx{0.0, pos_tx.Z}; - DiffractionObstacle Rx{distTxRx, pos_rx.Z}; - auto obsTop = buildTopObstacles(vehicle_obstacles, pos_tx, pos_rx); - - if (!obsTop.empty()) + double max_loss = 0.0; + for(auto veh_it = vehicle_obstacles.begin(); veh_it != vehicle_obstacles.end(); veh_it++) { - obsTop.push_front(Tx); - obsTop.push_back(Rx); - auto path = computeMultipleKnifeEdge(obsTop); - vehicle_blockage_loss = path.attenuation; + double dist_tx_veh = sqrt(std::pow(veh_it->X - pos_tx.X, 2) + std::pow(veh_it->Y - pos_tx.Y, 2)); + double dist_veh_rx = sqrt(std::pow(pos_rx.X - veh_it->X, 2) + std::pow(pos_rx.Y - veh_it->Y, 2)); + double cur_loss = CalcVehicleLoss(dist_tx_veh,dist_veh_rx,veh_it->Z); + if(cur_loss >= max_loss) + { + max_loss = cur_loss; + } } - return vehicle_blockage_loss; + return max_loss; } void PathLossModel::SetPathLossModel(const EPathLossModel path_loss_model) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.h index 1c43e58bc..2d798995f 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.h @@ -32,22 +32,6 @@ enum EScenario Urban }; -struct DiffractionObstacle -{ - DiffractionObstacle(double distTx, double height); - // meter - double d; // distance to transmitter - double h; // height of obstacle -}; - -struct DiffractionPath -{ - DiffractionPath(); - - double attenuation; - double d; // meter -}; - class PathLossModel { public: @@ -69,12 +53,8 @@ public: void SetPathLossModel(const EPathLossModel path_loss_model); private: - // multiple knife edge diffraction for NLOSv - double computeVehiclePathLoss(const FVector &pos_tx, const FVector &pos_rx, const double reference_z, std::vector &vehicle_obstacles); - double computeSimpleKnifeEdge(double heightTx, double heightRx, double heightObs, double distTxRx, double distTxObs); - DiffractionPath computeMultipleKnifeEdge(const std::list &obs); - std::list buildTopObstacles(const std::vector &vehicles, const FVector &pos_tx, const FVector &pos_rx); - + // diffraction for NLOSv + double CalcVehicleLoss(const double d1, const double d2, const double h); // powers float CalculateReceivedPower(AActor *OtherActor, const float OtherTransmitPower, diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/VehicleObstacle.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/VehicleObstacle.cpp deleted file mode 100644 index fd27ed80e..000000000 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/VehicleObstacle.cpp +++ /dev/null @@ -1,239 +0,0 @@ - -// Copyright (c) 2024 Institut fuer Technik der Informationsverarbeitung (ITIV) at the -// Karlsruhe Institute of Technology -// -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#pragma once - -#include -#include -#include -#include - -#include "PathLossModel.h" - -namespace -{ - auto compareDistance = [](const DiffractionObstacle &a, const DiffractionObstacle &b) - { return a.d < b.d; }; - auto compareHeight = [](const DiffractionObstacle &a, const DiffractionObstacle &b) - { return a.h < b.h; }; - - using ObstacleIterator = std::list::const_iterator; - ObstacleIterator findMainObstacle(ObstacleIterator, ObstacleIterator); - ObstacleIterator findSecondaryObstacle(ObstacleIterator, ObstacleIterator); -} // namespace - -DiffractionObstacle::DiffractionObstacle(double distTx, double height) : d(distTx), h(height) -{ -} - -DiffractionPath::DiffractionPath() : attenuation(0.0), d(0.0) -{ -} - -double PathLossModel::computeSimpleKnifeEdge(double heightTx, double heightRx, double heightObs, double distTxRx, double distTxObs) -{ - // following calculations are similar to equation 29 of ITU-R P.526-13: - // v = sqrt(2d/lambda * alpha1 * alpha2) - // - // with sinus approximation for small angles: - // alpha1 =~ sin alpha1 = h / d1 - // alpha2 =~ sin alpha2 = h / d2 - // - // v = sqrt(2d / lambda * h / d1 * h / d2) = sqrt(2) * h / sqrt(lambda * d1 * d2 / d) - // - // with d1 = distTxObs, d2 = distRxObs, d = distTxRx, - - // distance between Rx and obstacle - const double distRxObs = distTxRx - distTxObs; - // signed height relative to the line connecting Tx and Rx at obstacle position - const double obsHeightTxRxLine = (heightRx - heightTx) / distTxRx * distTxObs + heightTx; - const double h = heightObs - obsHeightTxRxLine; - // calculate the Fresnel ray - const double r = sqrt(lambda * distTxObs * distRxObs / distTxRx); - static const double root_two = sqrt(2.0); - const double v = root_two * h / r; - - double loss = 0.0; - if (v > -0.78) - { - // approximation of Fresnel-Kirchoff loss given by ITU-R P.526, equation 31 (result in dB): - // J(v) = 6.9 + 20 log(sqrt((v - 01)^2 + 1) + v - 0.1) - loss = 6.9 + 20.0 * log10(sqrt(std::pow(v - 0.1, 2) + 1.0) + v - 0.1); - } - - return loss; -} - -DiffractionPath PathLossModel::computeMultipleKnifeEdge(const std::list &obs) -{ - DiffractionPath path; - - // determine main and secondary obstacles - std::vector mainObs; - mainObs.push_back(obs.begin()); // Tx - for (ObstacleIterator it = obs.begin(); it != obs.end();) - { - it = findMainObstacle(it, obs.end()); - if (it != obs.end()) - { - mainObs.push_back(it); - } - } - // NOTE: Rx is added by loop as last main obstacle - struct SecondaryObstacle - { - SecondaryObstacle(ObstacleIterator tx, ObstacleIterator obs, ObstacleIterator rx) : tx(tx), obstacle(obs), rx(rx) {} - ObstacleIterator tx; - ObstacleIterator obstacle; - ObstacleIterator rx; - }; - - std::vector secObs; - std::vector mainObsDistances; - for (std::size_t i = 0, j = 1; j < mainObs.size(); ++i, ++j) - { - const double d = mainObs[j]->d - mainObs[i]->d; - path.d += sqrt(std::pow(d, 2) + std::pow(mainObs[j]->h - mainObs[i]->h, 2)); - mainObsDistances.push_back(d); - - const auto delta = std::distance(mainObs[i], mainObs[j]); - if (delta == 2) - { - // single other obstacle between two main obstacles - secObs.emplace_back(mainObs[i], std::next(mainObs[i]), mainObs[j]); - } - else if (delta > 2) - { - secObs.emplace_back(mainObs[i], findSecondaryObstacle(mainObs[i], mainObs[j]), mainObs[j]); - } - } - - // attenuation due to main obstacles - double attMainObs = 0.0; - for (std::size_t i = 0; i < mainObs.size() - 2; ++i) - { - const double distTxObs = mainObsDistances[i]; - const double distTxRx = distTxObs + mainObsDistances[i + 1]; - attMainObs += computeSimpleKnifeEdge(mainObs[i]->h, mainObs[i + 2]->h, mainObs[i + 1]->h, distTxRx, distTxObs); - } - - // attenuation due to secondary obstacles - double attSecObs = 0.0; - for (const SecondaryObstacle &sec : secObs) - { - const double distTxRx = sec.rx->d - sec.tx->d; - const double distTxObs = sec.obstacle->d - sec.tx->d; - attSecObs += computeSimpleKnifeEdge(sec.tx->h, sec.rx->h, sec.obstacle->h, distTxRx, distTxObs); - } - - // correction factor C (see eq. 46 in ITU-R P.526-13) - double C = mainObs.back()->d - mainObs.front()->d; // distance between Tx and Rx - for (double d : mainObsDistances) - { - C *= d; - } - double pairwiseDistProduct = 1.0; - for (std::size_t i = 1; i < mainObsDistances.size(); ++i) - { - pairwiseDistProduct *= mainObsDistances[i - 1] + mainObsDistances[i]; - } - C /= mainObsDistances.front() * mainObsDistances.back() * pairwiseDistProduct; - - path.attenuation = attMainObs + attSecObs - 10.0 * log10(C); - return path; -} - -std::list PathLossModel::buildTopObstacles(const std::vector &vehicles, const FVector &pos_tx, const FVector &pos_rx) -{ - std::list diffTop; - const double vx = pos_rx.X - pos_tx.X; - const double vy = pos_rx.Y - pos_tx.Y; - - for (auto vehicle : vehicles) - { - const double midpoint_x = vehicle.X; - const double midpoint_y = vehicle.Y; - const double k = (midpoint_x * vx - vy * pos_tx.Y + vy * midpoint_y - pos_tx.X * vx) / (std::pow(vx, 2) + std::pow(vy, 2)); - if (k < 0.0 || k > 1.0) - continue; /*< skip points beyond the ends of TxRx line segment */ - const double d = k * sqrt(std::pow(vx, 2) + std::pow(vy, 2)); - diffTop.emplace_back(d, vehicle.Z); - } - - diffTop.sort(compareDistance); - return diffTop; -} - -namespace -{ - - ObstacleIterator findMainObstacle(ObstacleIterator begin, ObstacleIterator end) - { - ObstacleIterator mainIterator = end; - double mainAngle = -std::numeric_limits::infinity(); - - if (begin != end) - { - for (ObstacleIterator it = std::next(begin); it != end; ++it) - { - double angle = (it->h - begin->h) / (it->d - begin->d); - if (angle > mainAngle) - { - mainIterator = it; - mainAngle = angle; - } - } - } - - return mainIterator; - } - - ObstacleIterator findSecondaryObstacle(ObstacleIterator first, ObstacleIterator last) - { - ObstacleIterator secIterator = last; - double secHeightGap{std::numeric_limits::infinity()}; - - const double distFirstLast = last->d - first->d; - const double heightFirstLast = last->h - first->h; - const auto offset = first->h * last->d - first->d * last->h; - for (ObstacleIterator it = std::next(first); it != last; ++it) - { - const double heightGap = ((it->d * heightFirstLast + offset) / distFirstLast) - it->h; - if (heightGap < secHeightGap) - { - secIterator = it; - secHeightGap = heightGap; - } - } - - return secIterator; - } - -} // namespace - -// statistical model from ETSI TR 103 257-1 V1.1.1 (2019-05) -double PathLossModel::MakeVehicleBlockageLoss(double TxHeight, double RxHeight, double obj_height, double obj_distance) -{ - // according to ETSI, stochastic method - if (TxHeight > obj_height && RxHeight > obj_height) - { - // no blocking if higher than obj - return 0.0; - } - else if (TxHeight < obj_height && RxHeight < obj_height) - { - // worst case: obj is higher than both tx and rx - float mean = 9.0f + fmax(0.0f, 15.0f * log10(obj_distance) - 41.0f); - return mRandomEngine->GetNormalDistribution(mean, 4.5f); - } - else - { - // something in between - float mean = 5.0f + fmax(0.0f, 15.0f * log10(obj_distance) - 41.0f); - return mRandomEngine->GetNormalDistribution(mean, 4.0f); - } -} From 7a540559a9022cd0281158a55cc142d8981de5b6 Mon Sep 17 00:00:00 2001 From: Daniel Grimm Date: Mon, 29 Apr 2024 08:32:20 +0200 Subject: [PATCH 18/99] function name camel case --- .../Plugins/Carla/Source/Carla/Sensor/V2X/CaService.cpp | 4 ++-- .../Plugins/Carla/Source/Carla/Sensor/V2X/CaService.h | 2 +- .../Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.cpp | 4 ++-- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/CaService.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/CaService.cpp index 0c4ea10ef..7e224c612 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/CaService.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/CaService.cpp @@ -12,7 +12,7 @@ #include static const float scLowFrequencyContainerInterval = 0.5; -ITSContainer::SpeedValue_t CaService::buildSpeedValue(const float vel) +ITSContainer::SpeedValue_t CaService::BuildSpeedValue(const float vel) { static const float lower = 0.0; // meter_per_second static const float upper = 163.82; // meter_per_second @@ -474,7 +474,7 @@ void CaService::AddBasicVehicleContainerHighFrequency(CAMContainer::HighFrequenc bvc.heading.headingConfidence = ITSContainer::HeadingConfidence_equalOrWithinOneDegree; // TODO // speed // speed with noise - bvc.speed.speedValue = buildSpeedValue(ComputeSpeed()); + bvc.speed.speedValue = BuildSpeedValue(ComputeSpeed()); bvc.speed.speedConfidence = ITSContainer::SpeedConfidence_equalOrWithInOneCentimerterPerSec * 3; // TODO // direction bvc.driveDirection = (mVehicle->GetVehicleForwardSpeed() / 100.0f) >= 0.0 ? ITSContainer::DriveDirection_forward : ITSContainer::DriveDirection_backward; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/CaService.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/CaService.h index 070f185ad..9f644a181 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/CaService.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/CaService.h @@ -128,5 +128,5 @@ private: // random for noise URandomEngine *mRandomEngine; - ITSContainer::SpeedValue_t buildSpeedValue(const float vel); + ITSContainer::SpeedValue_t BuildSpeedValue(const float vel); }; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.cpp index 79046a264..a6b404b80 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.cpp @@ -278,7 +278,7 @@ double PathLossModel::CalcVehicleLoss(const double d1, const double d2, const do { double V = h * sqrt(2.0 * (d1 + d2) / (lambda * d1 * d2)); if (V >= -0.78) { - double T = std::pow(V - 0.1, 2) + 1.0; + double T = std::pow(V - 0.1, 2); return 6.9 + 20.0 * log10(sqrt(T + 1.0) + V - 0.1); } return 0.0; @@ -363,7 +363,7 @@ float PathLossModel::ComputeLoss(AActor *OtherActor, FVector Source, FVector Des } else { - // fspl + multi knife edge + // fspl + knife edge // fspl double free_space_loss = 20.0 * log10(Distance3d) + 20.0 * log10(4.0 * M_PI / lambda); // add the knife edge vehicle blockage loss From 27b1490990b75d12cb311ea4bb89031d3bccd92f Mon Sep 17 00:00:00 2001 From: Blyron Date: Mon, 6 May 2024 16:29:17 +0200 Subject: [PATCH 19/99] Fix OSM2ODR build --- Util/BuildTools/BuildOSM2ODR.bat | 17 ++++++----------- 1 file changed, 6 insertions(+), 11 deletions(-) diff --git a/Util/BuildTools/BuildOSM2ODR.bat b/Util/BuildTools/BuildOSM2ODR.bat index 5a4fb36e0..77a4eff2b 100644 --- a/Util/BuildTools/BuildOSM2ODR.bat +++ b/Util/BuildTools/BuildOSM2ODR.bat @@ -71,7 +71,7 @@ rem ============================================================================ rem Set the visual studio solution directory rem set OSM2ODR_VSPROJECT_PATH=%INSTALLATION_DIR:/=\%osm2odr-visualstudio\ -set OSM2ODR_SOURCE_PATH=%INSTALLATION_DIR:/=\%om2odr-source\ +set OSM2ODR_SOURCE_PATH=%INSTALLATION_DIR:/=\%osm2odr-source\ set OSM2ODR_INSTALL_PATH=%ROOT_PATH:/=\%PythonAPI\carla\dependencies\ set OSM2ODR__SERVER_INSTALL_PATH=%ROOT_PATH:/=\%Unreal\CarlaUE4\Plugins\Carla\CarlaDependencies set CARLA_DEPENDENCIES_FOLDER=%ROOT_PATH:/=\%Unreal\CarlaUE4\Plugins\Carla\CarlaDependencies\ @@ -92,24 +92,19 @@ if %REMOVE_INTERMEDIATE% == true ( rem Build OSM2ODR if %BUILD_OSM2ODR% == true ( - cd "%OSM2ODR_SOURCE_PATH%" + cd "%INSTALLATION_DIR%" if not exist "%OSM2ODR_SOURCE_PATH%" ( curl --retry 5 --retry-max-time 120 -L -o OSM2ODR.zip https://github.com/carla-simulator/sumo/archive/%CURRENT_OSM2ODR_COMMIT%.zip tar -xf OSM2ODR.zip del OSM2ODR.zip - ren sumo-%CURRENT_OSM2ODR_COMMIT% %OSM2ODR_SOURCE_PATH% + ren sumo-%CURRENT_OSM2ODR_COMMIT% osm2odr-source ) - + + cd .. if not exist "%OSM2ODR_VSPROJECT_PATH%" mkdir "%OSM2ODR_VSPROJECT_PATH%" cd "%OSM2ODR_VSPROJECT_PATH%" - echo.%GENERATOR% | findstr /C:"Visual Studio" >nul && ( - set PLATFORM=-A x64 - ) || ( - set PLATFORM= - ) - - cmake -G %GENERATOR% %PLATFORM%^ + cmake -G %GENERATOR% -A x64^ -DCMAKE_CXX_FLAGS_RELEASE="/MD /MP"^ -DCMAKE_INSTALL_PREFIX="%OSM2ODR_INSTALL_PATH:\=/%"^ -DPROJ_INCLUDE_DIR=%INSTALLATION_DIR:/=\%\proj-install\include^ From 9037124f594daa09f745f00d7125a513cac8aaaf Mon Sep 17 00:00:00 2001 From: Blyron Date: Tue, 7 May 2024 10:33:20 +0200 Subject: [PATCH 20/99] Fix compilation issue --- .../Carla/Source/Carla/Sensor/V2X/PathLossModel.cpp | 12 +++++++----- .../Carla/Source/Carla/Sensor/V2X/PathLossModel.h | 2 +- .../Carla/Vehicle/CustomTerrainPhysicsComponent.cpp | 4 ++-- 3 files changed, 10 insertions(+), 8 deletions(-) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.cpp index a6b404b80..bd80f114e 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.cpp @@ -6,6 +6,8 @@ #include "Carla.h" #include "Carla/Game/CarlaEpisode.h" +#include "Math/UnrealMathUtility.h" + #include "PathLossModel.h" #include #include @@ -332,7 +334,7 @@ float PathLossModel::ComputeLoss(AActor *OtherActor, FVector Source, FVector Des EPathState state; float PathLoss = 0.0; - double VehicleBlockageLoss; + double VehicleBlockageLoss = 0.0; float ShadowFadingLoss = 0.0; // state and vehicle obstacles are call-by-reference @@ -365,7 +367,7 @@ float PathLossModel::ComputeLoss(AActor *OtherActor, FVector Source, FVector Des { // fspl + knife edge // fspl - double free_space_loss = 20.0 * log10(Distance3d) + 20.0 * log10(4.0 * M_PI / lambda); + double free_space_loss = 20.0 * log10(Distance3d) + 20.0 * log10(4.0 * PI / lambda); // add the knife edge vehicle blockage loss PathLoss = free_space_loss + CalculateNLOSvLoss(Source, Destination, TxHeight, RxHeight, Distance3d, vehicle_obstacles); } @@ -446,7 +448,7 @@ bool PathLossModel::GetLocationIfVehicle(const FVector CurrentActorLocation, con void PathLossModel::CalculateFSPL_d0() { - m_fspl_d0 = 20.0 * log10(reference_distance_fspl) + 20.0 * log10(Frequency) + 20.0 * log10(4.0 * M_PI / c_speedoflight); + m_fspl_d0 = 20.0 * log10(reference_distance_fspl) + 20.0 * log10(Frequency) + 20.0 * log10(4.0 * PI / c_speedoflight); } // Following ETSI TR 103 257-1 V1.1.1 (2019-05: from WINNER Project Board: "D5.3 - WINNER+ Final Channel Models", 30 06 2010. @@ -563,7 +565,7 @@ double PathLossModel::CalculateTwoRayPathLoss(double Distance3d, double TxHeight double gamma = (sin_theta - sqrt(epsilon_r - std::pow(cos_theta, 2))) / (sin_theta + sqrt(epsilon_r - std::pow(cos_theta, 2))); - double phi = (2.0 * M_PI / lambda * (Distance3d - d_refl)); + double phi = (2.0 * PI / lambda * (Distance3d - d_refl)); - return 20 * log10(4.0 * M_PI * d_ground / lambda * 1.0 / sqrt(std::pow(1 + gamma * cos(phi), 2) + std::pow(gamma, 2) * std::pow(sin(phi), 2))); + return 20 * log10(4.0 * PI * d_ground / lambda * 1.0 / sqrt(std::pow(1 + gamma * cos(phi), 2) + std::pow(gamma, 2) * std::pow(sin(phi), 2))); } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.h index 2d798995f..2e9fd6071 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.h @@ -7,7 +7,7 @@ #pragma once #include -#include + using ActorPowerMap = std::map; using ActorPowerPair = std::pair; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CustomTerrainPhysicsComponent.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CustomTerrainPhysicsComponent.cpp index 62a994b51..e199f46bf 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CustomTerrainPhysicsComponent.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CustomTerrainPhysicsComponent.cpp @@ -1310,13 +1310,13 @@ void UCustomTerrainPhysicsComponent::BeginPlay() SparseMap.SavePath = SavePath; // Creating the FileManager IPlatformFile& FileManager = FPlatformFileManager::Get().GetPlatformFile(); - if( FileManager.CreateDirectory(*SavePath)){ + /*if( FileManager.CreateDirectory(*SavePath)){ UE_LOG(LogCarla, Warning, TEXT("Folder was created at %s"), *SavePath); }else{ UE_LOG(LogCarla, Error, TEXT("Folder was not created at %s"), *SavePath); - } + }*/ if(bUseDeformationPlane){ DeformationPlaneActor = GetWorld()->SpawnActor(); From 73d66006fad2f3091541c7f76064b292d526edcf Mon Sep 17 00:00:00 2001 From: Blyron Date: Mon, 13 May 2024 16:08:48 +0200 Subject: [PATCH 21/99] add removing houdini to be removed --- Util/BuildTools/BuildCarlaUE4.bat | 1 + 1 file changed, 1 insertion(+) diff --git a/Util/BuildTools/BuildCarlaUE4.bat b/Util/BuildTools/BuildCarlaUE4.bat index cce890090..cf475cf27 100644 --- a/Util/BuildTools/BuildCarlaUE4.bat +++ b/Util/BuildTools/BuildCarlaUE4.bat @@ -110,6 +110,7 @@ if %REMOVE_INTERMEDIATE% == true ( "%UE4_PROJECT_FOLDER%Intermediate", "%UE4_PROJECT_FOLDER%Plugins\Carla\Binaries", "%UE4_PROJECT_FOLDER%Plugins\Carla\Intermediate", + "%UE4_PROJECT_FOLDER%Plugins\HoudiniEngine\", "%UE4_PROJECT_FOLDER%.vs" ) do ( if exist %%G ( From 12f09009abe5b144cb8f2acce62d809b11f48b9a Mon Sep 17 00:00:00 2001 From: Blyron Date: Mon, 13 May 2024 16:17:26 +0200 Subject: [PATCH 22/99] remove Houdini in Linux --- Util/BuildTools/BuildCarlaUE4.sh | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/Util/BuildTools/BuildCarlaUE4.sh b/Util/BuildTools/BuildCarlaUE4.sh index 19f204447..4db570edb 100755 --- a/Util/BuildTools/BuildCarlaUE4.sh +++ b/Util/BuildTools/BuildCarlaUE4.sh @@ -128,6 +128,10 @@ if ${REMOVE_INTERMEDIATE} ; then rm -Rf ${UE4_INTERMEDIATE_FOLDERS} + cd Plugins + rm -Rf HoudiniEngine + cd .. + popd >/dev/null fi From 142ae0f941081a53d14063fde509f09e7bf2eb13 Mon Sep 17 00:00:00 2001 From: Daniel Date: Tue, 14 May 2024 18:56:45 +0200 Subject: [PATCH 23/99] Fixed wrong sha check sha256sum outputs failing the string check --- Util/BuildTools/Setup.sh | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Util/BuildTools/Setup.sh b/Util/BuildTools/Setup.sh index e91d149d7..64774d017 100755 --- a/Util/BuildTools/Setup.sh +++ b/Util/BuildTools/Setup.sh @@ -94,16 +94,16 @@ for PY_VERSION in ${PY_VERSION_LIST[@]} ; do log "Retrieving boost." start=$(date +%s) - wget "https://archives.boost.io/release/${BOOST_VERSION}/source/${BOOST_PACKAGE_BASENAME}.tar.gz" || true + wget "https://archives.boost.io/release/${BOOST_VERSION}/source/${BOOST_PACKAGE_BASENAME}.tar.gz" -O ${BOOST_PACKAGE_BASENAME}.tar.gz || true end=$(date +%s) echo "Elapsed Time downloading from boost webpage: $(($end-$start)) seconds" # try to use the backup boost we have in Jenkins - if [ ! -f "${BOOST_PACKAGE_BASENAME}.tar.gz" ] || [[ $(sha256sum "${BOOST_PACKAGE_BASENAME}.tar.gz") != "${BOOST_SHA256SUM}" ]] ; then + if [ ! -f "${BOOST_PACKAGE_BASENAME}.tar.gz" ] || [[ $(sha256sum "${BOOST_PACKAGE_BASENAME}.tar.gz" | cut -d " " -f 1 ) != "${BOOST_SHA256SUM}" ]] ; then log "Using boost backup" start=$(date +%s) - wget "https://carla-releases.s3.us-east-005.backblazeb2.com/Backup/${BOOST_PACKAGE_BASENAME}.tar.gz" || true + wget "https://carla-releases.s3.us-east-005.backblazeb2.com/Backup/${BOOST_PACKAGE_BASENAME}.tar.gz" -O ${BOOST_PACKAGE_BASENAME}.tar.gz || true end=$(date +%s) echo "Elapsed Time downloading from boost carla backup in backblaze: $(($end-$start)) seconds" From 8774a16cb6d077db9252eeb2a0d87ec3f2ae5f8f Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Thu, 16 May 2024 10:28:05 +0200 Subject: [PATCH 24/99] updated patchelf version --- Util/BuildTools/Setup.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Util/BuildTools/Setup.sh b/Util/BuildTools/Setup.sh index 64774d017..f68dd378f 100755 --- a/Util/BuildTools/Setup.sh +++ b/Util/BuildTools/Setup.sh @@ -761,7 +761,7 @@ cp -p ${PROJ_SERVER_LIB} ${LIBCARLA_INSTALL_SERVER_FOLDER}/lib/ # -- Get and compile patchelf -------------------------------------------------- # ============================================================================== -PATCHELF_VERSION=0.12 +PATCHELF_VERSION=0.14 PATCHELF_REPO=https://github.com/NixOS/patchelf/archive/${PATCHELF_VERSION}.tar.gz PATCHELF_TAR=${PATCHELF_VERSION}.tar.gz From 22fd085f672a1074d4b7ab49a89242325b90ff18 Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Thu, 16 May 2024 10:28:36 +0200 Subject: [PATCH 25/99] avoid using python system version to audit wheel --- Util/BuildTools/BuildPythonAPI.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Util/BuildTools/BuildPythonAPI.sh b/Util/BuildTools/BuildPythonAPI.sh index 8a46145de..f5bbb5c61 100755 --- a/Util/BuildTools/BuildPythonAPI.sh +++ b/Util/BuildTools/BuildPythonAPI.sh @@ -105,7 +105,7 @@ if ${BUILD_PYTHONAPI} ; then cp dist/.tmp/$(ls dist/.tmp | grep .whl) dist else /usr/bin/env python${PY_VERSION} setup.py bdist_egg bdist_wheel --dist-dir dist/.tmp --plat ${TARGET_WHEEL_PLATFORM} - /usr/bin/env python3 -m auditwheel repair --plat ${TARGET_WHEEL_PLATFORM} --wheel-dir dist dist/.tmp/$(ls dist/.tmp | grep .whl) + /usr/bin/env python${PY_VERSION} -m auditwheel repair --plat ${TARGET_WHEEL_PLATFORM} --wheel-dir dist dist/.tmp/$(ls dist/.tmp | grep .whl) fi rm -rf dist/.tmp From 6886d25c13097dbb94b84afda513bf6ecc4ea73e Mon Sep 17 00:00:00 2001 From: Blyron <53337103+Blyron@users.noreply.github.com> Date: Fri, 17 May 2024 11:10:58 +0200 Subject: [PATCH 26/99] Aaron/fixdigitaltwins windows (#7672) * Fix OSM2ODR build * Fixing UE4 DigitalTwins in Windows * Deal windows specific code until find workaround on saving files * Remove comments --------- Co-authored-by: LuisPoveda <101111439+LuisPoveda@users.noreply.github.com> --- .../BP_OpenDriveToMap.uasset | Bin 770195 -> 770634 bytes .../Blueprints/BP_BuildingGenerator.uasset | Bin 1140264 -> 1164904 bytes .../Content/Python/generate_tile.py | 3 ++- .../CarlaTools/Private/OpenDriveToMap.cpp | 6 ++++-- 4 files changed, 6 insertions(+), 3 deletions(-) diff --git a/Unreal/CarlaUE4/Plugins/CarlaTools/Content/OnroadMapGenerator/BP_OpenDriveToMap.uasset b/Unreal/CarlaUE4/Plugins/CarlaTools/Content/OnroadMapGenerator/BP_OpenDriveToMap.uasset index 94bee4e500d75168ea4e54ee8cdb7fd28929ac40..255471a5f8d54a92c69fd7ee013a1ab9cad3976e 100644 GIT binary patch literal 770634 zcmdqK2Yehw^1nR`29r$A(I%PToNc0&jGTjPY&ekD(%KSMLc4Mx9VX|@!I5+3NIr5t za?WtT5e-L9M~?6JnV!^ZZX&{ry+V2ix~7yY!uTFRXd~CvW!JYAvPh{J_3Lf7xTnieDY!{r!;rci6Uz z(vI42vzbRssJ`y47uUb$l}A76wxiOve7WMhdnasrRaw^_XFPY<;`p{oTQcCa8@o+7 zc8l8%dG@+XM*lWs6{YQ#`t{jEOKvQFd)-q{Pj=sIgKd=ddCiSWJ}x@r+f`rhf62(Z z%KB`lv_8kJ;H{wR_{N5WE?vBVYUp7x&+DP5{{8w78&=Y9Sn=?og9jB2A3U;O*?_^t zBL@yF9W=QA@Z#Y@ai2LVFlnOaou$Y1cJjRK-}5{=T<^uag9RrFl5c$X=yPxGxW_T; z|M~vgUi)hQ=~MRkwQu>NubWpm{-h0W+Hh@E;ZY9_i1K;i_O~j*yF+!CJ-BK{5i$J_ zdPY^<-e2z;cgyaS8x^llxZwmPRa@29Z)$DTxOghjTpQO2k7{mgX{hcyuDo(ob3B=> zEN)4q64jM6RGZg){)gA^6S1Djl9P#XiAAD0UHRB}Lt7_%wkD$8n{6MIxQ#~V`KH%p#)yyw#J$JWlNNfk9N7~uVU=!I`? z0Q!`w=GvxIdirX(n`*p|-#Dmb^-#7y_q`idpYZ59*{Qxp@M;Hk|7_iGR%3Hw>V#SQ zC8|>1kLA60?Gegz^6Cgn1g55H>uOWAiKKUQ%Qe5R5k~ao+dFFaBg;1lB~M(Ks%dO+ zEZ3ZYC%X#%D+{U^6Hq-yIE-XVkjbr?p&`a89uIT5cbt@e6#Icp_! zUO(@Y`g?kE*Wc^e^xE!dzyAHa6&CE6@^AZlHz&rgRdS~v^Wee_xdD|U2c@6G{dl#NRw1&Hp-u?9@?_jM)R#mmsSJ1WRHoJ1cihhc; zfYJ+Y-q)jl{{pU$tWx=k#*#!b z)!ewyn^pSgCaa~B$2HDNc(Dzp&hk;Kt1HXu8sjPdkM~6BUO!+>Mk=|yA*KJ`{*Rq- zJ)$zQdS1MtDp5VLwxOgp*;E%_=pC}bmtFn#)@i1Dl{>8dt^d^Ath|-F{P75KHqsxD!K?C8UZdA616%DS z^taxNdv*F3*L^}5DeqlDt?=Ti>ilP z{T`Y0@)rTkaiRyUI$g7AG^*}ffBtHBpZ&?CnA3F6wom&5$&)WU-bv$L`pV~5(#@&v znpE9g-zF~^f2YryWJP>dUA%jBqI*85U*5XI2X;ehTK$1QU=r1CK({}) zskhI2D>162w%U8P>&8=QNNcHy@l;K6Z0)S(c=JN9`vHA7K`vTzlirw~{cpyAv?fhi znAEhGmS|2g!i!QX@0dZQVqsIlTWzh=-rh`wW{rziCq~YeQ(!Dqul>0duk*HeW9AnS z6H@csl3Hd})g~YBhRZ!m-lx}R)oOp57U`jN-mTf?#^X?Xv#dhc>&x1j-=DI#-_RUh zX=Sl@?I!EgP_V7H_v7BXu8c`*lcQ3{uJO;akTm6`eN?6YwB*tse4(0%D_qeywsDSk z>`{vr`Ewvhli^Av8oXJfx0>k>z4bxD*^*2()=TiKy_$c&9`naz;<`6lJai}%=`W!tPN^Am|C@1~YM8~Zc0LJFX%u{q@}-?jf1 zsE%2dGO=c1vbHMeUG?yFPcXYo-GzMUpX#nz;tSzIXQ|?Iyptwu`>QV(3sVX2llM-( zpSBk1!FcL@IKKD&sG?%;Z_}RL4vtDmR<+d0(e>4gG=Hs{?A_LQ$39!T+&V-DixM(% zQv9&YpP*jNYj<4RJsa2Ay$rlxo?ZXrEi&-TR%M_axYn4x7)-RcBkiNfSXKIl=E8L@ z`T<q_-0^!_uKEg?hvL^x*$>2A~E(o-QvdjdM)HKO6>IgKR@msE>TunmndCO zn@lA$@Xr5c`Mw$aF>5fcHd*C2BoqIMJ#QGpGNN^mC5E!yzLCy>e&YY`6PW5&wcuLRBUo1i{HkE?1HyHa@;Q4XBC7EsL`>F5=6>`8#w0c z4PI@pKr4}Ofi>Q3s>v=O`|nf8S>U-lf4_2@aFfQ$b8k;Sol<+!vpw1%=TK0KABdlx zAsl0+{72&ZRTkAXRl-tt@*@YF z^-{*H2eCqn+vM!V=K73=Y;)*Oy}E~c2&%Jl8F-tYzsmC&(mYOrQQK6vkY$R$cF910 zaFdNU$>4GrT_rM*r}iDSV@BPwIV^X5E7_2e+)TO?r`{OZemWNIai78ethfY3`R@zTufnHB3YAB`LGMG_%UO| z{iUQYr{xW99q-S;j6$bO@BhZ&@aUuq?OB_uDXvLW%^lxZ+*ns9XI}nzM&U;ue*CJ8 zF__XaE7csYk}>pGmKn&iD^_?H2f0;SO&gnNZpuLEHLGefyoTbq{QkI2%O$n<^heJ**RM5f1-;wu+3$KEZ^HPJNzX% zc70R*a-PUyVd$-@Y8K&WDiW;(3MWd zGjDBE)_%a+i+0#NgH|{)X|!gpu*o#!HK@doua0l5PI!yo`*5Bw7j94$1g}n3#hVlv zcR_e>hk>Vjw|TmxMah$U*3_obSdV&V&k6OV70U&=TPwTZ`~ios_zRlBGOso7$^CAf z5o(Erp_8o$Z(h6F2Pnv(uoKcXANh75YP4F5x;bjI_roveob1@;5~kG7X^3mtl<@nU z^j4m;?QN)Hg@ID>?tbj@p}1dqz&)Q| zM0g0lx>lrQOngU#N#Q+zb@}S9%}L^!zC!ZO-T0bbXqplQP8%>j-TQmB_bzzWrTOtm ze|{fu=7&Xo&2p%TUlt`&TFEvz)$~T~{Zqo3IJxk%v|8$W(Hb`m@rS!{euE;U)vZhE zVOQLEH|#2D(T15QdoRB8YhQFoskiAS>&$1mmsY#zdzZ$=`(PP@XDzY)=*ipjPbsD9 zAbCnvO`<+tIc9)&`vYfpLs2pH64fP*iVREVmN(39^zN!$^A}f!EVoGU+4IcE3lBve za?R<jA>fx%C!dZol@|d`TNB$zv7o3TRU6fzWRhrOkj`h z?o$02>-9ukGU0vNbB${mpdfmN2a@m}*k=5{*vKtysP?{IfAUL25dwR8Tdd?mA~mJV z9*fF}H%TwCXtf?2=gJu|VvpMDY6V+fT|DPOB)m=85hDme`1 zx74?K2a{ese|N;Xw7FT~ccNse&HDZ9k69?_;t%FC2XFKyrnxjLW5kH@jj2$YH?T|U zbiX0<)HEkk`&=G#GDTABy4Ab#l6SB5M??!w@1Re9-Pmuedsq}lC=+fe>eZgLEJwIBPSw)gB*E^nk+_nLZ)TqzTYmZs}WExji zuHCYQ{&tzTPoN5aF1Eo3U*o~eW>wu$g6bEyJLe|z2K{V+pNK9ptMuGCP}i{J4|&6i3YS&4h6uF?JT9n(ZJ3(2zBB#~$Y zhm^d}Z~yWX3{g%x8GAY2$Z_6B+q8!|PLfgAXiaJKF8QNr%(m?zOL%k^p;AkXN;iV{ z9XRSX_8M}w!rw}zx7Geu>Q{?qf6d&_f!jLJ^Vc5rDQYIbaYK?ka<5H7vg!t7Tzo;R zll}6}J#KA_P}|Uo@ZGtGToOj`jkk3Cl*Ilm#Js)hFTb@v9zj6YB;EIZymMb%VF!$E zR%Q^J-6`?>7a=)g^0FB8mC4MP|MIR=3jQR@vJ>9@m3>abvIG^E&#tIRG?d~{t~o09 z2#PDn8Pm|1@}4`gs7t7g{z<5EZ2{xddq@7r1`WnLXvD*QYBvVGiw#0SrrPH-`HH8^oo0rU+m+yUGlCr?3|zcp7>c>Y_+a* z>uy}5i_acE$LVPEz;An{&%jV##=7>l>hd#u`S#0AO(vR45{gV|gU<$seL_iA+?zk- z;yBE;tS2$_byI3FrNEF;M@#bD#g$ zX>{Dq9EDu2@fQvM!bjKXwRp1vfiht07AMPmbgh|uebX9(_HMgjn~Tw$?L?cs6EFI< z4&#L6x|0NlpK*RM2H#Jy;YoUP4oYs%;IxYP{s-Oopi5|MDr&4==v6#;`6_rBzMMG6 z`IGVM_&PnEl=dKQ+~?s#=}0J~?cM!-#Yx!0jOexZ>uukB=PI^9wKr|6<(4o*a>pLt z`D)YGa0!&_`->A6oVn1EYHGF0gU?vBh#6|@bQ5eXxRCIa*JY=*ug9!w-g}$=x#x7a zr29P*oCEWA+G?}cT$O39aQrFbUcrwLmI8X-&36v<_p{xj3o7=0d+Kgm}z5wQ^PWA&{$-Pha14}r?ywP-^xp?!1t559}pwB_;f?i6B6rOMY7 zb(+t{=~f|q=lYd?^jituSYdcq&Dre@pIr84jQ8&gN8Rf)Bb0+K>G}ErAL4AvTS|Dt zH!HmaF+!$VsT}srN~0OQ@rn7qksTYKm8kO;FFbk&CXrHo)AIbpdo~E35hU;CU55@p z2$U~zjMsbTfAhwta7PKP&f=>h?i!6GD{YDtOk$u;QuI7|TfYg3`DyKP*%e>=PBm7` zp90Tc*X3Hjb|r|T)4hlHK4!U4!VIsu?DGU}Iz^J+9lxJjM=$+g{d(k{o$uHuy~8e_w1A-w&Rr(Pd>-Sm(H+A~j5+HMBq|63 z*@?B0Z`|^UU&!A?_1@|K?*%?q<|*o7i?8?%9Xz3l*j2nvs|dngt^D79jdguHJE6H& z=P^emw7nzqM^H{3J8u0=H)EdU%2afIyUoi-w3|J{yKwnl`@n2hdTcy3R>8By-Ctat zL79-OHx0Rox9%jrBP}TwJ$(=DGuy}TA6XxGqpIuA@%!c{nWTEF)t@#F3Dq8Tus(XE z+nbvqClljUbK?r?B}W~z9y2+3_RUJ|0e%<{DNHuS<6wCI%yp5+*TR7pFc^{-i@S_2I@t9nd)w3-x8i5p`OFDK)P;fGXx#i}G_i?XMl|K4qxRoE zT!i_T^zNL$g1`Q@BEA*!HvIAApo#vGP0lZCPuSb3_dO^0RfNx6cq_er&+SaNT#@~F z`M%%4kkAILHzKhxi5nA23$|dr*(>#%P6u-B&w9;oZV~e{TMw8fnP1Kbd23%X(`7c* zN!2m~(=pY?`;PY8Jvq@NT~RxGA+Da+_1u?Eb48Mkb@LL{d+PfbRXV)y2gLrheAO|` zl)xE3H+klBNQyh5z_%u3J`xITdd*vGxy0{b==9U2sV((25n*fF(wnqP^;KxJR%Kaq z%7RA`2tPq?-Ep;d_->3MJU;i|syW<`kMZ1?D&tEA-fw+3z65u3N_<`-*e`VCueqan z2ZoA_>S?u!`R<^HchF;>m9(bs)hIUAtD=-wx&Dcd7hF31y?)`Ds@$*qeF7T~cKwMzVdPf{X zr;~{)g}Rg8s)JYj4+=#gS#6AJw7ge0n=lWiC3TF>tGwjI(SGyOXX<=X_Y6DjU?k8& z63&LLx7N0MJ8XA8#B9)o(@we|z$SFAFK=McE~;F2qR-1js-i~QsX8z^rH(Urr+o6^ zJqSc_W>4|SU{-MOez{BT{NArC<0}PEKeuoVzpvveO|J~__UrN4j`S_5Lr_{;Xw$p= zA4B|Q412}CcC+c`?XuT%eVFy&21e+#AHRPS-ILx}_LbeAFMi`}rry7#r~ORIf>NTKjw zyJhq1{AOl;gXZ3Q*V`;Wl2W_(rfV;ydm;9(J!AI@f3R9d#4Y&`T7I7=P$Ownw)gb~ zGD&U2*QHys4sbf!=d?IzYV!Ub3odmn3BJ+bD*WWekrUxc(&^!CuOH*b>{Lf9_jh`r zdFucLAw8qVU#15Y>9G~7pLgD`t`mr|uO1Hn^BM>Hoya_S;q@B4t$$!4>zq|}@e6}+ zNh@?9^QRLI_cwTSpY$qDkCmf6D&jh^>=yXm)z3Dq0XdiEwmSygy%F1-6^Z($N|}~Q zU+Kx;(J}u@bFaJucRFS$+nlXfgw`vInfHn2G};rpul@CFtI@7Qj=mAmC#98D4~`9YZKk%kdF;SjK&hy$ zn(LjkY0G%OE!qPMHW2-|dD8o?=Zq@9Ey`)m%-a6GnhX3I*p+%@>v>!I4QmcgL3wK~ zivI&aYBk#-QMvws4_;svvrE|;TKB#`c~CiG;HOr2y>{I0eZ+vrP}%vXyuGI1RwesW zqIC&S@sAxZ^jV=CJJ#pzS9aW7YRPgDHm^N%7`3F6ZFgh%AMbr&1?CX1pQve;^fun= zl7W7*y!;`9S~L}h#%4ap+jkw$wGRS`JdxUx&@fNdHVgJ75fLzzHE-_Id&D87X-bp*tAPE z=C1Wf_0)cKEBkagcjO)OOurR)ayu41_St)V2HAg7FE~5xbep$$@+~nU;M2YP$|n8D z-3)J~y$4;$G@22g?|pE{Hy4n)m-qa^ulGZ3^O@!@-jUj~_&MetE(@-PvuA*Fv~Xqx z_wC^vC7eV%I5UFu1;Tka3x`hexyD_*gN5^PaBsA7;p~#t=3F?tM!?xE0?zIcaEc?~ zltjQOjes*M0?vd8IFlpbOo@O~5dmjv1e|FRaQ2LVGd%*%j0iY;MZnoR0?wb7f^(2$ zKD88_1BG+#Qg99sj?JU?<_oI>I?J0<9~Tg0oPxK3mFM2Iupo;Gj2ljDTZ0 zt-XFxkLk3Ia7C@g=%vax^UP?XlgyX-9po4l^g!5ijJ!S`O9O3h$erwY0F&rC5q5QFCJN1Ndw#&l7 z594F=g?aIqOKR=A;n;iu=kY8Yvx7ee>EL|P4vy&ozEgUA1e`Up+HADK^?bGzoDW3n z)}_z_XGsK{6(Z2uFapjd5pcebfb+vraNbeBT9(qUw}ta|1e{HmLhCKnGb{qm@CY~~ zBH-*40cYn3I3GvA`D7_LZ>aApN5FYxDLDUBJ)12B=T+ehUCMZYGdu#$hzK}4MZnp4 zDLAjFJ^do!^pAiuHv&##DLkY-vm@Z_9|5O10!}gl&Y2N#{t^M_nFu(~M!A!f_R))cHSo^eU7zJ#@Be$baA zgmZK|{W6@xg>%eOa1ImBu}i^OB%I@xf^(>Fj?cm&?83*^L9B_MbxE!LGN0tupe)&e z$ajdde1v)k=J3h(MZ>g+=rceln!y&YT#q_SiQD>VJ-8V zLutjael7{*8JXX_9UX2stnmkC&7JIez^RFV^LhlF4I{K?hX^=3E(Hf&x9w8e1I`0k zI5x(%ZvC@xzE}#*A;S4G3+G=-3x>zPR0R*r)w*rn1FyZa550e{^{HnqVr;Ke^&wM+#aH1@#K^4$$x+D2+=XVJ$-Nf>6qX#K5GR+vf#e_(^)N$ zG3cBX^zGOO@=s?@4m#Z*%s-vOLv$>ja$5oD+!LbnX~4JYf8@VE_lD^F5YUL1(~|%if>& zLv|YyX15WC=K`7!7l6)f0k5F5ci``w`Aq)%V|E)lR|kuQuU^eR9kbienHccxub<_I z&V#`iQLV+yp|h)i&&OZnht2~bIu>^i)9LwTe(1PXyEXfY5YUIqZ-En^C;%PvL!i?H zL49WVhcDcHl)t(3DD&sO5Z`Q{0Xp9VmA;TCI@U(y!2F$Xe;!(q!z9r^?e)iMfX)#R z(1(k~iU;|xWA&3G{fR=y{2l1bVX>u8q5yQv-+@kbKsqJEJuJ{V{(BI;IaUEC8K# z16u%{GlTxDQI`Mym|q2*!9k$&vI5XCzbeePf0pOJKjv3K$6_PpqnDk|&w;LHD5z~0 z5r78%=r3LMN1yBSOo!NOE;?6D&ToH+-{zuo>0ZlD=cg>b?JA}r+VJi3z%967R$=IL z3Fy>vqtEd*g`q>O^ylJW{(M_k7&?dbFYP&eaaa=mB3w?ECxFCF$Kpkw`c zJCK80{8vdRGvX(gT?oq?`y09FoOWn_`@=lVCD;2ORTw(ia=q^fg`tx@K98PK7&^#Z zc>Y}Rm;BN}zlF!g=IN+&3PUHGZy%kXUpnli(I1>QebBmrW3>}t>@GcS1+3cml(81n8XIwz%u-6Jh z2YUydR|38B?3;z5gWeAF?eg~uLkE2dohO3oSNV5g=$L*R8u0C<&kIAx^v;d}omKx+ z7&=rB-;#m64f(M!bWFdk8&rSwuZ5vQU;O?Ae7k2kC`bR~@<+q=lvbnP2wOwv`M}Qg zTd6Q~I71O2%=ptI)sg`s2fbo+qL9h>Br4t)so zt$$Gcd)*5|$L!AmL4VfSt}t|Ld};!J=fvKHp<{N=`tx1C!q720cR`@v8iy2yj@dcu zPq&>4L&xl#_2=l_3qyxs`keray%Hq4QQi=XL)zGfIf~iP|62Z??|5eQII)W9zJsg8nR;UKl!@m4t5(1axZu zR2VuN1az!FJIpK$9nON%AJYeGR~LrPMgg6(gZXnpZDHu}%Ixs?Y~4^8I=n9&IyOEZ z>|YotJJ`rwAg3qyyv zNO*iIo-Pa>YK4x)ufKV|Fm#|1rgP3~g`s0{B=ZxC-YyIsiz7`8?84nk@=J$)gySKP z1awyWD8F>*2Xrj%Z**SxG{1C+gM|C@VGyo7`^&=6vHqCXJP2rzKop4V4omvHBgZ^&~l{r2MV`R$L9n%LkfA+qtFm!DGm>+-C)%m5vJ}`1^^42$4|6KaF z!q72!n;X!1;pW27G5t0^@DFymEx&Zw*ADZ|;uOcQhT-Ey@{Da*!Pxaql zFEj=AbiL=7ozC|mIb$;ovo)6P8J$mML`K5#X3DdFu{M;+QbXX^Z=~#be_0KOI z{HidW(}VGObnvp%`7UHn;af?_o(@FO>9f~}{L+DMx#*m@^RmW$lGcS z`K5#X$wg;=GQV`tZ@K8ax1ca|vgLZ*A2~$am!BU>k!}2qmx5?>l)af<4?>l9p+CiI;WkIUpma6Ty*|=`m)pc zD#SO$i{FAWc^ekU+eLrLFCElOn9ia=-d;N=zjTm;Fr8h4b?}Vy^GkVv!f~U`*zvY(>^E6Cn<-pFpazlRUFi&&Q zd3$kw>9AhNMdzbC@=FJMnv2fY_JV5VNBQLPufuwW@3V#JY!c|5pZ}5H{;-b`rt@kb zZ|gmlUpmD7!*pz(e)f2N>99Tx(=mO0z|;AqL;N~S$NF>g^ZBL2_sqg{<^}p~_m}fa zhwqt%>Dcdq-1^$G)A=&Xp7Ohi=I`_j(I@X_} zfX;RA=9dooEmwcOSW*}|)}L*H{`~Uq{L(>>(w}TP-9KG+I-h6B!8Fm)e}BF38G@lt z=@!}#Q))Bn5t(t&SbI*$bX+3eS4r}J5eZ@2?{hWHi>=IQ&(1se^@kMdEKt$T5X zAEra|p<{BeQ9x(Oiut9(x-s0Jj{~{>&HvGAYuVDTOY4u(F}-8``Ed2Z^vC#S)yrS!=t(&_N!UvnB^6I~0Zv`V>0WpObqPhK}t6 zT7MqwlV3Wl8^iKe707kB{)M4q@@D;M8kk=?tWR_G=dQtpp_AR8&4(3+PWJq%9Z?uM zHh)a6&)c~$bkK9*`Sa|q`K5!M%OwZPjVufulLO;hqPQ@0Ob%?Go?TiPIwl83=a*51 zp_8pg_Z?jrI;KZ$d`=x(7&_D%mg|Sc=a&xag|J+k9{pkBveWq_E}c{y@j%?Mw*kbKi{o(!nl-`(tz}X6Ba;dM6j1k7wtX4swu-&LQ>rr9<2@OlM{= zKI^3NONaGBn9hL+gg(gwmYvSWA-QI5?iG^jE9sypFm%uhfbs3AYYIb$TA^d}=Z@?1O9y!l z%bU@;?#9BejSQt9^J>mY0dAKli?ERxF2l{RI#|lHo-al&NQ~qRO=-B&5 ztv|ayQy4nYZYGLTu`$tUdFH#q(6RWA$@P6d7KV%idQW!eaN`K7neY#s==s+V( z=l(SdL&wI)`g6-V`K5y&nrnQnSidlIs5Q*D&o(Ly9rJsQZ*Ol}7&_+n8l4xm$S)oG z5gwmS1H1k3mW821t>N)`cbme{$sV7Vwkr&sY`gI2j)kFP`e4mqd=~d93?0)4=J!6- zKfiR4=diq)zP@WvVdzk6Sl(j83PUGb4!#{x7&;~grVrlTr7(0%4vfxAyXTh<>&37f zm>=?Jabf7-9>P1Lb9dRY)A@JE*TN6|Qz-6#5Du_DH0OrGtMR9-n^& z{rRe?Fm!BujLy^Z@=FJQG~AyzgZ^A|P+{m~_vfg?@=FIlC)}UE2K}izrZ9A@Kc;tn zJ+Ux!=mxsM#^?Ie3q!~3w#nPEf6Xr){GIUlSbt_;SQt7sKGvV2%kxVIyB+S2>FX`7 zEesv&&%=RSFTQcv>AV-R+v<*YyX-a}Xgv^Azwp*H9kK%y&~koq#a*5b(V_f%`ok5u zMz8W2@nD*cOX>J;E;<%NrcU$$GKZcc=8Js8I{Xv%92h@r24#o=u|Gge9ebHN&Ajdr%n(YFF00kq5%5G=t};pf*S=l32qjAEci+Avw%LmCfHrDsVdz>aEtDD z6>O;cjRlK!znfqq-52Znu%Jlrh+w4P8v*_Kr{Gb+X2KhzYq_9Au(_Tm>H3)9OTiX; z?x*V~g5H7wf=>mH3&sli3;rYcRls+#_?}dE!Ap8B6^s{55KI*8As8nZCHPHHCiq=2 zTEO>edI(_FFS=~0E5W^if;DvyZ(bKn5p1RBtp$^HUmUyWH19WZFwOMe7V33|uy0!?K1TP9k zC~dgl@4BBVxJ@uq&`)Ux>H4JLK*3Xj2Eq3N*0c<1xE>9791&vDQ`K!NWow|A0xO&aI9c=rSa~)wFDdM`E9{* z0`&7ff@gGpyr4+;C+T{k;8ejWf>#753zk=2S3wuS3W5~{yhmq<@=g=nD>y;GJ8yVj z(At6>_56>)Tu_h$*Z>3(&=Is$m} zuHZt!EIn5Vp4I(Dg0Z?EFZf#b{}A*QTq4*>@P*(q!Nr2-1QUg~v#x9CdbzIm3oaG# z9*c2;bp^}o`8~mUy5B|DE`s+3R|u{WTq#&iutadRU^T%9f=R-EK-cR9ybs|=UDwyO zT96Q2qvvY{*9j>9q2O-ug+qaHq7dESDD-~-;40_xmP!1GqYbFH4CyLIqPdFYb1O;#Ft+XiX6_#dOUy`H$= zA-MXP`a?av1z!pV2tE~%hRh*@CQGC-ri`zR=?c2C7MGmU#m{bA)y< zm+YB5aG4Lxjq?TMF-O3q|2)GF<{D}ApEUS!v4HZ(^F@No1>_;);O-(ohDm!*_bUsK ziCuO5MzFi!VZma-Edp%sBf263y9s_3E_q!Al-pfb%2Ea!ZMGR&BL#*}-J}%>iUr_P z?+U^5Yr2w0o#cUABEVLT*7Y%^gIg+iNibgUyI_Il%u@K8uXxzEq+{i;2{%_3y=@|2--4M@TGwClZ9vHp+}w2hbHBrN84$$rO|fq zCI)%5nS0X6gT^GmKLw8opn=aq`eecDf+qyb_X=G}=YC3%zLjvd7Emww)JwUQ1n_yP zuHOru6x=5Gy8s*cl&-XSngF>s+rONi_Y`2q$)6tNo9_Uf89^F81UP#I&*oQvvv-iT zjc|DWlb}ZMoq*?k1klCDfabn}xPZJ$!SjMy!ShUAkulm&K6rBkl;IgX%2WlXqmr5nM9C=zr!=Ql%rmrxsqmWqV2T;`awSTg9M~ACi@BM1$Bay+Ip+5(4H$e zMbG$8cj=z8;DFCqgG0F&veFv#Y<*_@z-tsx7k<#4x`%H~0_F|*`wJEbs25tKH4DOJ zpq~`L4}3vzQUMPB)E&AfttBgsa`Oa~!C2L~uE zT-SkmK1hI^BAf7(=NAR!AKQD+=Yv<2p*%P|Q;$7U z<`{wD-=lldjupTs+DIDhI8J~+i0@V`C>4-?yxNS~|g{(^-9>ZUEEvpxo&H1q{& z=n!-ZY0O2^&H{pzfa%93)`OXamnr3ceSRPda6u7Q8GtOn|<} zKA_*pdq(hz;CMk7rJ;k-m(=&HfI0fLuFP@fAnjz1UM9Fmu$T2fH(;EZwrW7aQ}{AW^n(m?q}(qe!nMRJ+h0g;Jq)nBDi0o z>(v7K`hfsBdq7v#&)|M2_?tkF8Ea+m=^K4SU)(H!)+YjF_g+ z>P9Y*2V{f#{vn`#XniAiL@-i-{Db=+0kYp;U^Hp_w}PRnbAhgu{Z8;F0kO9|1*9Rz z$aI4MS*E@p1VaVG1lC4ye-yy;>ve_aq#-ZH*PC=t8uDXl@R~H{BXY@F=?`6LAADyF zXfw~h2^hTJb)gJb(njJYy0#4HgOALENBy*)dH1xgM+!#j-gMk@x)09y3eEbaRqCEHHovVAE@o^}7R`85pK|MUv7jz1;G*Q>fbwwvV zDZR%B-i_8Xx&vM!o0bQ!7U>xs0`HF1HJndhk5d}@gub7Ul~3DGR~mh%z1Wd3ZS>xS zN~3L;3h1-ZMhCp7XY>GNo^Z|m1Gz&EKM+*wel1<`?}rGmLG$!{u;2i}bU{+EmtcmV zTClfZnjj&VFW5&gNPzwzR*O-Ie~OuHf;Et_VLP>jRaJ?1QtFo~H!&TL<@)+eY{F&+6G$ z&kIA(J@ssT1)nu8JTd(3vz~X*GrS@nIodIJhIdw`m(t*);q(rk;VWqXzQ^6cJwDFu z!F@m7-==%o(qH$Cm(@E!&y9L+7QnlKdbV+8j16y)(o=eF5l|0n=eePL@o1Pa1_qzx8 zv>6>WSXcBG&qcc8E1;JsSFC5|8F?kTAHuz^p23R$LJaRL^+=EOD@utc}f~<6y_~?_;ddV(#e|;%0u7mtTgj!Ch7Ts z0GG0p^^7f{96ZEU{zq4nea0QzU}@M3!^NM&w<`(KsBfCm9txhp!^VB5D|KV@xSye` z)xo`Q3zbe9b>OSKr7P=yp1G2?D9Fcud0Y3av&rX58sh^U?D-G68vp16dfw8|{YGo1 z?%z>X|A1@sAwD)ZxTOZ-s;EEJKt=ygSCos z(>1N3r`5wL6$_gZE@fiHjESX{;~Sgn<8}Vtb!(~d@%luvDPEOOL3LM9Uf)!gs82Mc z64mAU(>z<5Nk2EE@`>?OO*_q^A)^uviRQTKD6WeqlYV@#m1bsM&%VX+=DK)AV`E*i z?}Uct#(1?j5a2X6_ie+RK5bGei+lPzKojH5YPX}fy&B=)_3S&Ps=2l)6(Z9oliNN0 zevFT&#Qy)fiVa0?d`tc0L{nXD6&;`0+}M<8PSuKeNKZfitUxOdN)k!GRke)`%5(<_ z(wVi%rn>k-#>UTFRe$}yl-0%OB>jN$ph1I&4emd{KWI>%EQzP$6B_Ck`f^tmuS+I; zq_Wx~a=gFZ{hJ~JG5_BX$uoD;CF3r|{av~BX~W=dlp>>zvgD)nw^%Epd5XgBFN;rV zi#*0zy3SJ6b+*!C;=ikBlAfA`M{0|3XUl#pEqA$~?6S6D#h{)EYFC3O$HWiUs&tC+ zVXYu1rqMAzr0=XHQ`L*v`qx8V@>Jm&&n!Qt(;BXH=eT9%r;1li;w_xoUp2LtzCu97 zT8%Mt|Ez~r^1p3Sx1hdB{`i)NgDvWJjarwKw-?h%7)P(Y{H{U1wJDY+vPuJVr>IAB1k8j+jTHSe4z`zXU^R}Z*U>Qk5{ z4Z}>>Q+;&WCQYZ~ddh-&`pI9JrFJsXHnURFyc5-Kw9+hTGxXN}+7qNN^a(jf#{2m* ze5T5|8K26+*-u!FiW8s*mWCzU9ki(9b{m(*sqSjEq+WU^t*O?CREN!fbg|QUYj&#K z1ixR5skPOvxo5ETY@#HiLG5+?47YpjNc3&4r^J6}Q)*Ohok(Rj4zR{+1XJ4o>ydM; zdT2))TeY8$Gh1UH(-}QCFFWp|jZ1?@B_SHj=^9^B;M01M>M%>Oz0O?3yF`es)QqIP}^bDQ_qcqDO>$C;gJW_2oi!$x#7Lm#tPmngJ1K|XBj0^hG z_!RTHN2<|eFI{6ybw%NdNy%u@H?3?kGQpn-RepL*C#9m)XEV6i=WVsGBPukL4pc2M zov!Lk9atyqk{cnLjavtGEUTq8IhrQlfu5&*)^y4?ZD^Sm9_wp2^h1ken10TdwwNV+ zlg2$%Cl;?(a)u_{Uwy%cFgr6-XL;tU6h3_#H|??K&fT_6i%iFK&JQ*}0v@N-ek{TM zYKa^BwEb@{zh|3vmW^uqGDYKy<*5%y!T1TQZp|wK!*LQI1sn_91!VhG{N%(BS*? z*xR(0&Q3=Y@XyMnefZAVSK~7?ANz)-Pip~_g>Y_oB{wWjtuQO)VnRA@gj)RyVCLDzwr=`{6~-^rODc7q7X!P56LqtLt@0p^RAKFYOCRJJ7!AP zrRlr+Samy}c(+LPniU=_%R5LGwM^F%+1~!T@9*CY(u^*VB_6Klfyy1G=OW<^5dH`~ zkI+4OboWT~%mYkYzpz&Ao6)1R-543EZkzd;k{45J-Kg43$n6)Jhlc$?npokPPhA|; zV3BYywp><9e?6B(qGNSn3rjmy0xp+zssxs4RHsT{NA~Dc3G{t=r%IryM|Y|OT6IjP zN}wCZcB%yWZ(O7j7N;7Z84*)7FN$=f%P{T}I$4I1pV-MVjQylemSOZKcd`uQKP6Hb z(_yTCX||JiGI5@m&NI1Qnil?V{V(&dDl~3Y;w4^Ku3feE^7rag`-#lf z%TI~voRVw5>F2bLxAuD`4= zQZ-aCT+hRlJKUGOA-Wa`Mo0pS^bb9=Z$Qtr7rU1po!p*{dB4P-TckgT8K=Ep^JiRc z51sSP#5hFs%rY9KOpKV$POa72D#J~eis@j1Yb`X=`%M zNa`^Cv$bPy^>J4{^;O>niVsNV2%Ri$Z;e11cqePd zV%c`5-E6;Ms(4rvqOzr8>xPLhm+;%LG!AbSV6~06;(H>OtS3w|%hi&E{xKWMv{E4& zP2`ewM@*@%-yM&st+?nh2lVm@z{UW@6Na4l&a zQyZyAx#~#ACija}hiUpEVbASUiDF^bb*cnwgZfUDK%N>Rm9WvR@?&3EGh!pGE?L7FBPe7Tfe%ocTrhezaj(tGl@_8Hs;51qJYzCG5w9w6Qj1L z$|R+oI48m#(lI|$4dx$>Qdvfgk_&>8t_A#EFG!iD^-ucTQ|^5^_|zl74_nF#MTXfU zLHCW5-mFqP(Xt2Vy#(yqx_xmXy6zqgZ*wZ0?{>V?7{s&r*Rjl+gcZvo;tjCd!43zJ zlOp}ayTgj&=Z#YOFy#&u4r_{0zBCR}>R{11AQHXKcnaAoqqL`RU?f^?J%s`45gzJ5 zLE2NmGsWLw-Z)R8ZREK49<9vLJUCJ!}iLei9}Nqb~SVNBoK zjv@o53BwW`(|6ROl(l(AbT3;14-IN)JF9JOl}qOF5t&JJvpjf?G!91+yfmJe+u)I3(MX$fV%Sx#pq^vFm( zFd0A(p=sUe&7&ffHR(oou_8iuA(z(wqa)Q~(ehGJcW3y_Ivmq3|E!Fy0*ps7ee)`c z^oG}Rj9NI>+e2Q4&9j)ktq`R?)23({qAaXSu-aH>wB}%G7*@q2q<;qMpNm@)x$ZA4 zH0nT=Aewl5BzkKGSZ;L~Zhg4zCq$~t<^rpi7Jm$w(c$R8iIM8DxgBo7NkK`+!~YxW zeB*7EqKEFBX-eaRgojTbo*aoMCKsF!7~qdTzFMhlE3p&eaM&L9EwI4O5^>r9c`5NR zke`8~bxI_9ZS~5aR{asyD>h%arq{@ssqI<5QzNy+xR~Z)t}~pc1$DL6kS0y+)S2&m zdZ#FNJbq_Hs>`fS`h*|$Cw-a@slZyC8L2jthGNMAJ6iZ7#LPG|f?S{%*ymy|Yn1-s z^A8sc)%^hFAS?K4F@5hfidM2Qu-4~p`&p6d+9<#pr5zHiE$1x{kSF5SQ0UOywVxfS zcH<23Dt7SttC#ed$Td>QeBdO`aOIaO$L#>ZwGx3lc|&SU-<*xY8H;IKZ!-ImyC>&F zs@eGD{5($E!W%4Pjn;zg^Xc43wHu$%AcK92fe(&_VYTNZXn-#_SejC$g6HCZE^6zv zOibUT?+l;9y-D{aH=oXrRI~NO?a~r2M#>p$B6?U!MjXGrNc}_li_{-x1QAU70!FcD zUC>E-oXv8jM~D`(#f)R_!7XMRE1UkJg2b_t0zUE7p`snrcM79$&V2SXx7br^l9$-t zOt~mhy~Z~pytLSH4z3X&C{jO&v%?u?50PE;2rC_~W%^6JcerR>9EqMqsnh*%y~sWG zmqe=5`rzWtSV4C7*{5Rc=>x52>}e@&E>aGwP^S|}D^*HN--VAd7B<__gT#;cmI3=W zjk<4dG%kx&v-O14F>z?PkHoMKLSKlxBUS8@&==<)GB-J`z}_7_!oFV~iJnCr(mk<$ z&YwqL<5;Lv9@Pj?TonRZ)25*q$$U zP0*6g%ZFQeWbdJ^5!B~${}=LcZ6w~>STY{iQfvYzi_D+Ewh(D`F)-#XK3S3eqJz+@ zq!9hOu2b|}De6LF;Lo9YL2sS#^~Hs=JLGeyXf5s(J!-?7L}C~rv@^2|@58OI;4v8R6pzWxShpU-Yx;Yq=n*$( zMj)qnY|ta#L;n~v<^VI0SOBXV<|JGug>j7OO>~`+mlBnQr+E3Sr5F=@5l5H$SqyFsNcEXMcI`qZBMJC!~BxN|JTY+`!L zU}we$Ee@wy)iST?A$`L?U=HCKqK!Gpg+5{4LmeA{#);|eg;D6O6JTYI4|`%YzF+4~ zkh{|tcSowxMu@hfIh_pALg#1DVwaA5c-QV<1 zbdmPBdG`kI?TC5z2NWzK6+W4?TxC|Gs z#cmgJqEFw&YN~S@?X} z!|m2!J2E}QVf)_sR7LC>RAUd7dL$@mlyXavjUQv@ykm5bJ6V8ja;sXW1@Y}VWw78M(dmBROQ`Wvf-pG5rD`Gxow_&vqCG8@qT{YC5XNc7U$5gp!9Z=Z-%-%0`2 zXw{bf2FQ~^s*T?Ng;ScQ=fm=E-}8Pd5-&{p86W&%MvS;4v3PubMifovRu)9%@qO_c zT?~skz*xuhHoGX=tD_b_lQjaJKX9pYjzL6{10cZJ=F?{s>4kDEw> zrMK_xy&kD0QAh8Mpf;1t&TH{pr{~ff&0bxkb9fH}-xhJYl18Ct zesa3ynVfn%QZ1_oSe(931}kekZdun!y(mU6rgxi0smJC& zS{?rc--O*uv^aVI3yLl$&VhbFBM{fXZ|D6L=!R0YKc@FdN1S-L`p7&^@5?R;=((2v-`MLiKR(xrkDW<-M^{X5 zs*N%t#!WmVqVI6ftvBGKlK^HDazI>$^$IaTcg}>Bw~Ok=^a}yTM|X|x`~UBD4ox3t zT2J?0FxG&~(iZjW-<{$mkvHPd%p#&$_(@I=A&ll$h~Hk?2Kj z{l`IVHa`CsM#en2j?ZL$5{XYHi3Wj&_xLSy{gt_=-q}CW0-M*h&31YdhW^m3~I5Zjl0i%zeBf1YqiND)k!B>&! zv5MtiX7986KFaT<>v!0jXEm7F<23ib4r=cFOb&nNI{ghbTS2CC*@4gY$qb+G2rL)0 zz$B$T+@*gz)*|Mav&7`0?fKbn0?MZK(rpRfS-Ud*&UF7`dgFbRnP4)5_Qt2cKDvDv zv^Vhux8G^!!0?8M`Vh5qyJsdd-$tTm?H;e0;a2VLt*|yzVtT{AYj@iy@XA3B(dZtM zXZJUz-=B%nQ;X!WS7PsijOm^FQOc%UJ#YGUn13F ztw!sxI^nDVdIx_MUz|uGt)^GR%H7VZi@MM&PKF_EG5zXKlu@&pH%S_Imc|Rq#C(I> z*{5{j{cn+KwO()zmzHuOmy>EPjsWlJo1KY4|FS~Et0X3eh2x18+3%6)S=1=q3+qGX z*<5)!hW#5eTX$Gel)&_i}SlkG5#Ms z;7k#5V^%HjtJIfB({dftYs(e4myxRn%LUrJvo&U(PIjj|-7H-`QjNwFc08Dmtlp6o z_bozZBOF4a@otDa;q$P=$9!fcINyvn@-OF)S;sxF-1N9+pG|eGUm;R$)_UeDGuG`< z;wQ4-g-^j>d<~+cEEJ07*>uecZ%mu z7vg)mlY_)#IQ8qIE{p_Th&$8l&LJUzP7;|H{PsYUG2XD9-b_-owM8)m_6W0k#G7BE z)NS(P{A)Bmc9=8y^ac6B*5X?evEhUk_k7chondD=+)1?6BGF4rMR;VwJ;4u8j|}e> zj?xcXfre{p%ahe3)s^N6J*0O;qVPW4DHx~mu^*U9eTqV};REg0lu|cOwj8TaVgA&G#^mz{3spz3M0lSr9lg=Jx z$}c0?;{PrOdWKU6tQcxEu6=ZFqel0vo@c8Ru|RTW``;!?sTAY6QKa^o#Nvk%Pv_ee zoV!7Ckww3muuwG^KS|B-W0&gL^V#A`Vnn)V4;JJ4FN-Dpvg zvj$tV+fs|t_fdULbMS^8?82@p*FD5H$Hk~tot1w3-w<)Rh4}`6$wzj7c*{m-k&Ln!R#28fb7v$Guw%`PecNJ<|gnz1`S-XCp1`=^abw88BOib#Ojy zt4J-evnIwlVt7s#V&2w~YG|ML+e9jFbCXjXNHTIvtc4lr*6!#h_e}xkqvB=YBe_T( zs|d7M%-c4g*H-VEcIYEKzVC&`oE@B+u;>@E-!rJeX^YNywEsKVw`g?xJ&SqUb!sHs z3XE8n`xYCkI2T)C6j%wM``w-_9t@bw0pyZ(LriCWqRcuQ6>E9;EKB%J)jLG0EeaoY zj8v0Jr1Q%0XDx1oAB$aNWoUb;Zg-m1n)Bb?x)z^~-!^c3Xe*J{TC6&<(m!`c}5GDRO2_~+a`P{ctJY%KE+(lB{YS`jH%wpC8tbW`# z67VaC1Gx9|IjzR;2}F^dObyyrSK65m=ZQNl8rGm;z1rS);rd5viJgR)=zD54zPILn zvx;+C=~2atL$eZ#=;6PEbU*>?-%F!7FjD=tz6!TLTOz}4=T`)xjF8PD{1YOb#82EQ zGfo(|SRmdO{wMob=yQjGZg+8Z=V1=+6g~71rQMD;r+d(2&~x8HV4mUy5>dgkbNUSX z&Z?DJJEW8J=ncIidPQG|&Y&|{8KXJf%9wlnX!NE#tB5w?8%sk2dTq6Y+15TPVY@_5 zHwk(3RD z$-m59vGhJ5^JTPV53^>kVD9WxkeZn_I~Szpy;burk!rRRAer2-(NFoDfDgQnKMHqk z9-@~SJyv(DaF~~9M@EouQt`w(i21CxTj<(=r zHzy~FgA%Xi+p_2_^c#Kw^8tSWzQV zZrnQ0=l|VGp!1fztW#Vi0)+Kq&k~7u){GhL)@8(0n9J%u>Ld)CQt7w>{+=L_Ihxb-r+0?(PXAiwAlh2CaCKu^_+@PipLKAxh3lFT zsVQa(gVmj_L>b4<@nmkKI=2jXgx`xVhOKk^HF&?y??oeG2hkE}LKmxL zkCU|>@zP0q2`_k( z|2NaO%k2v{MylVq4HwzZ#A>ob#9GOnpu?LWs)TRBD#XQt!A2_+8{^a{zh2@brmY6t zKIlU~d7IVJb?#Tyc}ja*PV-HXjzhP(_Z{$?mDw0+Jsy+Aauokxo2}8j$L3CrFLo4f z5FZiGf;;C)uu{fn#Jk`-Uv8h?z0ZuZ8|-s2o05^}nP2DRH9UUq9RT}Fe#2v!id3u3 zrSz^p=N@^RId(9nzfKZthc>M@!*?d@_{Hv|DiK_wZJd{JXP?;@g&Xd72w5NEcQ6C+ z7>ObjiQc?O^z7Vq|(-7^e2&RMi}3bceM~5NP&HpM(Ws%|(RJ`K_$SkPc#vMBs@`p%>jwnzK^Qip6B<9UnWERP$fkvq`L{)4u?n zwoC^{s@=Gh>1VPN!MA-<($V2L%E%lNsb1p}mIGabpU)nq+p%HpxLr$Z46zqD=~iCI znTxg%wc;0CqHxK)kL-R}FVcF3J{%gUPW$%JMDcfyctLD}UwCotX=~d|X4$36KI?Z_ zP%4*wGCE;NO?!F&yKf+yY`EWn!nfx4#b!$n!ifd?OMEK)oub1d@zrDl?dndDvrCJN zpm8}>OeBMI##kdxT@c4~YjPrSXfF5rB1c4`mySF+D`EY>hYI%u4?O*?t|QwWXVc|G zn}@X->7ydGsq?%&I;i*m1qmAEuW}n&f0KkYc#Xy)<{cA>dnQ5HCBAil<#G`cEI9i& zND^Kt(GsE}?pxHX2b|_{J`lgK6Ggk24$htl`0=dQ8>A&!Ke`>jbZ?FeYHzD6Y}Lze zbg|21|M<x6#Gj&xl^31J<(*yUCcWv61@-gT|NF4=?|8v zhk*NP0oH~{0WnX~+391Ba6eu!OHdyG_oQPnsfV)f1=sy_r9N=@cXFhbMdj-$S#s6+ z_W^Acv@6#Lx^wpXix2FCupZn=D?zk&F6{L01Uek|9Z8c4d>SVgG4Iq!JlHa58GDHM zb*ypmPVn{IHzm14qu@~^6WBC-Y2<(yChG^{?WaYeXD2H=>fz~;YO=LgE-tm@Y0Nt# zQmv-7CWw!`cQ(z>GlTMNH65qK_?Nk_Xwgr%^0yIc`!wEvo1OdqZ@H`lZ{0!)hzGQn z$1e&k=hHM94zK)N4lOb}o{L8@@2sE>*LrG5uXj53*ziIBH{T`r|JXYZc+0N3-rq|{ zL4imSP-X%NAcRcIlu#ry$%L8!Nl?UjWRhG`NG4@wf|OuE<%#&@J>^kEQ9z3Ap(2O{ zQNXTy_XC1HEt;$z7cpc}+M#0#0WcCCeS`JS&0uB&%&M} zW2`VlqL3S;jtm8J8OTnM+vQD3IkF_|53;#5Je}8<*JYKh++6%_m-Z;e_h*%*aioi@ zxC$x!fvhKeyxJl%vTD4|oDtNEg47-f87kg9v%2#7tnw7aS{d~c-jG#-yu>A;b~4;} zZ`-Ttjn(tAspVMV%R@i-7w^(YzL*tY&7A`|e{HBgo-f4;TPs0Vc{^mhyT}h_^-*$6 zglc2Twk{UWZ}}hO*G8Cy9av*wdwCE!5{a+|@l9Fv-M?yeR~AUULHqUQQ_lsxIjau& zLzPvh%UiO_kpF*1XzyE#o?uq+4;4MZyyPFQo|s>vPOm7NBT*O4(8pSk=R<*aHs|x` zY?hK;u^3i!!sEM%6m`Ew(&J}-B&+9=Ivd|-Oq`4?xkpz1Sm8^Q=kJzzirHt`FPB; zL6@Q0`?Bh5uVp1KN(snES2 ztLNL+U-r|v%}l)u!tvah75=TPn&m@48^q>b8Z*={3vbjST3%iG?X1#7dFX7jHn52x zNLD3~PeGrdyhQ>w{!a91JH+se?Y#DZtorJiX>WVn^54lSNpuhgysSDMKA2Tn9J3w{ z(f;PpXR^gdXEQo}H>(WM5?cszfiie4)?Sn4N1Byl9lpTdTeJRLw=QbxpRP894|>%x&ZoWX5O&$czy!qDJO@ zfzCcu)hEld5j>-`ku1gY!W_u@uFbqTrG$py2_j{1jE&)7wfM(81FqPtD6-gwe4!x} z2HQZx4`MeKe~+ z=P0dCar9$ZLOPznt3MT&$DV0wp6ZWb>%Ozp3~@qqQL?+%cr;6zG`GGp0%ql_h z;&mf4j2j#Z2V=dwzaxjvlHa%_a+Ji%WdHtORw?R{MiprZ7?FAUf0iTWOUS1&j|h*!3`cVNAT_cbU{Pipt*-oiXDb!ikedQOh?c7>|4`IMGA+;# zyGTw2^s6xhxX*zV1bG@(rZ40WcnYuekDYB4t|gE5h#6<<^wiq{K3$a{>`)#N6OZ$+ zbW{g>fwnV}bGS9Kqj`Ywc!+7YKa(2W`AiW9%=0kDgVr*Zz;}}y+m}M`g27)QmA2ZG z>^QTKR#*Nht3LVHxHtX%|L3Y)&u=P!9s6kZaW(3n7pxrqnJm`jGn;;C_^u4+r7KSl z)V?+xwucJ4=-P8OgN9hno@ZvRO0b!hUl;EDm#kjirz$gU;ic7%aVpvk1Il(ky^4n zYvJIH6lQUCe>#qo=e0hwrv*7_Mk>iQ+nc)oEvqC&;i6~Euho@*&niRq%Uff+Q1Ir6 zoZcwHcG@s6gBgJGv{2?hv&s^p)_m}`eEe5cj>#+k%j@U9W&O194F6&a<;bNum%*=G zI-AvTDDa5vljpC5ei$v#Rcw>;Tc6MB`KeW_EPG^mJZ9q{(Zsu~6~aG}X95kdV%x?u zK?(RNX7k|nHICaagPOfE+`rWo!w>!C2?2Y*Z&N+jMjxkCebpKfUm@O({BB#7;+9V` zVz$cL?=`FZt~>Sxlx#TA$9iP>9vY-}^GvhZ7yTawW6?l5k zp5^!PJ!F=!W32PBRbzM{@=&bg;2jL)C$WE6Mcyls!$rw5xjc&kcrzDPZgVJ&w?*WX zBH#3s*~r{M?h_;roUxsP+7=6A8i zJD#W0x5hhl-|!l5$!53xx^or<%joe1S!GI=z`)28qlbzsuq@=LIdA8%CtzVB9jpzx z5<@$To#se^Ms>QPZ|6%)YmdC|l2wajK@^WYpd*&MW|bwm)%;fG@L?fxdMi(y+9QHD zG~|?_sO(74IQD~&_jI^hRf0)A|I6a!`aR8PE%$pw&K@_%k-ezjjIHCyo3#Nsy_bA~ ztI6{dJ0hXPXlCi~cVuL3T^fiSGza1%g2NJWjrUIE)F&Nt>wM`fN09F6DOqI-**T3i z2R^d9#3jL!k(0nK<+M)JAS%U@Gp0allUX?x3C&K#OCPC}l*GH6?8a#B(s z<1kQ`@hzKqVszy<(J1TCS%J&{P@m|Yc$rW0H213dCrOR%yfiGf^YMCszWMtazk6ZG z4_^~JQp$P@CDiX2w%gJ?vT0Y$aH~q^T^=R$gD$pb4rq)lk*%5}FJxm_L?Mg_kq@!_ z5cIaZ2>FovRP|Y{j_2^9rrJyABc?62HWv~Oqh*M@C~hkvfw&o zg&YHUJtA4oqiwuPq)xwbKk&dxief)NCOkEh`{IDzE)Q3Ta9M|dg(Tv&|9ut}`bY%( zh;Z0<-d&O-n=V;cIGeL+;{!$`WQlASvPO*0iZE8TV~y|&_6s}rfUNoy#SHaqQ&wqe zJ+0&)wi1gCU(o@0O0K~?82*d3X|~g>W$swJM(%ENQGK@l*0R0Kd__9YF(eD`K&*)6 zfkwMOU>$4?LCJ%shn3tn|KyuYYK&ahD?M_4DD%|^t8wvltS zS%&0aEnAEZB7sEPtTN;cCpq;Ao%x(5UrVKIjb}GjS5C_+^~_K||Lh$wWSqf5`e(Dg z+GE`N!mi)#vt6Uvr)RY!&5H+D&&m(Gb&5ScyIvAgl1E|22>a9=3Ex3S(x|70{LJ=Q zW{mNh?k7wdQ}LhjkG7JAo!+RAyp*A9Tcva5tPPBJvBLsyJt^UCUK`<8PO0iU8A?Vy zZM4Gj(0Ed;oy}J#qshE4!(`;2(R1xZxf=2oIrVAu5o@j}{bALUvJ1|^+&E+NOhV_$ zuRS?%fE9IkBHz8Oe)i#6JrgAjr4l{ZxD4o-`H?n)!nhP;Yh+Hi2YibqHKfM+H{Pd` zLrKN`aV$}9_am~(QMp4*aDgL;ItGOx#cyk+g7zm2Ej7x_mH z0$yNynF&Tlf_YSXLVa7a>eC2_dgT4_-mo)ovp3taN>_f&%Ze$++f$6{(w^H!YnRos zrp*w&yLK@YdQaInU3+1m&Wmc?^N|Ow`{9h+WktXB)^xQ&)?WMQ5rG`PofKuadNZpCF8oW_rwd1Q^?`FS*rn3>t%cy;nGCjaJ}`|jMG)lbotyapCsyH{!6?Q{6a{7CAR;lU*cAfEhB!jVhxQ`dY7tteR zhRh59u1XxZA$-QAKoNH%np@4luXn82HT9|rp2T{(+$x7~}!WR}=wyvG|_rXFNsbB@XF z5&t4D#4_XoksM-AdmE08fb%Y#oce@a>Mf7keNI+6(t3YVxzBpZtD&_y?Ghcp0k*po zxC|7eegB{d2pDT>^EYj_6!bt}Y_x1Od@HHX-YvxZ01ye|tk@EAGiWYUHax~GFc277 zJ@gZ*!!7oVD5=l(^058G>5-v+GKaRpiusW?_J@9;3znU=xmC#hc}4Zn7v``*Iid(` zk!5;`gV8>IX(khS1Y%#bjy9bY>f2vbpT#BQLK$7McOyYp(ag)gd{G`Xk0@xOtUyAI&Q7BK$e_p8XaaDa*Yn*}Ac!#YfuyHGU zQvve^t_pDrG3?`u+DlG`aW>@0vgouIAHgq;{v(Hsa)24&1fv1yKlFJ*QGGUl3_8PA zc*_|m4@FG+D3@=@9<4zlEO$hv?TJP8Ay3S)!&ad~HrLwZir<#yw4Gh;4q`NmV~Bo; zBy;$GdbpE+KARx6zMDhF{F=ZW=0o!qY<8Yt)e5MZGvo)D7pn1YM*g0hRj=$6Iz{#m ze~r|kVe|y6Wh+2zrIyVyGs>D*!-^nx7i879dDhFgpKfu#y6U6%kp886cVSj-nycn@ z#1W4yywjXF&E#-Pkqfyz=8+!>Bc9B_J`{TQ)T#vIC;tnPEs}%i%5ig^-AYm|k-qC5 z#_`(ieOgwJB_~*K^VXKRwHOyW%xEX5m7E^lg!!{zKs*iW#_(>~-;1*96CzRDQ!T$Z zt0cu+?0&?YF7jlTR8O{Tr0(7pawm4IhWUm$G9d~P`x}+8a#%;s7*fW2G4{kbBwm;N zIlj}@&yo)ze)_7S`fLmVx|4T->g4R9HTsF2#1i8r@JnzCeqgcjT+EC4>Z1Cv>9+O+ zk7}#LZ0(?BJuDLqxA9?EeA`vu=3;;_o{?3br1zqyb-$d zvZM=?hD}g;&&(=Mye5YUz9HXfnJzdFss0cdSPST z=qs@u5)C(3R}L1{M-~N+Fup}D91KJBW7wIoHV_RQwf*m~uUJnqyJXMViL-N7+{Yz8%18G;1C zM^F=SJSdaA2tE;shL&W-h{UMx*;Rd3YmCgLdruGe&paJ=$!2g}S=376J@6ZuIO7CT zg-l_K%yPgJB++OOUC=djz}IGB@FQpuzM3+zOi-EV)1qjyOGH1=6eI-Bdf|OY_4)d&GKD$4EcO*Gu}xqCGyquyVIqrU1L!f*Lhs4( zn5{>qu#Hg2YykV0$|@P}PnOXZ&1@yxVOf6P=X*8m_fkS-(5z*cu&H=Y!(*0XL$bhM z_)h#AwB{3z;DPXPhqLPYyTtC^7lfx7wOR`Y5zKYf@6F+Je>lLxN5k>w)#o+g^NMir z4F8T~)hq;OkqI^qtYag&=n&SHJ`+vQYwRj>yg+;A&5<{J-O?205%Vl#QStgIEmE+CsQhR0A7(bqCU_M2lc@}B3XJ(T!WtnL9K?_ z7$x;Fs|tLDeDJ^F0<08v3R$xKYtd5B65a}3#-k8jtcLtgNqzW8lS)HmAa7`9`ANRx z9kCEbPwWSF(vS=5aGqDyXSK#yMWe`;MRc@cG1O}C6D2JbKe5B)HBDonjAav$F+(n3 zEjvJb;4E6t`*%v}0~;dM@SiL(az|taCy;LZ0!R-e432S1#_-?djOcB{ebBQm$wWvO9K0H7tu-Mdz z=Gb?5N0e#N1Q;LcAX^q?FrM*}PMUxK_&5JM4Sbx2{W6{xYStSK+E;ihPKjkC8iV7+ z%5V!mhljB29p8wm$Q9t7@mY*>fTbf>4T7R!OQT9y*uj#aW~lsatvGuX{@mK&Vt>bCg*sAjn!xW$CyUBW_FmsvefOW_Lq2hQG4;~;5y47n2yjAvlZ|O`R6LS zgqOf$!5urx+h$7W17-1uXejzg*1|kL@gF>Z9!N932Z_VZ8PbPpyltkWK6C`%VF;a! zBC!G%6J0`EvBdVza$=GQEGYGTS5bY)GX5Q#0Dh6SqR-S$9ncVTg$Bz9lTRTR$J=U3 z`iC52jlkr@A6Nlok9sXKAsR6>X~@H{7swLMudckJs6OlgeIsLO|AUsyPNAjH6TVqg zK>i%r=1#Po`u=xOeNfV}W#AL~0^UVpXg|C)>A^-o3+@0(A+Km4@46|WCpkis5;OxD zMMAL~XfC!1Z^}1nqOV96-j&P^$n;f3^?_21he$cKLo4X1n8R=xHiP~^4wvGO)Vx zJw^3FRV_6gjsR085&H#p*y`1 z>ZDeBifsXT;(5Qfs6Mn0S;O;LBtmV_lV5lxP#YKy`qEn>5zqy85PE)JRiDo|);zO% zPLv($$cSDRo;fWX{PPv#_TIl6XXBU8Kepmit3hm@-OV9Oqq(Q?`+0l^09$P`bocAB zD0JVdjZY8xAXcx~+!01nkA`1yTUcr0Z`xj6`Tnf(l|O>ZXg7Ef3;=I!Mga1QEg?EJ zk72$KuYr7-B=8oS5(%?$I(!^lC)Qzur2T%o5Qob-;e@9K zjr9G?B+9W^;L6&;Kd*dJ^)*aX{e z^QG}P*dXMFQAUgA&Hvf_3366%E~?Mw^MOSf_d*`P!^j7+YsknlfQHH83Rc9%Rgsyu z6xD}SLl5xZ*deSR)`x6>%~P}A*nZ*z8&ks@THM2%ag3h!f9#JQUvXqhC=tnI#ssSz zm=|^=#G6kElFFQ3R>?4<=Em7hR=gXL`9Q4kKOF8#?f$^oE-s(ha}9am%{(O%07bCC zpnI?uXajGAMi|;d1`N%i1Kfd^fQrZs@AVOF%od+4qZrcNZeFae{750KjcRy*8zHvL zGZKo;;TMz#34#mBR+0h7Ym>*~T|ha!y+#5;?vluq(Miygr<;SwhleIt_ z@#-KpwAG?oT1O;EjDwXRsuKqOpar@J6&w5()Q?v)d0MkKFi*%7v>WE7In+`Ahz!VYAPI~N;PXuy z@DNBcaUf_Hs|b>TA|Nb_@>f^hSyZ1z8Xz~z)>tNtzJb?h1=J)q!CPV#kV0Z_qH`?p zPZ!n)`iF98DpHNNBStfvV|gPYQvTr?@xc5e^Fw{_Dyk362S4Z^*)cc+wlJ#)HpQ+$ zLFh?tgu0L&MmhF|`hKRUK6*xcX^|DYWNrdIwk#%ng@afD!^Om(#3r02=Ka~C`e-Bl zB8OmkdpKj6IEt`o0Uoz;02}KdOM)H1>hV^l5_^U$V2v%CMV-`58$cXfB@!p=Wg{!Z zkytvcJN@RZOeOW4#7y7Jzl`b@^*BE7&u zK`Ues%Z+wY2ed;2Y-R=eXcmw9-d9*3HCY5h$<)IC(3RW?qjbn9{s&87IXpOuCqq8p zUsNCV14>aEazK4HeqecSVmKRbwh?;d6uV%#Q|$FG7uAQogr?YN5We-#C}?>q8=b?; z@|#bhH0%&s!rPTf=!&k4y+gCP{8-USyZ28 z0O2g25PdXU2NexTV(rN;3FDzv&x<#!rE0L5`-) z*d?qxm==B`pV(cr%|<1$X5>PQ#vjP4Pf}?yr}imgXI$3uYJYIv0JOUDJ6R=4D(L}H z2JOXv7_LL|@KfZ57*oOOVe7FGcu;f{oVYzU$0Gmr*6<=mi0X7+|W$_fAhL+%oc$byg4f{XNQHd+e7-Q9` zuexjRoBaDlt;SA}BgF;?(ZBT^GEn>Eq$#Nj@5<81`Gp(S7JheB}_tB#I z;2&HvIW%;Q)ML%f_F2hTGQ*9aW9&WN6yN!=qWVl8Z4|)t9ot7uP?1Ot>7i%XF^~@y zi+0gpQ171<)n`7)GS5&6dRp8EB0&D3AO|)Y#DHcRPOvP+#|!JTIKeO*s26Kb&zM<( zEwH$k*wCynxZCgvT;+{cCHi2Jh-X3m=pP6Xt4aTen&7R;s##ieg6n7sR{zhc`h$iGu#w2OjSujauN-b^G{E*&8t%nk zW|i9HTAOa4$|^_HWw&m$!9y{AUHOy0B{nj;MOdr(yS5+6?>Qur6ohhSte zwGZ!C&0@mCp*`#+Z_g3wa%OYbU6S!2WdHT7 z)hFtz-OYaeOI9gbvG9zUO`;64S=gh0&3ayWlCPOP&ra{W1LNvh37^d>L1UuNoR#o3 zLFT`1_Vnkfr{~u_%}vYEy$ixf_jRG|*96_aE_e;?njXumC~mu@Z(ey=Xz`WdZt3a2 zW%XBbLS#q&7PJnYB=dt0N6(N3?72m2HbQ`O5Sel}Xq$J1<=8c4AaZ*6A61EM%Pu~H z^y~A)c~4kQJJfF?Bt~2CNtUayDAUFVKq$o7SRmpF%excJ;km#%t1JIiR3EVq+6SFM zwPbf}o)K5<8tBzV3oK^EgAz~SUsqQ?UsRush|wqFchhi1(jYb)y{4b!qm_9jMyAJD z*Ok>0dJ>}$BVk|25`zZ8=}?U53BQj`g6ibwi0*C1Czfb?sE_w$@xM^H??W4Z6AH9< z#@VdD&EZW0^&J!0Vdk64$&Jr3w}rT(NXLos0-cQ zA9(eJS@q?#{4R5I&7zPvf)&JvlGVU+8l7!i+(r_>yF}Go#|LwO)flk{ zoqbVJeQ=R65^|elJ;@r9NweG;b`5_(#)+7mnz7&bD!db8xnEpVpUnm#Zw-<+^iFwX zby+b4uE%16BJi7Qjepc=RWzelaysmv%XVyEkp`rr;RHK@hrqoc><3_%k} z5m=+v;bI8J6J$oaoy=NXjf(K!($D!GJ z63&yUxmQ-54{g+0pGjb`w8hC*v%Ni}Ubn3Usn>q*tlA}!;1#eQx`y;2b%twgbd)h3 z^2Rn-0vRiTlU1Mam*wBUSyu;7%)2(>8Qz)vFBvd$V7zB6M-J2rkTBVM z8=Js7FhYWyWA_+gun}yVyJS)iibT@!SgR}d&8kmwXT6B~a7pMv-2VGzl_zXOc~^uI zBtiGjdiueY1i5tP$%x)t-d;Pv+rCQZZm1UtL583@HU+9Xi<`ZDEv7N+0X4`D60Z&MO zvAwG+n~Lf~AI&FOq-QhS%tM$bvM9(#uFyt&CO#gYga_PQR3DfQO+icGAF-w7;_<2U zo6G2S!R`m%hmyaWf);XDuy}@3rh5UwRHvF4ss;@kj*Vw%B@IVp& z&D*+NWprUew0RfWDAPbO@QWyb`zs8k-Cnc0w-6NuqxsCFUkSIIBM8 z3Wj?4kOsZ;ex*<$6La3bg!fb56dc1Js=LU*$hY-9*bUJ>F`OK35M>H z*(BDo$c9WB+P)gBNlp(G`B}~boMZ1cXIzhSjEkI+Rgzkcb;sX8Q^v?Z)_h~!pBW66 zE#nSsxN(Ds4=v*E)$pdwoR(`$-&aJ(`I9qeD-p?|+z_k+dAa9>lF!U4*=ol>Z4S?D z$$Cb)7QFqDD#y)xxm1?Is5FOggdeAF+h_o{MmDn3R0`5h&ncqX)hxCH#krEKX_M-YgGd6O@ z)5sEeee?yb=NI15B7ZC~2oMB8n|O{lWtH}ixu$0Mk!YJ~Z&==PQPgjJ1Ctlzh@h)(1U z%*xt$1M!+s9+XBT#N09L8#H2^nhXH>bIvm|uq&%RA(MLRn{D5nRhCnNNRJrz<`C^c ziT&aGRkMg1itWiN%{9WZGgw5+G>|P)R*W8lSna@e(tn$`hzDcd&)He^IVIxOH{1Tm ztg>WhZ3R9Sf%V^HxcALI8HL1Ckh^9deew#A$|_m2JlZ9*mX|sx+x$>m`lGW-7tNs` zk)F-rVB87RMqEVZ2jmMH#>-mH48Mg9;x`s+HM}9VZpF*Bv;@m`jUUPzYlQHcnRm9) zQTxtYv`XxkNtz-gB17^IHXqUA1rRG(7T;}GE!MI;1#i*HsZY8z)U$IIrt_BvZZ)l8 z*SsOcFGklc>JpQQx_h&F>vBi@MI251ePihl4chEuO0@8pDgP+WUxXL~egpuVlI6nu!o^4t4pyICaE!epbn%7g-fXdx`jn zIj|*g(B|;MY4UhvAn;>w+%ON;oO}uU`Q&Jj=1kc>)4Ug&H)-WOsWDW%)>?S#30Y66 zf0A2UheqB2TWMJ{WEknTnbt_Gt&~7AkZ8t}c^_6zE4@B4otB@&V%wMiIb6%(-~&NZ zph|M`(9`Dg7=8c;mDC4!EXQy2_0Unv3o;*qXpquDuh>7EmxUhi6j+n@V3pK|-L$!+ zWDgjp;+N5mKH_=Ekb#f!M))P0X}}5{a#$A>)klWT`iB|(H(MUb}U2YxX^#SCoI zeqt%!fkPxu1LkqfI$nQ4GvmQETR!&RQb7C)KflLGP zj6`5Duu%Muw%P12%a{|d;?{H~mDFdJkuh0vN~U{gGgKt5E?G3` zE}8a2<&u7En^Ch_8-AppYS_P=+S(-#@guindWv;KqL7JpP2y`8#fXyT>%$P2K^OCt zJj7*uu$8=+uB4=Q`%D)4^t4?&HYe`sk?`J-qrIB?%#{NzUV#*>l(Bh*&lsoVSl*yi zTjD@nLv^X2{W^L}ppo&xEM(o9vgeWNkraUEbk54IKeOW)Z?WvM!fFlqYn@XcKo~lw z`p9zXoa$pd$j+U0tPT*G&Z!O}E+yKH?k&(6)ua{;(YEd( z)L&4RTGK3<5@}so$u1AwW#?KuB%*2Ib{?a*^OWqQwbgkFvedago|3WCee?4)#Xs@{ zR&qBbz#Vo^8I_k;GP$H?t3g~kXVNmS7l}(6Tk^=-sFmZFEj=5bmqe7yYWJ>V+A@B- z8An-OyQRI$Xty+e8D%d|Ga2_<9=%<|$JQO<)#bH&d3s6gx2$&WUZP%-*&MIkZ4XQy z%*uBUOpa0Kgm}o;=v=h}d&R*RGsG6Jw?+f)o)LOOrXCAT-hh0pmk%$y%eSjGW@jTM znWnd{|o;YWn%U*_EZE{+< z?sV&Q)wPZKD3kl8OVCAL#!(9A+~P~eIP2Qjr)AtJZCE4&l+rVmJ3cO<)zoO2Ch0I| zWi!<0c{8|_MY;7Fyhlhg_6UA+kMZ3(C>`a#c7~DCk+!i)Kai9bwauj^g=vu=A=7@$ zz@09E*5kBI=1xgv$|{?+LAKFQ(P4dM$ayLG@iU8ZH|1fPr8~M+{ZK#y-X!g2CMv+xp*_1kloZ?MwK*n+%oeR z!Whwdc$-=Ctj_rlna&%Y6GI7(JbmX;(NH8+`)MKg`JbE5Xx zlEi#p`JhRXq*Z2JawD_#ktBIe_u5^OB#rF%+T%+S@`JRVJQ(fdvq`z5R+d*=f8REZ zTTSCuB{GU%TyL*A$>=1b*hk0yL)cEZVtqZb&k>wF^1O2ZmXGc7tzA67bNyn3$=XfU z&i1a7r|q|P@l4|NlTuo!xM#9Mcc}1yt8EBU( z)*jes;PG*$&te`%Wn5$#cj81%z+iJr$ zUA9`tXPVJzy6}RCa`Iy*>Wt13Kc=z0$&Ve+dD9bG?A9`y`F*0H#S%Z}Mtji_%ZW@`53RN%%Yv;1^D9GN;>SEI zJNdDcpPKv_a|Ndrc6AM7jKW9vUGLmuDb^r=Suk1jZ2MF zU6~ZSI^`8loV+5~d3Z+Hlvms`oB7=>_ftIP9{=Qz$4Zc*e9k!0*p#`id!s3He{$}{ zkU!7QciigNuyI##O!NGvd446)jPKpnFQvIiYl>#(%Y9GL%*i{tmp2<=LPRGsBEm*b`CT-~ zMw^-=6P~qPo`y~HM!PlaM4dP4`5j;X5Mv)7r}SMf`lF8V5s@;>6C#=y5!w11t#Gq( zi&Mimu|}SSaPxMJOz+yv9=q**jX3Lb`dylGcNZ_&Dbz!t3jvgqd~BneHrhKCwv0X-jkT4`)kNOVu6PZ1&PsB2ytX$Pu%k7j(H>Kpk8Z}C z&>bsoSD6iGvdFHMjH(h7c^P>8?s-Rc)$*hEu50!oW-lX~-)uF>O2+Ta@EYvuGFG_K zFC^16NAo>XaTIq7b@wBRpq-H3L?MQL8z zyRnaj?(E|?EplzPHl^QA!JX3P6u(oPO}#ll?NY1S`@8#_1*|=?VzRMN7h8B>Cixr9 z+Zn!bOAS4`eSuM_%iGvh5DHNPz6Oey?wf+QVpRj#EOZ*b8GB5V-mW&-Rr7er2+!Ic zD&-yze8&DQ%&Z~9K?zPNlZLK#)MZ6anceH6udcclQXkJ!i!_X0$x}G0{A4pE>L3qLkuIo_Y?U8=cK->1e6E!5F2daGt-( zC6*S?#MGrlt?8GR+&o5k*48CS-1IXiu2=Cks?|y<$SO^;9ScMP3w5;G7IW)JS)_LRhC_jt&T@_<5(R$nPS`A z=(4S4e&)orJEErhj>XVMor_KZS+&JV-`U2&ydgS4~nnmexbe{4G-Zr~R8EBQY9&~{vJTYQx ze`n+{*70{qPF4qr?v6p~Rsq=?+cMN^7`yZX8xZqAWwhP3Z*jY0qo{`Ra_mfee~xvD z@6WL$-0%G}RNQ61>}nI0DpF2ArK>L4)JKinFI0jZmBhK#NM~qxySj2YX3H6+hnAp2 zd()xKK=SNa|2w_0qKey7SjD(b^x*H7oia3@>lliq4kY=FG#kex1zr3`j_uC%=eH2_ z#P7xU?Qi&X{U+DySv2LbI4f=JM+M`|)-{=`XUjlSCUcJJWuGL2{S+CRLD6*uYaeN;wpe5z?w&}HudQ+Ap_uaO%C(n|MBUkP< zrgz)UvkyU=*EWMjzM$W0#P6w8PHJ?>BUN;`EMHxp2X*6hBHH-$w)oY~DJ>10WTzt~D;ZPE7Fb)ps z_3`o7K9V@u@cdOLIr8Pr(?Qiy6Pa94PC1Vq>7vVLtq+}I_dF`IP51UzbTeiYt zlJtCt{0t7Gg;wINmEXc5WXFV?hT^@pZrjL*c++pkna!v>*PGw*ob6ku-yVzK@mo;E zZ(?fcQ#_jNZ!TRAYo6k3jMqc~VNA*3iIBlbX;$ieqG>c7kL9aZsVH|Dmek*5dh%FO zX6iW}=#m?sjW%RA>zTjxnw#irUfdI>*Rs=J_u6Ag&~n$Z+nYS)!xG_8i{&#ehWNjz#!Kt^Baunt_0}zXnP%k~Y_luI$dn z+o=#qk|&xhVQlr#FXlDJ=b)7B$>RGv9$!m1rsvtHmJsXXmSVDm?Uk&GFVgl?SNqot zlv+X|{C@o?i34LxB~5g{Z+s_~a*a)ol+a&nT|JA4C3GxedVcG`gv|&emE$JAAwM{V zpOAEngW%BqIBKS~%1^o1cDeAeQ|?r*q+e2VF)by!M{Ub#3e)n8OR`YDBM(tLKa10* zM_b|-DSspS3aE^~oP334oR){0^Y=J}CmwxD&etbHp|tzX6dn2 zkuQfjLL{hZ@|OGjv+kY_Nia9mxBk~mzce5jskdu=UU_QGi77* z^`>dXmp$%M#tG+{dbWNT`DEt=7TD32^1f+|3{uVUb|pIDQGIF*3_nB8nRz3QAW}Nv z9;wSm`AVxYAGN%a(-9EOXa&kPK9k&_p6?A6wplUqAL4O1>zvF-A-18gQ~bC1GV zp`my*$L(~#ew5&|<&Ha|O~M=QZ*p~~8MUO=*UYb(&CiJGOS^Jei3=f(5k&|1jS zr74Z|efPP3SsDii!X?A`>~SjWYZ6h9eVw1&$1{G$exG5Yw+>&QB z3zMH!Tc)fcld?(O{qg)sY1>UQE&35Hnmk?gKk+> z9%q}lgLCp$x(^(t`^r2brBO;90h3ww*2vC##IJg}Z~l7a`5Z~))=R79yUO~T=hIT? zTRD)S`r6o==vFa|N5Y&{nQ>kvcTXvv7gFlq1>S8#N{>^X-+3=i`x%pldFk)vj9oJH zSYGL|hPk|YeMXhG+{DifNlw!u_-;uhHI_v3DOt_;IX(wq@;PQd7t@XTGB@M(S(Mz`gU@yyN9_}qj=X8VCQm-6ZKK@>jP224-%;WL;^#_z&aPufrKCo33Bn>n zHKu%y?@H#fnjR_e9lH7@6&g6YvNomXjF1^s+f(=m{@Q3koS90YCPov6rD6WuTPklj z_WT{@PCMQBM&CK-@ug=1csrZL4ny4VdA%D4tI})r&$WTGioZ+>cz+VQ4+a>L{<{63 zEIsKpxC||ZCn#M$V2skyT$}SuG;{XKGs7>PLH3~vXXEvO#HG?Mli$=GZHc2iQ6`R# zc&lKJ#PK}5fF~!i#HFlZyqB9aFl`NeZ?GZ#%eRKPS)X|4tCTf#DIVJ|F0bVEN8rv^ z*HA`cy^m%CoGWD(hK!2z&uhrdv&^60;YqiWl7QvcI~LZ~>@)0#t+qNlAS0|D`SRGp z!7X_SM=$BO5p%Do(yy_(qZrg9iY|(0+?(6c==jBE`0#&t^;+y{64L*+!A}Byf{s9oav{%ECTKn~>Eo)@2sl)}Vjp~wrwD_gDZdiKKUB)a$+qujh>0$$G8 zC8uz**Ve^vXpxI;>%8X4c7(~J{;(mmJJ__m)QR}&!l{b^D>q( z*S0Phlcuy01*PFwl_SoEAZ>)}nwfmB{ z;$;3=xJV5gtNXYKtFO%{qKKMYLRvdTJJ(J)<~G$WZM^!mPd|_E9If_Rjgp*HGfHd9 zmHd+WzgTUHb40$OAKjjK98ok^hCZD7UA8jCkKDS_+>n2C{YdADbJsBw$-2(<;ShML zwx_(8$zT(S#OS4qN}g4*`nzUD)wN;S{^Y>SVl6WtY*bV(QX}N)T%@kfn-8{ipI(=BsS`ZRRpiro{(_RMOfz40s5TLeDP`ie7JnJhURet_D?35QttrJe? ztKzl8syjwwvgpf@PG6xsjaSI;_DPf3V{Eo;4xCEGK+-*n*5}XPr{=IMwr-^@ttC53 z(O;x=+?YKtze+o$^J#fS>(#p0dbG8BUXD`J8XX>j-1{oIsP>oNx)Z+=|WS+!^7TJ|7X!6*N1R&UX^m zJAEA~Ns6tGW}M+`JDuXo8UI1%#)}FZk%L;gXK2{fdC|YEXZ5-!^uL_hv&gPIu3NCQ z-uNose&oMwy=nWTNpH-T!A<<>q&F6`nAKKxMpRKWlg<|Csz*RX%sg91s_{Bp$FK1^ zT=xX=n%h2)!>)(&B#X?`NP8S#73&_SiH1BfEJg0|x>rS6&C-Xni{e!rb*AD3$5_kh zi?@9KzPJPp_oi*ryalG)^I|V#Y8YeZ^Boj?V1{Fn)aI&nY7@?N`4gO7qMHv4@S$l<8vIsw|>~=5aSx6c3G|nQ*tQeCo~^7{$}5d|Eeu zaOK*S!z<|#JdjY^$9LNdS@6kbfIf0@I#iY|sM`$Jbs=2cH`xruK8F3ewA-$-o22EQ zCY!PR3`YLU(s+fv{Nj3zs!lUY74I}LWv<;~KB6ps-EKLeHoFDdmF4nU=Z~v=rk2+` z%`DBES?c=}cog8#T^zL=DjYXz&l^JqFXQ2;J3X?9_WB)?sqsb@p@SkIm$C86Pse|Y zl;4i{nEBX7Z=6-noZFn0hW4Yk@n*P~#cz&ZitFNO69dg_HRxf=TB$y>REw1EEnP<2 zp_b`GSLv=1xb%>KTlJO=H`?NM4AWHH?GrDr2Dzt=Tq zeUS-uOFz48-w^fYm11$!EuNoQOh1-68xe}hc6rM=>-t_Iv$?Yo7egE=3H8~ME}`^8 zx*ywXU#C8vz3%tUX?q>#*K=(}SJtwgo2BP%ORf%)6LH|p3k+;ZSA5?r+QbN@<@K&XAv4_a;3^gJiED0 zo0>H`BJ8hkBj!}i#!T6fI6LBTu;`*W9O-P6uEx*Z(wgCcWXYd7+nPbjcPV65VcKobP3Og*K!IPF5+M2X% zxmuPx_l30tiUIny3>4&d8Zt?*7iHzO`#rwdx>Su8;kPWaGc@-FEaNC$*nQ0GOKOC% z{T^h`)LOqw{J(6Nd+9~m-;N=P%T>paMYVC8VT%fIXy{(xaw%eq@x*) z2?h5fuJo*D)nz4nK2ddh#%qYbW7}`_Mz|b$qA}ogi!z{8ca&jQ=Us(7?LqW{h|*2o ziwBCR7KyjYa%$Y2gM3b`oLZiSs%LHw{Y;tWw{0Qv>~>2!l}49wj?yp*TBIDX?PVx0 z<o3Jt{vZlSJMI&uP*{Y1^U_j4xenu&ZQ}kPVwH z$S0+EFD+NpRfb)~Ymvj^AL!X~I_4ux7P_9dtI|%@I)+taJkDnjNZ&Z?NKyEYvy%3H zq`6G1Mk^efN~f9@XkMMG=VvVAC+yKxR~wDwYdE}w>oMik7srBKW4h2H$IC1O`THto zYejRNb>5gR64m5Y6U#~NWBb^i`;i`p9T%x14{h#n*7*=?3lc-C`?X~}?wGx-`zI`w zw6@!0&&!AQ=q%JwzrDUi_|Vi4toe{m=JcmK22A0SvyRp3dYPK-jy7Pg$K|`v(@NnI z^RZwW--j@*m6BfPjGr;==B+oc(@mv1U%Z?yJ2`L3^h(~Suib4+V&gu>i?ZINt%>*1 zXa%BZTCb8iQ*!2eG`gHoi+o-@bJKSV?6)w}yF%--3O$^cW6P`I%pnW4sO;2xgoMZk zb?Zo~&Zf8R*7vluO8#A1(^k=Qa{aP8o;QTU7XQUN2BduCvU5&#UZrizGIok+bF3_j zk-HD!GV%Vfp0@FKzD(CSv)sDc+(1*?(N|i3d^g7R*B{&K5JZzk6&p!^uz|v7Lzp1V zG55rZ+PXL$s5ukfo^Dz1I zOxqHLMV36e4^3x0;~m0`tLcpAH2R~xNaCEqGIFXaUzPybz&7tC~ zOyQZ+((HBD6HRNb=f=pB!dGd%YiUxApE?@hZRn~(1|pVG|YmvJNB z{Zg`)8poWtF)uefE9$m8joEz%V(fyUyA&^$VYxl?myWWQXJ40B^7=-Ga7xixcZA^M z6GNKajBHX_!^PH}wc~-3x3l26G`2IIyyngQoA>Q3wAp!N8a6LSKz73s;rylh{N*vE zDa~tPk73IsEnRO;-#XsT!i)@!+9{e#N8$1Aw|zb$e-)o+0aK%UR!0-X#~B`tU@Rwx zY+l#mv3l%fb63bWN@}xIHy3<>Y)<hi8Fj!v$-mRmWNeXnA&gl_Lo5&3Tw%c-j*Fz3*gLh$qX_PGTz2Amu`=$| zQ4IT1h+_TN6KY7S`t8*CF%_*8C(`KCrD$;(u2X1vC3`g6r`OUv^$T1tT9hG2s3;D4 zjqug`C>@-y2Cz)K2F^BX7#Dd_L)(fizuvK;#V)_rMi%f;-oW)Wy>}j*^?Up5m&Yvq zxPp3wU{cYd)zP&1X763%nzE2@zt&4Lp|bpew;Ou8lr5$yP6O$6oL?y|+dS^Z+QkYQ zW51MHA7l4CLr;bc;Z%DhMaa>v#`hZ^>SHzDHoF?%j~;ZFZ&$hB%P?!*RfAoXCD2ns zx#_2L)v+Y?@htZ{x^dacu^E#5elI`Sj5d|!HQi=lPhHnb^}1ezmvig28AeTM$7C~* zsAbs<#|~~ud{t>ZP7*5Uw;9u#%DP4`cTHtH@)BDl;W1ewJP&?RRwaJUypsDD`A?oT zZ`kxS@*X8M601vshH6YXNG7_DkycF)Vx2Df4h^k71#OeB}_o>l(w8 z?FiF7W0y?xoa|Xyjp-O~{1r_eTeu86c8F!zP#>DuFT?a%TGb!dkyG%<2Ko-~;Y8`u zr4n7|x%qgXiphpKUuIjN>UeRKtfl-XoF&`l_ytOIM-g^)zFnn6XRixdb=PIFdpgcA z-I2xL$nlkXGSNjbRJ!N78b8;Lu=00c13$?N^lL9=%9r+QFLz4MbF(tiz;4ZzJrF8T z4MW!Rzzj=_r$ge?GUq-*LHgx&Ev_rm4s0eV%ZN_cf2}=g!CBWWc`-Cj(%!Fe<6*w_ z&4beKVN5h{mX*@o%gP$~8N&*TlrCJ>ZHwBYskzpujvncY?3&kxggE`IKY8mG+Yt~o z$ZC5HO=_h^KX@{?SM3;xh$5vC>?~%{T^&KHMg1DF%y}TR*s0znSK^kg=TfN2_niID z=9jV*KUnJ{$_xK7*Uq^VTPW#3KR|uT^BDw8VzSJp6?ADg1 z41jD!uey&B-bRO0y6Lkdx@)6N%^I6~)VLf$M#_y6ZshBrzioM#@R72rhJ3P z_~|^A$K(ALp#-z|+~Jf>Ko2eI_iS2Mp2{ty>(O|-RpP1SwU$wSI-|2l`&0Ixn4)R_ z(|cclKU^*hJEr%j8K2v5Sk^Ah?Yw;?REGR?o{esMg!SQ#qdV8b^p3RfMwny0G|?oW zIg28m0p(OS36sps$Ay%qbctMs21095)ytQ@NRbCmxKvxua{M!_cq^rdjF94pDSH$UL(HjS{!JB1YcoBcx#(w0OiAV>IO^<>O2aB!A!~i)pX8N1}XC^yIAv}0O0D{jSB-*LJ)*epM7<=Zu+@$R@8jgs}h_&IU7 z-;XSFgke}(yp@utlG!4qvbk7oDZkE&1X%%DjC8!QJ-SoUwmuOpwYV?0x|_KTSrc)= zId`Jki)EvTrfl81_UNOx!dw0Jqa*{9m;au3k3QP$a&B_#S+p`g$E>5_IAQ+MZEdW1 z@GhOpFTHJ3C&AZXJ8{`HDT~L^}4{9%VH8d_?ZbAM&K~Px+Cbzq7-! z(lS+T3@BzDO_Ha;cu^j-0ycynzZl zh29yuZ?=FtRK6p@uAOfiXft_#S5<$hI{{hqgE*M)A)YugcW;iAP5zw14LifA3$;Wgraq%-2G zbET{XB9wLw%ZOX*J)?%U65Q{Wj4YbyD+%(vj?uS!CT(+k1RlbrIKNrd;e zDoY@$Xys+P-@57}WVg&lRqNIf``-5P-8MrK-5-riHls~tQ7-nbu}7S2hSsmnHxmO% z#!5&#rk!t)sAbuVHqPjp+2=bO_S=kUW?$20q}~hW*udTcS9j|g2KiJ_E3REy`AG9Uk_*Wl7G46id~a-5cfMdWNz zek<}D&)-k{_PyQLhu`tcP~kiDLKZE~Gx!Xgevb1DcGe;}lk&0lGHP3LKV$keZ)S;B zyA_e27_)RJ0Zn52pfjayPw6g^k*F?ScG+s-<$g|<*lM?&sYn|-TBJC%M%^hsJ`Y6g zu}hvWW8@yA%oC8A7XMt9b_Tg}+8MP|sJ7(&cWqQFyWsUMhHBe2oG4g5&Kwyv7t4d0 zrkPEYcEU;Zw{B@g=YIV>zH_u3Q%Rpna^6kO59#J&wWaN)Q+b#p&L^HSTjuAS0=uHT z{d)Vp6piQ^QdeqY=HW+fU5j%AdYdjy+&~r=;r!y<5N_IN)+$$C$FNnobuG>f;mnB} z^4p?_Tj|BPq4GQ@k{;2DS8?~*scFxZu5}6rD&K{LX^tn^KBP9v(VQ=$v8nXvhpyVX zF0izZCXt^Z_@5+x4A+h;0 z9?L43T!6Bi9x1k?Q=KtvDjhZ{FuiW?h=NxW-iXU~Du{zbrq)9%-zBZThIHm_>^)av z-+(s)#ig?~zRO0xM_-0?dfg|Fbgp-{hSexTnl}GPV`{b?HdL{xv|*9#1>=nE+#+X% zqvGs^_jf#b%^Mk@Mbi1SyfW_rikQ6>9z?hOIn%{?IYJFid(|*r>Eu|N?VrE&cC-Nv zWnUfNc3CFTa=ke{?eGBx#jfBtkYCAMKPPfmI4~nX8lTGNn^kF!vQ9gE7}AJQu6P7R z!9*TQptaqRhEcdHezB_?f5$~(K2b&U($f9bRY!8S1bXr;_X|ZqX?a|?VD1^}dXtw) zT(;iGjyj@U&I}Ly-o|=^8{EXUNkXReF<6ad>5XectWAywWXy;hyo-U)_wlye;3St}D zXDz3wAQiznQeWm++7uPUSq9Vp;u%J?76oZ(}K1>#pbrLtXP0^AWKvcA0IK-nMS>b3>9- z?+;Sr<#+X`U1Lc!j;z-6jcw^AHzn!q&R*$`;S6A$hv}E^rDHDaon9L+O!fjrqby=Np(9<=4OEYZ;IQHHxrLwVA1T$hHu( zmXV`s+MN_;T}Hia&0+5g**w=A$4~KyxqIY(Jm;vQe~%`3sho4}OcUBGO?Mut2h!&h zqToqkz9FeI3%#*M%b_Ne@d(#!PkKJZt>wL*%gBo%NkZ|%I^%v?(wV}RxjIA5ZlmPY zT>h<&`nbs0R&!%&hef@UcG%h(vw+LcjjAS$f7W z+T>nKd7WI(Quq8DYsPT9?dr9AVrb*msFXS>d_vYk8PfiIlk>A*mc~W)^w{Z;vcFCb z?jsuTGxj?__Nnv0%Ne`mU=!@BCWNIQDB}F7ja%-+7pae0WCI!>P2K$ZBJb2u=}$Bf{lj zA`pLm#Gv^0`07pDqD^`u?>(*OSf3dvrLhElb=Oc*4Im4EK;erpUk3AmDey<`zhVaf=)I|-1A5lbr92vibL{~ zinKsW(x0J7OZ4pbQR7GL$TWSkk^5A%l{YJ5F-n!>|J2%kO68*9DgS5Dv!gbP1iG@^ ziWAUwWZIuYqoy^OH?169Svy7*t+Gs0Q&)X{(kzq8@y?^76SQsO4$djA(S7sJ)Sxu^ zD)+a`h)?Q%o_gi^%IoE6d4nPUT(39Jr=_wz(!`PfdCb6`HJ?`Zal)LsjQ2 z^l-Z(&G0jeS(;eGTwa@{x8){&Zb)+4{c+vz>QB2y{IfJ`sK%76miQdyP5UKv@;Q0y zi{~3D7~khG3r}%@BBaUZY&@SME8y6%+vh0e?$_kW=d^9K`+zPRJwI0QH5BXRbK;Sq zuKuKa&LU%BjQTp};Tu_*t~f{Z?w8aOpOcrFq?OW=^ehMNQ0uz+m7g!E%UT+_F81bt zw*P0>yEZR4=e}OCAhIHaGQ|HRB|er5dLA{Q8%Eui7H}0ycT-($Fn2 zi?m-pV2sj{mIJeVA-M+j(rC*Mkt3*+Y(RR(J$DFS#GWZ$FCI&nV%>fTL-$ngi7a7l zia{mUB3Zv~PwlibZAkAJGao>iq{UCHG8W!5{P_Ov48L8SZ!`h!^SsxEmUh==HZPr3 z*G&A4zoTP3E@0fzh(WsNx*9)s%Z#SnFTUbw+(+tc7tZ!O`}|A^&dwW8Kq6?{G@gJ) znRY-6vy9GRX)W4f5+C!LCp}upkK}kxXr!#h^@&fwc8-AhW!SU=I`w;?5*f~m6=|jP zCmky?=hW{Ie|!gG>73(=GHwu$yB3XKewy2hw7-pv$qJ|s9x0^lRUDs+c0Q}aA`Y?& zCA`kFSG3YK&FZeN8d@IiTwcj({(5~_ot!sjXgSsgt~H}%YrX0+w>tYDjc_M9vsXJvV8bPL2o>)dLtk1e!X z)(cb8Z^yHuuG>OGe)HN?O82ssQMxSTGGwQ&dGtm0t-ChIszZ|5E*<({+51XwuZ5&t z^J@bb#U)(YkjCM>K}ZOqPZ#jv;)|7zF40c)PxWB?rFFSDoM(o;X_F7aRQ;ZFzBxG_ zdk^vaz>L4+A$|2GrYG7g$7ouy*%0S{0!)Q9E;O_H>X9rvWxPNtdsN_jjv6M<`N?- zzbgIXYc%f(P_?V?U^mCExorn|z8e!V&Fk}Fl76L6_&)<&C}H8wFySAAn6l=VO& zW@Ef2=rQ3C%|aJllqXChFkN-8lExv1`S3Vy<-2i++kW|&MMr7+t-NubSi@(qr)@=^ zPj6~bd%QHIM{O&S_Q8vIgH&F_t-bT6+XJg_{r0*9Blh!Veh;jcE^a+f1fM+I8`r@Y z+3BrobsRu$S@z$#-j#KAgxAmYDeGFN^2wHUMQS96-8iD1b#2?fGFgq|RUyjs2!Fg& zz*xS+k!LE`B;PTOL6P@X%;|V@D1xYKOxokgQi-E&30rIo3gk=MbMcACH)_#(;S=xq zBKX8TzHuiHjUfGs;avL{K_fZ5r>#&K-iX@Hts&`Z;~g?h$~C#?D^xt}q8n|GXrRy%E7dwoQKWmA_OZ7z$l1gtm>i_@JMsKBu!rF+W>@pw`-m0pZiQVX-vd6k zxq9phy(g65Wth$AYKL7FQqfb&Kc%12RgX5Pk7v1GkwmHGkp}f6g30pKshqMri`a&G z>GC^{0v0Lzz{un6lGe%YOm?SkcZ6OY@ucU_un(i+Q~Br=vRtOs8C!!VEi+C|-rZ)Y zoV~IP?@oN?x+9;@Sz+FK1m|b_^o(b~O_nh-Y?7XtLGd!336A;G$4M}$BESC34R`kO5<1#Us+h`F z_r{MLmp#X^j_2TXTb3BJYDz0!NnDZ4ai8?qbkidMq*HN0dTfmSd6egLznqpbyKYus zy`?OEBgrIXW_O0T-IOx3{dJ3#D`ggw&s(p{v80x`UQ#Pr%FlGydxloD^=GjfQuf$e zJgg~hxz)QAf-SMf{WAyL9{c*vw8zCBIOW9;?0|bqv+avonumGbbEQ{QM&N5-zbLvyl_W^}f0#TTJeT}vt7?SQPqxaGUPk6(UTl5(}N z#LJ~5EVZk3TEfU|8yDAK8=1W!2})~Y%0u|rlsww}^B&TkfVJ#u*D`GKB2wJuHhxQ* zIAnW$r?vIwHm!7hOL6;n?YrWw60d0;c5Mv*yNI-=c%8z2T_fX+`Q+&K@f{iW*)_7l z&H3-$ab(?Rw9&nv5pTuq^19mGz>f>j4Qt-u)_GYa(|5NgUF{yW z>Kb=I0+btUuf|~SVIfqHn&)40+1`(j8ruEgY!d}?PW(~7IVUeW23}D4vKsTzu`9=l z-UtyuRieMH*lHRoQK| zUbZ{^l&(64r#_zLe%T=UL+SVe_vh(Z8PHF69zVO}YhIS2;|HqvGsRPrIcU%xyVp+9 zOO=#MV4409sVnysnG_J3Z>&KHZz*n)%|IQf>&h_D41+9ye@u zc@B;0e!{U$KH4ESfDY!=){ZpcNWN!M#L&+VaIou~S&TGdrW|QpK4Ol?c)I9>?~iFB zuMU;uv)i%Kvgf0W?f29h;SA^rkK8(=LEWgyu1IRSB&3Y|}nbRz-S zNLrMhry^PD#`zmHN0;LR+8H@0Cb@`d;#3d^o8`L>n{HbS)2<;sc0P7KpLj(wC;23k zrM}hWQ+ca?i(%2dN;Qj@_Uy5bZcC?8us%11vK3+{mb`O@FLe+v0T5U)F2A>Cfs8#~NugBK?z{cG)#Ak#C3UHpt5vyW}*k z1f{z7F7lVy=?YQ7?RmM zj7G%L<}!Qj%2GQY-KM+mWCSa33@dkKF(ZSr6}frBSi_}hj&LMf`P3decjtK}sJfgS z9X!L{cwPMJuFI&B&Qxi%nE5J1cj!8rS^8cqMs*nF%Lji7OxyLf;IWS~8wr3_|wninVQ4L2ma565hI*(G>tQwL=5J{=Wz;ozOi@YL;~8< zk{&JLUY8;9CWX69FC=Z_N{iWzCQrwb7{{A2wo+}970FbeG`2^-po+Ise#OsN>GR4u zrK??wwjGBpV6V^e#1C667w*O6Ge-HTw!jfiWe z%m8-g1ue95;${ZQtj_U|9@;wQXBM;ZUe4I|Y_d8a;VB=9zlIVfU&B$<$(oNOJ1aEh zSSOvIipTx>kWNW9(sOsItUq>usE$?&Wu083sYK)+nJS7+)8B1Zf5vEh`qN59L?<8p zl>-}+fA+q~LHf&~zqE9t)8DYPW^SdTFMnH9_h_@Mf%7aq-fW{lIb7SQwypd~Pc*d}49i z_1!S=iOub<9kwO2@!TQb=enQU8`C3$-8G8iesdA+s`~=ww8#^VQ-0f4m#jvkJ<^~P znV<9OkNX1oT|ZN*nTu0eXm6r4wC^4th0;Tj2BTEc)O4i59d5xCop(hVX5)rOf;OgI z8+XJok3YV~tcyRsBei47i9d^3s;=3=zLMW*oz7I@KXPKVc-8FuqvzB`mJkcCs3DEz z)GGIze#Xj}cU0QT>7xC-CHsoA?p8b2w)J9A!`FrNjoxbneAreRMX_$(x+vh+VoUo#@B!Fy1=>&83T|Z?j#??i7C;6K&>bMw{Oq6CtrFD@zMEzl1jAP3_3E7zOJaV0*jiQ(I z!Nj6@j`br zr8UpeVu8k}Ep1oYmOVY1Oy=A*Mm?lw=+Kb%rL)7FU0Jz%I4(GN}TvVY2x=AOW zy@^{^R<5>>_Wuv5o_Qg1sX8s;jJz&40|G#YO^}l(C^Z)$1FSzn0 zZ~ojPes=YtjRMZ8?)}T?ncCM+S0%r(`uwB7)Y=WYP&*m@xO?^BZK|4K)9jDVU3}Bp z+NN_aUU_qM?(Wr1kEnjnxIg3O6R$pe-P)0hF28E+x`VT`=dL~b;L&T3)V}{pRoAIi zF~{h4`ci5H%6v*&kAV=)=TQF;>pq(9mKg#OZVb=rS1X0xBIfYKlHcuz54X~{J*dJ zr)A?(M)@}-*@A^ZV_FsMI>cdy9U9lc^?{0vp zNdhw^@GB~|75mx;zwHOU;yd>}{T?5@-9yZ7upZ}*O!=WN}*YtO!|JI>m@eea%K+jj2VHpB53 z9XWXA+DZ@9v$7}gGdc_!z6;a4tr;tzb_;5Dy&-n({Pas0*aKGtQ6 z=@7h4d)JOUcWv#^rl(wW@bKE<^{{=jCQQPYDSY>>EKsrVz2nON`>)S=(p?YymR-Adp0|D9u6;YUZr!ocghIZ@Y5Q2R`<_4}aOuzOh&cpEVO0 zkH@Q@{vqq_XX@XYfd@&i*&ms$r`&Y?^x`3-tAkr?BBI_>(1?4wx7FmmUO8~pFHtsNtgT1>xoal z=eaL`(UTu|+5S6z;rY&A;bqsXU4CTW!6R!|UVqc`YVt-(E<^ULN0TEqqRNhRhQVi4JScX=SAY1x zo|jzslGok)Q`_J9hJXIPOBR;BKM5J;N*wELuUgppXv$vA2A*^Ik?U_dyy?jGn_BUJ)zVBTZy#FJwJLjWsyx-|ZZ!VU@e&&a^ zod4Jly!1(5`3>LnmQTF(8OL7?YdM*{2ajBS)uxNCetz2vci6$5=j`8c-g$fW?b);c zydB&2o^#HgeY^MV-E-cSz5BN9-+JzjOglIYz?BWa{n5Mvc;m`VyxgTBUdjXAF@Y0&qrm1t?``cc(y4FJw&O}wugT1^r+<8P^;OC?IA!V6NB8~WOCI~s@B8QXT=bg%y!6A5 zmb6mNrmhBJ5Pq#{;LX+NW2;ZuHML;YAO_~;W1B8h;IE106q__d4aLsQQ21Crr;(m{ zU)8W?`cTR6W^P*}G|d4Q4IDPd0bg8|-yEU-@#=hYzJw(5BSrAV-0jzxwj;->1u-5t1GLYUtN{A zku6QtkBoNZmhu{>w0Vl*+4e#oq{r4Q0YIq|M469Fex_8RyO6`T<~ z{D;5$=Bh!P!}mK>-|<FPU1_fM<)@wxY^>cvJruet}HeE;e^KKd@z{rK$9 zSKl8JzJFc696s>( zi}6Et%KldY^5F95nnS+YL?(BPo|ci8puklAR+}&?bm|-lt_1nm%}osW@X*!|SwSn( zQr*1r(m;sc>$>=|aPjxME`EEs_y=7Vzb#z+-L8w@5ib5kb+OsiaQged@;fT(CN4hi zm!8*iaj(e#7u8Lz{{DNY`wi7a8Ou$LhR(7H9}Xwq7LFee$4`XgQ{nhrIQ}gho2vpO z6_`Z+9#oyTU(x?}e(_D8dfSuEeZm9QKJ~K~{nwk`s%COaQBxmR6{>#CvIQRrCm$P* z`-kdL)SnFB9}|xIgzxy?w}U-N)Z&fU~&LreHO*3_>FKi(G(;`Cd>CxJIW;Ge?hjp6vZaO?`dZw{Z& z569tfJU1LX_l$5{5sqhuN^lp-wnq#;dn ze0?~In|0ZT|K{$epa1)N&iUbk-+T3QulVe^&H89)(l^Z0te-jf@qhp6C*SZzfB%{f zz4jGP`}yb2-K;x>+W9+1t-$S-kA(w6$KR#1|KtCPX?WEsUwrM~yyJ`ue(1BO?Y(U8 zAG~Pp#;PsH8hh{1u0ILKH-_VDLd%~Sj^7I3zbPD#3E#gte7-mwFA2xDhT}uw_?B?2 zhHJM8$2s9REByZN;rRJ*d|Nmk8_s=YIPM;f;;#P3)9!G^dp`S*PyX&7d&7tB`oVj> zVD7G>$^0Gb>V3nHkB8%>;rQCnv;*Pz?eP8E!?8Df{~zJ=JHqil!}0QP{6RRrGaR=K z*X|gO+l2!l4oE*Y96Q6c{}qmRhvQ}8I4_*r7mj;`qqy7mIQ`{+`lv_!!G+)SL;v#` zH@^ApAD_G1ZwoEq?^w4V7JmF`IKC?!mxiVt49E9`@2?8SKZIjfIQ}Laj|j)^aQtgH z?i}v!{?pC@%V83Quuv#IQ}*quMNll3CDMb;|s#I?+c&*I~-34 z-}i*iFASf=1>YOK|3Wxk9gg$E@5hDXHR1a!!@)=)sPdF>6qD|AH$CS1bI*R^Oz3-?IH!20fHphT@VE^Jk%y*M;M<(6r0L@qzID`@`|1@cn{t{A2k3-f)~5j@O6d zk>U8eaJ(@bKM;=J3CB~yeUA#CUmQMvFnqoz9B&B6h2i&;!|^5IDDL+2zyI}DfA!n% zw*UWp{FJBP@w>kEwsT9&-9k(FJ0>x=4L|-o9QO>(dUW_KZrVp)`O)9`%#*Kt^#$+# zqPM^43xDK^b2sfvLhbw=YufF?kG}}Vo5JyyaJ)Gj#m#&BRXcBf>)yZqncE-v^;hmc z`}6OdyLopBwexqZdAA8aKEa7_6gO-2W8b~!y-(QktZ#hmzkc(b&wlk!&)qC=5r4;; zMLRzkj;98O{$lw2(QrI1eE)3tyjS?VA{=Ys_@VIohr{tB;V5qY1AhH!@BIJlT?arE z$JfVRW3LevJ9c`pavVo5b`3@a6$M2=z}~QT#oiSZ6??<3QDaYH>^)Iqj3#QVu^av7 z&F$Np+nYV^&V$qZzfo@YelzdQdsE)LDZ3Y~ur6Dr+qU$VU5`&SS$uA(-X$V!G)1hD zeisUK^|)Lk{^iZF=^ZvyG+8X}IDgL+ksfz)sa`G6XY0#motEE98_~|ZBK>KKNGJPu zeDuOj;gPZSW`|YFliEJb*nOz8bt+|relG~R30@=hSddh8cv{r7AFKW zoLK2}Id!H&VZ{O~@CmF~Ku1bSf)y*0uz*N{;)LcdL?+#y)`T?;Vhtidu0_con#<(^ z4zfUiD|UVgXj&R9m9u1!rIBRdM?m0{K|>Pd{h8zz25CtE*8>7ehWF|ikxYC0!;eF# z(M~JB50d<(+Ud;?Hxt3_gMf+QiXI1z(CCLGW7N2@BvSDV$OSwdBL#yJGLj^Z@g#YT zCjpaefM8)H8H7pdixvrztD__hD3EAgjL6kFv~w3q1^oodyd3$n{*JU28)z`q)Wqt~ zs_d6CEFnZ_2%%-`C4~N|4j?18VPMbzGS!hsJ3Vw3l+?|KCT3ZL=JUf^WmATB*5-me zmF5Z(i@AbifNH15E($S1t}F{luE;}e=dsrSEzO1nBDavt)pi)WikOZCA{U{MEOljN zzl6ltKIAsNu=wnr;6fFqsB|sm!6^j$JL?&fA zGZo1u|Nn|quO8)=7C!>C_$xQ`A+OMB$hJv6Rf%;ZHc|w%tI~i*0R~p9Q6Qkr31yXO zq}T{Vc@WU%f>H`it8;mpo;5)ZL>vsNdP29-;VJ?sEG?=HOfRGkj*D5E@*fc{qlR*t~-&FVxlT8S4fj_VTuu2G_IQbJEc8=(7 zqdo~CKHCBw3U0JRdKlaDh;EBGQmqkqvH6gcG%qnV02)bekWL*&A@w{MZh;H@vEso} zL|}MAqKzLpNjcEQFTti=cyyHJB`8t}fgb8z9YhJ$&KS;6zJeS`5X7ceXmXk$5+Vt@ z)JBjLHar(Rbyk!^0<|o_S!6s3tS&+@AQ#;9o3EzOA`x3GjT3c= zBaH#cRvJzg!;rxWG6YsYTQx*Jp>oCC5}2k3i_Z{PGQ3yEh-B&}#MTtl3MPhYCN%}y zI1pG8nO27#3Kn!Bup}}a3eIp~V@*?2X^~};6Rd|q;OC@OesHoXj3zc=K7=Bs5C+on zlMxXQjSLg=WJROtMf!eG=5V!WWpRpC`yqGi=9UzQ|w^JkPK=|s*?;E)D{Xj z+IRtZBr-X%0>YjG1hxbg* zL4=)A2*5LP6((dQrRuW$V8&Pg%?e9zh&q%T%RaPo;9gShp?N`R$ttm^C_0T)N^zB# zWusmtHlX0C04%@Iyf!5N&Y?l1-U6X5h35U4*atxr^w&gDSRgWm6qtG;1HCOV9ScM* zCh4k?gC5P{k34wRT>L^oXm>2%GV02#0Tm+z>y219Y$Z}<*w#V;94$bWGQ#wU#h{U3 zu-=AzS%J%_C;urzDp4sGh+Il2Y3r;=ic46DL62CZV1dZxm>0{Z5;;lesV+qHbVX_w zh+IjiNn-UAHR@i>ayM(Cscj(+h9Hl67RnYQ%&4H|*i_crQAJjC+cKd+=B!d}%ZURh zNZ9~}NS#KYogQo`)EJ}}EG^4|v9y><-5PLCCDslLh&E6dMv@3~2(;*^X@VsJD6S;( z2LWQN*Aa2mCCiFXfJ8x3YGue3d>U%%S%9WsMJN-huC?KW0)i%MI2r={*cj^#re{rC zJ($6FuwEkN9ICErR}zJR_Ffb9q?yr7pz&dqlu?_y-jF#7)EvV-3+NEx7>|=RbqW1M z3Ia?Gkh3w?o3Ys05ti12PA)iW1dcEUsz+;Uo_02`tZ&+@A9K%mgkM;N8R2B0uB4GUChNZ3J8 z_ZRf!K}edG1=Q^i?Gzhhy@^OGuM=yQt2WB&TX>HtNr+>=zQF_Qv2^M(AIt zJ}`{jPv~txTpiXra~;$l=o*M5EH~Xw2Esskp_8#JLi4?XSSSiCB1nlV;cQYHf@4ta z5eknsK|>b4`R(a@&{+s&$h8FdBfhaW3`7;3$=Ix3HqW15tYWd6NQy)Hs1rzA&`V7i z&;W-%arXU2z_4k+71|W%d=9qb902RiH5XM$V7b_w zgjGU;ic6BqcoGoA$XtjaHG~A!A1O%8<|3m$l8iE(ge@`H5My)6q{PN@a>;~b3?V^p z6{sP%Oh_OX6RHxLzY)5CVCe9ZTSEjJ2kA&KGM9qJkw7jcs83eZj1>$zu#viaWjsj{ z<4IuHGEy*TQ$~`&&Zz+;VI&!ZiRz0M36iU$L<^&~ooq*g!3-0_HIpu|gp*e$B+#B= zg~f&F1t$GQvp( zL>7=UBcN_Af!l$J;c7sUluw24`B?)*qh7}C&)hWaxS8Fton6+Z0qXtuf z(2W5%iaCJ>lmMwupn;D-TvJV`s=1{zYi&mo>joI;9wY-)J3Y7^P$>{2IG!wv(0u*S z60<3#b4v7iXs#eJ)o(fB34xz0#t6BxEF`&NO6~JUz?EjR1a3$GKyr`_x{#O-`xH&5 zbC3*BnS*4|J+!zWpnWC=Go#Kn{~#H(Vl7SxXmdjTGG}z4VQX>jptZJ8#0h!0E_6sy{e}K9Fj=A5>q~EEzw?0hr(Xgd!kJp4~ zI`RPv7N9cWlnRs;MT(qFSk;Uu-R>GiRLeOgO2&ns5PxbF$MRZAwijHUyH^|1Sa{UCGs*;1WS`2W&P&26S zO$b|rCq_24qJ>^iC@Agr0Mj`wCI|>jJjsvH&=>r{4-g8R{6JC?v^nJ_h!!UVv|APs zY9&LdHRp_B@~4#q0c}pmzp{;0naFff^!&Cp5^^L#%=)5z9ASGFPDAFGU&S;GRRrdliz&=v+o6x$n=CCpK^Xc5q+ zMWIM_Q-Q>)1|Hz@YVklon+I~Hg~7H6jV54pwKyT5%?b4rixo4}aDpkW7AFL>IU#?d zmm)ekc7QMlL`NiwFF>`a@7FVij1tPo@R*(vfl&#G#CQvvt`kWv5Fn?>S!flYOfWk# z%n4(Sq6c{ozj~-Kbd13Pv

qIbn+}*s#ZE@#Ng*jM)5ucs3-Y zLFB-$uMRejtO?=Nf&39sy8|Vz>WWPS#i&doX$oAx6;oi2kOCLye<7oWLCfoq=O>o1 z#zE3k!Xz6p*OhpP+;7Q{kME~1s8aiVyv?Vipd(^G!wM2fV$#O$mjH^hKbU-`Dc1LiJtzQ6)x zigw>qNcg)nAq!OM(c^A&AtCmUsz3nBvw-zMk`G~P?MXAsWUrS9DKNzolOj_VphJt0 z5YH5f30Xj$km`;7N=(NB>hl!17S6_Kj-;|$NsgofPu(M_+?-(TX(|*F{LLYM5Fn)? z>QExKAjmmTcx6FoUMN?|kyJ5zJVHvP)H#w0DDOzBNY3U*1z`Dw=1n8?!jaUaRFoMx z0Z^A{4HAh#b1sxENy?F}G76yW1R>O}DfUZIEEb4drfy_O2S`gJha_l)LjocSEnLc! z1-KO0E5$rmAaVuCLx+zDfR;c<1Rx?aM_J*!7y(~Mu-=Wl*c@yrGwkC)li6uZBMVY; z;0lKg$VvM&CdddV%nsB6S}Tqh5F;#(vn-ecS3m=)qzA45lN`7L2qvJA0eilRS_>9{ z1vyBRO8y`Kp?KiRrWYwtGGov__ykGd4}9ET-{B1KMH54sjKIpoU% zGDo$r-jINIL*`#dC??e;2R0R ziBA10w+`y!9TgwpJE(hncube)sCUM~jg3~co*?^@)LnE^+}fKiyhsXNpM z32=eGoa8S{-E1r_Azzv)8B&=b4%g_-V!^N^=5v72GeXIdv%mVH*8X9?l3W2Wm+NYGXqZ}NuZ}2 zK$5*~Hh9;md5N37oZO)QdKZhNiZgw?b3x$B)5&(3wZ4{=t*&Y%w9)L`_01H(N|Mf-r&r0N>4q7+p6TP>Gujkgl5zC@l{*C$5_fDJ5>UNX)83 zxv>SI&&?J&pkW0-^L{Xv4bROM$=QTd0G8h;x!GbCIy$184JkBEGxX}Sho0DuMhiuM zLCUz0Yb-;^{O*^|67EejgiB80cd|C5Dkd2-)sq zqx~~rct^hjEu;}7*mDga$sSMM1b^+n=$41kMyGzcIoz`KgZJtr5+5{7jfzWYm>8~j z&m}}3ai+ik6T?+zDVBX_%?!iI*cDuS?uX6IPGF_Ji2A|PPS`qNpw3DDSTY$Q!_;i7 zl7uTug7@kuF(>Vr%5Y-|aT{VhhfuQ(0g+;k@GcZ2!*?K{aB$U-5tmv+_DQdy!3v)W zl90gWXRC(Dr&fOO=w_G@HBGp(WO%QR617v8C)OQ|XuP@uOhSl;4Ln&X2?(YMVqQp+ zCd8pgaLt4y#c-0R0$XT@xyT=zi%j#qL&^@e!`2JA%;V&ysb+{2bpldoAxNqavSV}A zkZRQ!<{BpCMvu#odzKXM)k(x$)wPDLa)rPE6T?-LCq#;bpd~i0WDePE0ZXD+k<7#$ zu8l;BcBJnIt|K>w&NiJ4n{5);zL_vVLZ7!f2o1`!0M0fuOq^|sOmWZ$pd#cXnVyLW zaopA<)S7LI>7eI80DwQ+gc#k~CZLkpCP2EgO+aaRusLyOn~>5FbtpHsAoR^P#q81d zp;GE>>Hx}{ZHnYf+YF<0Eol>yzdWmIVT&z(Ybw z0FVHfwtt@lFbNRDyqSSzV!VG(vo>hs3Q|(3^{b)%k_U|z4FqZ&X{i>PmpmA)1?@S| z2FHShg6d#7n^PloEx3{#Ffi|nFimc;_F=%IRbap)=Q>28>XTmRf&ib$dBiT$`K{L5 zpR_02=zIWy=G{*$8}0PC2L|bd$vMkHn24jV0IAB`@ZMShG4!n!R1=m3m00$z6+lNO z;F7mi0IHr(qvrq!Wz7QW+Oy`wXx>^83WOx+ytRVnOwB=>It8sPnge&0?=B)m7%Hs|reG?!l37!BYVHs(sM~4K`3k`^6Ayh1z%AEa|)&S0UKm;l+3#fNc*{%#nAwg3% zmGusysd~i_Cqg1O7Le!0rn25Ca>MzN$c+W)ixQ|TEVYhs)rcF@9RH**OaR98g$b05 zEqV&D*_AP8$qQT4=vIOlRmmR)tu?dn0o7hJgY>p#bc@q?9%fZaJ;F^8w4i0X7yAI) zhM3hpGzql0ac%^ZGOK+MMbqMH9{}3k02{-s_OWGcoHu|nN>=+sQE;^n0NvF-K(#m3 zMZz&83IZjBNBv+^y>()IL_{K8^HXcevd0BKRvG;Ze!v?R{0taInK!qL$VKLhnZLQE z0%0CT{vdQ096z|gACy{_Zo{L~D&$Ku%}p}Z1aWeO(_(aMjUYjv&H$4CUm_G&aj>_u zr3T)pCWv(dqa@Z3&Z1Z{nJUGZIUX-zNi;bDv6z!(PP?LRXqH$(GtmtlPnJZZ8q@fPHY{JTbPgw%vp$aH@upWFjZi{=7;y{C^0{E`{+%c zn)p2*S(}O^H-@fFrI@@nMb{cYAY7XQ0N1ACOkA51nc`>zKt)hjvX~<#!~sK-kh#-bl0Z1IdRvfAf+Md&^E&sgub;YF?$?zsgycvQ-Jc; zrbKc!KPmvrk6D{immwu1EFtI~F&3G!l|-51fCVYYD=H~Hd_a4`AqL`fx9kDcPLHbs z5F^>L2S~DIPa*B~3V@7SuK)tw^$I|BB?AKmF_QHPfF$b`0IAn2YLh!C30%p57~S;> zK&w;-{tzHNjtmf^yG{Y9_BsV1ln_lk0P2dh=EP{$DMmqVBZQcKQlmhHXBnIJc1>uJLXgDkjrb%Ne>0xi6l$=5V2xnqOok9UZ@e~SGmKBDXU6OQEWSRz- zsexK%b_r25Ejnue@Mo70!^|#O8-Y3*ewGB7NoJR#C^-ECKzDXYDQWv2L*gNbge)MQ zC212Mo)D=Fk5Q}1^2VtptBL-pCFEq_SrRCcrXU>&FND4-TxfY0BRJ>DSoDy1BpO!- zn2N3kOeZiWXXA6?k?6?@{YxCoS)Fo&Tw)LfL=qg=3?K;;xZndqED7GLlZd&fJuu7* zhfGWi*G$C25z+t>tR=8b5LgmDWfw*hla)E)%97!|I!dBdI*E-WMlf(Cxgma~&QoGF zfect+83RxeK#7+lCPZyD3ALOyF&)-30DPwnV(7R;`w=!LKqXEaK)OyFpj31=Cve(o zfS^FnU@fmAe0H^h9pG{OOM>_6Bw{XV%Z-IFSYUvO;VNUf-AUY8@+Um_iIh-bv|?Bw zaxH0=bZ?PHlN7WVfIHS7LS8P)ILy(k#g@4-p0a zg!gD@^5{fB2x0V7^O3{qZ$Yf40@wv+7bM`yBP~!&gkT*Z(RwTcHI3%;2O$EFV87ZDd96_co2Da{0W^+l`{XHPqox0AEGlbyGt zmy4^rm(pA5q;hw)SE-ba-U>S_30v8ULHYix6_ZD3-00zpBM+>zqzXL%O^+CPhEOe+ zi?kti@m{DF9ZDcd5h$@c!_*K$bpcm@V?IkyvC4gHd6;rxq4Wu-MpYkxtqPI|rogH` zxxX}|-A9%0pM^t;_McNA)MvhFk)QoW)fpOn?#i9j|gCQ`Q*yn53>f zea<##&*8T=l*kx&^nUSZU;y!$2EI!J$e;hs?S-2a#r;=Yx%a1c;UZ^v7+N(-PZ?Gr zw~h)IcL#5KPba0Li|IvC-seW2GW#6RmzDe^FN5DAJmyOC)h2R$Z-nk(Av?tc_JG za@T|W#go4nfR8Uu9L?K$rTtOMt=zm4 ze?!$sF|;4RQ(f0p$c?MJ!rt4{+uKR$>h0p`?C7adIJtR|x^Z&%boNvzrRJ##q0tz@ zf{OU~@If}QJ=8ztY|}cnN1}}~Iy@o4rd33bi1>(@ZV?Fu3u*|gay*d~F07$wl^K>g zh$#(P357^a*C7BT;3a~z|K*|I+gqt}aU|8~u5xyAR5>eM?7ZCU6<&4@F7|E;cXzgj z$&N7CdH<^;Om+|bo(ea2Co<+cIlH(!Il8(!yLdTxxqt_tuy^)!bddHf*^0rg`(LdX z(}w=dU+Ee8<4A`$@6aE0a7y}=&cl2U#HgaC^cm*P+9@3R;fSbo=;vXU82XFwt1?d0O+=?zv$Kn%y^GY` ze5OM=`bmw5Zbu6Lc-dyMli#>*w(mpps}KMGP4KUrrj)9aQ6pg6s&}`CH0?48%R#Pi z|I0(aqnnGHlbx%Zlar&ptFxoCr@NiP(^a8x^0HIdc`M!69ws}&VCVg>jxgCh^xNCH zyEr;3y`8)iE=o^tm5ZIXmy@%?+fL!&qI7rgl=em0iove_U#%F^hW-`>^$h(<#2T1) z=r6GK$?RJG|N4%rzdC2}sRzdMhW>^m*V?s8KmOyRhwq|>UPIeA-uVj;v&7KXrf#Z9uynWa$wi*vZ>j5;H@yJ=> z<>2i_W|H>aPAW%xcW-BBd!@Y_u}gLeSB17=`p*viIGQykCBvKbKO(p(vworas)|2gw8tTWwKH+LWtB^Hir^|fTlrq!P1WW^yzYe zi_V(l8Inbc5Qze3x+eL={Xo^Fs}w$)eyQ}dTh~)(Py`SM_BbKfk-w&Cw=acw$8{`m z{`}r+*GnAWVY!6Nfkv~iLbs6!!g7WbVvvmxQ)u64tw|myaS=a0=~*J}8|Cf_v%{NP zd-R9oAPOT6Kw1Ih-*R)^UdMo?%lv-sKI4aWMXY&P3G9O;y{J=;tkvl`$!pW~zYBE^ zsMR8|$F7-+1{U58!W*K~u4VlX_Vx6ua({5UJ=dGY*?>+`?4D3C`GG0y6a_d0$99jP zw{61XdqyO(w~)vxT_C}_g62#k@B<_8yWDlAK&VA6rNn{7numY)=aYn> zY-Q0xC-ETvq9rbss8upHNLtlDR<51MS0j|hKZO#jxGWh zIiclkhd>CHsz-QqLIky0>N_Dy(`y0Hr$=jnB22jAC5Kfu4FfP~g@DB%I}9Z28wQdI zhZLch4ITy*wf@a>^nHleR-boSC=BIq)z`85EQq#_EBkJcg(O_s_eyFe&}t;`J|q7W(wFxS@gh1O%)_SwjQc z(z5<$F`}cOfodQ-CG{UH#FRxWo(Ba7h9GnCtTSyEKWNlM#8SIbfq4NF%3(MehkRJ z`bgmBVty+db$32LvEa79%JVRON6k7zgEGUE&7tYXW)a?YN5A=Y%NEajy|?Pq3*xeA zyjL$tYwAt58{Q(vd}O;J{7{L}-7q|%?9elQ2W#$2-LrJ`_wm27O$Voaj-({ER(Sh- znOAYuq`bc#c+_rcSsrGIXXWPAoE%xRq2n7>=J+5QURU_fs07=WT%Vr+by*r3?{ z5g1Lcnrz5dIX#d9WL{k@CT(5NkYVRa3bZ4?i)gc&bO6rR;<*xuebZ!nKtmmPo}LBpI>lCaQt9toY`tHUzeGJt}>LG$oQtXQ}E1-nbYvf^kv%>SR%;z;K zh*>ekYXteFULz0t+`UGSS?V?Nu>WDN(O~m#Q$&w>-%JYHX!9OY@x>7L;K;s5fA*Tt ztjXh7Jo64u&PvTY53_`MpH5^m#k_<3QuEHkEMeYf64^{K?;yX_l=HAJ&b)&XQuEHk zEMeZgh~lBoAhXoG^RWM6^KS5w zo@CNEWW9F}Q`UBOEWgli*tyY)EkmO!JG48j8+ol z;mJCVquVUb@fQ(Sws%1s1dv~Pq=$!D!o0sCvYB$E2jrI?-{E0joOuT&q{nx7m?g}6 ze$oItG#Pc~_>5XUTlP)zDDry^y{l4a-a&rpkscoAMEGOSEXML?B(%+AQnnu>23O=( zg4_p1C3G{>ksgp-dZdSk@r`^Jkc&EXy)>c4oT=b*k}z@#HRdFu~R z6>GdOX!^i{B}=*;FT>UZt_{P|we(025BuWG3n(Ey(!;~PB=Z9DOON#Mu+Q~K56CJ# z(!;|nWl+$Lz9MoOd!*-cTN6$ytH-Mh`(VO}0avBw3yun&Yz9<}qbTH`;mP6x*n@q z_wLAoINGC`<%n}o%6e8Q9{uOR?9ne9!wfnMGIdZEKiEO4!kU)Ov1c`@zapn?~kWP?z7~fpZ6WRgWw9R*DrUl_{$^;4Imrjs) z*ylb$0-2=~Bp#OCW}k>fgFZu$P39en0|GWc`J>k40Yuqd)nbH$(O#C_^fa#>LAM?> zyy8CLt4o#r#zi#mXI|Bw!f+o z^(V9;UeKCqL+9zdu~F1Xk1aop`L^Kf13|x$$2H`2LWUr}-=;sumRD>(G^6*=n;iBW zw&r1clm2<^p-N5rctN?5awV4}MCiN&hip5@zXPY9Ks8*r8oWNWt8lJ@Fa19F?HcoT zcB3jIc4I}$jtyb|=y?q1AhG4|1r2rHumhr{7%N}#$6Ghf@t)i3SUK0!t4nf}L-`;R zc=-whc>Vj`e!Y%1QcPDJQns70xlM`cJj@aU$1@_Eo9f$eTh)a#fq#}gu(Dg@4-Z`bM>=`h`N{Gp055is50|IdGu79z?dmr|Wx$S-ggMS#zcL{( z!{uP7PV@e(*?K$B8lv#6QBmFcD4+a#UU`0GQI8_WKw&Ai7fY7JX~fO}uYn*zR&?12 zHJ#3h$=2%}IMS$`V zjD%Hla$i&xSh7=y`(Hu*XRddfeJ_cJnZdY1F|k!6Z=tkO5!XN<)S{NFbZiKqgzJH> zF^`oM8Z0W{HQ~;UzZ&o`z89GFMzq4mYI_<6=3HL*c-bXe=QdslI?L$G=I=i&K*a%&DcRV%%wn`*yLip%YN z4<_=kerV-LdW}`gTBB8gkXH*mSN=QZFgS*g*tVI_&D%z<(?Dp1?HF;=`=Vk(<}u_ZKSe^)heFwvY+G z{8`=>Qb9bXp;VF&5Ayw|6WeB#QAQSOd|~r~{Cm>fdDsw!iKgDNSI4i33{Q66Kl;|E zMcGRu>m(@$tylu;=+n{SUQ_|0;LvKzjw+j<>KRoIn&L&R-_@w&952`+w$4nZNPj z{$Kv(VfAxBaj1i)VP~yDGIc5n@;5ph>{LCZ^bF6%?f0+fTsoDIFNO~s;wH6WjtO-elTsyY5*b=8vHr(2x@9uSXd;5!?nULt)$k|Y=@M@=f}smn!E+GfGrm+`RC*v20o6 zvYsaquGX`)V-x(ZBo?0YcA;(B$0QzR2`3J!<6epFcjLTY>g-- z6n_aiNij3n%s-5A8c;9L0fWY*5yTM1j=8kxFx= zy43#Dw(|v_%9ZSP`HZaPwEiCGBE_y6q)VK!^}srt>^+LFDK>%_qDv#U8#`RQJ6=1z z>CUcjm*Xj*ixlIJS<+>>8^-E_GUJuXj>UG2po3pqR~e;rS>RcB@wgY~R~>+a`gHoN z#wm}#%{@-pw7UQEP@nj|rZPM&wJBgn3=N+F&%zVR?ij8o8Eq~#4V8={kROah&x*cUfWffCX&iHBwJIE5=O zM%hD+CsJ<^ewZKX5Cg+oj7ueN)>!d{l z(rW;u7ixR-yxjO`SkmR!Q(E&dOAJ+QiNX(qi?l2q zROM7~f^YJ>`V;Dc>`)FuS-@AF0P^o^`N!*8!LDCbKj)QpsPpj@9%hN5%Ad&Aqt)DN zt{$C+7Rujr{3zSF08qdXopKE+{Qg(3h5-|lH&fk?CVUM#Nij1FRnVM4Br&k$*YB|NQ0znDK$k$cELXM=Knpb+!?PzQ_c}Jameq&!Wem7!IU<)2*37d0)$X4e2z9Ua7 zPu!k4IA-L;z%7$NW_?u-@gRSn27^);+r|a&Tygb$P{Qh3Jj@a{Cz!~#s`V?+ua~wD z+Ve>OPL zzUSd5Q?5Q4Blc^d-+=x)0hDV$@AcM0w;y>Vb^UYC`|qt!^01{06OFOUo+T2@I)un- z_u_HFK{rp|DR)}eOU)O47ZlQ0soAmDb4j1o%9|5JG{6}GTOn(;Jcy1dLOB@h4E^w7 zal`a?ivyv?%a{l?O52 zb%rT}EGQv;!jOm6W^&Ysmv!$7z{c!A@|8ZJ38Lt0%n%Pc9BuogkwUfU@Th>LyLYCJ z>B+-Y?E$@6M~$oQHjJMh28V6P|XHN7S48Z*g;hRix6$SQ5@JZxar$?r&wiJc%YTRa3ZME>!)_suU@ zy{*TVi67tY7-Sm?@=GyG8IvF)OTC`%)(!ve6tr*oh`irU*q%Zly?R;PnDiAY8+)>> zF@a~?Wj&T8()m*aP6m4{`|H&&bMxisptSoRc0E7fwjV`+G9$)`24C_S+soBC=lPbt zqyLKhWkZSiNj&U}GbW(KUAyw@yQT*zmJF_1A$e<$BRuR1(-~^OdBcNdoP_7Qc3k`Wx7H zy9RdD&chXh#>5c>GGQggM0f=i^Z!wIe!V(Qs@Vl5B&WQuS&fJ7W0}zVDuhy@@K(4w zI=DEg+?*Y}oSi-09NfLU+?^eryu2K|9lWgyl0@Iw*tUpD>=yai>HS03F>|ZWxun_` zo0fOTptfg0Zz*OkOdv>

`Uvr@JH3)y3V((aX-+%ihb;-Nn<+(_QK2=}v;3J3Sp3 zYGeCN_<(HD8Y>4ZUf7hTEz56J`L3uOKWlhrr*0@Xrh)I$0GfBa^009~|7rm{^ELbJ z*1;)#co^T3OXs0kv%QV-!{WlS4`*f!&%eui!4eNRI8NK-7 z!}Uj&otpx3Lp-K|?`$yNLi{a#OIrPeJh30kI*4J<^f-uNBnzWW$;%sY>+1&ndm{Gy z*gfMP?fL^n0EzMmV)6Eyc$g*D+P#R3(tSD*TVJh0Jjh?Jce}&4l!2Gq4tlZm;orwr z@-R!RwHG78`}=p@=&ab6;$5zP`ae0g6#$YFgP|QLP%uf z;sJ;szj~eZb&r})QkHq`9WY^IIu9#^^-9ufRO&Beijp5UwuwQ>`o(mM?$` zS^lDFz`b8`Y$`r$A{7P*V^Gof%{j^B4QYZqH3@&xRF^MNr8eGd)Z*1_2oN+PRlUKU)FiVVNCy8w7 z#jmX0ACRNO^Rgo|s{YilJ;<)FRv{kbm;UTJ53|Hb=163dzFQGwHbke3<64{<@Z)LK zf|?F<&fg#Y4s?=YW*Et!IfF=IVB3ud>bcSCniYv=v-TYw|3~CiuNgs?3x!4Grv~2; zg+ntY#sxgQ=CPw~zExHG6to6~rPv~1Bm|AvQgd_OtU5u%ObvHl*v&8W_MPY-Qm%ES zOJ4?6Vu$hx)|(<#s+qx8mo%6YdJc4wVtf4x9R#hgrgGJ|?owOkY?lI56-;r@_z1)cv@2Fvy-+j|2HzHaybpl(&Di zzNP=&we0&`4|$j+%qH}>I*&S)YU0r#Bj3_o`>#8W|ItvL7PcGPbH7*O!mibZ%yqb# zycBejVrDR#(40XeF<{db0hycW0-+YQTxFrP10@_gR+*CKxBlkv*7sJO^iD0!!{972 z22BRiH%c4z%oK`%Y~e~-W5fdj)I3+l^&8(Y@ncV?Z&qY@(KR?Zosbd8KSg!Q<9$%x zAs5fKoSJ9+=;}O-Zyu#4-zc3>1oo<>6EwiEp4SWC2^!J9d2YYGIrA&uKw^D5S$siu zj!+}m5@n6(ExpGXiP1|DI2r7Fws!YBH922*&t0XLZ!b8<<|B##Wrho~u#kUwOXa(E z&BJ_0kFVFSzG_N49%hElnY{;tczd!utTvQ}5Hy`L>lglb`_~|bzQzpkpu>fz{%3kT z=&ejCSL@Hn)m<}q81ToS(d(1<0?7o)%AITi((q|Jf*`eY4~d8IP0c530zE)>S5xR} zRg@E z`?16D`99<8e;g9rXA*OhvD<5ke}n%yfYl$ei)(p>xA0 zoKuYRta~WgRTa#`_~XRqp@+rY(0YcRPlum;lpig~pqV0c34`5G=XaMYe_QsOfYou) z&;Fg_wufyvIG2Yr|G$-;`Qs{=qF$>D*IKcunTstCGlK!jUN;n!xX`Ha^#(IK1z-D_r7Xd^c2TXpDZ5SOt>3z2L3Y6L0JqxT^g(SOvuQjFDR!G$w$2&1~QRReBE0 zHT6VBh|i?Q=buN`tXGML@x9S3QV;c%e|4H#Q^VA|an&XI;GW4In@5bV-KRpwBA}iW zgB4{An)1sY7qtb+xa7j82Ra^E>bYQhsm^xy9KQuw45>QlV>Y0h6yuxKPp&$)>9O}9 zIs{sbIQoK5CVhMf66w>?;wJZJL3*@zvNQiMeW&$POfk8~z4w1#p~?XN)u}TsPaANi zE{XtUhC8>=ZaRIu5Pj@UU#~TlcD1;oc-okUeQ_q2*CBWqzhP%jr{x(Ds2qI_+I;g$ z^Q`*Y=zCL|Nssm4JUeOhPX+J!Eb6f1*5XID|FX>%Jq375Cvf(t?fq2Ek8Hm_Z{@qv zcHTV95>v;kM79~DKfG_NTy$j0kYDFt9#-^8X0;0OAb-0a{ryXZY&rGQrYl>Y+xBzi zVc9u#MALhM$TlE{@2fk?=1ct|iY+elvGg90Szk+qc#wZ{zjF5Plq-kKdVe6LWS(YC zc$gW?OZKk%gA!|#u8oWjF8|`d$mKgz^FIEWhgo9PzY?hx#nsTmR-Rj5Dx9jUZg{t1 zre`p)vSu`_TiVsbXLP|u|D+9?9l8N@l45+5nYF9_&;YM(s_V5>**GfwM%=PawTVK7_dS1=*TO9B1T9Z#!``c1KucU^Fq&zDw+5`DMB6wap@IUGh za6(zI=ZO_dUfUL8?IbR-wIaeTD!9z*q~D?%C(GYT>K$|92Oee#J9&-Bwr+7uSx=8~ ziRGv5n=oh5v{6v5`l=M-LH<_{{!QB#RHa+d3VSo2MBTj1!z^JZe;~4LTv)a5H_EcZ zl1fFcdH<-_aFE#$oeI=CJYuky_lap&W=^cyb-)MENs5`lPG-*=C56UJE34|MXA7DI z?Aw#H?E5{r+qdxs#iUq0C?z3i=1%Jb1e>qpCHz*I*4z9_v@5D~ zoY5}*X=#vMij_lWn#5@`kj{-_P2H6i%0PQA)P|r}`hG|`;N$$`UuQgK{X2LuJ)~%e zPE$K2mbmV-_d`Y=x81XISBwOmq?lng-n`4W(0Q&*aqW4~N0~A2Nc=)8|B|rjthb(| zHhw%1kRWU0lZ2M3^Oh@UBC-R(9)Zf}-qoyQ6)>)nFL zD+vL0-_;9Wz2?&K0pMR6q;SLMcODM&^6Top^TwV5POE}IVJVi38Id@7Lu~Z&Dd}|L z`Y3x(U>dY^tVU#L7aUc#qfaC2T}Q`l4>}fq5mFgasf7wDs-LC1)`uo?|wdp;9hxK7{%I?k!6#)T6 zV8oyp`vG!STYbB9&%l$Fm47Ztz8IBJpND-3?>hy#2QT!E`r5lj{uafjh@0_Vvg=`V&^_J1lBVHUu%GPNbeN=pn`U9&Ofo>AcwjD5*~;^Leyn4_Dr! z&A#8yjnnsza;xIz_GnZ7-1kqaa`>X&FFY6Bxbf#m2E-orsS#pYVoqz^;JP;eQgHfL4N74tnskV(W3=9rN4>G!^|-FL8pM?5(C>l zL{QHSrAC_wN8e5Pom@~(`kS~s%o4woyOYRf%J1ZY{L?%(gVIj}xRi4T}wAvZ1ur6Dr+qU$VU5`)w zgnfdzfAq{gY>3xn-u0h9W>u+CNg3w-v7+a^*CR4ov9*U&lXj#)XB5j9-)yqd3o`iGXrYi$q*0p#!TP%-R*ca?Kt zZN?^jhB+6674~@$krYRsWa^L;NOBNt-jAhke3miKI|eT7hjJS`p+6ue>$J zP)NW_gp5FmmWik5)$t6vkWsmCQpMPHt9aP2NI8f%_y1o1MOT0r7yV-dF3? zCER{E{q2)Sfo+QUzFfA+Zc({SK&VeIspU0&gSEV%%O@C4{pY6&n6PYppcB zEUdXGC1!y9D-xX%Q;|%*d{!_XG9`<3yG|xo=^5{q(aWpe)eU1I4$&f zIA=(kHLr)WVE>q_VIFx-JC7bRJ+;onNo+4h52phuWT}V4!z|H@!Ncjc>O0?@zN>5a zpIAHh)aXHVp;3Uvgg?0e@=HA&9`-r*Vvtkn;qb6e=*38?Q+#aukVf*#TjPL`)P_`w z)WZSAq?jc=9Pl+v@o+#7sW-#JEal-eCVG9Uhhw_s?J2Y!qvw`;!f(FY6%<$G@xqIX z=d{{C;1gUVy>rWAEpOPXgH3Gx7B+5s+F^_B`_9wZo<%aF;T!Tf_tt<;k31S2 z?=#`iHn+KrTk^0hu)IQr2!g0Dv@>G_SYG=+X)15uko(JeE}cAQWVf4;4B|13noRo> z)d1D3J4Rk)=~l`ahjja>b z6Z|J6)h;yhjcp&&NV6!`XM9b^w%#iP{<>W*RW*0VQBX{ZS;{&!B^p}JI(_ylUmj$_ zWnSwv%QtF9p}@VlSLJB7BjRvW4BPt9FAOCOMCupvuq?1n(hdOMb*$6JZUv6aQs%hy zPtcz;YMdN&8xlcJ;q?}Xg8=eN{X!m=1=fk?FZnRaI)R*0zmSKaiTPrz6DT3|0eP4u z{X%%vgeiU@=ppqBdD#D^c~2(WE+}!jWqa20qF)HV*+|E+WA0lq1mKWro`PWY_9RmhWc3aqU00yMc?O&s#KZW<61xBk5>R&aH|A3|LP(S8dv~x# zq2gA~UR!jHPo1<@zib`%c;6N3kw84AVe+N7=G%|hEwDCvRjhZ_$Y1WOS~uQdDtgdDI}H3DQ^Nu zN?r#wTCttSuDCb%FJRmIk2|Yw4@`*!#iZC`CMTLf1(GN@Vt`GH@c8gP1^r?YBYH-} z+t_v;WD_6JgS^Hl>kll{Cn6cMU{;k#EHzxFJ4QPQHwd3#cRU{Jag5>$nQ&mC$;8J$ zf9pLyI^sjo+1|PQ##ghNn7VtB!jxQG}VulT6`5jJgNZGyt%Y(l#Bis+VT(<-7zM0`X{w}}77A%|T; zc^mCil*nV(?2Yf(zTK7|{BA*w4MRVnbBFzzN#}kq2GXV>dDip{ z)aNY8Bkj`k1``yy)}LNib@9af1u8$nyeRG`RMaF2Si_(%4OzRJpu$3L&@d*11oAUA5x~ zOc<7b81|u`ry?b8=jCG4zrCnfj3PkU2_4)jjNBJh1(xg-;{I1q|C#IEX5UNVVOVp9 znSR1lQ|Xv36cdfW4~)R??3Jzb_X437wOpkmVHn}&dZ25}V`YT~iwby6xO3yL20V;E z56;@BLUt0_DtxTAr(s~u<%N%zU9xp<OM@09~TH=IpU}^f|I#z4nKaidQ7~hZYl#2R-1#1?3*MZpHK<`f=XpRpOsAjITFY9GvkS>X z>N!HTne_vZe?^qztsuYK0ZR`*oOf{S)yX_er-xJKS*uewl1GOLQJedEocS)Jl-H^e zvpitQ*&v+;u0CvE&EMmvuyw_z+*SGK2A!lB_Cgb!4o z^BMKNZ8FqQ%_dii{oO6(o2wCRQ)W-T>-;llCdIHv8rGTr7Y6Fj{t)D5vPfj!bt7e9 zQ}5ydp^nYpPMdjtTFJ+(5x_%`-AUt-9)jdyIz|9mYZiBZ*o;zn#{72PFY())lqDbPEZ66{i z-0;fVV0RmMfD+O}kUZ>HAw#%mGRU6Ce{G4DrW}F;LYN-fs5F#ybwOohLUGAPHp4#j5(v4OXv$ z8cZ(q@1&7`MCCrn!z^W7lUhAXbq+dR|DQM8XH5O8<1LUG%0Va#_^J~?{;&2#&&~)g zpV#`UOX(BWEV{(QK1bsUa;|#k`>m5=@WzD4rxthhY0`s-p@lTed!j{TS>p;y)azG9n$IqMCp2@Tmu^bbOup5m z$)%7{YiE4ZcXh_iPnh|gd0_6DUurM!cD)sWYo>+XT%D_OnKP_i%0-(hagNAUI{V;Z zmat2_c^ZhFnOy?;U%7f)UH1KDui{O}{usYN4<44Cb_wk$EI8XW`DK1n@1+mJ&yCyd zSh?U7Lv?x@^3I{B$F|#rZ{J(zyut1i=p@CyD0^kT4*WTsFMRUQ+#R@brG(}kg8!IS z{$s3hu8HCY4V_jbZ>@->2za_W?3|Y!_FK|B$V!N z8LHWZ)Xh%2ycX9Bs2e?N$)hrBKr<<3Txb4rmTr_#NF*4)mwHJk`cD~W^}Tq1vnkIh zoEq&}s+PBHw`yOVnQ)=a$U(er8cEc(F1ewTeei+&;}*N8rnI24b~_=8 z4ukwRy9m~mZ`W`^?uY#!P7oPur@VbPbRx)}S^oq1rTvzN zS)%_zpOM--Lv@lKg9V+W*caXZyrCpWkRAV$1QVt6<29%C9ev9!P+|K|6~5~neM`}I zXmxX86PCaVCMfefP_?gppku)Pksgz0p$MR59{3=k7x`;hA)-lZ@8?kycWgP(abWy) z9%hLy*oVlr?ZS+F%YqzKt%}{6GN(i^U8~Hj3xfP_p0*!&z^C7w+~Zr#zO&=GGY_*w z7mOydwK}_F?)#w1I~$MvefKNd@qZ8~Q?ml{Kb+pIS-7`Dt}Cs^jXQiHu@Mh5Ll=bR z3?hkvZ8svwxk)tTh$1NAc`v4ZLU5Y0>z#u;uJvrUi--Lr^c%=mBVN`XQG|ijBV~7y z>AvYvVfXW_9aZX|Ajsd42Ds|umMIUtU3_0&>_5Nf#}&SylN940yX*p4kRV&^vJq-J z`kM|t!lM%+m^&egDLR7a(<3|13}4h|I5Py1QCnHV*+Sp(susl8ND-Qj;d=+A6Pwmk zy?1&&ti^;gUC!2Sm;+zVcp^A{Can4oZ(?+=#WrMLSd*ctUOu~ zk}t`obVyL5-=I8;-zo1_TikrhO1FPIo#kP$IE+Cf9{15ROa|A?WY0;`=zUkNGs(B@ z2>%HRpDUMteERFM)IQ7i0%LuR8R9{QlgEOm5A^aG*08}hJ8y)on8m~Roib|;4Jcs0 zwtKUwe(RQ2d$n`ro1e$RLm7H?lFlDY_g^mP>xSP8)r|Ef+YO)S>xL=Be{lefNEo2L zSmhV4^z|KZ4^Klwc&ffwy%VmO@Rji0>a}oVbjOZfbo0kbL9@HGOj*3AT$7pwP$}S7 zKw!!np?R1kJR%rGq@E3komtxl`K6u|56e!E2;_!fi0qp(+-i^XSnc=bVoLJVy}y0~ zvP&^D7+UBER3`jj+XrI2>vU5LEp1ePjyzmTxqA885!2VNtn=>@9@YR%q7XFVNf#~* z{&iNNKO;x+s$oqaLn@`=vE+f>0#Y-wehWG165S+d-qH=T-hehz43>j2Xte1fK(dWRHbNkT zxmaR+zX&=hqc^&l5Jav{@cBfL_~X!N?aKNnd#!KQW%uC?O)BuP9>^Wii}#HR5r~@j{LW&jR_6q5bzVtP=M>il@*|utG*T9a3dOqaV#Rcx`c{a62 zR3YBhwlbaq%Uo0V1Tmy`Tc_JsxaRTmzRi=K&Pa9}-WSS6iqYAmkb@?JPd=XoqoaeM zJ{>B>FG5~SQzD2yZ9X^0rG>s{4wDOi7LH5n;=kAR2y!o0uj-BYr_-;0&6*T+Twu9G zy0pN&>@Ebs(}l~?R@eZG#t5h0&x&{OF%pf4$8`Tx z#|AWzIx#%#^LA`NVyR=p!#;1v1|*g`F+A*l&9Q+pkUB9u?DKbQvSZ0q?`swc2tyNk z2eNB5xAZ;Gc80t=Fh$^G@RI2(pL)$2tG-{c-|Nx*Yn49cLJ>&iic6+&KBV@hGWlG6 zQX``${IY)6Pc!fEFf$B%M!jYMWW-?7YZgF>s+&_%PJ8-CHLq@)aeK@kYk3&FH4B5r zH~-|>FtWreWsOmb(k_B5Y%@Ud=v6jC zNR^jd_3mMyelJPFCW-*!;NAu-qr_Budwr3A$8DoaEuYxQ zW8D}YW`>TMy?Yy=M9cg~=6?td?mf6tv7KiWk$HF+{LUZ-O-KFYNi;lnLRJ>6@T!#s zW(n0?KH*B_D6f2W+kPvs;N;*9K9CUNF%1&3SJ0#Luf1PY_S!kB*08(VYj$W>n}_i` zY}Oi~Jw&zvr)}y)1->gkbNu67OO9_n0J7`T$$ZNMH_0N9?2BN270ML*foxYi_(V@v zOe$nTS6sDvLdf5K)=MrVRoFMRm}(4)040NuD8-Tclm3IQZ1LYxxK7`K>BVA7zT#mz zlX@_qS$dKfq=cZa4j~?--TrFB*YB0B?se_CJY(MMZ>#YzohiIVgDg6h2+~0?M1yy~ zb;&c3JIq zwi0O7AiWqcLIh-PP6&ir)N*AY^bT5!rN68DGTJA2bot|6^V}x;_kc2xVmj8vg(PYf zk=QRj#zy@hlV@yfbVPVe!GdkblDAD%51Yiu2%Ffri1_ftsMr{rgnr$+MMQK@XkeA2 zi=cq4VzLneVWv)mkWOz4FrOVV&pvCizDJU5$f|gz`>fzHLCCs&)&_ScZMF(nv#4hL zhcS1yy@+Nj3YRPU5(ysMSv9kZa^#8z8{W^Id0@Xa57V)1RQ4P~!(=(r2>g(Zzyy*j z?G4!42a?F5vGuzg4mo+Xd(`TTft}(!AiZ2Kfj9^tf3tuO&CB`Zbw2iYkF*NYmOJq< z9a{&)7PfLA=i^#uqelnkToYEhnSVC@LE_0>NXSqmj*NJCqA^5ai8R9mhsyWD-| zfrclafKE~@i zF3Dul9`>d`aYy#cSr4(&w;p0u)Pzacg4wN(oe7L9-EHCiT^XGxa^J)iPip$r;N8i$ zJjzXc-Ez>TDc>E5=V4|T8nbsj1eAER@{f%6e#(|^C9dyv3M!t#!z{fXVx1?xM_SO9 z=Zg;{E$;u^Ybp^t(;)=(*nVcTpHoQAM^8)SUj4*&SrZA zhhHzV#NpP?-!julIu98G1SE_^Uqby=^C`RJ@ll{K`o#)4ex2=p*x#_O8jpKEdiDDHN4f zVB3dQ1o^@%Z;jU`B;X}NMxex3+Y{=v3EKR?ZOp~7J6A+*=3zQ-gP{z#C+ykm^vMn! z;NYCz6ZWS3R(oqI8_yI-?UuKYQr2!I3Cid^XQy{d#o)(9^lqu7nBqeG;NGI`72jfY z&UFY%opP|<8@2*)OC^zLy(L%P_b-$gfw?j~m-bRtDbK^OMbb0x`3O;fLvU>O2zUjS zRh#hmo)L-cEiFpvN#N{tAwY?u?<*V&4mq*7S^1}%!eeue;bE3~T*QgArusLAhbjVn zl{2;;nL4*|uJTZ9(8$PWfN% zpbc|h-n7QE-=WeAD$m(^`27H02kl47)Zcqi{^edVjq^ABefHDW?Gkv{7uP{S2}Qu+ z1zY^LzMbV8lvHiqhN?Wwk{vYS->`e56zB3M&KjPYn%uoH5joQi3Ob|}Eu|b2IB3P) zkM_$(PTy0IhgqtFTF$?>7LLXn?cYD{LwULEyOilRJLgIca{SShk0wf8U=pm|ZglRc@dxcl5-EQA?-(GF6DjCuVKz^llNK%&o->J=t4BnZVcxogM`yBmykaO&&z@ha6 zhQ{r<{_XUMZAdr%^1VxI}mgL<#^Ik8}ld!Yq6 zd6=dAdq<+7y8!k=tZJX=j{VEG5&#t(gZD6nt4*?#0 zmA=cHhh>2Ql5Nu%0SgRXU5+QVS6qE~?fqZNzR!DM2*?cami-k^u{UEVy* zQpOd|_aj87 z%I#&KlN3YSXM)+p77EQ7L=po=h=9zENoU+Z3F%=B9>$+hN|)izm?}G}q*GbaLoAR` zUu9W*$!D9O3f7ve!O{B*X~|>_HAU!T2K!?ZMid(8=dts3&3eOU{PO*wlPCg6gln>c z$o+uMPaXyb4?TRg{;j#Oy_%ooVP2twdu`YZ` z)PU}|0S0Mb<)UC~cxpRHE!V*}bwPJ0bhd|9r+h&CGFTnx>g1 z-~aE>+&j-X_uS`mmgg+@oI7PuU3@9rPQ(e94-pUag{eIvut?`a8pFm#4EDIeavr|; z(u3f>CsMS)FcMSN$V48~KK#;&Y!dtMR_x&8Ba^;m5f@1>>L^l|p_gFr^Lbc*i-3lm zf>T#?=$5ijxO~79S8y;5()n#-fVb66pW5rcZt4>A%a?{JLqFytZciGdJ@({&$h03e z)o)h)LA!u+NktX-lh@I(^3)Gp|IQ+A9ftlq)sl6r-;8Uz{)Mc=SERLRMTYv4akdAm zu~rWa_|JdcAU;Ph-wAGozDi?D*QZ^^T{UmhS}Wb$ud`m#6R?HE{*%fU zPo>+^+vx5-1McWs7n2{RI~ttifh{CP??sbC-Mgi=g`fCBAN+j4$#xET%>CS|?P9jU zM$_&Qfgi5KW`9t=imD*0FNLr*UQ#+;ddfkkprt@u6W_iWrrc}vV2iDdM;~Xq0OTnMkzR@scv{O)B$n=)hCbCTen@H@hYp1{n zvYnz~3T~%<%F<2&PqIy-VShtA1-!{NiH7|R?G*4P+awyMjCKk-s^4pe)I81YdnL4f z&Gg}WmTyK-soE*oXL~BbV|0nLJ)w|1kRHhW@#+$2%Xv(LFZG=6@tn4`-0fdgNz%;; zH2J4t58+l2KVx5jA|{`)(=Y|Jg1G+z24g4Ev4Pp1>EZW>FE`ce@-u(s7Tq|1H3$e7 z(k{l40DtlsI}KAnD@dbNs!lWTB%iU-!W2a&Nf6ipd;pgsnlHMg#R7(bJObFAw z@SjzWKCV^)Tff#E5ieYR@bj*PC|k*&f1+Uu&_<@ziW~&B0l`ooXmt`_0X)f{wWDDQ z&_GN<_*iQ0aucM`)w_E*eIkt1%|dol-^d@uELtM7xVIp=(SW4mrw^tC#dn#?Q1 z)Uw2vJHd(<`SxU5Jqc=NXBjb~LA`N_Yk#G*rPbC&sDzw)(=f!@a`fZ8`^Pq{A6R)A z4J*&uifd>d;#Oms&4v%$9(7Z$?ugS=Nje49qoi64{9jnD-ZqT`i{6$ix$gdV3 zVtACg7R&M1+Ew02*mMA|r;u+go?+curKhF$Kijw}%k*Y_`yiZ4xXtxNIiWkq`^r*vG&#p( z?jiNK|GZtH(YXKaT14o*|9L3&i;ZwP;-|EJC_!`c-Zr@L%8wHf8?=S{pYBZ>ri^+v z8X25>-^MD@IMRO2w^;#dW6r;Y{D*XaKXDHD54Sil=C!@AZQO=I?F-T@7SgcttY?^S zeRQ(o!Q1&ktngdyrrPePd_5}w>;Qip2ELQd4*@>A_g|YdyMcLB%NbL)^j>$AhT%#i zL;b_WqkNyzf)T1MpZD#4Wd?g)!R*%h9jmmYVTr1OBoQ>zWu6a!i6mWP`~xj`b^zZ> za3f&J{9#Y>2&~W7R*jl#rulVF(=i9D_8V(Q!&Xu)DW7My_}2Z=$)0Z`;=7vi-oLT? zwd`TPbpyd3@W)}`JL&uo;P~Rm{WP0SPdlA%7xr-Rwlo?xS11xeB9^a>CWynB&r8CZ znB24bIC*;VBdyEOa!Y07?l^t*ISxkViMEF3Uc5<~FrYM>&G<0l`E z0p#P2ZlkSVxm^sc)?5hhW;MDEL<0Ue3>hieSCxI2#3j@UiCw7lg1JAI5wVMwebJjN z#Wr+kf~WKi-Iq$q+cou?n68;xIc#x4Gz(LJl)w|*i_!UxfP~&n&zM=SN|+zf$~?n@ zhAE?=JCC>>7`L|bXX`-I#b)k}-)uAd0o*0!D)4wH(Kn@pT;pD^rF*GZ>pM!}`hWa7Sn4mCH#8?jcUw?7)wH6t1f zCb7*-{en0Jw8IZ_ibk2xTAnxnR}kNuZfTN zCj47qj!O}GY(}h&i$i16jj+eg&Ezt!yGE{83^1-Ob$(%e3$lCLYDd1ufMy< z)UxhB*8R7+zs&jwMoVKbS#`l+5`*Vb*a@1r@|78y`~fFvY#e*P=apI3GwfF!U*?(j zP2Cb~Br({wjh(fK5Jz2%s%j-&U1r~ zBY%M%Bvzf)tf`WDT1gK}!J zjG-JLhs%}NCaVZdO^R)@V46hdcSQWx8soeO;TfjRP+TT0!w-CwS+Upq>N z8xt1Xw0+m(Q!rPE54UZ!@jVSwM%%U+@g(O(fO|<*5ct-9sPH7G25Bl+^l=jykj)1qPB66DBysz zsn4*W`ME7k5|*U9U3TC((y)ru#tCz`+8NM0G&avJ!p+YudBT77fjfy+)HV+6Q2Jcg zMMlnWiz2r58(&#M>o)*(flA$|*_-EFT%hX6P3G+0d`Ug78m54frTA6$FeTA^)56xX zHO^Tsjp|(|t<%PiG)xX+S-x{!V8r#kwU=A(8)Chhn{{WUdHPox7L1!46kZ^TWuEJT zr>vUVa(T)MtZ%N~-gx7lE9Of>el7F+(#(#A%~p&h@GETcGlZP}0z*iQJ_S_fEUAKS zRpLT;7?Y9HhzOF{k@_Fe7@6kNhaB|%$2sOP_dxWiTC;vNPNZoJOzDyuL&N?$jR7M_ zjiF%`Ut@qZsWCLH!fOnWCiR4dDO+R6$1sStM2#t@vHCMOh~CrJr{^~s zrhp+hjh3Jfgm_8AT_f>Wo#hs@o8M^Wve{vM#B1PAVscP+`A#p(I@AW^wnxO?Xkj;H zccR;Zu!G@Ex6rVSLP;w~QN_Mf?jYheZE#4BeKup-K6z6sZgX=ke_~9UOl;QgSy}`u zx7&X0CA?d^yX*ytEq&EUhPrTTe#3I}mz7IJwb?lJA1hXQW1Tk7=A1 z);D{w);)NWd!L5Mp_-QO>np*C|Ei2lsAhWBI_A-@r6ZTE*iXZh^@}C2croI1Xq~#& zkuTRZ2;JOAQ@07^h@`>{{$PVzzCmL(yU1^zmQIOHG;bHsFnTXW@iKEhYV)WkHcR*S zo!TP!#`BJB;4H}|viHKj0A1t9lyGv z*8#%-L8M{}t1!?h$%#lJ$j5+xhu>3Sg%2EDeeGh)K({^+fh3#AR*uWuQEV&c%kcf< z_bV&vwu2*?m6ll@$uQl&ZL{4B;~sT{lNgWDS0Jm&Z3i?=84cY9#7&lM2f&|vyiUWE z(a^0z++^8y0Q|`<1~g0#4V`?q9hjn8Bg?h}Fpk_}K*JQg?ZB0JzFw*(4|tMW3}_f# zDjm?(;DoE|Z-n_2>%sU}L&x8n4FqR60;%ozdq(LzNu%@usQB?1;g))o?#1q1`LONu z6W>Oq>{16*P)-Bf2rBbZB**w%wT*ih)-jGMsi*In&X zHUEdNa<zGMC?5m#~}0azo+M)?g2<+Cry z7fncto&EGhmhc#BrS98Y+~O3UwJdili`98RaZmhWU17(p(|r(qR;Q9iIH7vksSqu6;W+~t5l7dcOe zAc@_m{}GLmY2(kF)E^Dh&PTGgkFjdG@=fPkG>w5dTT)|a*k7kHU<9c#G_2xl46r6O zhK5ymjRDf6#?UZjYYh3E1<{tMG37KEmwMyRcy$T$$6yJMQBTupv5m|IFn5Rm&EG7QHgwx_i>7D~K*%EpZt5PCDRE?kk{Sa!}0j-B$oc zq|JB`!_vQR%j?=HI#eyOIt^3cz5*Scp8EV(50!0S0kAf;8ry6ZxAn@n5msBPAFB0$ zhE;@p1?Er;-yA;C)H?gcUMEgKQoYsgbRT|71NM$3rhX8COG5SzIvHJ=@KB~OgI%^##(Q5g! zU1?`t>fI>Groj*Zx$*o@!H24f9rNW+AF^eXeJ_H9bz>z&r2^zl+X z-BdM{j{A?s@){2N%+2iJS?y9}Zx6_8NM0t1;p-m`jB`x1Kdyc8n^o3>2Zif8{=7-U z=taMLS5v{fp6A46qXSvb>e*V~3tju_of{Y=$wu*2L4E~Z;u6(rOwlT_z-!f$&>J*C zHu9K!lzN;z-0?)s$h&jxS8m_&Fn`2`c&R(i-O)4pDp*>%oM8T-Q?h z{fRFUnFQ#K(AD!Bq`%5LWSTL#lg;h_R?UNek_t2UgAK=r7WHPCB_CaE9htFztN$b# zW)6WFCuh5~`F3gJ*oEGLh9GJ9zv3Oe*21EaalKjRBV9CF+y(w5Mi(5#=Sw)^a?^NI z8=HW|>;tARIu3A*83>k2vP*taau1FA#BOE32Rx9&WlwC|>Dferl;r-9q3x`7?m>D% zmpAq?6P~w-IkCtHQvf=6%54KWf06uTmUD8x-G+r94j$vw|4G9XFt7v~q!X!an~^WM zb_Fhwl&jzm{0C$&FiBgq*D~Al)D-89^P18y1q>|V_M{WB$r$;{vgQT&A78P0W?dG~ zHt6KW8^QfD_R=spNIn#25gUZdjfe;F)ohFxk~&(v=tCWX*2x?DOi z^u#8+SP$kx!Fme888%svbO;fbHxO9qeK0SkgkWpM3TJ*p3Bsv?OyMyxN!z=$hh$%q2VBriy=Sgp`by>wVJ^WvztD&oMs(hnia;T8y+Xn+9!siaZ z#o@lq9Z}ae^KjwD*)(h#uE8k0pj4Ir;NoUwZQZV%*9-6Xa>8%FGB0ueKBB7v_S9Mx z^vIXhb(r_L7TXpE4Cqh8{*%haQolGF zx6bK+4d9Q%z<1JtJ${4M?~gS#`_XTP+aArs9(pwFzEC7`%tw$O?H=eK|JTfZpJ9rE z+aN?5JB}^6bb`ZPRPXsNw?p?fwD18tNQ^F~WO?+EwQ&>Sj+1N?LVw)2mv?~0+tYn# z!p8k6-4;SXNj526SYaUuIIL=7g*8Re;5G-vz++;PT3Cy&`6bSt@*m6pK=Vr(f#7h=$RZ zlPGQw1&I$%QlSNZ;7Sg%Xc&DFiQ@P(g^)kUCI_UzTN=BTR>=xi>oC-0chIk|`{r~R z1$L1bU0@V%*Gt4@%FS?N zc5>uwT{HLGjU|sp_0<#>8T=N8jVJ+c4_)uBZgx5-v+s}H&vqERreSgrneu%L0~nDX zntW`Nd7E#$Tkgxa@p;Z{8m6qbFu;?MW~MWK`ql$J75f&3Y{ad!Z($&3pJZRt@QKkscSt7W#`8Y~AF3rc^b$u< zDY87a>G{sL&IOahmxB_!N8EW*S4X%GLeCH!be?{>#YAwensc_TZO_ZpF^Z&N%9wge zM%*-h7P$|NJ6v4Wre3CD%9whB=`>kh zAqD(BTb)Z=V&5xyVDzvxTfcT|O2g!!mF2UhfvGV30(da=;k4Gawyb40b9U~Yr@0Xf zBe5O`!%i@C*}*`#Xy2FX$N~!BHP1Z#e=HYRL~UM?IPi3D9^6ox0!WTXz$OxFh990H zKY>k(9WBvDZPMDbaF5f%eHIs9_B`a0G1E!S9c&^oy7nt(iV$}spi+^05y2)aluK*LKwVoW`a!^vB`MmdlZ$W?Ll1jiOv{BS}3{Z;Vk%Xs|p#zBcs`K8{e zJD{ z4V#X_VJB#Z92iKrdgD<1qgW3nl;FXK;0#9~xD7(Yt zFfTBaae~CD7l#IMKJoip>g*wZitG-;SRrUFM1o1pg{ zxn}sX#^0J)hU&zsG_mWv6aqB)cVsdEGpg04iVuy=v zF(Bq-6?37;)#41pDFsHT9jiLBXPb-W8I2!R4dt4<(=h((Wah?#8x%3oV2Y(0Dq#x3 z=7?k#%#Ze1)2_-xO<(T%`H^Eb?91RkOAu!hjtKa_i;C>F=)-=S$o7R(cLqPIOT*~H z3dIlqI#wRl#nL3(bfaOwg4KhTl~@4fCzTS12~zJN9MD37RKjB5?@Uhov5XjUj>qJ? z)I)=dMwdfY*c&eMdHpKw5zCYMZci9}ksAzYm@;(K7;%$jgCX!IHyF~e^3+j8iSJ6P zg20m;4bw0==%svy08F8jxvLMxksAzYm@+mPW+QI0Y%m1=J6ZPH0)KL^Ee%sZCxNsFzKhrdMQ$>0 zaDG=)t9!ZOq1iX?Jd1-sl8Pz#1AlU_Ee(@{_LR?aDKH8g7(wo}rD2JXLX7)`Ps;wn zZ#5K^w!U0`)E-!~p7sd(z3Fomt4nsytwsNvRQIpSaczMcwRCfK_>=F+rD4iw==vgVvh4i<{^W0X(J(nQbn^WTFB??F__>CN5Hoaf01N|_;IrQ1XVu!vU#;7j2w8#M)(6K_4MM%ftO}2yg$u4X6Xi# z;k~Oi6i#rwbbTv|kldF|!{ks=%Xd!@7(wpKreVt3m)!^Pi#ukMqHejpx3m70Aho^E znj@&hN(nZQ`?6`6IYh=dL2Z%C((f|u%LcCGl6M+L7Zthim$+Yk8{$W98GvL|W&Yrt zbV?T)srScd)R7=E8py^{i_D0oQ+gb_^uTt@pe7$WXNK*ii43GExj%-6{dFP(Mv(hs zXjnzv9|K&;!cN1KwLgX?3{d$bRYvd!8_2ydG)!3{^9u3vx$>!350hz2A_@zWjzwLD z-)EF)S9yqxeD=qrNb1Q9KxUR&WGtgcc&c&LgT~D76L%wH<``j-!OL2sQN$7Yd7P(a zI-l)7xNbU;_d17$$w6dFwLb>RDt4i=EMx#9#<5)8xwbj;NA8~;r4?@e4-He+{ut;; zuXmkjqi^@hc&$rk|CaF$0>I#sDk<1-xqs6}3+ykR9G}%PIVWJ5E)AnsQpN6%$wA!8 zx<5wt85)V}zFe6Ch3kOW$7?E*_QJ~aC?fyI4(~y)bF5g{VEMpK#8S-XJ}&3 z`Gd@uprf{zj_&KW?ttNfkk2$s0W&nhH4P|%6B!7d8Tu8$dFhf(KO)$9c_G)aSz9v0Wt4CHon5Vn+th6?5 z8Wu3=AjfCZg!c0`=-dm91e-`q4suz(>%PDU-O+7>V=R;IEgbv=?S|Ugn1-<-l^7=& zAiX7OmweZKLA&4SaudUm7XDrV7vob{shlc60d7jmY48IF{DaNTn|!yeHt*V{fgx3w zF6ltS=u$~eW|zt){{4v$kxB&xaQvja+7E3P4ewvY@<62;>@N^rl1=iPdy&t&uUtvn zL$r`FJSKOfo_ofq^Hvw2OwxK@v-~w2P(;BAHbWg}DD}WauiJiyvM3 zo{b(<-8KpglEz?iX%`qwV#-+Bm4kT5va}2MlS{j3*fBKXH7Fh8tq{4-_)R3R@($A6Zl+!%D2vBf^Ic2mZi6?#Q+`37kXOOLk8N8{7yfmAxph2*hFG-&_yV*aLZyRTyBa%<^hw-47uWGvO2Zxr-AO>N%s>AH58-smyl6#!a&b?RT-;&O z0B49;x$u1_gIt`AdRzaJ&CStmCx;{+uCeAcz6)e6mJ3*6)%#)h30v7u=B3&l4?cWu zEq~P&iTxoL)zF1%X0u(KQ1vCOfcQn6@Qp=0#C#DH2NVDz7b+@$TmlxD`#2Vju`$oM zlX}DdjW=HuQ?j_6Q;O0`DhGsndsu>;_l>vR#_0a2nAOpv8ByLnO^@1 z_S!y6Q{`D-ahVw2KI!Dj=jUkHAA>Oibm1TupBY~68p9mjX1J)CdU&|GIJ&E;4M9By z4cCbpK9gNEJUm^z9DQ6p+%>#sI61kvID7Y0QFUO<6Kj}Q59UHBK@%O_yj}S3w)=g? zcuC($mY>u}?3qA!796%otke{}kwI!6Wviadwpy3tn^J$38++`2d>6Q5W%xjj)>6{2 zKct3#wPLC$78Yor$Q}mV7W{D-_)a?De?HfMm2C0sxZ0fiTWp)eo~2=bhz~@hWZ40p zS3cG{H^y}O^OsdJdHQ>Mb*5pZlN~VZ4=pKG4}>2B^HJ&^2w9u_nTY(v<)YZGd^U5% zLgpy-EX5bEejc3O^DTY%?dy0VUblZ4UdWV!MhRjUzN=SKQIYS~xg>)ZMHwdjHk_MN zWu1#*W)7_uC!hqa-6ti_jr}&X&%ZS{n*~K1(J*Dy;)jS^jb%0)K5%=~O}V-wPE#f6 z6y!hTpt$@8f8g&N-=a&d_2H+j9{(2;wZ!uZ4XcQ?7 zVP&Yr_)|$%NFLS#;-gG0MHgN#zev7S#JX8;P z%>AVniD`qzHyFoZxAE}S++Y&6?}Bhr;s!GjS?v%qctH*Gg#k^{^HzQLaI~gj%BX72 z$l&w;-t08fV%)mrQwJv4yYJ`?nItJ!!5{cv3Aw#!pIMWpzZ!K8=odNEoraZXRb%o_ z1-5c0QklY)PG-98E7q_Igm_T;ck+tA((R_qFL9jbN{ zY$7o^RKfCl@LEo-;7&+jrJ4^xS;8u`U zBxsldsvyuHok($|RU5dVq~Z$vqdR$WUbAi#Sk0Ul{k6%8bQ-3BDoEM`-=*%CL15si z(>W%sipe3b`G=N;W^Qt9NWKbF|dpr5RrcM)>Yen)$-)ew_^0<^C`I^wVfqS4a)U32sp4rxlRCT0OP+ z=?q8gL{tXKhN)BA_(k?QQ@20c8qlq9O$Y=88?YVtLg6FW@jRei)>D%vy>mD%2#`V~8emBY{|^&Hk*-Zs|}sp{P1dku$GUpuC98RoEZ%6AUy{FAS1u3KKX zUjJi8kp7q&dxUcmcPU`dVQc@r?N^(^AmhM>f%es}AEIH(=u$xGmt_tM_$ME(TzP~2 ziYog$`i4|#J3fwvRm3g@@H{f=;PpY)Ra_G0UEBCpWu`j~D?{soFGY6}b;9LC)Q2vv z0)a%KCDr0uXj%x|A5&7WOi66>p4&jeUZNCqC6B4nQaA4zJk9Xgo?orDZkzh?YBBAv3?L4$zL#lyGdh{^Q#LBv!2Yi+|ui0epa^K zB(RCZJRvg132bs;5Ns0;QG68ZQ5-__q&RAT#c>B*=|i{;zydjJp;(R2M^D(rK27kI zMdKILy>ol6Re<9}f8VGjZGDOIOyV*N-4xP}|iiY8qvJA7- zr5eHkN9<%8!hsQa;~m_p*gbxd6cw^1-fh%S8b%+&DSq=aEZnc`aje=1%g;62)c=sw z@}>SkFj!n+20w6MLkrcm&s8}!dd>NyzBkJGmM;yX58o7T*H^?ZJACpNBb!$@&~&}j6QTzyj{-_m-E{3UssuL8N92>lml(Y zhNIEu_-F$|{hBkhT~T256;0=G#?mlli46R5sf zhV&@>7&3R_Kl2bIQ9P9{GE(<&Jl{&_;iw}sc}!nP>QU_8H?<;M?WQD{=8WDtBgau> zfgu(dNK^DP!{1)8zE|Ixw|u)(&`~oQ_ScCFt+3EAWr+-}VwF^w!5?h+aP-H=WLus1 zXWuSvs@Y=RaT=yTk&*b?8d-ZdU_-qy>kWG>3X4>F_(wkMyDEZ)DNB5yhoe@QY+qo@ ztEVw_@K%mP3jasRB=y{4nHo!dNq>1Llf>6(K>rb3iQOMq-7I$O<%z~TrBFb#aKXrrv-kWMcm7f0{y8*^u0@Kq38uw9?zynArESN$hnuE{hP%Av zFKCv=rvA%gr#-&$$t1qX(3b~qEnNpTk=Sg6VJ9dEWwxm{inEu!r;9ts%XOxUjO9(N zon3&65SK_j`Pgst19ku}Ssi=&3$7Uvoar?YQ3Q zQ-K}WL}J-Ocjn)i|Gi?g8bAd&SD8NFqKC!kr*=-$LdOrZJV3)9^LhXNkfR+!vGPyl zmN(spTKwjcAyHnsPZ0jrdtY42@`*f*NrqBZ?3FoWLn>FGH~15pw zhABu-q4m}D)@X<6@Q-gtY6BjpnZwm&Hm@>q33gTh<#9hXYY;#^sue7P)OItS@rXcYo>4-FPS;)7plVS8o zyN~(r$Jfs~x!NZTE|A71w-w9#+FNobhP^Y{@#~)9IIL#vPW3^L>!s?dS~ysIX{3si8Y2~ zV4NV!%Uqstl=#Sx8s91tq2J#<)EZ>>@2ALpufj6|wxbzH>2ky(a;K#&yI^uB>pPi? zcGnvVHj!9Id?Vy1N1No3BWu;2Hn43P4*#%oVAj8u*++mqiFH;CdvqreCz2x>$V=87 zS^Hs0^{pniclo|O82^4zTL->P1ZJohn_ym3LzCs^<}r)yF>RWoyR(~%&mb3fXBRJ5 z_emO>mXq8)yj<9m9o;9n*tmN8$k>jGojCZro&lshmC(`El4ar`Aw8toe`dKmb;A#2 zRJvEl7VhZcX8`+A9+A%gXxLxZ(FG&OX8<%zK^_{pF?iuUgoc%OYb`8*GEMV?5qJC5&?~ZCX}`d5S)euN$U7RQpw=1| z(`uSJdb{vn?`nsZLj8*nffI-q!oXNzg9X8Up8@aStFyKjSseAZF_;`+6IeKnhAF6( zCh3UuJbEGGN1ndi`oelu{N6i`ShodzIeYUsn z@ZNn_>-0Re&m0<7-YWE)-S1DCR0xd7e5Uy!%eKYR;P)2mcsecC&@ct5P)&4uP4*Bp zD?XwO@&kltUDW92YV)o6nx(JPx18LQO~aHSKR$??+A`a3DJI|Dn|3rmR1i{c7lI^K zRqzM?S(3Q!G2 zsqwqCjVxnnvwx@6)!w4|xP^I5w&>*VzYkWBST;5R9pz|+P^|n@k;ZNYf@115V*A_7 ziGKV`JIZfWCRi;oXa0X^7*b^Eo~{^D#b%-XkCuI=I7J?d>mEdF82B^CM8iPC{{vUQ+g%4!|RhdPL^L=6Ie;7_&=G)zIQ15x72(n0`hvNfP#%4i|H5Vy44 zC6;>jm0rDRP$jOYOH^M3Nz9%9krqNj(mF*AS>AxCqCdP_fK{W`5&A=8Zy&M=p|ubP zP~tABH)(!~<<@OqCb^}*Kjb-%hLv{ii?^R?PI)D*we49v2L2U#~!)vgdoMucL zVmZx40~i;(QkS=5mMgd`%%j(4Y}gRvrJooNc|&5#Xd&hx9%r+9v}tV7?da$m>i##9 z7Vx*KNh)uD&-{@(dN;7xS!_>P7FP}#d3ltNO`B+*>871Y0X26DHv)JT8x~D>hW__N6>r#vkTW;fZ!BunSrq*A z^o0J1Zi)I2{K`g=4+3(1IBjWI#l$pbA#PU<=8E3dm2SXwn1 zp4PeM&VahtBWN0P5JhNwHK&!E<)HCzZ?}s*?qg6u!^&G@7+d)U%cL=2#K(KX7d>FD z>H2QNzv1e48dRcT3ep(ZBRJUBf$Qq!Vll_r%h4UCbOo+d?LN>xAGLYZ6Pu;``%Y~U zeB*gXHVspT&IBQDYWW6@)$Ag_d0ILpHqpFY0A@n|3FjeT!VdV8zYR^pl%X@r5I6Go zvw^!LoBkf18Gz<2#Oh2gva!@U6FTVluBzt!clY~c67tF7**u!g975?w>I@D0>vRT; zAa#a@DM)8vaDjBj#&yzUp9vnqBN*Z52PG6<m<-7b%us1LuWQ3 zZZme|2dy#NJK%WzchP4bWWeUG5_JanlR87gl%X?Q5V!wbo$+lXL1*%j>80+>Oj0>> z!q+@RrRt3hiz_|-FpH)$IVfUMXJ}Y?>kOh*>|`1=<)F(+ouOe0(ix^RGsMf$dotV6 zz1S8w`6c|Vq=r8S1tvv?hABg2q7k>t{hKygV1M!C_^g)6IRVRb5mchc0Dn?sXqYlY z26|%^QDh|k2$~im4G!0Eu`jVUc_m@?Hy5phEValSiSL*4$!2k;SB->(jGfDNU8G0^B3?*QT4tkXTNK%l}%$9US97AG&%{S*f{B z!+HQGm8;eNV)8-##Zh1-iP5E~%vM4Tk?Lpcdem%jF~q)ppVhD2Q~S&t0?$Mx+9p;3 z)KSYMcFx2E#mZxnRO-3eocIr4)Ytc99cb6;MwL4^8w)D{-ePqGMI8S9XR~n*we2%{ z_L*PVvBeP@26O$`37W~b42omE#k^Jshb-2;VxWW*k)mUXVvj%1-v7@HH}>)uZt+2} zZ=K3krdmc8qc6I*(4NWF)b0B;9;`n z@-wX_S-;%)Vb0jtF2m4ux6jzJ zqE&5cFPsQKqY``|cNG2EzT0|l*s>?)>w<4SoA_?U3>v14B4dXPp4?>3W*`5@oYo;!}rVX4WB`^2`e}gd9meHLXaZ^$G?MB0tQDojAZtv!0F7{aYoa_IlTH7&p zy$XS|B%5Fc3S2l-0Pq%Ll}1c1iY-%GlHT#7j;{XxJ7yK?YqLvT;J!I!KHgxvsHcP5 zq~IoT3$F_oxXR3(j-lg)58DqnZq?qB&yRq)y>XmWlKpo9mPiUAjezR>DBHvZ_yVF&!t>fA! zPu65~Q!jBn1-5CWhF|UkDP7z6Ooj-OK3uG@<< zyfv&|vwLlhJ~-oD!D`_;fOilbM|?XB{duY->sY@T*L3|0S%ZoYmDHj!8?M8-HltyATfOTj=ChbTS@ z7mZ?2!bx$|5JnpA-)o1|Jk9NUCA5Cc^x=D!ZwBrp7RRuJI0ZK#dt~zcr9?KmS8t=c z`wY0FZ(U4&nC@tBk_Y#f#wOLvc{i8Yq#ERm9UJzv)8I6)iNs7GGR76#^hYlfgaL=* zA0_37P%0H)!@rto-1#q0p0~xZ?kT&fwm$EctegLH?+OTMg8q8fn%4ZTc}$3H_c2Me zu3vHmTpC*qeEmMzTla2y&AaEaoVuh}gNQXrtOt&ZI2K0@xH#^B zi`C%^l5|+&uNlgu!_RDNKCHFVS*tZIbkmcqhb{{njCGi%3p7j_It+PD>Zzo(2S0GY z-~Z#T9g!AiM$eqxdiQAi(8Ay+J4dG*M}10UIhNopkcB6(7!*53#^iVu@-pF{oJbUVz$9X)9w+0AFjk^(=cV| zFtqiu=rHh)uJo+ML5u1GOlLgXR@L=n7!5P~ofZ5~L4J^J3kZWyKnV>d3ME#Du}41? z$mfh(wXHU~7cY#~-1MQZ$#{reoMwR^IN<+f#1gftoRQ6Mj?>Qejao5=hW#~qds&j+ z=6sXT@6AD1%6G`wxK*F)cMFHGwsbl;ZoAsEPc$(;i85eNGfn&GK?iJo)%w+_xp6=) z4O4~~Uq#$}4D%XaV$WZ8!^S`D!u5eU2r98q0e_dXMUxuDjAUoDT<6%omB~yRrVKIG zLfrn1K?^Uqo}(LFxpLrEUW06DZCW%tWK*^2AMG|js26|o+xc{`iNsaQUNJjck_nIWeu)_{EcHm@>o|3R9&Yowl7bt+6EbbC)HF-KOV2@|7f9z~8H_ zdU%tAlej_JPWL7raQ{fd`a@)l6XXXe#-JKF6#pn(RYg3|7p%F$IR9$gDQ<&8^l16C zx4qSywQr(aH|^KE-x&gbLw}#=*KTfQX*O?ovr!SV7S*)^TpC;ZW!=3nZf`ZK(9Y|+ zTHS7u4YrclUn9~mdoOl!LgTdrk@iGa@|X;edak+ViOMO{ZKjx}&K$Znf;U7{ICHB( z1|W9|{moLf`1Fw7Khn}gJ)+64#+fus0Xi(UJYkQ4h}*D>Jn`R1N?U1k^p z=aR||@DH5r?^$HiG;WdF`c+0p!@JQi1?VuQ4m7dj*AeV76rFs?;#!WdYvY)ZmcE#k zvTzjyl*XpYUZ<+3+3va6dsBm0l~C2~U=xWcK!-7PY!4hoR6`o>x01VaBH4Xh}0(4j`ckBUWY;~{hjSWrAm#A%iA2Vm&sGVS-G&Z$cb@J%}%P!-%_4U&= zmtTDhHjx+?B4b=}qWv*BQL4v!m^zLYj(?P~FwUV_Bkd9=KMTm`HFe14>##I7?VYjd z^*HnKD}BBPtcd?dZzI@5Vt>aqNl`a=(`quoYVM44Ci{j~k8L+i ztrc7#jZKx^HO9WPuBQ@gwKjc7pXnU1iNyXIz5O9cZ$m#y=--Cckm2E5R-vzrk5%%s zCdU4oPCoSeM>rF4|Mm<@&t03^O&`f_y1=*52 zc_6jO_1+Bxl~`_of6o(+O?^y_3eL@(yR4wk)ps;Z8F~v_=)P#^4L2-uvfa_g&o1!W zoZZser2e6|@>%SFg&2M%g0|S9B)tXxHZP@s3z@(W;GiiEDtN%1i0eXvz2QH3q6d4ymUX!{Bfl4Yjz@J>yK*JQEwm;&@xEO+by zZMrOa3;fAN4Kz#{iyA<0Wm(h!{K-WPH0-a@TZxMr#-sUL9#agYek68b>az)5gZr6= z?Wt<;qQ&g)G)aX$Vk1t@ZrJR!Dkn(od97W2V)AL20wfjP`41-|sn?MALN>3>y)O?q z8JXTGg~ulJg)2&`!odH)xV4=>TL+phHgj+MW}D#;8m0hA1$v|tv1u{#-4T$`yXhG- z>s1N!BU+hfSil9+*tA%M9dvuuRc=tzQ6qvc)oBYhk(dG`73h(!xHkqK(r{n!$o%c` zH!;>rr=0TKdwh2X;7(!+kW`X4d>6@&N{GCV{rbC$OfBpFW8Ht7`^zk7^`x@t`duIA zTJs8Rw`otfu)OoPZeSCM^@qq9SDa{nbYbPYG@&1|DKlhw)q5`+TLd~Aw4SoP$0MKs ztG0D@hMs7-wvFwYuxD)>J-iINlBBZr{?$3h_kN#Yv%Kc20jWnKhk&gl_W!Zenm*gH zZBpnNleM#KcOSmtc8eyp7f_OsQcJ^>A+^^LH(8_>_>)pg!;~SlD-btXq!##-vP#1$ zqSOLUQdVi0GNiT&$kOs^lh)hkhjW%h2Yuqb4?%QGlpo+v$|?<0hSZvhky@z3vPdo1 zMan7-``?gS6Ipt->%C?q2j)yL_s>5z`q_?y7im&^5hWujwKPl_Qrid>4WERxpd;*a zYbK?=O|nV|*o^3wSPg(bDYZ0A8B+TOxK*lKBXGwKlcklK%&^oyIZ#@gNT~&zNUS1C zE$}3zmWC-qYN3o39=W?a+vd%-f~WOY?$h_nkv2a_sRf%zOc_#ZBSvcLA^h8rT@fEl z`fa-5V|>sm|Mwnk1oP_@*iCa_7b&$g?5~kpi3`9?)Fmtc%avsT*x47&pVvI|#43Em zPOWtgt7p@6I2WZcxd4oYDMN>25I0#CfB}DU0T>Nah7R)(H(9#8z@Ju{g?lySpJ)oTzD?*vwG2C8YaX0R3O1{x-jOKc#tYzaV)?y=K89h z%UG3@F79X-5mck*KQv4kS`HAkJV5AOjzf-KN`# z^KjNGSZ%5@se|*>kxBmXI2)Lw1hvVR^b6Iz+A^rkp>As%iKYVVr|BOc~`BmY#Kfn;772b!CPGDz9R9q~?E-P&{PXA$73I;a`*HUFN1A|6YCYj6EXn|E~;Ok%Qg$5hJSI zm}mdic~bw%VL{c@o6;}^43KH5#4jG$Lmi!ra5Ar+V!_%JY49Scz}sala0Y)I2ELPy z_C^632E_))Q(P{~wu>G|CrnAirjy8rd=mo%md2(gN2dE-WS=TnGuPcO$Y%F)u!+RL zCS3K)%O+U0v#*cVihbRxTLygS^KDV4&47|@5?c+%SCcSLl!AJGJSL5?;H$%}kn2E8 zd+<0{x5mYfA1m1hpYyJML~F!AVU@(y09JaKjIxjB{rBEB`q8J=54#N?K*JPJ4S*u) zM2bv(WZ1ufLjyXQdVkgm8MpWPk{K{fSYnZ(tzMyF%BTkL^qzb^BCSpOsmlsmH_bC$ z{X?s=*|bzgu!+Q!Q4RbNkC&|t60ZfvnZ{3f*sz1{fgdH=B(@r;OR5H;vQ&etOB;`! zJwA*b-GB9?j8U!M(5eAEg(s^44O2!nXn?9gzU_SfxZbzP>~oqDgyY8y6=?c@_8OvRIiY&b7pUo9e7O zdDUvkji@o15xa*tK!3l)CKvddL`U4YZ~3OSdc#et55Br{l!jSBWQ;2>o4%s^HEuZE z#fdeVJGp`Prg`&+l(?7`iW5%%GN(8{$FSw{i7kMThA~W7+V0tfD-Fzcd7S>Qy|35QtRPGdxZ=Ekr{c%Xy4uvT ziS<@7$ltIc?DA+DrVJ5dBW|*c<`q={+1gsB#-?U$7TZu;PuGxTtgCCFg^D1Xt)pvb zV922sKsP3(|AkaXE`oVNf*Vf$zz_$*;3OuH>+fs+{OrP1l|LRBIWxEG#00=GmN+15 z+-1a%bgOK)9Oo@d547LWy(%oMAAr-hv%$=M4{;HzV z2%XqCdi!Wtx;wkf*0A)}80P5a>a0TQ2LC|_Tm+96RO+BVYgg}SEMqGWTuA+?Rhf#84GJkh{VJ_#?5gMVFZXvwnyFeSdWRn)$A>n>h(&0^-7; z&)_(h_+N1#5fJ%IVFLegfW{0QPB^vSUsY7la7AUJqno!&u^fsmH%%C3r7kz!+UeAa zHQ7CHv|s)320k}Vmb%=KFXX$6`fCiC-*(_s##WI>vfMPr0qUa@a~ISaIQqCaYp~$C zmAB#x4O4vnwnD=w&hNCtNnTE^XF8K(__i{%o+%Qyp2{)=xZ$)Qw+$yga>9#&TMgfj z6?wG^E}#D);;WbZ{63Vu`B?D0JK;AL)GMN4%4j_YB5pS87N^ZH>whdQFKqj_##;PE z3cwxnXVP8dps3bU%g}(Wr)8{XY^$0?Uwar-iT1I+&)l^dVErUsc zG8Dj~cM`g9DM%D}Orm31FR?{-h)up8XRg1VGk(pM>-$%VY}CUUcncBV5#ip{)FjZS z`O2(i>o>1lOv98>00$v%o7JLJPFrs7c)EGM?^O3wXCR$RTL5v#LhA7Yyb)XA_(|0k zeK*x+8F3A`+NNAX13hgcmNA=UsHJVnG1X&f8|j&us-U$nDg(ScoLs!UUEL=Yx0&T6 zg0-1EEkhafl=S{o4b;6Ubs4;9^rEn@Y0Wp2PP{$P`GTv+a!#hZq>_h{t;RB&4Ij8Y z>ZV-X5vQq=bc%*4qYN%W+)lk|7~*U>`f=XzJP} zOl>lFfENwxh!X*YFJaDr$zHg7ana&`k>aB`Y6uGv2}dS;J>ZxVbu=%0Auegc5eT32 z!;;N`ylNxMl#Tuy>2cWF26_gDdZsKxGaWN7OIycKPu~rzp@=2NV z2nU&pi8EV{gkc;Hy;O|H+yhsk5{GflW_m77l24f?Zu=UuK67bTOb*hQiA&`! zIyc)i%k)a86f^(BwO+Ta(It(Bm8algZllo2-WIO{HLFgxOIthgLt}N7EtoqF1K&xf zC?Pa7GSoKJ)8*=F85rxa40Vlljr4TQbab@M^z^v;y7b3DSmW@-Yef~poHkv5t~Ec* zwaGTz6A;U;^?yS6*UrK#QwR?+6%%WX3_|EB=?Ak+WSLN1x#hEJfp#_f^z0Y6m$aTD zvM?G8$vvbZq!7|DWeDMz3MPccdRp3Swy7?c!!4pAgEhxGcNuLgXjtkTef!a|sj&S&=Cr_1fO%6{8f*ZsY0;~LN~WeDN;3MPcQ=s}W^ zv9^H$8+8Q@jrEQ6^bB>ib#;t&boEi!(BQ8Y!Y(t9~y#Q*|@j>xbL7J+ylD;anP~jBIU;(rv_ZlRg7&RvWANU5bnhjYvUs`E4_k zr113*2mCe0EL7=lKj2e0zdgIobPu^q!#)T_Qv598kGFsF*Fgz|l#8ytykk6QjtELPS1mn?S z10EBN)RUpx<9@zYHEXr}b<;h5C+s7q;``%lgX07Ace~jW>-**hJA9h7Hodd<>WMT= z8PX7oxQ(pgJk*~xy>~?YCP7gJRSkeMqyv){@bwQzPKG)#A)p1JI&y8Rm^CeI9c_JW z0~VKMprr?M07hCyI;O@3Xlb&smMK~mujHrbcp)dwW*Lf^a-O0;M43W9MW8FHGq=1gCFKp zW)}SVR!$<@1R5LU%24{%UrLyK7=YsE@eLB}!z=M|)Z8I;UZ>j**4|(hoxJPi_AE>e zh~mx}yyK&VW@7Ly%LNm*MvluIf7`J$4O2$xcR>cP^G|*9l3 z?_q@JSKT{(rR~SIJv%0Z2Sr=*7yE-h4kNf!a0dKa=S&`+X_0%g{`f(mk=?Zx(J)+l z;7Wl_Wv)vCBEQc>Y=R91`)*abex76BW#Gj}i~F6lEm5VQzTosPbBgm54qIMkTlujm zsuefj=y73BkpW9fS5Mc7!_w2!V;P|39b98=Lmfk9uS{)Tb{$hrEB+XjC$bf%Vam|4 zU5J~l{r9$CZ3=^o0~-d~SHFG;su2`4eqn*(lm^jJD(M!Gsi9F8H&lx3uEpsTB| zljbm2;uMl$c&{aC+muXCS66%XZ*i4%KJ0Tr&Mxh4Rn#y!;ED%0&(JyfdJGz-j92Qw zZeH@WBEVfz;|l)3|Gakm*Hz|Q2JdPzZ=xiGrLwXEHWT~DfIj~ssVu<)2Qi<&hm7IUGj&J(%7X|m~3BQ%d4j`b?{b>L&|%w zi^SeSWQ;3MyY`@a)(f-Vu*agXNTr8=Nzv05C8e&k&2qa+QKAUvk*Nj+cup?lzFR;va!iOzU5uQ)qS<)~)AsYk*B#faX95Vy`4lnE>6oc4PkwV`FMdfd0+MzLJ^GH2mM? zo~f^E(J!La+k*j|Y%3k$Phxw75}}yCDlJd&o%zQy<;iyxh1umPx1ZXzP*u&m7Itjr z8XbsLl1(yH2KA~E9+!hg0uOM1EGhybrLHNJDy7Z6AKKV1VwUdY$Gvy77EU5uQ(mBm zN8Os@Va}ej)@<&{J))T@Wdv?URRg-OSvE(g=FdyEzE~9{kGV=R;IEgbwL_B3}Z|D_v}Y?7e{<)B^j@@-C<&AJsF5}m+G z@vhuz-Osl5gi`@ml0sx0*__ZYdL^Mrmq>aF-%=>e#h!{Jd<_)Uh`x(+PpZ^D(55+3}4KiQnnuzU#2xbmnZ_+HZRCz}r7Ph#}SK+6++Xa2EFc~TRRFNfyD zS6xD7faZh;iHMxkeXF{c2kt#%_l=W&qqEhEQH}Ztrvk1FFHwYb^nx38OYLaAH}+e> zynh{*(=d8vC}Jq#m`n9)ALd%VP548kGQjJeTu)RQrP_ZeC+1OSqh?_ZfLe)_0Rl}~ z+G=uW)(QKK(RN**9{jO~hUG(Kj4O}IfDH~u_mri@02_L&X;{KzpI_GMI| zVf0Eu%PVX>|A;eD1Z2Ko>cV~^c?BaPwPRIB_H1*}JfrcWs-awScL)p@(k=!+H~2tq zJpWVpL+k)Vy{?2xl7gZrbtSpmZCm1t!#`N7moIG3DGdB2oC>&-yh0I^-6|SJuOzgl zS|mw?Zz-G#a4r&%@f1n;UI<*i=i<&WTbyi`PTXE_)X1YfzL0h?6Nd`$C%aWNEFWKh zj^$ZNwxRpUQc1uDvI|AS=#_+)S3(I;#x8ISimJ5TDzQ}|1?8^T&Qp#o%R0FyucoM` z)#7gN^`=()w5oL&B3dshJvMf3I#14Zm^4_^$huEXS#4ij4u zPC+Fk>;T083&jpVM8!Zcv9P<)*X~5I8(Y75mfiE%ckVcj!_&Xt=y7|$nVo%}XMXcc z?Cee-dsV31E7Yr#SHHok4uQiMP%mj16X8r{U|4_;Q!!lS%?$DjV3b11)G#_mLYk3c zYL*BQL;cYjK_#Gl=W-z~DDwW!q^N_g=MHYOowG|gX8K1+uaAAQ9$1zSvK!MzoHT1~ z^#?N)U>`bmL&L~w7g9(%f!q-Ek-b^;iP{64pD%nrqSwmC;vO*|J006ki+Hwp=fqM8FLaEitWfmq%QK#d=tUJzIe2xT( zQr>s}Q4>_a)!NqGDQ)bwZpR{* zmtPzQN_N%|ewVNNlttAy5Rq!@UZG=pTZh9;(bn}r1%PYodL!JBwhr{7w{XzbHaIM5w?lZiY-?!#bkY*y!4~v(4Tt@XZ5_x-Z`W|xeo&MQL|y))+qwft zlLhU*w!A%lh$JaK?eh3$31>k$R6%q)b+8P*t;1n|Xj|uu^f#of0~65OIvn;lwsp;s zZH(5|CFq(IKWoUiuFmWe|9-VQY!@Ckh~4J?>AASJ?ln?jSCO(MC#_v;H@QgFFh~B; z_BiZUwslZbA!MM>uHLbYJ~~g5j#mU!d7UWy26$dI8RReVW8&gwmerkB_NZyL^6jeS zIP6bv(_mV`kntPXV)E0Om(TBP?6mROm1*Zny@iKGq%teTFSv z^$Dy+$9~^74JJi8ckC4G72>N3p$e4vCQ6k;^fAO)&oXB&_UP=EqAWM%aNN)`Uvv#jCOS;4}eR=Q7#PSz? zv=b?MdNo#DIO~#CZSM;2R^LH8I+m-AE`bu{%(4EIN-ZafE9?nVn0$E{Ht=vu$xOw5 zS(hoPohn)rmxW8iftCP@m2V#Z>6V=P{aumroA*2%yc~x?zZwEDU!!a~=E*Il~v2a0Ux&b~K^0}AEk06>#tt;%~PNUMg|WwuTh zI}ICx!+t9V0C$=K-aM=E-sw?kkHw1gQ^8a98j*lv$E#X1BNZLidQMw5r_O|DBXQVo z;s7XC!VR>>%9CV#)RgszrHKUs&eq z{TVpN@D5pieb*(YlE z^Oi|C%(M0k;UgQS zTwHmw&i)EG>{nKFQcp%tBwO26HRqYzan4OTHf3(7Y3wvGfG+bwJjlOd&YE(o?QN4f z+}JefD}cJhnv zgFrhv_FFlCu1KpZD=W`9B(q*cS?YM=JTpa&{*vuI7x!-XB@>jT zW50<5pqT544jlX3w#k-v3(Yt-de(+b?qPYUtJN_C>Dmald<6p>gX68BPIVpY`$wNV zx9nm@1FU1nM)H;p8 zTJ*xx032po#}I&|l&o%N>Fjo-ll#J$jiBjL=b`!^2;Ccohkihi00UTxu2OvbU88SBj^3&%AaF}TwfCx!x$lL&E zLZ2JJVZW6FfR#Ch%ng8I^tk~X_M12Ws%HQTj*K=pknl>!kfASH=bP^#gWKK3Np`M{ zx^S=7-1}kNRdbwUfW@xf($3$duG!B#Ke#095be2$!%X2A;B9ETAKV-pq->vfr1sXx zmXSelpC-??6XfRx?@Veaf0uf}Z_5VnY84LQFw;7Q6eMMnPg{e|$|IFCVxm%bQ>qNt zSG$UdR*X6h8zOdeJh%C#`HcRc9Uc2E90Mo>0cs3YYY2e$2Ndu*6x_{R@rq?#G-+vK zcCS`A>^E}&@E*8wdwISh`Ed7*C(2DvOkE9+#OhR6YtO*$wGIaW8#N@57SwyrpzFfd z-KsiS4|D8UW9z?Ni*46*0Mvs6pOCnV%FH}^!D+(f_?|nLZ0yu$G!AQ_QG7pdu@(4X ze6W^g$aQ1wGK%TdtYQ39x3IoV?)I8gcU((&=1Z%2iF-yU9^@|?c*wk~<422n72dC_ z^_-uM!?xmd!f&Ywm!*QH87WNHH=z?{?^KlXdfz^Si@7~~v@U-7(&WM2q1(*Zh&~zr zemnTh>HXJnMJrAhmwYw{a1c>LOn}ruE0tJ?O8I7seb43|A#P*$Z!rs5(eKUPT02>m(Wud#TH`QNvBhrrlACuOUzaXlY0<3o7dK(eh*k?yYytWA zF7W*%a(NNfvi8&sl^S>j;V@INrKXwH6Ek_q79&2C-yH9AEgW=$rtAH|Z`m7MImwT| zWGu3%IqERr2C?O=uG^IfhV(pkw%>T7i|lRih`Cv_W`tf|uUTU#Dt$rXejHu8hLfXW zlxOwsONNar>x9GbRH8pC@~=@B@E=981zVM0P&IvkGK%eeyZWFx&_ylK>9Mh+c58s^Gnv^uaYkQw_~qqbI;w! zQRyqnnEsSH4#QJvJ}HuB&Y+|^XpK;($bFEj4a2<{29j&5sT7q!{_71Z`K7trg)Znn zWyj=?vuoinJe3MpC%6UdJ8yoRwZp>aqV5aEXSa>A)1?!{X{F37UAIb74e>tL#qCyf z-kD%Ow_)>k<1Y66rdfVeZGcHgrwN`?b6XZZ7t;Mug(|~fy3~W zDO{btBiW|dj*jnO?{@OmjlN539`8I`mrf9;l`?j^8myqA26&mL**0ItJEWES%&oe7 ze63fxUKc@82B!iJGX-UE#jMM`l$Qbd&prx#a?UN3J>cN0X;)uG{=i|sk}{ON6-c%* z+=muxu0C;$yzuYLC;jH%1)bc`r^xh)Ke~=xU_ZIpk5O)|vw{HERy`n2E0tJiajn({ z3r3p>kSz*&H&`-3{FYj-_cuk`Zd@_-+Qqk;u7FYv*XH6d{itNzz7MXy0tV1#UW!T} ze?9wvA3Xa_E=yT&QieYtPy&bPM(UA0v{EMM zqmDif6P=lF${bEHo8jyvDLLE!WLo=0Z)0$j0sG%L&|!Fc*^hyKQ`{FEc~q-84%3e^ z#%-|5BiTyNo%pb%^Dx`$uS<>Jb>tHtOqdsCAi;kcIt->CWsIW}RYh@~0niDC2Dbvo zMrT@9cA3)Zh`(ju@xFj-(-q>hQprx2_W`RWK(;98?S0zC-Q`q!%W&C#z;o8zX;J5K zR5C-Eaygxk)QYX=I(zS?6xrCXssmZP4zCbIjTiEi}877U=x zyp;C=`Oh7F)uiREBJ$-8XP?@3ox2Q&=|?5w=!7~VM3{*FmY6s4<%(i~cB{nJFILuG zODrIeAenJqX$nfuTyv;Qw8QWkm#eE5_nEuoC1j+{1`xLlB2nOw-_)XD#w)ZqTx$bo zht9}1#qR&3*getB_WH*POLlw81-Uj^p=wVNB!>Cnr}D-2HyTWjsWa{V0L#iaOh1Yl zr)HCuVN`&FwG*fK+3`4&Z@ABvADSvfh*tAb6a)D~-RIsKCv_}a$GKf%!1LYNI7~l^ z8Am6|-cW7EWZJ(u{5r{b^1x$3n-6a!79d69^f02z3n#6Tfv@+j)7e zit!oZ(r#yD%7@g-ZFjWU@K&S>)ibKUPOkWW}1^&#QibR4E1#f+m9 zWpAi9IB!)P$=pL(?s}+G8}SnBinA71?=uGU(xxlKY4uhyx~SxV&P*W9r+44##YW*x zFU2amfxO#sbJu(xlSF0!Vo<8#RKQ`Tpc1b5L3VBCrKkk*&(FH$dBX0@=XIYx&Ym?k zpfV2ol~kfkZ;lQUB6@l8-Io?!`!zc)xL4?MT{=OWR?4L6qD%rhGvAciW6||+s9mKN z9V?F6+v@wdQ8>!rRKQ`TpbV~W}U6Re^;yO ztvBK@Q&6TNk}Y$L! z(+T3VdKq}MRV!sYP?q`jG8xZXG!V8+c9@#(+Ng$i&yG0CltdZds1#cEdS)%x)ympC zd!84FaTuO5xcf<zq*&6U#a74BM&-1-T7Bcv2k;ZU!2tr$#Cmzevj502(NyN$!} zlu3rtLxHlQaYiX*rVLATQ0i%KHW;Wu*3ytofQX*ev+ieZav+l%3$WX3*-DJkXmPv{KBV5!sfK)Ak&9KA2o> z?6p{jW{J7pWJ!4?D8|UKn_hHv8Sf&P9lNDipIN~;%oG%>gk-D!zH*fvu3awo>(*$N zBEY2;m{Oa0DX)a1CJr+N#csG>}Vx0W^ZWqee zKqeH$aH`=jQ&0>?3y@u#c`1s4{QDlP8hqP+>$^{O#irk8_wd7Ezmj5P*)bL)`EgT} z+H?YawNmCzMIB!0l_3pZN0;c7;?mnY1)m1Y9y;duJ{)CW2k@Z&Q+iC2JTB+zd^;xg z#oNI+3{RP&B=e}81B|-<2pS2mHSUMm8DE@s-@pHCPJ{1Pz=Yb&OHl^ozfzRVwUNIZ zdox_V;KmF4RyYh#nZng+K9YaINY86><(soz%ZBgV|7_uKT{=OWVU%H_vdFiWVYPbF z^^x6i+tQDGx7;mW&z&k*5QFkEWs!M14Z4^y)Y&$C!EWo_uZG{=kHhq%OpsA21O0~y zo2!=g8M@Fe!NPa%w|!+LAbVbv0r{8Cjmv&xzxqwLw5**z*G_S8n0}Nou1-K1%b8J` z;S!rJA*X64j-BYyPM1y)r=+SPieIJ8HWWDb`{E_aQIXNM!db-Qkh-)~?ltbqI z(rNvY_jYX;T@DqeJKed$z+rgG(7U3>xz7ZYfRKSchTJ;?`R~5y7BkZ&BU{z_&&X1rNjsny z2aMoyT~w3Rv~!7{S}Ppuy^d8{`_N_b?V|_0XmcUky~qIP%`?U?`C3V;DH^!^Fgintwq4uHN<~QXM3V;sj6E-3w90;;;aX zOw>9R(kln4OI<*MF6nB1d6fGbp8@TP&W|!LUkzl3cq$G2rU#Ipz6uYA5li#PlYi=j zE2msnC=mBR@c*n{MA_@3Q_#(D^Cq%7Q=U%Wxi{s?$?~8R9TRAX`ctREc{-80ls>Za zzS-`Y;JB^b<$jjyH_h9Y1+vqz4OE8c`={)M;|r)u)N81c2C4% zrf7U3kOe&*cJ+Me9`3qoUWb3~ZFLw6M$LQN7enWFIl zoi?uGmmkqbWWUC>*`VjW4#O;_UOKgz)Olhb;8lQ_ue!K4O z%M-4?b6uYKVb%j%PrY@bFRBEc=$I)QAK*KEF{-}hwB&e9nX=At&*xN(S=_1_w<_pF z$9`qw115zKg+5n{^;&H%J?Wg3`D1doDO1w`hj=Ot{H6zx-)GC&LF*j@hfMb9zE0L= z!89E9|BVu1Ija5pUlTWRl3+gkCJcWWO@xgKK{FUocMg=&;w zIY{=nhDvYcot^`QhoUbp^QeczOwlMsqcS$6Q3Clr+IZe(NEWp3SR!`3UwAxQcgXi^_ymPRC)UXq2WQ+2eO!sP@buF8YXYcZ#KB>|=d(YLdCC zcuxmGZN=8GP38VIHv^sM*#9?5U`_R)?0=zA3evTH(!-EO$!Yne>gSz0)_gMGK4Qt+ z%KzX-N^sx(-DA6V7aVJL823WFY~z6L=W&=R8l_lN!iF?TAb+vf%ZAO7uW^c=vVQA{ z=e)}}%oL3h=wwKv1oC&d7}e{uqol=gTkeETOUxeQFjF*2LZnlhqR8YSGi7`=6phJ6opzbmVm@Gjm;5E)A7M8izcC@n+^+=q)`I-LsxH&Iv_hWd%)H=>zr0kT#Um^ z(I{mgow^4(Vjm7OMWX~d z;hq*mBI_I}f&6p*`n&MmUWj8=jUsC$SDc8$OwlMUN3!>p_ys6k_l@qBHawoSz`hQG z^eU&d&s47Q?iY@&vgtbEig~yT=tRf3TQ#PR~P$ktyGkaF{9D9neYX z6(t(r%5?tR=uL#fz<$}FfId0}2Kjq>$jfw2Te&5&t;O2$pc5T4MZ41m$=`PN;;I%7 z0peEs?2;@P)d&})k50YUxAZ%1xA8<|&r);ty56+_o#>b;+8xko^uuw*I!LQkyHk&y zxKFuWWZfZV396$KJsWcI=i6?U&Ae854TR zt1QS)$Nsn5mlLRq&jeGU@SoLmC@%jC=2lr`uYG<{Adk!R3|Ukw$%^vBTD^UOu9tzw zpgTDUqdN_JC3A80432R91(EuGsj_Ma^g$9WCd--nuBZR zteH~%oK`MS#}6WFGE>G!l#u?4csLj0sWkAL9zgzW*NR*^Eq8C+J|lB{+oP@`9M%9C zl?p#~Vv||t(n<4jxgx0Zb$sX2DHA2EyU*8ir^DGR75a9FiEF|d2j{{CG%o^}W&rtD zh0bes&V^}F>9zT$lqS!g;xNrT)H)UN@--iHQTv$_%O8~s|3YBR{ zH9quI=-g9QxBXH6(A13iUTXwj1+8_TgD#dbW)V4m(8YhrWNB zvT&*~b*a2e337_QIo+EqJuzZ~aK?rT8$Sqf7`!ft3ToL4$pul@(MR^#2V1PNcUu=; zPqlLK&R+gMKz2Iz5G#9uDGUybMLaITq9o3}QMmwJ_e4g|S1(*Tm3PRF-@sa2U9Vmm z=rC%K{}F%pQYAAcq)xs%Hz*i~t-$I2-&HKq3D|1XN{=WTvq+?vG3#K zrk|R(6U2acDh>Rm2atcrg1es4QeNZlcV;Z*u8J&$!)j`rs5V-`+&@mNTspxEn`V_S z(J;bg+r>u5)+DbE?vdvk=Ri!5zxf@Xy0_hGey=va>%`@PY#9!-GJ#Gb(KRP+yOmT@ zxn7Zd@zK1s?ru8Y!9|G(@_Vn`<50w5RRgDEYv!GvFro<#t52PPzJFCYbw$@Qw47Ft zxo+>`{Pn_wr`6I+Y_@9$I?=IzOrTQ;x~9#B@tz(o3wL*Fdo6`gb|2BHL*nIGpMH2- z9Ez2hU3%x5HLJn#5%)kRI%aJGow}oI8d^?l|0IRd!Tm}6fVio1BfM{ePIRn+33Td) zt~u|{uwF0hnjiI_@?x`SUMszQghCo{_q=0h&muJ}7n?VdR|TEuSVI%&=V+*>8j7to205w}}@u};0v_0ldCZ@k@M*W5bBfKGI*E~yWE{i)0~so!fhl1=;Bslgbc%{|>S@B6>qVZ;Q!D`657JTo^}2EFizBH$5<7NFabbt1s(oflI~`LaLFh^e+o{%S#a0M)uOe&Mexk|A_#ODb(ToI2^ z1|@R!3t)N#hWLg01?HH?tiZ3f0K2oAGT}eGJy3m&4v9dJi!>L*4nczwCcb{ID8GH* zjs|<)n0J^9sUV(81Hb73%)q@o^&D5aD74-EzUj%e2dCq(M`R`h8DN<0%yA3!Q8D1K zlUMKnRjB46aTWR$K&GKn0F=z?+5~_$#Q--R<-ZS#LjW378Cab`WVAz5haOpO-u^Lt+dJ+895f-cfghLvrikJs zE#|mJ`>i-tY3k5~ZL4wEUrPJYr0ohod!3%1WeDw0zm(1x=X9|C!kygo&k?oRnuMZw zQWFXOD(%VP&-NbGE=Aae%SJ3;io+-c32G3^TA@Q3SH@*YqynBm$&vB6JcUTg<%%R? zxkMlqOJtlJPwzF{0t_bNLdb zNGX*{1T3kT&z7(_Vj-9P%RT*OBvg`JyM&vqj=Sxi)`~s6=`c2kY==Ip_woLzvf5jb zZl55yxBDqP4x1?oVXfKqD zd3*_?Jy*e(a|B8upT|~k#Bv!A)ds0j&ZveGxd;0VK;3$KRUlIq7#Qs17vL4Dg6U?I z5xsZsZ`}?17gqv7@&Te*e@?P&bEu~ zkQQHe$c2qK?2jh9lGIx305+U7(SKI)z`M+}j&8q`XHjI!B7ei26a-@AgTB8JztErW z%SwRx23j|v}$L>BnIn(#5e3t8F z%f70TC2<&~FQEl2BIxYiZ=lLMRPGlNG}vnd^z1_zaPy;Ms8^_;x2r0|SK=KS7~Jyb zZ&{#!P+)*6Ae2#6osJ0!QGKCeAbT_VQ1F~lYl}0w#KlP-XNR54P%Lc7nS1`p*e}Fo z;nHxRCEzy4#$iUNE%|zj9!}g`gMHABzT-HY1j=etm_8?gtstP1zEj)v6W`>r}>Jl!d^)>PZW;H>AC&oUa+R62QH*HR0DHg57Go-y4yb zw#@wH8Mr=Nl)Nzf{7(S+U(|9aUCy?b)1Gr9ZjFEW?ja5{LM5O)lv)PL5^5li1GOz7 zoi@b)r<2|ACIjA0sI?|okQz~X6uimU_f-e4Q;}u~WLfH6=@!2H_eb`zvXZ5ix2#wT zdkm*!1rt&QQV(Ss=_IwTB2zlWZdjWB=2`zrIE>O4&Shw8GAvPCPD9bjYd{F2IQmH( zz&U2~N%1wMAR&m?e_2pYYO;D2C4a#RDBLz1PY{mVW&;Kmxa~SXqFhp;->s58dh-QXzFBG{_@f~x5Qlu>N&+x>S1WP@V56sFfD!yAr4 zq)o??-+FU6p!3ZpSDcS#4S7{^bH|l;#ulLA=!>qcwNDm=Op*TzCaThXu+2w@4fm_1 zmDqOnvL>~u3dTfNt_cJH7qhm&>4wOOFGUTPYIw5(WwkrJArWoMHqkT~?ZIs(kOi!Fo&5URf_qtcZ_1auHj_Ih_3oir5L78yp-ffRN_coH zFZz}3x_{yItf|Lw7-bLWM|JoQ*_%b5s6D{>`NH=jdaZ0M?hyki z;Y8fYR4yR@hV9)vySkUy5yyy}+w$Up@;K~|Ci^eyFD)Yt{h!IweWi5J^$seEeABgf zg^T-kI8+!jaOL(5Y1eLHN6z(;I7L=psXxPhSJB$G=O#0b%yq+IziT&$qAeF0Xm$T_ z+XLJimpIeu>;j*`ipD@+h^NxPZ+ZY->06WIFe6agxZN74*!AoKe(>x!xh!S9Ng4ip z0Nj_>sW9EYn{-*kzHA-cex@N)sHri1#~hS3Y}RyNcJzUL753rW^FOG(ySVvP>tWxr z_V&Y*wz?h(zKFx{%OYfKzCy}TNO?*ziznhsP+fe9nHj9G|EdLh19zjzjEluO8$;dj*Obsag(6QgAPd=4551Q z4G>0ufDDIG76L1&hgoKY|A1Q$bUoFu8CSqe8VRGu#j|L`4$8G-PWDb?54w6hx2aiF#*q|v4r;Ph^d;e@v(#mP6}8>KF@ zohj>5@m#Tv+e3eR8C(Fuzsk}<_*ZD!FM%vzy$RoAV&KQR?p?QcTH1R;)9PGn&4Qpx zsUgaA;DlFwdP%Cx4BWI~QLU&$@i>gK5Ex2bKxVM{83fIoa}e^c)(A4b82V;4XA#fm z!#5R(OOTl}Mj$l2so1@`OL5od^X#J+MaFK2gb+`qf#381db}L`;KmZWuEVOY-M5sT zT`UHN{iURDM%pXir1!hrOFY?qa(uPN+_dHI<2o0B^r<@6NTZQ)zDYmM&g^5V!{LYv zY46AXXcyF7lYtcJ8zEv$nEakoMd|bO&7j@skJ8OI;V{ZVV5py@r_a^odrK!ePjiu- zhhnQfSRc!Am>BiobLSmFd-mDD33-tn=t1}LIP5Pa zJ>|plP5NKuqIeUYq6C$g00-C}ptN?ITC2D{Xt2_gpF%i}Q0Lb*v_cwV0BdI8~a zUS5UphW;s)>HR@By7$Lne{@AKd}%@{upbHqn4l?-?oTI@ z+5BgnP6B%MK>``6_Y{1}=YV0I9H%d;cYa+$^@E+>;CS2|W!h!l^b?n5uN^GQjGLBq zyk9#UMkz>WNeE(v4h1aqv^s~+&>>I8ld$-52@fqi5W@qEBDR3X7YR8c8Al=# z3K->4BB@u1is_;nsv2DAZ)qR|Lzjd*P}439Tk*=_V5Ez{ccROrXZ{GvljWef^|+dj zgB%jCDT?;kJ4!t5Fb?}mSx!BzFRJksIC_f<52<=O5xUv6>fwP@eqEAy`(xe|e6 zIqY6Re+dZ=qZ9#_?E0%G@zx>hkG$a)6 zB_x0w@)8m-1^p!?IP8z6z2OTGsDW9&d+|mby7tvIQ}2Q1G!jr5LeRVSb9&*B;VF*Q zhHSeMv|HFJ#12<)pdU^jy5ca(LLk7e9=gJ-WDOa*f*$mtD-JUP>8U9vFb@$lZB1di zzSTB`L{QLVVdpvrF#0`N!+Y#0+K%s@bz~L>CvIss*5hUN?y#0pbqzYu>_Xh&~fmA@AQ-V4z&Xs}6hRrSz;v@4cUY&fkeR*@?|oGj3wc-Q2UQw%ETii1^W|h4 zG6C>6&(&6eC{g>8hZcNya~m|WZuzvc5?^$eHYY&2(TPtAMJ37gjpGXr+n|xj-&6KV zRMbMbNW??$TI36r9Elt)vlgPVSBm)pAzMzAJ-kZ#mz8}my3~smnOi&^W$i^3ukYfy zR@g#ZAN?_;>|65xz4XeV|1!y~W69ec*RO&+=$H{2Khq884e#+$vy%Dl@fmU6mZ_`9 z2fg!r_xNmvIX4NmJ2n1@ZOI8+U-}i*^hi|W!bKU==WTHqWg#G-x_45DYpl@{TOy1> ze{u7+BN5(vNyos;5+Bd;=k8ByeI%7wusRgsu2KF|-ntH2V}ESnT(RXsLRIi-@X;1P zXZn0D4l_app-it9MYCMgppFBz{UMDu#Q-;6?{Ft6PGR*9_o4Pb-~6swvj!)~$)n+- z9}e3sDp|eLv?J9@@{k=Q-qxkB*oCZbQ`J4C_S-K$IE+$|&=YLOutFcHOeWxqxl*1; zBxH#MT&Yy4WO2nJHiyj@aM64hbSz|H!NKTNM9fZTUN?k^-rLocY$oWh>Iyc>dsjd< zs&;@T&2EkDE^%>?&DwNm`n*;}Yd}2Us&9QCjhFmeGBkGVvSl$otthN5yf(zOu?2a zBqFJpBb9LkY_?{95r&!&G)bC+kbkvCVaV_j=YtD3I&JzK>);yx&)SswR1rd9<+s4;UIFr;W9ifd(Dz?b;AnOL zb^ev8YV(u=j#41yv-lFRgv}GNrRXQ0DDdutT?*bA(l9S^n5&%!#E^oG85y#-o6Gak z5#OpVA2{`hC*(oLjL@n1|6V^TpT1B?8bObJ31W0TXx10C^ZD)-ovC--vxw`e`^{d8 z)~I;VLp0kJs_V%|BR zV%SFzaC=eWFv>z;Ep-7E+_M8&bncZ2`?=8f?F1R11j$l_pZ^J<1AW+v!~ST(%Sg5J zPk3Sx06Mz>!&as)2Mq(UeDl?RLA^c`9dGVxw;*dx{d1=sG#v-!RfMQq_myjLQs(3w zu%*3tecKI|);Nq(kgyOz6f1Nnl(ASsIZwi4@dbR;Z(+;jQlVHP76`d4p_rp!z-)Vm zKrf#VrqVCKFT_{nlaoOo;;R6I6tuXU(cf!uh>G#^h|DvmJ`pk^E|7-5%z+|Q& zx2{1C`mJjmW(3kx4v6HD4p*Q~k^4YxQ-G1&*xC#@y<20rmk)#NP$+yL8a$h9B0KyaQY4!IE+$|(2`Kr3LVNga*$(JBH9Z+;?F8V@lP%{qJXO^RYOFeY(Z`UTGQa@zoicFPA5Hc@dx)xY z?OnJbLsY4BedF^^HA;jxaGusfpx=qbVKpfRA_A%#+d>?oQau7#_kz0< z8-nmMTSII+xu!l9MP8hkw%k{*=O;lo`p^}J8KELjDj-R7f~Nf`OxL&C&X5S~uTci- z^8llFY7DOkR6o^}J$apvk|h{2_Wi++Im41;Y^wLWWk773L=2}tq* zp7VlWP2xGfH2&VL_r)f=dzN$3pqF+w>5)M=N8c8mY(3!BhN}ICxUcSV&Stp z)E&5@X(kRcLTxebhGD0X7ME^?`dE&7=9%f6^X}eeT+L{Q1mE_Cc|49nD3mM39Dz{IlA=FSi3|;%bKVwh;(g;Ikf5hao5hb* zH2XZFTF><2ZF{+a8lVNC3H-nWFhi@%vH_D_+c*Eb&~i_UqBTQsm=UVNpEy}GnzUVE zQNFJsln;7$tj!Hac^i&%-KYt*=EUJBZ-)f$`EkPhs&=>CvVDha$YlL{1BX!x64W4+ zwL*syj#MNQaACekhM2At^Mq*2cnNxMx=bo(%LKp03(_Nypk7Z8+}-NZFstG5`tu)* zPlPGcJSh)mIKSu2r&CG}XGGAknXPI^zQSRDH02HNE5R#Y#}Q0mFcy&C>Lm}=et5u$FI7Rw_IH_<Yi-P~r+iY?gwhkfPVPh-GMbGv~J$9z-K%JZ(2-{6DT; zhj+OBdPUVq;@99)!MDOkTL3fAhX**!2vxy!!vn(`4&(HdSfzFJl{`=hB#=d<_sc0N z2{zVxD!uJnx|VJ97jcCc9P8yMQ|k}QYa}b%U;gYiH>UKqfifKSyZ4pg-O`5il|a|; zs&eVgmCnA&wK}YuWIyU14l@F^joVi$iUcocU&-)EAZox^fDy4yFAtBM=9}*UQ#UuW zP+rLx-+JVX1{)JUCXp2e+!{4DP$10zz`t%Con1b#Dl-?%_j=a`hfxZ`xjDYk3LWs+ zLOxF-LT@n;$+$8uUnmp{(K1k}Qo&(ML~QYIF(L*pukx!&z;SHG(sG;+>oS(?&kO#}i zg#Q^jGttf^iP|FVP(;3~M+wo3TkBL$9XC{3do^Hl^l@DEP@;?-dxmEHC=wuDaJ0+_ z)`42RaoF$P9F#Wma3TWkf zsv({JQ={hm_$>dhH#RwQT6yogwm81qqpQAqz5hrx=eeQ?HFlF5ttGYTZ zE3wD&J}3ZM5SqXbOaLGCekx9qAGx%cSItuZ)^Qjnkq zQN~v2kR#!E*mW+m5caFB}XI?OT|L;mM`>rM{=KFui;FOz!1MszrY;xn9<+b z5P-DH#W_t$b48FpfL*MnO!!YUrqnT&mdK4{A_FM@Cd%15Uh<$$aM`01i+K$o8eWK} z(oiRAeuEiy2|mv0sCZ$vN98zagnwWO9QH?3-tg6Pwa8BNSki`i4@B#*15cUT-}5gu zVDhR@&3Bm7s#|hZv+9FRKAxhEPt3m2Z4-7-b#DlM-3jgWO@UDQ-$D!a;DGt z;IQAlix2&ILuPzHSNe<(4l@GpjoZavgcKgT$$RWJhcnNc?@{d->RpO(q`(yT-~zoq z81DQBk(bD~^AG5Jv&j|bqgg{5WY|9n@N6(2U&Q*|+(eF3h^)yv658kSOJS_a8NJ7-b@qwKOfW+mJ0Ko3Y1urUwYFrEGQ7s_ zRo5-IY{p?ms1B3|g3A&iFV(4Z)VJEI0Dw|B#Q>wz-tcDN7vB_)LH%5W`ahMTmi*auX zXMnBYY(?qncI20ZvzBr^{)^I z0n9+ZDU8F6P!&u!KV*1+i5d##yT4?_!7@YFJ%l@`4D;QZv>1A&^7Z0zZt;Od&zG58 z(Hd80+z>H*tIl2=8u?JZa`M;;HLA~N<1orXKqhs|UdV&xgXmhWZ3GI-C}0CWMr#apIqLdgez2U zopqV+rPVfU{!UfP{3a@fZQ)kO%7R`(AINPguG!8RDWuRJJwHTVV zR)abY)Ha1Q+7tuac%-jF3Y~A#*Z*v>{HUArvJ9_*^GECu`V@fleP8HU5baUafL0&TnmBmcF$<;-p_o&4QpxsRJ_P{V`$l?IqSRpGPLF8*(@HAr7M~1ZAQwpkGA# z6m-oe6YKBJva8y1pS;$pH;I$(gB;qp0dWvOkJEKsQvIE>ev}wJYtO45Q!H@UUrKsv zDm&k#&;Mk<);XPhhAe=1-?Y5j_>JcrV-H@txI%e;h9<9J{v1L_RQ8RPC*_WAqLq#h ztIWxMadj{bgB7+^Q1cpXEu4dC=1ip`zO_c=O7-&xku`Oxw+KI8)tVWp=&;sv+Oj!y zCOjJnNg?E0AadEFJwheGtMXGY64AeTA6|PP%(Y30%mvW4> zdlVSaz5cJW)uXVp06Wm*V?lR`?%&em~>wp$?Y%^p;20{xL^rM3+6m0@G6zzZ#>Z@W7 z^%@+eVg~jne+2t^^&6~e%JlXMV1}XHf&BtPLRDTqkid%>q6+c~_6k)o?Ny=7fIuG= zqtNd}QPS&U5zc`0{V`J(yCrl{cFy!!vI#6g$Nt~<5*F2al}-MAuhzxKu>4-DV>ajo z4c}I;=`^_2HA&3sq{<@}FIcJRB`L?;36UV+&9fTsogS6;Sgc4t6+HDD4l|WwKGv$d zSAw)^cwJ`eWU#Ype1wa59jeS2>@RiLH4PmhHmo9#8SDB_KV^vr zOYExF?p}ZqqQ@&8BgAk+deVa*uj^6Wt>qGP&-?RcBoE=>9Cl|!g7>?Xj$PgAd9B{M zeY_-f>`WYH3Wt3RRrN{3BZFSKR9iK!)ZCe(gA0h+86+~{0>BmE0?7Z&t!(=$u2!er zLL6egG@H@{hnd1*%aOnX8kf6ZV>jS(tHXW6FMpiY5p>W;r}^?d!@9Yx@qIk;PC~Ul zXB&Y|bc|v$<;5R*h`~!Cl2tV#tquKiQZN}Tytk@Wb6~3D;9Q#oE>SKpZJ9!xsocD-_Hv78% z$Ln35UNvWn?xE`<2caRG#O?9iDagI&BR3lYUU5d^u2KJz1 zf3#C3?k*u?M1VDLLF@a&s1241(BWl%(cx3WOBvu(E$aO{can>xS;mgKi(5|rm}_Hi z%BOlFRUP}>w#k-v3(Yt-de(+b?qN906h8GmDuPnS6X%&JYV?aT0oKoEe#en+1QavqUC+8!<6ux1;t!-`6SMpnaN6yXS#f&&KtqzNuF|I$G_Xpb_N5`F-^xyWJ(x7DdX@J5+T~)Mxf-e&^s;AdmcG535&~- z2-$4D6lVaVPfPz^#uQcy-+SK9=JZL6+L7xPSK)&(>6j6`w&_+pMUvFYzt^VTlAiCb zv=QGU&(P)e_gNU=_B{m5dpyV6p-FA#&sn!?_jb*G6y^52A`)C#S$W18SH{vvo3!1Q z&SRJ0FjKkxRxeoP4tm{@P*)GZ&}hI$PR^kJL9OtO7(Bbi!wT9++5mp+ODJm^ubwQb@agva>n9_O>>*eW=we~ zOG-ah=hha@f}or+&N<*PQ#fNFDBY<-DQV*b#6bZ0Lx;6K_E5TIou5;O6?M|yPQYQN zaK@fUz7|!MHoRdsvi90t#kTv*`xF8)>!VYrPxU?~yO|HWcCzkF)}YV^pc5UVm<)OT ztVn&}CkmPj$U(@zS|iAKqjj-CX3J6$9Xr@fUAkpXl}Sykjvl~ah3}MqFPj`X*(4%V z;r66}o zRmsL%!2nGZFE!m5j_ugcemyvFSh38N53vOM0AHOZ+q1^ ze9-f`B9@dV5pR$DsAC`I-VpdH*LVu4J=N81|l*-8;# zrz!qNojX`>)q~Aeos*9^&R+WXSgV85F*ximb?#J$sQ}JBLD#H^hapSx+I0IoCMmeI z-K1tV+im-9z}}hciOQAUbH`z(aPGH}KQN@{4)W6*1srAy=iUp+W=PK+t&r?VQEFp`}W%Gr)daFcE1@2*@JL?QF$0!|l zP@CRy$6Q#@jfQmGL4JBC9fwgwBy2+%$qF5cQKud4DWc#h6iS(hCFUvxVgXw! z<+Io9`Aw&~XQ~=^b|*hWG6vE|10MD`Y&GKrUhP#Y!cY%~gnC zGcA@#jJ8?PHHP^gb?#t2ddD4y{n5_d@WmQqZ$u3G? zC?z*EeYIP>JnjQ=^D`RHD<{N%G0haF`JsbCFyZMnCc@bb9)qd_pnW6a(CN3sopO zk0ouW_x(yEI_AE*9J4`>vp08qP$Ig)MM=ujI!{BBCCxPpg1VX72Wd=yoE?Xm$}t=A zI6KHsf1DkM{Yj1)9M>L#6szkqX-lk=2G_fes9LoE?{vL-7+6OP+ z9Pna(Df>CkBND=oC9l9?f3(Av0ZUQH|1xiC=CJ_NBthuHTJLW%4VeP}(mbJ25pj3v zR)yDvhCc4O-qlU{+rFq==~Li1%oP6i4zkG5mfN^W+nMf(C;ie|xUQ;*AgygM#6bZ0 z>C-DX%oP6C3(0246gbFFp905W6cGtSpmTDjz|p>X5-~?0;)xXK5fu))+sQ#Yu!;mc z9$L2{<%)F8`w}@7c$NgFzeAsJH#8aT#no6{GMZ%M# zfEXRQUN;d z@Dg;b&K%1){K2Vf(t+c4 zJa&)WRJ=ypC)cimr$Hj?bnYNOy-~nnrf}}wNH#+{?jS$C1tJIGJ(xZ^O2h=g$n zBUzzC30h;V5DPgxwm>0~vqVxcU&ukrHTWF4R3hc+?yVA8{YD*kP@CRy$6yWwkBY>66Rz_a{D z+*ilrjgFO#&~zjal|3KNn`XQ*tN7V2-an+9Tf&SQp9kPt2OpHF{mhBwk4ld`ALv;( z;daoCWE@tMyf_%@=dCw064lI^G-b}0)`(oGe*Pe`rY=<#9jpqS*X*1N)1uOA^GzvD zoD-DM_^qvzvsQqg9fVC}gm?>I^HAu`p(>snSX+L&i)$P}3 zehu_;2Fdl&X=#PtS5MeI58Bv1V|@Ar+clsQ9ix~GdHyV?0{eEOObvs)Bj>#q?RJ^j zrMYjN4RyOdK90jQ-8!Me|EN<2-S5=hKWw}Gqh3obJM4TmEom4IGlEk_?jv_d0>b4Z z{Nxfk3C_ix518@Rtx#0X_qr7$I^|co_I>JWh*QqY8b14obF+cd%dK8NJl@AbvmmJZ zs48U0Igwi)WhuQ^S6|DYlel^y6Nj0?DQBWGuGwtOv}=xI`Yns=y|eEPuSN*c$_a>r z0P^pCaC2;svVG!_+FK)AMh3OOVWx1(ACY|C($3$duG!B#Ke#095be1LG6SFCqb-2^ zO)Y9>On0x)YSxQ@Ev-g%8id0rCPO|yD^lS)WlHY-=$g&uFr7W*Ta>JJ85`31ueRy~#av~@$DD(;rq;TIkGJc6&+ z%Pqhr*6!sGTDx^_I-=OA$P$}6ZpUGNloQuC;HW}_!&D4-B?v^E zLmvq0h&$*9HsY?fh%9XpH?>8;dz!J=xS}lrCXTUZz@Qo%0qzbP@mO2LWo;4ger;@4 z_q0V+LlIzl0h~q#C+YxwgI|Goun-j*06+#C^bMzK#xv1xNU{ojAfSbr43FSIZ&gT$ zU%&u{=IKpPl%7c&>z}l){z;qapR@)_3aV0Sl|;uKgS>_XsDg>{zP7lUI?nq?M_dCP zan?HG>g$NBN5;)2iyNM?@d)cT*w4F#dypzX9_%+%)hW=`E2z0Iqjo;h!lpZrr9Szh zWdETQJmjJo@{?C#rp1*t$O+f{6XKw5X;w|mx(9kdytb-O#Z!9fsK$R}Hei#Svx!!4&Xx^^16h{VmOz$-cI7}e>ByObA2}Qx@kl;$ z&N*i|GTZ?N9B}0HexL3s?d)nLkIuWFd+)z;d1iX5ySl5ZtE#JeX6`#;y9<8!?YG}% zE*k`^EEBljiu(U=Egx>%W5lKJ%zJ*V^FMiWhb`Au+D`ZFGx(=bAFS}NBZI#lvj2A7 zms8r&zuRo)krQjKdFzD@u6p^APgdVvY299`IPdO>-LDw2V%IaCJ$!Lhccp#M@73#9 zpLpyRw;b}!HJ6O}WzZ^0+co|3Gl!L3U;6fXr=Fhbve|}PEA6w|>p%Fo`g-3> zhTk!w*EULkK0``}4jwq5Waz-*eMa;f zSUS9a|MCF?`wlG~Dir^lqYT3*1;N?6e0Nw7Z1i3b(BS=pM6gJ3s$idQ_PzO-5%>N1 z=r2a!@Z^VgeZI%ky?^dKdeN87%O8Kz?{4_rIw~Td94Zj!_x!DIRf2by%0BttRkN~) z>A%r3is}-)b91*QbwSXjOVInK#5%j`w0CJ$bA44sV`F`)_r!+g#;Tg}RZSz44aw%J zbYpYxlKPfpQ*&KII@P;mQe{a?U42bm!<^Rp!HkFZ`)x>PiiB+3E~>1evZ6VeOoffF zYitPKoILUK^8X}fuRMjlzQ>9y_Mx!yhBBPb?SlE4w#ZmHMTTYCsVzrrmGri zs+!eN)y<8m;Q#Izf75Q{8(B3s>AMq@bX|3CSJk@e@m1+$b6u5scw}>9OG8cX@uMq8 zHdm!mm8C7|bh4&$hDr;X&;RJ!y>&oG& zrrN6dbnyPEeTGyQiO7s(eSPEnR#Nk>Sby;7r6Hvz(9YHZd#`@rH#@~FaB5vma(-3) ze(=H0EBg!%Cf_lp8`>sMXN7$>b$sQBy5{7ln&zs8bnw*&k3ZI9N%-UH=G3N38W;2n zemv~LH#Y=*YISp6Q#vzz)!j|C!N+eLRJKOswj2Awb!$v~WZm3UrxAj>{$2jLUi4OD zb8_0mS^Fld)4}(nd+yRTa?i`FCoB<|maeO>OV=e+!5><#`gP4HqLc67=-rMQy-6f_ z(!z9YV}s8>slG*HAZWV0cd$_eWolXjFsGP2(;AwSRrTdH z!4AuvwGuk7PjJfIyLxceH|Wvy>TYPizI}q_7i^z)r+tGPlM~i;r~QKcN-w(8o%Rpj z+~=V;-06VewKWcU-<=K&8rI$DNXqIL{5pNm7o7DEMvt9(3}*v^ahrT{J!b=hpH?{e z70w0)-MUmQ;B0Vk=FZD)!P$^to5QB8$=T50!t)2$ayC4;cW&7`SgYaH)h%-?Xxg)z z{dvI(E=5`(==sc+GuE-I(t3^EipHr;Rr4EylW%@`rM2viQYSSxN=c-GFUS1)Ib0uJ zt^5^@Wyw^!xp84ItNf8oR?8%hZ=9D55*tpNRb1-mhMMGp;O|#H+0XHTv`SG9W_)#jO)FMqX??P) zIXI-}UdasB$YeUW`tB|N=ql#&jZRIks;{f@MXpo5_>4<_7> z%#{QijlF6j-9BqLdb2E9pG;%ae*1EbPoY*)l}e6F&P&!$kX;ELTy*;0u)L%yU0pl1 z?to;l@2DTwUZ3oxRSgx5bLP}1r`M(GW-;m)1{1H_b{WuTp%q*!ui0u|B`ldWswy>c zUb4Aa8dBmDtg+WCtHY96qf@1g4XN~qmWJwJ=r@ZWqSKYwTEO~8|8Vf8J`F3AtQpbR zY;tHq_{_k=f1%yVXEe$iAYT)VT&vIP8)V-Sc~@oi!Luv&cT%Q|lUkaSt`e_4IPs`3 z$JAt664gS5Eywg{KX@PYHEUdQPF3~73CU!Q2473_oaEH~lJ!%Pvs1yz*ZzJ-$1`)H zg7t>>Umdw=wd$eBBx`(6Z+mW2Pse-9F|wtuCU|DWji*tO)?AaS(zU5^b+ekQnimFL z4(PoJ0@Hdo6^!lC_eRV>Ytqz(DGB%VWOIrhUX)&W`z$II3!9R`YHOeN_GZd7YkXBr za`H~2XRYO~ zKMv(J%L;_OPS)1?_LRL`Mf3QUm8HSeo2*+)#UM=x6B#z2@R^OH-}q3d^F&Gm8X-SNqE7300UA+7#;{*O(EIqu6;?KfSP zw6VEgSup#XK3CA7SyPhfmga_%g_0nZDo>y$IC1Ek^IauzM^Yo|8tPKDO1}8K+E?Ak znVPJht+A6%E=UKn-aY7sl__UxZR32#*Wx$-y|Yhfsdk3psEbE!%j9d;)cMI|Q*c8| zuZ`VEt&jp}YHUsi%dXgW3v}ZwOPN%=FjZHb3a)tQn#UPkrtl)3@DKG@ec*&}p|>|x zbApp5cK_MQ#lmzl_~gBl@1?FKx-gywA5G|aFRG|C_{;QXwt=HklhrNta#x+2k^Zhz zm4jOvZ`*q-f43gd!7fA$mDD#Za|1M}ef74hyX4|}>y?G~(=!`7+DrI55_vB+|bZ?89F;!XE zw+-r9gQwJ5kCLc#Rqhd-n0UBX2M9BQVVhn$x=U6GtzDT#so}iMx7ad@C&{a>N>|Fz z=wBA(dA{T1y`(h?=ValpT|4a6tR_2rbzWZV`#0a=?}KtGGOu!KH^2P4%XU#ZovZ0s zR*oINeeL5e(HtY{>XYRQ>Qd=c7T)<^E!#VbKV}Wa*QKgmMY8c9-~GC=Oa@vzSz;*L z?TmCD^xJ=UGPn3NYRGvVQyS-wXl|T~ZLgfzlGbIg%lccL)ibB~y!g@aw!+8NclM5E z8rzTI>8i7PV{?7Y#M!gu$W%IIGpa7FX>5z;fs1zDeeb>LCYIIzq1d%+^3Xc79!&lnN&`KnlVa<1&YI8Hl{yPeJGdz3yuYcY;TBULFzuVJK zr_`PF46~-zK6J==6x8DTs!q=mj&V}{!*L2LOX?e|nPq3S^RvC)Ts^Dzz;|9n2bu0W za`houwHaTvU(z+QF?%RKe85>RW{r9fD>Ow-&2DU-n^lpm5Bp(g`+>-sb18 z@?4fQkC$N7HPtUDF;EeO$7+DGOzXS=F22W0Y2DmQW>?S`(Bm^ZOTYZc61c%xRQ!_1z(7 zJhXZw!OdMx8nnl1IE02ZRbGyUPq5zFn?KFOtD5d{s1aLHnXq-q?E<%;1*0_Py5OO`K3x>Eh3ezw5WH&nXwkdCEInv;R8yUTsZiF!;<}>+sidt!41d zytBV?VvX7Dz%T}XT(rkqPUSU9&Z^Us8dHua6Ri4rCnBlQ4WSTLi1ESYJubb~k(8H_ zPPWc~Q^9pRpZx27%Orex9CV@6Q(;Y)A3 z#^&6RA9M6~AAXnj){LO=DuZ0uUnqno{T9I6{+2NeO2?sk6Fd}0WZHq z(>$yE)Uyx&kqLHdaURKO9mBa|#WnBA!Wmnank(aoS8O=rf4Jm9hH`5;9!G)VT0<$j za^Fw0>f=$oPiROtpR?at`H>|#8o)Y>w%a_5 zRx}!Ev}P{9$#mp3EX2iBCp6Y1gT?QCG|$O}?^Ff8Yf{x!O^Sy5z(UvlM}o8GMB37d_SZUcK6f zD9A9g7t*yJ{&#=WXpN?Tb5!TxyPwWE*|W+N3qryrBjc~XMR-TN|yUg%(5hz z*1WgDtEM;V?wuOFiAxMW%WI^*7p-~2AlKcE^BWWut!bTj54rsMJ7HH@ix$a5Ie6in zpL?T2%7aZeS$96ey}ZUp+?Q)yyf>C1yw-%=#aiB;e@Zz;hsjf`Ym;-UD#!Kl>_xV}__g*QuYW{lhOE0_JCO85==v-YqH&%1^uZgwiD@p+xiM_mgvN9vE$F{o`gBCPe4eV-#S7I(KWuTG zs~l-QY46JtUd~8ro%sfTzU1AjU7a;$4G#KbQI+d5fARCi2x`(#W`nx3KDdgJkZ*Du z{Ce}2<%DO#n;7bF-Yd5zcyRXtPdK*vqNdGCHqT+Xsj^LQF4%U7ZBf2qmMg$M-{L8D{%*>X9Rd@f#dW4Q}$4PJ6xMCLO^iPrtec{W`L7f})tNURS)d z+>Z_uS;}<5ukZcrTw}*T7aqUl@F(WAB4!wPQ~kcrBJK{SbkdJ*rEOI3%=u4W#~{tb zB91w}$!$s*9V|HP>PO+v=mv#>z2Z#=zpZ!iJ@mO-O{!?DkcA5FEn9aFM$hO5CrQEO zd(R$)l#OoC)FwFMh?$q+B#my68?A+?1ClurQ!VISw)S#=LL-iDaB_Wk>DLGN0-9RV z!9m9zb0pF;xrf#RUJR| z4xZfX-3742g)L9n|EFUZ2V7{)&<7QRl~(=B`3Ra)y4*@!>AR(9OBGTMhqd>n`6DQzeAlpiR(n{P?GG?zQF{G3Tg9!+W`*m|)tF zH4j5f$M(aTRJy>YxYVL0>WzQe=>=aOcZ<2D^HgoL1+N^r`nA5?R)p4j-<|cRCz0f^ zTsOGN7B*DPt*d4R8q8h&%0*q;zprfr-cdQc^7`FS_3e~XIcsVdnD5ar{OKJch>9$> zFjJbBlq=L&UFS|qKr7 zZ=a64YjtvK8}3%6^WU6Lwr%aq9+CXfw!gjJvfpo?$sf6;W=rjxysMYPokYQBw|;R7 zRw5+XCQD|iCKx_G_(zxaP|+%te&O_>HHOthIGbIh4}(;?rP2>BJoHz>L3wFM5G#F; z?Y8jCHM_Tu&Vp*CrWqmjJqM1wh0&g;@Yb%Kzs|@{Q7j>j?}XG*du|euPS5`FRSR03 z=a+WsdUIQZx`tMSZ_YjBk|=^Rz|zxGll!+2`3|nV?B>2$^^mT~w)1L&b6;3~I}B&e z%`if{WAeGrBa+2%Ws>LA$IO@h_^ww2ZrJ4L`rzKmUZ-Il!h%Q7uBc5ml;bF_H8Sxq zsw%uQwxKZ{JbP5ha*;Z^T}`945R9`P9Q9+*d6An_=htcZSxSxYS#aK$ zU%%#Zjy>*9_Qds;mwWY(+{>D;-cmFA3^xp1zGM`GZbA zfnvr<+horNQo(AQFY_!$n|sbMg)2_MtW~~w9vz+&gAS&i@adUwJ`!#Y&VBB0r_pfR zKNNABCR{Z1bBC^-XjRP$@X2JYSDG5(&@~rw8m2W69o%x=))%8I+le^`CtmdLddv}$ z>-Q5JamM+j7;Tqg-IEID9F*FY&S@3#{SUhSexK0TRMJ?pFsQiyvQ_XDoSb;)_mc_h zIxU__%6I|S@BPqWG$az(4(|N6;v}qJRt!7%`IfJ~@daDBI+(uYG9NHP^2Ze3`PZhe z;soff^Z6z&ICG&V)zoT-2cEHL5hK**-zM0aNFm|rV7VRFxfVmNaUX1YXpcSMlFmmZ z+0zy5xaDTA`XV!0;rLU=zl`S~ECuR<8*d-%R<-@54;J=(d)lrvWo~ti&FD9K@r7eu z>ynss=M#N9W&ag3Nv;VeY;n`g=&A7zYm&rLRXpV5gLgutd}4;RhunPIuC5{qHEWgj z+M)06hf+Y}W_-z3m+^^nAA5JZc5hc=cU3Ul}4?Z|-@#(JL!u52g zkb)_**LejMk#|#L*VisO&Q&V^cEpu-+Ug$cVD@gsoQ;H+H?Q@CYk$suz)PR{S3M$} zv&HZ8OKyC{^{D)|Zx%f_*7ayzL)fDgcfZo#^=L$mUp;u8`yC_e8tBmtSN?5Yh+>i0 zVD$y7Y>y(snRhYx);nF+-^7JB$2Zor)F-DTwR$d(!8w&p-Hxy7LM9egs-32&*LXHg zw+iVy*RJ%vt0j2jgb`dZXV*6zx!fh0;O`fXyxTD&atEKc$Lj}tgnKFfC>adhto#zh z2$^c7a`;y(jiL7@B9e=qyc>aapH_VWE(s_Jc% z+-JT1a2tAC-m_Lh-H5EJcdmRYIQ+873+U=_4`p)fX9+GF{g%q)*t32^qQc;g?LHg+ z#!a8NOl~PPc&G2*7dWi!9nnJ;U;Ya^cw!SVsj7O-8wh8$@_*Yk*K>AuVsoALR*p<+ z*+%A%V4E6t+yk{LlTvS#i%u5B*KBsExV?rGzZP_0ylGopuAe{(bB zWKvc2epL$ArA8jJJ|j82c4npS02iJ^3R6v0@+Q_vFFb}G3z1qC%lSL}DTz#Zh3BWy zzx&%|dm*kqO=6{;(#^q*A8qdfDsFtOee<*LBO8-&N`eWyy!sqtW>URKxh=dt7?BEo zKIN(v9a-*}u@%!lIC!N&tvTdE$giwN?WclM&pzla*x<_2GHa@~R7goCkI%& zes);c{{lKg@?x=*F(n847UeFU2IE)w=QfTxp@{lW&Kr%J--sqQk;{sR{Nw2Tw~c0D z{H221=P&PO+?K^zq2PDlpBz@vZNFqMvQ~zJ9edt&f-54r^CDR3^}B9mxaEu3SB>81 zD;N@4rVWNA7p8DyB5C15Y%qJJK6}uBe5Q*@|jy#CJihzb#vR3?n6U z#?MWi`7Dy+_bKoMgv>`$AViqbglzg2sLi*a$?m>$6c1Hmu7H@*aSGj}mMxazj%?dU3Q)J(5S z&iC6rf`cCYXIX3do{eJDTosfKDmOUsG2CD9T?2+U)Z`Dl1*@$4Lw81()9Aqy6E2-c zuT8DijIyFufr$n!0lQdgw~tp?46l3?J^1a8ZpbMv;bU}#iCz;NoT~xW=B*)8Sx}sLgq}nz*wVs`Lr+o6!T?j6L!LzFq&hJ#9;AE0m@dTG}4{z#un`VGY=6Hyduj z&U-%Fi%}15XoODt{@XXvJ(&e#r|b^B_>GHQ2M9CAKJ7L3FF(2ta1W>i(}&)03tB3( zS0HPHK`{C9hyL9q>wez71i`4kUcNnj=E{-oef8S%8Yd8G6#lC>ZGMfbX7i+!hpZ+gtAc6HI6=ImSB-cx&lD}mLfhqs!ym8)2DxECr|Yf;q$2vV!rj)=;& z_kH+0qnOpl*6?`n?a2d1BL*(DBG_U3ZQe%=xQyhTf6Ciyxw}ls)64+2Oq=T1pmN5HUU)eJ)2}#R(x>kgjBWM3bHtDA z``}?z%VZ%l%l!KIveiROXP$mNXobGvwUf<}J;tp9^TIIq<(n>7gSl(nSUs&z{mPCm z`-y^Mp6;_eSANx@>)v~9KqtE^wSpbgUbh8{r`(hv=DkO7&xpz2b2cMbX|DknGK^+a z%@002hu}y(cKK7nUtAU*4QKZd=V;-~3eVfaIZ8Omc5r5d z>GOs2a1IWQ;&+Wd1P2M{lknVV<-^$}r_T9sc8!6vTMV4xF>uOa;FQO}84&|#R1BO+ zF>t2Fz^RCVGc5+r^cXn1$H3Vm2F{EaID5vx*((Ol?_=QXy#$;CCG#yyz&SuT*DL{N zAvjAIJK(Grqnx8-;9Ri;oCTuw*%Iml&gVK8xdcAbu9-1#s$$^Gih=V>44hwM;QST?rx&J6zxMiKp4$HO63S^2jx&)R zl#>?D`#I&99khOg&yTv=Wa?u$){jE@&Ak^PLMtE6wmG!$!}!^FVO%`slUmzuI5u9u zc{~Tl?BGvfIyhgngJXK&BjNld2F}_!bv9bjaz0xE&WECP%MxgT^I;5}6=TraI0nvU zF>t<%f%E+maNbe7T9(kRw}tag44loEK#OwTS^~~n!WkL^XIKoJ9b@3^6a#1H7&xEA z!1;6uIB%%!tH!{2WC=L0shlmAfb)uQ1}~vc!5JC@M{jCzzg&H2V~}!ojDfS$5^!Et zIelW_^o@bDUksetOW+~(;Z-yI+G{&F%`tFNF>ul`aQ+wr=d2hw&&0raHU`dfF>qFF z$DW$}z{8$PzMpR*>KF41Lw(haLktj=c#sZ%$Eb_=^Py5y8LY3!5rinpVZo?R-Xl7 zTaFOUG3~U=a1IyFu}i>NB%I@xfOD8|j$Z=Kp~5*K2ZzuMKbtEtZ+g}zwYJOrmRrKS z+zv&)L!4z}ltaLWU#^ad(jw}^uOl2nQv5o?A@<3yBOGF;{5rxRBFC>IoHaa3hd2b^ z_;pkcv0#23;h1c8gk$~O5svk9M>ytFcZ6f(pd%cD?)*B!+0dhOh{JLOKP$(|wK>i_ z$@6m_r4`58`C%x}$h>=lPo$h&9O3{2a>h_ohh4Zf*oWCh8>>hWh4lfw1f7#k!@R~dOkv%NJlCqB6 zQ;}I^g7Bu&m?s%>O?ZNCxjR%aKVP4rV|X1M^U*QAX!#xqPx|V3YgqByZ(n*kuSVKJ zu?s^w=+mpi^X5AXPv_PMofpFM&F(5Zo!cUGb`AOVuOiU7JwnI$*885qwM)5G>8o+vz> zt@6-0qX2Z?kJxQUnB7L~o(*aCcyj66lS{|!Hgxt1{hjZgE<7Ex+t9f(oGeUvweWPz zZbN5M$hV*VSr|I^hkZn`9}4(EXBT&-=S#jQ44wNTbSyR>rE_e7=!DgFDrY4K=;!E! zlch(BK*#(L=rlQsL9qM^Y|x1R%cnw6-6v$Y85d=(bmQXo23Q{=$>ooIXJxYwc@ z){>9ywa0Qo=O_s1$ALKmzgLPt$NU}W%we*n-%2YLrhj~CK1O8z4s>clI*scVo{srD z(AhH7J1=Zrcsl0qK*#NR*74hZg{Ncw4s_hh7IfTVc;V@ozXP5B6Y%@Fyzq3)-+_+l zgEL1Io{oF6UNoR{rhwn_BMVQ*{3_@S3cV{(b;QiVcSFeHXogJ_gZ>7KjiR@7zp+OzI_(D zA5Y9G4jpzvLZ^-s{cf!-4joE`&c)&Q={mPKbPzM>*mUv!roz&pZ2HIKdiRiT$IdG( z9o8nGW9@l6l!JHN3np|k<}aTg5|uaBH}cWB=di-IhjAK}>leb}FF3k5baLf-{}YQt zC%1oIKeae?kh|#kx$UgN(m}sP`^U!Vp63>aPA=bmx}dOhSWBZlHcsCN$It73T6#L) zNAxwt?iQir9sy9=U#}_-9n>ds@E8U{zh7@C4jtBfpmT6o{3DBtL&wJHm7!fIyQ4UC zOx~^ti~sEI;?S{iYIM$gsIYV>Eh=wje|CPdICRVpIWM$xXFOXRI!qVgT{5K8=cVG% z!QMea^ADo>janmb=u_xC9yVjM ze-x)Zrr!pKeEa+7#i3(*XZw)O=I%o`F_|W`xO}5{_?8OgZS)VtX^-i*^}^!s{G~W_ zXp3u4$hT*gg>w8~T)q*uhR$=Lohx0rICR)c1Raxu^;Rn^9ZHMp>kmS{?Yeex=rC`f zJy(Www%o8dbZne%8`61l)56lB4N<=J4U7M#YjNn9{W&0PPj~lq6;&eUZ%J}(?Xmu; z4gH;qdKITVX6LLuEA=Z59kX*6g!=99!Ns9tcFx+! zZODk?&|xnibZ!gjoIR#Ebl4vUox?)8o;96B3?bj}XP&%k|)Lxe-ibJPcNawOpUynJr zICQoQ>GTiv&KDOHht5_Zo%h53>2_&x=xm+Cx8<)X4xR2H9rNF=x~@2MdW3XroQ`rY zuTo;nU)=e^HY$& z3m<<_SUR*L8V`9mq%-s%g{4C~pkr}=qx0LRg{4CrB-);j!f@q7UlfOqwa5IotG_J{ z9l8a%o)+r2$A2mg9rF`!3i-B00;=(UOR_)KKV}y`2Gls}BYbEDjyh2ez#J$&SULldBJ|D=7{gN(D^stUIzebaM5<{IP|l zLmWQeI6Y%hap>4MT{ZMW4%odobZlM5_5~cZXL0D*x{Ub;pX^f{I;MAKgmz)&n&Qy0 z^%CRTth(aRG5xktXty7kTO2y3-*yQ7kayhc&?WRSe@pUrZ2Xvh`#Geu+JfS=$Ml=6 zJFj$Tap;)d85YW0|09b-$NUh}2Xl`tEFI)IpMG0#LUHJrezScj`<9WRfVO)Ixuo=^42@lqob}X4jq%X z4MIBeZz>KQ({Hmw|KP-13QLD|?I_HyNg4|3k=rLB+ct{=smKQ~h)Eg{IJ+ z9{k+W)A=?+2R8A(Y@>5<$hXg4E)E@&H}ezseWN&ZOx~rZ;?P0Npt(^vUwB~k;?SXZ=yVO~yt!_1=$PH^7Sj1;qvFt^Er7*cw&+q=I?U&z z0p1NbT$q3+oYa_rNcZSO2^t$@4nxsn=yY&8mIVG zQ97rG{qx+QrEkwS5qk>X$|Lr)KZ;JjnjH&E2fpQ_bJosFPv_r}_AqAn4u<&$hlc*! z&_aHoCMpbj<#kU-jIm!qP#VMcZ>(*q-4NibE&2Js(Xi4jr?n z#<%G+3QGrj5apZEd3c|~(m}5C(HZ2v1EiZVfBE!IRIZIqZvR|fSJ?Jof1>T#FO;_p z8VgGY`;(8(qI6;Dpx^S*`RBso(8-nS-49)QI$uTf8*;#RfJ~1zg!bo=Ba1`F)jWuV-gYClIRfUjncV<0ju9G*A?*!#K@H=i|Q?mJaiUe009Ly|8q!r}^mobWdUF@H|_T&L*MWS?;02(qSDV zO6QeO-nMwGuyly~N9ou&{r2&~(qVoYrDOW~$fpZShxm1rj>FInPp@W^{`;6wltse62%D0O{ z$J$d8(z*G)!qP#%wP)+FJ{k7fBD8~ly64I+GFwf%exn+Jto&i=e2E$LkD?4H<%o(wtaEvpiiM=?b*F& zap>4Opta|?-i4*ZyfG?o)#3Pgsc&)Un7mngh72ey9pXT-WSe96IQq==eEn*TT}l&gGMX$A=e(j>&=Xt!G(r=$IVXIGs77ICM-7 zjLrk2ibE$?k9Hqh96F{)t$${WFAg0_jmq^26AMd+`9f5#O^@C)dFknV67j1TpL<69 zDtrIvDiwvLgZ+Vy$=jI_*6$B{7M2cnA=)0JvuRaf>7aM=(YawxVd)?T`RI&jC@dY~ zmQgx0!~S_AU06EI7ov0yL?HCr@xZ00^KnG38Jl}W(H;-`;_9)F}v_xNN3XN#i3*4)Y>!hkHw*5{(-e;*#8xWj@gCJLcaAqudsAzM^p|* z&{6treqnLwm>**8skx*$bWGmHh3%PqS#ju?yqO%Fe?@WVpceq++Zk6EhYqDe$Hvd1 zzZ8}Z@*I^nqm#a&ICMUpK*##0+XKa+gWnTv&$6lN4tjO=k5=RL&x4f`VvB?-`jsL4jp^{sOh)G|0)h0d;h4> zx$NuW(6RTA8l69WTO2wT-!ZxV!wb5QT%&@p{r ze(wqW3QGrhj>?mvphhYqDiqA5Du_@3&#|Pj!IO$Zhi0G~tbbb0C=MO7+a_<5&nYY&{GDk3SbKV1R2(|iKh~aAE-x${>~^$0 zrmz2gb#dredmakq`k)(@p3Zv_yRGH~x5;kvgH}nn{eJi@89Lk!Q9#T4%NKWfDnf_+ z@9RH~$TfPE-x2p_==hY5|IbIqV#t(2Gy4gzAm+X;FIh?9a(9CJ&-)`G1B-2~eT_}&fQ zBqILURRABbk<{;4HR^c5ae`w6CkUYb2OYWpir{*|4T2j59}9jE{3xJJuL^b(Y^p*x z5!|HnT?D_=`No39I^R{WkNr|ZCfHoplXZMl z@P%LtUH8%P6G2ZwKf$Mh#{}a9eFa|&eira-GtXmn5xl7Da=`?_M8PD%D8YEaNWm|H z5rSU@V+1^3)l~qqe$t_vjy#0XU$BgZJ1%ko4o~Pphf|OvsfP6CqHG;haJl``!&|lD3u%lon!Onth1ltO>7EBlJ zb~C;5k91 zph_@HP%W4(m?Jnuu#ez*!M=i<1#<=Uf;$DhRL-qB_SW%s9sB9nsAIF>Ho*X0r*&)* zGznf13{%=r!C!SgO>m1~rl60~4$|=n!GVG&1r3641<30gfAG6*jLt6-jMMo9!IwIJK+s!oiC{;;=Yl^8E*3m1;C&T4>A0qj zm+5$~;8MXvU5^*6Cs&Pn55_b`pR z^bqhfn%jow+l5E&@uRGsf-eO91fL2>L++46lPA*XSNhocb$Oll5j-OJT0k4n>)`f{ zTyu{!$_EE}Bf_-)I*tv~(an^JE<@j*dpciPfL!dN<5z;+1P=)o3vLo%e;?KnIoMV3vv9e$qJVt6=}2DkV5iMKLu~AD|kY1i{P&U?BtU=Qs?OcSffGy|#9^rlSAD}ZMOv8@= zXV383d<$^)3e&b04%fdI)C#^4aJ{zxy7(Df?<1%ZGzqw_6g(%G6<*KO5jmp`+y{4# zfP7qoN1p2Nnj>km1=O)d06p`2$de4y@O!uhmwc4VHAm8*#WnS>6VMi}IUgV(oqpL@ zFjr77NU5$j>j>@r1SjhnKk5#hlNTKD>2Gkz_k2!TgRZU3^dWeS0?NW4x?Sg#1<&9E z;|HAm1q%d}4L#DD1-bcBN`oi(h2W$^9DJ+WbWU1JP8#&)3CM?E3C{fR+Wbb+p#N_H zb+LLa)H!v)k2F3UptNXN2kQDD0rHBB!dI?e5O5Ef<{mT-7LeC`T%9_<5*a>J@P>f% z!vt>%C~J`b9}eFO9}HiN^uq;D362ur*I^e)KSIEm`h$)~3yu^(o8wD@WrPb3Y2>Ax zfdc$LctsxagTpoD*fn{M5g7hmIw$Q|0eqs4q*0IK1o(#daixNC0qMsJo)(-eC{dc( z?-NK<8Q|Zob8t@-K>JjVf|CT$UfEOG>)Wk@AEM2QXOd%W!|fE z==@3WrGPT2qv2krYiQv6-m4>JUM_fFaE0JR;ZpBEhu1b%xd$HU;4Gu#m4XihlyQ{+ zANOhOI&-DWG{Gj8Hf{z8z zyFp;-H|iW*j-+ufihGl;;TitRE;?U9usBTHRY%f>3y3vP_Fo0yGoPHM^A!a*hiT~T zI|a82ZWr7ppge37d1mTJo(2JPPs#(Ad%bl{InUfy|+V=_I zEAyQXbx!}$SN98;2Qogmen4RJGOiyK(7(hY;Gy|`B|3jtP%41;y9uB}+Cze`1mIX- zJ)-j$1$_ieeDL{y(kV0^6-*Z3M{@m`V4PsAfHvYUJ+9*v!Bhc#Wp?C1oj)l!NI;)a z2dEwAz@RHzg0eT-hfu85y(}I@;#|xHI8oC(0NqNr*7^`3E$XI7AQcuR} zp9B{PmJvKBs0`1a*Kuxmj_spdXmwtzSW=kEw+hUf3< ze3s5>_j>~7Cp+s1-ur^f!}AYxyi!10KNKKm_vy%-8r+Wre-Y?1YyJ#AZKI9oiyH;d z`b2=N{H!B5p9*>kMhlP;aQ-P^o<^(#oX-Tk1lW`F1f+c~=qG(oib0qB~opTL7 z;|d(gMs7w3;3ND*mcT=nIET03;S&)5Iz#6d2>vJ_oiuzC?&EJz7Wp~n-nlyG8efOJ zXNA}J7nH*_Z9%6XOOtfGOhzls0#phmElV7eeFm@n8{FhGF*Aa=1^c#f@K9G-6+ro(G| zgqw8SExbp3WEY)t581}9AfH?_SD&mSWz#lv4dWD^PwyRH{Tu6yX(+6q4NU3g;n+vZ$vr)zk{edK8S@EYD( zo*k419}TBxcnx1k1MofW4A1d#ZVk`-==>I)QX?` z#5+vR30FP|^-vwp5pX?L*VrfWagASck&cX0(wM6- zZn=j)_duA=y@`=~=$oCCWHa3s*89G`SoI6{nbkZmTU*#+T?ngd;;O6@&yIVIdsc%U(HPX^R?*!|No(qAjc7{6!ltB8nN%@jQhDWs#^$+I^=>`8 zHP?iyxye*hRdrGs)m*{oxlQ%SxygofvSzgYYo4u}DR(!k@JUta+IFf%MMfqYlFd~r zqqM#%m2xq%R+`!Odh{->YOb%UXl$%c^`6+!+*nm34um+3&Ar<&r&pVl%F-TgRcKOG zv+C_BZmUYTvmU*tRyWr*r6Xi|WplfSYsZADwAlY27x6pMo6s_MO0ucGu9}8VYHn;w zHmB>vJfx?O+dt6CgR*4G)vB(sK{x&8g3QgjR8xJ`Li)ztTvh+Owv4E+nv-$?<^cl+ z4jI_DpWA#eI#pJcuA10TztG9uh^qQj(jkqgE8$MC>YcwRB9L%@4@#an+g&p5Q~duc zw_g1&JR7MfX`?Lp82w+W8PPmNWcQcFC$&W$<18I#DFQoNX$kS)mor&cO~NC!MYywN zKbCZNnK19t)?tOPoQbMegD5A&4_~WHit%CX@J>R#V|>V*Sxu&?6|?o%RbKKm;Tg~D zenLAqeD2P1%kobXubRYLIJLh@YA=2Hkc!nBW9I*?g_iR_tuJ#l8;%UH&?AmNXHkZC03I$s&|QcA|)F1MtkX2C%eD2(g5A5 zYSA14BcV|}Mf;3{?cKM2?wEsXgj_0j6lO`oFcNlG8@;y4(CN6G5n(xfz{wYu6d{|L60O_F3ZsJ@<`(R!~F zi@uHZwD|9BO0Dv(8!PX|A=U)-U|MT|UGw%;SFKQEtM+v`v(@(r?c3{2zci>qV2;xZOIp}jtF@>w64p24%Amu9)X&RCGm zW0hv3DBF&15i76p1Znd+5KeGLzo0LTPl=#QtP)N3G9@NdRvfOFl#CI5)5<0z6WvIt zcIgT2o{CeRY1UH5+Zv}MDm0P~R4EDVxav$9SSRd~?;#tFTZLsTt)(?Nnl9ggmS=p{ zOv=`6Xqgrs=d>I8p+z!GJ7-H<%o4sy<0zGh#jBH?p$Yd_Tks*w&dk)_p83j!PoKff zcq`p;TyV}!D?EojnwY1@YMOkd=;#wI=J>>BNCNw~Vw%B7V{ z<738eHi=1S(&_n_@80&Y>TPy-oFcEriJ9`==7}F@poWN4CbZMs(_7j$nOANUM~U9P z&M#>HPS05FF|9O0(fCq%>Vp*t9;vhbYR3?r4b)^U*1%iYxo3CGYQMoxJ=_3pA;L{@!f%89Xf7_N$Iwlq3)vI=&ePvGb11ShNaJF0h5L3 z-RMkiNP%i$R?5eYuy}1#hK95{?sL04Nt(Mw8i4=tpmXPF!wOV$^Ru8ZM?7pBp;$7; zj!hNJbEDP5PL@5^J>?S0~1W0h-Gc%Urr09n)#I+n@y_SJb` zcQ!yHx=faMsIL3#?hsv<2(O>;hv|Bl&e5a0#iC~(V8;4IwQBFI7G>oztB81><7}s49|S((y#=Jga?Uba#H&0x-1qQD+60t-l-gLc|@mjV3|gC zDhGCCRHt&F??-nk2by|Jr*fcG$95_Qx^Y~ma-jdl$I4-Gs(u;~2}SebNLMBg{XVgi zdFc5`oy|WPcS>5Y<9Jy`ta8^6v9fg|aqYSK8z~D! z3_dfOr^PDOG-F@YvA?uknbU`Z^#4GO!V&s^q-Gx@q!*c)^p!RoAWc&y+%l&d`)PEe zM-$qy5=TNTR@t6r%tRG3dU5wyC9fA^W%!=W_3Rks90=H&RB}`*X&R=#GD%%uSzsh0h>=lbQ(|cpd5@tM9-|FQOYf2`6bM_)(PvpvA>ur7i$QMe4^k?< zQKD-i93zB@b{HYtf$F^hx`XBZT-auq;r^d7q>T0td3QabweyhP_(b| zt+3+3^Jh}`pK2eAc`|P-m3>FfXQ@a1ngbfIHbSMF;_HTqKbLfM$jlLm)tKV`_iwF*j2!ewS@kUBP*7Vby=Tpeyn`v6^)ckSYIs&b9%b`zkZl9T{EA|j;H)9 za&V_>h#$3&6^aS7I)cUA&18*E#D~e`y|-8h5vL!ta8l8Pg8raW4>Q(P2|Y1jJAAe zE1~A6a?D65ttGy~Yy?}4O-5@D zl!jq0JWM)gp#FTsnwWK8VWCm`D+h7J<73e?KgiDsqqUFL{e)O$*;ruC(&GAn5gm;Q zoEWPd8{5$uoD}BtJpA97-5YPK6*u%dOw;NgBs{wB@Z?xLF}Yx8KtI?2cxdIatwcvA_a*OT<0{y%jZ+Uk`7t@3lQ`@tAr^c#@aWTWg ze7iSK3(IP&Ax)ZCqcbn;^iEOkxc|$pULx z_#;Hh*e!xwpch!-Vijwo{_ymN3I^-EpY9+l_-Y9~@ft@fSsz&K^Vj{XSY>S#VvW?= z2)tmYZi-8Z0g<+28 zC8(d18!Sz^Qo-}lKOd|0S|*`q=sUxwXlpWU$}R#s338yp@2^mb+BkB z^fX}{&Y91i;TEe&P4W`k8z~pXD%bc%T$dVq&cQXJ0wrn((RDb(=pmkq9$}`#afJRS z$~#oFE{;XdR%bHp@U6(-_m{*f)7s#p%veFz^jV>z?`Z?Ir|+pLbuQ5zW}#jukXEjg zgr0(r(-$_{(St;dc)oyDn?{|t*BgI|RkF2&*)h>)xR1oJ`axTWwj))njnEeFA2K%C zr@*QmEyBKE7K@%m9WpJkcI5Am%fnJVmpbEr5$A1xb;aK;&gzQIsfg{h-KG8KSbQ?6 z&5pz6M(KSk5_)%294WHCMklc2ll4{Xlh;;AEnc3FnE2f(j7?-5k00HI)k1?@8H-*% zUk(x*7}nEz?NbY*i&Tw z1h$3vs*iy&cJawd^glWXy-EtvuWLF*&*!2nGzR`08rpU=p&_tHq_S2|ov=FCNcJ8h zJJ)uK9xY-YvR|7mcjx$?=qcj9 zprb~t4chEjz#^H|;z$a6T(0XBJ$Q#!Mc3jnGnZm+P5%vZt%9SBP(~~>az7tJLwoPx z`cBcKBzlH5Zd!onh4jEr-%{)nb-}y$5=D*hC5GruLho7Y3_qbj{|s;~f_L-~b_IIa zMasq__TCF~31k%B`_FsC2~W@4QREZ3U?(3^%Lrh8K!44KKAuOCnE{?d1wZB!Yq$5jU*x~tV_Tq8P9Q6KYU4kPJo9= zPe7lZf)Z4iq4?b^#B36JzhGzj2Q3b#nbk6`X(4UHKVS^u8KRBZ!-YO!+(R83fW}Ga zy@he;ts7!x_s{O~sA`>GM~_*Q_0Cu&S`SfoG^dv#YUuq8YV6aIZ@gYFTZ~;Ssn>^S zz`J76%O_#^>wkBw@@&0gqT0W}dHqDIdBQrO_cnT-X8t!nJMQYL-jIStr1J0E=-FD2?5D8&GYagj_dU;3 z10|aM@YV+QX=GAMU5(+*0a{b?Z~fq|f6C*&ShX-&VVvNxVi6fPXjp6s!(0%}hXzRKtxIvFy{)H=Zm_@1Y6>(nskR@;YR8@S_X9l;t0w0EcGSNQh9xZ< z9y2T5*0*@inRglZahll$nb12uJy+V6U@J0R#bJBme3~M54Jxs#ay=a8G)noU$oh}I z^WHH!$nPh>Hu+ht*Mj(Tc&BJ-G!`}nt>t4SkA(Dmefht$BddE@Lgz--{MP3kcox); zEQ{5y7nYcNr>nlv1CHOz$^PH%g!yQQ9gkz)qGDsQQuv-;e`B@qlZfAXzYzZdzo%43 zMg!WvuV_6Mi(W=MvWupp);=Dqyp=+%F)A(d?8g&fs`cLg!rn~N^HKS?C%m7G#S4>u z`UiiQ9wY8ZEFPbq9z~P+nFUdKd|$jqAH!k{(ANpQ$If%EW7+Ab#!u(;K~+`{=`a6I z7IYIU3A5cZe{+TXLacI)x8Cyl7y}*}UNcwdYGwfN8y$q_=2xSMPoT-r_ryA0j786U z&uBZ46W%LB8=@_EDOQQLj^+K4M%4zt3LnPG-CyOr9G3OJq^)dJWZtilc5TXz<|g!Z z;5ZUwJ99b!dwOM831OVnrh z+Xr;8`}?(6RNH!c=F@o(&USZY`+(-{5lJxo_PxE=W7Q;X@4XS0W|G-?EuL@pT!y2$ zvy03f-oU`qg81{9C+nkWZ^mlr#vxXAJe{=%c5!9sRX>3U|UelHnMMA3T*z11{MIX3>$>i8%4Cahkf#nA&;P;@zQ4)g;Wfw%^KJ8!N) zHA*;NDLE8gf~Ux3Y+A8Wb763KlZ26M#gbw zUG{^Jp0D};##)#8QTb+ktW4V5xe|IuZJZu4ZsH*keTRd7z5yS-1TdPA1L88wSBMGv zeJ0GjeN;E0Zvz+~{V~4p|KD3VG<}?HJ^dTOm;<5(Thy+IN^i_>G+8|?BqVXiWX0t1w$1109h{bFP+veXs zfPQLH1d*q_e2l8A=6+yc1Mv%d6p9&4%I&o9GZ@~&<4Ymd66N9-v1(&n^y_|pCWz(2 zn!!15;m~CG2lPIAj_5udCH`(}1^$qb)o1eOVFV3N`vZbIJ_F#VLt6+N@KUiK(4xoEq8_N$O` z$E8}mvi;6X`x1KBeVmbCGK2QUr@%h?br`fa@ddx$Y5TzNhKTwQwezcICNuwzMbGLz zK_kP@+Wq@rZKNdhZhc?xwlUn5!#hNyyGow@{|SA0CQeH&lE+$!y#+F%x9P{po2m6I zw@-~{A^aMJtrdOWsdBPcpV+g+e#o@S_#sv~)@$?%))fu!BSge2(3iw6Sj}bh6Pae0 z8>_4AbmK1b-F~9=V=Q_$D~Q%RTI-);m14C<>o7ZEuK{`oe-&SxNFlYRRm95u%BzpM z&?L*~ptLjXO*Ig=J#A!R_2#y72y&SfyGk*oR9^*^$dmH6KTS_q5IS z#Grqfq2W~$lf%Ms#fE1n<*$FVL?(;2AO-CYlq6Th>0men-2Y#f}2JWGo*u zM8+&*oc1w?p~cWUAo)}=i?ual5pvs9Ti>!_X1ys0B&uV+TyRrlZYRyJ~S#`~)L zyVY13k9zd}IX>R&$1dTdi^4E-T)9&`_qq_@)9)N49>cC*A9bN8@Iw5aX1@;!3G|Z4 zxZtY;ar*do?X+gHqOC28A^11C;lE~D#5-T(lx_0k{cAKnc9=c+v<3OW*5X?ev0;Z6 z=RE1g%CNT_eka;$vFK%_BHA<2mgKf$^;qTF3^ZC&ZZGqe|IYD*7ScK*QFtGI7mU|< z*mb|>izpS5N+L3hJ2VH}<1L_`URy8FG=Ht+GP4(8wpOa}A&Cn1*6xf0WZ`)Wa(kt$ z7)nMjH~-qwVXxgTw$*|%*NMdm%YmI=w^KQo#je+>9HW$D{Z8c=tsEP4D#sY**sxPM z#wy3}!W_np%#M!DbeF%bdJC|h8#Zb8QMLrrmo4s_9B3N$9WZC8b?-FaC{|r;jN)Yy zE$7(@cGV!4NE$O@v^%pOB2&Z$u{GFeqQ2N;A|$-AzdcDZFOzq3`C0yK&Hpp{CA&?$ z#lO9hY@M{fB-mDBIP#u;pT{h``ABfk-{GvAfIp&@_!C4*7**`LrLDBq$9=G??1)5n z!3*>)z8WpZVsF-N9c?C1qPAigQdwyd5WAYto~QCZJCbL;Isqjg9J zyU(_aRTJAuVw@vF=Vc)gY!$17_IbZ`to$}M*`t9ZBgaHi7?FNvj(+mb0eBA-9|8}^ z$LW|Opv4kF_mEy&ood>lm+*L+Yj$KufyK6v{T^WnUR!j=U;XdNzQvl`Z&@PPrc*uP z=T}6s{4;9I(R}2DUck>s_xlxB{1Y%41IQ(_f`oST#2IzgD^~O9PL=2zsJDw%S{y!X zAFCvjNbhswty)wFFBQAUyw6rj{n|5gG4GxGSt}kJ-z@NaXe*HxH|wQ0%gmOSjV&bR zos@LWaC*3ByLqjpcnEEC@9A>)3Ue<>cQ3D6^5^B3m~HlT?@n=ySs)`9Iq@@Hi}5gq z@$;G4_@@o=*OhxO?w*lhxkc}a{ z6QY>JM*I#kb`SVCAHEjeCu>w_bB}>$_c3(uUk>aPJ+u(H{c1HkchF+c^G_HsO7Q`S zmf+WUZH9GcM#`8S)Jb}@hSm|8qAf&T(3s46(VKqO%Q;>&TGQ`CM3?Y1(%_I@TODDR zwU=_(3Xsnvz&`!0?k5oA5BXiW9eF3xyj>1XwBJm%%iEql-W_06; zCIoRLWkX@|m%ZYZS>t28jM3;})a)6KogIr(GNWdvqLjRsO5QnE$+o*An;X{qX~zlp zz+3j?aM#8mdYRs1ZpZwFafx=M2YE`0D`r8A2j(60DbZO*E7m>{?Aj@M$OEfnQ1DMf zu?~YJg)*zx%&(wgV-%mxKl4UZGoiQd$7!EM>?@>Q+1-iG&0Z@WuT<{LRhh$Mm1#V~ z&g1JK?`R8lZL=$q7$>o4o`gkjq2KTd7!P<0@D(m5lq*gftk10t*)53Hzceh*kC@K* zr~m(pr&_eCTz=02jc?un#fo&w-|5C3~TZoa+$`l`)i`4UAOUUXBd z`D3k?Xor7$6876acS%GVd%#_62fdF+##|ijhn*+-!FMd;&@cBWd*C;pJPz znXlRTmh&xQzL(*7*0vOjBl5*!|14+b*#&Y=iq+mNgvlSClizK{zH9&O%eGHl`|*`o zGhil~P$Vc$zZz%p|FDSc#D#zO_RNyuF5U&#-WR~H@Uvxf1)ei=LB7)whn~g9^R+DZ zX>zo2ZmXuoqGDR8R9u*;+Ganc-nLx!f+zIUV4N1LAWZ%;k+x~E@>!jD%S~EyNt>71 zjw%0iu77)2rtIml%C@zxY^^)q%~^@d_;>B^9;>X3Kf^Q1_C7Nk_nDn;3B5Hl4!^8! z(R~cQv}jo~VwGjmN;DrI4LQUgW!w{a#D8OUNNf@B0IvXzhZNiVl)X6#`QX0p?T_I0 z#{ORI<}}IZEq?Q5ZNAFksd$Oue_K_F`<(f<%EMpV_wt*Jq}9LK&zk$)(EF+H*bhb& z!$0H7|Gcjn?O^rD#`Q6e3^w0o^Z0vrs(+X(_;*ONBihe6y;eqFvwMO#0h+__a%EOy z77PD_uY|;rEz{ZAt;pZv%2*|ugt3a?-`B|u+3&|dwunTa3E9Pg=ZRJIvn=ebkE|k> ze6=G^3rrtY$Xd*Do^*5%ZC9ryI(l1eRV*sjD*A=k3a#^T9C`rWvpR^TC-T8wJNktv zf#0daIpd4(b;N0v?Y79YDl^v6{O!HJwmMenw#J?L%1Awmz z@f0C%EykKpQhj*CC$kr?m)hEgKH|h&SrPy30W^1u%Ny6e^j7}PSfXU7_)z28#Je5% z_C}okF>kKze$P3b%FnxA?F|#&#?;2jZ{A=gzxP?{!rZ>cvS-K^D~RqmnklI~K)r## z#`j0)VQgz=f0Cup4sRrES$UAKsGpN*mp{Qjkz< z;`C$Zc(PxtGP{L5!q>+C!@l|zB0O&IYoigdy=VzEp^p!*zl80`?1QXh++@ut1+ zj9Fi0zCAHFR=MVhTYe%FJde!oi==AT5UZ4pLvG-m;dxJX|7ZJ?`Tg(4SmhhH;UX)j zSWVWXn4kF_d3Z2HvhZh^`S|!V*l1pU`!Vf0~ zL|lkiQ9|5aM*lDU7t3rNEBEOldby)}2gGWxS&VE?AeYt%r^$G$RU$YrR=LJUR?4t* z%qEF_dheK-CelF^m9+(8ZfIY>M(Ay!x0MO`6P}N@M*>eKqb2RkyyW&QACZF07ppV& z@8DRa8<(=ZS=Ly1Mky^z5Y+_q%ptMLH7;SF&}hsiSe^B2QH&kG9*ZR-sstzf{0=$u zaU|k#e0L@em(0h>ZHKiYqs?f;VX?}zXQn2JzjMS3ygt55rhYi#`c;L@d6VY@l8JzIWE2kr6a5d!dQZ zusa%?$9@tbw0`DKj1kS{zlw5XEP9!knztg>4m`DJOYrkE&!QdGZaWE?9Wb+FM$Js0Sydu9CKmThg0M?GD}m+maTqK(D^o}kzArHu zVlV#LZ)P1{^LS5-?*hfqE~bNXM*_12-;%DaZSip!-bqNP|l9A%m|i5#iTBSsz-h7Q*`CdgT6lV_l5BpKk4tTNnh4H_ zRjTQniRug9b!+m)cZ$5uX{)E$y~bbmdZ$H5eRRNjsO{AR_Xa)x%<*XHc>5|4F@yH* z@fD*u8qln8J{~24v%)fb?XzQq=GR5FUFNAoJjnmf6Aqp2^|NE~$wmQsihTg=-th0+ z#X=HMU~DjhA@<;7c0R(-4kthBB`@DliqkK)DxHbD+jlyBq{yVjq%WU5pA(Cc?JA5) zKt`(lDpj`jNd)J{D!E4}^_ezoqY;oD7h~q=_X6|GU9=9?vW)fFM&+FsQZ|X~yr$he ztW~Dm|Bt;lfw$}`%e?QEL2yJ6P*JG_1A+vqQbkoNijt}fi~&u+0jo(RDUx6kNU8z~ zhL3h=TH0>uRzHV!77^68ZAB)PMg`}walip_fOc-@fp(zR|2*fZcMogtv(`EL+^SnS zw|=|sx%=$BhIe@0Y3;Q?c?%i7HgS;mY{&U{*Iqkzv4oXg|BXe|vV^f7fcz95JnL?W z`KW|}vPd4!IwEIC6S7Fwft43z9LNgu&ZZIxvp-)q_irw0+gZKlTW0$8k8dez%N3|= z=CRW4X@=igbZ1o86=ji+<8A8fi*xnND|lhbP!o-QTTy$COw~rag>Nrv!M5X>sdsYY z*mUih^{V;(tIKtBzeqC8JgwHPT66xE)PHkzSL6i!E$^vp?sM`TMRT+q6LqQ@ttWKx z2b9x6epQ>cN5S(T+Es*Tkm!QvC0||C-^Zpa`8Sl=@oc~rzk@aMJKtHYK4C#5_NTwD4wvzQ;pqu$+7AiMRK+^ z&8vz2w4xQgq~42m(wgr1o}!ss>a;R|YC2g~@`*g9s63*qGm!}SMPgg6=c5ilHkwL2 z?*J-6Pse)AnZ!K0^ZwqVHvL4A_BG;dJsOE6C!TyZ5)v9SG)yJY=& zR*a`+l#wCBhYVA_1Z#=4USHIo=QD(z-FXCVzM-gn#|Y0%Hi*cT9k+OEjbzQybv|R? zzZV&J)BN7$QO&#khM%|C|056NyolCb7|Dix!2UgNE}FMxfG4i>)D^i9Rr^^-jL!#` zy>6Vin@9s~K@zxvEDLY5DWS7vV38l#pU)2$wV(3^`)&QmysbXgSxVTe4d0;u45Os# zE%O!v9bDsVYwJ^!9Ky}0j`sT@-NiD52jK7XjOmMN-A^8+VPw!nL4CR zF)!bf8OCeVx(V$Vta={S^vCA?SzpU5HfJt_aPK+qS$}lXtXlr#Ra9dg0URL@rWGUF zvrSafGi3N5)XY`sWUU};fY4>A_O_z_`p@=~O{E27A)f7ZU79?Ep6%`0^5MPO-(ED5 zKE-~b=svH=EYA=GYLgB4$$2l9uH~}9#2#TSJ`NQ|DGr_u}FN#F5>SSz8G1&a5v^gmtHpFPIh41T7l1^Z6UdpIn7x}PtiiMa^RwCV$N#9QTg4RSYVHe6KHq53_Mu6EAh9_=^x3q}34bK^1g=E#4s zs3p_E+>Ex`boiyB)|&D0$&^{}TJ}3jh&s4DG0irQV;; z4(*2V>qR56e<}L04y{YUcNVp?h!4LpZ)JDN7TKUaWqz}WGS*L4N#Pa2Q#@qt5{RTp zmW0=!v}`J8!613pS0vf`t)l*dqsn3R$Nk$y?F2{jvwv4nE4CEcIi1xM*QJX7%?X*w z!@nS9o_U)~3C_8;-j1S>Th=$fVD{YPsf3$e5464Y?xJ?hAMhPsXjdfG1SoPL?jS#m zS41XH>n5?Q_(Y0rKndOhQ!)=%)P`~$F{8((zR1g)W|8&yy`rA%4LdKy8(&IB=t@WU zXxm$VP;{rgJM)$`S;VO?PSkl%Q45xr=o^`#MsZs@WEbCC)RN`5*%J9sqGmFU|GTIa z&&YL6MuNY|(*%E5)Pg-jd?Vyjd!uL+eC8R0&rIL(tS_zpQBkXwT5`&IPK#Ovo*p(z z`!r$4h=ZvR6QRqiXRRH1X0AhO|G26@R`sz$9sh^bSoB9OKu^I@gC;hhU!K;)Tf(~# z_Tf)$Z~e)DUn9*U@mT?w+Rqcm0KWM%* zTlGv=c@KP1Rx539 z{hz^6I!Yo-h5uk$Zg2fX)fmaSKtFJi>lJXH0~Eybl&{QO$R=Z5C7bpAD?Yj8GKlWbN}zzejU3ed@!h0(XF2zec0^A2fu z+>@&${dE-wWO=A3p|#X4_$;~6jvamj4)zME)HA7M;#mj9+cQc~-}bdRoALSo?Y!N{ zbUIhww9(sJrqks!it{8U@hwPtZTjq7=e1kUO4Pn39ok)norA?SW#EYA;MjEuFQWym z)cpK(<=+*}@}uT$Hb;2vd@nt>AFY!grtQBkYCAAlJ{uTG?hTHiNuKGv?|(cGE1UXtY_ z|9@NJ4*9Ccc-hBkehUIQBlfRFGq>C-N2JUj>wAz}qFSCP!U~a1!shezxGJRh0$3x~ z2VvXaU(}!1!^F(5ovnlE&(D=+TZ()J#C~qfdwWaXMc>DGz?=hqk|ds1@5f0WFmJ_j z71bCaQj9-(cKbtD98JEkyuEH~yj2-&yCHFzJ>MUdMtYC=2*&4c4>N~pxiQ|es8ve^ z_8gy1`Ft!4`6JMZr-Afr8Fq$j6VH3_ehIRWpd8poW?Fn0pM_+ZyoBKqknGk!PqyAgCV zzD8e5C}{b_dnTJtgouO^i3#bjcjR65^csFQJ{x`=aT-X-chq%C`m>Ie&Gi07ZQ7R$ z8l9K;$W9l}Oh`uNfwy;*jLy^`_5{hP91sVRLjdRT4aiGsXMJVHp&8W>vH{AI?MwZA zWL1AuTc9jeEUh#VUHO}slV{?2PM80oJ~2E|F~4PL9yssMlG?<1YgiNK<2eD<;f8jB zbd~N4Qx^Dn$s*;@+g?KZip98X&GWkCTTi#n-X%5sf-c&>2XBmAke;n1`=d$~u?BS? zvL4C;L2qS0$a*|@-k*BqeQ6(%&hpPb7Ijnh{^WfqC1V?#-A5O-(3D1ILKKC3C=Nz0 z$;9e8Eh1wq2f1`#gUunc%X?2eFU_f3I^@lDIctq`e7e)p@sKL|;gL~O(7p)dyHtbV z6Iumj@#~NkG6`hwh*vp}w(;hcHvQ`JFb_+u@ULkHhVn4iB;W1&gjy$)7e-ATTR=8O z|HrB+^pTkLG3n4}-uY4@n;}^soK}IV3LqLGOXReWH6nSQJmdLy&B4-tOT*)D>?vA$tcKzVZV3=PCM-?KgTn2Wa#!(^{1zFmD6P{Ez*IG zAz4@lVnvV#8nNC$s|TSkYr`%{{hc@OPqIKvXY3qWNox=1%;}-6hkd=vlU3#2F*R}q zMoEr9C#_y1VnW-H)P3lXj*)B{UoL& zkHQl#JgIvseZDiz&KmWs*>hNq>xS=;H2S(`{O2qqc^N$FTW9_81gyMkq67B%U<_2X z*oT34*_801c2=KQ)T-xB9+KLoY7)veV@W|ft$-(Q$x1Q#WMrAqbMM8;n`BC6;Tj`o z?kN3H^E-_T_4ehwxr{dLOZeDhamLeTe7Gse!Of`+OIZ8tCl$@il$4iB^q}es-ZSeV zRVShPLauVP9x|H`0#0$MT*vLwv6}kK6u*Bk%TThQ?qV@P2|sKWA=7Nn>WLk>s60 zB^a?R4-OQyZsbt(Pp%lBhDZW`Q_o%!XHq@Dk0G9C6(Y|L6T#!b^4)eiQ!*RZiIB$T z%30n7)Rx0~3u0sl8vCgnS^GGTrrnS*)UciTBmQyH+g* zYO>#*p8JQg&>q~7CDD3^?R0kuU7MbTYocTGJzUhPXMs&&MF5h)Y5};91;h?ABV>lG z5C5<$L=)Ibt#?8*`l3qRcKWNPKfTw96$p4F)Of)X@pbN?jYxNd#e_2(3%mtqd$`QeUManW0 zgQI=?<+W1eFo?U+I>z+4)ZgV*{V66Q4@+fB@1=sS$g_6##p~lA^kls`a;%68jo(h+ z)X-D$8Ew!eF`MK8ella?5U@onSdkq#3gyW+T%P*7a^9bMZDxO6Yti!xs+s965qRP^ zrI?BM`H5BIB_BkM4>?i>pYdWN_{%E~kV7gg_zZA@N(A~3eV$a+pH`?rXSfP)IRoXP zh@_8p`Go8-8YDt_E3$k~uIdkYVig})g$`*ox8#bym0{K1v$}%#P%#vd7jNk);s3+a zmHdm93{CVsFJ&w#r?4!YRF?iLSAvbYry27<~Duz!j>eo1hPLX-UUL$pA z7&8I2^o)s~E7LkQQC3zB6hZEuR@C2lvspIh8HoE?^Et*0nO}Z(R~7Z<)o{^AGs-Z+ z2hDjuPzkpjxsXR>rTVFq1!9f&ZE1GTn71H)^1nT@(tVjtqh|hND8J5m_Fl=2#QN@Q zs3G>p`{_k9ww!?8vewEPE5-$fskGv?l262%utFCf5KF_8X;?S#_cMz6vq$2w=SF^Y zQA>`u*eQzj+2rW1ncvyRNMC(X%7yCKPE;$A2~&uwm8b;DfsUM!r;PQY?nMn0t4r=4 z+o@-D$;A*qJ*%oe)i0nsIUlG_y#QLHpWq}&jFrGH!72CwVq>{jlk=HX{ekIvx&@1> z=g{0Mg3WNKRxm6y2LxnID1GE$)k1K>D{Cyys>u| zZCMv+4NP!*pHtMHc}@Nl|At(vvTSf3uSz>~!xQ`lJQ6AZcxNE3tT?oIc2$4a75qXx z4)KKWho`g7;~^(Eh!#DM(@v8oi zN7_JIKw{}6{xJB1kHXB6Q^hBoM_TZyw5R-aRsDfFAiofYC<8A7zA|&wGT}Jc416=P zAy5;FFz@YDC$6C$TC#7EYAkwe}*RMVe4B4RVB$+IU& z5PZaIB96z)Brk$ZM53W3Sur9p`a3c2Z&<3Il`NAi9k`^`W6!M`CGj5q8<{w90;xi# zz#<_BJV6pgd+34&q75L@jaB_A5BKm=@=(^(D&ztwRy#M)$Y1I5{`ky6r zo2V<~Y83W@UE3hO8LQCTQbjjW8_9xd#NYTNSREt+83zx^4}k4ppW=4;P00PNMg6(* z;90~Ra&x||s7?Ev(bjhIZfc|kp8yR&7V$8VMX~|R7-?bl33YHt6h<66n^v4=4JSI5K|FZPp4#uE{pxQxRc`5^!NVWsuaL{%__5T^CkfF#HciMZ8<6W~AmP$V#SC zIsj#qA3(JR;fF%%ByS@UJ@tQ6vLmMLM~g438YLJ=ei`eECx}Hw>+x*K zh(QVD&VDXjLhq4zuHYR-i$=-a-I(@^sz#}pOEEu4!{2BGmWr$oXa!mzFX$(<1SPNl zV8!;<7Y~lo^?FtZGAsYv-ujZNF@l$lY0*_EiKb{BGxkT39efw9sS+aFXf6@Mmsa%$ z=EDPY0>q|IG)JG|9dV=L1H5*qgKQ~ophEHQ25Ev#=il;gVu;EMdu)6`>e=sM=zp`l z_42Bj6JNn`qF=a$ox?&XAIB%+B%*(;Gd7E?0N$~(1-$vE2C29gy#+bYR^=VB?Vyt4 zOZw0=(|Ail8A&ZZ#+Oy~M@A8jfgpGd;;gU)KaI5(%pdCl737cc8*4$P^%Yh9$;x0+ zoJ)~6h-}gi)*Vd)>G>ZY13QD}fuy`gsD_?eGt5Y_qs)()tb_TlQsew#Hs30QP z3?-oFmsj9WV%72MloODSFcM(}d_w;D z7G1(hV6oti&TenLvZ_BQi$z33(NFRaviwAJ@Bn%s&Db6!4xE#x57l@lPYplN5p0J% zbaI5m3LqxBgtmgj`ll?HB?1JczyDIzAF_;n2NUpLtgYxXz0(IY#JfU+ZG*{>kX_r} z`pT;QkYmsYpPcvu6hQXqSCI+Ph`dR89`e2LEa5!w^r@jIc);AqLF#|JCE*lW3O(VQ zq5?AF$TnA^?ezE6RsBIp<-hPxm<#?c62ti6t)vHxfEHYVCxyJCfxP9XW`1P-BqeAD zGKz$P8)z=rgf-<8Juz1#3+qZQ2G8_ss`|rA5f71adWTlf(=mtqGBAVrKo2BSIY}am zubua&SvEbzb_^7@_xhPt<~=)glo3ThQ1lbK3pa>Iu!GD5{|w}W)5roig47`c+go2> z)gM#^abypm5_vGVjo!j}r~zgZM=#d9TIIo8f{ zva20y)2~bST#yd_#q;NS*Wm55isXw=KjGe)!$S^ zp^ur5@mVQ9!*eKF4MJ`7&h%GvEM$`69pc+t-(1wbt5=2d81EBTc#EHHD-;DpzCP8Z~)Z9(%>gRD{@2B7nlilmixfrZ!hZ4 zYb2Uu?~eRcMJ;{AT#AmSC!?>Oy{G4<^qc$->x!TOe{FAlM^S60gE#^HfYtaWV82#C zV{yPB=sOpG&5y6O3PP_PS|idjc_d_fgIG(MGH~9vj-K zsFu+Y2@>Og5=2#6NrMhCPcp~&Sle6QThyQHkVlhsd|uL~6X}1RCp)jBLE5#5_a@cM zg3;pTV5dMfWg0TzaBD9j3m;mdBpG*w(eMSAbCfA(>Ppt$Bcn<%gs7?Du zdSjG#k>1|={>r=A!#nQ&fug%@GaT*VVc^q2Per;&De^(~if99A$IB%*?WhA!_H|YL zfj-1a_{YR0*k+<4xCajYXAwIb) zI7fTrhw+6$O=3(ki>j%Crf303An7Ht`;n^tRC~k+!5dYM6WKvt=pT7OM$ti#8e6GM z5mbPlZ>j1}aST$SIY3{QS1*$pd20?#gZYPZ>#DL{D4xlh8)nJ>Icem z6T_+AtO`AH3N9#j3SPgxsz2}&nu5`I_?n+6s63Ubb68pa<~LCqIE0pLZ~a77e;_?G z!Qx2=9dAlj&^Tfcuu>UJAsn)UZQ`v^CGzs1bft1deiIOpGw(-u?rhf(KF3oir_!}Q zRn)HiBJfdqqme=td=sz)?x6)lT2K-lfS1@t@T!R1Ej_2+0=F{j7PGaTN7e0%E`i(0ZYGIF8|#);jKKZnF&pU4T}?|^n-JlKHcM7PjH z{J3AL>JQ%u`2xk{&p7Xd2H0}Qmju@pAIkRuDYv(NxvD?u53z%C;7C7MOFk7Frf2{x z#>Y||g@s`xSRmeeCA`r8&D@kRf|X)CKN`=^^><%>N7bmo2Xdq6zC9UufXB}0ZIj>^ z_6|D9x5rXoZGWYzKjJ-AsPMv&O!?X14Kgj;Ktu#5h}h(tf=^J3H&d0Ms-=z?3+s)J zfYoFQ!5nzP9Ep`cBoIh_Yu1WbSZ(raRsE4Gmqg2I<3})0`~^NSLwqCVg+AiPa0ecp z>NLMz)gL(wIKiCcp`km>7w?Nq2!0Hd!!F|;Dq3Re&fCTMpb|COnNMB!VAQ&U>3{}s^L*^R#kLl6u$yY#GClds{WvyD$(S` zXjhT4VkPB1;3fEqRg+dQLhd?}`unY_{@@>6k{rsbM(ROvVV_zC$>cBM6@&9wQEcXK zSM?`(RQ6x`4))O#R3t(}dYBnFhQ|Y9F)rqdxBITD{$zWUafV9JQ}G_20P+t7IlyQ< z1vFFsfwB|7Q`w*51NmxryP!QYV?_m6pm>*Ghi3?C zGC!gvcq>^I(xMZ5kEVe7zdP^GK2QDA%MVVi@GpGD{yQ{PrJ}Ng{6uBcJM_lAuElZf zdGo7(uZkv$REToO!oXp?K@e4|THpalL`-752Z6Ek{LlNgN_gNJn&uEQ=+5;Iidu7Z z+Hcg1R!oKWtjww5U6Q(U=Wypo}SP{H5p#;}} zk;u2|0=yBdgj=ox@J!3K$%D~5Jp9(z{(S$isMRjl`tAHtQ9GtCdwwJNx6kT%RHi>Y ztxsSFz2~J`K2hW!&)ZvGUq3pv!oTJ^2r7!Xw<>++EEYVO#z;K>hA;7mHcbY=FjGL zN_Lvw?#Irr?(d4)Kf^jhM(2OqTYo-DyWO66XIP1pd#1$kw^Jcb2VOkqu!lricxHc9)SuUhHOJi?^0d z_|{szq4-7BO!CvS;<%j=%kq?PF2RjI;# zYa09WlJ4J{tcLeqZ_2AFu07Y!+xnz5;v3V|*3ZykS?X7>Q>W|n5?SsyEwPbg+zKC!19p0;|1d3U)pu|(y z*X^x;t?EyeFy=)3E)91ijmM^{HS;77?TjliGBXBU-(S@qF$ysf_(FCVZxBBniV;0w z_rWBnPJWK)UMoG3DsshJ+a+>j%Xekc5i|u)=Df5IMSJf<fl4uAq8QK8tRJ~Q^TUtQ|8k*8(Nq>IEnYWTf+(B-XG2f%8jeE`J z#a>6c>z+k-89mzcduAHP?TMDWHAUm^>z)ykox^WPw0~jp5xC>tMg87;K3X^h*LXKr z38n1IL1EVYXq_Cf)yWx3f|aZVYR)HSbDw!1M(^fYH19Fod`A9kcrT5;bmwZFJ8x#r z?^{GWOEofzWRs&rrojQS7s}-jy`i)C@5nwn3NGSxp}SWkUVTtee~lJ_DY-ym#6otILx@`1K$rUIaFlEG+Yu zy+GnVys|%PL-a-_jW)4p%ug9)GIiJ)vV-Iy$#+wmCzHtBd0$xx8kv9CZ@5S8L78f7 zH}g}L1FGRyVE5>iE1el-M7*!8ra!ntOpVu~b?E3ZIYYb&Bng{~Cl9^x8lWZ>4|34R z%l)hR!{RYwP?ubdGLgt9`AU2v+NDqCtU95d>=C-~#RIm~Y4@#XK-#@OsHk^KB>oD%9=e9~A$9U=RUM_qL*7_xB;X+x6;_Xc zKdhvGa8ZBuzm$K&&$>BTV&2#Z&#=zqf60K61LJLFC34_d;0cqxS8W1xphAM2gL_mM zRJqogB}qMAB$AHB;+@we{aNlbi{>0yvELm3#}u_^--z~ZNG(``9#VAoBjyqm(pe@W ze#d$LnE~DzRze5UU0yE|f($`*Fa@fEk6I6^tc=z?D+4c-0Eu|>S4n>l>&^7)M6tFm zboCH_GdIJJFY3`VWb{O?pf;8cd?xZ?Jpq^vb`l2(+f-}75;9+~cYEuhRsErlvPp{c zw6aYWLY7ETkSbSbBQ_Hok4?e??y2ezpAJnyOW+@|rE>AuROU_VczRrcUx6lJJIK;w zA!;AWJRKIA3kLb|5JPtf_QHL{T z&rJRa@8v$4jyqFU63hDhSykz}#8d4!`H4l;GIvy;5z^xcAno$bK_PSj6e40EX5<@H z)xk|T$GgT#(7t8{k1A@>GawGqY6heXi^VKJI&6|xf}y))Hi@+q*^o&?+qYBJv}6X3 z{FL*+&(Rywsq1l$y2zu8TJp$2ckB%`rACHl%_r*qtYA>Kj4Qx!af65tE#m6!v^z%0 z$X(NqC!w49lgG}UKqQCqf`kg><-Q=b{FtJa)jRg$ymZfFi|%o*1#5q5p5tZ@9=9c% zQ?8Zr+lF!h`j$7px36fv^W7d>`-<|n29veBA8(AW+kG`Pw{DpN?5Ihk_H+$pcq-p%`96{;ogc@IVsD5Z`>k$<%;IZP%V!QRNVlCwV;%Z@#LtcgHM;u`?L2EZ@kS{q41aPOqg;qNweR_N$y{KY<{aZ z3#lS^dC{zlT+N<|5MP-3iv4if9@`Z~Et_6sRjBq7@ey-?C2&w{c;Pg8JTeg2F*q)t z2Q(*N!ke*5G{|eFwC^%+mu3f`k~>{P#cG{McRi`-F3-<$tLM+i8-SI{njynTw^mvs zv3gPh$v~p1C-Y{jl2Jx~WIC0f1F=;TAcw0Q4mJ>P3a^r!JoMCh9{CTv*{Y^LxT74u z*6X38$_ug{f@qM|@m|3{t;<3WxC>tszpJJ{a8qkZ$sSOr;xEyTIbwOpkl`O=jj&5v zX}}XYSBB`MUZ;t2YykZVgNILN!MYUqitNS*}`AN@$k`dr-QPe_+LJ$%Cfi^5mHhbX)RwuAD`gx21WXO#iM+_5bY@mzB)J9#FGg{2jb2 zS|%Sz1bbWh)NK7Tidwf;={W`HghW9t=&xLY{83fMiQLgR)qwU5x8yJ{^>+OQU+WF($Bu@|yHrU7|IB0vlfivQ6zt^QKRoOl(hhWsLx zy!Wc6KOrMES#nC!J+v7r68RyIS|3HsgQlPl=)WT0?X8z=ou9G>=cn_}o_*do`+R=l z%K0e|bAGyu@6J!H=i}$#BbzA1c?(sPaT)Joxt14k85^vYSJRc8^zNU@!kC`+ zdk1rxGd-2w$Z_YWran8p`>e|=JO#BfHLtK4)3n@_Hz?JYIJ~Y!eR-baI(k>4k@z5l zY@;cA9l0M%0sfrNsqOYX2Tt=AWH$-Ii&Q(bcsa@-W(kgxH%F$+w* z@9Sg*@rc4Vs`IMIDXF!*SLHEHulwt3narN&G^CvorI7QKl_n#i`$X5FoI=;f%K31I z8yv9@U^%F3o%~*RHch|4ty?O_THlxa!{sHEbwe7-xZl5#&~6s0D=`}hy(Hy-a~Zq5 zgpy0NU(s#|Gn?lx5~mso1$}j6y0yhe~y`Y{=Au(Buus$42|`a=3kctD2oECFK99$wUj{)X*68En{G2pdghT zs#g~^+Q@MzdeFDbg0YjSrwx#@$&=u0a5>u0w_Q#<*PS1|zYT4pKicGa>k@Ral?g9} zbAkBQG0uiIj%gWJS{qi$0Oj<|?N0BPFlu^KrpY?YS!0Ihyle)SwrIEAL(B+i29Mx3 z*NE@ILF*{j^)rmLjf}nO=kAIiDLFZ+RZ)c&XP-i-FwsI|Ac!Sk66hMUw_bJ?me& z)jl@2zB$iMKJ?k=dqW4%I=n`xGVC3TDtX^=@62M@$Iy)BO%GkKZ{?HddU0atdVSlx zK1b`Ai@xRhI49X2>OtSG$7fchv#lX{FNoDwRs5Hj-qm61tQ|W;-KEwwz(L zha|}wIc~M5mn7r|X+3v*v~v%WN~>1NtL?mP+tjT#b*mZ~#V+o&)!fMFMn=KM@ckG0 zcJ?cF)*{Cm!Hq>;b`8M#eYs!X4H7wLp z_9jhXG%*Tg>4)0Tw|X}Ll~S#vVMJ#~RzIFE2;9lnz2a$saesZCs57+&Z?p^z-Dnx> z#+2P&NA0Y1Jtr$lVpY(XmsqM}n-!hdpulSRHbYo#&u6ouQ@Zey2IXwW&ej#3HFnIk zy^S3^lk288-r}&9Y329X<}KFPv8c;#>{u=e3Y!EP4M$1(cJpKc9$Lg>=kAjUHFnGy zhm9TE*fFZT=!kM6o2-YQwj;{|*5dO!LtkUZA}hPGV>vsuv16#wf?O0ZBT5pSWl3ty$ zS+9O}uU9Y4@0RZLy77p}7OrnKz{VpwmpvjddXwKpgH&zmRwg2AxjqfstQ#HHu(NgD zXykX|`G=9zbGm|CfX#flz?LUo49 zGwXF+wG^(D?mSeshv4$9D^_feU2nadYWzH9=C&-Y%Twpr3M-%@H!_ZTrQUnAmy=P+ z)n<=zWD6}cUTi#z-RD_o7kfCl$g|My=ep9!n%m`WdRxGL)wWrATfh~zUxC!iTF%`5 z-6i|ImSc4v>zILaO2LV+f$?NLSE6x?IZ=vs%T#Y-XYinRcovqAn*EKL&u)9C!rsYO zqw#DdYc-KKw5$0Hcgd6F?0Bs=8L*=@)#!*RWuv<>Cv*qJ^)0L6B#Z27NmZ4YDB8f{ z53f7Yx5|&|UDxbG%w9%X->jaDlFj#KL=XCQ9Z$G2FCp?qv zl*4G(_qxxzS~}3c)LUX@3L=< zSYOMLAqeD--aK=2$Mb>~wolT~;W#H}-H3L~MQdK(y0MRiuN>nyBMNQSnDTF@;7V(A zj^8=X=H49Oad}kz{oUiu0veA|%oq!G!NOxR$=_|(PX0|GHS`#^1)|cBwb8eDC`1j| z8Yo`7Zwl6mry9s+q0`vSrp1)>4vj(I%Hkm-+^aoQ>Mb7r8T+@evW5%?Ed-?`4MXE- z%Zl$3?hVn`--Z^_ANSIWHH=x=QiNB@S^5;fu@*a+&b;-cabDJLN``qF7`t534xAXZ!tY^^H)*RV` z+CrMZ49*!zWS6=Kf(K;H3~yhfF`-OWAjjZ~relG~l~$(VJ} z*80rZ@Gfd8-sNfJ5Qe?8Ws#1N+8RvJdd|;_H@P&WB{DH>Y4K>rrKL2FQJ=L9NisL% z%-L&IVvHVj&{rBk>|#k>r1NbFoVM*_bJT&)T~9{HgU4~nmi=V=KAZZuky$w(a0fqE zxuMN-ylt7q>j{6>UJs~jTyCOHM0V4l4wlTZZE1Ab*RnWs_TrAI8Mb3JZ==n{pny?r zwbpkh_9%l8I0#j`$Qj=X?T6w@eG9knDwL^YhtjxT=rVM_z9ljvi`%|aJQ})F-zqvM zf@ELQL$fHo8J*{>LX1t{(gs?k(c@i!gl9)=9q)`>?CZq4BsZvoL=VRxZB#(^rbdQ# z4^y{(Y!~`GP#J9x?OPppR7I7SSAsLm>r2q3d3_0zaDB{AUhxoq>D#VX>PR_%m%k0k zrayY*dV3|{s3k5?BcGw+?ds0u2+OI`Lrc6vz3EUZkRp3F{!VXD)Ny;xR}t5V9^&1y zn+#3lIu^xJ$FlrJn#D0o!4SWZV_muP{I&u- zH?Ly^jHJHbKE2k_Zw^UH-)+ly%8+ClxeBYXdAIE{`w;Ybtrax31>;tu`JP(qRnAM8 zmeQo2zwL{V9kbuGDBkPq zwkjXy%{Y#;n$cJ8G{2i`w(p*Hdn$f6--2p>6H{BCn$_fZbLmc?d5*75f6WxIk7*e^ z8!|XK&C0z`H17>JYx$m4F3Md8lE#}%&mAOXrC#_0LvjrI}v;m&8mtNP3()hT%hy{`>W z$M$?x>d;m{V?EXQX+7GqHcvf%XrLUBdx$<)lTJpOm(D5aZ_Nq$pK|sJEx%-3==i*+2)FZAppR;;*K#Q#+_ z-dZ;viEK39Z{5O{dDV_q6E#=roJ|@Z$g`TAWlkH7x1KE0$9_x`d@#OGukkf8O|$l6 zoLe<2UUy6rnR1VKm6#wbl{peTT2)t?8MW10@1r}iW4jvuT>h!}$li~md+D=M^le`< zw-QjiY5Q&1az7y)Hg9=)@5Ys~&;b7{R+2LR)mG>?SF$3{!>#Gt=Jk@x{EAfX>C(I& z^dD|t-*SD-PbfLmgT7tIN?BqZOIv8iP)*%ED#u!(x;7wejv=b)7KWQqM9 z&nyy7X?b=l5`sQ~6dNS$KgsI&B9EW`cKn%vS|qfGKdv7&abOdvtchXw#dl(<(Aa#X zg!zJX?JOcl7`}+~{O;isb|Z{jj+^|3?cfx4!qPE~2Z#1Iqh?0y{8U)&kc+6Da;0-6 zu&E7XAmwN@w>-G{9UB+ON7;DqNoj)c?O?7IUe zYWyd7VP9mYd9kejM6F{=4`Is4X1!Y1ZM}&qw&hUA9*I$I74OoTdglEn&_KTQxTLPv ze*#In9(@-_m#u-qyJ*WCjWf;(*u#=tjc97T!b9u6bC{duW8a;gnX0`T&urbE8R%~8 zSmX}`K8&w>T@+P>Le)rJbyP6*ASz5xrsdufEQl+uDKGu*oGmwq2ig;G0?6!lH22-cYle6F5DtA2t5jdh3p8ll_gbH>JAM zjaqWg*DSA@-PWg#iMp-l^JdKz&a3Ccp|w5Bkfyw^AG^I>ud%!j3GS$&~(qeQe0c1%ToBE7KD!y4&1)^V5CW2A1K(Ff0`uzaOE_tCTI zxzn0P-%wB3m$QEPj8V{U3QCp7W2O7vmF6%u@tC}sh`Z6d;kDxWmh9*z9^0vGMd?m~ zc-r{H@gMelGN-x)b=~zU?8j8<80UO;GC_Mufq@Xb#)ez)@Y^e0h3vd z(HQ3=;&;DXw|u|0eBnuy_RFYkyXxj!X47)sw{swi`s@4NM7NG%A`<4T+id1lO81oF zetSyeyTAuF8}pOe*cn-gmQHa182xteY)m${kV<}~-e(u_7X2fue&%sW#y$M&_v=GdB!Yx2hC z^f5YYz|s?c(}c-gyr^_!=5YB{t?L3<$2&Aq*K6>tFOxnrB%) zzr&q@l9qt=_dAuZ?bT=Chn}{&BzZ=l9r^Mm!oe+DiSS{rv2&^SwLtcD6ZZ!c((7RpZUwsol5BPuFF&}6tGB&y_hy3n(* z(i!WJ{DYzE^=)(SBJpA9dVSlx9!VG;t-d`w_Bz57>Su(9Fr&Ht&XO4D8t(<&U`7|2 zW0$BVW;Ely4Q6Op4zFzs-B*-1qCp#6$y92X2#k(yXAh8dfT zUKcaYwJOr#jNcT#j`7d2vV9+<&7Rd_UkB|6DMBh^ho|s~Bi4zCp4FXU3CAS0CZiY8 zQqCt9LXj6}KG~|i+u4htlj#y?M7d>a0@2RYE$95?=xvDK(4y40ZS$Ht`w=E*%X&4Y zEt0Z!ulYD{>TD>phajnU!dxAv6SNx^Am&ugTjY_62p;%zFlth9Ng#r=nLKq_az<=d13mt83XOk7%QGN zFkPH;$h~>##y#nMRr48!NPTYFn|smX}2Z^Q+Dp z!0G;6)}L*pU!(;I3$$I$3bpMVJ%kMy;y)5(^p0zywp33|Td1jK)z6zUGsab-ouzw0 z@MMi8Xxz4ruZa^TgYZpHQn=9d5MvL6pjBjdj3v=dEiaJbu7pk7eqVy8Yd`O&twS?& z5*9lSAZ_w}^Y|YX-0{484gNRtOwN}CFPkzJ+BPI()|8MjVkk#Wt4o>I^tW-09*ioh z_K=r@Rpe|nezQu_*yFk7a;h7CTLS8EYiIb)x+8PZ`i<1WQQ4KyJ2G89JH~PDk4R3l z&aWIAw;}4IYb`W_rWX5*&}sR60<|!=6+VE^tloMKftGDOr@KT(YHtx%>wEEcjFUCG z8}>ODX$Mv}pWWSQ4x8Fjb9bkGbu_F$m$D~LmS2U7)WET}jobL@CuS6JL`^Osubrk{ zXeS&CObw)MKK(kTpJ#TBR{vRznw(TOO6$s%?ULueT5qd!#I|AFyFL3j;%KhU`v~d} zVP%dVrG4eOVfz^RkAeh5DY7c+e`r-yTN~DG zPmawHYn}OEQPH_bSIG0ZNPoL*K3IH+zT|5R^(9`8f4j*CpGa1We{H!$PmBzqrRZ7c zZdkE+@^&0E*WqQx6Tat8Mi>v2!9pjMG$!oI}cUnk&LnHb$<3;%&XoTZ!fQ z+~)+EWK;-FgoG=%qSc)7WWYElnrj7xH2HideTSTdr(`*kUU%b++!LkissEtA(?td0 zk>j-tuh7u9%XIfiG~>XWZynFv4!6EIyJ(DC+}q-qd6l`qJI1ieTxw|7$Fw*j z-7b%y+rAe&X(A8fvni()zSpr?YxtDir`GAsdJ*#P-aQlR$RZi*`*~0y+SmPU&x$Kd zyYK|b;JeqRFBtLdxJ^5=6@WVKwE0i{+uncBBcDBqr$)!AF@5%gQHDn6@yk+Vt8Xsr zYIN1uxk#?s6pD7HZaJi@21m%enih34fr>fg((|iA0PEm#J>Y5edsv76)#edBSnq?D z>+iQLa$Vl8^$`vp8m~iN^UuKIBZO{S4}wyvI1}}j#gN#PFGn(vcqGy%ud&SKK@&!{XDPHXyWtW zHR~Y*pV439IL>;$({VfEkTW0iF+*ceNX%52PU|@=bOdWEn;&&ZOY1RGOJkf->!A_8 z!a7vn8#*_h*)3by)z9cN7bDOxA95ChJB>(-X4KaP?lwI_8}h3Wxz?Q8DQ$q8(nLjW zqJAFx7V+ln^Gw#c8j;o5#;%Yk&W65=wq-I~x*Bn6+sufKAt9lhwWf#f%vtN`bP_sl zo%6C-QlE<%NN=61K*pV?$RS1US^QOOWZUC{hQ^bS8`D~|Wqdxf4CaJS*XC%TOIYC2 zr|wz7Zh6O3GH%$aGcTVD4RAl6O@74|ZO1*fBXN)QsPE60qH|xn=+kmP%m>?y7*nhw ztdlCT`->4Y>Z0y3Ji_t*c4JOeXtK$U2#>_ysI!|c#;R3Tcp&YT<-mj?Kjh5qlfXFb zFXgdfy*53(*}#P9usNQfO9H8l%A7OCHZ6MWFR{p?hfSIq|4Wb&?Z9$(wPf6y zGi!S+!BNgy8*Fhy=IeV{Y|oeVjTvd^gKa|4%NDnkI{gTRe3~f~$iP`ss4XoaS*Bd` zN{{f&t}qEnt>b0T)$@om_Cb7RQOkWwlZ^-s4806|X;a$X$+%uNGiw^t(7JAUXo~R4 z{4&oqG$+o~N?zLwj&_D9y}ZVlZZT>oA3fG`a?!|}2vghkZuHuqCc1C`WQwX5tFhs@ zR>Yyd(K=WEBKis`HC^zGO& zpV@&H$crKrTe*mij0%w>6&^;$j5|%yerBIKpLj_4`UXrlzlxD$Ht5AV4a*Q}lH)v}TwxxWqh zqCf6!q8b!I4y8rLI()hCDeV(*)}Df}P}*Vn-WgP56zkKuE_F)Qb@aWFat-hEL%7rC z$52fd?wNOER%RWZzx@3%Tr64t0WXc>#>cKNXSr|UV}I>Oz79LBr;hxi4Q=jlHu%ug zme7oy;ZDvzfmGJoh>$#9k84>z$eU{;O0y1Yp02`&WpuJ+K7ou)$&%&G=_PY%b3PxB z$KHkGC|RSGORZZ>%|i8+c^cof!g&$_11oc|kpG=~36FSdEjdUEU*I4)_McZIfP6?z0O&AB+U znkLB4T%>2K%1(PmNJxx-Xhyj{yVkZ26=SExkk&jZh6Nax)f!YBUu6tEgo@34V9rLa zJLlBqRUTW`u~S4JUx+=RK--RS);QM27kjefJUg>ljK2R}F4Jw!EY_e^`s#B7t+lmX zq(8A6<2WzYp+DN|5Sht)6}w4)z(CV{kx!80SZ+7MJmQt^Mp(nKQa|ue!y4oeZ?UA8 zQ>j*mmTei|&)7BW2d<)_?V03pnpiJJAq!K!&a^L4V6WvdFd(1tJk&sGaW$V+-c)~% zZ{4zWGVQ3?kL)-zT~5{QJ9CC?5T7|mx6ZXQ^tGw}1f{!Z?r)q4T_sNnt&N$Xr9*kS z=1zWNdOAJwGfsPQd0XvS3?t~W_`JTB*ZF)16eC`ecN39QWO2;F$nte1%_x91I5U~a zI={Yjx7UqdFKYo`YvSTsZiM}}tTp2?%jAX|%W@+SEwDT9vp07l9plA1kUKJe=MHl3 zY-EVmI8Qok-=d~BhU5Lp2CcjL6RofI+*v;!sChdJHp;af?3kjF9Cp;mYgtxp*|)PW z=HQV=yevoX?84hIPKF<{YU{bRf6KR?=XGS*977BtlVxwGIeqtdJ4-IFlaIn#{oxGi zn9h|yOA}eZ(p5*SweTnci`J7vmetLzaM60Dv+t=Ar~_vl0Zy?BN%mkjuZ#3L3R7j8 zxHxJn;ad&q4Lm`b#u04Ydeg5ZZ}i5V!{)6-x;sFS>oM zQZMOyw2U?)l5vkV_NpG2Yu4OGo1($c`fXD$=SMMftp{jEIP&1yYr5gRbuJ`i9af@U zaiU+x1NHsZR5siF!nKf#rsP@LMJ2qSzJx*-U$+hk&GlKM6@4kK%g;6a5z`?TW1rdl zT#ic1bEYp1amG>gYLc)zSFEAq=yCROWqCaf9#}`?%rIAK`pa>pS#>s|6JZ7Yy&@H@ zG=7b9h5Nw@MFY!Yy7aM)-mG|DY-<^-`me*Rvh~!9t*X6BDBwsemvd}p%Z9kV%3PdP z3VYL)sl{^{u8p+q477{Zhi0>^k45XYL&LKvrxm(zY$l<~aP+0j9=zp0<|b`iWnBp4 zw1g@T*?0R^jkDIl<$Az(infeZ>yH8G!MGAAw*G#niWZ0LTHmvPhsNu` zFP9og!3<~&6|5bb8YL37 zF3hm43qONr03#wouE`B!7i}%a{fx~sm2Hh)?=zLn%1aZG?2j3Zu)<_ijO@+(>bx5C z(~?lrBlp>_T-0OECyuB;WHn-)wnyxK#wB(77?vI9tUGu27#3RCRxaXqTVuF0?5QO- zEaQ+&bD#07uE%_gH~kY$u_`ZQI4VqS8D<8H*MuFAJ>snu-8`}*Tq}9YIJ>h z-sfVn#hkCh7N|O19OXQ9Q~>19hyQ{W497hBmbE`kpGS5#9}!49u*#-$^hGPfeaY7! zYE|Fv{`FjubvIq6h_HCh$&$E8d)41!?WIlY3uJVa;{l##kfC zBJ?~qL#F9;$b4F7E&>WNzvydqUD@owCP`UGbb>yF4K%v4|61fZtOrCa_Pch<=M!3X zYhU)etx=(&@>-V7RxhY*kp0{f@nC;mBh1lpjacV85XKf%AL6`e>F<~2 zdps>O%$4P(tRIuIzn#Y#9sy?qx0(oL2^r@H6bmeql;l17CT-o1`^b9)+_9J+xfN5T zlG}gEmp(0t!+hz=KtGnVjj_LtmgRJlir``tj(VLoEl^>)_VXE?Roc(tzw#)G^K7L-?>zp8T$p;z=+8JbJ-6X-ctq;E?YEZgBjNFT zq-7Z0w+K7K8+vgD&AiF)NQ-aCoEFFH)A1(9g|Zct%W)xRDVzB~^K=yrX=^yNHdRBz z!!`?v7SATKIbF-&*GM?o_sE9OH?(vreQbJH!|2Pi`1aU`(6@`cUAiqBi$y!;c$^VO zmTj3?*>5f9HyUMZs;dvI$y?WcX~cC-CJ1dViB?yoZbKChAJz6}|wk4M}w&h1Toylp4WwfZYwvG|C>QfwWPNLSvTV!i_9D9TK%*8>DRL^cR65)C=wm$gB&V}) zW%=)A_vmBHA?L<(<9;1S@)2?%%&M(No?;jq%cZH0Owcg!-@Z&9nW7TD)11D0?9o@c z*BJ5}8I3U;(X3)guJbi$Dj0mPOjBv(7w_x{*<8nyoKweX5hJZL9^33SwljN;v7*uz zH)^%{oXP%1+;%4QChUX#sEyvpQo>C*6FLg5hI1z3;<=v3aP(@bXl3#cRs3ya9`DMo zaVX#U28#owu@B?6AO6{rjAt90dBakR6FXpp#R*-K1T7mUl+|r>aj1PsSy=PR*+53s zuiMg_QENSOv4=3+`r^5S1TCIT@WGfCXT+JvsEblHty}trXH(91ykPkhL@xb|cI;i* zmrKv2G+O9;+)%+9BJaLC0=?Q%VkfS9;~T>V(afWpK%UZG@==kEJ2YY5q*d3T3%m`*MVO{yI4eqW8AYS zjb-U4WTlVb=Za>c5yrZZC*G55tXx%7LPjhTu{%k9+p@U3>uED+jP%>@-t1xlS{MmT z6~`O-D9qo6w|7@28UY0?w~H}DS1gW3Hki@2K~ULtxs4fd*7m?>>a6PqGoUe4uy$-P zW1X1M_cMl8_J!9s?q_UP_H{7>pJH9{1#yCT7>E@88I8K$Y4g51ghD_2e$(O}xzB#( zq8@WTaqc4TQnbd9;E~4l~6`5F}8h+LKvyDXNaE#GKzpGiHwwb;v`E=dFTPk=>C#pWkR_ zkvHAt1ybCVuxZ=xOYn5<=l!&GXl72rnokWa!vBy(^Q`I7S*vRBzieG6GG^%>mNAbm zWQ-WfIYf^*q_tMc0(sj#g!J2o_nEpL@^Y|>oUO+1=Ke#b-iF^{MNE@rC2D8*-CW^j z{YEbsy?iFFYQV7v5d`FujNW^A;Yvh^GSc{a6U z&*?64v8ire=DmTS`?xnygViDDL%+R_7)+91Cx_VY}V89HpGkBbD2WtXuy1p@>Dsd9m4Z<@nYuTPL?p%wk5b0HZ2% zY<6b4Re)G<+K2zDT*+&WY7)`Oa5YKaE?c?U?77l^#xE)q=7IU2ui5$A=6!d~R!?z# zldtw5LraJDT;V-ej-1E*iFL%on>|UI;1oD9?GmQ@`7WY zQ%4}nwwzlBZ>+HP=VIGZpP}o!-`#fji1|(@uVs~><#+hti6Kj}JcDIxzt|^7r_D;x zRIQWsa9fUZyV6@e_P&2xv%^QM^xSDqZ+7^=2aVbcIYUXsI44S8DE581e;mm9R(?C{Z~izu~@XMXoDIYqrlECV+*jC5G;HT8kdwaWl+Q{XIvp{OQ{&=BWFj6c zvla|})7pqb4P43FghkPDxsJ2=M$X%9oC~_AU$G_d^&0UF}P_$Wr<{c1WF|0R3zLfpcabIfs3Lm3% z-{($+k6Af33O@rJi?j0BSPgA1*~UWU<@_rAzdrVa6<43RRoTru>wLNVb0Xb7SE*=NtRdOK!@!n0yAXdBx)FRpetA$#+=E z>GSnnwC&Orjn_4cxYnl_oHIfNJ%XFfdU?|~GwS6c{AP<9(Q4VNW~N8|wlk7Jk0Hq` zr%+q2*Vl4$PD7*a>kIEBu@zjz>-J2z(^g>^6Ux`Xv|C4tJg#Vc{ayk6TK3o5Z(nnG zYT5D;niJkaQ***1kK;&bZVX-q-nwGp(F}QRu`fZ;D()HfvzaL}s>q$|hHFkj=-pK< zhnmDQoA_Sq{Dmy*$crIK#)-u`6MpEJwJFsZdJe28)tPBgb9ZWo>e(CZShsetiqtkb zw1cyu36@*x*!FbCZAwl4s~P>fr?3!wqMo?yieY>ZT2=1AZIxP>BjcGkVkL88T^13RzuV zPTQJ5>&CXR)?s!Zy`<%5A%xk0bC)j3q{rWpkrtwdUnp-+LM#hrO9qTDMmkt*;iTwCPV~F=9gd z8B=kW)}t-A4tFi@_1w)xTKEH{kyc#kzGF0MM=>`0F1Sra1o3)+q(ZhYN!`?}<7Lg)E}-VSAKtjput zQDd>ob|Yn!fj2oE3G6ZA#u?4&T&c%`(at3ZqlYVFZMz2*gDR#IXQ5~_L&`Z@D_=*i zzOKGsTcEJ$>xfVK^EIB=_X`ay?{)JnvuU|(k2P^oe>p4H+#AVyoL@u5GiHt#$2EDg zhN>%3=hhl3_-maG4GD}8a^@tpd`(DBR!eOTl4_k8m(-2T8QPhzEy2sJ0h-?CM21b) zoLFIFb9SH2v3-p^>9EbQ*D|ij8=KSCSm+UmY;P>itmfS|y}B9;(7bPvx6++YJmX%| zBe?{}0E>Fe*&Jno@p3~}b8!x%b3fyfT4Qrc^Civ9l#sEVFQIxJydRQ=<#TVjUCUN` z%U7QlysIv(x_wp71wuHd1UEe2Mcjxtqn*v`q1)QPtot4qXB~gpK9;YC?Dx=*zD!fM zzI?31>UKwuL-JVOI?|%*ED;KOY4qiX$PolUm-8#`xx#Y}ZO`u)frOa@;}W)e_ltl^ zF-L3Mu%))_Euu&4#<+VlE+l_-X>DuTxo4@*#2d9)`xEkKSs^W0vg{eCP#Rv>C2woZ9oH=|b5F6V93@VX4I7^P$5AzmBJ%!k04 z)iOlU&eSdE`5XOd+#$p6Kcr6R;ityzV{o6|NrPo;S|{qCZa=J3-nV3QqUpGGqRl`H zjVQlrhAWwatd27r9#5XH!FA6*t`~jWx4$fR$D{7I=n1(p{*gtLZ`NEtGBk#^7P(#fd-=QkZO9k> zaWB^!M|mrW zx!ZadJ)kanA#7j-!C~tSXZw5oE{obQ(?f1v+3rUycoA$o9N zYL2h3<#R2wg+B%Lk?3Ka?t31_vc%pOG}79` ze)QI~ow8ZtJUXuV$eN4eJ7vihTY_cn44I+DHnIe9_GLI5xvao_co?{-=%d?yNQ_Z{ z>-s(9qXAkoMvG79r#_drBXHi9zUfuPsGD9@&~rKo9naO~WifWU4BCer<>_8#NuWpH zp0AQI?IJ>n-yGEMqEl05K)JqWzzq7B!`VFM1otgZ&1{_QG&aMMJ?uKyoMQc7IiDgXC2Oj&Hu8%U*-?5236kEY{ zdLr^RqbDe|@k6`{-E^_1v6>$ePk#l<5BnjO)ty3laUMTJ*~4K!q|Bx-r?-8S$lKsm ztU(^HjYPp4@H)6)9L2vdLhKZ8a)?cK-PT|y(DQ7t$%|zw@7d+8G`ZzI*N3vMu?Ofl z*Ed<$wzqYzWnGaP>;JIc^)qLEzokxAa~@^B1{JZ$xTH>(ceU-<)S$v^tf>gKH70NI zY>8wGh&UZf*iWtLF=qpt2)8&-67h{kl#5wvWNbVNwT$7RyYGCRv&=sU+phR7=hgSU z5qdY>L;F|pMoM_kSOaqusf3nm{55Do-o(B`_&c0)4A{;%c*cwHBxpKyd>YbkX^%6G z+&s!f^ypGNGVZ}qXkl-|@?B2xeh-XV9`!oLANsI*>wRRP&SB{bY2mCX)RdOk_jz1e z&g^q2A*prJ5>hur>GGEQlqNz94KxNLiFrzg4qHZ>Jn;yd>p(TzDJx3rlIz8kUN$Ek z+1Ai^C?7ovQOY^l*7s<~9B3j;ZQHvss{}QXNas&fYhEp{#A+}&j`z)qtOJeK(T?HP z_3ee}e)h3f8)S5vEr?V3{ElkGmu#`V4eKvIi>HeC9CHMPhex4r$@k#DXssT*LLW{o zL>to2p>gP2dn&$bn(R~^@&rn4kf&~SSr;!?!G;a)sNU_|+y-}yAI1jNzAs6bbN1p6 z*o$u*zGZ$54g2Z&$}@#JIp1Lw4L-IDYepL_+ihA#d}gmSw2ZUpk#x@(ik}tNj_Dcq zhwh3d`N)E-iS3^IaUb~{PJC-0I?l+0Ue^0()KkXGT^pR+dt~{s_hUr)!RDG{#C#^0 z+`F$F<0Q5rV#zU1a^)B=nWD$jsQmHo9Sh>7}S&A1)SabjDF$r6THj-7h<;`nj&O$_O%Hxgo zF|~-9w*;&z@wn^}_)KjN>&FwUiZyXDw*z@hy`8~cMj85+*hi_XM-c_8j9-G_sef7CPUefI?);#1((XAzI zXEcxfHO@wy?eArNE@@sM@))-_nukU#vZ;N|JCrOQ8Z3Q6x``O_G4R3Dc4r&~YdoBY z(ZB%p9#|7zG;g}JCm}g##~X2v@hHxy)#bC!?sw{z%T_xsMs=?$fQMdD&|m*}DDm0Z zzQFb6pSjdi#m(n+=^^mZ)Z(mtK5H=N>_0WHGtU;uaXTNCj}Y9J`&^EW`R5N9Kkc@) zW@xn+I_7IVnw-VLzQmQHK|b~*M)j3By-_dcf`){rYdKlWSKm`7MbYl`J?+L?F)|J% zVm$&B8eSzOnHyUFq;FY=MUEW%!AdID1qerkT*&lr5Be6#M^DHyvc8MBAjT-(4UIzI zG79b@J1tFaj{^A_9)-STc04HzF6fes6~yjcv=K-ujUy90_}4dzH6L7oUz8#`%FCjAtP~Tw}_6%(P=3 zmwU|3D%X&0!uD$f>fctq8IAR0rFE|qI5wk+_|^4gMQaA;zP8yx+hxebvCar@iCj%m-v%hAM=wW4bes4HvK@! znmxq)eg3w2U*CVM#Z5=?<9fQm%~f!dynr#zxC!zh2SPq;3ci0_tC%alTjBIMIwT-+ z66*V0$UrnRl&jc)ent+8(IPyIj2vezE#_d?#)J+xtxUg%d}eIwN?J3&W%*?FiRY%( zVv1~dZpu>Y*)_9XLE&a}D#XiM_NI-t9#{wR>!p-A=+oV2uw(RP{p#Xvljg#C5I1IC zvb)Rj*~oUh&s-wA8q}L^E=KsKgtl8>JeRz@=4lta8=B3s)h%dc=^LI+Ip6VdkIl4K zzEl_O$Z&~LeYup3ExSGvoL}6w<=1rVR)g*Pb>+G5yVD=7aHT4>ycw}6^;}`pio6qc z-}kjqz+*d`{f0V8XzQi&f}&W^BVSkJSyW#+hKbYLY(^RAp}yOEU964eRBBUbeJwMq zK5CI?jJaC>d}a~G=X9bOyBht6IBeV*m-qE>*hn#C4JCV1AmaKs+^0Wi7AUfa{((X} zt6{9Sws!Ak`nNfo_bXRlpWn8oeV#Y1o;0?NR-xg6xkEN6a#`a#d1hnRWzjXB1RU1u zh-?<2Uz_`3ug2Oo;*GUU#M0+7J9!(IgO5$LwLb;Y2L_C3c5`K?MwE{xs0`YVDa{i$ zHQc_|D(kDI1=Hp3BCiBh*OQ}zXIS*;i@%2Z60h=^D({QWY7(M5JWgW7+V^5n)g?B? z^Tg9;zYhDl;?q$7`c}J!AdBRV@o%v?(FSrdJVSlUeRv*V4C``PC4N_<4awrrIP|Uk zbocB`Uj8nB8!;FCaWB`0oov4O#b>dowpQV%)zV_H_@zchU`>vQ;ok{(u~1s3G( zC-XJd1RkxTe{D+9et1yUZ^@KBr&@2a+e55=on{7oOofj2i33w}-YQp`595|`J=_jn zO48aE{>*TDN@>dRdUemKEm82$G8^2^Sx~M-roqK=Zm-vZS~jPWf9A8hEGV47W*FtC z*m(;J25Q1PEFiX2SvS=Hk&$5wrf<~-)(ll_4bhKXCzQN-%f0Z@^g~vSBW%A#)TVc(7MwV>ZsDn`le!F$f z8jXbMHE&&MBO7fQuL3JfDYw4L_>o1>V~W;uc3A$I@Yd3jua+R~Az7YVu3EyCA#Kx2 zi*RE)nzZ>D{^l^f%kusG>X*=BT_dOUkUPtIoUu=6eGpf|D@Ot(3qx;#wF$h5osnoVXvK33P;IeRk$b*N)& zyg?oKJdE#cT-cxvwr`V*m)PWwM&UU5x+DrzCQ ztUn{u`lZN%~7dHh4h!xFjM|$0d3CpSd@!k~eTfbgt1qByf@ZH{X4=v+@u9 zL&DW}J3kxWp3M;e@-JW7E4OkQ5pidJ%@fpcUL$yxuQzjTnWwZ{>&?zT3?pCAb5ShZ z_LXAy=qcLHb2==Fv2Umr7ONe{J>DAYQ(6lnd+U5gPW$rJkyY0FwmCujmiXYslQ_ zH05<0scdK0@nVfy&5S9Q*4J8=bJ_LXX_1+=t=c-Un)V$rOw)d!pEXaTvBt(4G_Jj8 zmY?PF-L}0(rl574S-sX!OKC@88%mF7{gCNJkp^`nYf?Va;EKR1d#K29oQ)cD>fm^iKRmj8rb^ac-oTiJkLSXqiF*Fe z)FLo&g!Cl|J|H1Zu^2~i!R2#$V0jqJAj9LY;RJu_bsRUFOKPsw>j4YSX!36AKoB#x==EtkVA-ya8BIKmv~H44dChYQ zLaJdJ1%8PBr7Pc%d}j}bTaPMh4F~c&%9x_Vy{$4A$C|^fFP=*c?Homo^=I#{o-@94 zxb<>c^>qPF@8ce8dP0`NGHNB(;_OXLr9D>JjIHwmBSHi6I;a+~;ysh8gHUE82{kgUE-uJ)%{m-8N zvA_Ezcb`9R;_>r~?lb@GmbSQwlMkHV?F*mSy^zU$NIE_&9Uq>K4^78|((!@mxK}#v zoer*fKsp%T1JiNeblg83%>IMYaldr@W;*zBN7)g5aJt}IIwSh8d$=uiW~wj(U*wa| z-NPkYTQ}=h|NlqM@BX@Z>+XK*W9MHyV*cALGG=}*nBSnk8vlRXzUTkky|4WJTR-T= zmw)H`9`i%nkLomV>HOM1Zrs!Q_&4*GzhnOUHxpA^7x;_T$;KZKnBRDhdC#zE_QT|^ zx#Pr%J(pdx^_uy)`_C_W%>3^e_h;OE%FQQlJ#p&l>u)-7>+#vy%T7G^_?@?$YJL8x zd0!8kH*=bP_nL{)*4D4gFX$22vv|k+f)~vP;1>SU1N#2?hnLSUw4}Uje%_p!b?A$H z@+tF+o;Uy9`}L#qGrjSB^}M^c%`Y%D5#reoQhw@=J5OwRChweo;VVz8CFgz7pupWS z@2^_mZhPjtKIxrL`N==J{V(tH16RNLcVAj9a9=y`*+ZO9BYq8jF~6iMaNxo02fcmj z^RGXC%bu%_-+E#rb91tsH8S`8%gWqKzWP-+zWzrKU;bs6-0<1g4LsZ+-rq!S&?xk04+l4Ygtq3^i(x{r9|&maA| zhkw)`e*WLS@|UZn?xj;B-N$LlTU#HUK0NKj$(#0EdE&MccO<9p`M2%4;^y0KK6%rL z8+HQs?uRqAk-$O;eAJw6)wcE#-}kML`ii5^y8kcV^XfOAdjCJ&QZ0cWKD7k4Z0)7j zUw`MVd#<@TV`~pvQfI$sqc|^pyy(Ei7wtcI#HkmZIC0yaXWVrBR}b`J%&nk6yn2iUUWETzuJq!+Q^2df>?ZeS5DsbY$Pb{d@Occ5s$- znYX^N#FHgm9U(}Mx;b>%@K;FnOki8(iu5+j(!@>t`7PPLhi`ddGeH9M zFs;kE@{Z##xT$`Ww?F3R-u}k>KJD_sQEqL$Y;cqhDIF!|`No^llBa6spZB8c zFMr4L9yvVNCi6dXE<#?ybXr1gOd|8qbFt}t$xY9kPwU$G@A&mu^N$wSg^Pav`p%<2 z`tm0{@|*tdtyh2jzg+w4k2fW0=e(f-qEbIIAK;7Tzn?JwZDjBWW&@(MZ7bC^I(DDB z-jKcfuCwmwvl~o0BhpQ9ynQ~fZUWBf$bYfu$mlUnH(YO!_%=R9iNnrPfQ1L{^)doACw3mkq!#G6gfU79S=*#1?l*N zbex}#N2cSU>G;@mpv^G!ymYW8&WzhL=l=Grr>!l>I1{Hmd(tO9_vy#e z;5JU(BOSlb7wHG^>@MTtoY!aBh@H;a(!kzycuiKLPts17HIp>g=fFyyh266DEYq!* zNSV92E(aHKEbJ8eGI{-+rteqHX=_o-by`%%FC4)3tSH|g_IYVQHe|>bKe<6b>`W<_ zC6y}0W;qP-WoGRTt&q76$sLXr?-ov2eb4C|61{(Z#vqaFd$e}5+?20P)8WUMmFspq zThD}@y~+}siDihry|w-R?QL5dV`;8`WOOJ?yRdgIkXAwX(*lk%+Y2utqluXSzOc)l zK3ErR#D}`fglu#<3h)CeI3sxa4}15e^8uZgKHq2l8JqRqbnt@>`@s2mY}&`oKV#z_ zIJaZiytmBHV*}qh|NIH*^N-FyUywfk&-rI;=9|;O4>t6Tvrn?AZ<>DwbboJtJvR5j z^S;2yFPLA0P5!v~d2IBD&99&Nrt|Zkn9hI9{4+NFruj8{(&zs*|BTJQ-+k`6^?OP5 z{x*H)Xa3df^J#HTe_?cOzirRq13y33yh*3@zZWjC&ED_>YhQ9m{>C0ao`tlX&%U>V*^53T~ z-!b&%m!~h^Gyk$X)pYt>KJ7ovshj!oi9hz@kuQ&!{O_4x)SK@=rM_P^|I%Q&r!&x5 zJkHdMKU?-$?k$KUtV%bxtu6My_e zSO4p)U+ZCVN!3uFIB(SRn#J4iOedd^4(#kh((wc7^QWfcqtfS(NyqEb=TA!q;n30a z`|asCl8&E9$EE4`>vU94=~Z9&*L!bx@+*Gj$KJZ{)ldJbSA6x-Q(|=doSqW;{Tu1{ z$#j50Pf5R@l#a{N@$u>JPfx#pDjk23j)$hd_om-}k`64-Md|p{bo_KWo|=w*>G+#; z{Bt_4PS;+Ojy>r>=2;r+bxZ~E;&x%}$Kf8OUl{+0jj>mT~wrHASW3DD&;$7)Cf%n1m`ES$j+tcy+>A*2~Vfy{zbev4bi_*b;pPh~y((&wcJS$yu zaXNs)ed+k*bbLxW9-od+OvfYBaX~tsm9BkM`u$1iIFUYsj2EWkSo-`!>3CfF{CVm3 z!_#jp&rRugMEZOn{r=o^{9QUeEB*c1>G({J^!Lr__~mpwCmqMraa}sDPsel9abr4O znvQ>yj{lX8=cVKI>9{o=x1{5T)A5+p4p#B8>Gzw{Z>nO?PrvU-$D7h|ApLzR{k}6D zFG$Bb(s4;TcQ_qCm_9!<9dAg-wdvTK&V6C}{j=$KNjiQm9k-?9@6%!AxHf%m|5VHF zbFRAb+pc`-!Aqb0)9?8DM|{N#eqw2X_>lQPP74Iq`?u2Z|D~gPSl9jfpMAu`ul$w6 zmwxy0Z@l?MH~izY!}{$sq?au-tT!Kj_dmVyX)pM&zxeuJ{f4jpj30T?(!;t>>Ybm{ z)JojmdRICCI)1L5{onkrnua$$;KOhEv)5mE)pz~l1xKzs@@p?$daxeL>A^lYjq7*P z@o&@dIcen2PRGxu&tH^|Pfee{B>n#4bi6zr|1KTBnvO3`$9DSe1JZG6Iv$t){`cwl zk#u}nI-ZcueOfv`A|2IJ{pZiP_YH6T$G>{oSAFld|LTYS@`GNo^iGOX`$C32;Kc(OQF&+Oo9j{EsuchNF(s7UU9S-$8*y0 zlyrP`I(J3-O?>jCbo^NQ`;v70c{;u!9sfNYUzLszO5c4``u+c>%0F+O6~AvJ&%qsg-X|$8~9F*Qetb)8}tV$5YeitJ3jT>GO}LX z!QbGhcJXCGUU3 z(!=|Z)H^??hxY;LkN2eGwdtrH*7m!;>hO<0dGB-n?GygtOYVEg*S&G+Vc{3?^Z(ep z3cx6i?jIyjq_~z)f;)r|EtcfsO0m*VAOQjil0XP8xxxKl|-NoSh{sXz)`^~&J?~S~9BfF=F1v&pTM>{Mr*_x8gM>W zJCBPMMx+zHTRnK@ z;OUXP_Ik^ei#2a}k@$PYTM9YZC#`Vk)(Ew6tRYFe+ZYhELE%6ofpP?rBA7w)R!*xX zNhCnG;!3$Z)iRg3^SPKHfqPC#=?a^p3kJGi{6io)a5aMjros#o3@z}b+JsBzQAj?x zZ4x;TM6YJ6C=yClf@IQqVKIrCL{+GHAUa7zEwQ8O0-cT%G|=NjfQ}O{ogt?-l2BB! zUo$lyaDh;u_jQgZv5dWP}#Clte9_8M(mIu~0CSkcA|+mXqYLoCGG>48bB; zGK6v3iyjG)Yok;RD41zpfXUS+yiHq)3jG9SUV{DEeaqU4JsM1TEwT2q9RH;lPlyN| zAzHRcLiA5gFdU=2?X244_)&Q--(E=R!SI$`ukTxk56a z`st~QB1X=YXQ9fKcxdfB^%~Gh+3-O0W|q0u4pUcA((yp_JQ9+pE~DwyGa;@UdlN&? z+OjnV5tWaW8xQEX@Vqhqx9Kf680qLnetba^bSgc02+-$58J4LX);%iLJD$CfiI)eR zMvn^t`do;&33<>l^f(cq&x!b#sTJ3=n@zDIQbABJ0e$oqDo$ugOp3MPDw0qB{}rii z4%yYkPk>bXWorAem(bMa+oXxAq&iX>DFOObX-1=ffz@ji1n6@jS&cMOY6OZr1n6@i zDdncsrlgdfH$jd}911>I`<4RrDB`MQL&8c$wUO(EQVQP6Fr#ajTUE-6U40VdF9yXf z0aH2V5-^AZifLV|tTbcO4dq-071@0Q`8&405OBdCYyj4L5DKzC`ElW>4))rU5X#db z@K9)@9qBQ)+bV90GE$K*#^=LQN_i=%0q7*X#yWL`1Zn5MxD|E_CXw zfPe(GEW_;1K(HiPXfp((4dnTjlVEib!HisJ8+eYELXSjgu~M9(OB`zqM7Gj=vTht1 zR*(^R0jp>s`BTX)o@;tod`95O=w2J6kZGF`UsI?RN{nj?HHB>)1fIl5tD_Eu1ziN5 z#7Kw284hZ!E3{O4WGUo?_9_AI4WjAbA zter7L$x@bN?5fa=m&_-?=$Wh*Bv*69SO~=B2N&h z+k$8G3QEXJDis&c4>QJG&=|$V)0?A?M8vZXZxg(iF$&L-m$6i>5-W<5(x)e&+#*}53(rauPLJNK=fi(VA_QY^0t(8JP5A^|j7K$c?i^ohsNNGRBC zCBD4C#k7QrB!l#i;Jr77JcoB+)Yin&VqeReUjiVvp$H&;Mw?1pB)x!+F z!ODi3bGWvuU0Dx#@-kjydedBA{(#(0{nX-nuQRuC{X zAm?N3Hc_$jBdk;p2D#9z5gaiFYDa6Ho3;&M96>-jDMKF6mYba*MjFC!#>r;5tT5)D z5(B-QrD2jLZAuicc0iDg0^5z-K<_ArUf>i4%OD(ZVVnlk` zqOuXB5|wu>XkG+Na>FE2y_9SWmdNmdqN14!NNQm&BB4AZ{q!&nB!_Gqcov*-pj6bT zmLf|QkW)$HZT-DmfiP53TjBw1h$5cnRqDP>VW5vZO2Gz@Fj5*GC|jGcL(ujY^5h|; zl$Hmy?T_pfA7i(XNo!mu-YglnQzRoB49w`fWlJDE3*kAY+p_5f_JD^e^Au(BpiLuv zVn#xXKXYZAFFGSr{8*+M&Bc}r$aHftL@F8c)8Rll8$LH38RSyP{$;sEfDsF5YY03U z-3zC1uUTRo{^KZG2hr115s&rHa2UQ%|H1>sbZyeS&BoZsK>IlV3L|KkU|aiNwe?QGDb}U zSF|a?`JAkKMOrCN5gF~+ij8~9iS{aZ;dD7cOeH65xkku>QN8kHbT4fBwB(GF zrwEi7SLC7#N`7Pua8eF|Cs7QE6r+&v3&A*ShhQcdUxu(;Jej;oD6!)TgeQStV<8FD zwvdDwQgcYCu!qVL^SKx)Y$6$EJ_)aW4)X*fl97U3%qV2?RzVG&QXoMtR#YXLKVM=g zSV)2`S2IW=STcmM+KV0uk!zz&XoOLa662bJMhgXb zr9gsm!_tfexqyV0A&{X7!Dzt3(5ProD1gD>Owi)tu!Uq_duy`z`*bX8c_Z8G%ZAo?6LAJ!gKZ` z6V9hpPe#dEl5&N_l78f@iF1V-T&_F|Rj!m$|KJj6rEC`Bh6Mns6KLo{N;>LOQaXbZ zXh4meKtuP?<3fP`VH(Oz^3ug8(9nwYI1!-FiTE2i+=GU#$AtiWF2vh}JZSHFoCwh8 zMEr#(&_J($0*#npAx&vM)K`#PTal;_7+*aB2#^FY{|web#s@*+#RIBF0aL7`gAfGh zD@~FZsRXKRsR{mn(_+P_f7p^5fl@vM=$EppX{pYHp_&}o9|gk`Xv9^?hALBP^&4et z4AG<%yp<^yo&&9ucJ;2xnMgwv=y*UPrYRbvQfPg4%XDnbFK!CRQb<+MgRaD!An66Q^y7#lUDO0nj zeK~v8;aoiqC_PDN7}zp3eHmrr$b{$y+O>*XqXVH{GLl+%b{P{&y(9$ab0Yp_SfNC(Vk(Q9-B9Gng2Hi_ z_PYe=GR0(3NrDO@KtEFwMQQU?URq9=-61HPcp!Q%6H+1+i-4J=LI@EE&=-LOgWma3 zsmOy$QDV;nx=i_k(CH25Q7=;hq)f}y^oxqq#KpyT=-IM?cF5)60k(PKk^zU;)j zjJ=NW*9~MnFgHX{`0zmV99DSJx_=$$%0dsS^1a&cs`iM9slo}RNr1jYB&SkvU#QBT(h%3_TEN$GOBQZKMg(EP|pp~+NbZ(JfxtcX5S8=gjhfpwAwmZ&WO(s z#50gk3JM2)wRM1HWc3-Rmh6v-iie-2r=h`IX%Hkv83sxzXgOC&K{+A?t?r{_%vzsE zo~bNhowH-2gjqI9uw{4nYok52Ur1Oblp20_g#0CnD_h*6x(dq}(*5@zi>Jj4vPrV? zQfGjH&;_M&5(zp#f*B-q!jcYU@Fb`#xhJwaC6@+Z&BA!?MU;!Wm(oI(h(t~+GgETm z_bLYoaxy_ijeLlJ3}!?Zl-x)_I?=)xgDxi!D*YcNC8j z<4X71BuakTWhOFNQ)C8|7*{e^iBg2A-)bhs@*K?UtY9}Zt^AM70}~Z# za=-&@LUz|nK3#cBosb7U@7VEnBRL`Uk8&V@@;qR7kmbYJ+IdNtrLbAdgp`@mkxPXs z4@g6coRAJBDhYW&n^2k%P`^^r@qqR~2Ca$nF}gFYyjH3+t>9^Rrd5~|)}SV$knlH? z{UIQwIqFD6d_k~-q>UJ(@ElXvr|L|rlKlWF4{a{GHy`k9L}ywRaz3FX0M9Qx$8yG9 zKGV8L5@l*u0NN6*C})j}?qDfjk`hP0$|QhnCxp;CqSP-Hv3MYQk+zW~9$+nvowATB z90`~xQsGKWc|b@(y;8}82cnmdru#vcW{oh+3MIB9@ti=2ifM6n{5S`WDv zQgYh zqDQ=>BqQ*R1#prkdS#l1wDpaNkMi%=AwDuTL0cOc1q2R zGiP8FA#;jCeXxKF{<5;abak_-xa54LOtZ60bwL@f$(yBu;YrfY0VdCgY%`yW5y6Or zthX5?4P^bu%<3x#ZHR1DF zF*PC)m&&5@InljPL~2rG?kF*?Mp_~7GlQpvBwaCrhWuBXT@~5BFZgzPpH|mxE$j!F*w9d^|n36>SAab*ngk%$S3H97;CEXB+ z%K`wgn~fMlHyfzR%?4!XW&@QP1)r19%|=RPX!9f-vP~D;&tM0x)#5fr{L0 zg`Ce%5`gEIDmPon!azrIvynpQG_x;KZAntVX+}U2q0>xWwUP@D2q~ynDil0m=w>U) zcu|CIHd0Cv5SRr+HybJR-E0X-;i)OUqe+Egx*(0X*~rPz%?2uVvk{|mvjM5xYzb1i z*}zn8HXw2=d9OM}HyeaHH#=J7W+Mr_L<+o{o$Liv-_1sP=Jn~h*}$ZtB{v&@5jR^& zOXCgzv73z;ftwAOO2d3N8&oPc8;~S6xqAQ%-E4_c(su+1SWpOgKykB!@ym1V;`$o$ zR{PlCW7@|?3Nw9dRAL1CL&$I+o9rJyR4 z9wFEB82QTA58Z2{lva>N{`E9Ljz)Y${-rll%_rkmaOuGz(g{}wnU(gU=!eIpsC8hV zR{Oq2gp826CCXPmC%V^0DLLtvlaZzI#Z1?&64>)4ICvrQ-SW}9sByrDcnBA>ScRE0P^K(ozcD`%Su zQyTOEltxaf>6wy{#%*0fz1gOc4m}3}fOxiv7{l2nP}OV`kl}0-s8k+&PQuwHQktWV z#EmZqQ?pGad-8oGDGgp!0#r2HRLJ@KBmsDS+-y_NNmr=JNe57Nn%ro$#cg`WN8!NN zr<6Y|3j$KmA)!P7ECAE@?-K#DfEe!84m=af{d*~Evo@}fQj*%V8v1XE&}mUirlyfr z(n9x^2#d9ldJfv)NLWQw2hTYzHPY6CE6afb_reM5b*Wnf3i)^2MBa8kK)E+2e&qAJvldphOCGAD8y+Dlg+6ze& zo`ocFSGi9~J_7E^X#pME=Tg1)0;qOAO`Zb~i8T*sYtK#)qkHW|I0#vQ>mxDH%ULo9 zioxYcCLG^0gNxrIyr4Vk{7pY|&cb%1FHBr=7@0 zkwlq6C7_p*S#+?G0xE`l6Oa^!Cm`jCHP2$Hls zpxr^`yE2YKLQ_7K-FBv_cEyk;LJBt?FwTunWw%4&M)M93g~eU)N{#c4T@G*wDF z!i~}DpzXnXsSogNh+FL=lOPp0&5fX*k<~s#NomPP2B7Z^@G;zK-*Qm000PUr0g_R* z+NX#@t9<|rSNnkKZ>lSVBUluIL?}Ix!Zy{LCd5ZYB}i+2T1|QOwBWZ~ODIvAUho5N zEclr*jB>Aj8NzI#8Qbus81o2Olqh+S!UcaQwZbw65&!?RD=P#!D3e86Riu_6mzTCT zP-^L_knjr$h~Y`F2!wLi28E=74A7*FCn=zfgR97bLP8T?5s92uOQ9pda7Sd++xeVK zkkQ1KW>Gv@b~zvI#XvwhUc!^;asshJk~ybcNjEY}yr3!QMvf;>qSFlpqUe@JOK503 zd~S3vTpXcQ4)O^pF|Ji0oe~r=Q?-OfB}q;!pP!MEBogvTEg(sfr8k3wf5El71dXhR z;gx9AS!M}xGNYR5{b;;^Ix@YMkK7{UTrg*Wr^}Pky|9{zaH-6I65~qu+9;)(wM(8| zY}t=n^K5*b)?ee3&Pael){15k^mT< zga9g9n^MU6{3HQ*e%#uWwhSdQ#uCBsh_S-dKr0%skb=GAQliHP+7k^ih%?->2dbYQ zJq!Ucsx5m!sx5m7(qFFtWYKyB2n^RNfEr2$1BDpXdIccWdIccudPP-s2c>8w12Kl{ z6+p{Y1b+mir;!0MhU*kS_17tYNQ7kK0f^Tr5TjeCF#38l7xXmSjv~ED)4z(N3ub>Ggp$en_I=E$I@eUP|>k1&tjb z(SJQBazq7!5=jOq%=nzgMwgA z+a=KEs45koq$o8IC3_w)blQ+i(5P=iCZ z>Rm!$`kq4~Ll6)n?Gj44kZDmw*JCO_jN+x7u2Gtz#7g^tT8WUqFOjdn5OAe?3D8+8 zZDV$0s1y5RtvLD!vt2l`>VdZ%e9ykHtNsgjDzjMmg*(#noavvCL&nsft$ZKBL0NeD zC+ku!2s+Y#jpdC%%Hs-)I0K**l%lN0zPhkKRs_;31NaviN%X`EZYaGn;8*5o$U;fK z+ojJ^`lkKJ!7f$^WktCWNq*S{R;#WPN>QCisC$?}5+Sppg5*i)UYkV8McdM-5c3XK@-Hlq z${>zjDauY_RZK2_TwprKva2L6PamEGwpkuMw6hSZ1W7i?%>$AVlq?4IBqZaFAXU3U zZUFH7WYf(vGvF=>&2!<#Iw=<>0hBZ-Ko}9$Q^kGlG`i0pEa(1L#+qGju2HX%_xqoaD-{3NF-B)8u$D2;TL zBFnN{UkCTPj$U2s+OCvE^Y?>L3X<{^nY@X2y371LL6{5^{Q8Qj$dqs6;uP90| ztdxc_z4oG1ij%LVu8+piyRM6yyOV>LyO)oTi>sTbm$!qD#$Ds+V54Gdv|>oU|JI7h zAvbQCG$ z`_ZKlnt6Fvk2yK4LLX{XNFkd7o0{zYmjNx_`}qHvH!OeenYofqMvAa9vcjN!j}Iwi zmr>%Z9I&AT6hYtV3Xw%(OROp4Axl(s^2}|{UW0FJD3m1v!-zZl#Mx7r# zwY7|Lb=SE2y3}#ecsjYdI61pHd-^!KI=Z_$ICy(GyE?o0s%=YsMx(P}y7HBN8(Lek zny!&Od+HUej=(0%V^!f|O+~NFsMH~*I_M>oBX#Yb0Z1T9gtY(7b}c{@epHjZ1X$88ao8RPaNCYv?mHsn{2+aipt2TRV4FLgbgU7Xz<9DE$>x;c3} zIC(nPb*<~-;N|06$JN=%$$>XaALh6%=_9LTY-m9ml!FeOAarSX_c4KwmK1=Q};!q z6+>P9zqMkl8@C(hHZg7|GHZ~w<94pCk7iU3{MUa}%~e?oPCPJLG;Y^sxmK-Q^x+@x zJ^bg__8$0Ey`8^`uyh!=Vg1xWZ@&GQ#h(7^)1NQ2Y96}5H~*OL7xiY2kLjrn;vxUI zt*178v#@>e=#DFH9(Ic>FT%)rfJQeSIkRT(P`9q5o12fDldreN-QC+;8pz!od^PUQ z?!008Fvo2giXfe6zWspV*37q2hA(cE2|C^~A!ym(Rex^zDlA@vQRipL`EvEtxVbyJ zY8<_M+@0!p`M9~Ud0JgBH%}J_Uk5f>P}`P|c)nds9?)rJ%vUN2_KUB^2Ku3Lgu(LN zMYcweC`THsHlu_Ps9zgh=W}4cV!BM`Vz88Vnq^_}Qr;u?1LYR2^z_^G>*tT#w>x>7 zM1VNh8bokle+`!3{3Xn{d#gg{&h5Q&wa@_(X3Ld|Zb>7%jPjf%w)9~%f)c2%dZy(V zi;Vj5QKv%7zt-$7H6yZ-okwq^N2Z)Ofb;_7-*SE3-nv1H76<&?Vd@Vp^4W>7!qf*@ zdPS!!>8sOIme;1Mf9GivRJn0N$6eFr_szQ-!keShuEo6%_V5ZQd$)g!Jy#oaw}(z@ z>`%F1q+J+numm}V#&w92>|wLW_)bv?{4H{}StFBBU7N(5mlDW9F^=4Eeo;67h|&XX^@VBUIQ${QjG}o zs!&wp8#sN_!u?O~cf>(uqm@NlUyy(PqjnQU1_$*yU$oZB>j$eOi7;nQ3SFUzbkb|@ zDd|**W#5cFN!7G_WS`i^aXn)aV&Y;Uw-R)jF$h9%f+&gT29jUy7ybFfz`L{SUEYE`tioxhGFvZj`Fokijco^`k{IBizZ^OK|dY9N3I_}CI5&`1SE>j(LzwAKl-De@1 zrpKpLAO3yQlNUwUM`vE3#MHGOIh*1uGeb7!|| zGpF4g|&|}jrl9;h0h#kQ_KKopReRPIK zv~McH#D+$=r%UY+<;RyLzEj}S5QeMNAt@63t?D&$Btkr;!FLMe$3Xs7M}jvO2w3q& z2j_ERb8q{rqzDst)buknBr~RLjt$;7jPiB({_AhHZ1K9&Wh-}3& zzU3ZW{`$nwO10}A6=4}U?SothrdlN8A?L`=&to@fE`^N>bJ^20tM7XemeFPrvQe;V zdIu%ebR4oPHmpj{pPQYY)1j+R6%i&ji=wGe+D-4uv0BNx=2E#yetWaoRXa1<=IG2& zC~K^;$SgwsTK(RK?e}Z*uurtd{HMvyUyHE$!p#T;V!!n9o%Hj4mpBpu;?T6siQP|sT=`CY&m6ac|9F3( z;okDYL|A5+@#3udrgt9Hzf4$AqZYku?7nik8J@jKu~kC;ht<#aU+A%9S-_;`6JEa= zI97yZq#38K7sF(G(qB{mwg0eyD&uDlAHL<;9EGVf5L*sYDz9sNg+z4f~J?(W|ntSZ99=3Tw=C>^%rW#ZdBWTe2SAq-bN zueUNwHGK3l$D+O+?mg+UZ~vYBIZS$oFz*>;R?PMeH#1{z)H{q|0$c1IuHO6I_b0<@ z1`fJgGOZJA>p_3ZRXtM&@DOhDzpoH3M6k%es zBJ!}(&TI5!X2lw>5%R0OMiKU*dySA;?KO(9|6#AuZ1ZlP&xCp3%nI6K^Bz|E*#P&@ z=pNty>^-Jo{f93^<{b~5s?ECy%M9~AnaO62d58RJ^De?N!@N&pvRPx^A-~#`i?EC~ z@4WYAm3fB}YV$6_GQ+%kGwmw8SXOei@0S-}ht8amcSmOp6W6GJL5l*AUv1t+*oSW3 zA+y@Ni?IJ;^KSN$o++$x81>#gtXbRLvGjbeL1%}1ZW$O;#<9g=jmW%X^idz_5n%@A z9qxZ_pT1GdpHANu-omVpHMuah_3Hr7+9#^j9o}p~mcLluM*A4z5TJ$nV2=nhF!DOh z()oDL3nrm8$9tfK`Y4YGv&__E-$#4sCwEXx&u&o(_Sy#ygJasoN5=Ovc*rob&jLYX z^;sYhW-u;bnNF*yRzux`f1#1x@a$x>=qUS0>0!%+IQ#ghZfxDuzGHk`H+%Ljf%Kg& ze8Sp#%lgAkADdd)Z_B=M9{K)L(d051jVI7seTGPc8Jr?z*&}GIK6@m>3`U~{jIc>m zLa+E(`xcSxk@nnPadBOvB4b%O#P^D_kLhS17aL_C7jNG!E}ng5<4|~*BZX6wK z{{P?-D?t{_KDczy)L>`T!KEBE2ly1IH!oyz-`s@@yB#aWw>??`M{8FfToPfH8BR%a z_3C8Co{NMM>Vr!n%)k~(vVWL14f3lGE{U)Y_23d@RUcduVFuO+b&>%Fg^chEmYt;s zmp-(W@5JIJeCLRFR-B7))!5A~>|^`GpzGd~>UVyXi#I2<^6kz_PQ5fD!VG+8)Nnd` z&9hhzjSmd+*gj-iz=7_^J9n5nfR$0oUNhuZFO7&W1FuGuN9=y&y;E=&G*hgnjpoIEScM&EwD8kp_@NJAQOKpqNe)4H}TyKZI7K>58 zlK_d0HDsC_L;k4)3+;Mv^;@sq(UpRKy*zn<2+Qb>NJ`IS@>zN=_2cQFNv2M$c4uW^ zaR)uOtya%PSuT2S9#O357dwxiRP)#Ej3#^EN+q|>kH|0tg+V0l1l;d zt0zbzEHfrZE0}E7OpqYIdV(avK00#=CDaon5hga5bL3{pH|;E3Q&kT7vRw26pN5an z^Jf~fRMt$8AisKoB*H%Q2@+&hPmn}dMw@-AFjS(kip(JMj^aR|259_1IeW~~=-zPw z#=&AQ%VF|z?;RmG?$y5JKIXOGzBMEQ#3A#JZIg!6<`>K5AM0N4pvUrDHpMrIu*@*; zMOoFwb?^37WA9I!?_8NYqG7Ie!yvnOTr$G2olww>b z#34ZbfK7jnEa|!V(9|wJZ*tso*iM9rO?q32hjG!3>Lk-~uY7=ovhw8*YSTVi=040= z$qkhw4Bqs^wjGSW>8GYlHAKGBi-lmU5h@zXZdcxHxt|BT3)nT{^^7md4%tl=ZFFpi z_{YSm6{0isuj82}^z&loirNh7>5=&1f4<=jxQ<`geLYBvkIl633 zxh0!}8Dy4D0~SW+J05BqlJIo+jDhdAjfYNZEDZ(}bQXxD1isxUpnQ{}!r!xmSUBC;8GzK^BpR_Ys#Fczu!V9 zHFh1$w?gn!-TmNly@{hGU`#}VAbSm|vPT}+Z58obbKV)r>8n&gN zlN#G1tS9wv3Usxk?Lj68&`)K^UnvBzY!sMi@CAsat5HA1pM%i=-sQVQFAoQB25M3A{WCD7bkm6Y5bLt8{8bP{Q>< zyV!@CQnlvi@*Z>R+F!LqnAi(Ue26IPI8o&qZSRksn`rN+)7&HM>et$5WJsS^jr+b`n%MaA zC6W)y!cj-?V1H^4MTFT>BV*}xjWT_YoxljIJv#=OY%_@WV1J+X=&RWmn(t4?g#Rq6 z9Np`Z2ulZ#kmYO;bj8J@Otp7Vda%DQ@^mYC&2Ra{km}#8&-2Tf7!j5R#_7ZG{Gi;L zgHGj(u4(VH-!IAK=DvGlMObfP1596|Rf^?V_Gyc90T*0C*PZ?9M2{(D*|7)nDzQt_ z$j5*C6xelecg1g?rJQa4Kn5v+7L)Ud~Y8~&cbQji)XWnF^ZyzH<) zPeJeJIbyekjrsM@l2woj@sviQQhj)^?>`;iHno^0I#0dxo9BMAXSKTs8^|%y^@NPo z@iQjFqn&rZf9=<}_%B1NC2IODTL^Vb>6qzWR35qD$Z8uMRW?61F{&K2#*13N>x))1 zy?yR~`l7+EG9I~YNd%M`?eu%H`yn}tl%MQ5wMe^BPexuZ^h0|QmIj8(A}>lVHHd0s zl@|pier%Kc#T(6c|IC~)XXE|-zy2%2YH>N~8g}{`Bx|RlkpGLrp-vUTica-f@YVih zZHl}VVPem)Ey|Jwz8Po{`O|2G91my1NSF3+{ z?&JJmYN0X<8s%L#k}qpo*7IV*RerK|WY54$33+F}o>yi0`$Q3D%N2>P$)?JQ<2Wj% zC9$RmRL7k{+i!RGeYPj8MVFy{3O3n@l!&J^_^u9+Uri^%(!q%niKV9#R=FxPe|Nl; z=aGiJF4P@y-}BHp$Zw8L<98Pr-X>&!j??W9jk+_l;B)At#?ruM{$YvJU{ql!g*l zv!hqmb&>V$7i6DO{TIlt#$vfr(q)h_jtnVjjxJUItkUMZUzyJxcKHph?6m$4bWvkh z%+e*!(t6;XP5z$5*A*K>%+ciww`)6Gd|O>PwdvNbNS9+t&_#`j$1L@-oU~6za^Omh zjmJ#gOR`h39c3x|zqBhmOye@wtNMab&(5tp0Af=*eNf|+$KPo^PT4oP`}07*_#US; zbJu+t6I_KaUmB+{7O2N55tbR_)Fmd{kso7%^8~N#Y2$KZ*7(_HTcuQ`h!>4-A}lk; zDRdWgd7G<~dQ5^&YV4yMr=Wy-OcG(~JWkQdi$(Sja;nE95%w{RQ;=IdCW)|*VVr{8 z>M==#WyUxKNA+#qiMdYr);~9;V6I(XZ5=nCK^Bcuz93-1=zMCZJSrNT!?@1;heSEj zV6yeO96{rR(J7UOspXCCEDMXLRN*1Ho47cS)$IK8(WS-BCw)sIKubD<;mz(lRmp$8 zsz;}b^}dfty!diLQxTR9LlwkO2R-kjIV-yRq4~Zn8dCOTXixtsZ)%RI4g!>@T&ik% z={w}#_vIfiD~Gy%TH&ns@x!#K>w$SbX)t$lJ?x$gobG^P{c z)b6kKW(BT%qO6R8S-B@ikbXwZ%4s$T8$G$}kS(oGXKkrzS3Baw>_qjNef$XTZp3_1+BG6WmyY*>W|hYg4IO#*y+@edtyBc@|mhyB2q zU^-gt4E^wKLG9IV76eV~ws2rCsUODHokOt97Y!havU$#22mgDdP?UO8~a1QC`7 z4IagWtd+paqk!@a*W7HTSTo2%3H1|(BCINxvrfG9dshG{=E(9@KcNXxOf_c2Lx=C1 zKl;McXVc+fL5p_pTr#4Q2=hZ?Ii#^(b)@rF_`xu3(6MLV&5{2>(%}oA`Db;{-{<6_ zDErT@L4GwRc7D>oUILgbm)z%-2_892v)Aih#m14#Qye)m-N>AgTNU*vqedpt)Q=k$ zu(iU-*bQ*(x&QMw!P92BM&Fn)!i7XY(;y>*wiw(ryzb(wr#vSf8hqmR?8=QqSVkKe z$VkB|BLgLx)KWJ zdGf0&nkCQ=eDUkYXurX}JJfQJ>^!a%bS91=$b^@e644bZe)324IW?*|`OL^QW=hiA zO65h^ex8YRUzSn2y4H2}Vd}cqb?|hm747WS8&8d%ON~ z?p}$a&nT#3PTW>)3R3b}{@ zjIr896k!={)%p6g%0+|{Y8O$2eW)%XWL3L}A}k$UMB#5;Q^knpj!a~eoe}ZSLG31r zFtNc&Ki8e~y2s>8IQOD<4UcZa7u>(U{>b996CgL@DGk2!A?+68ZLuq%{n)63 z81ck}gBZcGu-KG5zt(+y^^kv$$DJFwXY_+ze~<`}D5orzXunB>*>c6G^H@@~*3NO1 zg;6~T?ag5IJ{?k;s#U~8{t{hU9KN9mzSz9qv#t04KDt7LrNdf#iaOz^$^!%2ZFKhB zm*iWb_v(MLY|96k&C#h+_x{B?hctZGrRs>`cb2|>0-e-Y8kl@EXNaT(zTGIGe8Vez zLMGIsHl`R6LJ9RAnh48`S8JdFs`nnDw=tbQK_m;1zwck0FDwe#J2(DZyS;W>wyqUn zxj1iCS7>wOqA^u8MAS<2>X=km8I9I)LUjlk{`3AiGda+8xY&RYp)JbdiOG4E-QwZqsyt$ zBhP)}S*C5ns9&~!{p#=<=%U8NqnYSLC8u;MPgKG_giKiatU=J7U$bl~IDP2cDMg^9 zDV@@8Bs;_EB~ez!U`zSF96^<6bR@ISZNe!|Vp&)`lI1#l`rVw*n|sbFvis)ad<~0` z2q+m^>cBCHM-ysY$ysA$=(4QcW4BLP;V!~#Wi>#nYoX~olAU0AtuAJ!P}o1<`e^4RV{ z_pf;DXr6Orxo)}bps*TSKpC+(o!Dw~bIuZ-6h*ijJ)O`nmqa?xYabAP^H$d%lCHFq zmcGoY#Fiy{+HH#V@tGESd10-Y;b)@7+@)F3{KW24%Bz}CI%GES9-jZ~Sw8k~ z$eF`Cs?FHzI%wic5oRlFovAXLR7w0*uXR3TG1FGhs~j2}e7tr4rz5JrU)vvvQ|fV$ z|I6A(+Mo0dEZ?K(zq=NHm+ig?O9!(F@zg<2C-k^#4_X(g?@=o`=b~);uht#?BM8jV zXQx-udHI@cu6U`YSDS?`<0&q86v#^;Y6Y5bLQ;Z0qMBP?p zCoB(Ge|>P%J1bB4E-5O)ytqtt8K~bVZP7DRBm&1-Yk4W+9*e1TwwUYJ{v+Z?o?5-x zGuc~OgEOWRF@pRPd`^124aqU!!kI58+KwJxL4=9TquS(Kq!Wq2Ukw^yM5n8HZ-or` zs!{fUy;(oeyh37AI%WET>@2xPs3jUTqBl$)XJkgtV&Ai=d%(%@IXigmD!O!g?wR)Q zNd%M`Ey!Xa|KgT1w;dWq_zxdlqgPFz2`xle8gx#J4hBI+3RW%1iuPnhSXIh}U3Hx^ z{TKd3`_~Y~RAWXwbT}W=`*g>9T{KB0D*qY1s$H@O1AhuSy;8jw$R zgw*OiBoQVyHL2DFJ;3O$rrc?5us5aNsbi4IT1q?b%;Y)g2Id-;Bqpy>?=0=lNq5Y@ zXm$TZ6TJ_d+57c^{hhk;RtMfMg6Q0?2(zVnU^Kc$oGRCi<0y%O54};whXLyI&PW78 z5i#NrApal!T{=Dp?dOy9<+9Eb#vLjr!qUNY6N#lOE+&^bvS*z*@_oy}bNoivd_N$x z{-50;yBbS_QQ*Tk4-Mtid%GfR5m&Uj63y6sXxJe2o;ices?@!OtG7S8b%NLQfG*Yl zbpN6vbW~$K!AuT19oxzX-+d{SbTt|wr%IEVE_gxa@tu<0l`Dj}~muwAc-Gesi(RH^sjWTGhSllYb|;?co~^&E;|C|M%k4 zeq8C2-+NWw%F8x2bg3f3(!c;&M+B$efw)44uELZ9m5hiv+ z)rQ962QNyo?CZ$hS`FpKp_Z%Gf5R#uy=RQwNT>4ye+pZ?=iYlf(SRJv{d` zx>AkLMVQzdO(*q8Pvfsn(`ss-de<(ybUnCdyvODtqpNl+)hZv9-Lv#eG7^(ZgCsRMF zghZxv%yg4`N|v7Noza3g~{FXazEO=1mU%uIrr+}w)f@cid-pi-ak?mJ!uXt0`!B>RY zlI>vWbtXAgQ%6*gI_R0H%Pe;4@ON*UYvv!BFyOa27YF5k1OijFig?K1qGRvC!eLuZ z{4nJ(; zwe`8DQ`uFuZR5BXo*`*-=ikh1Obm)e{BDCYV_5tbQt@&_i{ z#(Cv>e61-yD6vTNnzs)+4~ER<=#;DS;UWFKeUDGNG;M6Tc75JKCpDG^b~0n$C@FUs zsj|wQd@{FT(7rv1i@)2G{i|laP)v>0Kq<*VH&CyW5o+32?<6wcTH>l>%{ZG=DUmmd zHQg3as6~EF-Ki~BKQ0Q{)mTY#rdgaW1NGb}){8q<6Y7LKj$C+ zI_)w2-~J1vLyG3;G_iF;p{ss--zD3+?VgdnbTo8QW9Hd-i4eU6X@YB~ zgMOOi*+=5%*#s8GrnAXSZq?$-{otFbf~EXZz3 za^Zv8uL5v4av$Lk)dCJG>&@KgOFe_Czo`+qYRxal`oO<5OX1p2Z`~i{9nj8w=e0e3 zoK}WFVKp|Dlfbwkws`rJbvk8zl)s1Q2zo}WJd>eCXiV`|eqY$_`hL{*kfZSzkjR`$ z&3mYUW1p}iqk9j^H?)8Cs7KIIjScz$bgaN+h!32&dZ%}Re$GK_r#2dJ3riU$b%ZVm z5z?pbBTE{-QOxAKd3wqPM=jX61%7J60^<>5i#_$ncOPjyLgqZ2HgoOjT*pU#P9mTb z$jD+qzxdPgY?XZvUbiW3v#HVi5O)!l2Aw)%_dcM6*k^2}@gwHwdI^2Ro&+-{n)tNQnI zMVKwu@N|tbRm;a5M_Cw^1M!@}1s@bIyDg-}1ly`F7A%fiUk)ivwHd@ie)X@ciLi9= zXpQOwxe&~eUHzN5kX?D|a3;ET*i7Udcvvd@6Rgu0wxU`*RXwC2BLVopc;)<}$_?_G@SR=INcXA=W`ZsY! zSZ4fA?oUiMOMfRWxV(^O@t9cVhbB9_dfF8)+kV^X=k1P7 zOvOGy_kT>xKJ1y-l(y?Xe@ri1@pDat@B7kTvtJHLZo*qbnwqp=g*mlA&PqdrcU-7^ zeC_Hr@vXiTVd*ehN)@U4kZcAS;Nt9NRe?5L?*z;)Q+sZ}(j(rDmLWajDUFI=`U?3w z-uE1I&$sN^h-M=b-^IQP6k+KwT8hNc*+CX-j_e~n?jPCi(>wP3fPnE6md_jv+0|Go zMoS_!kd<#A>PS&}TddfZ38!XP^9nhiTqbW~>9}<(p_m%G#^tQbAY;yKRAXB9tomD# zHeu^}94|T|v0je(*&vQNmDcuni*NIUeC0fRWQD!cF1B-lZfdNOa5F*pBnn^Nrs@Ua zfvd?^>r`jlemM2bqX)sw3iv-?yvbpHiA^9hrI*_BTED@HUuZ>0h2b=Pekzw0%Qma$ zjLLJ>uiD&smF6cM=rQ1XzKo?hX9D9f_}WDmR{GVWzumgM*>`oA^{S@`%M9E2H7nGF zKJ|~^_DWtK6WC-$>77r9qmWHiDdHjjrQhxU+2+xpMc*YYW(__aQbL4%h_(@OUOPE$ z^Islq*1bL2bl+h6Mjb>L891!xN-q-%atw`QFXzAvu~}q%r>F$}7Kv=s2OKhHBNaKT z``O3s;WReo;hbiTGi^Pbx%)?4j_|NOdh zmEZbj^8^l<7hC9LsqpoiL<5n-9-;nZV#rPjl--ttDvZO7ud<(|mv zZ+3-r&-ZZNg#|O4?C+Bb7s=$@vH&|`p0<`Z;>E%GRRZSKYktacOO>~6Ci6XuWhRBM z+2^bqeOf>8sCBH{m7);dl1kC~b$cyIQVSsLz$Ivf+rw?6UndZ$TUa{&#c{Z7#eUsS38f372}^@AGx~ahSKTf z7j|dHFl{YwY`|CXc|x3XoS0H&ZlP0Oe#Ki}@(b~s-PK!qoKEtY)n?+_x*M0480jj) zGRyMb9kr-fA+K6K{UQ&q>Yl65KTO;dEidGs_Sa7?t%CZGcbnH~=;cD2N{g@$(egsh ze&4OC)yOmV#DuGDCw>`HY_$mc=qxXki0U)x@-WW|x5^x}8&_>($p<1Vv#e9aH1G?p zUzaZ{dlIQIE~j6b*w8#^&AR;Uzy7Qe5-?=w!Dd-@T-p3@50U-A!|$Q1z2+YaYr63D zFI)D+K3hIkgr$T15IJ9Zo?A4N?M`&|4KKsKi`kZM%!V!}7TjS_iuMEYH(d4EtQ;PW zXGR?#Gqc%*Iy*&JI@pgCb$Z5Rd+K+n*EyfQ{VQ#_u=2;!huFz3^K_bgvcS#W{x`RF z{rJER?JwNe~n+YZG-4B{bw z_3*3D4rxApIQ+zn@tQ{ys*13Tv|f-4!5rBWo<_{u6#Bexv9;?rH@p}g3fa|IDy$Td zO7id@eEZ;W+>1J>MOI2`R7WqlHww&ErOO|;R^IHJ6fMFQaydyElw!GuM)k3892p5~t`q{@vb!4wGO8)~3IKXVlf>}8xvD$E1?-=bw@w1Q$yW{cDgk#h_ zj}-?N>W_W+^EbYuyGFgsKf^a$z(~I7u=O)3v|*o5`fKXH_8%5dW&G^n!?#>pB*N0c zw8#?ZU8KfDjVqExZEy;HH^;MLj|y*g&+HoYs|!*ip3>mEIzayA^-CXo=zX!*l{NMD zR6Vf1lL$)()1npy-}Q9r&VUnv{Vr_@+>*CikKC&Z#1?*mMCR!9xAU~x$9*rj7hmWx zYuBdg3!sx4BfDY6QWrH3iyR|SJ(z8B)ctP+N`eK;k81AL653eoI25vVX!y#1WRLbs z4}Lqh;)a2#=)e(wrqF@^m4&P;7a9%kQsrCx6j|Ran&e3D{#oDl4WF{b|CSF`A2Old z-Im?A&e1Q}J!s^$wtaT2j45naON6CE?>5>nDB=v0ZTT;gYmM>Dw*J(*atp?OlB+ai zM?9s$cXfdLjxCd?l<|7>Z(zW(eV2OG+bhD-p?8bKdJp+1q8+<;KJs~q);?WJ{dp^L z_Niw*A(~k_tv#E!K%J1OJ<2=YUcI@y=Z_#%W2xxfL<({A0^e@*BG?zwi^nB}2|xl- zBE)CJBc4}HJ=1hdmW(ts{)p!t6Ft|ykQGDk4};$I^72gTzVl*%$=_V?TtFhAT;vsA zn+SHF-zT_m>oE7fLV8bI?>6I3q6nj!ONB{CF|piqftN>zYVY{^d@B>`Q5&mtB8*^s zTo1I1eW)o_Ykn^8F}JS$RZE14=ep_p?W#`R@+aSs6BC+{{!AQ#K~w&}NOFS^dV-o{?VBi8sDjmb|A| z|FeAKqLC<)X&v9V<(?{m<(rl%zkl|q=4Z-@Fk5OwEWNJLrSBtlomgIVdJGvf+Rt-T zF8V5yNnln9K{t^96m^WM79%~SM7E9$@^*G7b;LkC6`s)JPbRNrk` ztlA|6fvGluc*wsjrtXc9fSW;!4&R@BaOCCjA}k#`FtS$%J)PRK*p_2rHuvy2{cUm) z@0CNQdtklTES>tUI$WoGpvO-U>k3S`?Guo5uz|=&{-L!SLG`3oaI6nbCneGTCN49o?s$Z%&OvrAAY0d{cj* zxjKz6ANL=(u&*yiHBXu`{_tz#sh4#LaA3Cv8`HG{Fsg3kHSPZS;E5 zv~!aRKjeEi9Zl@OT8R2+q6o{3-i<9HAFtTo&jloWleJ`?`8g_k7c-|PKz{YnL=l#e zy&G~Pq-2>Or}}832>YmdF%*Xq>Z6Gw>>3iwLFcGv%tN_VSnXJIG!c5Jk0y$+%sTv2 zmFZ>49v6x~?dCoo!s3O=&3QbcY4I|8^sh5_U-GZ{ACJ{7W~`{U;~;Nbv&-!_id`#Q z-(d41q}KR6|Bf5_M@;sEA}k$@E9{Iq=*<&gToao-S>haWs^&khwoje-SF0N!0HKH& zaR`wA(>+~hB!`yFVfX1TtH-XH|BDDq2jeOdOJ^dOT;|BW@{RvDPM-ZY_I!A9K|88Wy*`^on1KN*&InsXcI_3FDSPjhzAT^|lQ!+_ z(gC?WS-d7wsM3@h_3QrIz0}1H_mo{TJ7yVt@e`SP5GPHHR_ z{g0Z5MW^2&yE>RXlTi<#*7v_OIDP8y+{E~oWKI9u{GH?2y&*}>9A|ggv7%n}y;Q&` zFLGef#?_}!MObF^KPM*J!|G@IFZ5WlEMQXe39sJ_91Gb~YO9c6-ET!$X7oRiZ8KLV z^+{9cq{cG3|Hqss~yH?H}qfemaQ&MQvqmJG1MTrK0LL^?e#McE^?jt@_4a6=9jt1-miX zww<4vb8(2HPm=;SCd@1pDw(>Jx*+6#_4up42mE@?%s#rwj9WXNI*YK(=z?9DY)#JW znDsWK%+7iv|Fio=mC=7NC`GdZ`R`9|*f7%9G25jkqedM*pYVkUOM@6TiPHfGdq02SxZXMilrBjPtBJ3oWlTN(!JuSF{$>x!?JKtpg)iDuw zZPyMf@=pl#Hm3oue7|MFeP0*<=NEd<>GXb?KXg)K;uDZB6;F$>H0Y2hCb=-Q7hWE{2=;~RCN`6;>5x#OS3lbYZ#1{d zFKD!7h19Vpvldq`pi&!>Ygo!(4`WhN2P-kt2h7$wUEh_(F=ZaT9kHqs4 zCUsKJAFTIZ&YS9nhvjOfdNbM$ADQZgNz8w7ghnj%(Ozsmk*|2>SPIYO>l69py-TGNbL6NelLrs9z};DFuGHWTv7KT7=mO+kdK#D$5e+U8Jr> zSz!=Sdp1a&Qrn08YEMdpWu!+0xe?5feN(bq)uA4%0$yE6nlf?kZ(l=pHI@d379By7 zi9Y!DK^R@BPVjw_HHKDdRDTXVTv@Yf>6syu*RQDd??Mq)8zxZ>I`P!+A2$2PP-Qv2wXzU_lnwLO`q`#5hek5I_2#_;w~3c3tZZA|kro}L{OqT(C(ONfq( zl{_B*sIFb(C@;&kIsC`8X1|9Wbm>|@WcH#B(_cXwHHI}`3Oa4t%8=2HhhQ#j&PHIuyPt$pQ!?wE*Z>V2Ngkfc$!iTBFsjrsZy6->c z(9Z8Zoi=LN0Uv0g#tI61h584)x?9qtQ7E<8UzH{e9BMg8p@tv3b#cLc4X*}u2=!EM zt6D*Ud=PYn&%T&byG>WuDRsr;=Y5;UJ)SznZEz2iiyFHP&T`OYkm`e17#$sD^`)Uw z`C^zELriJ&p*b#%O+EfMCGQ8}xHK*JpXweV?geU;yEf<4>Z_meCWRaqESIR47DSk> z&?cv^<8qeC7TLb}*_R=Q9Q*k6oi}RdquwJQ#?(t^kl7ra z)XocZQezqI&_H$yRyj0MV^cXaBJ4wSXdtKBc@bghJhZl>{WdhudKZAtI@EY&v(oAdq0?S<@5L1NCZ~7%91J0hg98EET^mA zlIX5ueqF!or)jrDSQ-p`8T-ZqC{b>6Qqn1}z?eoAswCeW@yA*bR*PH*mR{$Zr+PNb zxakFnHD!ezGi!do6Y_hmX_O}@^k}oNxl^{BeBRbWgo&3++sXp*%|K5^qY-kd9PHXL zvTM&MZa0G%=;?<=!(-d;+ph>(JSE4`3gfe#zXvf*dSMySQBCe`B+IH$DH!dj1=x9% zWpY&-yf^4{J}Wxv$w`UT)`Z%0yXu*H`BUw%Rtl$kMT` zJ=Tp7VQJ7&E!x|VOHI01wYLE!zWn6KoOhw2UHX4sVCQMiXj>766YUgq9W~XHXgpBD zRu*jNs+R?2i5--ZJugKM^Umq8?e|=BPxRm5hlGfyG(^Z>p+}qFy1Xdky>nRQLASS8 zYT2-=2orbM^ff{_;@jtxeYKe2HzlWyezRctHy-=9bmWcd}6766ASo^AQ4b9^z4!7g>fRxmTMZi7Ms44 zdeKYuQmR$NL;meAHhlJ0)8tOOPD_(#&-kXi2+PPxJ>)_#)gloOIp6%=)^=pzjQc;9 zp1Nf9iv^QKSQ?l{G+Sh;1ipPJpy1}XOsGd~OfhOVP@?F!)t`6u3msnanD=bA@qryh znAm)@mBlbBqR|MMFvann^faai;?vG#q|KJ-6jP4{*|P=g6t_fQ$ZDtGmT0Zp<2Ks_ zt(jjb{@sXM+n#mhD~eVYdoU^P-C8-Vt!C)5S{vTZns#8nod~m~#>CR=8ejSvp}s7y z{Bbqg9u7NkxkJpVzDUZLb>sCF5D`UON3?Q3L>>>G_+Mo zpDyj{u^?#e5V!Re-sfA(AhR0Uyc6$#y5_Ux%HoS1rX8q#;t_OGW9hWA2*aw~8r9uF zYy_!~l72XY(znMC5wio{J+Hqz$GV|kdsagtQwA6D(52vr4zY2eix(dI>H4%qkeTSn)^lR{@$Y-3ndZ>l9KjS%hWw(uJLEe8=S>Tb?dBkhq}t zQ}2mP>=cI(=&}9u@BpW23dZa;eI&Kq3uwQ7b9|gF?W}=Cdx95 z&}Ay!Wl@fq8(sJ?`3vodY!;KYueqqh@c%lq3xcym-+VDX5UJX zU5%x}>JlmAsvr3Fp&uhIZ;KWCbbHTg%|bTca~pACr=jE$XZ(TT+BkiTd643hjuM;A^3)4)$RwB$p5y~(a^Bt3mTSuyeTp+>j)8+Sx;o{vnCw*KH^#!ZNdiM*SOcXPD>NPZFjNUb19Lhk8up6gwz%Sf0O#W<+qm zWw+ngSv+*|p4=iVvpQ(z`S+#eQ|uP|_YYgUR45zK4^4-I$5Y_~B_L%OW>J3e=&d!D&jMObF}_c-&Dd9Qr^;9s_VkonpcA60zR zyY`|b{>`&pxLbDK_!*_Q^9G1si-BiU)$h|5Vd-FisA=+70|VsU_E^GKo|o@mdHdJm z?{b_UfW&C$rrJ8>SHDkNgr$Q4f_Um+Q9p&8>i21jFtQ?6%*lvUEvK?TW)Q&uQF&Xe znEHL%P)vt;j`t+W?Z;r<*Itew+hlZc zHp$de_c&r=v3a~!_|TNe{*|VVIpICi^~rs`=1=|^_QH!eZn)Ror|jjTpW7rY+TZJ$ z2+Iuf_z#n9-KSw={6n(cbgGzr=HqFBM^SSqQMpv{)gXutl8CU3G>;@N_Ak{3aG-!W zI!%1s>feU`?@P38-Em{`rJIYPlNux2XNB3M7K-K!k(59Y3Si{Ms?%yvLVXxRgo$UA z>Sego*2+#Q>5b2*EcGE4Bs5i7nZD$cEUQAbX4K%A{Q0pdYz@_7gEMAGp1uJdJ6~3+ zF?i~)-yJ$ZB0wTqlkLau`?PsS+mE)kZQ+q#ul%k4b;QQOv@MJLB?-88S%*dvQkIi?yk;-SZn`)ZUa>R;_} ztBVCjTwFh>wg?k<()8Wd#c8J_0poqg`z@Qkd)BPw@y=^kLuOMtsmFfnw{`O&8x|~H z_Gx$Ve!)t9=iNQmMJ|l#)8S<*mVHca>v}K&({|bCaqi!<{vUha0no(KwGAp3Y}o5n z>=mUqy-G+39qhd!prQx}*c%|IC@A)ZfPw;of(iATx))XeQ_+zTogA0Eao<+xcf3nj_IeRt!k@^@JkUVXYY z$=S)AhG{U#2T3TbbV@bs15uGq#Hz!vPq#d`7WbT*{%o{vNJy-4As21{Dl9r=9BRP- z_|5N6X7HmnZ?iwT=)zUQMl`G}n-!R(G~6R*=9wE?`t_-oXuYd)lcxQFJBgLT>f&25 zrJ^HSKZ-!+gqGeyJwSn^5o}asfA8xYx4}UdABOcjnW_tdk(jD_CW;vL5ojlpN$lip z0F#WxIv<}HkJ12><;0?y!%!@xD^fIoR3 z4O4>spwSYsiT@&QZ3q55-Hda**VL;9!TFpcmw~@DGA+&2S}@A-VCCGgM;1O^Q>PGQ zA~9?nO3^Km>3!Z}1qPwONh8=v<32;?S^v!Z^x{#BU7J34Krj+Z7R2`ZM`*Z`7!<3v z)UWhn#U?mC&-7=6Q6pFy?n8#VpVzmnkmS-+JF-$lmutYC#JpIkBzyq*;-$&5cBvqb zb-QZAf5Dpp@wq@C^do!}x{yYePR}}yx?Hs*UT#Qe}fGi|NZ$*<`-Mg~Nf}SMe1o?oI?JV+|^|^VgAg=KS%Px@%KVIH` z7(z?RAF>s#(t0XY(jsNK>M6B1tEV2boa2}}-8U{bwc=r1m?2qkJq2|ESx?b0Rn${p zz&Wm4jr-X}u6}s)z^ZENcn5*Iq$~x0TKz`DR8dbsaUs(iI7=fFSto%^B=*PEQy>Ic zC($q^*Hb^`si%M^Strr3KcSui-ejFb!~TSN3V4%s5)D&DJp~Qb?=`}!o#FSq98srQ z#^60mHX%r&0U+xs`A2)o!!)|Y(VhsD6p9_~Ig!(m>;7QK0)38$1cKFs}T-o|TdP16$PG-T#`E(GB#8f%QZi=LoXO11@Am`X=*#Dm+ zS=SleDaA-ujHK7T6v*@1m&A2C=l`?o+QY*xWXsoTLlW4!kLSDQp=>3;Oh?1Y(l+8U zSdt9{p5zzkXjpl)fxwgesvHf&hU||RnNnO!<`7e!WS+PB-mkJ-&gZv|t9Qj-t$DHG z>{1j+iSJ>86)!&+MJ@KeG$1eY>~!;|p^cqvBZt(jJ!;3QU#YEVrFA}v`1IR);cm9W zpWM2CeC?XP6&KU6vMjAkPO05O+^Q~iSo@LRwN~ntq<9^*z!Dl(9!oLsbXM#6kjG7K^LUZfrcJYtE~R0mD8=|zNJ7B9_Ey5C11*J@;;Hs6)VkUF{k4^^w%Bm`w~y>x!gX!{ z$_axh0Y>S(xF-X`S|=WxwDA@VQ$i^gs~FhhHsU5vDF*(=&p#UFTMiiVXup2OymMpr z(l8~IVoV(|C~{IOJKPa~{?4V@bsE4M)GBpfWOl5_x@;PTi=rHLF}@W&Nz}3RL)1sX zrC9#a@1{%wm!c}wMp1};yQmf#oRhh>Jm-{eI_kf>Hj#!OejZBu;=oQvJo+7o5;XVL zySmq32l67fhi>NoXK;gtDWRN^Sqawyon+EdZ8$o~z3*VR!z{{q<+te}nj_A=gFxVq z!@xD^0ueCS=D>(I&H;|`Yx}i%kZv=NhAE+(kyPMXM5a23_|k{(=7e(A-)ud}F{$FU z><|b9^1z=s2mJka@4q^JMqTUZW>Y6_HeY>=hT%daNBP6*QMR+RAcT6e7d^XNp2}VQ zU`7k0c9ojZuq1V1(g-bAsow?!14#yE_**Kl_6gnzi=FU62mt~t5;#oJ5m=wAp&mWU zO6Tj$Mk5Yt^cv|z!?4)fjEr#ykK2Ji+fIm6Q-m**1ZHZw^TCj zjyKYpIoi~EhojDGkLa#F>0L5Z;(OaW2?4{!&e^Q4eO^G5$z*)LC=6WQE4(}spAp`xQ@j7YAYL);FG zTGipR{X)wiE3XD`x0(q0&2S^_W&{fy@INxG+1;_zhj90}MfX#$@X4KqDWRgH(Grmf zYPGo&QgDuJ@yOEFm9TxuB*6nTd20M_6#1v4`fjSG)5&y9D z24nbGqQJdSh_>SkQW}n%;+#0>VyE$^t3|`ja3k$z95D#DFQjd?wF#!2B_)?-kqJ|PqX%=NFlq!!!+qEZvmd>0ui-Cs5A<|sKRO+_lNjApj)vzV zCpOu|di=hR^)-UZ2>Jbm0>(@F*_N`{?QsnyZUB>i#SEuEUd^k1om!ZmofUOW$mOH z!)chF3T0b}ILa&A$GyEC=oH#JBrnkXYrXIN%^(|z8K^)uoDb6E&#li-r+6IxZnrk& z{?mH8Z_+^q5~CZ=vh6DbBVISG2hFXc>0*`j)qTHO#5&kGBvA(y*XD#Zk^zjW7c-q^ zj0d(8VohfR8t)KmIw5+QO{Z(+k=4FgIygmla`V>Pvb{B?04ak9S0LqHwJ_dsH7wpT zVdA5DZ4D0mpkW$}7;vx9!YFqO%~kX)qqN2OEgIdjT=7Gm3za901a)9y7(X_yk)oFY7!3t@60KpO5lpRc;L;@1PafMr8gpUBn)w4h z(#SaSez(ih?WZ~~J+av5);BF%kdee-CopzG8Ame^yZGWzf}>auCX}${DLlgw2p@wG zY2+~7tMk0R!*l0_2lZbVw;TEkM9k3Nn#cS=V_b3apMoTs&3K z#r$psUTpi7XZPJQ*dndK?dP^R<+lE`O|t2bla)Ump9un!*d2(BaV*7TtSeS|nYSCE z?UZQil%8qPN9z@_g$nqa|7(-fJE^19&cjWtx+Kp&PQ%J;9S4a54mex-4+@==+sqeDL(C(#-*Srd4D?JH`(GX4PGaS?jsrPVKGp@JRN!#&5?lL? zsVJfL>w^lZ%$1t6bMr~g-tJ8owc;yd3P7h4{2&KI5=}PFYcWIntnH#`^P1`H zH?*T+3NV&3jdcmgF+XyRb%7Aq_SRTpzi)v33V!yTW!4#AX;?VREDMcdsmHotmQ_bj zA+xN&`o@ZF4L0n#Y`rM_*W$o0jh$%NOyx)dUyo6oAms2D2ts1?A)r!c38;LDpFf2@ z899uIAc>8R{}CG_*LeDXg8_fJ#XaF4h&^3>`mY8%Xf_6hbV(aS!^+ymu*!>?Ts8)T zAZ-i{EB`hISd%t}hLw981EfiNLc>&TW5{V3L|dYbDWksn3u#*`1+^r!R$`DaGPhQC zZf&u3q;>z6C!9_%{n{cXpKVDrAbF5mjQ;9h@`@Yj#0jw~e4dcmWP*?U2pJP7yLK$Okn%&1}7mrP+`#_qWCS-fGXEaI`Ax49BvxBr>B3n zZy*ziDWMBqj0*yU$%QVY;jX>oc+Dj?Gn!m)?7nIAn#ec6ox~Ji*<~7Drlq$?X35*t z2I00vZol5tY2xl3o^#h7T;FIj4co|KAWTu^zEkcX;x@T|c-MUnBU(LuTRnbL6F$6* zRH{sD-0OLIBqz7?e!T@TH+Og33o?<|D2R-4LYYQ02)nrAP=cda4<;0pZGYdX?t=V<*a`AHupXaQ$R75>GhQiJ;6b)PYQt$|5X~9SlRMl`?$xy77bmz zbUzJK)fY=(@nYneh?=$Rqh7798?mW}jzL3^R+2J#ME;M^f z!^*?911`!IdA1#ZJnpV7^_%ldIGx5UUwUEZRXrM39=07=AsHthz2wy2-r?Fp0 z^rc8@a@zq7Q$j^Y%NUVdJ&(A_v+V%*lhf-oObHcTi83um+~nDI0Q|`<1~g0o6`f+Y z9ay3yk!RZh2uE%^pkYehb})firzBJ54Lr#$1~iOrDo3Nc!Lf_$Z-n_3>%sU}M#tZq z4TNVn0;%Qrb9(79l6vWVkow8oL-6IAS3Kf4<>a?vsk_ws*T`TeIPRr~p%kriYtyU( zr!e~}RiCa5wzzSKhAE&xmTfN`gow_%(kS01YRO5H?48wZS3Rd;s_LafUC(RUx6Tji z)dp4{)Hl|gS|7&JB-Zud4>IHjH|8hudv($LR5|$3>zr*gj9w^}+e<%$xXIc}FN*?N zUiSq#TkU_}G ze91jPG>mRU$wlDGdG9;szYK9DHxhs#l4Mj|r%*Bbf&$Qhq}b8V03?abZJP_5T@$hw zhwxWT+1>n()8?vd(}_nvA?3(@K{QMQCp8K$Y*;FH^z#~emOT4{fIqn}h=wVlQ;42i z%n6eVc}dbpxD$Aidw^(|0;)2_PTW>TlI^R$#;Y^`)`{tLZ|<~gHx9=0r4pDdx*#x# zm4|&nH1j8|jN~35kdeg7>zZkh5gc$P_W;qb^0a1JK%C)D?g0YsBvxM6OoJR{RAouM zFG#Dpnp%lle?9?ocoh1RQWCcmB|@@>Gklxs$tmfIEpP zsTM0*5+>(pGl-$`!7LSS{E2ou9BDh?jzg07J{z61^F7&B8lGc}KxsrS%BNupFqJY5 zW+7TdPOiZ$5Q1EkPs7UpqI_UYF3P82<$h5(rgTj*^)MfhW&9i281AO3=J#)HU?OeHim|k zdm96!NgG4MRBdC(c@{)lqKzq|&bZVYf5vD@7(WI{WbS~Qw{fXnm6IPdYq{F~huS(_ z*p>uOy{$y4L~i_{VM^$LLk5wqSZ7t9jX%Jj+~h;Ul+Xbu<$-IN#*cv~xygryDZsMJ zG=3~rFkH>c+tCK$$c;ZVOcfh{V6I=DjX%Jj+~h;U%J0S>(m1MgUqK$4WfeQKrY6t6 z0*{TSxRb)V*(^Mr@~U<2PkXjy#4~HFP$rW53TT)rETao5b@J>h0RH5@0vcA9mJu6} zdg$cCbBhmGY@7C*|JrQJ?(xGeBf1jnaPSBIq^LE%RS-dO#pI3(0OOmNS1VC<# z;8*yguI9vC6!#%(M)~(5NL+T(1Bn9;*GyvHZj>vj+u-w4j!k#A+-X63#uR3Sfbafkt9bLkPhTj=5j)p0~=*rYgWl~L$bofW4PoarI>_4_W zrrw~>{H(SoZ$bTaJWIU?B2BlxEVfW{ySVz8^*ETz@gWc*d8m0h+FWXUl5JLa&U%lM< zx+jK?*uC5G>7+e0tP^Mu9HA@b)XjK( z>yTyUg!T@%|64vA0!mV5@CO-A3@k9`Sfv~bvX9E#za@A)4YP*8j8m{&dIGuhaO|=T z1OV69F~_bpwW(lMd-}O3ckQNkX&Bw$C_i7;BYro`HnwyK3F02GeA%v#OI%-&R8qbu z&Xn9ky}kfO_lj+0&jTLFVcip3clw}r28iug=KheQ?yP?HVa9`wZ=K`DzGxbEa=t01 z0Cez>+gfz~GUe%Xx0F1mwevn6JkG20lZI(9^1;1A%~bA^%}wZ8R*Xio>S=?4O2jYl&KAdbr-nGwXy<)SU+p>w4hEK{tMo2kI#V`I1wXM3vt-ICaUnAb>h3B`=4dG-8`!g zfq)u|9zY@vqZ#gjbl{Ms*ec^?@Vpyu@l{0{k8kKk8}5R_i}YtQzJVtW&6$s z5IHX*<@iSHmfv!oe$<*$kU+{e57qJcZ2UO_=b9XlgL zeSTk+IQ$0FDvd3t{`7ag&utp>A-a`uus_^dQV9og%OF$i;K2yXNow)YRm9drfoq_4m_u@zVDAodDX?AcVHRx3-J6pCH@S z)Rp`8hr@`StZ#oHN4?}ZZE_F+!(>H@JGGmAuowNw^Vtii@LoJsCnMv$feL7 zT_W#1t)~a?97wjcAx`HX21*-0I4-mV%`gg2>=Us2}J;TxQ`LL5PD9k0!TpbmT0) zk+XC6Y@H1>tSiLKIN<}57zC^KeTDXDKmo7%+%o#hcCJnIrlmXjo-vPs2a1yk{J;T! zvL{5tnlLkKaF0+X<@VBOy+wGwG&0TG<2rAj&G}c|4!LJebJg?$nMkZywIPU{tl4Fn zI))fXCrB>bfPq3q?tz3G?2u4D-D@B0#uHeHB z$OXYoG#AKt>|l<#OQ#012QXl<84{^?2={3qp{b~istdum2qHF}AqV3u;6DC7l;X>Q zb+Xg?t=@6KF6vj+)lNyLKjXp&5#u#_G&@Jblu)nGGDM&**aOs-tRH|o_~S5eO*-ID zPQlPHCDbc4S|T#Rh&nlS1^lIvi7YxG6NxFHUXiKHixn7~%o->}&ZBtGd)Db6zF1TW zzo$3c0|choB*3Lf2y$C7Bm{{mXifPys6b?IKJv5qu*u@)% z5*)>PFrkDKF2XY$f$%X15tlcRDByrIxv!XpmB)R>z?0lVOv6y0vB(J%r+nmr;_ALD zlIp%mOrghmC3Y+}rjCTVFGrqX67Q3@k6z4maajA%$RJ@+FOfH5;7P7Xls~>Jn|vNL zGR0mo0FeOxJm;(DKA``T}qgD=H+~8Y7+X(&bY7Lz_EP}w& z$P}Nkrd_qCv#k%kR!dJ#4;~IOk(dIiG*D-tROGPg76D>TmN7Sq+$~NpoXH@B=5dXo z-CAC-&TQ~lBZ6=3MZ@qg20UB%fVWIEn4(NwB}{=Wj!0&~xNO&ztt&m!3E;1p6E$M( zzDz-bSDZ{ZBH;f%I;!*hkNX{>+T>5#8TPmq4WoA}l;8bpS8-TJTZ_Y%8%#pxuIRV8 zLQSX0@jsRUCAi;#aXIbp!WSkz5{Yng|eFPL5mU+QeK*#FJz^v4_@ z>N`cD_eE}Oq+zPCqh^SkJR2Kw_y#pX&WqJs!cfjBc~RJhS3`h1@R>oxba-sg~3JPfs-O zHyAL4t!^*=RUuPua zh|dewHMF?rR5)Qu%46M2w-J4bH3Im9Jmh{}8b+`6XftrQ@I&lH3lszwQvCdaFgOM< zA6dFB4IcAn?Cs-zHOxah@f`NYVaPbiT2B5MHN|{8%tzs)imhf`sO55WwRQ3$%cQIS zh8$&Aba+%T1|P>}mH4G_eDeqzuc`AsnzMmM3O(cR$K#rQYE{EGEp{DsqC z!ZRF!Kt6mSNe=P-WW^a&#q0-tt@5Sl!?oYOlTeQ|Ka%k8eXJkMKa$gP&E3f-< zfGer&G)z_da%hGD3ZJCH2>u`gxd(@asmjQ_M*RFQf9l@VV)BB>{QTtO(U;)6kP_u8 z3nQbLeL1O;S~7i*m@*p~+t?vKntZL$5p#OPU(cL2f^B5bfUCg8qTfiPTfAph`k$RY zdTcy->rD;~Q-G0?X{Qb7Dt61|S;zoFjN*8B@f~yK4BbB?T6ewmUo@=PP8-2fm0x4R zXvP|kaSldKugzAucL;8lP&Wh~T~Z+h87}p1RDZ7Xg;Qg)o2BH0EH>F|+A(fNHs{|CJ$*eG|a~9tnE6=`qv2VD> zq6KY1CK98YN^&q;CYgX9>53`fnDMu2JaU{rxOXMn0~M-rzrYQWWK!JNi(=M&!A_L9WE5Q_xv}uUlqq_5J(z<$)#N&Fo~&R zX;%*7A4NJiz^N#IEwXPLTR9*zwcCcL3>DWf^Qc-1R;`g zMsddR3F>YHz@v~Ww%Fwr3_T^cOu+2ZYU`p45m-s0_MNs9T z<975nw5r>{V9pft$T|%}qaSD((=ZK&DcmbeMddaXAEIa7Zv52#zV*SjpT@7s=%BY^ z96VoA#(_WZk3YKgZ6fc`;RUq4xZHg5SNlbMgFAa9Upt<~ z1b_@6E>@=qnVMorc60Eu+F%4>N zDc4*;(K?rF%t^6%enNBR{mqUIw@cLv1DUM-T?$4xSZCfzyB>UMs83fKR+i?1(asXh z0`UAYXz9;47CSUn#QYVxzuG5D8m0iV0Gf$u365<25b+=`!g)DOZsZmsY9KFb!5p33W-iRsre~vM~U( zC1o7=)2s;%D@&_@lMf04X>ozGG%{T-tbTTc<&+n%DrLnO?d{$HWFj#ISc|f2M3AK{ z7*YZ`*_WQ@FzGv=Icik+9h27YgIYVB{>*jJ;frrCZ=U%a+kk!h+MP@==v|7n>#3-r zFLuCK3laLkJXJBf-;#}A7GzrVT6=b8rPb~xSvj=Qors=Tqetp3Pwu;j9)DNcWEC1~ zO2br9x*s8KRTn#~{mAcHEA>iJypCG(X-J@wN&@hAOK93L*Z#<}=1=~Mi(cS!nTC~R z=?325q~YFY(xz*jtqpiN_l)+ppLI0?xRY2ZN-@4wz=!?A)(n|L*N#Ps3DE)Z9>lpZohp`)M|#Rxg>~(kp797Y!@RqK5gxZtTQc@d<1BJ$lXFq`vI1^F$bFmP)2+ z9urUPwXIb%t6A0o&C8qigG?lb%TZN`vm|6)6_F&`9N1ZNt&dDy^dZJ(U(?Ss1SsaF|O06Mq`(o}+msiFwdiVbit zsR#o9+Wl^6Kew+s)5}jk-0j_u?=(ymMKBq0yU}LEmC05E6J~r*4*ThQ`;@dY>1{tX zD9bUzyzbInp&kP@Z-7iBrhpWd5A3GRj{Vwj zX$B2bLJ`E&u{>~;x?Ki=fv0|lxb#XEhkWN8S{#wJ(WM>@Q$SHGyV|ZSmhws5lrWCT z7hD3w7Q%uz5(*&{8kw7-+Q;iR@^Nh6Af0gb3K5Jnf~`{hFB`OM+ho8l}^)PLLXm6Bd_JPdGsO>UI;e zK^7NPcXVRu+A3kbv;L%Q&$onh&R-c0RKOpHfosx%94|szXFs!OXr9As7XNPR!iO}> znssAY%hnGG@Nn+bb=I7=5npG;Bu}}&>Iu-1Mz$_r(tUDy!Te&a1LqH71^hDWOS$ zo?OfclM8u4GP07gSYY6JblAab{p>5bC(gdQ;howvFB(>g+6CWQ?AdJnAU$cEr53CP zGhSS5ND5XOiLKsq>q=N6oQm$0xq8ox(OEyk=d0b8t&<81?@qR43tX9znD(kd8m5E- zAvTS%2fR&>e8nTs27ep|u1N>{$+z#*FeMZS8ZCj|U=Mi7FZtC1;4h6#wX9mc^{)TJ zDcT?xy(Qw;caVw1U`hzPB862imEpqFakOwOiW)AY;ZDAd5V(^V^d+zpJ^*@J;IQ_} zv|?5)ckBT=M!v-no+gb<F2rSAa6t5eR{o7K1xPd8g-b=}Avd<$E_B|$Wj8lz z=fJU@>}VLSDN8X*EmIc`IARyUtSXT@)8R%C;?|hao|T-QJWY-c-<;q%Y##63=m!{Nf=i&prrI9Odrh3Rio@Mlu`v1o054so(a*-Il>!y6U zo+B>j^b)=*Nr=Aj5SV4g2Ga4+wGL(vM?5>^^>IW znY@uSOjSl^58~IqPfW`$R;~lO<`;&~8u!<11W7cWDmOAxw{U#kNoe6{Au(m{#qNDu zJ<`KzVxncv@GVnwTtpTgVj}}-ioQ_%?Iq`Xl`XfHY;z4gW<|rw+Q=~NLdahEzT!<& z78<51BSR}#AZ$r30g&P2u^)vgj`|7Dzg^f^t?BF&G)##`M&g@i&JP@8YHLsGzlAqCRq$OgN%)pgxbxmTBs+cNLQYPH{G8ZJHC*uZK6L0CZsQ8MwXZFD|`Fqdt$S z+ieI-nX{z-)eSUE0hXz3--H1|{Ax3USNm&gyP$;$J+u2y|3t&+mZ{WljHrtq-`(0} zvU_*#R6l?3$&M~Qe%%o!bW-&sad1JFSoDs$)8mX&c32O+8C|FA(J;C_Dz!A220jY7 z2A`P{(W({%lvHNHANbb_YE>ok@Ace0KSrHU9BUHG9uQyzxocGrID%klI@e9T>oT|&~V_ZgEtqg2AN1~21Ld< zp(2z@CZJXW{dITtarff+dQ5YdQ{TkeQ)tcfXGo7>j`*O+F9s;ao?1wn-OH^ahdr&x z|7HD(SN&)Dz%$ENWjlUh+f%`q6iSRV^cOtcZ?CKK+e$xq>m!HHsi{Z9{y2LILNxo; zCab$cg{?JCHQKyqZI6vKOiA_>>lr?ZSfJhrH90)i>kYSAw@uY}iyz&6-VFklR9b<5 z{UZ-XEp^nKUGYlDVVg(#A8DA9tSXdNh13qfIn(pb(U;ub^TD;XhfNT9+uGVuNp|ilpU!Qu-}`%XZ3rxlOzN+O zPx5#8no~Hd-5S?V51c?I63c_D@~bW)7579Gbh){5o7w=9-v`Q85!W9 zKsi{k3QiT4H(dtgx<%UUZI|O{mr=8qdoajEV(`Tk>=Y;yw9~tJ`%T7C3y#A0(WNBi z5?htSO@B^RuKPkl*C-D)wPo%a&0HAQ{ILbM)!0g%cb-2qUXxvwE6v}rZ%D^bW*n$;1*y$rd7LX7dYeN`<}E*J~!-9H5#TQ zdkPExbo{hiYonvk$t;0IOlGa+HVGbMUTEwHs{g?eBp@+WSkH-whvic*9Y3cy?$}2; z`)-aOlmTK&YQ=#+@E>H{e}$)wW6tX-6*fNj(#n&DDam>Q1-28Z<+71aEmxD+p-zQ) zAI8+lKDEMs9R!v}CeNiydOF+k$E|yBk@V}H$!d^^#Bv}q#t9Xn)PrTvL)FId3Xa0a z(WNx(wQubHR?+cXh2H1VQ<8%N?*n@hQ$=S7RH}{s#NBtDcmKET$f2kuaj`={LTO}r zeYtVfEw-i`1LG~yG#}`62boArNu3=91&)juIb5%19PMzrTN^+t2CmPf`0`ug?tGRs{k|lOr}!J8d1g4<@v?zmqk8ckPiN z6N$A~j!X*3kyTo*Yq<{f27lbyH~Vkf!$*NViFH&Cdq`lm6UmWGVieI}t@t1HhqL1IRDFqPs5bdx>eYaKX4|8{ApNOwsE1d00$!k zv>|^lgttzOiMe2D=h3@u$Fv8*kKs)b5-k(>gIwhBJ`Gbv+gBHvRe6T|fj>FCPs4Ih zIP4VIR#C`k2=D^V4yCOoKdI(^x0{#3!c=_5)zq5 z^{?i}%rkKMesO+?=b|q0>zc7^YrGT_x<)4a83{f!Wz6B;jsNotG2Ex4eE7T&dYL21x+G!6A*K94E zbaW!y3gKt*YF^K3VI-BeKSHa-v}~ zATZ;E^-!q?{4`ON+P}4JXeqVL`Mqu@XPYXc=G|(zSwC<8eUO60au^BVpg<{Du?kK_ zD!Zu&imP3p8|*MM_Q@~3=)mP!AhpDt`TwC}NR_8~x^zG#hk4FFn)R6I8g)FrODL^k z5R4NO6$1_X<0=Laf~**5n35_6G^wqoW9{zE_4f94^D9l|0Hn#vfrhD~a_~mnM%|h8 zsU>fJP=~os(%TQ|B}mVb3@Pv@D+d~;s>*?!!9jE-njr88{$%Aq!<1AxAOnFaha!zD zO$7n0$;yC+<)Cobl~o1diyoMsyTI1axx(wWbt}aebd2r^93*Mn|40R)EooJvwmk1U zR5KdfImE7hi%6q^+ixFo2&YvL2T zdOO^Dh1(`YwfVGv+n4hp7ipL(>WE2*+nJM2%V+Sc=XUQlbpPEkv8#ZyG&0SY^3Rxc zwm%DdW>!uL9LnhoGLe`n>WC?b$Hp_i&fc}!eKY#H+seb;&lE^2Q$|AKnSAT(yBr22 z1~14tFOZ4ElvGE+D7-eu)phFR0k)IfwSjSwlUd)6+b-oVwT@ktxpr-wuhEVK$Qu&N zDT==Ax)3wbGyl!*+OmO7=VQaKYXx6Vo-5dxCQ0A^oZ%xa^d?}jgV;XuETtSU^wKbY zhnBH1mK%2_hg93it_1KPHmta6JmTJHb8DaPrQu0DX9{ujvlYWN25o5T>K}LqDv2yt-2cQ>c!jcHX$!?%d0vU zN7FD>*#B;*;0;HXTj*K6IWTY-it$;QBr!2XV-`5wORHZ$FP zUA$mKSLkG__ks4g=uN|(IxO1Xb5hf=>o3}IX_zYPOeo@}nP=QU(<$nkkFD#DhB~(& zfS8iXB=`e=@?*|4Oci!!G2%vk@ESNvlIhQ}GkwsQg;+b2E03Lt=yzh5hIQ}Vy?$AQ zf3kT#n`UPYq4Xo|3=R9^>;JjPG(AM4HT!LZx@B`7cQRs+tY zk)dI#Ffw6?TYhk3ej>kD7tK$VgCD)l*#?{?6-e+0{-lwiVX81PD-pN zk>@Rs59U?vyPKQ%;F`1Tw#l5A6KF=}FiKO>$j~s^j7&Ea>+jE_Y1(`EO?LO!?(Yw) zu(cgL#`?PW&eV1uJJH?MU%Q|CICo!nFIP08ln9!M941+|FGT{8Ns~mwikYMq=thp_ zZ|O8O2TX9+_V)D{@8RX*sqH5aSxv1})2WaoOv4C0#NFLrV734)a=(hs&`C+<8-yZl z77Z(Av)ZB?Eky+VEuXf(x3-H9db5rjoN*K&E?XQp7s$tGhuQ`NOijuQU1_zq&xtzk zWB+}a2|LH6lAE+^AUBB>vuivQsGqz4R9`RcK`x$C-HVcdqwVEBoylbF=@UF$Cun>4 zY5OA$aP{_bMOzNNT>R01skZkxZB7?UHT6=f0f@jj>DcT*0^`A?9CS|FMj9rYZA6il(%K1PV1DH4=;ffBNoz;L zidj3sLrbm5Oap9yuZ!OVu8Wr-Qv4%OYJ5?WG0Q;#Nn=LCiWxJ(14=E2AQsk-NP&z+ z9+!GIsz2BH!l^OY%~Eng78^iVX=EaeQVzP0#EKazLFCGn30jcl(a1>rOq(tw405=H zi+#XhN^lPYyv@zEu+wGj}dd!W4iGHZn)h`S?z~_?sNtW>%la z+wpYivIrWc03%bj@AwBHR?TtR?ZfFL8E)Am_nX>szTVHiGwWSe9Jsxw8 z6tukBbF*)H<8zQX2p0UoIn99_c^Z4CEORVu)vaCP`p{V0i8PFEcuFl>HS~DBZn^@e zCUSwvikPCu2yNNfd%$*H+e?4j#2*|HJO`STQc0<^THC%4FO9F;`$Eb=qo8PzlEmny zsMJzI36bhUdtIwFy%6qPr^kxdUTHmM4}f`GiL!~c09vSK5+{>|PO2!ik9L*rM1I&T;qub={M@zG+ z#VWJP%r5Nq&;E+%?YB+cytH`@dtaQfK(PY+Aa@M?IlkX=Z_whW)~myAJRkRd=~Nn~ z3YBp}={TX`%1!>kPk7rG&8yR-@j5-=EGc=xANU)uQ*RdAp*}xVJum#{>ocA-Ocg5g z7IAw&J1fY0*$aN~+sds*ICakl&XQz03;~cU_Jzj=OfHJmDP2i#A<{y3|M(rV8ui8A zGArCS*Q_UN9p`r&?KwWIVf?&nY=x`HJn1+(p8vS*NIm|Ql!@amrTrLH;W`aVhZJF) zusr|AAncfND1lDnBq6C31tLz0q6S=2CV)TiOpY7eq%-IK&F-0Z4%F1C{*;C(;j41+ zc+v^D<766yPC6NUcfG=QbXoQE>B`K`S|zRlfe3;BGVQ>GSC)SL2VM-_`?%`e02+3e z_4J}dQ!jPZ%!*ZTT1=+N<{iFTaU4Bow;H!JZ2oI=2qh_>zz=gRH9JA#iv5=3PgFsQ zEqXqZ-i;iCHYv$mx^4$$`f1y};db8?dvNOe2P@cR0B?FafuwIc@aO4foa4QwUNs2L z=N!3A!!!hvL0YnBDwOk$K>R36^sJ|K)1Ub8KV~@(niM#_PQP97eDKF%;F@&6Ke|Ki zNE@p?quWQUPS$P`_k)Hhq14f6iD>9a#O?Bv3d@E$K8<=e@==WbuderizceyMm~P6i zrHJugSpsg^N#&yr2Rox~DY zsaM3k*yy}szvak9Jj_k+?la~Ozj-0$QHG20sThz;8ky8D-MX>ZA!xnToYC!7$)Zf+M@Aig=(4Rw@;F3GQYpcfsqOXK!|?b=pb8(f|E|)pLIC zT?!#B(4Tqr$xZHB$Avp~8IfH5+C>k*rIFP*An=p3y?LXne%%)5-0BqsvXYn&M8>!x zanwgMh**)tdY~J{%8H*OjyvFD?eKX?c39%~7Ui=tXqW~oMT*i`O*!QoKML}iw5O2%;?f@czybf@!d*#GHvbHtHlxMv;m#?`X_zYP z@H@oqMWI8NR#uhLZ@sI!XKj~$0SJ;xrZGmd#tnC#KjF=x9q}(0{?G=QNUS{CVc93N2ShI&0Wy);A7gJXNwT*&-z1EE=b$?k+vRM~yvMb>`2#qc+aDaYP4oFD zb`DpD+(GUX`s>$N$2qp&0mlH%URA4Y=#xvsRAG#-Aa4F9w;EjJ&RKljAvpc~wZ1tB zDp9F`zx%%hpLv&adL9?F+me(m@14h zC{u+W?YEw_th!+P=Z*_@be@s}$ybu$0{*_OwAME~IG!J>=X!740k1+DW(AQkPM9C$ z&?{IC97=Fx7gZ4tbb)Oy8yDP-8^tYAh_20^nLFFPUG+BFW8;3q`yC+gH}v;;PK_pZ zwpOzTHy#!_eSR%Fz@?G3SN7fWqxM#|i|DYrlils6he1{n`(unWjC6|~oX~zF!ASd{ zJ7pf6sCKeq>J*2GmTA)lu8NEqpu^5wY==*y^qj74^XU<{ca*KWR%F9p4YFvMD(rAy z#BI>HX?FFTcb_|(a%0c?j#Et#RHEJh|AjMxeF_{J#n0DVv)uI9`pz^=6?S+aQu>eC zeA^*TEnO1RGlDp&^Oj31Q$^p?Rni^zTrl5Qce`4I`Zkb>#Nr_`#uXK9729Fpc{8O8 zFN)j4BjK)3^vJxWpJ|vX>@euqitb$+m{?dZ(A@MPZszJ?J0bZ>vQ5Ch_3~5C4%l`a z#jj(Op|j-56B@>W$QUQg57G|HGzA9KNGFIIdw`Cu;~knl)M>|r=OKA9jYj7R>@fJ_ zFk}R94gB{`-S}pd^_XS;-$Rxr{AIX-hW#=2_Oc{<3*W*MI~@#-VwvsjoQ{E2hkA~* z3%PxE-hVUC9H!aZGboKazaCk?r$x84Dp3^=-ZEJ9FAY&p``gT9=dX8_`W=ew} z8PP{8mN*ZFZczjN33YDlIB2h4_kE+lwAN?452j(Nu($SzTR~X2n^n4oIK@`*@k)=_ zW(J%~Dht5BeO#RLXntCSOAmAcsugNm(6I7oZ-M8S@waL`a-2W7cO}~c6{>Q-&@ffl zThOsEt8*6L9V^eida-Y~#-asn5hPW9Y;iH#=xRIc!6VOqVs4IAs|GTW7!M+2oOpW+ zh5?5X9N9%x!~Os0sv1sxlf7V2Z4f74>$z$)8YPu6S>kw~Ls6}_}azPGQf7G}39 zV?d87JdlaR{uq1vLz2CXD3s8?ji@TeePcMJOWjnTVt=;TET7k#C>j)}QZ-9TdlP-4R4%gG?k=9_=mgyb)$HKF6Ayw(hv^Mm4*74m3;^_7-$3e58NfTh<4DrfHaFuCDag z1Znf*+lC1@{Or4Y>*^ApcA9Y27SRW;821iyQqqIpo>phfIqpgfrgbwdkZ|tg$*=J74~)x;wH}|8}KI=Hqfx%C>(Z0CbgKoRm@@s zY>45*7PQ3MoAnmsjr5UzqkV_k*-Dkqa0= zCK4-;_7-@OiyCN{D(o%P>GIfH;7=}UpkaIz4m=7GsYDT@rXViJ2nlGyF>JgVm!&G5X zuOe>qxG^p7eR;^s%<@akKR&i6f=V>0!2iIgRUJOtFSHD@@@nvQtH}=o5D>TfJUoL#-#3j$OO!?^bF~*{XW%UNwwvD(vC(A09i@w|6@~Y`8;Xs_=tZjR!w)@edN05O`54akCKcu zwKPl>ruG`*CXcBF{-mj;VX82-OA$ADOfB#y%_-oV zhN;5Tz6EX-YE@mBlw`4}Lc^)HMyL8pD-&sIK_(I_kERxQlBSl1slwEPj^!V{yZf-i z+pQ0t)mgUBC@@Fb{2)y&$V6hQFtrY1OfBrO{Wf4%@etpHAp)nt?EJukAYdTlv4c5Q0uUVf3hl1|1}yd}mA@DdEQibQ zd(_4-M|@CM+scG2_R5q3N#7|6s4m9{viSqI^^@(cCk_0OleTS=TR%(=$Y8N9qVo)+ zSAVD4{+*nXe|Ftxt%4&oOpf=dK!V|P!Sa`Mlqz3wB)~K7+VXCTITe#HB(;tVty=9b z8m0tWjw!H@0`5%is)5FjtUS}f%s%Aq=;`~md(>;*4FZEd4g=Su1OAUMSS2sC8`Pg6vr1C2^e7{J6>vch$0{L*zK(e$VabYIO9ZWTqrXS< zoD%lEv`^|ExZwsS2Z@CB^)foIJA7X+KS#IgtGJgB3^m%=^ee01^OnRg%7nZ9L_D zk)R%O?T|WH>Bz6~voG;8PJFM@f9f8QZx&PpuE@de`^X`cug`XV=Qh4~#dV>TwHnbd z4VFy8JS^2~S_IE0egskDM`@vxA+FX{Qf)XJql{lBKk##31>wOThav74T+-esK*K<7 za6Cmam2USYjgE*+r%(v;O$>08G%__jIwkM|_w<96v%CUB9d<7PnMe#|!bQKVWP-uC zeLZxS?(1B|HsoWEZ}YPp`jjM-*kUjSt!);&Q7{#?{AAuJc(zv63x$OhoWsugRXM6V zq%Ye_;$i?RJuHSf$Hx5k!7=vnrxlMn5AH+5R8b7-Al>+T;lPmgmVTdg!$P>sp`Vk1hZGHc$D@xTXDVOQ<9B{+c6KquE9P4j6*Qr64t5;#* z<{Fc$&@jkv>=ab{(-K*vTs}t+d=XVpJD;on&zjWRE1JC;F4c50@E@tuKKiB8)G=M| zk6hSdzWFN}X2N11lu4gK*{Ovk7aYZUh=dYeh{*H>;Tvl%KXt`!!S(17S&_R3jE44p ziM9s#Tf|1*xo`WnhE~0eD-OQCbBu=BL1c_8E1ABc=QXG|*xi*goIjzi-^ST<29&s% z71Rl*f2mVkkYiYK#l*Id(E@B5MlfmW%F-DI`h7@XuIe%crH6>G;I38((zi0R)HCK9 znR0YZ47o-orp9~&Gb4_Xo|&PZv7V`!U=*>xkIQr~ci$pwBFTu=P@ECVU?^h+m&1q! z_4D(W>ssydKJ#Cj0N+X3p_m+S#d!g<;>Z8>aH#IE-A~OpZ|%}`mxj|Y zRTwcY;wDdTUResr)zh^!v$W!JxF&jr1|}Rc0|R4Sq=Hc4CT3vD(y~d0Yo30FF_MiK89Pcrwlg9f$nLusiIT zZyGp}Nrw%GNTGfMPwEQ1uvU6`3bD#&_38Ck`%t{@S))ZtgR* zZT;XwbslbNq}>oqguqQOwV+lL{r&znV}I8P?vq^vD9?SI%T!N)k@M5cbK5Y_72FLm zXuuD0SC|0B5*tf&nF%occlh7WN9P61wb~x$WDye(D}xb(<6IJ4;y@xG@|nm4E_Q(O z3Jxcn=I={2HPl^E8|UKb=U!wE#p+FChMCNI)48>N_3akBXAcjov%aqX^;0tI4f!Id zyQsa!koheKPGu|=c_j6w0S-_Homji0+5mm4&`p~I^HzS!R~klr{xqe*6SsoI!%1F7 zwPz-iWB9Rh)Sjslx1P$=1-R}yH@77(A!_W)zFSN_j1+mb3f9m65b+fYetsXw-E=%` z_MP?D=hiNuVM?eynIscAh%}e`A}@#4LFrSidLK`}wQk$D2D*Yp3cwxn7rC3cP*&}! zYhuhb)HO3SGcz$BWPX7aeWmQ1ju#md{0B^(=IswmC=-N_`W6C$?>sj(m zj1BcnIc8jriLRa{&(e^iXKH9=sfO0VsP*ync6ImjL!WXksx!;T2-ac}v=ln%BkBFA z+NgOWvkqP`eVO0WvfA76C*K|DaNa{?IVaOxQoDtct?FWjwIBIiYo%UEiq}y~K25_^ zp@Z`gx6^Oyg}d1fe{$>o@wIFER$Ppr5_J&x8w@($cARaMn%3v?(;D{g<4eQZ<3vE= z10eG@|?OH@^ zwN5-XX(JRWi5d<5z@IFQGz@D#+*4F!)Jt6sAUd`yiW)%B6Gm6qVFc%ZV@{=JA$Uj` z)kVRKL?vs#%r(mTnunXbs&n5t&2Z?T$2xak;YUD%;dH!%&L3R%Fu3sMnN!N81Gmnn zZe2^m%2J1cA2{HMc?tmHhqRX?7=Ni-FFiye6g;XGf(%S}dK@c#zA?|r2pLVTsVpvHVto`H0OPve>Ds%U5dq9+HR^qD|qIQSHoc-MEj!^^O#ExIm=O{vsg=0OBp zE3vgnBptxDWR6P(gl4gJ_aOKmgej>Et;>6B#%O-xPnEDa6#2D-*(h8z) zzL5ca8VK7sJn&jx4Pj2pPCr*!AK^P3HrW%hom>6?4B;O;3a?5-c$g`e*w)Bl2z?}d zFv~)o0o7%jKdV2`tL&U{_~q>dEhdUAjK+rK9-P&b;V&(*Uspbn`1DTZ*_rXfrGt@m4JFECoTwfk1H|1*UDX9(q3 zT$WRMLl}T;o!GU{axE@E|eO+({9+7Nc^ ztkph-7jbd^ux(Mt`fvjO&k+8fA(X=q9x1&cgzY0@4Pl-_ftw!CQEVZm0uN`UA>d=Z6M{;SHDzdc!O1B{| zEPC{HSYf6acrhv}A~F@x71Yg4lEP&%2mG~1%v0;_+~-s0z&*SE=@Nd4h840RDVj?t z_5ypsIw)31`6dl<1TgS%gRDOUPU(6)ez9+M7zhCVI1F5q4*2t3LQTgzYTJM9 z@Gj71;@CnOX3UDDtYm_GQrqkp&v(4XV4*5I8#;nJOTEoc@UnXRMzxr?}vL zEV*K0DSG=5b^2fY>JXqYNY!*;}NXjQj?!JH}Pk#!n|MnBLn2F{XH4*bc%(9r-QC-tn5 zm^Ce2eLW*RV-BBVtZN8k0H(U8`j%$KXlb&Ut|eL)ui{yB!Qy5lCeCI#)J!#NS{@aO|(Q)-E<>*Q;&W zm>dwrjWc+EL{ps|VK;5(j@=S9Dr?Mbmku;c725BPa&UEU+S6xz*Tlw2Myt0bPSghO zk~9eXfq%=+-UGJt+FttGCjQ`v;5oHv7)-liSEQoq@H$Cw?9}>=Fu!6wL_!HK1W_}Q zsvSXip2prO%Nz?^b!(TnJ~Y-=u-IQ3nOfvb7@TF3d!x>nei2b!bmxOiB!){5JYFbM zsml^X$95tzHALk1-K=o!9M8F9-wTg}dYy7C(Mmyi!RcS>6c;2emb}!m3Sv`MEpE&+ zXC z`uYYuLyo?cse!&Jk7vTMSNQa9dWCat-RB26yYxC&(!}I|EAHUHCT8;W7&J@+ z=Qj#pRGih6`+_xiH3j)v5d@WJqJaN7y@apJtvC1I)o|j0RwLKD)3EPUnW$AVJQh24 zGGdH!EZoFtUe{rVn@NX82|cc}wGbEP z7l>O`fAdA=oY5v7FE)zwdG_9xh8ePC5Gu%eM)%k;i>M>pgB63=QxTRDIU9iO&RA7YgxlN^OXOGCnRIoQY_@KEFom^7&L`|>vtnM+EA3hA@%M>KGXoNh4T ziFr~Bb`s%|@)A8^*v*OF*4&w^tY)3sGwf3K8yZG0DeoDcIA-{=2rK&}43444iUec? z6)7n?2(0?$!Nych9lO{YXn3zity~BPH_~nfKXAa`|MI8qT`eXrh|JGVJ|2B3jE3D8 zg#P_gq-ko(D=C<>EqdglO4;i*+YYqY9s29*zL_0|0Sjs5YJaJr$xxeM-;fIlshl)k zC6J56=p~4jSMby#hcmGVV4YyKo`RbpoYO_-T7m|D=99f;vFnS@OnJ%1cg7joRlAXZf z&P57IRTR~boM8B`|$S`rEaR3|dm7_~0--TRNzH(ti|4t6hx)$hU9 zOk5aVp@?f5hSl$!*3N$K_HPen|2=vM4Wk!^x1g8E;g|&rEPg}3f3XJ}!{^Ms_)>5b zNqBhOlgG&l!_<2Zp7jQfb?)Sj z!_(JqesH_{pV`^xdFDUQ%+Aive%(mIesyKQ3dbP%^l33bho-aY7J1MtL^0=|*q(E@ zrW7GzZkj@if2ZSttWdnF-zSFxRSg;8PmH}B#c~1NKJJvlc-;k zZi-w9Rgt+WNecug{0M$T;ZVk?rE|rR-y?43>EWdvx;XH(1%h ze>el`B@MGcxP`)hsGpaGe1y`|BEZLwQ355)hS5F}vS93nb$3FSxW8jr!~y5C2ew+z z-YFO}?IU$rxHRl&2w;nh2j*o1Y{s+^Et|Qf>VxTW5_VH9lWZ>JPbZQ@*;zv*TvF|_ zKcojan?)Y4Il%Gx{P!b!t!O0b5k5PdJpqJy%(GEnK~ zskF#0@e-Z9)s8Gi`VX}j?%@|~5$tafs0;?jU^Zc-_t@w3bC zz)p1R2EGuAqb_WNc3eDsmB4V=Qs(djz`wsmFft8juCj%X64?T*Kt*I*5Y=W?uIio$ z<(m^UM&u;PwU^5#7AW^x9p`76zI#@6NSzm(G@dbM6HhYsPEz^J6AwKp zHyCU}$F8WP|CwK?fzGA-1=pd$0Yee5klTRM(IK_ZLi_GMgS|XG0=+C$AZ1xZsiA>> zXcbKCZJJv6^tb2_p5@0+xdj@OTFsD5mqvHVlG|mJbS*P%j#>OE4+Lp7qsCV4PDw+z zYAFkxUVgS8DBe*`@J+V%-wbui;8yJw5|`epkuYPlYJCukNUd6LgzM9)fnM}hjfDN_ zts2~s1kS4Vu}iP@b_?322o9BQ4Go=ET0%V7g5Ii;u-~y&13Brf8VUQav}&M7OuH{F zZ-)&LFN@oDIjmXy83g62jOi^H*olt)iLII=@(cR3YM?*81tVd9NvqZznZsbMTD-P_ z?lbz_tJRuy{M;9tLpC9?gII0upPEBz)m|eNb`~mKeBzolHj@ff9%|1!(w>C<%2o}L zlL~1dTkq(G9~~!3!sLFHUMC2s$7K+Y(|k{v`xoRdmNj8vGxMqrD|%EnS@Cw|QWEy3 zw_Y$*pwB%S*kaPt8JExRXymZr*_EkhOS}jtVZUSR1#-R}y(7$j`V&R?Yg5afE-jvs zu>VTybpYwhpJ!5IX~T+&WRpA7zP&g`4TjmQ*ojZ04^a%1+2BH0&kn4UoFIG6?Uh4G49-Up16lEqKiXB!8tU$;9lJ=?vQoV7* zN-xv1Z0r`ckp1J{YTFI4tTr=hybJ5AZPH#cx@*#TnBDfDb<-4*@ugVz-feSlU7@pj zdxhskyg}kV$#iOBDKE0+`kUe#=QimOLc)yEUL8iVg=el?6Ki+8$FLE#H}r5_KjUZS zg?NzPHnVm4H!`b97wgLxr=)c_MZz{gVpYhg27OeBy0vgBYO65<#X`xWDJqQMz@f^V z9qKgnlWQbIjDVI0T)6dJE6tQFa!*~_yCO`Y(MleO2Tg?Xo*s?l7tT0kRN1rKv(+~e zma8=`hEDoELYgC0ww#b_{)PrYZF6P6z@u?4zbE3^siKSWC_xq$?nGA!`WQ)Y9kxlD}!0 z=oh6=hqckjj+aW+ttDPNEXuUy#q|#A%*74>W;m|D{@lE`V?(##{@Z6Q98ofbgc-vD zFp+E7dTN}YFcK}h1)a?LK0uuYIy6@I+~ zV4*9=&v&-E?$n((P-s18*1d^r5Jnq$ARaV1+N!KayrgnSZHv~4B8TBaNZ4=X0N^>1 z-9$awdNOcIp6)$Bv166%TZGFytZ|>ZWOl9b&qk53-^2kx*+GEEUyT$e zWcDt?74{D+&CYyr^{3rTjgDb&h8D+QQAm%TK}x!Bkwn}5RU$m9&M$TK{&bRKc!$&& zmG$vaRY}^;JttrshniD-WfvSaCwfKfdfsvw z3EQN0k(>+kQK9NqQA_yqr$X5+YxWL4ow^7n34CvIZ1lx6@@l2pjQH5pq3^*ec`3^EFC%7b zx8HF4!J;waoAN*LL0LNXn>YYa34%7YG*)!RCoL8IjF}!4JtMw|V;N`ug;mYjiOK_v zM(UKtJpd?%x3>F+o|lgpWtDVs#fe(`%8{@FsOY#RP$pCT@~X07T2K_t`rj6oenNb6f3K zW3!WoG~`;ll%m5=QEz|cMZ2XLZJmZXnl1mZU}*HD7u^Sec698wasXYCR##S3oPOGw zu{gZ(wq53qV;6x%@}g{sV+nIjkJ@l5vyTlV(ncPL2TjVosA9Rvxy#g|jXx}k z^Iuz+g#A{Ip)(R%pRoZ@tVM9sRq@W3m6sxzDd}ylnvt;I#4#Xgsi3V4H9CMhsPWf0 z@lda^fewo-i?!G)aN2m|SP7d6VP>SB!3QKTeQbb)6@UW(E73!)Dk4C!`iu>L{PeK_ z5>@~X0CdW(_t`sG%Us$C5vtGF0BAxV8z5o7l>>m;Hu{VWfMWEq0TT9`H~>s(m_%f- zv4QwkT5cKo>N7Ura(Ce}8|Q{yI9IFh`7rLPDakRwR8>z&=Wi0{%xCT&oZ?f2yDyS3 zV>kvSGViVjH^&Aj+9w>Yxh1@1cmO=7`Dxn;@^b=rEVGimOTOTeS0LY1TYhvwjE#ZwVjpn7E z8KHQPzp(#7)2{X(&FYkUzqZD6UMdOOO45n^K}@(T4(evan6@pY6Sj9UN_o9+pTR|3 z9zI$dH*Im^;O@|EW^6$JY3IHk`0DWf%ecbjr-_O`n+-UKs3s;r*+C2n_VX*X{(6uX7a94VYdnmli2Q3)=Pp8%-%vfx(S-R-vUHjK1 z%T`!0Gxfzym?NUmf|xBJ|DG7{e}zsjhPJFZWqpMP9swlGSZt|oV)?{GR=mZ?4`nyS zd0h(uoi?KX_Xoaau6Jf9KK`7xz^wY{LxAhWmNVKOSH|np^VrdT!|^WCw}B()WXzl% ze0iOEjlopQgSqa|Fp2XjwL< za_Rs@1k3Yw|DDv(f=2UVDuMhJpFS+v*|wd-l*vb@mE+bwNy5lfDj1!xy=x(@M`yJZ zJF{-sE$FqeA9EI$nu7s~7q3b%i*Mj>iTSgT}jCaD6&^ zCC`uZir3(+lq@{gvDef&XYZ4!1hXyZ@0gP?GL>RfbWqP3l*|qqBeGNE-pNHJ(y}g) zTvJWOR08?0TUGGc=4ulh(|>Zxq>r;|kT5cp3RWk01nfO`UTl54`Ok&jW5P1qM%ZZ6 z3F0(T=9RWbCCU1DpX;J_%RBFgx1D3vyxq8qJ-@1#AFd7X$hv3u?Wy)oeJ*)-s1P}E zb;@!QMy3qCrox;1pk#JXzhpM3WhWP9fE$IrS|yy66d%9hW25n_t%vM|bALt|kUxG| zbli5yKRc|=Wb3X@9}`N#$doBqoxUO2CR_g#*TL51#H|~B7gs;ld6qVvAWkD?Y_v64 z0fqJOGEXxbe+jeOR^}6@^3t#xuW~K+fGI;#frJ@@GNfYGW?t-NK>jn2{GXh431$sA z@M`MSSK(PC>{n6-+gpxg8^d{Mw)*N5`|u0rW<2RP?=I-%g8mCln~>FYY>e%sW?7?M zT4w|RuBm!JoJJ}!(R^Bs4c04krp^tPlpnXbhV%W6k=7fQPq}vSt-33~s*&1U5|%eA z8Mg03>aTzaHJKMv3FNP1>zBo~-RQKK`6g+^^8v+3Sl*~)Se@!3;p4iN7CdxaF>cL! z{+hM*d2!lwf;f$o3HYd`k7I$()R{7el1!#MI*5zU@;$Mw{erhqB+7vOZ|v_dqP;Y0 zpwDF2n8S~1G$&zsql{r2tg=Y9l5-|JEbchmy6Wo^VLK21%L5bsj53hmhlY-T<&83i z(Fs>kQfB~kf?I=I{$nH4%_}-hZgtq#yl+G*avpdOW4E zfwMtpE`e-Oz$;dl{eH-3pu$y$Ih*_Su=esgVSl%dR7@e@aq1uc|w|#Ty^)kmv1CIu5I<$eBfEbSOq{q?M zXJ*}V2$|k>_MtNy+k;-3bcMJCl@U0qEuLM*2+`)P&Y&}OrjljQMo!#;5Zg_y2Y3f% zZoN(NR)vumbZ+c<-Hs{n(0tF0R+tm{*h6&yXBf7jcX4q5Hx2@ z={^%}dWEL8JGa=bd6_~aEN>JuOwGm=D~5L5S4MdaacZ|CJn2Jn#kMFnB#gUMmBzF#E1BI(@0p}C}tR)u)U$$ki1ncs}ZO%M4>n}OWhv2#{`8bk6{Bo#=QF{nf;elVdX z^I|H2{PQwyxgWPV{b}vLA7{-R>sOJ4{Yol<%n(e`PJC!D51#Ad!fU={ZVT)cycBRv zIzgO9$|P%}OguVMXUgn0>v|~Irb3I3<;U!4_3iBF~-cgL+3xRfYOPhe@yRt4tkLEZx;5 zyt#Fwl}WGojonC;fkxrO$FW~+T^G$fQ+40YR#jVXAYsO!OnD?*`WU;@52a4?B*N%~ay$rnCs*y5oC`+BaOxp7n4Fv5H z?WUwUH>~E_vm=Qzur~IM3c;nXr`K>^rKq{1=Xt(}gpnyjdY+W4Fx4*!+W#!T$Y3@d z6euhEp1~Peh5RHjM@o%k?yu1s$LG3=DpyPy(t6({j7*t=(Fu2>g-F(!t8I#Pv>j`e z_44g5kC}(5J8J>L9T$Ilcwc@Y_F1G~bZk&mAgJ{W{nOV~2ORV#*#P1+QY=8*omw(F zQ)i0ZO&HO5XF{lS#xUi8*^285_439InHiFk{uq{o<(*=nWOh)$WHzW}Cl|%Qy!0i~ z;apAT#S{bi>5pMaSl%g?OX7U#1hZ`o_869d*s0MgMSas_K2cVROMB<)D?-8CPz z_#iQz}JW&r?GN@^3q^BECYGkBS}j15D4xw)7`qWXcqbPS`8Kl(Ik*@w(wAc229C zOzk%9W~csO!C3geSaJ7j<`ZdB$wK#>J0-(S8e=Z{FYE2UEG@Z*c=eZz!6t!6?*k4t z!ghjV^`Ox!xuKOCG*V2jJF?Bir|v%Hcp$OL*lW>t%@T60PKmt|6l3_LZS%5?1U*=os#`1TOHcMvR_Swm9*AQ?`Hh?&d6pPnJF(x`w z=Z3FllTt-Z9Phdmb1NS!JHN{b`x+1fQ;eh<2{Q)8NVEXiHJKMv4CLSYVCCT3wp-r) zYg1&}ZB`E-680-81~Nlfi2g}Kl$vycb2L)sPI)a}>6JbWUq`3Nq@t4BJNW+&m^Ez7 zvArb9ltQuw^q<^gqWEzcXUE%7(J$T(CShdC6j3n`=j?0H`A5)5c&v6k#7g_@uFT-s0r0XM_W7Z`fd2ha3w2mt-SP%nynbOF-od#V@8|G*o z60@uRu2&;&?;~M(ql~{nDFgk7@tZ1_^cptbCf>|@&)2=B#UT67CI{a!d27_$wqocwjAlI>oc+;DnsGt^5em1 zDAdOW{C=488=#6^QXdRDiU7`-3n5nfeO#LhH9_#*X#3(%w1`- zYI$HCD>r2}_b$>h606cb{vihyKrarsgUfYMbykxy(OBV_@3qX*+KVouvyUF|qRoX& z*FpmvH%$*)^reDCT{Kve4nkQZyn{o(bv*H|ctzD=iSJA{l_p_@)s&>hDX6nym=S_{ z&fgK$uf~X6sd5f-4S_fyyy~DX2kuCnE_WXJe&e&}hk=(GeKgJn*kRmTvzZSOuxTkZLBTPE`K^ z`MY}B7E87hFNozoU3)J`8BN0c)iTM}DSt~2s*8d5bLn&ep^LhjULNiG#%n;k!t)|b z%T|GedC`eJ3lDUnW7O0<)s=H}B9)UW(f3WhxCg@jFnckNItAPeF>NBPHTmhZ9ea|l zoG1%A(J{W7s5v?n%-f0hQh6y4?pN!be85saqrAq(XD=FW(>T%C*V2 zX`mAwGe+Zc5h-BP-F0dF)pyQI(?867VC|k~o#>M)K_@z9jK-%Bl7l`OHLvBg=vY*# z(vGpuXP1v!*s2+)GU!Cder4kWCWR1z{;wA4waQd-!f{!8)}(Her)&cp;&B={rU#JU zYx9{w>+Jo9OmgeKR@x?JDhd04qeNNmzjR0R3f-k@Y?K1@X_P!WZEeL<+^u;u>3Wn& zoG{np7u+bpbdbz(RtitWot^^)2O}>pajQeZjL|4XqB7Q}Q3Cnh+PL3lh-2D!EEXMR zKXGs?5@w7>33Sq@Q3CnzI6uAgLD6(fv;ASq4+eJlLc)yEC|yE2>C-5I{Pd|vB+M9% z5^1^?xEv(1RtFC9%c{38_tkbbNB+)aL8+k?Q%RUH8l|a7_P8AvsywrcjXW&am1J%o zO^y8IMW-g|D~tBDGJLjd zwL|3Obz6=<=UygZ#%Pp4Cw&?vkiWylh+d!U#Vw9mbH;aCWb&AV8KY4WAf4JQyLZV| z5zwRj`SUxkT`#`}K|giiAU}Q12MIGqqePk)lV_bIL%#*P-j!C5e-~%T4-ckvqG85p zl;$G^?nJFWxWKl~=M6Qsrd<9w@~2OJL1&PEsCZsUONTV~W}~7vO3rs~Ov3)(D1o*9 zQ;kxHw)a5LGM&0VJDNYSW@@Zsc;PG0ZY{1ia>r&;qf`+Q&O5&2oyHP}+h<~;_FTUC zcqIulMxzvmN?4yp3FP0wtiwrHjM(I+yg1dzV$~@UW{gG&bke6$0{MeiZHd?~JvnQ@ zmN#o1R!vw)!i>=n2XAn2!!63G8-|E&#soL(o~%P2Q} zD=%~}2{T5c1Uix47DOUzy;B1D=lJw@;<>yKMJpSI*GMcsfrJ^OQCf;*?=AN6Q#kMa zr`xs>am*OoS_sNhIjwo7bdGbqaCBwkuH&zmhB$#vbnO3)5?J$hX_SDeIH-GmjHz!m zK2u_%Ty&nZpgeAWd9!>?#+Ihtmrr=q#6tb*c!aJJ%DC$jn^x_eW{OILo{f!-T9iz} zjM47gL#E-iaFLXiJ73yY&vN(7nfuOwwZNk4Rs~Ewfc%Wb&MOtpcLVSAJeUxk^lcdl zGe)}uIw?FNgae!{96vRD6KXfGUna<&7oGeAeBIq-r8;k0u{pf0*_trWiH;eg-D!j5 zZ#!#YWivZJQLDW+%gh*6*5_5H-s@WW9JASQJiKR#*?XMtnt@Jq%oyzs==9ISaYZ^v zs#LjChn28K8gVzTI&F#+S{!nn+~sRp`{--?nl=TU=-97pcR+3kNQ|G>n>~XYr0fz8 z>zB%U85MlVqcq4)$Nt;x%W>4juM4I^;fL9DC{FhYb1Tg<*E~PKm&K;L2Q8?v%o6)y zjov<9+hX8R=t+*wO~KHXXRpmytQ@emX0yp%EIN+DB7l;3s$gZLG<`jD5(ekskUeFE zQ7}_hROP_g>5dacl{^?bFi3+8%Khk}xY|R2*`2Vym)N zw^pvp<%+=PYuQp+V|mk2!rFVi-FMiXxl*oghp5;l%yDoo#N#w@Ob;Oc%HX-p&N^9` zRd{W>F{#P(rzA{0k8GU^c>0P$ZA7oLNhoqBfhlgX{ zOBgL5*ALqIvC`sr(20&+Qp+SqCt^9NUqY{P!WsNbc8%58;)Rx3s22KEAD$(oW;S*rVTZ7OXq#iod{tw$!pY7& zJ8M9GW=fD#_|@UwB+2oS>jl%-m)r0`K*EZuT`A`R#+QB8ffg%mUDk%wQLb3HqnB?M z$WF%|5oOO8g&{|9U`*97m>L3Q8hklE+Bu%q^VJKdPG#*fz$o z9$lTdDzL{-SDXU@LH_1{d2#IJ$c7sqrJ5kg&S=1hoBCI(0?Y(zl#ejk#{? zuj*IxXhgCmfWuTM9bSu|_I=VDqbV>VmGNZ+!~s@Ma0mIjz~df49t>_PEC# z(20)KFoI4>bj|v=lNcYIn@=(S8X21IQ)DlQfyDc%-;?z@66`L%`s~`5$8q~jFN_AA z=vYn2Ocj1rISohG)3=<8l&~oBQRW-S-xarp6Z8Bt=tRe;$1T5Dr(WoK+b$JtwB2s! zoQB5~NkiPkXF-I#lvDJ;F{A3ZI=1UFtZB-%Go7x0PIRocN*~z#s&ax6^yt?OAGH>n zK5$CU+S7Jty)d|bUUZU9t>WEP@_5R%f32q-VFoq=o#bJ>t@{NpYjYt?)kkX4%))MW?xm=l?C*-hrED@K-5s5i`K9?`xFr^BaOvV#2 zN})u~K7JN%{y{#$KK|d$W0LQsEx_)~rWWuAs|RN9qg^Ucw~T zeI}{L{K;ES4u|)a*=|^ z<#JdYu|&+{3z;GbU!;(sKZY4fkDQZy4TB2QvLdKJcmM#or~z6~n!o`efEjM51(xY-SJKhZ zZ`;<&nFCvpu)mb@*b(M~@~_Y=(WR;);Hb9vAuGcMxlElqHx`dvSKAI7Yd7J@o`?)9 zNqZ9IYoIGxzU@-i{vzLH%{ljDL!vB8lQ66xMGZwmn z0x4fEkn;F4i9+zpJw1G%eVI+W_?xYcx$K(SiZ!C?a2AMcgZ@|T<<_gT%2S?d8_&PD z>nXer`%~J3DHeB?nqNCw$Z=IUuMZDgJ%*96zm)dtC?+r%`JnxsH(F>Pq7Us$RaCq^ zdEt|M#@Y(^D;@MZL!y06B>4LWXv)eXXZuA-quv#*d2|&C!wLddzWYa@Js)*wqzW#N zE9A1cT!}&=l?tRHfkGr>^W-uPhfxJ3at-tufV%azN`DKfzki^YkDo`d5{8>mM)cnO zU|l-5R2H?Z<%U@{ z(H*wM)gE$T0}1=1$*xeTuJHyoRAr(cX7RvUW+AG``Km2-LjyVDC8#jj9;*_-m=pw@ z@Z0ypoSS=%H@nH`avIwMy{7Z*_NliksP1NQib6Q1T8l#Ev8*5x?gGIlpQCpjnw0K+ zRW{T4vUy)+@!}*5>r1HvlL$Jy_8X}543_x>1q}8W2|fED20Z-e80-=3{0ih3!+mZMO@1>d#6D-Q9## zwQ3`c#aFu@U`RG*in*36TRf~)k%VCjfqk(i*>s}7K&yKtm_VV3B5@vu(fIU>U4A>IcfZ7g8 z=4@L+I!%fJPA9wmO$Mw@sIexLP-%qq$bXZu_lp)@!~9#FZz1NtJeQSuw6u7!`7KN4 z{2n8)tYAW1Aa#(ECb+R>?O`was(G;n(?QlPiu#GKRb=zNzDiJ7e?FaP&pj*4QTtK&H^Wf(a{i zAKdt(-TM1gwiVlY=CV4qaRswLSFP1?e#RZg&0dECgh}taXH_R**g{Yy+0KqwX&^;* zP`_k0sI~)j&;@nWsLDv~;K*F;c!|(sh5V*`acRIdH>niS_}S%mkPwPXRb+7ZLjX;f zkDqvSJls+m7aRX(dp}c3J33~7>VOTJErT}INit_!6>`v|7~qDZeGQe+I@8{&k}PVh zbG?3wVhy7K&Sk~D$)E2wp44$!?;h#}flJ8}8B%$z zn472KqEG3r`{rNIm~xDSVGAKS)M!t?Y0#;^q_OOA1dzR1qdHySaCDEtV3?2%ppP;{LKE?2jh)=}u>2yavk~0gWLZr-5U70A1;yCMRJAptfPVHQ?0i*!pF0Z8thCX1+-p z@q7S0m)5E<-M<@kTEyN=E!}<#eTGnzqxz0HAhl}NbZ=(l{=Mb)lH7AWRNh@&e5&-Y zZCP{sp^00Z4+mZ(VdQBMEIwZ>6DtHFfe_7*;EF^FK1;xs$`t~>NQ|Bw{}$6CIwBUd zc>Cbl7@2)P(Y9MVhI3aq|BM+B4`vA8KQ`FRu}I5Z<8H4v*d#;Dv# zK6)ftDIcH@(m3a$R}zL5 z1TK8{nU-irF5wB#vC|`148}@M5gOi4h zDIGehiSiZJLRD;V_(K3QxI6AC_f8UCyg}ITsYl-0S0-V9H0AZbd4*Iw7%fh10_%npMEt=T>n9xy)`4P*HwD~CqjX#3Jnf_ z2%v+-(5vf@*|%;u@k+&c(vT0|NSFZ#k8g;wWmv97Fj7>uJs}53KuQD{y<4L{;jQ6P zDCkW1hRI8;XGpu0KU<{Z_Ta3~gY!Z7R~cFe{|XKJ=}h<@6Z}8ccI~>o)8gLan^xu2 zS1$-$N><2_1INGW(@R`whX2O(3u;6hj3Z&#LSUur0x~J1DjM~iAw_o37@dPqDa_ZO8RChd+AJipUb^OlUygoRe8+Ww)A~$=X{VpS?e5WbZ4wH>Brfad`z}G z6nbIX`>?Eb0o~OZh)LfN5o7$M_v}gvucvPY?Mi)=YPykxVGDtwa!5}ftI_$BPIR8; zB0CqwR(`N9nr$~B;=!lRDFM6pHii>^Ms|>Y^qw)CO%9*R)gLu=-s$)DaU|?7CHr-i z(RC(!3)lUbKDG_}G)p&0v>5U&ARlDktF22@R-Z1-ByK?1IQyb9^Dnj5hDvsqCXu}n zB1TZ-n-zPzt{HN)Qg}!!(}jge7`6}?Du?X9#>0D|Yqk$gn`bR?zOcDY$&gz9YgT|9 zKO;TpapL5Qmn`|`qakkwt~pij^8gZ-0U4n{&1=zbMnCo)-!nqL>bA}XRXeK7<$|+q z3aBQ<05@E>2KQ2RCcOds@n^J=-bNqN`+gefzf3;!*p5xJ)^_u4dRo08a49uLhNSo7 zNf@>elu330{epfx5WdgRF1yX0-Ff3D)ZaPlaz8%Epotd{2LW`T_v1;}UrKoF!*nM6 zuk!LCrh0T~TAz%3^u_*}!u#ftklkY(l1PNNM#P|dc@l;#1Z2t~{IBuy@Mf|;ULN$I zdwCM}my#a)Fr7*NtGs-&KBO;{QQ>%o!n9j-N{wafg5D6P8Z<$~pnG`|hAotv^aVFs zgIggWJju%|5pLz1R58}|)E4Uj1LoI!Iy@O01-_SN$abfKR7p7<7lP#96UR@}eV$i)m3Bwiwa{X%W4|B`)@&2F( z-TRZUzm)XYx9LoJ1A2e0H@0s2kUk*3)ekkN) zfTk>ZKD|_x%?~d%#-pVVbaviJpZtb*vY)n~&iS?RRS$G}L*j9Bbj2=nryaj6eQjr6 zYTVR}WBuBZFsvY@B_*XL+U20>2r>yzEMdy!Ts})C=AehPT!lm?A%5V&LSzX?gv#zadg_rl8&?V2yo$UiMLp)9c$MgU?kMuODT3Y&U zME85grtfb0ek}^x|WwGS&pJf?uj<_Lr$CQtFp zUrpbJgd#0M0=Pblkbo)Zi;$48KbrRXPe8yoW;*xc4S4I?SKCOv8yeHlx%YEw{*Vz# z_Em;#y%MlX&??A=RBu>_81!3L5{4~=`1i|iU12F%eQsSr5BjYu2{Qoc@sJakhYISp z#u(lrv3>~I!vPQj2}p?mqd%U~zsJ5#b%}iVdYcDYeEl7LdNgf>y_7tc0LHDhmYe#T z4j-g$N0_Yw0q!0DZD`pd*2X;IoI_km_?vWwV*5BVX|V(O?S=a9~+fq3-N&0EE?E< zne&FXi}r*p8unH;4fKM4dcYVdFA}yMpMWwlL1P9CYKEz!Pmr%NxTB}H($|Ag1A!d_ z2KxlNp%04%`Y8Rp22=0uEBpg}J%SkxQS@jOrS?|;7>m(vf&Rh%G?Y@b3`(9GSA8ag z62ub4=BK3Kl~KZ_>6cK5WpXx$EmLr0EG`eNx+fBgctV+&$&!e;Lbi;O6#Ne|N*R@f z)G0~D;2(_ zLc)^OGWmPTUd|DqHCebKK2I*;3dCHYlr5AAnGzP4FJ>#mY^v;GDd}HU_JQb9FP5io zcDI+d7nZ-ilj~e=Gj)CRqfgnlZ^~3ZOH6JePzSpn_o2XN#g@Jha_{h{UMDe#Q-;4?{KF|oPz2d?nUjt z&it-ky&5~f!Odzxmfd!<3YPEG?TA}RF0zBzvwq1dHbLv!RCZ0O`S!CH3Bw9fdQwKW zM7uI6S0)v)q%8EZ8J8s$idcM!T*MW~nQS&%$4g4BMIjv;7>Jf4vgm}yb%QL>x?NpW z%>;d^t|10lcLgNGwF5M1c57^Rv6G#2=Ej55=C&$a4dMY;e(n1xOnk0*aP-(EOQO75 zVZ84BofC^WpSgUw@7}eeXZltKW#OM5Fh;rt38R)pRb}#*-t&tak- zf`G#nFcl)6NX!>9rB=K2I$oMzt@k-sIPiqq5V93mmo^pi)MXMJFj!E=yaXy z?uDFJ-f#9&xLV1L9HQQ?;I1bRk)ZQ9hsk2wE0<5az8SZ~H(@6U`_;XEBo-A0q2Hk+ zi!S;seOPZ%yA8{QUwfT}2#CjN;Fumj2P?-50b}gnTg_WR@Xgy%1+&JV6P%T<+`^_ zixW}@N59SOMeEwGH?L2^u!59@D56-RT?P7pfJ`D1F@*v)SIXgu*gP&%z>Oi#uTf3{m?&l)25DUVwSwQ?%Um@8Y4s*(;r=vFl-?(RE~$w z*V7!xstEf3>C+q-%+%-6HRwTqbWOqxKzi(eKqo4w+Ztndi^TdNWZM*CAOR^6V1^r< z9HzQNKD>P2$66j;$5+sUv*p&W{(MpFRy)nA^Nt1;o^#agh>a{lg44gCLBgg2pqWZsG)sxE5Q&8{G&aeU!-oVA`s==xq%uEa3lfU-1r3PDY0&Nu0aT`c zDT9O=fZoRQ>H2qK@Wh3D(A({)7JA>&hu$IH1M41DDDUliKXa>>*-_%^&Mi^7(!Z2J z!mxrAF({%~qFs@k!(z$=0*Me!!;rCAA~91e7oc8^l#S+U2xLZ@nL){i#OsXy_4!f; z7=Zqz3=;N7ll{-WMb$d@E(AGmojWiR$+|}89jX-zY2Y}i8#}5MsWE7Uh(W(aC1Jn% z78N&EFzy!et=^p){VM|Qry8>-uk}^3czy1Dvv?6F7uy}1Fs2J{@{~J_`|1UOOQ|&~0eVlK zgkcNiDxmz$%Yv-()RTuHe|>uLpa;DtPs09E($`c~KAlN#zMi(!yf|ZM)&?C?2oPp3YFR#2QEWZCR(l9g72ZiFaBT{d=^#X zyOw8=L^}6)?$-I-IJ0|(rj?~sTqIl2gAaU@Rxj7-ddC%>@@M~^5(DO<~x8^prE>vfT;(t%8qG~MQ=Z^WH-@^ zUwh#4rs*Wi0JX)i9}GK%w77ID*vowMGv@?WztfQoKU0fWYE#&714A=aHqFPKa|oKV zrLkr(QKZf_V`R5t&)JS?rb{kWN;>`S-X>DbXom#f__=FhV@dqG*DhI;AGDp_o`hiq zDXvh;TB2RF7`l|p<_MW$J`2rN<4f2aCQr`dD>xhukIxqW77L_@B0*1;G>ID}Z}w?q zm7b|Z+xBt+H9!kW6F49QFhi^K(teYi+c*C--+XtA!qtOFm;tK7pEy`FMrFH#qI_R{ zC?D|dXqy}MvNmkT+7aVx%#I~d-UbQY^W*q=m2GajWO@%-pUymYgM?uPDQZy4TB2Ph zn=6qs(R@6qkja&!CDNrL^jfll%|o9AkV%EV#|N}Sk)R$=_ut*(WR+octnR!AVF@r~ z`cuk-8P4xM{qIS%n83(@qcd9741Yz!{%FeU-&cYqUqdJ+Fc|YyTk4f1ur2;%3Z`6w zDgn&xhLGLkib9`{)9C0Sdz~G9Ldx4=(_GB$BkwJZ9Dc0*2P^_y7I&+~C}aAUUq~2M z1J3=OK7gmPB7=v-(&x)Bpey~$FC@$W)HdvwUrdnTXOFyU((+az*;1=nC%0bbEP=8C zgTOy2&^tEzQ~r;?Jz&I@D5qfgI!#^Xe#v%8;s#RPkRUtKZx2XVmb$(F=-Y!Sh&B4$ z9)MNow+AH50JX@lw+E*|;XnEIfcZ_!?ZFv+`btH8kEaQwr!QAne=zxBuf#*7njuBy zO}{-LVdUEbmO#$o2t^7OmxGoiVsp@40#C#e2^B&Ci-X>O{Vi?}A`vs5wi^>x&$;V} z4!2(~uRKxo8hk3$b@loVn0f#+&~Fb&m;tJS@oo?FZ#WFoS7Mgb(pPdrC9p(QM0x&7 zUIqS!8c!v+y-U`xj{Gbt7e!*d3}ssX!_sPriuRX3xy*?wxpknFg#GS)C0JWppS}|4 z`b}9TwYkF4JF!NGwG(YezawD=ptfQAN`;Z&`Ryy|KYaq6(!yGgn%-bT!bcL{<;ZNl`_H*_baeW_tY{H4&*NPi5{4C|+#os!%_&0vav6F> zQ6OdVBvKw)y8wML4EcM$gpY8!RLbXn_wpViEZqEqe1d)aznjN|{?4K=YQw0E@sGNs z7*pTEofosI1^iJf{NsI`hRThS5+UH_m7aCjHDv;E*{aZ=Jt=Kg@afouEqi!>zLg`iR3)O_4Sz zLg(sHO!(r~TIEyw^%d4!_1hGAOr3Q2)>(lvw(l97kyXe~5_6=~Nap?;y-C>b-W(K1 zdfccGT>5%?4d+#gnmc-)=ZnDfU{Lti6hPN9-%2-@zl*e4GV8X_PIkM7B+LMHz_87M zITF0YnRec8cFhuJUN4_gDe5|Us;XUK`mMA6%>nKc=c73|gA~xn_hfxK{U=Ay&iW+# zuqQe(eQH_HyVfMW+oG$!d%f>)6~{eKH+jk?tX;KRM#8Xy6mQTu-TkIxYbev2LuQ2tGXWBoYsgIa;5k4z}yG2knx0a{R+zyTqE8FunN&h99G zVX|9kKXIh5e=!o4p~{46)%E+>lJO|7|LnP%s$Rl4mHK(U5v|4YKWS=v&$q;YNh|+t zzSAThb;eEG69pSoraE_vtdrKPtGGScC9$$e)j=m7PbSqFd!%vVDe1Oamj_EDpAJrp zSnLK^vX9T;|}Y^Abm|EhAg_Z5^_0Rf4*maUnRMoarMzBl|JG_!VJKB!*=l(AceiTMVGBVyBicCEZ_zIhV~ zGeC8~9tdAr^Ri7Uxw8|hcCxJs$6!~LZB^0VH-OP;uYWV}iysO{p)RGyyWkL{na&J% z8Ev}u+qJ7M5uzbm54uM-RHqv*5GQ0a`a@w7_TPCZ9FI(?&qHCb3jLul2{S-#G3-O( zG*I|YekgngkyT^Oh|;HK92{?P@sgP98SliIJ-+9Lp`@DOjLMt-P?&^~$A<(G9$T!C zG8GCbpUYAR#c26szJSe>a`|$em?!%!#)smN?Zg>PBi_r>uRYveX-?(Z50* z1TX{rp)d(EKvnqv%`&ogUog5_$iq5V3~kR4?x4JMZcSPYyHfFb(O8!_|H9`>O)6iX zRA*ceF}y3!S{NMuP_|;y*mBjX&SQ}a25J3L=Pqv;rCLZUwX~U6u8J$ykB+LM0$Bpv$3!`6k8)t*69gv$I^zJ1Ybud(` zf8UFA)S0UdzLoFgEL$Y0JmK7y)RgWjhXqp#WsgnYF9Ee1ouzq2BCjjLo|qQdTr73URyc6Sj_=4X@#GtehUlQ08N z-gy39{~H6tO!_%fPD`(*FDfOSS#MdsZ}d9n`saK`AD=#E$%y_W*28Qf`VbHa``w3t zS|bDLGXw;>(uaUZm;tD5*dd@YNbtKax<$=!O3PHXKC!ezF=wdWTI(|XUReJjAnGME zbTyrafEp$*v7RCAQvPg_j@yH?J`c{v5Kw@&l@9e93ERWy=>8K5%YRu{}e1$A3v3~xbhddRjZL}*eB zaKn+lvPx*3NniJq+0r8}j!V)!2F@FqBJj!w>HEIWG9lWnupX^MX8O39M;zZ;zbtuc zUFZp)mg)t8OQ{1gTL{V|yMTTX>66ekpG>H`E5oL8 z%e}H1E8iqcybp3{;s(S)06k9Cc1rej$jB=8&&=JgdQ3JWVSg#<2ZQ}k(3$kQ5B6&u z)7h)f1c>)d%esVZIBOq$;M&FIiu2Rec@5*|5IQ2|8Yxc5>|KN_>>pN|o%!PGU=mhT zWdt}Uo7apYDpWmZNRb^hMr5bRy+dV^+OSd;}&UtLnqHK<@OGAqGOn>kY~0|41+v(>Eu7$Ps4K;xEh4KXyMbk z-;MFEEkAV`b9Y9@k(;$Z3p%zLGExOf3nz5YK^crb0yhkO0VUX5X)(-W@KB|Ne}C0M zppQqt!OErA<5v;VZRR&x5`FklDCI+#HmM2kI z`n*_#Js@>o)Z~RO@m&<1)4djL1dGtI|NCCbqIsTWqr30bIQbZ+-)nTtdM(iKb=B%l zgIiq_N3B{`apc0773y9RJLXP^1b%OxReSI7sHEFMdFsi)DPKvLu^jW!R%JcnC6z;J zTeMCTISd~H#q%?=gZwd*`}9ne2Dt@fja)o^obx3T_9r=Jkl%amyx977^Pda5$Ao3J zjj$nM1?ZTyxFIMJ2w%|ub*l+v=+l!P{CI7TsxB=TnY!PfJ3Vm-o8+)NBNDvdrLgbnQpaP} zmhEBUoOX5_&+RG8Y=#47l9tP~VWtAE$N%J@TT{JlXEy-CS0CKb~+WzDl1n z4M8V5hM5d`=Jcdjsmz5LpwskK)wz&kcA&Dx5l~KbXB^4cY2T=~q8x8~v&ah%Atl7) zG;mB0ApgLf1453uRBN`beVZ`r>g5}eu!48f1!EtqZ(i)MaR)bTyyI@sux4M@Wxd|% z4tAhpf2niE>zV32l3~DaH{5xo#W^!k>!I^Qo|c&d`oEGpbPi4n2tVZJ?1if)kOudr zyC4!Y=6vzIpm6qxe)MQoigno*B+MAj`5=;W?K1aj*5bR@TBO|ES*n@&Bar=PWC!`9 zUToc;E>8Yb-DzG*&7@J8B^yk1W&bHt$GvC?vePllSjaQS z3B!{g2b4gIg&SxVwr5C>y0_W#Nw@IOgW(Bzj z8AV=x+i10<;}Xz~jupH!E?7H(EgTb_KdY}>Y*H^jObE$MiH#l9qfbU1ben+1QavqjF+8!xezj`aT!}1D)MpYqUm~f!)cVk$h z9S&crkO*ZwottzN}PN=<=pl&oxuQfOx^M37=VX9TgGQeMH0C}$Yruv6123b2z>}d!sdyY zECr8b0D})p|6axvR0-L0-lp-X6J|BT*DkEY17p%L19)xY&3Fn|QA>BPjaNz6xhrkJ zb>tb^-2PrOJ>0$<-{KzE{&w)PHuGk$-MMSKdOr%g{jP`vS5{Py2vsT=2PCfdk8{b3{PkYB_p4)H>q+v%WwAleFZBcY>6p4V zr{p)dQ~o_{aqz&kK3AMJ^)6a+cSQi^)HZKv{v4hQ&#hYhWn%Knh$bJ%5@J{*n zvdO^{O+tg^E>CLqx)CdEUt=WLgpU2u&RPHQ4QdJ^;$eP#>o+aFH3~)QJZ8LB+&;yo zZ?be5bKxPut!lN@D-iar-BB5Cs{UePv!dQETcW$YuT++?n1mHY>2S!Yvjyv0Z=nmy z7Yvu2w@Q|W?=ydCS-jB}kO4$d69=GN0pxdE=Xj{STRLK5193>|D$)OZFfNQC)hvRc?LGRuRSl0&Dw|7}2yu*^U zy>^F$sr%>e8Cs%z&|6z?BxZ4iQjtKQkPAf;t+p_DuRGs%)jG(J zt(F&q)~Q|M=+#ZHZC3XhQtT?@^)oOi9W#J)H{LLa{?7e@%8vPP?l2)kve|IGC_1Hb0x1jdBku_)&190vTA9};gE#B-9RTghKUGy z<~TIIfWu;;AzTiV&EtxgXa#yUi_1rg6ic{F8HX)lR7I(?oqPX4e_x9Z{%F>)+-rc6 z$|?We9Sy@VSj~k7@a>>>q|KJP9bI;cH%=_c=YA>4BVlCU&J{=$QiV*QKy4hCEftAm za+XN0;IR2<7d3!dP4ORf?qI!@4>nnLPCRTsYw_cwtqw@Wkg&hhx#JE~KAd~Jwowr` zeWv2I>Go;NvcQry6Pq>OZryi1@yTRQRIc=%I|(y}bH9!Jfj&KVke}WtkT7F7_g+Xg zeR}R7KfRYu!Y~mjmyFI)tv@g2%GnaJSRrJ~xI#HoBH<~}LrbBM&611Ra$dpr+|iSD zhKOyDjytGL@3@mN4bGj< z3HwWZJMJ&#!?(Zss-@$umv2w*bj9VhLnoJ|w?azvUiaRe)Nv>I8WLs<-wynu`)Kf1 z;IiOfQvmtt9d{CD4BrmV8ujV8gZ%VPItjx>q-;YO$r9}v}YjO^QmVwp_9-X?}+MGV}vRm9`P99b#{=L{^~jjQ+Mo?76y0A2C;~i z_eimI!SE{MV<^`aw709k@@QPGkZVMO!`q3nNzX`_0UYz6I8g=D*_e*GuQtc5*X!)f z?H?42Y;aMW^t9H~;6!nA_1cFYruIR^puf&e!i?pZ^?98g$opvVuK8UGn=z{Fb1B#d5NGleF&U{k$t;dz!S;EJg!v8lyli) zxdcsH;fc}w9SKj!VRN`zO=0k{mVBGF2r3uc z^3idJMbI@mceKQm?z7GxE$LtXGNY}-)*;6Re~4Y2Omgo1&{gRjcM?_r&K*-reVfY> z-bFDduSo`uOL^=Xy|HMuwok5Ig~Ui?ty~59>5T#jD*)#X;?YAcojj3j`gGhuetO59 zgkd65LV%$dmgpaSDqD=E;&BBmk%EgJbxI^ssZh=lvSf0;K>DlZt_YDAGQjgqP@CRy zCt+mg&SnWE5`{>PoV$Q4Q^+MEG#Q^Of3RDDIdN) z9z8uUtZyH@xok<{6P9e-@=N;~C&c_q^6eyFL&A*V+kszn9}V6L!CHMg$WQOMlQ3iW z_BbTFJ{@P( zR95-!VZz)M!*tw1ZF_v|BrUu z!Fu$LI|=)voqIUNV}0hXSgXz)hs*>a&ntc#@Vh#0Z?w#8gr;MOuEM3gF)9DaCeAmg zn@jxkYM%y>S_dzbsqKsjWsgV>KOg8`JN|aSjYJY=jMkwtkT!U3v$IYXW))tWZcJ+O z{3(o}&k?br#Gw_l&} z#oxmb6v&HCi_7)CdfeuDz=rl|VW}6aSA$M;3^N(>q;5H2C;ubv1{pm7c}LBCE!^ca zqf2w|TI*|feSD0Bsk?PbhySQk2Ho$}-Zy-^?W10c%{%OPHg(x>5@rCW{3p&^!BjS; zQ+}oGyH9=famwi#BW4|TY&LLOnN{mX#Ce&KoU#%TV|MuFM;QvwRaMvUW+$u~XhFh^ z;gr*nJE`7m_0((jWBM(L?Y*P#4UdN4VvxvMoifP3>%q;j0gCnshih&LZy6rYf`l2v zDSt$=drCTglQ?HSbN}EJpCa6SF|Rr`HLIRB&9z*snJ@e{w;J7P5a>k5Fq0wAU*(jc zJRs~t|IKDwIJ(I;E12!l)~E8q;0`5E**kaSr`M$d0&!4u}zVHAQ4-inysM;+m!ic*&c1aTquz zM!e{Vf!Wvm6XNK0wgNycz@b3R z_6}-sunX~6Pc#db;TGucsSFD8@f*M(W%VZ|{XhK*p3?uP-w#yDjruNLW^}P*gUD2!;y1& QERj@{>n)*u-=2Q_MFd;kCd diff --git a/Unreal/CarlaUE4/Plugins/CarlaTools/Content/OnroadMapGenerator/Blueprints/BP_BuildingGenerator.uasset b/Unreal/CarlaUE4/Plugins/CarlaTools/Content/OnroadMapGenerator/Blueprints/BP_BuildingGenerator.uasset index 0e6e56b65057b791efddd4c75e403800f0bb5f33..548e86b220e4af1827aeab377bb3b2390d5aa86a 100644 GIT binary patch literal 1164904 zcmcFs37pL3|9>2%gisQd`^de!ZspjMb?vfCA+6cn+1+7wXU)u7>k2tbC8O7*v9YmnadF|zn@2`OMYn0&IyNjS zG8Q7n=U*gvd5942Be=eo5S!Z+6JUw3tYV@Ks0--dgPz*q#ciFJJUY%uDC1m=cxeaHczQGJWx)-_{|QlW#bi zrbXsG<4oC09sYlLtMVmz3!L^YE@!&kEe1c6TJYfiE0>sLUqxj`9`WYnS!=_B$RjZ& zKF8y=<)qoud)Pf$;{2qo=VZFroJ>cKy;*F!1C8oy)82NEE6<%~_cTjFqI8=ZZJ*|L zdBjWWdaUe9yw0|4yU{}w@jB9)=`Lv2!{)WS9X51ZWUkHa&9>)w!@`^ONHK+ayIdJ5 z;VB8ZUeW3H*>_cDj!9{5N3OT9Upu>Pxmn`Gx1(Yz`bT>mPKUQZ{F{9KsdA{Ud!K~V!S*z-I2YffLrqhhQE3Agy3qw%eSs>7sGT7jK~f8W1*6I1^m! zr9XV2D4q0&;g1+7wlA%?PV$=%6mPAWX82nS6fe$s{$0s$IZ*sD`L=gy_aeo|*)czm z8=2}6$DfON{$~2qpemxt&f5KM)1mIRRJ&8WQQ4isW|IP*WLJD<4x8qDb@w=SlxFv^ zyEE_CG5N0Cs$i z7ypZ)pH5p=iK)Triyn8mBVx2GUR`weMYdXDq!A@@Qd+)vhm05|2S}nLC&uB)b=nHV zn98S1-O4DZv!^Q^nsK?(u_*RUWOk|p-IO%xGIq zvMV#wY47XsI8qJsnea}7;zpz^o4OK}mzwIdL-%v+>0)Tpy4__FV7Lk+WooBg^s4jV zgVga4oikyHnNrx(ijxB zZ1mCTkI7QS*gY5-1xa!mGAxHU_~mck)kL0AcFb8Z_6)n*jeh4aPs+9B=ft^P+0jm$ z$0MG4>W=?p8^vZjJRZj|J3Amg@$CrN-)fCu*QM^$R}9);<0W=ZY8RU)VHom7ccUpp zxd8{ta%7|$rYy9?CmwSJ>_l8%PMT=@_o^*M)*g134UI1>DPj(?~rafth-Pzlo;StX) zd*lJuI;wkY&lpVgwxM};F+Ahzx1_c^?K$Z^U{b|@XNxZ|IBGp7?rhtL-Lhzm-u7(QFq>0U|8~%CRizMTw%DP0 z4sbD~w7u|%Iv@0{Ej2@`dm(@O?d2v)U6OpYo{;A2>~pujCv~QW-HS2pNTUiL==|7c zobpn8y4=}VS%CFK#49T}C8T1VESlbyevI>Le)E@+WnNA?v~jp-{7iZorjBwc zPRhgLv0@!B`1AUSPw(wN$CMHSY|GFY)lE{49HbmR-`U8Y*H7$Re`|NyP`df4qtein z|7ZFDu27;}!^NYm)4!tiD00!>@$!x^+5biC7E+?c(tGa6;^0AAzojyw&h%{dB=>)* ziH@`(k>b-Ax2=(7NpuWzc@tgOgG74!+ubhl&SNJhv*f9X+?XW0y1O#P)JfyU$>~7x zu-vrUb3|&_+Jofq(p>=Ckmtc%h6O^p$U1hg7-ORn``WOS#t?=*l;c#w<|9*E647E4&{nH?{qvQ6`n>GW)icWSET+pY6aI{sYzL` zd>Z6c-~H8IjsVV-$*wreef#4V&z9XGCjnzVF>L0_x+yh`EOYH?c}|;~IJJ8$++t*z zmxc|FM@*dGrGf0-qP<&Lw-1^AygZ>=JG*(~4@$(Pe2RZk<}9Qxd&KAY@BJc&sgm}Hq+3?{l@p75xxqp6-M`_L&C~;3H}ej+-hZd&%h?<@ zxI5N{o-|voJvtBO4BMO%xy$d6vlSxMA~y=F4@S*DHS66P$TJmDg$p3ecvul3UfWMG z>wmqHr4C|R%CkA45&kdzci@-PPhWgCvj{+A%aD?ghZf-Oq~hC$wp6<^ zLz5U``*(kINh`C|^_GNwMR{rQ{ysJQQv2phKe>p=ek1&ftmf5(-hN_d_m6E>*DpIi zyPM*-Qh&YriF-g<98Y1jrVS&9N2Y&eym`r64S| z>u<;F|6D6mEWKe1jm40NsPIjrYn9dzmL^U--T(ZyYc)Z4R~pW=V1<9m`Zmd51^oL~ zVUH>Q-neU3h$}l-Eph4C{CF-WuhyH%Jl=_$R^Yi-;pCJPo0BeHnA@g*?Q7-6xe2Fp zn6GL!Jbu#8hM5)t5iwYFJymRL(`yLy6YcI@7|-RCf6}=;NP4H6=sb3y@Zx_xZU2cC9eeb2* zk$z2u6$ZLE1;=mr-!I=Wk;VE1HqTi#K3uT5zQ5cs zYViGV}|@F)c77Y%Od z+bXaM#+lMXF1OQv7&>3*HQ#RpAb0-_l({S=>))C0XHOyB-Ib5S9%-0a3Y;j3#vAq@ z_ZzMd>xm74v38Tw7}`Yvwnf_!6M6uAF8!-Ba}*KOHlR zBZXf>_G#9+k>6s%C#+}MD*+nsaewMJ8yE|_fJyW9o9>J8%h{0PkqxdDytbmcbym9y zH~SU6r^{>TaS>~ePOE!N_0vjY--8<3Gwts990W7%ewDrd-1lGknSvVk@_2}6&oQqDFuH}27J_kMEC`5HVryK*le=9P`gl=U)3 zx1ns}%ZIkFmbEarNj=1i7kaHOjx1ut(wm2sXJ>KU+09-c%5KOTKv~~9R8)QExANQ@ z`Z)UVy}KjTZNo9m<1V{8)L<4yI3=a1BYGUQAANCA zDs6>N?y8t)(m(%?XVgAPV}UBonJ(AjQnzp5NDP$0TO#f%a?)W3;o-v%k2v~hhbS_&D2_7sSFvM z58#;GXwaA?gMXn_4-hd-rWRT~d&rAL3CU|MpV0kf!e}RbIr&zV#v;>q8>SPu+nw4* zHC74aD;&Ok5UYMVI?NQ2l!m8Rc*o-v>!-bP6LnUl@I|C_j_sM!H?ntpB(4C(+hZnl z;aPB?l+3$b;)g%eK&VJVhstmLt2s?xI;NjY4)?R?XFo&TmUFG|h-OmdE%$Id`f+ih zQE5k3u`Bug#DcwLGp^+K7bE}v-)BY{Fq31{xo}=BHYJZNVU*f~w>k1mNIo=3L}!WJ zOXACM7{)jRr0H zHRnh=O}}PD#E7SM_PI#=7vl)np^MiBB=$E7AY+WV$goC_++Fc5BV$J4u;|0L-ft^M zBy#bVQB$_Q+lEIJsd<_5g7k$2@!=8&TzPu+LA!3-WNEK>t5!PgpNmoyucD+S-TT9Z zX0$=E;@*4i$Y-r%qkQ+m2mY9FndOa5Hy(nObgdf5vwjt(+N9|DW%gTlw&TR1;&4$U z%XT<_dMq_ov6IrWa6XXIEkeA%aaLKj8%+k5ZmzUEK5~f9$#98vDdo=_X&7Z}0c21Vr||23-`^*%Pn*MU4A6pPn>6DyN+cVysY46pn2RJXol z`lmM`3GT4$;+OijFO_oo`b8E*HngpAm7Sd7V&zp|LX5G%LnUPF;>W(dhx_LuW81aE z5sh)_(mf$YY^hXzx9ny0aKk*N-kUhFAqS{>)4*o4i;Z=A9x5rB>Ee&Odhg>+p7Ewp ztSJ_Al$sbzUD0nPpc@`xA6KR(S1?z^v}@PJk&fXa4y?-DL_=SM1g|1<#ER(6^5$L& z_?2imx{v@nlpi@!^1P6bg^RTrG4y!*qpp< z(f5;yE~5$ZvVHehy$;OnBvsbXRbGv}=dWjfp3k zm-Id-+d`h?N%i)<1k$TU++An6(#2grd~rakS7Dc9YL;b7TkzL^vb25rs`H_~zqW~$ z-J?0}+8Hs?SvEXia*EL>*1RAM$}qIGVL%2hDmG9W39@imZO85h>i@=qAD7DZ9d1t( zqfU;qNrg887pl?%*%81iC*gSU$eS|H;n--zIc=F9yqS)xMUBJdiVaib*bW!um8=oe z<3!wjPCUx;7hb^}PES3@%3gUaDq=G)R^kXK;sjKjh zk&jt#@MO4N!t-C#ZtDY5F?34pq13`SH{L*|I}7AYR$|Nc+hn#lvJ{JcKhakv(XTYz zXVy+-=KWNX>fmg4pGf6?3P9SFI1wn3S3~l`ejxsTRhX|#tS-;RkDYCRi}?- zjUz6PX!q*0kBH~v8(WD+H87SU|JL-vTWw$i6*zBJeGY*%cUwK&Vj%6yC~N^H9r z&lBi?!&H4@D=JREYb93>0r6}rk7%;$`xjK6hIN-mY~tjOuOH@sLmIy$RI#*Oy){bS zbXqE!{J7&h)#%F8QIXZ~LSyz3qI{>J;*p_MR?2MnwA#1w6PJFvAon=3Q#$i8)q?S# z5Az8YcFIcU;9U~$iUU(IAbVL4BZYC6stnDcVZ$!SRx0`!RIIOe;w2*)pAJPusr}07 zI$t~@`^jyvA9AE)y)|XZ(s)@X$(0Wc!o~7eBOf}2N2Hzcbo57&As>jkL=9|g?07s{ z1B;7c@a4$Ir9zZ?_dN%-RMs*&@xLq%pw4+-9RJF#f|+davF0l&0{qJM{O z^63;9zPr>ZhaR@Ep5PVc(r0P(NsdY|<=yD;ZD0RGqk^zHy`A!8ZfPd-yA?gQ^t*N( z;O5)UA#+`jX#TA4Bm%GM^(w1sUvGUj z4@B@>LM)y<>1QJaCz{6}AGC-woVwM$_4GO}8-@85l#c_cne*)&hJ7_6NwROx%;RjkLy2NmQ);>IF8v14Y?aaaAP_ zNEA!H3)C;Gr1fflxwKrHBGR}a9+MYeTDBV)`n~d^y{)<$1;t8R?4C6DH3MHC9Em1X zhUBu3)RDY6wDOy^)Hc~+(}$j)BI^Nox&G~$mz|2Ms#nk6*OO;6MIX_NcemDP$6^mV&FG6nve;CZ4^$#wn_fDxWz~YLa@pm0z**FH}e+6U(Vx zcqaD0$5iuJIelX>nqR_dCH>6U{{ z^{$CgB~4|NU%$~-Moj##iQI~-1U&th#SohwsQHzt2)>9EBl?Z^_s=pFfze7^jx;-I z>rhyP!kCo*&+g;WQ$v^3D>4_3S?(9Gq{Epmzvki*zcrh6xK5GMKKrAMg-D7RT89&Y zsB|1A-t6(F`=XV5#>^t3&;Y`{qe7I7y7G9aOq<#N%1)9| z=2Ic(^4m+w(#ja4nEKde&Hkp%O>ur_Kx@+DXL1#8oHOA~ojb;kqh7q!)Y{GWqv@On z@>@MKjVq8VUh7T%dG`;@zdOb=Ribd)>=9+E72n0Fh;hb5vH#CgO^j?5M?K&Wsiptk zLn9b)M<|k}{qj7Afay9=%-MZt28Tf5J)T_18s{5bHZM$&2)=7Um~Q+p=C7I~4Y&Ec z^v-Bc9QS)yy|EMHFW%pn>kytQIdva;MCK?@15PNu!=|C5mT!`_`p9m>g`cSws|$SPcVEg!gLEE|X;Q(ZHO_5UP4 z%|St)@1js#SaarYBV&ChDEiheeuVQ9-oMJ(E@Ald1x9AMzR9iS%yHvb0pG6W)bcao ztg2@CtWRBM$*Hujfe|=2;3^0YjUTAEtW^;Lo|K4IDG@O(+Qzhv!bwxh=CNV15pCPF zh-n+yCcJe-Wa~DuEh0r&>A4lC|ApCO!pz`8tlz}h_nKo04BVq%)NXdN39*($bWL{zKT$ndspBU-g>-m-Ocgs79bcqP|bKuyHAG2i{5wfqWP z4?9;9a!vbB@1dn+?@N{}>a^-BS96jyq!Kai(MMxWjDC;<(O?$p*_hR9J4)4%>66m% zRV~r}{u$eh3~+m_Pns^jkycSQXi-Ays#;$tK$k%xAZp>@FGb$dCy`;V?;nT#hvx%P@fX0_73eOho z;@q>J?v_1>HRj*rc6XCK=*Tg8Fg&GsbgSrAkuAeppc7j~G{^rjZJRf58`iRU7*0du znv1FS@TexNj3Y<&VB3_K)==tJNYOSXrfo!vn5dYRaS?HCqGQ^IMa1G8*9ZnS1yWnCw^F2h1u)k-43lIWLEb4LX(wne;N5a8;J^S z?`yCBv67m|#gsni9aJafPwE4CQr&mIRdOlSoeZ@ zJ7woOo{2nS?WH+RHZ()VKGT`wIL5lm3&6ihY$?kg(=R>e#(rsJ#&6)@bpFioadOF3 z^iu%w{PxRt%lgZ2?0Cf68RO@(qYQDgK2Do^-+e|*;rjpwCwYe~hyzF}~}i-&Ho;-!>cDG(!T(mu@LsCw5NHo~;r> z0{2+Pbyu0}89msA#>pnP!duIJcV8ig-=+EDk(AeD|H$`&9G@Q1^4`}!rFtji8}@wxs6}56V8}Kj5D>n z4=ozN(ITx@h1I+MX9RFYo>t=YI+|tUdu{x_8fJ2QFH+>XzT7Fxq@G24;t$8OOHoIo z3QN|UtHCNHay>43cKCX?3^{EugD*babO2}0M22WnQo`G$L`AiT#I)I_bwq2J-MHwe z=y)P2(@2VH$0RRS^&-BBRMjZWRp zrc@Eh_`aOz*6YF!DsAE8-1on)Bwrk;r%Gaaou_QFFt|#`&Y!nmFdT+K6Rr)Dr?IjS zhW&G76mZWXO3m3P_XgOOyPU)9=?~%OKhp3s74p8|P>HlD9C2#TKF9OC>|gVPwT0eV zPq1A~yc90w?&XPsF;4@gR=|E78TQ9r0wpp;0hFs<1>rPl)NH^ z{O)7vuFrp1R7^kd;X}V4EGnkINFQ1)&uAgv>t>YK-fh;vKyE*=r|-pff!zM$w%j|O zr?&UD=ex1Blb4$w98mBZursnNq;o{~#%mwZt9|-n*_XKYH)hYuWja5^p{t*Di>T?t zw{dLiP0ACFwO`9}>o5EH=7ifz*`~;D*D+?Z-*NOa9gS@Ar6PZy_4r7sS+0DjK^%{T z#l>b-7tp>0zGf3|u64^>0Y;?vb=dQb=dNPZr@zLqKP11u%at9Ojf}h^<*uhbqk&1n z=FcuZ@3~MOe#?gpg~Phb-RUWuqa-^y3x{_(c$y{e!)l$lc@-7TxM3ET*FBlfk!alV z!lLjzu3M!EQ`k^R(Mfn&gv+Avy?eHBA~0RJZKzgCez#w}`7x%MaS#4+RuR;R^QRM49^}8;MrZ>5V{c9YB*wf`9xwyOf3ticG2G>{@ZadU|7Q52maYb0U z%$}-+91KEn;J$=mg%HX#zB~1oHdF`?zYL$U;Hj=g;ruQF#fNQXjApN6C9kc1lyOf~ z<%?>R&ID#ARF%GE79O6HHPx#@>|KKiKAeNyG+*MmMxV zmHa6mPEVp@zfQ@rXMHSV_8V1V;C6}S;};H*oIhe~$(GPB*TtFG)pi42y=6BtIk`MC zQL2X)^l5dmf0IwiQKn-GbANdD`oC+imO9F~tnl4q>7%d%?l;D9G6{Z+j$5P z@Iut|6EvT#>~x-c<^T!f{y;=d`0Qo2xF;`LKI}s|(pkFtowm1-rQ`RL3$J_9qxZC6 z4<_@SfVh~yus#Qn)W78CiplkqT4Q)bvCm6=%vMzlvwqBuyZjNGBH4z`y;nrO8ath> zWdx1w^^%>rw{vV6JpHp7a_TjH?4!>=KQ3oO83MAQyb9Mt6a zG-q==?;6>PVCJb`{n>Gsg!(EALt4e8;H=j8IznM0yV$hu=}qiv z>{N2ZxD|WG(wzEFNbh!UzEWxfzfXAPh__J*inzqQ@5L6*s$2#pV;T6~$x8~sfYQGT55 z6NBTx!*wUjbctiF_fwbq;Jhl6x6p~UOt7ogUeH{!F%PwB;cLc6b02ZCD~ftREyCu_ zTE#6T&$ElL_dQk)5>yQ1xH|&}D3}c8O#Jw|n~w9~r%&H7QMdAQCk%hMm{IzlrwxCE z=+^k|nufo*xDY-%j_ubsTj%;sA_SuVU>4zNnsiu72h5OMaO&(__YqoI^ zvi9})Rj9@WS8lk($LAkTYvkj3Qd*|82oDPn<1txSi?Fz`sMwZKF=5SHM@EOWZ5b0A z6Wd0-^>J^%C|AooVz7lBGWp7{ zW!P%`+*-_VQz6q+`L89jH3*q)LCAa>gv@6_$ZQWn=F1>tb_5}_GYFYoLCEY5LS|18 zGJAuN*%yS&S3$_^4?^baAY{G^LgxD*WDW-*^J5S)KV3)0hH=s7Ix>SGlNK-r1IJei zWF}uHAIjVnL_QB*N9IxF)9X4|10lo396whZ@08JY=2|k^&Rk2TMiAwx8H7x?AY`5h zLgs%#$Q%hm=I0<}js_ufIS85J*XeimSN|YnY(dC86NJojLCCxogv^Q{WZn%zW@QjE z7p^1o2zCBCG6Nu!ejStZ z5Hfr-#?Q6NlVylpQ^pa5%-A4g#swi$@jCj$HoPkcnY)9KxhDvjjzP$D3PQ#agv`hw zWX1&{Ga(3>IYG$09E8l=AY^_GLgrKuGQR~Ob2B*$jD!myoPRkjsCjhI{i+W z%0b9%3__;Ob;?Yvwn4}Yy^hQQ*TWsGFz^b&rZlpzmCjy$W*Uyuu^h#8?G3btW*MHE^K&g3p6K#(Eg9Zw@N+F09xL;6Eg7Dz z^K&g3y)U_z43FFSxt5G>vunxdz0|d2w7y(RhUe`3TuX)r{rp@@hIa(~TuX+RmHb>w zM(_UuWo9U)Nr8@ejcl&S$1L;VRrJs-^Lr37lN9c?%JV}IGG~I2`SUt5+%G3xr_7W| zzK#sX@>@a3+;pAtFrPcGBg3JpXALP-d;)M^*lrkeMBz z8$W=jSklQ;0gj&`wTuA&f|ULcLcwU3pUXI8>6a%34uf~h#2=FTJ$a^Ly5;;!6(<2c`$un93kp|8(O6V6IipU1unJ!@Ot-)cg#QD>J5&KVBgF_6`8HMxNZ`R;&jYu55@LYG=8XWE`iBm=O&pP=%BLWBa zDQZ3Xv&rtz4(N3vA!fEQ^4<5xjn^j-XMrj*ads)2nkBzUs3L-Jf~k)lo5b0n4hq^d zk-ZfJf*}$Nj$XeJ=QgzozPUx{arF9)IIpOAyFzT}arF9)INQ}`?w$D1J)79}0J}u>sB^dr-{w>NL6osSb?Q;s}lM?#$ zFc_4g&ne6}JU=nlXO_ZQS39&gJohu>bl@{=e3GKA!O`nc`4iT_dA9$J)RtQgcgT&pk8bHHeb!BFU<)p4s$c(=>BOp zFSIz^FA_)VwXRRyMWMyv_#{rCUT<9-S{&}{&FwZqji1`ftijRtP2Q4Yz>aKqu;1@`|YzE z$N4W{KIQjU0`1PWoz~#!b0qo8p6I76`Ij=_3G!2vUKdp#J#WXV_0Dejv$#QmKrC1s z-r-W;4k~+a*YDP}8^)@P%#*GEQKQ=eK2N4MLevDV&Ze0W-)?u)^*5EW!IPH~QkNm(IoMsAVlfrrb2_`snea>$9P}H8|Y%5KGsm zT_tO9s9nU-^;udav^cB>?SUSr4b(WTSIrt6J$@ci`j$}J8XVm}tyO(quOC_*_KVq$ z?&bj*K8G4xgQNTBG1YEwKVS`xwxeSePLod7;AlNaSMNiX#aM%*?WkT?RYUzqwS8y zc{SG>96c{+oF;jp#o@hzd0wcX^x%U6YjE^A`Cbkrd_Er&S{#~Z^Y~e##?LDgt-;au zdWpj6^Mo}x%$2%5SDhbRdfFNsyTVzm^kB{mYj83YPJe~dYnC-QnF?pA>Yt@^t-;As zIO~*N_g!EOjw1l4!V+t61_$7L@s2e(LljQ7(u2vXt-*0BoY6`T{#s`Zj=m4>r0O&D zV{33csy_ODdxiYna4>`XTyNi~?I^#8OS_}zpQ@i*Qy+c5y+ql!H+EWsqwj;Y9whFy z21n0xLzNzUdB7SReIKlGIvlbFN8bnUR^#WLpRB>r_rZD}JocD1IC}r1_3ivG*5K%S zXFboocG?;oeeXO;>D#5htij>$U(y~tuk>KTf7amek2Dfzt-`5t*%};uzrA0z+ny5Y zzz^8Le1f&3`hHu_3yW{H21nm-YkPgXoHaQ5ep|1v^X{+)rv^HKdZ72gjrD*`+b=0>8r)~hwosF%*si$xXRJ(2P{i-)2 zg7^fh2lbH`^-bR|v}t8ceePE{dj9!b{zdK}DxyS!tq+@v_0jXGw}UnHX`pblzMYP; z2B)FI(fu>Kvo$!46wco~xWcDNcWZDOBX4v6)JnDnr%3?L+=s2fX{vAv)VzK7Kx=UH zy8x}%&)TfP2@7bqG8xw3ga@?ScZACt93F#Eul2mW#BB{ubA^+q^sQ;W zH8?F4j$S7&lz({)%pgC(+UwTHkL{+{@de|osSm%lZSJ4TldQpMt8nywd%}~};IvaX zdi_>R{>36NgZu>BKMx>3v%Pl9KT#ee2*iTL(f1|#9QM>p*0fuDRi8d;{4AVj4NeDz zGhgAHlYhx9^zGJB;pqMLON*_kPbY<=_4?0c*5E`c9KCPMeb*YCXoaKKRmvh%9GuGhr4$uSVIcso|6pp_CIdst)oaBK1i7UaIn&3ad&I^5zCFccw zzH>tUCA-k$^i??8zNOx7O?@6xIQks+o;$6}}tF*KR$EI*> z>b!SQJ8N)K70yC6|7`4N4NjWE(fXDiXAMqz0M3c7p~c}dPV@UJr&?F#Bv^x^-&YM* zI0utLi^KN-=KAPy8uPFl2_q$%Dr)%f3XNcmh!`F`8Qhezr>lUa8`M(!O{9=S2*nptijRxR+Wv1 z&w|m`;IJBm=&AI2{X}bUm_2dyey;SBp~YeTW8ppHI8XWyTQO`d&Z?y(TzZ=vz&uq5_ zN531?dT{qnYjE^?KHWcS_gaIa=ebYRyxsk4YjE^Dr`zrJL)PHv^_zYlviwJDaP+;| zMl~-CIBE@!K2OwoaPKK=aP+y09zXB=5n3GX=gjkhe%IONpBu+H7qIT#Zd&)|s`cBK z|J^vwSrZQX|4S22V=hSWX)ibf2LCDQ+_ESfJ=$p{ZEB@p~az&6@@dTQD|{!r_DICl-=197FrzIX)})g zI|2h+g%*eFT{Di>gGTK`i$gUwW}H!K-u^E>v^dPojPn)0FoDmo z#L(h!J~iXqqwICJ%+TU+pJ2vms_a3=kkI0ApJ2wBLc@*E%$ys?`O9QSIV^V}Z*8yj ze0pzgXmO}s#9=k4(zmI0i}r>VhjzzYpMPn%@#&c#S{&LP;^=wdCRLx#BSMQqyJN1; zF;$=LqpiWw>yXO|r}@~>;?TaC^+5Me#N(mGp*=9;=yq!~$r>E32S2HHt2i~ZIJ7(F z`czQ*_Sciv;OP43{<-Oy8^`(6WOt}%yG{0>tg6qYXRX1}_0c%DJ#P&T?J4b>#<_cz zH8`}VW}LcnLW{$^i|U_VfVb{db@iF0%$lx0}ZKboq_roH5xQ&OdulAC0q9t$RnbyjZnv+uhZcwWX2v<9 z?AsqZLW{%P%s9F}U+u95N81Cf*T3zz1}9LjPam`fN81D4Znqq^21n1^8mH#}tijRe z@w$K79SbcE*Vjeq+XKJcIL_|@c66V~j&`Hs;gfvY8XSGE*<9hw`@+6CHFU7tOF zT7$!L9^&Zw-1m<)ILy_IlX%V=9O|7J=kfon!O{1@y4_Y^um(rp2Wy-Ym#o3jzgMGi z?k&ca4E}>5>3d71Qx!E%^}VykNho0rj=p!+IOA`!21n078t1)I*5K&-ZEX*Z-)aqx z{=FJqpXOz(!O?#wMdM_Yvj*pGD5KdPyj0#AoGJ=O_sD(x@9$`wPw%k?N3RogyWLUE8l36@dL3888k`yddRs1B4UT?SqucG{CZWY){};86|FfAj zIC_7o+pR-HXmQvl=K73O`-Q13ticJaPs!HS;OO;^ZnuQC*5Cx%(b*4#7Ki&QbN}f2 zeA(U_oWTCMyHjX!xQ{EUK50?b;OP2jd+>HlXmPm9DXKm{##w`->+>8v_%x2U1}E_R zU_&=+aP;|s?w>O~tijRe2YUR}O|%Aw`e2^ta(i2Y!(54@+ihL4H8_Fi2fy{T21lPC z=>DnM&l;S-^8@DqYj6V359STD1}E_RU{8uQIC?(ScIT#4YjE`WfySAo|L_NNJ($n+ z&UduE*5?Ol%8oY5w5C4#{6OpV(++EJ0?!Y=8Db5NK0nZQr%aADIQn;jHBQG|Yj6V3 zDco*ra01UM7J03~(dQJp-M$`X4Nl-W#cc)F;OOq*5EV@!0GdnH8_m|aHh<$ z2B&cV&bqnQ;51P-1(_BIGqA;I&ZfICo%wM#241!L$Pq-t#7pz&aJmtgQM36x;~A|S%ahPsK#l1 zr!_d*j_Pq5RrSVkelyt})?>fP?);_3&w(1&;Ap+Rz=IxqKCf#Hj@Ik#sy^EqS%ahX zTG!{-f{C?=haeguB0o(0+lOD_^1D}GQLW{%s zjW}8lepWbl{c__tCr$NXZih|vc~#9n=l{HMoD(J-s_~B|oYL$leCGUX4G#5=P1a1| zEV^I~4p*PV(ci1yci9>o=1QD8sy_b~=L@CaKj?}pzGqZa|LAv54XJqe+;_7zIQpH? zDTUMd7He?yyP7{0PK(>D!J&S$e{{RmFJ}#oz6ZQd=|QjZ*5GhE!usfOnsbLWIC@{A z^8CWy4IBYL7 zj&8R}b*#bBdL5_gL{G9EkcXK_uXtaT_3#;$!Qf@9IkWB{d2$4>$z>M!O`{6I9ndH z21mccZ>jp{R7Y!Y^gDcwQ!C0E9K9aZI1j~GgQM4@8fRLZH8^@bYE%8Qv5Pf0`rUfG z!l~8G8XRp8v|bPCVGWLcPoAd6>2rzJ;OKR)#`!178XWzeT;ue6$Qm5|o?PRs?{5u` zeowA(sy}KCj($(B*CFF=*5K%Ui5@?nrdxxkqRYe5Lzmx-~dj4}MlS z|IV}qhuO33_NjLJ{v~U0^tp@1d3T;QI9jg{sdk&R$Qm52*BU47O>1zpUawL8)9IZX z$2nrM*XVljkeUnV=;tSAR~6#W#*(h}De8Q5j|qo)hpS8)z+X>gwtI6S&b9K_aYf;5 zGT{(nI>6|%?P$OGIU53;-6ouW0q~p&=coZAN^H6D`s^~{u-#rW;fz!`CqjV3lCmDu zW%@Z}Xy^D{an9dtJH1cge9OHN=MSnP$Jtq=W%a36r%1MWv~o5JPa6m1K75Yz$G5!4A335o*6 zfcSTJ*eHCPz71|~P&ZI4C=S#a)CKejs5_`9C;_w?)C_61zzu`j3vLo98FU=s1W*#F zFNlBVcp#`c;u?YYH+VLHJ_cp+?C z*M>{|_yVp2?ptu{fF1(X13AIV2Gxf@2d)cL7yiL;hk)LJ|83C2pnjnKp!Y$`K(`|P zHn?|z)`M~p9tv`U_%~|!cZB#}ocdk{{)He9{9aHVXgR{e;O2vdgZOt6nu3mlDueht z=_^2NyRvY9gWDR^4F0=8RX_y@^KPdc{8d5xjpGprH-y^;?rU%x!R2oShk;JRKLGA% zxMM)H52HYjfXB1?lOX;cChK-P+{fVZ-Qh2wUqPopW5F8;_fZi0vOL_^L38160Czmx zouD`1p9lAM(A%KBpvOV)fcAlwfzE=S1I+}z4jP0sLqIRVzZkR}bRM(-^eSjKs3qcC zfxd!&7~FB7=RvQ4=7F9C|7*~EP%6UTzL8t4i5)8S@--hw|9?ghAifL4IM1GNBe z5@<4LF31VW2Dw1FprIf)s4ZmquKjb+i=dmpTLc;h|NU^6z*4<1K@1~eG1A$_%pcq za3{f?33mhBk3p9}QxRSYItuy#;WMC(pg$4b1or^kPvCwHcQf2?;BJL`2JSPU_V7Os zngDth;TfRkK+_T41=<6e2Ko-X$3ZLM{|Iyh{&jF?fVO}RB76YuM9_B7_Xtl1?STI< z+!sIx;r{{di=fHy{|I*$XbSv4!JP{Ce{f#{%?3S*@Eo{L!F?I-({T60?Ev>HxDUcT z1h*sH-{JlN`U_MA;i{l}K=*=%gZC8ZPWactoe25>^d#sO@G8J<4Y~~f_n0pYiHsO zRXo}q=0`c&0+y9yjN_8yig6rw%#(J5VcHPd56X4`aa?m8GLB=F{Enb0AdXS;IcAwh zC(vMo+aY`me)1wg)DyN}2k_bFQ6TC_4-oT<2E~IqgVrJaYQ>L1m~G3r_291opLxcD zh9J!J)Hm{|pX5=Ge^xx^$GjaXPs()xEkL@hpiLm+Gk;=fS&c(|H|I(H>;|F^P+vX) zv96ziIG(9D%&$9$`am6xh1(lMY=#*}9qk5QDY(=#>Kx@+N9xYIAf}>d9WVD zBR0!G+($r^O$OCM`aW=pK_2}~&p2W;J=2iK^vp}^1oJ1Kn7aR14vnvQ%!fSYt$D;F zk2vHJX8?%hY=bf#h5rPIZO8IbR`XZ}wk^v$5JVeS3e<=$!qijxBjIX2(zcHADIn%| zD`ZmPPXncc>>!q75Xc1A z7^dCb0hjT&!tVhsguf|>_Q8vA9%wnjD?r2GCocKKr7Y8sN4Y>A<+CA2nS2nj=~9ky z!$HT92l@1q&-k6-u?*xFD1K|Wzk!;8&wdyIDhK~-AkOQ%;kE&fX*i!UuSdY+JbPO4 zM_q-_IhgVT0^~U-2l9)9_n6|d-eWb&?}eMG(oBH=N%*J2odNfMAkIykr&!O4Am%v>?j*{9*f#W&e+lkP$bJTw zvP?4>v=-C>#I@-caLJzn`V`a=^b`2o;F3>lmg7MX@n?g`e*#2|3vmAcZ3eL(PlCwj z{Q838O;fz@z}o{q%lMSy<$(7x=xKyM1Tk;=nFsldr!4b+M)Ajh_n+cTSG<4WvYyQQ zS;b?S@*w*)+#Mjsv5lDb7Pz}W6G5yK`{+3k<7UEr9rO}tFybbFh)+J_*@u)R?|H@J zT45`Q4{uW640>}+I45B>cC||%h_*o{FmH6ZnYc^;ei1i^Z!;G5) zmvZFMPu{nXVLbDGS@D?nNKm*+KNo!J=cAj-a?WZAxtfg(UG2XUG2Cvb`NDrh^1 znDjGl0bI&ae!k+RB7HXK8-zEgILcA}Jlu4|{SEh35Ziwth;h2CuOYk$#IoE3mtn?J zj{JW?ECc4mJ67erSjFvxyBx&w5pxNMdA|vFDd-}I z`7=yD$2eukV?22r^W-u8TZ+dq{U!VyFO*%T`0v2|UGd&lym^o%kLelDJeht!{7lF6 zEF<|WFUwBZ6^b_*vQ7}kC1u}L{L|q51|n~z;(Y{n9f;{yfw*ry2-gPp2N3!1frzyj z;W?n@Am*`J@oC%EgV@Gv6mJt;=1V^Fqx}0I=JNs4GoF3E7R3A}!}Y?YP2!rG>+2HW zeE?#br3kYu%#&e`OV)vS>6^Wn1XK88zK zy5uwd5{SHwipMgYfuHGFAIhvVeA>}(z^BdH24Wj-0Wr-1 zxCaqOo26~YRuy*?eA=EfaG8c_nTGk&M$i`0rn8M{*Jpvp@Uw7f-?=~GUWH|+EYnVh zI|;D91df z!DV{N?o~Y62-@_=5vJ@u#eW{W3=n0%GVxfBRv?yzW0Luvg?kRfx^c`h4f~IAYr*>y z{w*Np|Fz=hgU>oMAKFOD&WB6=n*^EyqCCeB$0o<4)~jz3raZ@_1H}A^`JLj^1~3oK zH_YP@i2H$85xxvRdEW={SdPOW=Gz4B5zr5y_f#JA>p03${zntQfhd0*MEM4A z6F|)SgyM0(sPiHJB#7nc!#qHDf|$oICjPJRQd7H67oocYX>pi zZy=^C3w{+)0m4joTJcB29RmtO+(@{iKuq^Li0L>#ECYQ4BL5E%`77XZo_#{`&nW&z zxU>_0f+$ZNp*(db3q0y4`5cqvbA0{-;&>&Wb2Ir1;EsYk^_zUkkpBi;&ZA7vzTg-j zpJV1c{2UuP4PC}jhWRp%b?016{%dfV7xQE}rh}L#{fvJGE@fFZjYkZ|(LQi3!Ms^k zmhl3JahywOYjoRORQx4ye?}bVM9R~)Q~qPPQ^A`Amwb*D@;O#GhFT+zdLiI007byt z%?Qf-DX`=n72Oi}hq5K%Hiw%CqAYngfyXs6*AK6Q$h%qjTf!Zoc+~6ppks(1sM6ko zF!fXGD$B|JH}x$A{y`uci2Tyvai9Azs6Xg^5V3fUdK>&h;dg^dfXX1e5VS(cP*1tv zYK=JRF7xBwzZ`fY;2!|@5fIaI4>T6;K)4m)vTm#+*O*)faxFg>M4Oxo$^nf8xj;`s zekR@ZG_pkSqQU#>cIaH$O(TA zXfTNR)>V8Ru4j^Ce0>#W8rJiEgxPoF;9shE4HR!K!kja2f!h!++anCL8`K6owoN0r zClF>{jo?y;Sx0Tl8zbBk;qIUoAj(lssjnIEuY*foQ@9?u!$HU4XC2ue)Xf6;*;ni% z%CZbB5A7+jDH{%#W9eo1m%#OaD9gPK!>_>qCS1xkhr1Z`9{exCT??1|7VuN%JNRe8 zeNpjS!p||g8{s#|2QhE14H)K{VLDvqp>=}xg!-a&xeffCKm)*U2bX=(7A|$-LAcD1 zd?^P%?FVHZ051j<2V$7AOh+5TaC`VU=W)JcxC6o+L6IsKv79U;%R)cPrOOZtKg-8HW*Yh#Pd>w);dTRc0WlA{6a!T*@;4QSh@b|AwD(jHB$o@V^1#+LGlR1KtwQGw{ zpJDbn^?~}vvP^>e4cs^3a$X>BGW5{K;pM#(6@db$SGZ7{Z*T&4_dHA*NaO_d$1@NeoJ5=~ZggH;@@jeUw79iqMp7m@F zVx1YD4R;3IsVbgr#x{HpVPd`vKg*!U4t0q7L>_gSwt_mwyl8i*yYoOyOP9R2;lBVP z?^T2=fWC+S5QuA<4OqYMGavj?pkz=ZPa6G7~&BcS&ce;xcyKurGy+)TJ^$K z_%Omd;Oe!*4+tMbSlj3y5uS`N%Srj45S{{8=l4H^ry@K-#ZzBDf}c9fdi@OdqKZ2T z{~7qVf>=J&!IN0qO#EVgg+A2Q2Xq{-Jx0|6Jw6sM4S)XP!OR?a1-USDaCaDN%V2XSyRNv$H+N z?zVYdZt-ANF>(AY8VDoXN=#Oipnrb1L#!M{H9~ShuHE1yCihE>P3h@!XWN|e1*uP_ zr!Cv=$+e}~kk4H`b zK3M;_`pu$kZl^8T<#KwOCFHnWw)7shTwjAU^Cj~%E2SAB$vB^+A}Y^w>{VC zNVB0?6Wy*{yW8tPvr@yujAqom7Gw9wvN>Eih%_Gi`Whg{;mLK{3fOBh@;3Y{YZT|S zWqRZyB0Qo^i`L;0E#$X5;yp1ouPq_RSs*8rIGfXBm(zEgBZ@Ji>fsBQOF((~-)?NG z=uW@@HaNz=xB5bND_>_ENx5(&-WC5wV|pKk#(%n=I%P3D0XJg)f4x{% zrRpVnIR@>Rhq`B>bRJB!#qe;?$n|RRrBu8wVbQI7i;~L4rOOcHpAM8_&{!kyP}L#P zlzR+XHx-&lUDS2BTD-=;b{%e0rAq>>7$3M3&|)?7tuqV7$KLXfEuwG{`{77^MR z#R*YC6ya%=j`{~b5j&u&w1{>=YHS&?zQ*Y zYxu9V*WUZgQV#E2&ceRWt55a)#YzFX?`R{tul8oZd_8h zvuPR)`0U2R*qTn~=ypo>-`1q`k!Am?<)hy#Ik>smipQ1`e&OJ-r5(xqovm*lx$581 zt$fVtsWYwr7g{S1FW2wHm-BFUn@3*!!M1GAl9l!z-JkNiK|YJNm1hoDZf>J5nSZeH;gQyZ zw>8OrxM{J^7j0Y6NP9Jln^JJTwTHiltu&s#k=uB>lAEJPSALh=Ki>KkZ~XB?eJbtR zo~g}VF4`ucjPhc=Q`!4>KE=Q7Pd;&rR{4atw7EaOM28oe9FT{5mo|IRHmat7Z)#j1 zxeqi8`&)oO@ zWn29y@34*W7j46Mc*3{#v6huDyjl|Us>Y-E;8(ZzUbaQ)WFs!Sr0si_qh7ScTJKkV z_DQSH@(s({UMCoy}u*JiJ@>;Md|}w}o$5qBMH{;8HTrw%_h=zdzC}LS%Q*0>zAG*LN>p zeb@O_H0H@>(dcNqxYOzH`tB7g`bXQT;_7q`r@FXk+X6GjiycSd_mY%1Epf;_t@Zui zz#4vz9z$v0RSh#;*Zy4H$}p~JcIMi)WO!Y}J2y1ja&7xLyZroy_V@Me_v_lH*R`Lk zmruU7{k>>Q>!&l;@{dzn*k|qNZ)y4QV=i=Xu4!+#AyayHv_<)=TT7pON@FVP@TMmH zPcAKaw;0pUK4qx?g@JnCjpV^*0brWfOuWGzElGZTD|T75ME>c_PQ@U-*F0@7@NG@Y zVYHEFK6PlM6%kFx*Xb?VSWjnEB~^V?H#A;Cuh7uZ-(E2^lIrQJnq_=ro0ZqJ6n6i) zyvgCNPtWfB^vsS=N&c0m#Er66c<}HNnLrjj3$*$9RYM%Oef8As4aYz+hs_(re;%&> zPlnGoWRqA@q$8u}-zVBP54E4XBPxbe51ZE$n~T5hX&n8qW``i9``b5Her}!*DlC``6@R(?$u%olN89T9_SV+# z3vFcnmLCvp@vq5^Et<7Hot~F}L*c&G`gT6#_$RI#8d-TU$Z35n*AKm49KE;MI@!BL z^HbqL{rw9SdsSSqAA9w0I?}pziOP~8d8~1&qNb5&UpF)(g)7c9lyGJ9NN1azUf+Ho ziL(u}zJBSM&bDu^X}_Iq1xc@MpIy5|Avd;nu5bT4yOiYD578@6ack2F5tN)mAI+i_ ztV9w@hdMT%{#Jf^`sS}(z4;4WlD1`F6UE=&tmECSJh)r1{>i5e@wcSnbxRpI*CYeN zBo)^-Nw}*0`1jf-4L3F!xn_wmU$?}gk4Uk_a9yu9&`O8^@kLv+D8DTKA&WQ~TO9XVX5M9cs0r<@M-nljrB!m}Qxs zY;E2!)NaYJXz9$-ioI_6+qF$%Z)y_#x}|Nqy8V6i()L~7{$=g1Yu{eqWSFgcU3+uU zWPC)1E34RNaEgXyou}TpBmQ$kt-o;f)Mj>UJu_apoSTN)toht*^RS`ZX}-N$ebZ2@ z#rG>4C$DWh71`X>Mt|+nitsHg$(4=6S2zBOQeWHtoN2tjrhUrByuSUw1#cdrSD2)- z#ytkTdFcJh@I<4a(EHnapE>kyS(vvj(W^Y_qf1-$mZ7(c@@FqCU1hp&8G5%tK(*&QvTj$#EqMNr5(c8{KuiKwKLsPDIJM>vYRLW*ddEZxTw)y{#p;pWP zZ@zE6qbf3P8)~U!W4op8nuObjS}a-IZjrWUW#@cr>77HZm9?7cyzJbftzVBwYT1l8 zH=TX3S*iz`CNA1>MkDX;A4y*gG?I4>wN{wsY~zCX97-bzIC8jbqt2x-R)@OJr~uV*hgdf+*4>rf8IOPPD!G=1h}m7CA;b(K5x}xS@o0VFv@1je4Jgb z8^hAmwRgU)s9e^L)vG5-;IAGUSFO%$ulhjj#%gV>M*HU0lY80^JaMjhDr;h*6CPyI zR_aIOwj{(lc&&ZDeMu>6X^VqjGt^GSp3`<9)>NG>T8ksSDc?11rCX`HPTWRcE07oQ zbF|)69CW5VdC#mj;PQKCy#aCGH|q`ZMAnWUN6qeC%ZTrxMkn!wweK%nO34F5?Ud}_ z)vTe4EqGhip(rvLH(YvfR$J@q;z3#6;(z{7Tjep=Q5SC{Bf1&qES7Qm@mwo(Auhji zi6}%b(8X14} zzJF|1|IfGn)0suv_K^OUUFi9d`sB*?#N$J)moABA%ex;o$vN9}i#?aSTP!1;<0ZAM z*mhg%7=}MMzP0L^e!v`$wl#QC2=&ZFMaqD77)qpIw0 zY7|nr`NgX@^ZqZ)xVJpXW+c)%_~s^g*342JCgMJRe#?{G*rH828F6Sl1`lBcKy)e> zCTk{VBSyV;=|N=HtP5P-{#~>~6G!O1c=gogC}a=2jIWR6ONUyX%bzbBYPF>8#>QLg z%p#;OA9}Mq$<)4h`zwatu1K%j6YqZI(7UDgT|;^`>Y^P!I5JPwMn!b%w(P5h+Nfx^ z+E9xwMp(4XXY=}yC~mzEUp>@D??c+?efSMS@4s;Ml>B1qF~xG$xNmMA=={>MrsmiD z{Kla+pTDQg%@!B!;GFQOWU0r?a^fOP3Bpi*-F)G+y55r5QY(YwMsi(r+H0l5mN8(ZyoAMS-37si*|^_2*1joTdR7w$s>KpYC%xS zZy#!$PuaxK1Q&ZRyTtBQLb9Uv`|( z$^KifN9_AZ4%;CH>c2z_o?f&=E=HukwC&u|UqqK+S!;{xXY+H@QroP#K(%L^2J#j+ zv>&;YYnR&g4MX(GGL4S(8&|DXWZq--LMxkmbEZ`rQMNf#5WEOYQ~clqpLM=As>iJ)!}}_2G{UwNg^R|72Eg zY@?1I@m|-opPL$AZfJkMw(&_^nD2Qq(gL$x-Dv&Mne=!&Xiuvo?3&i@x#b)~K8aFa z+x|uU`u0bBO5XGc-utFm^i;-^B<-cjiA>9n^4Gq(rhV?)*DmSl*V(0<#8)rcVc;XP zQv5U~J-)8Bqa{*qyw|l+8V|`bUKLgn_$(^vCR`VC_P~Q>xs5uM40ywBmQ=P=-4Q{5YONNdVg*fJ+Y2RRvSDDe%`p`Wg;Ilf5UQ~(c=^F zv`~VT$v;0tZ#^QimdC%wE*!Sq9##?-?ZSgOb7STciK}8GpEw2q@eu3+eyJt2M~jv4 z87mJb-PCA(+Yr6&T)|bXjjZfl*Y*tAl_D!(-H$xLD3>>iyY{N=%N2b4P)`bdS{!tdzRLo-Pz71uV)JX(oox_arBstF>5z9PM&Q% z&FsoKu}F{r?vq(KQIvjt`I|=)XDi zUd1YPxu$QtAZ!c zg1{gS^vxw31tW@EStql~b1m9YzazY<@mcwW?@-W2VtF`^HO97-9~qM_Jp(VbO@} z7RnGXmZv#)Qo{?8S?P+hM&C<$A)9<{1k_(_b~tE4`1)n2|;NuS-Q^@J7u=d7M7 zJGK7A@zwL?SD}OH>ZP-mrsoy?!xf!+zEht5_QKUu(^1~BTpO6yyk`&RwBKi#bB?dyL(Fhq45 z)7N^Qe>Fz@@#e@tgq7F)t;YL8vc_Zo^%_?p2-A~yWl?Z#VYcg z{^cpnhS<*v0!ic%{4CnB+9NXfg4I(aWB%cx7E3cnc)e%`qmT5m+T5HIwL8{mAkIEF zKeB3b8@H8h%xPoJd4t^k`A{DUxjoV_pEc*j!M_-Kuh7|M-xmk}a_Ie{kZ>1yfgFF>P!kRDI#c*lqXnGabbjy23%hpWC_~S$E)cmK) zU^?!f7<#`VwEjLWCqDYus}^d$$4@bczHj>Q!U1K~E(H##Xnd-Jo3h!SaLn(@V19qv`frJS{s|MpIo(-7HM$d#C}fhbe5*4=J2-rB=J%r(y@{K z)DV|SYOGd5?BWCdST!8^Lw5YgEsJmbE-NeFCn8w1E5=4StpzqSv%u;9Bvl$NxV)M5&NKWk?q7+Q<=(lqIhj zN-ftt4JR(zr9~qx)U0=()H9etuZwog(MU^``leh-ZJaksWcGL%a_xd4;iBO;;r#aM^m}BE_+7up+ha#IH&K{nn~xLOyF~teW>Sa z9>{dQ@mu+_{^sGbUZz$X^y|4pEnU8(#%lCaE~mOk2k&2I88g4f@k7c#U{ zy{I^?kIPwtooDcH=R$bWv2sNN+i2{4O)~YopLpFl=oA&ZUQ?@g`!c^p4|*I9{dnfm zpOSK^XXBR)&Bh!){x3rY861esC<18-n!;QZ(Vz$x2`+UTi2iH zt=As=)@F8WQ(oTK>K|`!vg*_dyJYx@+!x`ScP*>2A z=&nX7k@~HT>fK8Xt-Wg_ZS0!o*p1s;|Be5RJ7r=0nLFC4QLGy|VRK-GT`k|+W@A(O zx;5?;kALQl<_D+e5L!`0RmS11E8OzN_Sr4XPrj`^d&i2;sdTx#@h!U{RZHI9{ye(u zyKF`7>WKtrhb#_2NqT?R5*0n(I8So*^RXp|`uFOV@F25NPsp97vPT=6vcLN&m5A%o zzWcdd^1b`XO^M$9)VVe~`a+J>rSE=fTW)b;eVp6RknP>=9VgAZ-m+iQx!dnwO5bjY zJKko&xizCFZDW1bPuj|+T%5F>ZOJ)lOS@$2q-||V-$~oql+Tm4vo4*d(+Vji<0ozH zI4w9?yW5_*{Q1?*rq#UAC7$?}W-D)8`rpe}ze5PDYrplS+v?P+s_Ww=FSMufK09Z% zrQdhvn>y<++6*nOTUS2IZFJd*anIHp_5*Gs(RHh1?dJon9jicfvf-KbzxT9v`TtET z)jiPL8?tzEY4`4Kf7f|)`=2)oBTkJF`@Z??4edLbFi&+lyL`<07{m*rG3P6~M-&>X z{Z)J@l?Z!)Q_I`aP($eiq%7p{77YUl;;WlZTn^@xNU7zoV+jt&p zC_!|vPN#F_+_DbU-0_v&e{OPk>W$OOTiP2u|M@1N=-k`z6M2LzclGq<_Gz#Zk6*VF zo?p%7W)C}3$XV7R9_eSTE0CM2f;n6w-`q!8 z6;#gSylFX#hc`x{ZYq>|#;a;_rWvokX6*FX%-#d7pY`ner!OAreMR=gxw+DtB`?D-$7T$I<;0Wi6TI`yVY)_ zg<7R3E9}jWU%i=G@ptL#=nBfq+B<%xD=5jiM#I_1=?Mdg*w`?q3*^cC-DUMmvu`XM zuDVljWOSFU`awEU!({b91g{o5HQm|Ir7~GwCp&_&m)E+wiqzM)Rz7ivUS*Px8qeXX zrEMvwbr^R|Z{LBcaw}s#`MkVh#gBRO@`2VHp5sE(aPcB3%{=z=!#BUNm((+Sn3(YK z$`q;Z`yg)(CDkL z=Njc#54}(Yd6t|nfM0&MMtD_wi&x=0K6w^B`xopSC6jiH zTAz>`v~NN$tX*WsNOmB`x}?g@94-z%Wr$v_s%}OUZi9Zb*+c6C?%&$ncjzX%%zt5* z>6&4_VMmI8_EM;?vadzO6-`p*nbQP)qAt|l6)US&Qo}(u)W{d@q?ZwTh0!+0lhGK< z_DEhc)N)DnCc57~=WWrXG<_|3>*u%J)kflHT{mPwMR~```V~vvS;y^HGzpRE6wN%m z^j{a2ob>D+d%ly$aI+fpkqq92mJ^=$JUlfrBP9Wa{Yd88PBBv9e?C() zMl$SwBMGk`qE~T*NQfqnjpYqPZI_maWu4sOR7bKFj9h2*y{q;0SDs>f?{4jV+9|f@ ztg<%_wO5*O+tL;|`Q43SBbrd0>Tf!?S={AR2zDiB-z?g_Vk7NUOqDj)TlkEj7HX%0 z9FlyFT~Vz6qRGfe4@!<{n#jc|AS!#wvC0T&2Ihl!NUVBbvaMzwI!q1JnMUvIEPARZ zp&4}@{b6+Cxd~m8#9uaAnttvB?Ics+m0s z7ih1D|Efms#+mf8k2l!`765XIZ$pi(P?e%b>gk{!`@*sx@#;qJ+$?&k(bVB(2c+t4 zD3Dj>O=F>WDm>*;;VXDb9UF|bXk(tkPZqeM195;Tmj}%LOMHazRF3nJJfhl~{7rWF zv^n&Gbopa_L3F*(DC!lv*;NI*}x&*NHsi8rskde<2C-m z-kuP_I}b4Ef6;v7obk~r^ORFx(Bo6!VsV#T0sSN;o;1tGW(NF*pPxC4Uh-Mw(3sHU zamBT%cckMvw}>x;%J?!?friq*x6GnP0&*6Lkz^lsPC6o+z9S#9a^@8;oT0`Z;qjS9 z@0Jz4%1AsDcB@pzRGjeGWVhp6XYr1Wj0Pts;ru4NG#fZcB48#w_8ZG)N0a%3G!~8W zh%D}^Mc%i!dH;^)TZd@9ruE9tQFmu=*QV5o#Jf=xc_0e*T?9?N*Mp-nYVXXG4o{n!NI754BR#b8E|De|~#Y z{Nfh3k=gl))n1P??Tz#8&td!HcY89lLJl8qe|!!Dh~oTyF?&4Twd$D}%+HHf|Bhz# zKYsQ6G;@5W_0y`-lg$sT=kxnF6&KNgP)?k*XccrL+`4S_7C+>!B#|cj$<{i@FZs9F zTmOr!@l=WbJm+b*(2dY5^uKEapF7k-q5oPd?EACdJM?~ym{*sXgrn^9fcklTW6e(O zoNWuWLdr(UDkrEvkW?*$&S^?7S&V2T$sQ+vn!cUDH(=hmtq%|Nq;Sc( zrb!R3&Mg!xK#-3NweWFEj?2-N_8+&`wp+AUws#*LqOv`+j}5(7`p)9Ti}@{ijhrC| zby!Pf9sQw+e7Jds@L&?Q@C#P-w%7Iw`}c8)`c%!U_J+D+DV|B1RO>*S>#5UK6*6*u z)+|7LaEja(Ta=t-=0$}CZo^GkNr7GH1K%!xDYJKBh~D$tlYX{)KdrIT|Mw5IH_D9< z47FA=$+{$m1CiQgP4eVd`6PB&B$7%3)&&mBS`r*5_IP3zJxDaD7w+WcAY{l9@`VQ~ zR|m(!a4enA)iRxH^uBN=J@f2`H?z*0c)~bxzedo8oEFNdj=~3-PBHzHv*el`oMkhdcDh zy_T^I+cu@5+SF_<4!(G(XO-Wwy5vUfI~xvTfxcwu?UKtxgmloToTP|*IF^$y=%TSD zUoFZAvLKuClx}>?xJqw!*N9YA+j<>s5OCFjed$n3mS;l^pjlPR~*~&9qrk#9BR2dhstDmKsThT*yVrC+yAizE2zk1b5xaRMNG)oKo4@e2hCs&XbhyyBCzT1eH`Iv>Fwq?e$&v~h2c^c zIOUUD8bkl&bFpisAhl4tZuH8^w7lhdKf12>CvuKQulfAVL!+&^5y6P}`6;%XCrd;H zS@5Uw$)Y-5l(#c`vBhwOyB|m9<|EpZe#m<5*;yak*9^5&xm~+y>{o|G76-p|=-nDK zoJ!WpS6XL|)y)|sJY2FRe0eGptg&>eb5yNpCU|9hBtDRS#zum+*GGE0@7K(Ke!^k+mkjXZZ z4A@AP!Fox~NW^34$9JAz9Q^KC^mu#PN6S!>O@?V9d-~`%Xh#H<_$q5UbW=Tq8yx41 zk0nkfL(alz=mTkiVw1g><1#`Rmz_=}g4O0L8@=DNqF46tnUEWNVe5A+&}ME>W%>Hv zp2fk}&EjaR32w^TvL}8cL%bR53bVq|sbynfaULr4t$Qd(X0XP9D{X9@gY{?S*o491A7362EtEgyLrJq6El1j5)&2CIosN`k>nLgaL#sYL6Qym_d!KLP`NKmz zE@?|HMbuCj4LXy7kPRSPY^fD1_$J6LSr|6e+T0%*qPLwtUO#E2?)~a_0YDVJqNYE+ zzoO=k4)vrobrF7Hl&`fR-Lj}il3sr)*V>}@#>!%qF1?-X~mct|2iq6{6|%> zub)EZZqCT?c8pRvNis+p{>)H+N-mN!=w~~K{;hIP&sF=Dy|n*bI|Gw+J$sTCOI|08 z+9K*wC-)SJUP+g*^{*HTCR#edy-a89a}%Eh;4fIBrTQI`_3Wc3)KbG z>4Nqko#Z@2J5blpU^{6`&z_`p+}V-4W&Gs)KKgXTleMdM|IZHLh!-#Yzk21I{#0i~ z<*wl`Z0kPTc;Z`!TJ9PCoKIQjc0o-}?s9YW2(B-rleebp1+}lTPWf^-^*)qUnc$p~ zl(s~oe_^N(#ietNPdU+QUvGL}zHL^^n>7`?v89u#76;!x)N-9$R2hXjt8916*0wiK zEL$A>#l8G|-b!xjBpU0S-!as$iU<1nXVZP;)^F?uty9nz2Y+d()ygDRbm8o%^>fk= zo6M2%J6lix@=%+#{xEHGQ%}gycMi4IS4!j+qiv!F*!}+YxAW3BTX&Q6h>ldPXr0Gq zRNpm3wIrpeuG>PZX6hO0 zoHutrkBp^sxmvxY&BgkuY%)6ol9enwS>-5XWUM(^dlDOqk;SChwUO0& z`P@{JpKGoB%^`YKHCAK5+dhJ6|G#^vz3RWLplVX}NXB5rD(hEP>r$O7A0UUM63Xv# zJ=R{V-MYIvb5MDg`4tt1D_*WwR5+WF<~_W%(XzUxwX)Le`o|HBXVWVN>q^rlhhdg z!B8tzdvxQ{dhnh>e{P`;AGc+p-nn|?gmyPc=bb`@J$JgEXPu(Wz6*8a(|_C5(9FIa zpHm+7U7tU&YI}RGUiDP}`)xMeH>5I+%C%%m3|pZQLu zuGJV`-`a>(5xatA(e2;K`bnxz$d3D!qdD6%DCYF@mWFrK*Pd&cvFQyfC!fO~-b=Hj z=5%QGS^Q^1TrGSGLGt*J9wZsey*4pA?8N~SI(DE%WmDw`3|gh5DocI z`whv(=Uess=d#}Op$s`K`RadTFqz+$%T)_27IGl|C=Ftg~m2}oj(8Dp*E`S{j*yi+?G5d75$y7+dKbm z=$)!C*4GcTKXu=VvtFNQ6{rxHh%(XdVbeJgi_;Zi!*T}fzaOGi^T7Jp!CM){< zB|RcepPMi1vq2>MjJV@$8{1C~(R*%t($7uJ&$#_%QZ^47F04 zy~~%oT{zs0)cL!7|LBPvhwU9d(@a6KecSc^K3Cmwdm9h!Jl`s+$=Sp0{o1u%&&cR) zKlNXS#$3{1hSlGwj^NwXPOxa|`glneUlvHVD0`dPO8og``o62@|9z;X z(gQMccjHly27hMO`_|25g!}tHJM@0pf&PB%z|Rf6T{#MQh1?;rIQSo{H@9(hJ$+TH zP{<#*=8o{Y?9DDd|IbwmkxGBhmFQ1e%JY~+=Ma&uyzVmJKJT*C?k=~YWO{M$l<%-XzZb-OK7YDy&sMVTH`RtsPEJ{o5o0*gIX1ne5 zmP-)b$oO~yu9pXvCo;Z~QG9HB($8%z2X|Mqnfwm9+@96xjAk}IY=}bn^66b?xdSS# zeE3i+#TVHOGMsZHXun9te(CITVI5R+`G5A>s=yQ1h;z@hk^a&ldgYC#y-t5WV(9&{ z9^2CK$xS-$TV_i6C|Sypd8+Z}Wc$cNDo}C~739t5%lDHLwlLWxb|5>t#mUgd2))V$ zzO~7P(~lo)i1eYBsoR!|nu^2f)aN3&}tlDCa z`sb{zc*tswHQK~P&mZDS&4LV`opt;PJe53-Xj!ymg-sj;e`SwXK9gZF7qs&QL-fi+ z9XHY!4z*Ujuj*~KBl|#E4SNbj*><00$GRPF@>0nis(?;(XI4jKsOZUFi{9C+?1JNY z_@$iNfLq~Us;u!%4x7eW#d0cS=$%}yUa^ve5xEj|h#(Ways!20!t(ytbyQh?u%6B; z(4)&8pfp?6@Fo&{@hrZv{~~DGZcgm4rp?Lb2DN9$4iC-}%7}Q*ch|QOzhsDB<-BSn zN00lZLv0qqwRR}S&(eL&(3_PlyM6f{4fXEF4!v6v$1jL)$WzwAc}U2J_VKORH&DF7 zH-4l}xOV%~90^Z`#QrIGO6+ZiHQdQ7v%Xg5gTcr>%qr^&t;$!rD{2lsdm3biWn8ke zQ(Twb+q9KF)3lsuN8i(ntflh;A3uwpagnS#jhMFbG_iIf%;ewjkj20Q)-G9XxxY^s zqF45Adgi{fa7&LwWRUSE4z*U&U~X$gghittydz{_OmvK8@_!bZ-X(uUcG#c8A$sLA zr|CA*`I^P$FD)~f&3*G=zx>f6J1@5(xA zdD#$0Y6kd7{51>mPrQumvYqzXBLtgdzmWN%Pv(Y4qD}6R8qtsP_#>ly`A~~Bf~>>H zmE;5-8ca5fhqbj=#cx?_izd?dM5tuw6&F3v)t3<;R#9u8*Z$k?85WoK8Fzct2*;~W zS&_*eQu)UC^PJL_`Gij)=-7(v=aMUip{{KFdF2qj%9R~GzE=&kRejH#LN}}d>&!Mo zM`X`P#1<@rwTGN?CW2;Z<E9nlqm{N16p^ z3C$--=Leu$(GJn^;gIGtt&dmFq6Z_0Pb#ivC42&niSyLy`CfDwo5Bj}ndnLW@tPIAlS^FHfsaU> ziW?`*)(w)0l|`VTza9%8w%doCU^9)6-K8}$-!&ujpB<2cNqng`$;mb5z#1*@2_N(B zqCfLN&TvqL&vire%Hr)C;q^nURIf>Rqy;8PY|JCr>6>`95I5{-9NE*%52!*|v@y)# zk_=W_z$uYP&N0Lrl1W-TA&&)ziuA}dxr^6%-7I>rl%D6D5}r*wl*k}aIp4>o>j$Yu z%Wu&ZCjrkHpI*n7=s6FPb>pBv5@Fs|9ndK8S-eZdEQ^CT%%UgO!?7U7M9L5)K4%rc z_{=1GXI}ZVWDP}6?(v#4KD=Z}a~2bvV9u;MWalz|8=1VjSjhj`iJY%RUOsIWJ=!B< zl71&bp*3X4h;nk5CvrvysYTyBh)Uf9HfMa=Bz4hT`T)7(D2X5!B+(4wc&g2!6F!9i ze$^~`bO`QZCuG-B;X{Jp4}YTrcd-)YlnjX>$d#Phr_Z9N1=fkoc;BWLUhNx)wcBG&PTw+eQGqeS@lL0_FS03n~5MK9LZ`@E3( zBKgq~5qG_#hyW3-qK9CCfU~VD@BqN!mL2YdveF zhW?$KMbBK(Fjgv_f~SOZU&Um5os`#@zE@PmfXWu zR!~CkYUdx!K0c649P>GgL|0{L z*g3xJY~#>dhv*ef9vR`=KBzqJ(PRH@6XjP%wLh_Y{p;2tUX*n5fUFW*=Xbp3W#|~& z$Lgla9j6nYvBB!!Sy8u;jc7yhzW2WWwmH(z8fvjd0RQo>EGe(S%JR&td$ft~hdS6? zevGuik+I8e0vj1Y(PMv%o!w+@qSJgliu^I31O@Ym))67CU`PJn3jG{W)~9D2rKe)&TdO5{L7APID=PVgKsGVg3;EH8=RzZPw; z#TTj=TizziTEv2scPm&&i88#`v=G z6MUd2FeU12YStQMHQqgo9+bh4(Zb|eX-BLyX$i70Qaup48oxgJLm%EVi=N(l&&Wi$ zyn@^%eK2Qo5iFJO%rsmBUm2xYSR8!rEP7go_{F1@4<{A4YVObxf50I0F&b%{xFDze z-dXg#Csrb(kemLaMF!0kIy7Al19BiQVq@}!5AG@((T5kdC;ik;4_@9r88xl;HDt$o z&Qow7*+`pZBaK@Q04me_(rLWP%)y$*V4R6JJS_rcGu=lvLa%CbGKTFD^qus-W~jZw zHCgLcD|2^4HocWQhgvBvh-u9sUy!&oXrG@5))(W@K$6UsCMu>+(Tuxh(-UEf$D;Wx zNq9>4@SFDNRYizq%2TA-P1MF*P>^H=&^*cK_pKcfnPKj2Uz`ZNF>UNh@n~SMO#suLyy$69I#U| zRd4{B>;r$m(~*3!Wh@g9&WG{|?)Dm?S5@0LwAF}5m)T(_Yxw=1wjQDW&#he}EfuFo z1a!m`rkAX{&v;~`&|CJ14HR|xl)RB7J%4bBUfG}C^Yx0fY24*zt~q0%KdF9KtwFzV z)m*Z!vI;Pgc@=5U2eQZVn4vRm4DXvo4?;l)B7(W%OWD9+Xx5oLK#M^y<~ciYR8F}= zE90ve@0oB$cSR)Uo1{J5I9?LCDSr>oQL!OqkU}5=Po;AK6tKd(-=QvJk$N13&xElYMlkClwp1+MccSiT>hkWa9 z>Gdb3w@TNpko70V?~^`G%FoZ@WiU_jK60q+gGhrlz&SXGg_S>t1d|EP=lr!>!Pa>> zze0CTCFT0c@4hwe@hrVo};|c*f^iq;QhF@e){ED5AI#=V0Plk<{8%RI~(Cw*#xs8E)vy=lfrp1i=X&a z9vAKr(?b`@F^Qb4^*lL5ZEHdc>FM9=pPp&!XPcH?E#emq^`u*Ce9Ue} zoZP-A#$9J4yew;d+{}FOswL#VKY*sne-k$n?S{MlWILO#T* zU1EY-DGy%f;j^YLzL!N239tZU$jxgbT&~!z`n@@>FCA*7c9XoT&3Ecqonu6LzHI3I z+V%JD<@peq&a~JweYmBX{6Vy*d0O0r*K?Pz&;<)$&d73N2*OjF-hB$7~=xEKmQnv*^Wk zM%QD{a5XxpMOsH2%$=U0PA3yTLfXG`7QJ}Vtgg^E{1of6CXsu(&ARzS4mFu&S|pe2 z9=|#KOk997sdF-$Br@x6Y_rd^J{ROidaWwqjH;a9J&PXS;!RX|81k7>WDQ9^kLK%F z*>%s+4tCHzesji04&&kEsc0dKlk66mN&X}{fZN&i=Bd=$y2o!0y{vE2sCYaQNoJGb zqJJzX>}^E2A!^e@o{)Tg-7I?MO_WEUqkr*pEEaE&7(Eu2|JMW3$>z~Ox9ZIqAIo7y zBh>Vsm8Ju+aEU(sj}JzNWw73$pX~M5&!Q)Wl@~W_#zY^CAz5*@86Dr!3RZ>R=b`0u z=)>=uMNb=M3qnd2rE#%W))Y|ZiIV#?KH5QBA!Am4aqtbZ=q001r(=^zW+Wjzq%E{9 zny6Pkm#1O@;fZgYMUU(yd#lnX^Jk>wCo7#SC<4}KaXC#HTm~X2DG>Jd@{j=!7tu!8u_y_hF*J5dSAhs>}Q+O0VNR#i`>pw7y zp3Dk=gI_F$`HTEnuMt5RGfcxHkRrNBURW6O_XlUuqirN5n#||lQMy8ygyEGqYnP=;2_FJy^#T|Adtriv&2k@FK11&e>@!V_*iBq${ z8k1F)lih)xXrJ|>KRQJ3rK?f&5lqkge9guv`q^IJG}L;hR0#stAjXBz=B&8{Nn}RF(o?+|A;QfXY%N zhxN@v?Nq;mAM}XzGGFng^oy@&-}qFYTWMqy*l?DQ7P)0^q~9-I&8I!cPQ7sIm=zKG ze&r&aYag9>VyO}I;7<;1wuht%J zUX7zhkh9bd+i09#^FSNZ`S$z$Pig&O8=pJ5?`pI5U>of{%kkge=>F*;x;0Kn9PblR znJvhH+_6#SC6TL0jE6IK@rGG_a1-3fj1@gd0Usef{uw<#G&{7|?5YLh&($M96a3KG zHok9J(F@hx87MLHYucaw04PW|`%6TYO{gr!a=8dlqHt)o4NEz8N?9_#$M5VEwcG!&ELU`Sx-rYh3X1-;LM@NGVk1X@{X3hu`9rFH> zauFUb`UHA3&c(sE&7y~n-a=-0M|)E3n5YTVG)|ud9w>o%24sB=J3i!?=Q}xmzpFtAoU`tYm9ZrW!N|NPqf1i$O#0Uho9du ziyk|g+>0@?0jV{N9gYn#vydZPCEEq((FMBcMxHtHqD2^(ZzcI`PGU9D4AhY`K;qdF z2Sb?X8n@ee=Fnp^_!ej}aRZMI6SJ`0k0f&fufwOL3s!=BzH^A)741nsYAI@$_F=;( zyk(He`Q}BOgr(k*?{w-ekLvfw+H=-6R6iarpU-cPH1Fd)p!?eQDy#m=P+!Ui;4=)) zcCjVo6$)ev#2Dl{HmFd%nWkSPNd)p&hv=D=?Xgd>&gR(5>xLi3eLO#S=1qQl*HHgD zKg@T~1$|}#Ngv+GkB2+BBu67IWjSDw_)d2U&5^xm4O>LR5+~CzD3c#%!El?cAf0+) zy%G0mzng~U(9`S8V34ey$Di>9G>VRC-{*WQOd@t?lhOO@v*@w4c#|lQUhzCZo&2fj z3>r0heM3LiGb{J*D4H`qu^rBtsYL2*EnkDvdZTstoll6TVNLiXsL>robLg>wi77>~ ztdCadl5a?onZ@yv5`8eXtdA@XzIzruvVd3NmbPdveT5;&pwaVs=2Dz1W5R>WbITC^ zty%Q&F&R%Xz$TLu`A6gQ4SteTk-JO*Sq*OCgBJ&Xdlo$&5)I?wJ>?Iy4+|Ls+B}-< za=ah?(-ZRyD}2u^df^QDq{;ao2{k_G#Q61t&mph$&#GCx9^3zSX3--b@r|-8sY2no zVQ-oT7eONC*k>7gaD=&B9DMIAdNdiXsoBwDuqFRSa$?un9vmPmupqP^U;2Hs=y@wT z!DgC2Rs}CTG63=4KXhd`)hz8;?Mk7kh8UL564fjdS(Fc)} zIfA$7akpb^mXXjD(is~ToP+~(()|6?6}`k0{;s_E=qbQ;$Hd6_MmM$SD`!^M?QvCY zxBblz&*DTZAK7L7$QTP?#xlh+eSvFyJbYU z@rL_%%lz0-PsX_T<3nwAeZv*9%=566thBsCa7!ZG;05+M2oPo|efx=7^yHm`jM$l2 z=EReUb>Llpcv17_8MX_CGH-6+8kw~kpK&EBfrr=&TF0{Zfnn$vN+bzwGLmS5*1Lf# z^ycfED$=KC=gyd<{M%Wa4C)c*uuJBU#zhYBkaYOe+_BdDOt2Ck!!rM08=Rc)Q(x6u z@iXF6kG>6JeUD}BL-@cl_i0aqoBlTMz;MIa9NB|BFcl;AK#K@(OZwGGDQe+9wTo$|^x9G!G^tQSN1%L(hoJUo0stW%F=M zn>>IOGFCP`_bJ_lbL3Cl`Phdp#8C zusUUTcse76Yvl#mZuiQ~kuKgdUY)m=HKPCGI2f%eCg3B#^Wr2Len_mhIQXwCdf|z` z=SEwHOKz@vhBM8Ii>sboR!QBp{M}8>Z)kMu8x>Tls_t)|`hnI)o$#>!>3^HWkK|xv zAXurO9dd=&BFtDz_AzTfkO<8d%b1zP!G9m3SG7F*NAoj7?UdZGb}YTfIe7s+gpou- zqz48I285?+L9lfqqs76`&Z0*a#9ZPU8Aq{Re4@-stZ*t-#Cozwkt!&kTrCcMZWcZI zs@2R3UG^s)3;kp%S!_kdL&O72-$`9-1|+<8yqPI7Svr7I1O!q07Gu@9n-d zuk;}qC?kk(CZDu6`8PO+Jn{_5r;uIw{^$<*e9kO-cqj@9!eF(@q*nRs)FZH{!CA>z zTl1qCIL(o3m z7Ll>QEFq61zNoyP`Ed*3h}5n3e*Y*xY^b%eL1F-ZcnAoBC7|+FQPiwS@p=r4|PtF^itQ>$8!uHHrD?B;BV+EF!vDIZ72kv^M$WkDNs>+=-WB zH`xK+H*s+)yI6d7m+isF-~qj1V?Sy|@8mlA^45wU_xi%R_qIORPe4Zf&piomXc~NV ztL{(E>T{ME5H-fT?&y8NQ|-xb9sTSto5d}06pxx{+ngucL=xF$bH+-?f0&^}?6}F| zx$$;H`aXI!f;nRzX}2QMqd2`dc;QeVYmdR(+6>uUuxln>G}Kb*8lQuce#kYABKJHy z{o@s^u0vCv74ZhK@xx^Cqi4}$53HgD!v~M19+i&sT)|aYWlRpjJM5Z%Ee>8hi(YCp zA{|)~uvWxY>Vt9mn=U50h%IGb@Ph4n$t-%T9-kjvWPJGPGa5}+^@w$5QB>OS&EW<; zUmU!27CjkN5xuw>&P{a5QsQT@Osu~60v3=xqfhM04UOK%%%T@hC{nMTOz@3ykQ3vC z_xU4uhCeW;u)jaziI1H{FRQ<1N1h_pF1RNj&t}3h_zN?N%HSE+lt(wiZaf^(($WWU z5gd>xHe+K^Xa@=L8?P(Ykgeqzc|wT6sNHxthn~0~l99PGYw!n-8YexFA22HO#}67U z%g3*~@o)}3m=?bEw^5ocybS7w8*mLS433PorL*MgOr!S+v*^K3DBz#pBk#Oz>LU1T zIwzwh9@95iU!VNGXm=vc8J}^{Gf}L$!cYGrBcua{PlS^hrWN`{D|irhBF>=)V z=|pUBpl=ojFP}xv?2!=mid^7lB!^t^6tR@-S4F$DCH@J$SInYE!$^CwEQ#lXYh$s^ zC5w`rV4@T=mywdsUoneb`2j8Qp+?GM&@ozOmf(0gYV_>2SSYqsmj9Kr=p`y)ulYUW zGo$(+xeQI;kSP)gx$Bv^MekL!=xLcW;1@oj$LnN;jn0`r{6q)R@xA%eM=Ox8o<&cD z5l@$T591)Oyg8XgnGK?!G{o;LHmiW|?kk+559WdW&`xwbd3C74*l^eAjf}+VO(H>B zgP)%=iyo_(93`zFbz}q`T*O(3kZp^G(-qRfsu}&F)j4E*$>L3S=GB>F(;c#Je`?Q( zI}Yb?COhAZ8LlA5L3GI*WtL*&BN6-z>x4h@TW(04Lk~ZVJ=T{52Z5M%2#g2u3CZ#l zDN7!WXMudK*vpwZ2ko}yj@8E+x_3+T{VgZrPQp3836Y&D&WAA|-;J;@`9 zFo#T#O6==q(Sz8Ma}}kKAt)_~gKVP+H)b9oSpI`&X6x91>u1puQ$#9w+}IsnDqab7 z5*z)7x8$*SFWG$7$qj{bWR|sN8%ZH71Cz4YatEZ8C1c%aJWl~R;sC$TA}-oN;ghUq94d#VBwN{ejuz)AbAHBO^QppKg?FfoJHW?|BVA z;SEFdDtp;&w4HLB{dd3M2sf(tun(yvPa;u>D=QB1-{u=iCUG@W;x0(myt!X+gkGKQ z*?GU+_w{{!oBJW%EI2}`MrNhWyuggfy$1)!Ye0-veC>CM_f9S(vMej$X2B79vIKr^ zUhe(3Ms0`U<{1EPJ2hXmE74QxDj#V1IVTGE{Qb-SAGW;To$cfht&r0v+HY!|`hHNB z_tS^^R=kiM#SI!2+(KKSGdPppg%62P@QmLip=^%0?=xo66BCeg_7P5DF)|<4tMw!{ z%^ZkR;;UIoxL+RY%q)6vUTUHfm6KvrAwI}btHDM7W|c*vGH0y#nMUvI5WSbSC;hyA z=>yHlqsuiAb9hzzlk*=+2HaC}f15o%b3~GAw!~O^9V^U!;Fy>XuHhmKfGd=-8ndKeC9v?kuBswwWCGjhTuda zBqh>fKI3t-3U|{idickKikxvt)Bz!rN_6A5;A|s`ba;oYHfHzG%o(3Kl1HLLEKuf! zHW-6;&840|h4HPtA3Kcmi-R|>=tbK6{i62A&*SVD~L&Pd2c4U8{oLDQj1J2HW?;a&~hN85-_4c&L5C^3LHG-$nZ9mRuu`$GQZeL2fWI%_NVp5V#i1 zAiwijv*@A09r6k|( zxx@)Pd-6Mci515=^s+vWn~7BM6RPEfa5sFG+aj6l8+qqh^a4L`pG8kx!zLRWA4R|V zCu}$#(g@yypP~VLeV%16Grq{{NQC;5)=NLPHSg~H@<$pK(x~G6j@EytYdFQtIcrYn zaO-_P2X5C}?*8b{)(s)k`#;LoZa<}>rushL3slT7y)&$C4C|v>9Q5^KcdTvREp|BJ zfEx`*B&P4JyZR}+VC{OFr}ocT>+WNBi{S{3vcideEB7Wgr42M)6fDxB89b0Uk_54t zY;ZDxi-UI!(W^1-JF#xp==!;J?;fJjvn*Y<-m`kM{8aZ`pSY5ZD;j6-ZhU;O@%KW@ zY@KUTn>}0iw!GSLv;VoXdUp3j>fbx`W|zX6{oQNjpEuOn$F0UJ59NLXaaBCUVZ%*M z%(-XzDGnSS+}iF~5kKKgeAlnu%gyp?XWIKuw3eQ1E%!Nf@85`2e$uLc=O*uVUEA*U zW}oS&2!gL&9Q>Lgnk6;2F71`^E?WObdRv$Y>T^n^n3M&`NrQI{wNV+hx3@RhOLz5+ z&@TOz+2JXm#Goj6MU)|f%gQI`o~#OOr^~+K<8Em5?ir$28KAnKV0zx<;iO8&{e5%# zFYgDfCZjEbCC6N=--&l9N^1-3;maJL*!TI2!)IW>B;4gSO zXhytimaMJtC%gtkrGnw}hv-#p&`~3N-%v}nZ@a3Dil6S~8=2`Ed14cB3ICTW%dAd8 zb0TDz4VubMCZo@qHr|LG9-c)H9)uD_M#);p?9gTCOh!)Z2dCjK>TsSPv5FkfBeUqy zBsd=KltZ9}W;^w0iTGiEV@~}qTngq}ao!<2IVY?Kduc=AFxR!n>MY zijgnO;vc+92jnZ08)9wb0eO{V$dU<^u}Zaybwev6@(qg?A&*FJ<&iqtzPU-TD%00A z3E=tHNAZD;S(zV$yr%Wd&vxsZk-n3%r+dIMuiNjbOMjw86?Zm^BsZXHE;P!s*E?|L zovlqXlDojvX-?mKVu))~tzye$6U3P!UNX+tlYRNpRO6W=YgX)8)uoxGFC3!x(QD(W z(e$xwbKuFLcFXJcmfS2iA~$9AZf$ZV8<-xf^YYiOS~@PbR9W=xajnPK?`%@}zV^p# zKhii-_HtyF7YAQFG_H#F*K<%uOWxw(ONQDmsbPbyjIy%Hf6A)UY3n0$D)NZXF3%)m z!WYJWC7=K6hUitCbyL$L(c@ujMJA1QUugFH&gP}=Y<&FEq1I}~`%LG2(VJR(IhEYK zawD=+2&T6b&0QRP`Oy1?d;7SYF%A*l*~TfZGper`YOCf1_K>5?8f>r%?&i6DvM2D<@yuZ!i;^3=iaS}h^A{k1E)XYJo75N5n`vfwE+pH>N4a}^& zUv5NF$^uOLZk>Iz_rGzdwJ}corlGb|i!}rpW)@u1cfpDYwau%vSLv)d^xUIc}&zw3+H? z|KgZPEZT?*{s&*ki&*ddEkpFm7OnTT#`HBqZB(E2LQY@apS(gsGBvEEnM(G9>?S*s zdP`QwYMD6tx6Y!Mm9JFA(T&8G>Ywn7CW+Xs;E)xPr4OtjYh=!T+lt=F<>r;G6+a_8 zDQ{^KV`bo6i`(A6^i%upr7kVY-6RnBVXLWmWBa>*;=Z{#5~a%4Y#6(FNo;Lia7jdA z1)kT7eBo2F=vEfR-oImrUg6a7(SGevyIsoI1~S7B>p4rA*`+n9u~Lyo608M5O^_A~ zYJKZ>&Z0+_l3PqJh*ZOFyeK`i_Jo6cVzdvZ;ReWG6#Kho(UW({T3Tu>%EOBR)sB&7 z6%o-bd=SyI1gR`^uiUyd9FLlxz6#7jmU_TuRt7~L@X6&T?ys98@3If)Ms_U!kan3IVGpN{O(h=hE@EI#51Z_SV5 zr*(DKiyz<-_-gizec@$Q3$S@vdspfBjkD;nHZ`I1dfoRXSfxk+uCDOe(NY?kA< z-J>_h4zS6|F4BC}9sFBrv?DoHeSt=Bmv`W)pv&JsL~n|u5(}&Cd~1vF9%(%K0~giC zoh?V?zPtT)y;keja~5@XJS+Nm(>qpmaZoZ;-&PGzuVd(||MiS|g=s65FPl~@6bE)a zr)Hrdk=^IF)CltSz0C()Xxwv;-RAkDZsMCK0X!)T$RdayR8f*}vK&c{l#zKd0$uZ_ zB;`!w*dJce`;hj#pT62&d8=2odVx2#x7Kg7y8PhXJ3f7NYvGT~908mbtHz4KWjvRd zF%^su8ZClwv%?-X@vJ&9_wUW&m=~iF`^RVTkzGw}E4xS1L_7FN z?ntB=i`5m)s2HfO8}k0%oo01nGsrv*tv{%eUctYHP_ibO1@i3hn_Mp;t)e=yCq( zi{|;9xbhv#JcL`K9$xXgIE(N37N?zD5c@TKqh!0@$xO)R%WmYoKQqLek`ugVH(5_Q z4ny$y{I}U5+o>cMb5;!&L~d@bZGHTfA$k>QPDc|-tFdg3|IZG!`-@gwD&PIBtGBkT ze|;i%@#ki?9iRT^k8PXv{tH8G7yq+Xj_Yi;Xc7YEKj1c*B=h6@oD^sl$`8+Nee*NVkdbJj|zrJzGQ4$2He&bd{Q(A&FwUfsj+SBF}tQ$tm^J>LGr)_vE|yH($IzDbfw4|ltb_>Vq+v{IFcI=5gu zc_rC@Hc;M*KFCT$S7Swe>vMOz&7lXsWu1uRKx^@ou?ES{k`8$#dKYRmP8~TL^w(GP z%I0+pTsDD6-L?sTV^%-ajT;|N&cZ;IBKXv9r+%K)i$O)BMinl~@sR7kIYh54!kgOc zIZey_tJ$$0X~&idg6|$`sUw2*ma-mRZT+pGwz_oioMILJQ9PVzMDEf2r`Evi_@7Lp zIg;aK!Oyh5|Lq}qr9&z|Ht%8no}m`1$H{!kf|@Vc_SCKTn~WPzc6dehV$G9}5uLd! zZH_#rX3Kcx`NN~wK~YKkO4bL+ISSSw{R@ZFpYL7K+m`40gopXQS-s*<-N1~Zhe2j z-6`oqRqePiX>bv%VC*jng?45|90Q?YRFavPynReQT?5syBf@dt+5FK=C(NhQQ4 zZ+>v7t%|0P(#&0)|DmDQWeNRsPQ0@1;#uF*GvDgSEBuoo`Xe&*PlsA63)au2Q1R4f zK-NlTy3qR%54BnrrSb~o&L6enESGEpYn6&5xYkOaygr+gTqZBH1)?*6lpF&92` zis^%GG$LiIv(WLs9BQE~m^FsSn+@XSz5Sy@Z&xPfoo$C9%=WKlzoowR$7a7JpY!9h z-@2x~^%FyH)eP6XnA2FIND2=9>!FrvhE?w-TPKU{{eLs`eqpt;VI|S)?JW-e?NDo# zLz(JGjcd9q&#h9CzmkvbRjGbIMy*fv^9Sma>55f(-M(VgTW|-|h`d+-*K;=2;Hp7)eu2k=(0Hf@qm!%0fYRxFCm|dJDC4|78|EnOm4XYw>!{9~&)v4<+)- z^ux%F3EuaKx-I#E|7R9GaUJxTil0>f7zuuwTR2}XMJ#C6a8gbJx5eUaHyW`RB`>P2 zje(R{K@O+nI#g|;97;he>g@1amdhVr>c7pRr>-fvA!wUzF*dEUB=QRAlG1Pj3eu;n z=-$xi{r6e)v_#^?Y~-9QT3N{ap~qHb?+cD*%?;YhK8MA@&&;C7PRegZ0~5u`E@$Ob z1i~&RlJq}uqdciu&l<+huIN=Zr{^o{6aM<=X7x(6oO#3htVZM{XxfP1ECF7q(M$H0 zyak!6w*Mcq=#diRVRe$XML$+3aTgv$o|94YM!4Y}cM;8zVmwT>6ipP}nLp7u-X?Np zF-SQy?Kgf)U4_5hMKnTh>P4=2$aIwC-~pAYZIQt=Ed@)snD_koPZ|MNc~{JWIqPv554Qy{9Mo z1MSEl&?!DMaz=`Hm*>u+r}wd>e1`p0w1RbF+u1(&OOK2TUAD{`Lb%`#pUlP>KfQ$p zD`Z8|Dorwsu?Do1FE_qePMJo!CELXM{^D8m$ZEW#oF!i2EW42Gak5sat7mygHXlxM zd51+igLTgM_(DJQ9tTC$G)1c<1O=!ELdeeT;3c!Ce{SEIL$7KzQ)P%QspI#pNZEPi z|Ndp&NKEvYy`rBYgU}29^>^vx=;>&$Y47-%R=M1^JnzH0(8J4^e!3I2Vtldjoy$D- zZL76p5waa|kGGRX?rLWPB)cIdt3GYNyZiYMpT$MePBK+ZX8%Qyq;)wGAH-wsf_qXg zMpJ???O_?2wTd#fM{zs{K4OSM&85AH_cXqJi7uv{PJoI+$=$djxEr=Zo_qA4DGOLx|`^tzUC-~A;E88+z7U@-ORr-xh z_SO+Zzr&tIuAk{0_VpPAab`ygGRz+{G=`d$=@`Px^|5^H;8?ct(VKSkZ|+!r`OsJ@ zr&;nvMjveUoy33K-u_pf?YfOwaJ$QhBo+cy{mHw+4{%Qq5hPM)X!E32r63ErqQt7H zRTQy&!rnfX{o^b1vo0}aL?538` z+m`LJXP?@}xv#gE&FXFT_GRav*av2@a+tgYUizQv1gHl3gI*HNTKjVfczSzs3{hvV zy{TC)5|#6rpIp|DsV{l3;e_+;Z11y63+qJZXwmw4mSv&)Q%*5sxzv>KWK}8kNwYYV zni4XVEJdx5q$)m9W%g={sNvL9a>5gK+qk)9M1E?Gt@nS|C|@zuR?SFSaJR}x4@wix zE>~XeZhTIaU-8kMDI@Ka-BU-3|JFcMDbxva*83l8e0kMSYZdi&d-Lj{_saITb^Ltm zg-pM795_){L(@ zQA>7pTZimtvbfD-q))}=>eJ1Q!=fPfdyKqat1&k%-- z1WF0E%G}B5_*_Qk(}w7k2Rm+rZ`|Pb_@42nzsl)`W&NO-)!O%)+rM>-hWk23B)Miq zP8;%u6mxQbyon5n`ZO3l_0bS-D#ldWs~d#gq4Q54qE`rMz30%$wC|rW)Kiyq5vUD!%R@_(dL{3APU zK2zx`b4K=|(Ln4>MmfR+_5F)ba@dzpS?w2sPRW&J4mTk$RnCu&@@@8{Cv z(?o83oR-L7)^uqk|7Fcu{+K4$nyXP7-;+J!DP{`Q_|r`3QZ>! zi-XUcMNj)Aj)b8`0unot20qUGvk4@RB_(Oee~7+$=SV4M&D+n}@4J4=(XDMR z`hH*k+dj4FmRbBT((J(C&v^}5cbu@cW(7+29bdA;+W+|uvlXxY)**U@X?Kn1Z5Pea zmp88XnIfm@UNw3DyP96W;ZHWCCW^bz#?enT%G3F~pCz#Q++mBG&$l;g58kUA&0B}Y zU-F)_TdYU1vNBZus6QZM;dbr6ke9Mvlu9h<*n0Kbhv*fG+8jacA*_*p)=+EJd$X=L zw1`b($7rN18hxadR`z(@{L8Abx@_K+t@rPkMURD)%S&yx)qCw^WfuD6AFLNfhsiHK zx)CAq!J_4{=Gbd?9>3*0dliJdXS_t#LSu`p`lk9#9?#0DeADf-=!svnO~c}E`98hi z7p!L*N$NI|3qwhjkZ;d6dhZ;fR~BbIEA(JHHTB-s%KMvkI3MuAhDPsi9%s5MEb-oF z4^gSeau*eLYMsvEPD-CMM5*M_tgz&%>R``thK%s4KIMJM2q}uU&mA+Y+O>^;?;4_4 zc`$baxYc0MPRSUNtMZ`Mm)H#)PF6L$bkDR;&$sWA-Kw_VGt_n=@>`eIDEDOW&05Ln zoR74Ae(q3P#ZRc2KVYSDG66ZXl8#^2%5gXtg*UdcO&)1HORzY2?@W4H<^S0TGn9%` z)d{qU$A!s6FWK4SDVULd!bhLCqF3JdnSk5N7sdup&y86e{OVc!3pQnY$T+*4-A7_> z@{L=m>S9Uxbo@*u5p8iB$U2&NCh>1Q?zyeyL)|noqL(G_>RZ@d$UIeQFeeYkli@BD z8WaQ#!bI>XyW%bPlZ?=-8Q<08yPknFP_}1Vf~UFUyN7sFb0LdCTE$@yW-4JxDgP)J z$Re08a%=^N4S>zfoJ__&L-guIm*n;NH}-NmlH}*DlH5DgVvRtrU=bJyHX&2SL!Nka zT1o?1JJ=4|(|?swJiQxKMx?2*-E;)g{>$d-{ry9&Rqw^OdYP)UtTe(HbU;;DW(7XN zclDtVQg)=$l|}Q5BfT$rJc+jLVHDMi?ciWG3^!mfF@Jc-1E?pp_Udmrn+J#J)$Uz8 z&mL+yY%7s`B;?~?Cu=|~@K5bE`uw4mU)uWMXS-!+r`oP{gx>o5hFUK^;SX=f%LehL z?$DYr{2jEDyp}oSzs(ZPvGi_O$-I=0oFB2y$xOd>$zfQ>TJn=yCn}XKgoS9{C$~TO z-Q6s6Bq&v4LCCa@mZ_cO{gSi7H?`Gr26T+gAj^I`(>U|U5WUj3<3{%AP-``>{D>$j zb=a(hzLNh`yz|%M0+FKG%%^;i7+oaz*erS?3sgjEs0Lf1$41d_fAk84+}k0_po4NE z?rxbgJ9Jq;$t_!94l3uu0vcT~i4_Ag2V?q%bzu!3pGA)i;-6Fb&9d?+i49n*#LvbW zImpV9oEu-xo}8aWkDLXKCf+^Z&L?M zO38(Oec=$jS}*CnpRQVFgij8&RJKRlOkU+)<@ZzFPVd=r<&kHlarGrB-E(XoR*Q zHuB6@2GyG-_pZztAFIN%pes6t`9jYpXynxI?DHlwVrhQd_k8r1%%TSkkf-cMfC_l~ zU}b)S&8CH^KF0?;;Zn_S78eJ5oP$T|{ctyMTPjYCQJ6%Gr>S_Dkw(ehn_Fz8MRw|_*TV-@} zeybeK{q57oTRT-1vR&b#I{xTyzkF!SRox>;)Xx;_Cr9LbrwfhRSDezADtf!QdA!>i zcm3HuZDZ`IFFLraRUKW{=HWffCS2Bd@Au2vtXv@UD&lK)?``v0}7|6jNI|Mjc? zzjpQi*De2lZ;RvK*Z6GUEobPcQM1HTI{RjLyXCo(#CD8O(pzf? zkGd(yz~o0}x+6 zdzQ<`ae3Vb!9wBO{uwOZdXh}T-g)OZTDxY{JJI>0X7swJ?DVrUdK{P6XB6JvoKf*` zeU>>K_j2Yi*0XG9{{*7e-a4WZG1VNGy*bXFLgn>N$%RO#J}XU^b;)N(%Y{sPJvZN; z=FQ#Kw8pkyUqmx$;kcRWoSgD@b3VJqWF+g{zWymq={9l~=R{z|kx<+1iJlppTj!CL z^_sJixS9iU#cIh|j?Kzu+r6cIZOb;L?Xr=g$&*nlncpv87ej5^B8x@S(=I=v)B3D5 zPaYtj9j$qmF5mBQ|gM8_|!WzKgtx*{@j6)#kV}%Kq*2dEDRse7>DNzl*QE{e0{B{@IlK z_50?xU61-VnW-FbJb1d#T681&r5AmceU^4# z-&!XtQ$ERXA4hQ;%ZzxUUEaF--e=`v?AGQ;N)~(TIMls(X6K|iHf?S5>h$`r{nETX zg41pPQu1H_w`bsV`+q4Bf&O=!vQM{*gHxYWIvcN3esZdJ+qytsY44b>p9VD}`ruLP zT6c0z?zdsv5fXluc6PtDD@O8U>Dkd<>(WI@`cRV8b-nr@WM$Q>W;MZW? zeX&ixojxCF+xL9F^?Z+>su#O^lyAG%_V-Bm{&+CoPT$)VbtS6epS$;hUCWA2qpo-@ z&mQf+QYRL#e{`PDlVxM3YnFu=G8^kTZSNd!IkxqqukIhMAM5BIwQWlRv-Lh)EWYm< z&^h|PIi5b#W@s9D?LsYCHQt=}-O;wak2RZ_k=?5Ur#0{E5qIQ5Pj_d2%|&5_OT)iy zi74&p^iDJ0$T&0N@?EFf{&oa#y6u-vUn>4|-McjW+1B`r;m~RM?e1s= z!==%`X%)aOd#nPq?DeIXjpRw!wIMaWMYZg2Npwi*%{{;In=<*e@##yX@{9KilX2 z>CnGt{p?&nzH7cyb+#GTOsmfNT3)X!J9@sK&Z?)vgFVl)>5q2h{gaQFuD5L?+WtxS zesW3|KMzIw*?G9^sR&^HjPII!rKOeIQy{2?J+q<(yc9cdko(}Eq zHO{-U3zs@;^ufsK%$todjB}}Uudi1=9lH1PZ#JGzr1Pw9SZ$p8rKb~z{QqG#=0wG# zdpVxYsQ9F{73C3oKCXXq8fdInZXNHR`;L{<^Ur->%JypdI{KdOGTG%3I$vr$L)XB%?C6E2F+k!kmY-Dbc4}8J68{7dxKal@Pl}RJOJwB)b#3 z4Ga%`R+@U0UhdPA9{qRwZ(XC-W4oUCbWBe?S?i%kR~=64*^Gi8?=$(qMMHYMUCq>c zlir;aYiYf=b@7_K%a@PG7J5^8h@&y@(;HiqWY6iy)5=Kg z#!p&5UjD16H6zA&i@-Ij0-_z>@3v(TZ?$)EcZBF-3 z3Vn~Zyo=A{D=zF@#bQVE`Lz7ox}E!lpH-HF?RcF>W7&LKGdxA{JoZSm>;19^N27R8 zmUL}rJNKcD(!FlWs*PF!-uBHUN703SNaLBZuMXdgHT%de_B@lzTWe(9-eA{szdfuH@?cr$2V~>>SUH`NqSkIn5vK!4Pq26`tgBwG4 z4bEInqxo2+lg7^{+gpYg>o%j$vRqE==B`swoH|}MwOc5kmQ5`y<+HM=u}gDkl!fgy zIuFCKlCO%mP^)K-qqpt3yXW#su)PCXU@vWbp^jun6?|qt1E=Y}K{QB65arl0E7)wQlds$`8t=n{jF@~;S z2wEn3$~~jKg)wxct|4u}SP)ikAu@Y3y1Kme8mi(2@~;zef_LH%M-W!GVVydOyI71B z3&b-|ZPD&Hrd#o&eG>^NFMIm7=+f);d!N;{XLW6Pcgbn%TA`V#uI)N+1l}wxe4MU{ z7z-i9B8UMBaUOR=Lf+hs_Vl9A$LV|ildgUgLfeldx7R+5q%6|uk3{Py@&4;0=@$OD zIH}L>{;~9!BYc|EdSRmdt&d}}UHG@JK~MEyx6kQoCdcbR@$*vnoM_0=)d#{m*!03;%m`J7HAg=ORdFjj8xynS_FxWV9M$9 zBM5T({0Lt3eD^y~CpPSN-*i1CW96BqacZ{+N9*aF6^HTsTi^M&+mjt{oqPZ1Y3ikG z8K;l;S(`Rz(*{&#cIs1PT6Wpxe%8)(zW+b=z69QqqPqK`Ft|q}4naX4ih&pr1e7IF zQDl=vB5HK}W^{xHGYT^}GicPH6PIWb_XVR#l&GlSE-Gpg!=`c9xFs>sPool(xPHdO z7^C0$_vwG1>aMEps_wq;zBlxpUr*mxT~+7Q+3QqQ-*CRwPB6}g-;AVo9e%^A(SyZ3 zZ(n{lbL;k=oj5GZzL`g}_q4R>Nhp`+t~^Z=*qs5B)i>-mbomW2^ZlYrw-eq&dVK zUNq&|PW>7T@_@Xy74$An`@M6HWxXR;ZnGmDL5OZcpxOw?sqyK?nWBx%pz5fGjDT`% zy$>D1n6WD(NMIR@67`v`tFgY?!*Ik&TdAx5Y%#^C{M|&Q2-X21XJM+_Q?vMpiqW=i zTSC9m1kI#PckOTL={{&NW8AUrujv*w+DcU0`bMI_I%K6Ril!YLVrSj6bF&zMQDb=T zA%7h{eP!Oml@~kTHeQTt88zQyL+aH|=zHkRPwTw2{w`phzt%GnkO4|Qx!u=#0~>0A zS#RUdFy9c4(E9ft<~1XX?)i+(YUjagI}a6}&){Sh^r6n}VJp*hOS(M#V65TtBdmKi z_nikn+}~JB*FE=4)KKkMO}f{VBs;Zab^{Vj?vG)ad~N7&JL>oYQ$K3$-}`XOL_aVO zO}H^wCfy^T*44F4;aR-p3)=Z%v)<*8A(2b!v+iJ09*e%xdk)FH#VjtJLm5Wwkz(}G zPUl%5vELrc~cJes(?gTUEk-i$1c1S%yEBF=G}t{}PkezR@ov!1pmIB{k^9 z=qqgAZ~J8O@=R$lSQFlmU!Bjfd>A|V*{+e397$42C5j4eZ<@M0@?^{5rlINObL zhH^z)m2Nxg&>(q~XM^Uh@Ter%-u*7x`O!k2Z9=v}y;Qr-%-1$i9!UQbUi&L5-Fnhb zs={kr_~kvuLfy8@w56R7v$0)ve(uIfOgt!2};ev zU{p9wi<2)bZMP+;$Edu0u8o?cqo02d+l&-mP~ymmCLcmRT&=C{o>MuhuP0(x9dJE% zfvvfgs56gx?Td@GF|+|L;Z-$0%U{a`-2jysD36*L=vY+p+MZ44W_1?Xywb2gOzHrx7KC`H2i!}8}uxxC;!bK-@*b7`KuAncXQ3);xlZ0CV{ z_Z(%i^TX^s)(|E-Bi=`(YqM-fp3br2zqJ}V2Lj7ZZ({pO@oog0Z?(ynfmqDegonI!f|?eeVfNhxFuR^X58Cwc z@kZ~=(#Ct|9F6wcZPn$`>N6m;WR@@;UUSVO$A1DMxnoj_9w}w6l)7@(X18aNvj(Q5 zba=gp06H0qe>FBDVjg>>OOn84}o?X(2XJzX{|J|eYc|><4+#k|#yTtf!M&_Ek>%N%AJqc`^eh$Yh}e> zyXGDWd-vVM3$@d<-Sj)@d>`un?R|nPnHThPl=c+)rf4AI8JDt;W zj)2J#rml6O4Qbg%6^jDeXJbu^Y+2ZN@68y?B9|`it{-u26*EA4Ycl8pywpGOoJPp6 z@>%{F4#0qZ6UMNpVp?xqDq@0WRFJol<$C*RB?~$M>j0nBca1D&OT=$L;+>7yHGo+n;{4p1qG_qY*4bdl8$*lrsoTz51l*Xckx#Ke(kQ@Ld+lM)4eaG;e4=+c$>YRue|rA&OG^m^+Dzf;Lmk# z06%ZBtIlKbz6g8kce~xm*%xR#FZ~<`yg#7>Q%XU2Wy9WmXt@dC+?+Y|ePbQ4Ayo{5 z*(;@8|K2TwJ&WGm_btXOYdY?}MkBH%bzDgbzkAZ&q`v%;Pbj4oBm|UE1JMGx2ds5bRx~>hj>a?xR$mhu zS4%>2Y;WZ4mScNs_&ns;-BS#D9=lL~gFWbMGDR*~$t)}uvH>O;3IS!5i!OeLIYMbp z;Rt1XJ{+;Jhd2`QQSfY}4z;GQUe4A>=^8cjaFnN^9IsoJ@O-Pk%np|)TCde2PyK1t zzD>hv8~PAe4xwc#ar#{MhuOQ5mq!l6Q8s3YW5`=tegn`< zvdni4Ij2;YEs8OrN%--^vCBrc5N}@FusR>p9{QBi;aLIt(xsYw9&21)2G0i z_SNW*QnP#c@o1gL=&f63`>w5`cV9-WM6plr-Ite~J*$ux%2vCbnD(rKGqXQS2gw^} zO>)|^I-7TcLQi}@9NrU-y7bQN`h_!!zC9jqPdNJbEoam2(09NlXdGehBF~G%0FC1@ zOWg%;KD*Ent=m2_P|DRp&?LOex&J;gz<|dZN7JW$WZ`{epfV-Sjhsvq+=v-*e9FuX zy;4ssavE1t>66nnhZbo$w3O1TdIRl<&j;7fY`-V4z^JK1v(Qtwe|(SG0i}9qcZ+5N z^_^Fs7qfTap6scs(Z}$V;tVqejTVWp z2)oN3%u+w=C$MIrpX3B>z@($I_=WJColD>deQvvs&T}V6-?bNxEbf=nd-iAU$PF+C zFlbj1U8&Y*WnU%dBp zzWX*0a>dz>s|$86&Yhzf-MVx^&w_z=Hb*l`4asf;U+P($CWfhTxUWS5jc6HMi1w~w zNB}HqUp_-4LSwQw!5W07y zBP7pb)5^4iv>ID>Ee4sTTv6(03B%VxL~K@?FIQvE$vHCyN5h$#{#ooPhpqWMSQa-2 zsx-$e1@<6Jb$e=&9&AD8S!mBKK0<5is2d;Q^k7O3J7-R4HqxIh01xPxt`(`4 zA?6CtB7Ey;CE7=NB-x}=SAMK-&&##DCzsFkX6~Ml=1c(d6h?}95j0|S^4o=HZ%hG)hh)PrB8xT{uZn8zQq4DrW($By#H)`_|xgt8o#k1(wVY|5hR#of#} ze7|~E(ncjw%Ph_uKg$u`r)H-H$&J2Q4RDb>bNTINSB7Z@<}5yM$DPT9{f0r!9YIKT zEOs&3iA8|+c8|$p)NQ&^u}goOvE}435If~kZSok)=P}F%w`)B-4){2mym-uG^tXm} zO^kaCM#)2c(rWb>nlaK?p?*FTtBRz*<|+K0D$QsY`FF-8d0LNljMmbjQ6d#q+O8Pn z4~cgS61d4ov1=T@--U-IW=g~6*;~}0MX{rW#o{b zm09lDT3GMv-q(-WZLdR|@BX`b@NO#h%()Kbo7$glckA{gbl%y`+N(Zw+|=v%{bUIK`xCyE4MsUoF{!}IjJZ+lGK z45d-HJ(?Yh|KW&sdF>UT`4(juAL=#)5GW&YE$_C!ahv7y9nwXZF5koJ%NBhv58s=5 zZ*gKs?=cq2@NDQ;=NI60M}I^3RfiYOHHX$m7=LtmnUFl#d%L>j!QP`a4|%XRbA{~# ze!tSUoI~hU=Lh=tEyB3{Q#VbX$Ll{VPs1!)SfUuam_)^PyW5+^+9e9Kr>>73W&1p} z67}VMqf%g?9=K{iWRXqJV8SG2}&2!|2X<6L?xFBU)-8XHR|K+60)Cd6z#aFwvGY z%GVc*C^%B|$8iBCWNdsN-gl&7o7+uUU`5N(HOi25LI(WVovr3ubdNoRl;n2l94or7 z%ct%tjqf51ThJ6q>CdyUU7an=(5{}bwJ3>6+Z0Hjqm_4C}7d1eM}>En^=hiZsv*%tIR7^R6Ljz$sbItIXC8%V*R*eAxdEk$@0K zZ0(?%BX(|g9vlHZ=vhJ>LF_~OVH_D#qU-ztJhK=!qg(wE80bjdbEP6YgR^tn%P$q+ zfN5b!DndSXhz`|dARKXx*?-7q59vQ-1MEz_%Wcbaxbt<};kW$UzPDtPx@>@sKxg#S zNnqM-2hwKj{w^_K<=cVT!VLR{G?+O#tdO+ic?|mdc}UCTF*J%xlZ!O@$KIOZQbF%B zNd?X?@5*rm=ijbpu~TraXHi+u(*o+rv3s1kD?5oc&t1#ook9p6NjWk-Lr=pip9r=8uG5TS1Uzc zI18SSyjU!pDlbFkGbxgRIFNDZY*s~vj3C5s^D`;@=Gf-J?;A^=47+L6Kf4?WXGApH z-yO-!W=$LMBqNDQ1HlDw&V6SR%5;x{zU4BcfjJgevyJoOxBGUpiQj$sjVz9@-{FYN z_HMOX+*$0Xx_4&=?B0Pa_z?e8_ppF(9-ecTF+FT}K0GD_^hIm#t`v-yC5&ZBEDmwK zNKDFzW4n~i#*4UbR9GoiWjrYkOTf^#wfKG{=lArWxAffY97l8ro~Xw`CSf(4+y>Sh zpJ^RRZ3Rb1l5>{6Zk^B@?YP0PT#NQ^_PZ-G@O!tuX#1=rxA)=lLds3@!Z}brM_04F zz-AEtZjWMl*LHcCl}Bk`y9=$_?7}0x%4@J?U!7B z>6~(xkV{GdElL;1(`0Pcxl714W0n*fNQrEhvRTYDfvIW!O37UUE9(7hWMD{k)VC^m zbDyKC{k84h8om+ z^SMLhvTpm(zt4?v`zL*8fqytY7?yzwOB8ninM8%(fdWg(y6qAL+S7jZe>+4>Zn$3| zreS?E_Q0Bvm2uQ$h`yLy&-29?4Rv??-lunt=gl+NEK>S~nKIjq1eZd>1ImzVj*|NXM%7A?l3{nVa)Yn)4GLYnA2%Pi6{ zRnB82(>XQftH&@Y@|@c9aCv6rInjBx@|+g6&(}VuO5IA9XU?1_d7hm-A?e;tkN5I=OP?nfWKK>G{7LnwrP&_KZVd4fB=Y1?R#OFR)X3TwdVq?2N75 zESQ@sfe%&4wqL!S7qiH*15-v#;T$_o?s2`qR`gA}Ig0vjZeMR=C!Om47x*x`7y>O- zO978w*5D1x$@sdND-WdZBoDi$Jiz{j>_aF^j=Ho?`&#!5>>sY70xWq{spAK1#Y z$4b;T^xwBQs~wThZ^nFayh(M`M&tr(jc@dvup4c0Y2C7clFMn?Vmp~g)0o|+HS8Ll zZ{>2Onvf=`uJfd?zD!aLn;MShC~NsrjrfPHEtbPCF42P6ehIw0hNbONjrO!7t7j)U zu|AHEK4wkHM9d$(+Mk0pIxV((szbH-+wU3Sf< z6{DMY??ZF}?_>0>Cafdj)~zPxq}^)HVg`)g6sLZLXTV2~!ugOChu$e-k-2dOmWvdk zkL$~OjMw_2l^q7bw}rshw}mJ*sjxW)_^L6`^6)>*=jF9mfW}eJhSPw+S*AfSm>Me$ zu~|Of;nxV$d|+JfX$_W#@4&;Ay7rl^#eFXI+!!TB!Ss_Lb-N7w7(Xr-%+Z8~; zY!lFil593%m<`o;kZXMTG{Hhwk&a!^@4)BS1;)gf%b|u^f_m+XinQc$EWKg7et}-p&vyMn z&A5JH6oih*ihYLlE)-!7(Ym_l1umqCX*DDQ7(xeT<9UaS!1uD~jq!@{8}^E{t=m(^ z^zHnftvxkstGa~!M0JX%=T_=GwSLC#8FU`k2XtXROim{MGWnN{3+FFvUs!Uy<8c21 zsib{0djnf)R)`iJb?J-R?aeIw3*rN_@A%ey7u7uc%Mh)uTa56$Zu~cigO27)7)i!F zOzJOv=Xe;@W&V@0WtKj~S$jIRADCUwptIlmP=3~BX8iuwmva-Pb3JlJ^b3e9XC|Y+ z4X*LFzN;)e+fd8U{_GHm5Amzsm`P}KZgITIWStt#r@99aePH&0+1(M2rH00Z;RBXF z1qL`1h&_skpzA$^IAS>HQ_O^P76ne>4YQa_S*`iaW1tP@QD}8ye#U-Xz1`1@|4u33 zNq-og#h?bgpv^PJ^8@(B4)b%gcjNX?`#%f(!+s27GHa!CTZ=rHn*hZrC7OG%*)bwu z$P3zr-wy}MfnKQD9n08ieY=d!CYEtm!$KY}9Lu;XT%;j+*+s9q=Kv*VDP_VO zh9ee1G~#ABbFDV5O1p-wB&$uIG(7(}+3cml3bn@pc{y{-uP?tuO*!*?o$!4$){YpF zn~#pIk!Vzp7;*Xe4V=sxq{n^MW@Sfx%Mp=5Um3Z&+_ss6yFy}XQp?Y6U}~HTaT_(5 z3!BAU4E@`z3%KZc0mEvTJfVNCIL-q9usn^udlOceQALVGk$TH7QFxm*Wj~yq2+tdd zalW;!$7-{lHOBaTjM&ZkiXvu`>`8 zLc0X}M=#e-XY@+nw|eX!u;!@aw#jy|5C9I~Aw^NgF)y>6Y_ zDRz`mc$XawNj|)ozrq~ejg8ZR+~>6Xmd-L?lciHG^y7EBXEQ6?u2-|MbdzVx&1L%f zooh!q*KX(cWJjBMA;h7Kc)BA9%gVLWc{X}=wCEwyi!CcMr+q<`Or=Itvzs*3oQpWDFH@>ZHD>i$jMA=Ik-vT#;JrgsiE^KN6mbJ*u4&c1TqW4uHuGXQm7rp^$Ls`7>Tc_clLt1@F5fT6g%nXR_f z9YDAF8Dv*?p^-|uI@1Yq9Wp!fJs&I_y^MM7*bXlHCHZ!KkN832O!sw8Z z?HXlBI&|483%y)L))YHCPH;tTyg!vkp%L~R`tBDu=Ep;DmcYI}m^-q=7I?f7#C&o}^pPI%gk&sd*T0=` zXqU0sc;%J2H*&Sj5pr!j^}3zk^Yyo!^K`|eb(@i5&r^H$^(yaoCGC7!JDqd%YRV{a z-N8J9@mwQx`lKnNgf|j5=ODgRBc7p7q(mf~v$RX~EFzLA!vH=Zg8`nA52gtyqVtdyHth274|OE;&2siY`O^w*59P zzs*wF918rVY_#juY@!_7DH4wI=M&}3dhKOM|31I-{1xIl)%tdR&(~kk2EpdTF71lz z+&EE0EnmsJAdX#@DA%W@pA8!>^UQ%vbk0Bj%2?j@CHBS**O%Drb0yRH#$sC-Rjwvp zAPV4oYJ7XsQ1}P&nA|i_RtKUyXD66D?cZa9_7_Fj+QK*<4f<^x81pPrsrtat9j0usQH{R z>938>W`%bMtl_*!%U4Xi=yQ@HPcLvO5^~yNu0O=lgLWMZZ&f_UVj$Dd1ppUrH>VWgOK`=UL2e zfGMHFTEcJ6|NV>556Zo1LMlJ%o;<8;^W3Lko}-=LlU_C7;g+jcjQQK?Jn5BMsxf@n zxO#>6N;2~A&I=q-#Qm_j%g=9M%9+M|>}Y7m`MBIb^gxYrxe?xNdBhCn!Kr5qrZ7`Lw1_L%xWyj%iiweA*FJT-k2pa9WDI@4wd~Y{}5K**a$a z$bZIb@YVhN%8`}j$eDdN_fdxO={P%8j}B*hstmo83PZ+{o~^feM;koOP4YZGM#C9l zy!Ujz`!)w&ln`89(2SnWrl2dx?V&DbF73JiPed-X>jL_uF8c3Y3~K{mGvn)0W$d{; zMz1I5j$OcMIbC()cZ~1Y1$NW~bO295X|~4*@SQF788WDvIcK?MA(}lZ zG<~L=fn>3baxC0NC9v(;A;M+NjU6T5Fq=E7?3w5I!eg+fkRJRR5Jrqx1;2@;xSVrT!6P7i7ULt{Yy`V?~voK?Z^0U#=aoRJf#Mf$sZH5~P+Spj>Z ze2>A_r*1oiiTXM+?4fg4U0uGLCYsKvrh(t>Iyaj+)pT+c{DQoKe|7@B%Z~e&7N?Oy zGplec@5U0EBU;XrQ?`Z^w!op2G>}f(d{WHvE@r9vc|y>R)SI2nuSY83Jl5Fb3`+|A zoB3o=AZ#BP8P3B#fJPc~h9w13PpnIx^3N6-$06A zqVS~xevPvZcgKcB!R=Bp>qw1!9(&GWmS+5(mm|8YOKoU0<66`8WqhjCsz)z~fHZEI zqFIZ`>2Zz~{hFfL^B3^uHN>(_iwnC%ACTg$=ndNK(k!A`V9NPx*jr6;4efQzFQ@M# z^W&PlT!UrkW%{ud}v-;0&Ntvv3J-?{hJ7t2^g5B6N!FjQ>z0YWhoi!hOpZQ~#WNe}ziWeeF=N7cSm&-20xKo6f#{a&{kBTP40hM5+DeI(b29Pvi$d*k zF>71Q%+C1v^4ayg9J!aeOi_p3wW=u-&soc~uLP?BD|KH<-u_YhC9-zAG~fNB^cCDc z&|DYhiWPHW$j10*_(NJvs};-Nq(Tbixy{G9D5P!Dw2k(mD zT+e*gFpAYZVwfl6o^!}M?{Bcj=UczK=b*LcgEL!qpU`Z%egbT&ki1o7c6>YOqa(S?g_(e!=f!n9^=X35Ntl+La-Q* z^Oe*Qg!#?>QsQ6knQFI%vzVViGEE;s^OOF0%^aPnM=oJ00Cfyka*1*=+%AOU@bRJg z@`A{Owk$~0be?s%k8mIw{Z|X0#VW{>ZZt&yi@$3)!r{0fa9h#CI zvOdcrV|KzdMaIa*b{U(6O#%;0&r@v@S}~3pDrI5&GoF+|M@)}68`M3})E%{NIVYl0 zByGqTLUzke&zel(-KNwbcm8GPu-auReVqo@hIy;hv#n@j(lr+CSJVDdPyiY-)|vxy zXu8h^dgGoVRo#v4uGFVG!$luB$%^y6N0gYMH^@=fN!CN8&Cya9Z?%P2s`sEAj^UtB z4-q(^3C;yWHj(kW*uera7RN%Ly1PV~D~FuL+v!ucox%jJI&R#-Ewu@zVJM{x*ENiK z*REmHOin4hGbJ)$zNcNoW?{8~DKn1YEY6hk8#~kJN0OjCqxBSdVZNYUUdE3kfhQx3u(Y6* z{=#x*z|%_Ap82adrZaibA7E13a$%w^wJ#s4X^vVXtW)fIzYmdjZU*!AdBvd9nRC^x zA*&bZTIk!cymK?i)1*jBdSnUsW*hMhk&{`TQ2rRU$!r?+cx;QcnsS1mq8ptm9mCP7 z+RV0R)BEjIzT97L*0^6Yq>#}N{p@LbRuJbDDZkyZ1K#tOqI0u|HG!%5>5wi?@2|oP zhcmt*mN@U%R^0uV%9rpilUYQRU1zEAoDrHucSF{$>RBE1@5gbFRC*G~Ec}T5PG4@M z7tEVfV! zOu6dYGgej^LB;W=?wD0My3(h-k${T6rr7wXCDa>2#GD9_y7Kz|NfNwm&xbhf+Bjek z<2V)l*(%zljLLs&B7RB1=iAUx`O!GuXHDu^WDr}Cw_SDZ`iWjSZrz)qF*fx}cLC5| zQaVysSjXVR5z)SiahDBathsU~O!SEGzjZP+w@>edH$!=poeed^X%TN~?NpQ65w41FMm zjziF=ZY0iJG-w)cr%&B>3KN(q*0|@a>*MX*DG~fU*Y*2)G}H6pzS6gc@L%aOB|AUZ zZV#t;#iW}$0gX^?tjqZnuh4qKgD~pI^H@{7g4hCCW_tW~{hZ**A)AQpA~Wp2E}*ruJ%Q@k?8E1Y>u`IYo2%%4x>ibQ@m1tPol3`(fBJ$3UXY7t`fZ(Q+;WimAn6-uT1gE6t9dKujH&#Ku=*EyYrxvAD#T@ zN3r(bt)G)0o&4zJN5}M|Ir~82N7L5(r+I&K-k(cn?n-T+SIm>n{^^9&GZ+3Y zO^!C_EJO}8KQE2l!d!E+a|&3e1SN|vl?fjmv{!u2o_E*+-c%|rC zYR^8M@m4g(aw&S1w%#)fy#l623te@u|1!>e^orCQs#Uwno5ON7msV*dYc8`9<7;ke z&mqkq_#7V`*;KAC7-k6I>?F#_{l3O}xW_G;h}|w6|FT zENtwoCScM6`y3B*7H#OAEE-`iW-|}3My5Iz`gJlt4()d`(@yPo>GS%Topb`mwGTA33;rM}?+m@-ZdYb(bQ*VL78YO@|6!_Lxv#qoxHq3w)Yn9$n=+}Rv@fOUj* zWp8mC7S7H4Fk=40?6Se2E$y~k(0XX7<;U~92Wi?ar<3;xa~alh{p3AFH&s$6@3ABj zfqzY{%<~?!(Cu0|d5^eO*6BYl??F3mmc8kp!XsEM-h**QyPQtmBh2N=dvMM&d5?_? z=Pztu7{_~zpS_*t9*mQhbMC>M>1y#Fm@h$-v17#M$cM{!=0Dvzvc36ip5B9zR-CUZ zZ!QelT4cf5s*OZvuW55(jo958r1dj)&r=>Rv`a>Fe5x^19uJvC*xFgWBRSVb(Q-{T zsw)>&pK(n#O5-{BLS3WLQ~6W22sUtv_uJzATpPt4^<<+a8-<-|8vijj!}wxa57iYU zyrH$8cL=R;PBzMNR-ueG)|@#9vAG^fDR=d`9_P>PHVW-I>urCdw5`|K9tC76Z1$q7 z*N>LZ_q1HlaJrLgW8%(S!ffdt+O_1WDcbIpgLlvdOAVfve^-KXKu-YggJi0!ls`7j@ESF5oX)N0H^+v?H;c;r|- zLuxxzhguTkkNxqXlpJAni!$m=p0x_^!!fALp0fA+F%7p^l*-9_KzD}7m(Pn_t*7L* z^J3C^?3ZJtoU4(O*2B)y;-U?nino+|~Co7NBisRzFWp zal(OqBGz|*zXYy#V@?^NSF%}n*H}W95Sd1<*J5PNGmMB(&~JT3*NvKhkM5P#UkdGx zk5;4njuUmIopwMzgEN-4m@C!R`h3S|Y}Yzs4R8>@uV$sj*CQ(#X}3!`yAe~*6aiDC zMM&R6rvb6fOig0Eh~KYLIquSvdIZdq4v=f(2JjjW!o4dUGYG@R;PV`Ig0{ovIo+UOO)j7wu!DY5YN{an039N^?7Z5IK{U%b#KD z8!Z59`X$o{l$tG|&FVV~L~q?PG-L$SARB>|DE8^S`}zzE#95-r3rbCjTzR1swad$D z^v&>>J}1YvpSkpA)HKl>p0ms6`tl8*NXupN4R35xZ}P2vqC57SMT`PW%`O4wW)wZ2 z7-g6SG^3z!j4~`Q2d>v=a=siO7BGtznxmiwy`f1;c#dMf4ZG{iP-;4_Q6q8QTXAi-PKP@vk)GnPlvkS{**#0$2S>1bDRu*H1q}AVt##V97UU}X#jq8+R+WDi!1Jb7S z;rUUORqy8cQI%Dg56_LOyAIDG*Xp_BvfAW1^7g4buUj)nOUQ;21GU*rcscW-I=rw< zBUf!URbl3=5&E7LdtBM0$#LxcV74E(U5=-Bcu()}4xLU^JB!tq*zWo1oiE{2`_M?* zyA(a8PIu|4t!=hPz<^IL;>Q@_SmIt)RFrO^Va?R0s;q=o)y96)1SmH~0<0K%5wZ(XAbaNN?~%_#ZuE9(h#RH{?UTduRmq6g~+(K#H)p6f5$I9qPb4 zhViqfhe$i{7JD>+4d$)ZgU&x=IOtRCe#N{3{}6ejz4d?@R2&C=O1ZFBkj{83ecFBs z1^E=pxak-q(lk%`huvwmmfEgkvxwt?DPxVW?r|J(&0C3ae9B5Z$IUoC#bWsD@Sq@V zWSmA_uuPtihlYkg27PF;XwIy!&4n3dsx=5hPz%^x?|{y!{;GV^lB&k2?E;>J)f^q( z_D)Gpf!>T*ZRHfy1tscpOV|wdZ~A3Xfw%!F#kuJfzs@T4i6WNyeT7IxyKaW_PNSI+<+*wYBN<+IILHB8S+BFG~tWWwwmV~{L#z1O&ViHeE8kJbmZHv&euA4U_0F(o_V;AZX z!!e~5Y{n@XPw@T8&8G^7G)KRzuULoc*GI$_!y-ZW8sxbVu^}3S#kE*SH7$e<+UZlY z!}<~Wz`or4I1oK(1c?<6>|u0gZz*vgdVr$*A zp1`WO@?=r)^2pP2%MHdoJE=tP^ki{v_LceBdNN-wDbewf_;Q&VD}qwATy6c+zL*~y z62Aan^2fEUrh|1|AoTHc!FEmfa{<_R^~{K=Y@A^o!Q9i

(1=MZBNXg(l@XN_pb z(YNsj_0porx_qIXZ)M?=ZA^?V$+0fW8n%6eV*JLrDk~+$Ap^9;?fgDcT9Y>I@#;#N z`GKGG196T*syMbTdN(=ho+OFMV_(~c7_ZwNrT6a33T9OF3??g^$b_YK9E1K2&gq4H22*pG1(mx8s#Uh ziQUjreJyM%t#lk-dS0fk_vqbhc8qpIdN;1mqIY_i*-(aDjQ7qOrZGoUkx{$GtS_SX z)sTAt-^R&3xU+nXUD`7ZZhf^avHJSdt*_D+tFKQ{-*O+C?T)q3r>3>m4ietX9yOo3 z?Gz^9&|bnP0VAEyL8juFIn<@bw)-z=Hnp$agJB)c`eaPSw&4gCcvuakCr0GX4CoEg zqmuP=(h6ObG&xs&4#|R!5BvcIV1Ja?I>xXZ@GXAf{?txjZ4~?jFOVAp)lG_0v_(Ay zGJ42CA)0bmcvJKT+(WJjGZ{ql*x7G5q-Yc}irDLeo^YZAzoWb|bPO{xaJ8vpu^5q- zy^@mw8eK4Q{wmG{-h@mw9JtzUkQPdeUbmf~CW z+<1wzf_9Ei@e(oz^(+^%Eb5cYdxn3P4YJKSOFNy@vs{=@Sqzqzp_Z+WKNXw*0yBepx}4GR>O} z&kBO-zyqFCchDZ={(VXB`=86BZwD~*TZTQa%S$X zL6xx>7W!28B%lxE$*_auVh0P&uE%=NrzVYtJ)}CEbH(`esoPFr)~%B5g6OtN_Ey)i ztWuxcyXkUFyH}!Bn#FoSmmPxK(qH$B7GU{Si{+WtBg`_WW~|)x2*?!m*tI*BCvvk# zw)1T)yVEBcT8_wK{p9N>U%%k`Y{s5_e7#CjIR9n-NaG9toEy9cXDoRUv8ySu-iOA- zuyt-EgD8={E`E-V87i|mp>uS=KP|H{&v|a&C`ltuiR9K#$uGF|Rg*$v!;D^^qQ24sW%JA( z*v@0~r|_J#3~mgc`fH5iyj?K7&O1xXu3W5JU+}A47yDaZ@O@T&lYc{ONPo+Yx2(`Y zSu`@9bsu(8r|!MO79OXYjQ6pObGp^_Vft2nY?za!kNFJCExVR`SGM%9=#*!(^q>Q0 zNp(w4+tePx&tm6?=GSQ%!!uuBcg9?&pY6^Moc=T0sPVw?edl%i5`OE>5E}XOL0!*L zKBY($J<>cR%A%ZbR56deM6mXplMMBdVSW!^J3x%;#zVl_>;=AIPgvZFa9+0jJO`$x zWvNzV%(#L+rXJyq31NPgWY{QtTLNy;rgz&Cl_t=29&%+nAk%HhFnZN>aQ1SweAXl< zCb9F~^Wi%ESB&d8Da5FSUL9}ypuIF3&w7yfW1W=(NHn;MQhzRrzGzQvR)#xb<3@@( z@6E&5IFfdbug-Owkd-jYLhYhPYn~MEW1*bk-exm=eFH`PnIB52)$YvCR;1dgkM^`< zW1kyD-)1$bS4}Dzrd>3t`%mjn=eG~l#6)peW`-pDPv>w?#p4G z6|nO@?Q%F-f$a-RMHbnO9DM2{!bW6)7{k17EYokl=G0F8Dbs)cLWur#i?b`Q;bK25 zy^BS-^x%1x+2TU8K(HG0Q`SE{PhS61rhnVQMPe^MV z7jX*bW`Q;1n>fA3;(R!dIxH9LYdvx_9JR}z@GcI#g)Jq%n+1P>sm%*%$J{tIwB|mH zUiCN_@iJ*;{Kx)MD^;Btd%a}ni9L7@mr{9eezV_pZP!XjJ}EJF2G^`o%;NUVQvz#d z7mTYYHEGMUg#Jn!dh50vLq;$reS9kc`6D&VN+8lDTsPxy`RI0eL3?K9`^yWo(maUa z8MfiX*Enq@%4Hi1e0AOki=r4?$@BM`3n z`#h*&f7gWA93`;oH@`z{RG_+z_*XVrv1YIX(%|5|0u+O@EVrjd58fPuSwNJp4JPg|> zl!kcamNLd@N@ib80L&1_QedJjsoBN1dJKY=zLh~K$3<=Mb+GS9(`<|n4_HwjyGH3t zCw9AVOs;ggJJj%8-=J*S)^_O}E5^py0J}cdNAD)7F`MC23LZi2rP3)h%k_OHp!rfi zZtUJ~pG0#!mML%Ut@8P%lg-7Y~h6w|OgU@X-0xK;0#hdBM3 z)&cLSAV!qGF;4--Y(a|EOSeD1R3KuZEitJ;2HZTDSp#=QrFt5EVMR#oG!^`1|t~=^j>T8U-xp3`?RKTb~ z8RoBnWqAFq|Eeco03Kneywpd*XG;0DXKIgir>M$Us5UsFPu=>Ex$x*vU!S`5L-bZm zQD2{;zLi0O;t=$ySruys9>m+}Q@5SM#K;wENCBeKRQqjfQRCTf(>h;MK`+-%(0hb6 z*mO0fy(@3t+t&*8wL0K8EwlN!F{2PN??sz-EfiIS^80vaWYdS5BtSo~6O^7` zEk%0YkfiptgE2=!Phy<$M?xK-2Wm!d>0`6LWBTHctv@t!V0p$yo3=dA{3y<7O9^c9 z4QCw4?_8;5Upb?LUQ+XO;HgjaHG2GWatevsY;mKOQxk1Iq2;7umq&tUCs*2|M>{d% zd!(@E={u9`XY+L2A$_tD;;C9b$_nj86Q;!n&DmZvUIhh1dNq5fA^n;?R8r2>vT>pM zGpC$9ipl|Xx=a4;1YW!JLzby)vzGr9Z=#X48?)}3nUtLOk%RNNG&X7H{5*G`j1@o7 zZo8VuxGZMpQe-Q}*MjG>wkI7@KT#vyV$nwa=%JmqkC6=3^*3zzO zZZoc<&8T%X%rZD9Ssva`K4W$H4E*A{`mlM($K*4X&u1V5&pCg6{%OB2UC&Thj-X36 zR>Jy7-G+ze75)k^tW{`l=a_5S3WJfE&6URXMHmVFyg?Z^s|Fb6J(;H&8;1S5nvG+8 zYT56y8I)l&Nim8sXdR^?wn8{m4`G|A*|;yyx+M69-R)hoyY#$IGja@T z>+--Q&rI&eha1ub+q2;MANN!>Faw7bA6m0^?=!7Y>8vHDX=8AL5;JiE`@u*J+Pr3t zXO^5uo6XHvC+P3mX48HwMz3d9$x3MVQ+xJh9y_LJ&&~Rvlvbu5``WwP+GQR+7*BvP z?3d*Q@SJ6Yl)5tll4dkuv}Glv3jJfd9jJRC^qrEw@6$KdK@CgdJ#^1k9sksPY#RQ) zyubtH&X-butw;MNh1ys1XSbg$jWSKDgDPxknz|hGrLkujq1h5R6Z#z;j=0UDg;uRV zEqV*1*4QHn&6kGFWPGlNW=lh<1+80O?2twd3McG*J%k;m-3dOnlwCN%n7#!Bg@rhQp}403$NX_OL= zrVpowYv(n7Rhf~+*wz?*!vnUT1L(`~2y_@tfYOs=2=}ld|0X*7` z_-HKqkZ1eRJ7quKdpfOrZGiPviwM~=eLy)OH}!$zZPy1#RhmA)S5mtDs1}&iZ7=Z( zuMirqW86=tSKWinvggpdKn$KrEyqnO*#F%lc!xZDbLDE>T}pN8sie^hFE3QudxNUj z(BjjpLDE@9Dx;=KIy6M}H#Rr-M{GJ^urX_*yc06!HN-N{Mks#PUrg%BZ;q?!LvzOD z+i%;4$`QqBNxAMbPTC%$CVL}XKeK`v6}j36CMjnyXTd>VGnBKGium~8Bgm0H<0EZs ze1NRhRU?j=*Bk~JJCm9*jY2kQCS=yk9bagN?$8{9??rR>SlMrQjORlwLTvY;z}2*f zb0+t63u^c>->qlO89-_b1$bfUH&1QSKc*yr`rYG7U!NI6GRT`rGH}8mE*U1Fv#=4f zmke0C+}xl=iCxlxzA4#b&qmYci*f(Yy+Ufs)8h`y(9}JZ&D?1vQenp}l&{I^ndpsE zW=iIJ+PUSveFi-1llupDz>Vvk?pyalHXiju@5!UgkdpnQDSvH7VVZAeq&n0e`%$;W zL$0LYoj{B?NU0%Fx2-uF6#p%Qw*M(Nb^(Xz4Q2rW5uWjz+!)*Pg}7t3dpV&R_m>kY zErxM$IVkMM^u}qGeewWQq1CW=Ea%Iry}#HUX2G11HGp)a#qIgq_EG-q{<+F?+eUw>sL$ z#)cY>434U@Hz|>Uy_*i$ss34}NM~};$yr1O)@L|>s*wa|S+k>KU8C`aKQvPr(tlXaEOVG5XSO?|UCwfH^{IIVl_Rrep(r$TK70tx>M{ikIM*;a9HgEB3%;E=9heyancv2~($4a5AIHmF_0^7m*_bItZxiP{3opXNooz?zoD zdLMVy1HDFy&#-?(_qnl+&h5i(^x5R4;5W>ZtZXlZJ)fK< znZ-dVb)#u9rk4-!c`p)WoqgcMQ390D)nd`c2P^Z<{Pni+H5WQ_J1!2yTv(1v&XT0`nKZN zE+?ze|5+x`ykCN$niG632`v!d4!fupL4e{Svs5kFxzr&nI-j^E0c%eT8w=bPFBc3piO9&|A9*8b4?}--MD-j&S4Ul-0@m)4$01B@9K94lz(2{Z}s z$l){19<#pEu8vXt8R{!tSq_Pc!BDz~`_pIoE)vaw>-;=a8~o6xZhgo^7&7YXQ@4JI z-Z~1@*Qcm&Wtw4+VWdwjmv8MLn{mwasoPFr0*+#hJO0rwx!M}u*Mi#A?QU(QuFOVT z)qBS^r*8yg8n3+aS3dgpY_yK!O{&qtkluOLrF#_P!0BhjsNHHmAjKx9C{xSGwJNO@ z(yQTi4AiBKnS~v5`^WdNzNYL5b#2UK!+5tI9v00eTuzQnAhNKS?DW&PdWEsSkD?M#cBsm|H_I4T{|`c-0ybVRBzy1v&xih;(e z-l`?YJ=KCUF|Yx^1DfI5kCd4jY!Kd;fHR!XE!eJOGHnp74|Ls|kWW^-y-1b=@nvcTx0KJSjLnp#G2M;hNjxo!(Q3%&zaoAs?6t`FP6 z(v+*^;JV5wX_>}%Mi}judlr0GY$tusw^?C*Cnt^XkYL8R^%>$3Re3w#=NbF<_1NLJ zqK|9Cu`8XF9m`MnTtz;Ep3S(5Qff_;t1CZ_?(3O3VxzW|Fn35F))j?~L1{+ND_4J3 z3Z=VdB%q-AEO50sA3+U2nu*Oulq21-%xbi47#l4@nSXL!fH|lZAQI)01f!23d zTlj5*oFP%mn`29d=IcE?WRBm&+E_}Qyc%UIoUfbBSs;t}UB4E~XWK6gscvJn+T{f2 za#y{5#O4{rNwgb@##z#9+pQG#QdH3vO z;=9J#U32-STrCgZA*q~)q-lFvzF-zyM-It!ZPN8Lx$zfg^3%X?Vc~Xiow0Gp z<|i#3zx9F(w{BV5vSa(gO{DO!g}vne2cCb?(uLbLZ`sj!das4|%hT9rxAMUw(UE-a zSKfEmKNlAMwm zu&e~K2R}b3Ti>m`b6gAimE-ts`G7qFMSNaYKG(mT|L^dPXYcv-yIuI8cR%Wc7wz|! zYj6Lz*F#;J#&p!^`_eg>g>*3k!TuD|G&NPTBJZ%ML)v;sa72f6=yWB5;dm zoxZSpS?}{@y?d6`3KkT!KXvo=3zl}Ab@ryE3pN&|4_Z2R<3;E1sC_@LZ2pb%UXc)- z!)JT>z@sq-vaPIeX;EE80AGKbB-*R|vUgdL!nLz(K;{%u$Vx0cwXF2?^6uUCFMId! z+rI>Nm$Cv03UMty7~zg>7cEsRIigXsQZQ8KaHBH!jQ$b`V_Hp+jcBIXycBJ%OG@0#7XENatT7W*jMN-IpbCL z|JEb+eb8%O{+<&a|Dh+GI9TYunj>@=TT|$2h7QuU_^^$SJAY}CIS@-eE5^{hzpuRBiRW+Kx^3~qjc4!J zx^4DCScF|uoJW3;kx?OhZy8r+3*lXV`M-|3$LS9~^iGev`=uXy+JQIC7Q*J-;%{?C=m{VHyqlJ}~zcDCeQ zb=CTtUU^J{(?|jKCJv>o-@X%?-J{&kikip*e#T{E0&)l~4?4|9? zFx8l%yr8dLQ<^vCBoU3{!))ThP34cfHoV`Tmw*3jqw%}T)FN}2MTVS}Sa@++=^Pw72~A@a;?6j^8R1*=-k{4eNH++1oZ>xMSh@Wn1>i zEbotEeSY+SU;FU$Uv!fXzo4wJvjkER@zt-|=YG_WCdT`xVtjk4c+%32GnRg5hbY2@ zOWRJ_a?aB4+7q4IV z)D>-b?u_Dj$5g6fUFM{vE%0wk58b-;-0k^@e)_qey8hg^9TR8&r#^XF6w&=s5k=BP z2wLS`kao$(^`4LX*W>qo$KPESW&Wo=d5`HWvvsQB#T-nZQFQZ5B7iLRk!%?=TBISi|P?a91#`OyA(JkV2PE; z<2Rmv_C@E5QWf(RF;$zzb?1|H=ehrR&8zl#VVeN#j0!-OGdOQgJ6OT#OPyKJBPy*+<){Sohcb=*6&8Qm=J zP)41FUFadfw|eDC*I#<=6Z;{W6&z3!N~%gglTX%1-~2Ww-uWFQ7bF#=jn z)|zuKrVpCg0H(5u0=JMmbfn3T;}8=eRIv78%CP@KU|7o4-WRZ zK!Wcq*WKhgNUpocwI~-X$ANMkAQ$ZPugZm32>W5k>BCCS?zQcwk{lY0*40gQKrEi;2f_3 z25u@X=+izGnXnYPv*bLLC4_J4a#JVjFlc)e@(XM#Jcv3KIfMgf7F})V1dIwwGoVlb z#$pJqGp$PqIOHUdaP9=FEtbee4 ze_>g^DBoXEeuqVVW?2Uo`n_d2EcWZ05JGpllz%+-CeE&CdJb(~yBOWCP%KUVIi$^AFve!ASDf!O@`QMn%@*Kf*o zKe_HN*Ku+^K&}VM^&q)ECf9;ohs*76^=#yayTCQv4f`9&3 zdH&~ezf!K_<@fhwSzsvOeV?2Ds5h$jXrhW>>*j*e9prk9e1EK58|8YOTxZL5j$BJ}eOIn*v~TnEW551; zXIy&Ui}!ivWv@N%z{0-uRGutxBUK--+bD$ zj{Nr7M;x&CfA>cEcS=Mmq>JEIkiEA&I9IMi7=C*{6b?r)X*fpYz} zT)!&U`BHX)TnEYbEpp!~*WKhh2K)rM5MsVvu1CuCD7n_jg>dL?a%Gd?sw-dqi~l+0 zrE7n3!E@g7;e+4vfZilHSTMtnwugm>&a>oSm`||zKa=%#aPnYXya{aDc|3}KO zob+#UeO|8Y;l1gkTO4q^pMCt4_kQAxN8I#(4t-AV;RW^JmjtC}2%2Az`@hTe9l5?M z*G?&0FZT^{WuyH5Tix^)|9Q&KPkH~dfBN!c4|v80dZYYKm{|E#9DyUdt)PUg&7aBl zUz7VY<^CDD-Xz~&EB7DB^>(>FFW0l=dWT$Jkn3%7{g+%Xlk4Sjy-}{mN}DIhg_!uw za=lZo|B>r;a$PFd-^z7wd43lJdnMy}V&^%5!nd%6BxuE)vW{~-4( zqsg4eYu`1*PqFCzFZf`wNK-fCC**piTzg2_Wpe$Vd_P$3m&^SMx!xkzx8(2tmHYSQ{%*N{Pwual`=7}5 zkMjLXa{q~3KbGtDa{Z}XPm%I_$@NsZo+j7ja=k&yFO%zc<@ z8o57R?$40xKjr&R<@%Id{~^~-DO)4gFU$Aa%XJ62*2?uBx!xz&RdT&wt|h7Sc)9*k zzW*sR)f&Bdz zxo(i_gYx(Plj|C}ek6ZiEBC*X`*m{vd%0gP_kWQ4N96whR!xxZ4b=gRl5%l(h#dY*j$XSx4@+`l1rsPn7k`Xl-KPvrgr zx&Nu$Unuu4$^CwE|DxP~Q|@1p`~Btq1G)cDuK$p0ANl)^a@|R;edYQcDSLrjd&&0? z$o)BTeNe7Hk_)i#NsfnqOhZ++rxw;lO~8=m@~U+s-9h>cHW>24!` z{IZ~Qh}_>R_x~&RugUdwx&B$MZ^-pcx$Z2_{z|U>_mHyeVLaiJZ-2-+5B~Kn zAARXd-g@XAet1LgVSvc^RKpOA7H%*99bFWM66D#){`hm>f6^Hr+3U2+KmF{x?(>>c zYf;ucZ=!HM1i13qU2o!|CFnae_7K(X6?+IZJtX$&dz4j^)!~#)kAK_S*5CcXS01?kFWvCdXVrpWz=)3bowsTmucRBI<9(-e zn>F6s0TFy|E!RogwqCU59Ni6{Kirq!@VxhaaPRvc_xo?U>MNiB!Ye=T${`>`hr1}o zD9YZQw{2nXqDV^CaAER_4}8*@TemM>h?V-qdo6A~cX7w2rNyOl&RfbK`G=4B$9LZM z_Afv2j~?~Mk9_>s*4Od?fEFG3XMg^SUqna#gCDmrI(y_W`o#xc{6R~S9KB%k7FqgT zJp25uXFuV|o45BE_sce){PR73{E#!QIOFyA{JU$fKRcP@JKGfc2SSvnfFq`gavVfy zD)g_F!!8z&bPwv%;<<9#V`-yof!@A!-UT?`E9`$!*F{+A=yVDuQTGIWCYH|NBq>nnNXJPiyU(Ph}U28vaj6ijemX0`<`*de>~@PuYFYVh;J+QJ<8-C zNMsjf@`ds+I^q}K)MxTt$^jP(It7ob0he}ywj+Q1cij6e|9kzNpL^n)Htz9&r=PO( zTgl@;tWEzv`_mTvf3Yw%I{xDV9tBg-;&YVze~QKpbRLVF)iQ1>Hc~AvZP|L!d7Bn5 z*!YB{#q(unU||+SLh=do!Obtb_2GBA#Tn1L%a_)E@pji;)g(;wZy>l)F2=P#D}7LT zTfiL>`*OMTQ}w|3cE3_x-6j&4hMGK792uM4GOroZ&-fsJg%57H&Jy)xdUJ*zFg)?RI2YjI0AbxZ!dE!hCTTxn z&rS?9p@EEhps@H<&^U{7;h+X!RkiC)u%&>_p3;IIAj)CYjpr=M;X#SyWJ6r*o|XVD zz9gV18_1{NQ$j560AZhMPz+%{8DMfXT`SsEOmiJK2~Co*(4JRhA(C=1u+i) zQ|ZHJlgk2QiBOD90HryWjwXPT*#xXiY(iZ{G7%q_FZ`}gD(6xh99wjGS;cL3a#^Ogsu^}mQ1`wNXcke~uRF~?5kS(K)sTdylPI4I zG$Xx#L*CFCY@ z$PD8{65}30jvV@M(V*Uh&Gk_Qsm>w5YN8l{Mf83UfE8&%GYJERDntqQi2Ww*kUPc4 zZSqJhD*vxWbh6OSg#>5fHj6-Flb@9RB{ZS>QL)`75yrxeQBbjTf{)uQfpQW!)|y1d zLs|Ie0!Fi+cBy+zQXi_Dkw9w^>tPTbdC`2vAcJS_H^#)|Bv;W@IlUq6sZQA~KsmA~Kr*vF3OZ z5X)==#4?+_K7TA|k_iRF$8cRyO&ES=6AVAI2@q>abpm3UO@LTt6S(_KBBM#>@WIL+ zO%lgKWyan(d|d9ItVQMjm7zlDOecIr`Os|^;SG*}$kGuF)M;6AB>)N9Dq5HjKccXZW6W zSQ}9bA&BDl1I=1dBn96r4Vx%ND7dri@E-%PB28QC}s(V<(g&*J&Qk%yO{+$a0KSsv`O&pw6G9$LhinWB zHBXTLH>@j2ds&Hi#R9ir)9XW6Vq46@TIFCXs|y6&{?@IzuQc7T?(_}olxyde&~e-M zasjpixK&{73Sv=!c_Kcb(^^IT?nQzAS0MjD5ayL-X>ra61#ZiN%2j_5tfD`aj}MnE zQFOwdXo?TJVCABKivUG`sKNAp(cOl14=HN79j1wCc z8?NH?1F3>fg_B#b>3PJ-?Y{!Zc564BfIW}+6lA}w{3A|w7f8|FSG2iG`05tF4JYuV zT`@9GrR~dV~Q~|`Hms_ z4)tzQ3JGy*?Yotd<{48id!n<&O;T-bDIfQg0)F;=lRPMdZ#Srce30`jz__AS6fif5 z4vPY29Z|5h90J$ws!DFFM)*R-D>~zf4;mJY9q(JKh=H;|D^}qPi;E5sq_9ARMfQ7m zPm1uR;LZC>?L!+Um|z$6V1lJye+VYN%V`#Z5!Or@jz()G9Hj_KS1UoGn zT;@Qj2NSH;3?^9a!SniCw`O;NF9P~Y0z^L`6PJ5H|9fJ#STuA6vtFO;Jg9&4NkwJ1 zi_(?4wMuef?u1XlXh3!gl&eUyHJ|MJ7QxBmst0$ihG$6S;!^=}3pPDXy4wHHlQv$k zbm;LHZQrr=0(oiecG)ckn68egUqI6udEJ7ducDy~VgEzV+97X;Jo``{!Ij>%vyTBQ z`BaFx1)H8qy1S}x4Qp7SAq(0X0x!(9Du`}@lH#n>tFyvN1h?-JJV40@>yd?V`Iu8s zjGv2|fU_S;_A2U~P&CtqUcG|~JzwK=RkU#nyf%lPE+{-tdOh?J^5td)G@0e?hpFCS zcV1Z7d7S*G=d7u75!3o1*gf&D8m zK=}j%d-EF-5Z1e6LEUcHt+)V7R&67HV8`3_AV(X9t%}Pa$ZxrGosKQ?KaDE!gx7HUuJ`yCP;qI~SmJ4a-%H z23@nD=z4$8#kmMZx&3bbDOw z6Lp*-#;4#xYc9?sN>RY&4W&{cLR^bLQBlV&*z^a&fhs)H=e0gI?Bf9{s-rXc?E5at zl-ujUMVoJEmBJhxROJ;gRpe*iD?9+{ZBY&v;1;R@tWMzHa~9Twx=wfwNZX9Q-8a# zC_eE4r=4}eLNRKzetFUs>->_+i;J>%L+3+>kPu;A4 z@N-$}4&|U%xTQ5Txt;}J2OV_i!=-cB6;+AretfVqS;4Gk;W%Nlq6w_n)ut_VqSj;) zn6O~~Q%^bT^b;Odk~WE|3`#1hvLL0e23d)3(U&^_BkScjtV*)7{=qM0sXLg1E_F+Z zR?!$_W#dG$p1!IhS4BR&rt(HmLO#I+U?JrN%`TTJloO3txaY3Y1h+u#mfPqS(g8T< z*4lR)By-bi-29cxZWvHL|^Ze6rH#Qn=T`)TEjMq z{WP6o6uZ_{tp|ZD@=4$T19js7aH)s^+OohnKqOoau$FS5Fp_9Y4p+oyf%Qfd+}>C# ziJt^r@v~NNoil`@2H3(HU7|ufs;+AV=(<*bu32EBLSRKFuXmu=MTOO@A-k#?vY_6O zrOsgPh|c6wlY7>y217m;1=mUSS^);bg08NKd(}0WT6JA3K-VnL;r?7oYWTSYwxD)x zvlP(8 z7x{`B+!7Pa7F2imY6r2 z>|}v$P$HBK9f-9wxeQpzr`beH@qa}PLivB?v&<$KPC}FGq}u(Zp0i*Ecz4Es zXikJtU<+ns2}*UrtguT&wQB7aZ2El$4Q}fK$o-@ne9%tK3mReswVqgDJ-OKVJ?ZR? zj73)`V@Pg6(a6QJ7zY_!HE|27CPZglAXIeK3~;a4KX6Ak1D<>L*0f=SV;}P z)fXZf_Ja8Kz7Wx{H^iGtV-f^+eph4~RDGK~{WAfzVO_EDtEfzaP-MW+`f6=j{GdTm z;~J+x7jqM0Kmt=mSR?Kd390E892Ja$7xA9D_UMk zm@X#8INd>&*iz8yE#3Z#mM&^eOGujEl60$JR@iRXt8jR<AV{1Z-An69SK(Z-ZEl6@+bVUG3bYq{20n}=|$rT@0 zusXCl)T9Nu$18y1ovlqsgsN34q2UhA~Ggd z8k$Y;w|%NH5ej&OdWA-G(UTV=Y1Hf#|n0g_vw%PGhlG@le3v5T;cq12+(Dg(t&%U66B<=S+Kki=`g zACSZ5>t|9V-8SWhivy$%KSff}gIBDe6rCf6L05}%Y5wNp@(rIw{I{E2Zo#Hk6Dzl2 z(LZB6w9}rxBj4~@#DD0?E!gyj?8)u_E~v`ST_tC6e_q^qPj|W~wKlz7`q+CBj?C-- zz}@c7lK=;>L%HvA^!RK!xJ9{ddMhd6QpqDt23=r|iuR0k0j6BtOCYP*3~P=*7UfEB z4wR&(wj?VYYxR(luJdEaVkm*2yVfqi%CXz)Dx19s}*u=DmL`S%qsL zF&M=Fzz?tQwON#+!lZHzi~=t5xcYu`DMwGYMa-isg5n`^2!3Ju`!LuTW`|iDw;3kLghr?1HjBjM?o0J3(Fx5!M22o}E)jB@K@jazjqUMe z+5eVzw+X-NqpFEUmhX_KX9;(zql+Zy0aAU_djy+u^ByUN@`BoKK@sXWwnKm3RsqWY z@+2PS6o3%s6ur9O7eNdURuT3TD`74MUbQ|bkxvCmUZfEmd9^=}lt-;{wc72DhRj`@ z_ExL+E=lY5b*D>9RVqeEEd~^K2dMnHP~k_pDNrfi_kiWU-Q;qgv>dH-5f>x8ID1dIt7BL%;!!s7U4Ht@WBn2YXfnrvfSFbSpHyr%m@Ms{D6Kcd!z}aj`6bFBtpAp8WH%p&2Cj9thZ`Z1Jb{)OhDRPXc3vXv_yiT zkK2Ub8wkEnWP;@Q*RnaQ;;xz`s!=?v#&w1?Ba{Cv(2QN^qpF!QnGN6Bx8b{T8}2Oe z`Kv&~h>WnwyVIMHjvov(Nsx~Z^lSDP{hGZ$uNlqFUj~{*ROS;RBW(7b^k#0X^}c8` z!mLE=^8$@8aC>i{S%d*JI9COlL?nYvu1s%2$@uF)lL%t2<@iuuGm7rDfo730vB`D$ zO|DOGLdE}9ph>I6_)|gqL6Xco?N#yx?>#_my5zf{w`ReeuR8vNztwoN1?p9m>CI5E zAD)!G(v4IV-2$yxK)(WQ!Oz zs#d@mJ)q#Aq6%Y7lpLs{##o`Ks0}rc2z)^TousSRt0pURRJAjRY2EQ70{_w1$0+c0Uc3QKsQqr z(1}z9bP-hnjXw&UeN^6vu9fHbR1Im%s{&f;q9@Ja(GsI*Q?;kbtyr+YHML@K^c`z% z+lhZ5JwBE0DrBG)0r0?87GiY(iJV8f=2*`l;ecHlbTjX!7{753X^# zP58Y5MJGh~U1R+IaKqykIXE;V+9|2PSx8feAT?(#A?J ziu{#clor%?@kC%!SWI9^ilAm0n2>uYDtx>q&AAEmbhJeu)O|K zcG=@hFy)LZ$t63A{vx8wCU=+S_#`yp)Zx|IqSoY*QpPSF1;HsEHv3~oNdOIhGIx)> zRh7FxYsXX0UyA-{6Cmv&mwqZG0VGQO>slbeW}LNY>qY0Evv~a0Eju=ExhM__SO!3; zrqD3`eTj)nKmd_XX>2MSIVlV^iOjv&EAuUeZDPLs9qX8MU=s@Y}pmiHGz^CY<@bFFV5Tz?t8x~7gz_)~%&71dOAoK2 zfQp3ikn`* zVbE%$v^X|-^Mdk1CDy0`u&z+8-W7dD)zvK$y84=QgHO@biwV=i>Q0GWRajMBd06e6 z&=pm!z^Xc;@HN4c016I+q%3d_8n9?n)za;+Xo;@y0RX2Zl&ubvx{J~ZCcYOf$!^qQ z+cFk$<+*6+6}XHIsp`Q=p*7sv2TPJZs=T}Qq6n>laPg_kH=7(=)=g+a-*R#Q3LIo0 ztajJc-rL%2cj=%)4lj^rmiOz5ctJvZ1)`DI|D)3EQ}XyxQb!EcV~VAqAY2 zLTOQrbf^kAN)%v;vs|*}C{TR!vaS1?`@)F21+3)0=Dw)p7I>Hnz@kzSg9{kYZl)Lz zAjelQ3$$hd2CPx+O{#FEVwgPR=S}j35!EZpLiB?V?&D7Nc9vb!%D9jqQURG{RK-UL zO$g<+W!;P>ugP!nlYpW`#zMsYE5FHQ=}pMa{|PjSu#?&wY7)_2Y$_t8O9NEvfD~$y z0O?KnV+u8CfkaX~CIAV|D2I;y11V^2FOe$vfFiii3nyD33120=_>gUz&)d8uI@^NM z?je_cD$T``5NBJLI2blT{j#(>YiUV-oOs99MZ$~%L+b!AoipsjQ~6xe1@58?g`I|K$Rlk`G@2Kf*9&>!V64>dN)=K*IfVGGAqeFi>YmtyWdCRYy$BRG0b+^P z&P6P-386q9n*OK*F^na1_;1J`J`meeE;14K4#dy|Dv;3xh$W8270@P;Tjbg$G$-@| zv_LXpJhw<2kBc07bxF{IoZGBv68TQhREHKquo=vLb5set2LJ+q}6TwImj_Kd?kaL?gk&BQ5 zV`8(9^n>=}yk<0%-1J46z&%0^iqs7ONNlc;8X`qlmjxO|V6n-kK|uMi|3vhfWM^~j ztbraS1J*oIGS~!aj}fr{7WCNU4e3xw@NY{Kd|W8}u1^{xBK1JWB<7G zdk_}I_A6yAR>mDJ$UYU4ZX62+C!$D5FfmP{NAwDDEC~45Z|l1wh7!^$$fRn)^tIgaTK@+@;q-wZ%v_H1YItb*j8C4ka5m4nD?k5#k!qBexL z$>7$8uJAS?MyTitZx$>v8p7Lbm?*r7D3W78RAN!GihIYXJ{@S%Nd zNJOv+t%DSAR6wbaTm+j$PeAbM0JI2#B>FY!O^6(bzD6#WdI?0w{JJ?oN@#{fHheOn zp?;Hs3DD52DY`Aqc9vK{beklJ5T1I4)KC+_ND~qs5pE)KZm0@%M9(e-TZDJdpaYeH*jMhd<`nq}%1rb|us0L>JA55m+t}npzcULUKb9q2@#h_ZHRQsJ<=LnuK5%@<=|7 zQ4t;hH5<0TV>8HL)2SxNAeuF$BB9wg1JGJzkVv9g6Ix3%3e{x+Xdsb&Dq52KH^{Rl z67R9v11EqRZxuCMxqp@6Bb8tc-gCdQDgn^xP3O zEmNe4i&zs%1TnWs6H27XZymm{aPQM(m+BevMK)@kc6%B3x;012@O6Kw?ipo%=T|`` zkj5uN`Nu1RkZ_9O1*Gl`(heWg zY#gtw8oR^s2qEM{AM4h*UkUQHuY>N)Z>t5KlhtyuT=F$7t*tVvGRx|*aSx{#i0qGeX(-)R|@Vx%kt$BQ* zZ@QzHCJY0$H<)vW4odGVSGA4$|FicTfKe1(A4oG4MJa+H7eGNoxL#;-dnJVwAoPAD zm*gPHg-fUcQlyAT2Lb85SLsba1ymGJx=4|tAE1B*vGKn*yK^_Uw-+uUA>f~Z-0i)c zdGp%5nRzoiOLq$44T701kFR!t|6QWy5C(^rMFu6daxVw5lfB?{o1h1qpTXm39TVoL zV4a4x3Mt6KbiJ7r&K4bPNx~-5K}F0zX8Q%9gfUJQkUX7Q7R!J?CSC^@7*xrg{nIQy zQj%^DBB__n3JeHzjwM0s?HKH$SL-o#sDAeDeebg@pUM+7e)cR0}vb|=BK{WgMb1UKmRX~g~=mh7T|p^7~SgY$u>uD2MFLB zC5j4@CkqSkYKz5B2&3C*J>^hamnytx&8j3Ma+=q|f5(P^=H27Hakr2Mc&?VYfAiKMJZ^9XU^ooMOjdZLnNRr578j1p zV+Bl<#R9S=aojaQn>4}10+QdSPKCu!vauG=w;j6K&ch`ONS;hFvH1Cdw*+221zAAy zXj+g(7k~uB?PJ3%z{?DapJ1X}+K~d`h}@S2qVUUm8po47;P?zU@zFF3@ITiBW$_Yn zpNqp4ewYt9sax_`90hol#P*0l$3c##<0g^>$zv=mfV>3U4=0p{Ga|7ivF5;|LmALk zN3yU0U!hRhF+!m`I6TC#faIyva#=z9Rl?JOA#Wc#SU~bnzy#H5%%pCDf*nZnC@`K) zX(U-#K=Qjh3PGpjK3fHkg6^mA@WTR}XCV{2yt-qYk+`~(xLe*$1z zo9Eq`Y}fTP)Pl0f@-$N3j3F1KDjAdymZsVS$z`}t$%b=@iP>P7&Bw47 zE`uwdyexp9yQm-w(#zf<=a=%Y1(jm$W1$W_8;(3{#{vj4mLz(XDw`>XxN}$x=G6QX zjmQipvHq4SP|}N2>+zS17a+MkszA2@5FbKdHosp8h-i zCwY?BumAk<889V;`t+Z7StvCyYRA5c0^~_@-u}}A zVfs&68DWL4TcM*5y@$j>^7fzj%hLy7FNp~O{{1JtBkDgXn6k$9gn|1{S}N=QljaHv zx3~YyRxuKm{;&3GY&S&AfdvHHFL}ez)V8w-L(^yB(S|U<)#XLFz=nST{%Cno7@C4f zKAaIyKtUK9goYjylc$*?fJ%t(r!lJK(@(PiZ(x&EK9M!6ECM*nAQGl}KQOiV1~w@T zq$FD->b)b?J6j$Co7Z7cw?i>wIZt?TF;gYM!~%Q+o3ui4V3Wd0an^qP@O3D*=sB#p zpuL0C^Ub8LGAj2jj{7N2WK#SIN^DsvHG1N-^U&!)@-&-O@WaPaRx$wk4mF%a(Mh@Q zB#JFgUlaB+?lY6d~9dSbmkB4zEu)fzT3OczUJfbKlz$*$C9m&Qj%4;h=Bw!W_@Y)KC-%}wKA&==#h6Iv@ z1&}bhry!-&Lldo#0NB|!kNOutO%*}1uz=(dv`w+CpJZbx;4z`1i@~4Apjm)d^DKTw z^Gl&5CQoS=kUXE#fjBXFvayx$bRcXmB~Y4K&ZRcNTM0Tj3L$K<0IzFBq0r{Q2!)M4lhQ08+u>+h0l|cJ zNddt-L@4ByD>_6>q*Vr3&ZSlG()g4w;6=d#l4sGbg5{DB%htp!=hDha9=3xdnnX!c z=R zVGlnG^2Q_R0S#M`V`K*7FS zloZh!&H+44z_W=M12~vG*$VdE`i?fJaG22sJ8vSQWdYfmsId`ff{6t@x{x>RZwLu& zuax6{kaV#aW~AaHs9AtFjLBBW51r6di@~4AC|Q7a{>t{ee)zqEFdq_dphN-QK^Tjl zU}AfDFHI$&qz_FL;H8Ph4<^HIk@j(|Hvts|_|B;*PAJXHscFmg5)&dOh61FC3BVS% ze;@U;0B^(?1w`=&z=UII$`Q%J0({#Pt&nL`eiL36kga(>8kr9rEWm4ZIDW!}`s9U* zoKrCq23UYs6f8QDja9kV>U>DREEM3iIu^gDLMj^`(`_h-$zydaz;{D7#ZNG?TR^=u z(LU8fHU)TTV)2t~Y+#VbgmDueIk5n5MA45sRtN+&8?WF|V|*Qxhg}x%fPg+FiN~~r zN94uC0+JWd86i8AIZW3f{%*%7~ge3MFIJ-OyDCK3=>g+Z+DZn%?k%AW z#D6YAi$6YlOC%%^_}Tn|-67bD*!AHD?GB-hl-LV9axEAtgCzOh$#1a80TY|SBd3rMzP%yv+$?$Sw$Fm+$(hmIz9pKVY2jK??xD=4x z0WS5eJ_B4ToQE9XQkuL2Tn~ib2UDbEoJ{uMSIyIxTTVr5ha`-9$@jDHdkTT#hvzJ} z-9jFEi!FlFL<*NEGC{y5E;57yytVWYvi>en#FLxc^AP5HBsCVqu8C&GZ+cD2dF%2m zxR$@`$^5{Ad!WFJkgJRE`dUhIEr2KYrITDLVT4vovb*g`4tg>gB{hoz8Oe?Wnw=6z zvd^XXStNvZmJEFSU@r27%&_H!gJ-B>5G6U%g9VVqn-0Zx!aaUI#NPDFO{$w=J%Ekds)`J#1U=Yff4#_s@iv7#3@YP1b+^2iWHuLpEt#j#}y zFSVw$)`kMf{U8TNKokf2qgfPE@35~ zS}7rQ62(pTMoN+jbC3EK-@&biRBF2fo#!|WmH{X|&Fmeypin)fsWp<)c>V}6jVy^F ze6h6>0Lv9$7j^x}5y8p=NEvh~s7S2bFNdE=lJy_fX#K2M8Yx>u8Yw;Q$3rO#kVeYp zkVeYN&`+p-NC|*d2H}>qUxI@L_~G!&Ax&618UQ2@w=6&!DVswYX)2G?iCKMLRdcS%IH|SB#CFm_`&&fgtI-_}xW+(#} z^fk=#7<;Ni)>Fv(weTHIvyyMplZV2kQl-(Tbt6`3F2{rmlj|+HbV1PStI&{E0Fb5<_ zT#roFD!`pWvbF*5v<`TOj=BPBi8g<+mMRD+WvDKXmdy4{N0Q6k-%nGNQ@)f(Q&x-F zs@JO38jHoGQ(6p0jYg$2oAi3lY}4v2I$0$sK#>+`>w(&$epRfka#UN-vf66ya;9Zw z_~|NzW+vYrU76Ghl~$t%6{#(Hn?i5a>9jVh!D`}kDo&{|$c&J`xhtiAk}FM~PEbSR zvS-Q@9Er{}2We>O4!1Mak?C+3=<j^*_@AceF4}nlppqtHM?WU$s)jZ*w&N#Y}h6ljz z!bM#H3!Tg0;0V(KnvwtM{d7*O((JSd|K|}`d_X~!8Qw(W7+%oLDCKZN-?7($V8E5pf~7m`W=X5f|}km!-e(Q(XpLk zcHF5E^X<-kC+glo1bCn3p$OS;r2oD8j$8K=Pn+jdyfLU&;^CL1V021H$`XX3aA{E~ z^=8hj&?q%3twm`wnlu`vg){0cYMWXEZq9$A_Zk%QOe%1u7Gkz1IMVDPA(GR!Lfb@Q zBLuJ?fyBnU^GQbK(Yz=-pa-{jCwU%u?U(x9* zzjzGACWg^D79qeRHl>(F-$C;$ z^gJviA`OB$4tGdM_NNeqb_o0hlxx5ngc<)2kGH^EM!^2^=Y6-hBiGrM{MD#xrzMO3 zKsZ(^RE$48i4|7J5sK@f(*1&q#>N}JjMF+`hQ zW3@og%4W23W-Dh?8DKO>7Q>lY0NSwkXNZLB2nh*(bT8>DSUNq^7$0C3KZr>2KDA>M zMMCJknxoF&i2Shhvh7dbokhk{2oh>K5lq}pXK0w69u#hKaMnPzi49cc+E{c#vzbGcLPnX+1N`%SoI zab~2a*vXwi@;95iU70QslrV~OHea}~cAaBA<5XUvIx$+anzM3xi%MfK>dh9NMWci9 zkHx6s^cs_fQ)mfw?En{;+(Y{-94#yADF_YtO_NVEvH>*ubjK1~hB~7seR2NOA!Mu-{_DooM`v=!6m0{+wFI@9lZS6AgYd>=(~BL6xXqRSHrffTe-M%sT%DNhZshu z;5?uBiLMmHVX+!v%BO!hnJjj)bZA8j$*dYIZTi+ZkTEO_#s?q6`8Xadg+H5w6Bbbe9gF?Y66#3&y zr?>18GG)sBsO8I2t<_s}&&-Lw?Lwg*w6O5)zZzde7{t&AEl*5=ssl&3>1^Wv-SYgO!q{D`HX4m2 zJ8#=M(-K^LgH{}bwvARRXVIvYMvD%DPgax8s>9ij+G4aQG{GsZcRDQg@_NfCP@Lb= z#F7At^I6@EOL3(;{Po7pnV9*hO{3IV^+p{`Fs!gV533VaPOURRq|1!aE}N_gG`Qv| zcCr=^>+*@tloV`n4tYkpJsx(!I5PV>9BBlS=}PByC$~fE!#r-6E3rV2etPT{K#v&H zCJ7xV5qh*EBiV0-X@roA|MK`wh$*PGR@ld6(J0g^i%tc>8?)7@)?0KCGvidUmJ}=K z#-mDDqDM`o+1+keUtXz#N40yF3+2So%H!>6X|7CAxg4Tv362Daqh-1Z)a$3-D#551 zmV5*3!*EKg*QVARtttyB*QC@NGztxeJ1{sH;V9Hvja4VpK{>$cOzoX2PbOPDh-SMB z`_$yAy)%gNGF?P}o`*~nyWETZ|E-<^?w|?JY6r~_*#91I2h9<9&^hmR(6qd& zI&*N+{qRLY3XiX&{OlBMNN52x)KCYm|M*xlXJO~MQS1H}+wt14nFcA?Oe`cM&svsD zyrPbh@L3dOtE9#8n^++W5UzceOmIo}dh6LmQXRW(E3WCv79BX9!+cmc5CXi9^tX6v zb@_g#TQMK5KJ=a?g{1OP$FHpgTImh zrwd?dK#i~4E!0@>GE`Mx0aJyDNQ4i1gN0>vO>`(Am4yN-<2R?rzus#T_pVz}xpq(M zQ7jw*@YKqcZ6TT=QBx{*?5J6nb{*kZGycUEey{zypLEs{(7CLWq#~Jcwgj)mG50NvkyK^+uTPY2iT#&H}4P3X5Lv z6Tz7Sf@n*+ssxZ-U!sf0SHr09bYeTKelvjaJl1e^kgk-5n*+S|3E9v$cgrlhcUDdv zd1~uq)B`F5|JD>KWZHeJY138uBOQOZ+4*U_hY7X0FVuDIO8EUhJC%r;o!Yf+f)tDf zbx0vZNHna1O)mzMnbTNtw=XnX*vzFe!=S}tG{ROG8`<|FgnGtT>_=Kq2Bz)c@s~b=zL!zAB}8>D;cr2bb%L>KDUkEC_KDghc)D z_!-Oy! z)Pfg)twSM@8{!4RG&YR=MK{3Fa6E zUMPH;72DrU)vEv1C}EvGwM^pPTh%^Av58?cNJA%!$Q0591%zv{$UJlQ2S#8Xk+@p)NNJ?&emQc2`gDz7jueSw z#r312TFB7-2?_uml#IFBEI5Mz!M4ZP#&z`sI+Q}$zWFM^spkX)EUgM z1x0P*t;`cFc>@JTe|bcft*FN%64%$e2LFC#$<44C^V442*LLzNthl}{GCD;wrdY(( z&nAs+_la^Lic1Wmp$L(vRt9oxIOMGkSXDxTS8CvmO30_29oe zpZ|e%f0fbz8#S!32idICtF=0l!fZCF4A|wF)oOTdp8j6r9yZx57Fe3n7p(jHD=|-wJ)zUMEY<6su!+?hVBH@&Lj&ymhdGTJ zPCHTSVHwMyvf$=$joPHrsSDQq`IbsQAF7L_Q%bQ4eb*nex9$&tcZ)?016+d{B6>DG zZaOw8L8&mvEWM$Ff4_3 zr!i>ZVGJ8wnG6O!Y@AbCRYo$xDOmS^IMva~wpew(?Jj%k{zkO|PaT5gU;}LVhVvI- zSgO>)^ircX7-5Q8ukTmAfydr; zHoZZsD_Hj@>J8%Lj4apvZ^7Xhf!F<^io9F*-(dTz%Bri!!*;D6uXfqpO zbGJfUu{Kugy?@? zJS+vHK^Kw6Ot2&mPfKVldaXeVPw~SVi2-(=L2J{)j9XE#E-%ZSjW<-+)L8~vXGhhQ z+j3D>C;XktA1|skf6k&`Kazsc*o&_^O>lrA>>AX-$X*9QXC+L^OxOaAS_`L#U87|6 z%Nvm?SZ9~mWJNVazS%z7=SF}Zl1(?zdOGUWe5l&##pT*@!#lh*@SA(*2TH+cAcoZG zakkJxjY^!wfqreU0}l3v!j!t zvwY;1VfT=A+H?Y~v!m$F{8f5gmH4*YuH@}QRz_VrDg~oK5yZ(4TteXjp7XQXRB%R& zO%EFjZ3>9~!#*XG1@_$P%vyNj4-e*e64u$N7~ceXvl3&V^>-9mjUP`p+&S7}-F~gc z$KM^icT5UK!xNC55u@G;b5tc9z^T>iEH;x7qC#eq(f~b-Qmck%)`-@9 z!NA?h_~+}*tk9ZUVxLvtex>=plw-^jXk8vf)^PsV<`*ihix@tA_t#^`-Rdd@qoD%C z$yg)o0*45jRbx;aRq)K4mQ%w6sPJ$2&|Kb$KdnJSRLWX$M-bN69t~IXQRF zs;#CO_muzsSnaG*3P$JfC~U8^aeIwk0gYV6!NU|9t5T_lqm7KP7zk&ODnZ)ML2kOJ z?p;%V0@v#a-va9>^M_lPe_~I^H(24=ZoNjYfkOo0fqXL@jiZky{YjqK8C^wS}k7kc2yPJle|M>G)cO(W+I!f`S3Id0OC5LyJbs znPAJW9>K7gtl)Hf|E1f9SRh&~^qOK_mK0RU9wsSXon;TsVR}MXg4Mv&XR!YdHUPqQ zHHfv@w6GV(Y*g5^dZVh~bbOR;u4-|Lpe?Z$rCX$MR;5^-0iMy;>l9j}MGJ=x>r9+p zZ#5_k3KeHEa-dKfoIq1>IzDYG*ajY=DW(TdqHq=w|B^`WL70BMUx3r`wQzQx&ZdUN zS`I=vYBOxog?(u-LgBD4goi=vK)u1ApIKCJ7=DkK|G#~;4?UVs-1sE*mW|W#ArPa5 zjZAPrzSRN`Jn3|BBAXr#x_}4Wa4(ae-m*Td@Bgjd0zTWD<>~nA{=9!b;2NLepZoXo zZjDd2;nt23Q*K!2*I)ZhsT+5dZ2XX%>J)s!9(*8&4-(t6pAVhgG^$d`qK(c^NPG79`zSUsjLr!NUXR$|7)hH( z53_1G)7}DmWsMMGHy9wsZc)IaMtY;Ku|83!+7m_v;XO!z=SRP>B_ra>igV9@KWX&D znln&~lLs=}y+Bjt=%J-7e}Rrnma4DYZ)+w%_EAAIC; z*6*guqa&B8xUebzdT-{~3zqjkx>$J3>`sj?EJOD3KFx!_X=0ml-Nk8Rhnd{FJB2(y z^G@6Di&3Ov7#%8;@&sWhTtdeK>ts4O#Trhdg4t zDlQahg^poyZJX9f9&Q-FV%@e0U6FmfPxIh!noy*6;YSY&6u$kRYI|a%=Q_1s2|K+Z z&S!$yxt`--(58Tw7+GN0VS}S>3!>*9ozwAuK1I)!u(<~w8n-P+;UZmbfhfSVs1pw z$%w|JhB=AKrn1?6oeF;O-xygot!Ypb~F&m$zyzNN?O-LmvN&s`wGm#a_x z8Luy)4_48R2rkz01-M5M+u9g>QXQ|b%E?cASx6t3=nR!LMTRK<7_r~wF10o zNQJRE1q9@5MwR}Fi>g!OJ`c?GeYrx#8Zjvgz8g4t)SrWo|Ad@hfWOTZlZ>sx249`> zP0LM->ZSOcV~Ba!L?fOkQgOsx3P$G^1P9SAiWwdfP^lo80+RvQR-=R?*VPbFHo{H~ z6}%uwtMN7NCn^g6lprm%-@fY6&+Tp+Z(LFA*VUut_Y`>RBK(c|ykUi{QAer_9v(M) z!1*&{5Pk{%D$IW4QY&j>=fTf(m^a_NbOFLqX80#gtRlpbdsKuNM&}0v4?!3Tm!Jn& zEQZLV5?(3F!RnC-mO}LK5=~@Q73c$0lji zdYuMhgH|{gP{*0T!eKlPN4LUTcl16YebS=&DAMdk^WPz&k;!%nzK9;${|xm_tQhgS zjBulg@LhyvI0NVHl@@@0`>*N?x#)nmo{(|3P`w9Ba~OOF+}bh^LRWQ#l9XWD)D{Ss zC^??*#Bb(1%Dyl(a+5V-;nyjr)=&~K1Fg0mT&vFwe`ZAaE)nAn7Oph#`DHz&V11ZM z$iNuR(U*l-`#Iuevfjcy7C+YENda$oa`;~OjJ%`aUe&)$hOgRJik^4p%7reCxOJEv zD`kj6kWWG`G#!`y)*|_|Y3I>CnP(bpj*x<#6vT>!MVuANTh7olrtNtv>Z;|HgAHz( zm#=TXeDQX zD4_HF=;hpYo`q_EJmlx73BwO{Y&W{vZo7h#faIX>!z9&!rC@%}la$U|=YpaWyFaWJ zwN5pUzr_jZe`8|#zgpRb9MSi^vbJ&q%W^50pW8%4dF(J1P{sY@hoYy#qo;4pt2?{f z_WqfqTC5r`0wknAZCce<(J@Wz^UHoJNMkm$Domys*Y9ZYz>otyV`o{kAJl|jnxJ+ zKpF)^`VFmKDcLFf$4jescAwYt?mNFr!D@+JdO)6hY=dQ%ln_3s{gi^=rua;kyOk^2 z)yMbYi=etDiWF&XzhcroOm49pW9v&)nLjLb{`J0+}T3 zxKQR5%f7$!-EeOGVSC*0HM2IXm4f+oT&RZ_;1J(J69GITuQ&(6SCr-6j6*J~4ev1G z@!=~T5@oMKEg>>G2XP8D^HRq58}ZWT=OgqjN8XtVa4R1C;JhSToh^!$O{9ZDIb#Zk zi;o9)*|geP_N`fqYU~(1yh9|y1L*W?yq+ArWbrjwFXWB%~F*cN*R@@90Ojrl&djru3KF6Ue)zGaae2eD1K@ zAmfnyH{d*?t{golCfbh%oT)X3Gc^N-xfD6-%E!I3zf}6uF{^*QmDaldf?kvaB!`B% z@Ff;cmn)RAVBx#wQGJiiXy0brUMX1ix(lqquMs@j82~aNemjR0%+L8t(oWtSLfaqa zU}Z^42p?=77Vgu4>%blHTU9V~pax7GDbjB(+xhEJ)dxmSy>_Wwom%IINWr2cN6uoW zggjxbo)m~DPX^J24^P*C_~Gvj?Q$~ZRqLFiV+Va~sof9r2jYq1Li!V{|Gsp?_}-D@ zbW7fPeL~9_Qm|%{JQd6aKzy_<%bu;8g$o&y6BlwjVyB{9q-#T&R=;k4al_~&)S&baw}xlFAG_t#Axp8^ z2U#W3f2?v$rJbfrv6Y`2GA=5;$W$qq-#maI&s&~ippJUOJ6+s)__LVpo3a^6o?ZOmqzZLi1@Ta!_R!s`_#JPH8;?Crj%eQhHPw%L?VeX&DJ{uqf z3(nQ&ZVdSVXe7HaWK#x$<)vr=AKe8zcDiw_Un3ccl?P~rfB2r z<*-(s(kJfOIfv3m{eiUx)2NONH@3~NwtcSX{%xy&S-j~F9x;OhDV^p~V~Q2s4{bwr?}B^qzsek>&@PEYjb3 z#!#}?Gzr)`zOl;C7N(z=A{Xh{Qet)k$rRp`?+o;aLz6-vW4Z&v^gW^d(xzm)#kse(0Z4FuxAX%UK>Ra3JNFEbyn# zXq#lNeyi#9bEW1M@74($QBa)q>U*TbigRCB)^Dv>Vf}OeY(>t*uLf7TjQn}rC@#?VZr7fkAwdl>@m9&w|oyaW8e%E^=Sd! z>O9~s;Phbv+|0IHy}s#}rGw4tB3#v$qUbz=}SE-9~Z|nPQ z=O3hC*=wSNmR1@miggm&@Bvqi3sJllgd z7n@6$-4WgL)v_DT?ue?cZ;aIf*kkO34B>;0JdytE#~LUrT0iK!?CR~2JH9M+Mhf<* zXX{8erbPJbHFKh|XUv~#rp)R!x!kgM{zP~nzVO~78r=lFJFgoII081qXMx~sH^Va@ z_Nc3_^^s}yD+@dHf8)|o>Ism0?7}hW;Lkld{pG?#%a~S2kNs-cG{<%+nBVAzl+N4W zrW@+GJosq0aUazQoAALOjkg$+=3=#3X%+7y{crW@SH9oC&F004=f`(BFyy2Z%x_$S zh4XksQvrxCy>9Q((j9&@Z;z|9>3SJ=Q&KHfjTZqD(l76|rNqLY%f^go|R3p1BX!KB@#*wyE5!1gd`Mno~2OoiSg7@19neuJnKj^X8 zEnp*HCxH7ivfT-sZa2SrToqmT_*t)gz47Mpfovy0$6|UweCu#Xilgms)>Yf9s#|Z~ zQ$Y&$#5osaqH68frYZMhn@;Pn`|zyS`|g&4NjsOk9gCF)RllCHCVWrA$%rkjz7PK^ zoT04}Sw=yWZ)tr*Xu%!dnWB zZc||#!XN7fic@<`v~>iWEGb}a5wL-N1Q@d2Ks(j8X0$%EFJ^tQo{G}PO)0*_Cl_RcwyCUU_3@O+X*Fcep8e#9H7M-B9PF=chdfx%7*Gj>p8))9{ z%^v`?m05SQ!@Nc@(No47oeMw#4VgAjq`zyU&%S*jQWm{?{E%{U%XF$G1&b1< zsfg1PlPx606Xx(F);>JIEG`IY+BoqYwyEdl+)YUAV;x#NzU-m>D?h`sSv5|)kMt*< z`StAgt%^mij{9-nw+9ccl!85uJ9F~A_Yc~+-1;+%gWKg`U%9)GyZS&`b=9F2Y&#cT z-OzQ=`(Lt_MLiE5y0?FK-@ZjA>a3H#Zhms^@CAudut)8As6nG~<|r%@+GdswN_=`Xz~1(WtX;&}&oNh(VdD@&x2CN>X+;kQpKeHL<^8l3iQn<+(`E^HP( zV%OjEZ(t@YEQNr29;Cnd&>vcFtKX#A`b$O6PIta)lY&Wm9x0x%R!<7VlP81d!iOg} z5MFm}QWMM0wh^O04F7OJ)BQIwe;}SHE~J0Uv~LGh?zE1ZH7RMl?bQYENWls`51fD_ z^eEIG$j%`YB-LENVa>e1v+z7a0B!Di9`l@k2OX(CG8o>49 zIp35YS9@vX#L=J3I#GM|eJR+Z_B==aW-bn^7Z%AizKy|g5`(j=>^1F zN^E>5RJ9{!Y?-)L+(dHEkp{IU!LcszKSwmb7uzL?=)rfnKApwX2L+NlzJYd|Ml(9 zRjL}TC_1BW&50{h4s4Qw<%j2)2*lt0pj?rfJKv1hK3uo$%&?=!f!qgr9;AP6!=IOF z!xx9%8S(4R3sE1pm4ZEvp678}R)Yun0takvJ)eVs&9llE|5cx9-)v)zO+!x=>NSIP zA#_=-5opl1r&piWgVeUEE8Cr(cDYS2DOi3itGxrXUEcBW3j?YSGp(Fm?U{AU?!&Vp z54K9AzisIuwW@|x3fok7_q-};&C5%{@?%-;S7>SDPj{@p_0G+RrBD6w*3mN;agy-B zmWK34{Sx=yun8NREj)JMc!hS;Oj58X&ebCmZw_5ktp1yon$2obY0$9&{r5=0q+PvK z5Gwcfza9r=HC(>8z59g;vGdF^3Hz*9U(HHc)YT*XPrWw3jxpgQ>xSM=xh1;j0x6jE zvYHf6#6GZUOl&*mA^a!yK$t?{FD}KE?r3FC${-N>;fdZM0JGB~Gz0sM6z^JIve-{^ z&v5h3x14#n!tVEF&4n(c;bxkzyQJ^?r1}rxi>lmQ{`rZYK9+(#aqa|}_<3@fd-5jc zhy}}jiXFWE?PF3fX?K#h3u)uQVqd6QZ%4z<*TdJGx_0HMEfZ~M%z+G*pUVGp?N}I^ydFUrNCqbwi}iV=B<6_#|oA8}++|z5jkq*;{)*=#>>;c<*r=eXXmR zMKe57HV31xW>*vgUTv~GYSEDm>sNM|{w&)J>FBEoNJ2dNl7i*O=xY?vcJ}99Q-_R8 zh#L9yy+08L)I3K7jgA% zo?=gXh$F|4X7Tt-3ihboK9EIHR*mLybMMXNS-AHJPv^kB7g823-(+I@u*o+*2^&56 z?(b6W{SA=QSI;$F@kjUcn0MOLTu^89tvyn({BZB1fwsQ?9{B6?qpw8n8MLXzxi&LP zqgu1lD&9x>Z!8@6;$3Zv@c9=G{Jcos{InD-KioTRN~^H-!sP)?m9}{o-~M{e0Q(0> zb1*!0dv@&H)pw7Fjc<^UvQ_?667nR5J#p?GnfTK3hSM$)c7OQrQZn3b~VXc*}~IK1buFK4f|>^M85-12@A%cNj=~VDLk78nd3LYg1cmjJxY|N0TzYVxj zoDLz=fD`Mc;OnwIvHr8i4{!Wf>u$s_&EW-~+--4?l7QsUiFH%BUNdZJs6FID)CVVL z4f$ov@wcR4x!_7rOi-IQvGjPM{FNXz@}q}P(5G}DA4v-~g`)p1+iP!~QOP|0WR;=+ z`>^6HDHy(rmnLrodH+mz1E_ary}Bh!#9z0p-Mi7!_OIwakd8onQ5u`V#c};>&m{kP ziklVkVZ$RI7K@aENjJuALU1Oa=mXxM^^3lV$fyXf!A<@AZM)7!I(n?`VBBE+qum3i zE8>wCDFAq$5hxYa2M>7&H~jWwTo!JW625~DK=u4$O>9EsYiS23OqIth*yO~J#gX|pX7at}f192iBv(V8#IT2OwzMdcp zj@{hhkDeQ~2@4=83^`&Pa006T0ToiP7{*a~cq$~x6I(}C`e5_XYagD_0L2G;V8*O? z3Oo{OF4W=g@5IiTgnuD-K<8XW5Qg7dYH%NCK+lcOLSv#b3FuyjyqLup=?ILtv+Z7s zFS#Bn?~%Df=Q1t#HQaiS9n6E3k#ehEj2Q(epkdgJKZ*5$@ELM?_b7S2rp8& z?agF!&3;L*{5&CZ!QRgTH3`AwNEtCMDg1BJ%At-zM8g<<;9pD=7oY4%wadUbWpU{# z&dlb{G@IM$NJ~iRkFUM7x!kGtOj#|s{U+S9I5W~y?BvcM`J2t%u1uE*N*H|xvirh? z9h`*nP`JxkY*wpUtJSD93cc2%G^iD7czZOb*6D0UGrUv_Lwo#@!sJ9@Svf@MU!NGS z*{oL^m0Awo%%xW7^hT{!sW6z0X3h-nr&C)DB!4u#E*X=br)!xVbyF=6RKka+0nj-L zs-ymjWn1bsz4K0Z<6?7bRo`+8^Aa`fKU;Tl^xEo)r)~}TA^z+c3P17UtwYM#{~Z|B zXWyjZ>$)DHaIslS5kO&5^-9487DnuR%2(6K*UI_M^s%tZAnjadXcRoKml~X>I154hG?+w|dT` z;4})W)uQ2)@IrHoi8GkBdYx7aZ-3?ogYe2$Vz%P3f8GoR%U0-WEgjh~X+!k)lLz0b zKO3t?HI?1?jj2oQ%^z+yUiePC-bt*{>#dvy28AY-%3wC>;lH99*K%efXHeL5DkGYP4pUTwAOVo>JNLk8UtXePuLU%(7N% zc)3~S&#zUQGyS{W>ai$VOlWz*T5s+J#P??v5Pw%Nd>T{;7!ZH9W)=bQc{$lMuM@=sQWo$$*L-4X15+jj3pS(+`rE+r21fo zb=&LhGlONLkAeh$<5XTC%m;*9_6wpIMb5krnCfkoV^cTw$5~>WCZc* zc5D!U&6`-u^FsZvb_fN1N(T}Ll`pb>e(Mp{hrdn?Ut3|x+`U7%nNl#nB@R5D)#o*R zoXeHsu&0HDWV(AhWM@XXGnIbEcB#<7EuYfm%f@ot|o;^>Q z!)4a4U;Mne;`=J=g!-3G&F^Cyh&TcX1@GmaXSyLnp7Lfysz zC)cgq$cmeKHVa5Xd@i~aEdM+k9x*OHTORe7m2UAqaj^RFfDGN`Ro|C=) z;cr}t8pDM&YOT6D)mXdMU`hf~^prrB6~2pU%l&4L=>Kh$CVJY)Dc?_&f@QDO5af+T zqgND@P%Hn%(&KYO^rL4^ngTMRYkyC*o0GXdDV#FSdaKF+DcB24WnS{~cAXEMG$x#m z*ghN9a!&O6Imf@&t@^NKI~>9n?e$AX9e>A+| zZlcc5t^Z(5Z0XGd7T=z@>xIeaiL&G^-y7?0k;w*ZtWC>g(O5q!nu8rk3H74~Eiyb~ zS#r1g*JmcJyT&$-A}BaWxbMn#ua2v<`gGL%BPA;CzWR1&DcBR&Sdoe7(;Z7}8S0Fl z^u_s8hd6^?3YMRZ^;MuTA@p9&QRi<&epq_h_NVX8stKSh4I1wwA4TS@Jl?Z?`S7LJ zej9%H+?{JuFg#+{sB0a<=fvI`O86>ht4Zgck?b(Hk&cb(+@J%zu(~Jqi zMYcCnz8=N>opEbx)O+vm`&gm7e2H~sXn~ld;ulh|Jey(hWcYrPW=Gk_Fn~A)gxT>v z&4a(i3Aqr*oTOlRHp3DVgulHG1%3p>fkxIjY)qXA5g!z5RP3plDV31}F)VxC49-~n z-|m$nk8@^Z!nR2{zlSo2DHS#(z~xP>eR-k&SI(S_Ba!hAO;dV)d~dIL=feLDuGHy; zX;QF%gcgj|67ry-%G$czDG743D=pK}FH>MGB({4GM|`Hdr6bYdcBI8S{I~ypA1sG~ z?9fL(!Kgc2zx2$K58YAA?iQ+0IlgKXawvvvXKEuA)P_tEY4W&CHw5@X%=QFFnmr_> z6-*Q}2uPmklBc+mE7UNRD(qE6%5TXQuZiFq~aykdkl?xPUvLSqHo!6olcY45N_b z!60%W+z8GMJS*fz-d`HCyQyjCnD8;tO~MxKtNgkYjO?Qj$`ES{> z+1u?12?^dt;$3MO5NDRj#5-(S2kSBfMak;HMeUZ2VGk-vb;ICNr^D;ITw^+5tZVXI zzM6v)v@T*5^hcm($eLZ5R>O8#4&hpqN-(Ka;3^_)+Uaco@oq@|0X^td_boFt_(|V_NhvwVY znUW%RJ2HBwWXhds;MVvB4s5p`yqV5ahdj~kN+rQEP*tKc3B>%+^KBe6sn{XB=Lg&% zDQE%b-f;G7Ft~tE^2`l(I6I+Q7Q@*g@Z?Rl2cMrR*Ur8XsgIri?2*X6*RE7#oh3R( zOyTf%@R!R!KJ`+Quq`juXmB!h%F9x){2P2O0OMZwU0v0R#hqiftvL}L8fWGxV+H7SEMxcTc5&3`=qeJ zGsjPhSk-Rd{kD;Xan2Exj#baU_Ii`qLu2=}_=p?9eKZv%B!(3i_eR(+N82+UZYOp> zDKHwr$C5%~T&dl$7a{{Ugr)%$hcb4ufJvMgJh;Rcb0vaDlR7{NDfgrY$)z~twAtff z#7M>{F`yAoSsw`pWAEWdGpZMg-4-!sUggjBjIY!LWg&+BON9>iNCo)h1(iie1ek+6 z(LMl7B1KN2LD<9bT(t*${d!Mxiw@3;#@JPdzcXE|JTM-ml9dc{&!6W`ctTzy3xAFq zQ67Wv#DSTG_dYc|A!hB{*XmAcU@guXD-BOXfZWB4kW#Qb>me9>MH?W=$9rI77BA#t zuB@yD?;{uD@PrgB&w7Xla)wS&ysZc+4~8>whypni!?M?NJfUF=WLzA!kb*tAVGHC& z9HNkdJt<)eT;0w|*aCSLhbW|A|6jru$h$afAqD&Ihb@q6afm_+c1%1_EC^eGz$s_Pj_CTQ6fAo~AA-EGD3p_}T|DeqFGst0kckT?+WmcS z$!Xhm`<-nEFMl>j3YOm+1GuEl3g_O?$O)mzOWWP?mBE~q|>wXEH$Ra%FSZu=nKa&P8+Agf3!9=?x>w)%iOlF} zY_hj>RNU3p5%0ZR=-QEOBYX}_!srgBX7Kmg-w{!+39rU%Zrs;x-DY=7!SZYpO{frk z_)MaUfOOBD8yON8v%2m0OSQM0?YV0r=6_JrMJ`f)*-)dO;htslyrcWKoS!sb3YKS+ zXc1H7rw?b>fQ3JI8^@_KufikWvXS1_FYQ!(UbMEz;a#(%17e19+Z9&#pz zWv?fx1sF*96&Af5j!cNLrOQq6_@u~#7sIi6AmyG!n}P@MfD0eF><0lHK3ej~(PqC` zFZ}W5*q_^Scz{z-a#=KZO`7b6J!;&KU%k6AHGUk*MGRYy0u~afxD5P=NK0_^BT>dA zha1-JgggNm33x+5j9s#VJUu5GOVP@6da5XLG%)t#4)<-}e$h2*)zqK*rfH;Lf76N} zKj9JwX{b~ZQ08|6@TsZC74IZD!sa+=v z1qo5e5vE|cE?ueF)vmP`+NN%**>P_3Ob2o;hWT~FO(2uclL6B0HY6m>k%mtPIOMHd z>GIe_IoI2nf)9bo3W$KD^A7^z+NPKy%TFjH0%5qI8i zV*yA34>Sz8(m7SIl2XDjIq1`7BQ}q%wqma?Vq@%>?web#YB-XoK-NR}reB2~-1TSq zmVhB8b1>(4Z9v(d!!y@~@2+o_?u^V3liO|YFLx!%+rY*>7__J?-rYMH{(Es+fPV|> zeKM3p@wbl^TY;`W+~(VxBW-KG7^hr%@AFM~?rTt1Jgn07;T57zHcGC!YP6wxN;l+N z3?qgkP(Uii!5Z)6VGTGUDa{3o!_rRQf9GPhTstFhp?;BTZwWb8el*n<7Jlvb1JSm1 z*FNo77jt4kslpTsvU%y9x~n6(XKYK#9K8AdOAY^$g2jjfpEwkZC7bg24Meg$K1z); zf$h0!Sda0yla9nL?Em+aD@*4rL}s#LRNRN*vKglA_hBCkWIRL{B&(jq>@!DQP{q-G z*PdFuz%(NI<6rJqdFur0BVaa5l9U^ig5_BkB+%jW<cm|M=FUp7c%K-=Unav> z?JGskyL072mqy$=DOjF$K}du+`EZ6ksruaTXGWCo5;5*z;YtIaU)B=~1jAX{jIm*@ zDz}ZCwRToYmCcG6D4f@zvMz(kKiuOpAzwM6^&Je!ymxOgkL45KkV-4dMGH zej87GvOO&c9^1u@iu`R*mw3x)whm>(%25@Hx^n#QbB*^f5z6r5Dg1zhtaPhC^6xL! zl#1H5CauuE*PGm<@Y}6sPb~UPeALRR#lNrq)tgf&T$iuh*F2phQk-;B;D*%?M}dSyfh**#L*+$S`(5v`m#8?9t77I3CoZQ=2q84h~;5 zDfCL6N@X!A)f&#A!U{RWM8aP`Hj_rb@hSeIa(P&khRBAZ3Tl)|i*TR`~3Z+70HrWh%jme_a zsZ}Zyr&4nolUl75P6U(Cc>5p*eksW$7a`i4s`2d+87%Iy0q#~LZO@*2Z zg|XkL;+nWKVR@YMw&d+hhJ2U%>^CFtwY5d4FL0&t2`M}G&VOpj04TXPRx^UL;mAjzD8nn5>;Xq=?TCIv_N|Xe8N#S*g(B_(p?$wGys5W z^YvgO^Pz*Uz-+dVwv$GhCV8+=kQx*aniF|sh{q!5#ld;L`T3s#ydVCO~|< zhu}MQ3*U5G4B;~S8*cvE*#3}FX`VBBM1!g~ugs+Mp%ic;iYW&E>J9I7ap&RBVzzJE zVlYjbr;&o?S>!?Bln_Hdh=S=26+n+wj;XZMbSbv-b3?{Or5Bls8Sy^NgTKWIxtLUS z_@(&WVbG(PM|7DE7a&>qU_>F)VwLht~iDi9FDw4Nfs~5l(}SXS%yqbuH-Pqcfju?_zZzprMcmsUDhA&x@3v)=`A6L zljj@&iH7?r@Xrp{R=|@fy9j?yz>JVsS$9|fbC7!EvX*d_2!C$)O9Pk#@`u2`D9Dc` z{cG{kl}gGXUGrUiet#=a8$@_D_B}Q9Lee{&{ZBz{`hgV0J7l zg@DAg;2ugotyJx`FWqTx8nNluRwcI-c~%NmRy?f1LrkL`FsPKrreklF5h7S0Jk9C^ z2y|Nf?KtSRo$>G^BbncD0Y`B1CA=dZd2JX9z-TA&)sPT+6FR_TS6>_vr;=*0leFX7 z2b}ok7f6c5fe*_k>oI{+Ph#_UfN%ngvM?V#mf6o0*O?4s}?JMU^LyoH&uuoMDT znAJX3)@rh3iFL=+U*BzCV!%BVrWh727Un!4KUUV87?jtX6J)IUqH$B>&mB`nLvAHY z1_PCYaXVyv;X9s~x*aHS$gqC9r_Q?Y%SoCPHilk6Ej9)|A85pXjU5df;NBESC*B;s zS3Wwyg_sE+Uzq%5m`!o&%>iqc)EToMvjbRCClnRRKc#B@q^XOvVN)*XYm|vTb3h8_ zx9dO$1$}lMc+OLR5hxm?_b5Ub(+NkdCiYHwq~{T0NA%R89YtQB)-8OJ{7a4M@314t zc~(++6g!!-d=YgoktYl|>Y4z1dg=?A{RUR@QaRXFux^1Q^Mb5A$ ziNjS)vG8YZeo51?sk2wpLqkVbnBuG_1L4**cee|I#t#)Q=?S8~P4E$b1Kr6J>e zq<@j(=UXdn#~R(QdvU{>#NXeRf{nx$AtbL?dT5?dQgVuye0!0@&#amu=0-}t`SI$G z7N(m;wubF~_r3Gw`$)mgFiH zbA?K26Wo^F?gD0AGJbD>879&)(ND@!wmAw>K7DO0m;A+&?n~C6&Ct|Ej>Is(&H`&I z^w8EsX{O(VcDj-k2hf4j3qN}TzzA4Qi=seq-(i)aD9j?%*Wz_J? z!+&49;!Nd{NHe4yY)b1U&!YP{0yFg7owU#BUSwz2k;hHDV_J6m<Gt$3|y^^I_XFO1`*m#21BU z{f+Rf%m(ix7q1LD9kTeT{^4s~J-c2wHDHPqEYBwGNQ5|LtMMbX5ueRm_Wq$Qu?u!j z%ozP+!x$-8_WJ$DduJN*=NuWX>UI1d)1HxW+q>CH{w@W3pOGvPDvtQ+_F8#!7o0qn zk-vM?EMTC!9fN*e^X4M+jxT$L4q1HUT_idfyM3YDspXYlw>6#CK=#ec|BFvV35a2f z5s{FH1WLn?aECJ~IrGu3WkmuZ7Z-j1UDPsV_>foZg$CIccSX8_VYJhYql#gwA&xNLCp5KnN z1;g*>^|`;EnYhC|{_FndGk0$>BfnzUTtp-!!f$!_5$1OFhP5<~YwJwNOn$Tq#s#Co zudkc%^2oNaTdQ3>d864FBq=C{=k|2AD1H1HZq^CL1WhRqQ(Tmdq97|suq zZU+REEBE^CpVj+f=iiL4K5vb#FMxvLxKUxFy~3tj=GkFmlz+4t_!4p~hW#NPfTBFx zI@1y$zLYO2ZV&b6RK;amd?oArXRol0?hl^bSf}p^WLONlD`pr~>|r=RRNUbqI2NDb zjvR|&i^Uv251HVADOgv{4|c6kyZCr~00m{yuXb6~yw$n7VegiF={NF*-~Vsrf=%#G1KrDSM4`v2Iw3V^7duZw}*Viy*+E)C{3yh(ar1lY3_Z4qr4zB-s!1*h+fFTyr%^hN<(I4l z{1RA_iljlB8c-7Zqm($(-R}8Q-QPu18t_8rO`k9el1Y*jd}X3?c?W%6{?*QHBR>o| z+Y?fdicP1cAgpp=!XKuBzWGLI*y`VED~gj;SAj!u5N@&-gJL%LRR)(INTCb2lQRb} zFE&x@dhg(mRSMJLTyZHRx-S~i2*Tg(erhL$^m7A1t3*Cl=Of^S(?n!1wKHnsiR`7O zp@#+A2OYl|3Y*$qeRdY26<17PKadNYQ+M#9&N1u*?rqYO zil%QTVdTC!>P)E#DC^;>#X&fYi$O6P#b@Js3$|Q(WBX1mttlsQqY5K>u0KDo0CyZ4 z)4;Y<0^K`u<+Z+F4(5vDDkyS%uGDLhuJ4E=M{!h>`NcF9Z3asV&HGkkqj$eEG}O`j zZ!T9`OGTN(VltR&(!Tv&OPR%GYjV`ow9vbTIcn-OEiHAfh87LYKxJ!asL}qs{oQ&# zKg<4_7+0EoPD4g0d=oqd|;Zfg1zjs-m5{@3C3g`b(8 z4`yxE_A?B}co(wN;pY_0DsRF^PZ28&S9UY>nneRS)Tj=C66jpxTFdWDfI=%Q)>qa zbNa9JLb?@~3Yn{_gr%3OrA9-gm!-x~VRKlTnyTs?wklUkMO8(OMnh#<@C*o_+dnT# z4|6Ofdb~%PQcBfoxCRwl^O^KLX16%~%QDpOq@ zy%ZijsH7oyZiUaSdY4kFV+o~{iY=`!rL;uOv{Y49Xj&>7YRWWpt3!IBNmEv3Yomt| zH8`3qWv;YNA`?AXsHINRRAV!h)ihOAG&PwT+R6+XgR7#Ut**)Z<0M)vgPi^Q>50m5 z5*JNs)h?!kB|D)>cChkGYnT+xcM^TlFWqm{EQaIiUhmZq1H)j9U%qbYo?`rt>*H|u zY`|laSd5p~Nu^pk4zFEp<&5Hhxf;&#h{2ztmf2S*4V!)lf>Q*oyy3 zX^kwUYFcXQ8p`N#b}m;#U7f{2y-sYFGD96b%&tXaGXIoP7}l(^hByq9Pvy?;tbMpO zJ#dEO@Mf!5@8ZXgKFXu9qC4Fyu4^4eFGO~&OZ<-O7UCYeGnb}o{rCF*@1~DGu9x1| zrxUB+xl-@ug7zc?=oDIsi*5MjiyI+?y%R9hko~e6`%6JG==-*^HhqC%P}n zMv&MXtO`jI`%KDVf%SM8NaSc=i&kPr`+U%(z;ciFjeo7v>$Ps$tRy4F@Mq^EM`05n z&G2XgO#Ys|-BLb}_s-gJ#O7!pjcLv#tO6vdYM)6V&1xrMf4xEnQs>{_=*z!~&<9@; za6u-`{D))9s-$55!5+O9pXbdtYy0!i+6|Yc%p_stN?Q3#USNk5DqZ5!=(}?b7I)8d zv)N`nWsVo{n}YsQkA1oo%L_33m3cO@7PA&STp^aX=nDKlGLRpEp1Uu1)xQ3++3`7w z2Mpr2ex1YZd(B9=YU6?YaVTY}1NkJZ0;)F5cYus64#M^ngJL#HRgWI19!N8g59Fww zStN{HJt}`7A8etHX+fF*PHG@xxqxGEz!>RTB&-?^W9tEHtvD z#!}&^s<4?fO%0khhr#4%s%bLR(S#Ma4MUS2-B_!}F&~ejqBfEE@uLqYc~sHEB^4hd z{0+xbYX=GYZy=waYBjF(YN>Ix8K^fFjihOyQmabS&|qt^v@|s}wb)#S`k$r!;4y|u zFTMOY1Rv6rQmR(NHK^Es1Nr;}u5qPQ6^(vzVKGw`hBCS@py30w+^C8c8pY>mFw_K- zrK+Tl_FqdW)v<(9O2w+-Kt7YHs>)>1wA7T&~S69{6(ne$ZEYyK6t&^y% zqQX_>s-jh78Oj=38eAGnSzAksq0Z$ZHZx8rqs#Of@u3g`)vekhIm+w6v7fl+il6 z9LAsda#ijmQpX4&X(2$#ql!{lP9n8-z%{7Ye*^iDx;3x#YI4<-HCSkpvWB(>nw(EV z3rsVaY;6sWHbGy^ zf?nV8|GrL7xGNhEQ2;szVdO!Os*x$^-XY19IBqhRq!7XACe{Oy1NrbkmdM9; zFG;hwr2f9Ceq8#z4@K!?HntpZyabzol2Hy8MTY?ClknXlxjDV@q!qJ{#teP<(}RSS zPm<1~fjw9^)*h|b+DMLx)`6ITo*cJEPmII*tbZ0ZhGmc8*Su289UGvd79$MKEqlcW zWc&z9`c|#*K~h;QANylJo84ZE%RG3*mYGGu{t`ZzpTlUxvY3Tl6Ho#322k;k8*4Nj zFN=hJm4s45tm5hloC3yESMMWXf2kc1Vpbd>uthkO8tIjGA_NejPB0*0%Y=0AD;T}c5*wK3UsO1Uz*NF2bEfC z_)j@))M%`=;tWU!hN9(SMfA#-S*ZLjvKy$l*ivzp`HXDzuZa#1@7qQqh>@_t}~-a;z! zey~8Axu!RCXU5NQ9$*l3QO8Z^Tk1P(0$7A6cEM!1s~uWB>0F!3+SxTBuhZm+D*(x=VpgIpE>@TI}+g>#e4r%5jL|;}#2OiYryGYny6`gCvWbdiC4e{vN5aPDF{7xIlHdVPF?dM$6!QqrMCu z5?13XE0CZ*SwOYX}H0jwIFsH1_3OuNb3z9HdS61pWjb(BBAE~TTb^aVy zqK!NK_&D3SQIyubK`UR9Dl4>JsdrWqR^uuwsaa0KWLa5BT^VH+XxI-tsCQNpChN*d zU178=ZZ)T}I*W6IY3NNi<(>o`X%O3wdwC2q?54$%w+e-&dTOy73_ar1%1Xkjy0Qv; zN>V*?Me6D&VX~~O(1%GK>?*53!+zjFt*j(W)|HjII&N9qs-m)reHf{opxEKtn#eY* zb89he)`!wOjKt_O_`*;Pj{c6B`#Rov6=07|fHcFEbu!vsR4~H5k-af{tKHtihM&gf zlCTP>tX2Ck5|D^rzS@I1=Y_Ff-S^WUd(XN-!cv7~p~MY7K*=>ovQj}fElceX{D7X- zKhuI~#k))O!@xiYxZPW{C$MOpxA->}+}{&EUgveWQXdMx8IISf{ODKbMbTee+$+ikYlH4;_<6}M`K1%Slf`>kV?^&fv3KX|>XVcfwNB#eBQ zt(*dm3n>(EvmDJX9#$=l12!FgbNJg$Zz#3m3Nq{m`#ZUKyuYWD!MfpCl(C~|?nx4+ z2?q;8i5OKbC#amX{dWuc8y8tUJaKWGp>F;`FhLSd)F%sp6BSzq7ZZdMPF4a$xM<^} z_}?OT2#!MiLgHTrj`K{~5dh%Q)-~YgQvKfhf3*IPx;$anb`n;VLW?=UOD(k*_P_V( z)?Ch}6O*SeT;FXsq>H#blUz{U;8G|w$GZOKXUV6?#USbn3~VAeGfVK@LU3*rCQx#% zKU>Wn4SnRoix}b5VNGl}U3ZDQ;DEn}8gRJ~=||C!;);}GI`VtU-RLoI_l5pjFK?=i ztFp^@+plbF0@#Sy*wX~hBXv}{J zI(qH=Y|BNK^JiL?4B+Ccf<>i*u&JeXpdX~XD5;==14sv94EXJ{e0y&byRDN&t>#;M zM{amR!u*9|=10&A0eHAo(Rh)ymG%5ark3zNSVa|f$(v;Vel_gq3VrCc8zK^@<}|-R zckuhEHZAwXOmA=wOa*?JBmAZY;21UQyl1kG_a3@s%e5OXDg~3UE<*K(&l`q9(eknA z9ZQP^eE+6cu7&HsGSrNhqYYGq|E0EJ9|V5Pm=09XUA?+4TB>{E#Cvt;?d^@6Tf#w- zP*yhId`3}MvmNuO{br@icZoomiZv!uwpb=(%0)lxbTH>weNk~+k$SPU0wkG4l=Yh2 zoZ60e-+SZO8JpY+$Mv8=IrU5EQ^^!KGLUNSw*;ft{Df~Nvu8v5&Q{C?EDRt@_Ar6oJcwu_CWv^7v|6n zVl@=>_h0dB`e@@g9TJ9bzi~ww$~HM5$PRxR@aD>kF))!dPT!QMK=qdx~N`8R2GPbaE*-*eB{||HnBE!752; zz8)W1cb?@TZo+eomhvkDnLv|@1;NDxflpHd{V2XujkRBHi{8IwXNzVnH6o%yj@w`F zY|yPx#|<*1;Fwxi^wfcd$*+tjKVK811%``D3CWv3T(}epBAY+W1WwLK!FSz1$IHoy z?N4$M9EEQUq8l)c#N3@sq#3n2YaEdB&QPxx?O|BRz2;jZu?b)iHhwzV4%}d{<{*pL zPT62>uy%sk1rk<1rQ>rRAxI}2ZPoTC0g3bBXRh^R)HNBuc5zb2k>AxxST>X%LHLa~ zmoi#NWq83+>VL#Zr>k7a&Y z$vvJNM-ZBkjaCu+ux;=f{qCbZSIx^%HaCE7H?f>$E?CZBAqu$KiWIB}ae|eDT%dCI zxSZN|YjeJ<;iO*iq|O=yxS{ClXfU1Pe&? zb5ESnhCRH`RBqlu`US6jBup~Fs@(nr5U@Srw#sIPDfa`Lcx4XH^@~L2i!Io&-yHqD zoRhQF)X29ZZ{~dOd$o@)CSkG=Fc2aLAYgME8XGm!@g3_t;JlY%r=jtHmnBr@=otH6 z!A+DH(e9mng2K%Y?r%lHWFb_T8wi!h{f0fqGFFbCH!yo$@{O165hM|}{GUF{(|NBS zxY#ML>3qm+J#eF9wNN7(hpG}`9G|%S`5zJ0htha~YP&}anXNxeefIRX9zj2Utt5%6 z1xiF6+cg(r=#~%L51;I2;4}I?39E6U3M4)$8a5fB(_yVz+oDaj_JdZCu<9bJ@~Kaq z9~n>GHDUat1g|k?Bx>jZpL#pntk|a)&Gg|l34M}TIEsYHQdGhFyR}70XD#np%)oOm z_66%Lx`LoGg$H=FH#%I{SYM&n6-%3>vorQ=CSkG^Rq*nbo3u+*(7XLHvCp-%iI*1l zl9XFga2H2oLx$b^p1(4g9WEsSH!Aj@s6uL@$G`<1KEJaKfH$?^QxZ=V_1uW;_|2Eb zQ?1n^Jou4uXr@cxJ-5jBlhlPp6*sNHkr;LS{B`6n!YYf?Z90UR^vpKNSxtS&ESbvXSb2B1mjyh5f*zwYkDR3r>e`V^$}-hvq(aCt=k=j2`DFb#T*@ z*GX4+=+VnGSq<#3)?yS4)}eqUS!5rcSTQn}MvPjRH~Ml^f7+Yf>YtOw9W7{!O#pMS z7|lZ4E!(WhJ+E&V*phXB?_KZ2E+nkRi4l;X_OFmIS&ET4vXR<1o~LISqa*h^_6mY(%(J}ZM?AgNe&5Tm2J=lBHD=hGHABqd%p`&8yr5i%DeYeBWb zN+8lR%Bd};&nN<2rQBkaZ#hF{DP8FmqlZV3`QppVu?djpb>Rbr+31gUY4FW-<64*8 zUIgrAod2au!fKot0f~h{o3(9tMZ30!Ec8{_;aNn&$YNCa&*iBj`(Eb`Rc^-#Ub^Gi z2loRPn%qWEnUxhd%sk%G%%3;9(|O)GzoxXa4@ekUh$@7a8h?#m%JYU`I|L~1f+ElV zP5l5{8+X`p>?7~PV*Ty&67|R4P$6Nm7Mnqcgip@vX^ET@Bjr|Jir;%~%xd5wj-SlM zrbv+TxTcE~8(KXvVk1}h`**p;X5GZ)9kdvym!;<)jB1}1e+ZiZX(kUJC_s;1UaOOB z-to-U+GgBNNU+Q`AYoN4Hhkj*A5wWfKw?Zt{nlIAJ7%&cjabv{$nQfW?2}N<_+1<; zb?#T?PNkTG;$6gzaI)i_^YV;0&t9M0!3#_gSFm9}@X1;*Z-_kI@adjrq2XH!=FcTz zYtelS2hkkIm3N{h48oN8_z8|z5-xLfKB+shr)m^79}v<0c26zfLdCo#;!^JXLX}TW zc_8}7@0k9xg-tI>GK5INV}lhfV6?%*r_)yY`a68y;Q>6T7+FlI4;3kQnhBy$06FR&h~mq-CMN17&bgwI?W0qy3N=4))= z`s!@rsgypM(?hTckY?ChgSz{x=zfDUob;9PxjO?i7Z00D!fKp=0ttrO`i#0d8qHRn zN(dcYx79upmV-+dI=-Z)Pz!R!PM+U`fR!lb~`-X#*5hnYRU8Xh0gNw`l~4&YRG1;yD7TAeZ+|uQkdam+ z%`HxuslW$?KZK(c z#zk$HD&lZQ%4Ch%(VI27pjU5NQkzYjBXA-_Du|eP9kAb9U+dU$PDtLskxm&Kw#`f> zVShb#23M<9Ih?SelGv^v$@2^}`h99@lG|Q=g<*HWb}Ci@cMK@s*ew3{KV{ZA#4K=Q zlgLfHwNFPh9v)Em`dgU`2Scntu3hNCE2erb^0o`oTnp=su_j@DWYNX^t6_6*~UAtIrv-n z7>vPpsS1>YjyjmwW|Xe3!nD=P$8OvIMI#;#f|E%Xz|sTu51pBOmTk1&#>MlPOCD?U zNfP#m%t>%*Vbd#)QwF+v8+XI=uXyIP%bvW5JhvoRJWwJ|zMZn;7>1$!Rom>2B z51go&2ANZ(=F=|3se!NI%#Dn|DG$zV-1WN~zojM-CyPl#KFwpi3fvTbZEMF-cfSKC zD)w9=PT+<8dp<#4K!8FZC_s)Q9rrzg zoyP-mJ{2)L1r}`aPU^^B2ERpTwtGv7qnYQ}GYu3Ah30DtBzo>o625hHd$0f4epz3Y+ z%-Y@2ILIS^^qVNlLC($iwo@?dYa?1htv&GKAqd|O{vd)+kvjzYq5DPbyg+<4QJMq$ zW!_bhEy!5RR%DAoQQTv5^zTyi^~z_C>5y#vES(m*BScTsg^WM7{KUtNyf%;T1#Qnh*2PJph5*>#q;Y3j9Q#7+p5wMS7Zg1kMZzTOn5bAz zHpsRgD?21TXWSj}vwu*KubF$9D?-U!a3t;%kYPld(mEe#n6qrz!;DG%WcTJQJ z8QgoYd14Qb3we|0lQ7x#jS3P|A~tDhbSEBXd}!|Z87W^jboB-{R7^6dsoXwLXv5cA zKWv-^>vNkE83qB5JdQX4PjNXWbLo-T*D+}%rgzl5ND5zP@(S)`3s$d}pLWsKJ+JMW zPm&&6lzvoShlJHQ=>ZZ{Ux$Rr!q-tkB~}_=2kfW%IwY(n`8r@f)z=|mk_k}7`a1KF zZU0Yw9jOF|eqwZ&kA_8G6q5r&R-at>h$J|Wrc_^tgw;5~Ar%%9CJSGORH0Blh`n>d zez2eF>yWUT;p>3qRKJFVNhURw@9QL_Xzy!k7~Le#(?2_feF_#$6`Nx<$Jc2g&eypl zjj!XC=kwE6-@xpeazmGuNAojD(lZ~WAJx|(VKq*AfCSaoAz`xcb^1u@>wx`KUx$R% zBwq*Yr}{c1OfmtgSYO8u+4jHd>nJuB)3}mKaC%Hs_qAo+ep`FXEYCBi)(s*F4x}m7 z*CAmwPH;$tg@nn%*CACXln-L>oUkA4r}{c1tY-K+U^&&-Az_k9P38MKs|KXK^rCx? zy=FB#(l21+56F>f-LE6@^9nw{e*YFZ-8Ki&Ecax#TP@!F8h8I%2KyX|PdQvEt; zZZAJ9K%aR_R&};>9!%f=VD@zX&lzJ#SdEh&AW=(m`R)OB=a|t=`b_+u^omKsWcj?p zpDYkxfZ-Uh`<-2m&Yk!pI$IT^i8uzb#D_gt1$_y z?$0HF&Ed@PyMrygxiL@Y1@`rswTOgCCY%-fTtXI7#Pd&DcWiOxxzYNh%m(JqZd^m= ziWSO=n*{tAO|%d>3D_6J8U^eIi5}8NR}n3TXlJ?QaGGI+*Ab5gjM%)1TL)SxXkin; z96Y4I5N)r%SztS6ZX?4OPsjFMJb%cOFj>s)ZH$uc=j!M|N0qG%d^74>EMd+*B9w=u`VohXhIeYBMf)KmuB&;gu_6kaY9F){2Q;gU6Y;DI&S#zSl>#=qLU^DE; z$G~rD0Q*O@x9om**<$_p(?^c?e{1@UgjK+83yO28=!MHosU4IbS%MQwoh^zOCJQ9k z&0pA?r;lWWN3JtC5PkC`2_wtO2+A~tbJE(5sqk&bwn1h!N!K62Y(2<0ZF!U7iVIj} zW>&??%6Y^^q^v|xh>MgJXLO)QSxH7wlv`HTOy=gq?0c@W{^-8%tz7l{3KtLTWi3MK zsgk*K&#>VyO(RRvu z8G9PJeA4)Kf`rLJU!xK66QNtJO3JL^~B!3~BR#dq>ta_?&JP{;>KIK6a@{iSkU!`SEEBJT_FF8zTM z6{`S!g>nxj6$jyRQw$O|tOX~QI$IPmz##yMYa4VwI?a#cY#*z1q*YkI`6TS8L^}FJ zQrmI#d>e#5B(fbJ4|e{HTE1q?;;XF06Yo^^ot?6ege4Pgr_T13xC;>54o|m8{CKN9 zI{37?epJg3uXGbt{Jk>nS-b`wqVfm!K>$9Htc_t~XR5OjRE`g+@B4HE37dwkLdTaR zV%2hVKyg1vyK1<5^$WwehHJ9FzfN9(Ac;60n7Ce^PCLLzbK9ct(ZX~YaHL|Ri1`=} zQJ{dUNjfTn<$AQKB|7=fYjwvhUtl@f!E(`ZW&RcM2R}V=`X-}|=qZol?;fAhafu8)3-B7n~TV;dgvdO(ZVt-n6G?PJuGgr5tBSoi0YhCTIG2-sZ%3PFV7*m!&hL3l-x+ z0t-S(!vFId2O6SFstd16QvBoZ$Pgk)E)UR|n?ART7k6Ff!OOF?*Y*H5RIEBTXk|X< zOyWm-E}`rY*+U2wuiP!z@b2w`bwBK7rzj6FRy7M*BrG?0-~k-lG`mI*Vx9Ns1SL|FSXqr1G1^TjI zz0&nijV^fo;KgTTuE+`r`yhb*=bH7K^o#b-b{LG?al{5vUDT-bh7CjP{ znBpH`AcPV<0gR~aDiTJP7-}v_+y=zam#Ym3(noEt!iB_f{2!4Yb40V; z^3!|7*gi_z>oR?F?!WR*3>r+5A82zPyc2lhK)XD>P06>PuBW$2Ct)>Cet^X4+TC_` z*_ELal4R3xRPDR^B&;UM57^(&M|BW)j6Wx0?Ta=IeRdupVU;95%~14%Dp-HOd}^Nu z39BypL+wjK=F41v?x1Fk$N|#TU?B>)@{8>0k3b%YNcYDFU7^gLeyJBynSwO21gUNLU336{IIWPW&Nk55`E} z^8_cBI$PA;32+ENg4)0*VcYQu==hQdsCQs~=Y!CZ#rY0V2?yb0gmM0*@lLqoQaeWA zVAzk3f!{db9wD%Qz>7<^oMuny8RPCB9&zB*G7?6|C!+6SPPP8I^Pxf(K>^di=JYK= z33ZmW;A~yIeC@n3PNPYfF&r!i)s;uy75}f(JKOW3xohRMpS(Q*JgC?$Qg=ZmzxN%d zo2W8{yF9?&ZA({Qcyc{jH!7@y+WYVOhLW(6LItxVFaEh{5A8MNYV#+I!8Z=YQ2-zb zhue?h<(0HA@V3mI*(p0RF&a2fG2-0Rzd9N#*V|r->Jrv|04qcO=CzTzwgV;Q zI47@zhWq!OoUGSF>n^_6=^1dOVz7`K4#kOBMI3RwlH}JTueHna(=&Lx`uh%-yU@4` zaG_$V#Ck*3=E}*h@^CS7`)={8=TyT?m8Kybdi7QTE>vu14at|dLw&xriCxL_da*3^ zi|=`L;6lZw5c7pPigH%k`#nzj;^GT{BxUO0z{0QwldO0f52#*U`RcbX*iOZE5c7d* zJB$EfGx*<<`YQOOQfEtIyUU@%>8E{0u;V($T?jNBrv|oDu>^^1zf$G4_x<{GqRx#Y zoSh8@>TdobcNlD^V(~=VdkIRC$mA8dLy*wLqg2HkQs+P$%a#ToyRz6}eXr@8pSgDi zSWvM!7gIq^f(4s|LoK}Si|kEadO302bE9AiB3JvIR>0;Pcf zp4=I$tD|RsxWvpltng&{x$CP)SOqklt9FQitisFg#98`QrR|pFc+{_o#uA7OG0NO=la$^HyrX? zM#6qqa}GB16<)u8+khU?hI2dX6o+52s2H*DwUV3AIN6q=bgu7Yr)%D~9(%2F>cC?L z8fPF6UZ4W@(tU2v#8&-vcjTrFe(zitt*;@z?8#hIC4L8d1nTY)DXNNyX1PT*f%hcf za%fY!uOjD&KJ#>%u&Cm3TS#l|hF)DXOpkMY;y$piP21O&gw;4vB^4qP)*dAQ4ke9< z$`u?elpr3|iU+ooC8ogRpt^thinctXb#fP*z0qrXm4s=+#RQ?Mxm`pgvfjB~KCo=1 zal+vzjaN>Op9-c(!Y#b%zWUrxA$lQ4bB1saea!)GRE#{5Qu%$ZIPYKzx#hs?o_kWB z7_4*6TW}=AyhmC5WG+V50_(97i1hI2;+~fMz}>HRNvdvmb~ zkY-qnmZR<7W`{@Y>^(-$^^M$-o*fP3NLW>i5zce4RjQW{0*RHz(?3qj9--%5dtWUN z)3)9uj4Vc#*WAU#Kqw}k%-xx^dLDOY{LkU5ddN%kycuxl(zC!{;o*8-;>OSJ2BxhW zkT9|kRX(qG$Ud%SJsrD7UdG`o8(Y=?X7mt2Wr`4R2)Cb7>(#p(dS2FDv(~*i*Or9I zT7-t6418EG$i_omPR}hp=x~b}(|?u4ui_e$_rx_Ow@4~A$;jYxtBFV4xXHN%gY~=$ zA1v(tMxMAd2t0I-+=LsW@y7+aYk#M zE`8bVEBg-3+m^{6bcFr*7<{7eH`qUFrRV1@Yaf(4l zT)8s8*6FEZ^h1nvROfjWbOqZb;bdLs>fHRDcHD>Lx}~Gii7Z7 zs2C({GVl!kU|vt2($NAA6vYW&1nh5?{MIaDIM2v$QG>eSFDKfOu(2dg zwMgC1IJNjOV6r&6vc5}k(n3e~)Y&*s-bb0^xBW=q(iJ;*!v(}~lDSJ3D&UWqi*(6M z>WgU~(ok}jTSRBJh%eed%7>TbT0bs!aK~fV1V}UNk~yO7(ROW|>^ss8eL{_#;}7)O zO~NXma#n4p8<5yPXp`;O#a;BbzQ1-QKWg<)5=M5(s-}H71(l7?F+COSp7dg6WS;5f zYTiWb*fnGv1mKals$J~mf{n&mOvg6*`_>eaFtS@#HQWXu8*hJan%sHj1m?jx`<)XF zpI-*s#Z^|=4?I4MpK6%p<;d6+<+JV6`R!gLOxCX1dt~SO{_VN*6&@NmrztdP+tI7c zCp~2@M(-*_j9@X7a*L6%SwpvVdp788Pd)mzZJ#%VBr#fv()4rO&ubA)9SptnPbiOS zdd7@|)i^N%5=YrZr_A02(?ixCYv5|J@;nKviDCpi5@)s^9MpC^GtMGph{aQrUnES{ zVl*srgUQ1V$$GAVhpue!&YzCVE>nzvhi1a)>xSp)jI1gBhOgUUwv2>T2QhNJy)C7w z!F1iwNUP|LM-n@h#ZTs9R56~BIg+$;i&3Q8AP-K4DlfUq$R9h6evTrE5xkOx>KT!+ z8Yf0Tg6bKOFjMkGwuV#GS#?N+S9 zM5e1**OgZbAAqKmDMrA9>KT!+>L5mMi?n*1jxN*rpq59kcs>NEqVA86~OK$h7DH@ zVEXH%Jc<5!-+`u1!fL{r++g>{j@wdi*r&3#&-U}GZ~Hlngn5%XrT;x&;5jYjf#{!H z$reub-*^MQCCL+&8H{?zBkLGst+#2}+jPPy;6cU6qDh^VTQO^LWBbL~UU5T;r^O8^ z!kSwUu;z&DDyNBi6~QHGdZ(H#_ipfDs3s@DwCTJBwwp^W;)wd?`N0`|_VMlW>xD@$ zJ@E5!{Rcc>HxgC}9l-)0XR{yp>QEVC`t0l=QLEMlk<6_O%WPz{C)guubBuYNW$s$rondi zR|L|-yliG3R9tbw8J$PPbcy*ymHCQYQU>y=ZV_*ZzF`|ZXVZ>;6JE$&kd%}C3ZLdb z@4w=OrT;vlo#{UvI8ib3t!o6O?46Rf-hinPN|ikjiu%bPJ6oTh$%?%9(xG)MkPhx68Mc6@VPE4{n0Y~WF4 z7i8Y^&0aQjUxYJ4wodOdyHBP+3Ht{L#-~z}q{MspYX<^I30|Tmf&)kgVGKwpF_m%; zS+C>zpRj7aVcuF_5*8p7dr1VOsx8qPrb1UMwOOhfxF93P>TH|RSfwL3#oSi2Bl&WxkGRiR0`s=dN{gR zw6Q`fu3d}hE6nX5j2DcV*B0iKNyMvBj?IB{%6D}SUi*-c*`d(U1)WF59E2)%F|S&c zKY6h);-zrxSW4k)58k$SM;EHDiThF(FUe(#3ztGcq--@4&>kuH#&uUt>@#Ge1i6B9 zRiuxuh^{BHYXVkeFL&33W|yfUt8TVsWh74Ao-v{h1DgOWvGHrr_PAy5-}Icj&%o`= zv5i?LTdyHuSUvcY^1#72P~q9lvXq0(aTbfLEbWCi5r|&rB1k73ZPiX^0TNrc?)YVU zBb2>~X^<9F^k51Jdo8dMEG{n0e>H(C)~7H>Wg;c{?CLdp>lt`|ix`;H!utut4@E^# zT;S(l0qk#|=Bpptbe>UCcK*RJDfc}|*c%yevO$J7@Ev)}-RqTpq{G4ln|r=}fq*2O zn%zx_+1hTsZnDAMh!rn*t$-61Bl}5}J2eN*`R50ihx7Hvu_Z+|2Mj$&DTIA+O1lm_ zW+HM=8Whf$x;$IYC(C=xDC5c90Z&JNx78iALgk+@b{nWF_36N$u4_wi<#^XoB2Kwq7Y*^9% z<$(EVz9g*12^Emoy>!wU+PDk)DIEf?D%&^CC1KFx$yOYM)3O*8vr)=Jx`GZo z-DdaLyx?!#%eu?}!Lw~Jk7whA`Y!XJU)RoK03K`EG z_|(|lOi&Ehyw`}6pTfX)%=D~N33Y=vl0D0dSlsYCCU&$~3`ZP*x} z$?0Lb^BiR=2(U!T3)pk>4lIBw@1XDqN3J;o1jP`!~Fnn?HWCKd5Zak*Jvf_B%KA z+iAq^aL2bVH)ZsTciTvqEV>Gz#J?@-b;r0)E%q+IZ)@|MEXwQwK&Qxo{a3XQe6n*0 zrAMSb@;a?HgNXfu3gc5Dx>7;7+?3jZeh3O`DY(R&6C6M~2%iDO912#?OgG8lBwOrG zPCjTdhlK4Rx>i(Iw_@L$1y2sObuo$Yn7@#l>eD~({>ddWcZN1HeC*CUDomOe6(ZA+ux4>zlQLn_@8^% z(vKNs7G@v%HTrHRz&|7WZlccSF!`e#H|2=6cjB_T0FGdhX&`f#>N{A60xr2CU8;y~ zViY+?K?;{@;!p>t>-8oXhV@8vr)^tVADaN?V9{NRws)NC@x7qqV8ig6?g}RxnB5{_ zxJK5PwjYqFU9aF}E7t(__LuF|R;P6RMZ$<{Ysgh@n?g_|Bt=E_Q!R9P=|5TmS$jipf5yorr+cOUJ^^6zdrzUiTfHp0pZg$e?co2E;4+qHAL zZV>$W%!X?j3)_*f8mFv4;_k}3lhTjh;-$QK@N^q1Jc@*o8>>~LtiO|)>gG_r>_iQS07 z4nJ#i=}<~aW6LMNjdXheTpVX=)13<^pdhm8F0z|H7dgNp+x5o;Nv7r7VYbi z$Tn{F!X@LKRJneM6L0zFnJxsICE?V(+bG`b3CVhg;=eR~5!kRlaH3)raN~gD3?>x^ z;c`<9irFY7M~@IQ_ZD*^E{w8g$24F0IcUs;K5(uigm3PgKkW6zVa%9|L0u24tzHF$ zsaQX(4QOA9*;G%7Kf@2A#6c7%;bZWz@Lh`2IRyL~+ih9j@X7S#-pt0E>u&l02Z`du zZy%xkV87YhDKFYzv(i1l8dYF2d6gas+W;36gc43x0z{PQ#jQzvD)qY_0%lv-F8=3t zT7u2(y{|;xub*PPc}78Nvpt;-ldvPCy!mUz?}~YSA|@*;5Ac4lv)xVG!|HX<>u+j! zr1>zrA^S)ee}bIgr0SLj)$P_5(N&BuZH`=)a^Je-FQ*PKkTc@!Sn6SW-6dh0aG9?! z$Q2Lty>a>II@U*nbrT0A_M@pQWsopg+`3L7+cquJY2?pIAA01De)RN$Tg)9x{J$*0C2u9H$1b69usU#OpVHU4Abz zh<#Xbw-bL>+(c7NgZV) zVY0Y&!F`H4I*Fh%RS)dXJ8-Q1iY{vyiJ{$^C-3;(g@noC)-@d2CQYjg>}NSO_A+?9 zfE%vAxxOE5Ig^A{yIU8GqIGDQ_c7&tn$E#43zXN@dJu}ZNR)}DVehq;`gt%@T3O`w z(x}w}2vadx+`57gr-GCL18*H0s_Xlkopa&dTj(JW$*BSCL;>u-trB-!x#4$iq}jFEUDGjTozulCvH8-~IyHv;R zB&<5$x@11KA@QiOa~m-?HJZE>H#NJ-t6QA2R5y$a>SuYvb7-jWO$}X-AH2|KpN{on zlpGGSU0<9qwP+B1f`nCoSXS+fVIYy-!0q|ndUFlK^^Dgy=)G_h36tfh@egF<>S3zQ zJtITe>tE0_cF*?T2)TkZlm7?XqyRj|pL{lY-lq`m#sgc|FCTjQHVLbwQDd>a{$M)< z;C5^L%<$HheK_I!PY+0+(tIi4l5pFw>&t1aAF13l<#&@6T^u?CH!3E}fn?}6WPPM3 z&b+*xmmQwF&i2dqZIW_RjhFNNblyfkBs)K7%M+L9z>SKLM{B6vqm?_5d<@xTXFBqC zqdYg=BCAVa@-~vtq&%0)-zq27DUYDQMEXWpXlt+IAWik z`o;vC0BHsl2EuyuH#&BDH|yFb^>#Db)vbGZ)D03=`9m`2a;Q$vN7UZ>*W`pW%G6fpKZP)dsq-;N?C#gJg#VE4_K>_Y8W;qZ-TtV{l+A$ zk_M6+qv+Awya&_xL9QYE#6QqBKa_NJqo0!Sv07l1uaMi4neh-!yE6!0%+D(dMi!yU z9WoYFUparoBkV>zH%_Pj(vNNL?rNO0jPGQM<0f~{x)Uyrx_U%H#DoK3!6;!LZf@0?g8O0Cfs+(Z;&4lyLW3=Y#1zlM8veDV}MfDR)+-Za>7gpVlx z7P&)kM498ISYz&@4ZBnQ6b}Vo)(P8}*zs-mF{9xclJHwMXi=a=tdh=wl-S0KzgxHg zKPo0m{e(5l+$XBHXm($o5j1vTtebbwyJc~!Ir{k!4JL|q-o8umY;E0JzCV5+TFFY% zjp*!f*YA>WA;bC!EwkD)2QlfpPcZlO8a{LME6!~aR^#*&NVtAmWNQ_@n3>e^ScCD_ zQxA}^O43g(HuxLLDFnVI;L185Z9Hh9zgt)T@$95#u73UKz5L*yvMMX^sO1widSGk^ zqiqR{@uPL}mXa`82rA|lf;QGEe?4)mvAVHW-YSRqljq_k<@VY`@uHsjazp=?U0M`% zxOWD)Q88HyEqHFG8;j044c}zoGFGj_Va@RpIo`l!%($QDrmv4@9Pn~F37oU zd5%5vB71+-)1JfWR*odB#)%P-c+oW9?1|HE-e$iO7d-}!upnWn*iAvlmo(EVe|ex) zDBgD31*(Vko9d;u`rhW2?O=(PJpvB>wszCbYh`V;OYKdgbGtw6Az|doS~cBUMaaeh zEiSPx=ve7x1T|j$)Fvh$LDjpW(j~2^&f>bal2I)#_w1a4&U9_{S0C6h-yM6|?tkPY zTv4&t;Dgf7D2HpdKJXwTSS3hJZiS*F39E4x6-cyx{?*L%@iVsXJKo;Q`<;f9Fj;yH zg~-O|b?sH1HIC|T|FwP^Cyd6w?LmS?p=Rk&1bf9{%}j{k(F|Jb+Glu}jEfemBv9 z)Y%YVKkUcHz;9{*F4P(FB#bP))R`3(v$Q<6_X4tQZ}W*cZCc3bgohdWJl;zO2T&}h znj^T1-Ngv*LuqDG+&Mjc`qTr@Se}+$6i>|D8b=abSmwaSY4$SCi_r#KUrif0;%9Ru z5?12`7f5LI9)9&_lL7Q3_4o@fdMPQBu<9VV$C0hl2rls1wPu9c@0L?|DLjL7#&;MU zNLY0c+)K#T{ygrrlc#;S{=Y-({A{w;9YJC%FYE_C)O9#Wn5+eNEwYokjtSUbmf!*x z>eI9&OcsI*bIu$7c)*w#cbu7I91v>M`w>iV5z9&Dg6k-_U0}5n*(u*b+~}uNFUmGi z3(g*@Wu)V_`$G>UeUm=e1V}U7y!J)gsfFwIhOVxsyQ|lYf@}3dr<1T6C%8Z&X-}_! zZJCQ$adQ&lwJzqRk+5XRJtIL*Lh^}xyc-__&pXftD#Cv`;cfoO=%dsq=vD;W*IDSD zG+M_nFl^(De(g7Yh6CYZ_=4~o2mCMv@Ud{-GuEqBw4whaJI}*6PCX@IC#wO+IAm+x zk-QW=WorW;-$hcCP?GTyPSe>-U)Am z=@9t&h&z>Gvapp|OWy_U4Y*r2ncD7eJDdjx!AhOIvtJavWwl>@Jg80Zt1;$B0Cz*U z%B_=!dmDIO-lWB#n`wI`gULBKj zUy~bEx8VBxpZy%L36L&W(4a2O?A*b|BKWP5PwQ?Qa?be`kgysjXh7n%=D4kXh3Sla zX~*(!zHK{*gyjhG2NFf7V_zTvILWHVQt4p7LF%Hx>m5I^_PkPEFh1*K7zwMShXP>I zZSe%ZQa>Q^Ae1B^`XR1b!ogrURmMq}WKvb`#<;LN32%dG5K7&0NVh^bNE}C*OOM23 ziq7Jshh8AXOfqlxCKJQj?P0odx{Mg_wc|OiN04S%{$b|Q(2d6W3upCXZ+{k?X#dzj zkA&4Y=>Zb7<5p`%4KddV2;+K7k_Y|(ExLe;JrQgvx)7zVIHXr%$ z^g)Q;ZRTPUR^uuvka*f9rX5e`_I=|_hs}E(2ah3PvV1r)5ZNfrlDfcyt2bhK0zF7c zf7Gia-h^6;B&?Dijs*9h_yHYoHep#>9LnV;fYH>4U`SXcIX&2R{9TFz_8mzN4#9!q z+ymGTJgnMhwfoJirImH`N1(;XRxL;vSy8F|^_A-aokO-#yYhg8IF8iCzTDsh6q*aQ zu>T-}PmxPe!pfi!nh4I6_$_)B_=*WRaf7NpsDOxk#RRxKMJHl*gxDt@u?79sUTc#O6@>D1huLZTrPD664X~rkT6-iVqy_uH{(KE1NGng z7{S};d%N~mxDHH#G>JIug8=rMc740dLZuNS_1LfXGoN32K*GqXJc817P%*EV!1g{s z8)LrqdrYrmqL(%P_rsxAEop`}}$*ZPe zBuonRk*1$ETwwEAjVf2*xY7)Sq9OAMFzlDR$ zMM<5a(;`JluB8}Jl4_*!Rrhyenwc)s-)Ooy_(q~}Hc6CVaKwXY<)}Bh8$0qs6LYz^ zmjxuOszpgS52X?%(x?v!YcCX2NyVkMc`9dw3Kv?^$QhU=u3*D{;FDs_{XEaIi0$sE zsj;-N!W|Mu7N@G^2oE6!StzG;#jNYFm!o^=0tZPrQm2FfM=C}Ztg7LNg)1D{ zMV;FS9AO^ewO5^ZuXXcd8(Dwy?0@2^0^s7f%Urk$!8#PMYKRoB{N`eW%Lk=RxtpXO zQCCzL2j{YV`?KHOdD;3NHUZ4Ry@gPol%qoWrF3}5+xcR~i-qilJ4jfK6D}YjKj3!4 zZ#yqm+}z&zXBdIwNSG@wb&x9jyy}iNXqqf_EgDBfO<7fo!PQ`DF|^gVYzC9fU@%lv zw7C2wZ6+%A9b;!}+Yin}Yobvy`VT7fDV+R5aPcPYv%=qaM~R#w1R@bcg!h;F28wZY z*AD1*I*Ok5)O_+++d--%Y#Ncax+;UC%4M+BI5e7?wiZWCQxlP9XtA`^)M;v5EjgH* zJV~*yiM9RAIn|Cgb@2$`O~s1Gvmn*@3E3TOsBkniv^i=VHFXUYuDZI4riO;58k51+ zVsMzMDC_yNT+9^vPO?~9C9H7{2P504OLSnv@iFk58h|L@>9S;49f<%YU!5(%qustzQm z%O;U9vOD_E63uT%R?xCZU^aExBoapUI{%ppzRTcmT)oP5w*h;p%O;VqW%%moyCj0D zd&v9_5|R~8FUBR-?yM93O>LMv^KmaQNu0*Oe&9mYUlK;v(aOyutc}FGTp8SCuAiX- z>#=x=^oo<~iP6twRCvqn6*toFD0h0oGyQNS$Ml}+OJ-pcAitq9KnOv9ji5QLz9!%TEo~no z@Cffa>vBD3Ki!Qxw&b|R9tt2~vJh0v4JOPFIvsX#*Se3aG}{@!M~5rG9GEhN2zY3| zHr8HHuM0hGO_zxZh(Wof zEVp;_LiNTzjEsWhY4qzEx!44-5ldMp+J3&-%cky&a7M`1>0M^`$@C{;f(D@!!zEY+ z1xZu#C2UU#`e#d!A*J9F*8stA0O=r%0SP6hQtlz^bzJ`wR?RoeTkA{00)(O{iGbRp z1yhD=;Y-6A;%pbXV)14v33EYL8mqHyN@JCd+!TjHQMr%wCcu#pfp8?nXA3sK{@&rH z4Q^do#q`bi5H;iT>UAV6Md%_zoCK&y(?#wOL=Q!PCimx40F{>JI26MQt+;kAqOUNw ze=uG!W?tK5I1nNhG6|ns{0$r$<=7lJr+ioU;I$74nH>rpNtlD65WLG>j;ApG%B@IBL(UwC) zx3`|k$W}X^>k`>5jf9bXsLC(Q(k?>8&z$_YHDmJTv*I_do_O6jZxRV3`%jh63z}1l zf5iIi{@IVSf7Y8|#X)j+%BrNWA2^&ae*b~Zv1EqCsH!PV-5N^5WbHetAbyFRtqmS| zuP{!3KZBWmqvMgX_{m&^Bwphr2hDdDDMHSOXSuzfM(sbPHjf-+5Y_+lz8yYydtx#t8|laUujHsB4^%u_Z^AL=+D39Al|+>^#qk@;dh2-pvN zsOy=KFmIA)RE2AtL?An*S>pt_P}eviVPx^8dg&Fr#>p9E+Zg)HyDMMY8o4v~`v2a$ zhu>1J)?VLtNxi-taU%~45cP5k?$4O^T4uFZ^Mc0?ONowuIe{d&5$M9yS96iD8Yj3w zg8FJM5+=*1Poj{GTN)(oQ5b*UDDBOSfN-^rdk|En2muf3tGP&6wSW2qjHbSGi-c9u z(qb8)=6*6CJsgt?idPs0T#Tq8E@$4gRT8=XsohY}Anr?ca zyI(C^XUp?D>=YyUZrB7!Gu(KNMB7cKycsubhox?utADcnhk>Rftj5VGkT`8upg*bb z3@_@At?sra=D$c7x$#^zBWg2hq1h9kY~Ai(?#+xc9n$`^Z{u{x90c?KV4D-`s}-v(eucrG1LY1CHy&dWU^jJR{x(aNrAnq#$#tq6;j;Iw4Z3 zl2N9MY-0N$ZsnG$H!X%Gu=T$3yzgbqZtl8)C{^He^!N2tDa@c5`W@WcO7HmsE(xn~ zQUxS_r+$mw^`bs6x_bv#$6-@^Nti69>N~Pgnl+4pN6$MuhK)Y_&A`{u&BHCC)*cd8 zJ)~+DssX<8n>S27{6>Fce9j{K&jD``0kPE<_5&lTKTN`8DOE7eFn3A8e1jIp>3cWr zYIw1BVh)1jBG4bTy#aW&mMR$cf>5SZnIOkWq*R%s-n(*3mG1kG)|;9&;d-~<8+c=A zFR5~nFj@MDBta>wK*N6E!7w-$)MTCmb7QOE z)3n>iu9C3o;UhwI)@Dzf6m@LA-quYUieA-w4}-j7t1avYMmAdE-?~k!&y61R-Exn@ z)?FlwEK^k@!G*}imv#F6-r01w(SeTJw_fObgAKM|T#Ig@Ip%C8-W1912igeixZ-c%rk7o;_+({jjYjjYwFHlO!NPy|0llS*>SB z@&O=2#1&@P4;-i!oP^1;qLSnhY!}B(=DtJ4ta%GAYPlP2+w!OT@IKFAgiI~;T7T(1 zUAUswg@i*P4*mVGI1zO%X|`eD^4De)cP+CZVKuIz0*U!sH*9%4VuFE3I(^O%gEn_b zSPqmPK`3_q{~G$Q*fno$P@D~XN8WPxdZi!furR^qo^M|;L0mzG{b0ZA)BuMwp|zR5 zpW@9XK6vdz!YXk9t^(J*1CDN>N-7i#g&}ZZFC4U7HrFYtnRMRHyrHwKDf1N!1Q?VQLQx39E5Z1th55k0eZ% zQgsp8NbSZ&kk|qZ`+*0whlPYy52=DDeW(pEU?HyB!hT>x?O`EdvXCk)H!zM`<9b*+ z39QF@AkurHqleo>cKR;(BE^%3ITIgEAMnsl$5ZL>mpwz$W?&N_zw5&X3i0S~?x!{S zo0FsU-TEKP_%_(#GYPA4k_03=o>fi#!8~ESu9nTC{JLMhlQ6O*Rc*5%0oi)1^~|j& zI(zB|wK2$QeC7Oj1eIB7flp$jW7l?tH2Pl0yzm~a#%~~DWNE5ej)}-t-$pvMjGndB zi|rb|uEEDK&`OhtW5=uWhfn-6jlO=!UAED#&a?RWNWsX$R5cud2kx>2+cwR4X>roC zgK>b>hf!V+5;nnpz>Sk<%H21-U>xG4bokR&&I^p+tsgZn;@d!jh^BWtFYIhESd>^} zAtc2?!d7D^4QH4SYwwu*)-+R|26QC4PaaWpt;3>7v^HSeq z$oIT%V;iWDupC_C(D7B(TN{hw9MSc#j@hQCoM`KmFTFxu*rDjlya9s!*WA`WTQl^c z&iY}^58wIj+lz$NjNV$Xoa*Y3Fj?NtapB-g4#kBmE64svq$gh*>2c`z)BS3}5dE}N z*Uxb~W5<%D2i(9QS69XJ+#KWhIs;$G`I_gGuo@>lK;m)#^A;~1uInbfUpJv)$E+VD zOcv797nSI~qnF$2Hka3p>KnmYdZ!-DG%r(nz8W?cd)KjxgLT$;uA8`(c4sqW3fyDyeHMOG1K3~GbHMwCkzI76&o$d|e{af1 z5=QRYsNA8G|6}hf0Gj&V_h*0#Dkv(pvs+04a|1SFFi`9S0TD$&!VXG65D+B{(nLb( zFaX6?6!l{lb}NdCqT>I&a~HPj+1RMb_xC@_?!C{g_c`&L_r$%Iu)7f1cq!rdij&c2 z*}mJlMoYEtQwlsp;g;5+TkmJIU(Bq+$dd3c8oPlT852#2>NdT8B0J)3%jIs|8pulS zn6jd4+71}w6Us^A!Xt8X%T!LtEVd$)ZekDnEU_Bou5U9?XK$35>GhPJo;cx2Lh+|= z7?Ij$BSkySe}08t)59@1tkDS%kVtM5zwMw(JKeo86>o-iYcdvxL;o7>}hzcPmrR@dM_Uw);N3~uzdBG!AmA7eW7PEY`zthUr@(k zqDf8tPL3%-ww{_C8?~t--Z)8q^R(usJA&ykV)dc4J=JAo*bny0#kFa*?_IfeP*cs-a_4keIIM9<4_JQx z>e#{IIq&p0Mt4f_cAaX9!~PZNF)1F@WBL~@!~KI6(`TOQb`eqp>MfqS3!us%ap@7c zx#iYYh}Q!JL~O68DNEHmJ*5>pplq9&y8nZxIO%~3nB3gLVU13DfCRa@g~J+Ca|`Sz zH@9$@B%50|kc~BIZUGOnCy2vD6Qa6pZhV8eKsJ5>uR-jkD?Qr0xA`UDq=$EJJaa z01tudaq>nPWVOm5a0mAYNOhrai1$HvplNy~9n}nGxs`an`#rbc1~^w(W`_O1A!UZ2 zZFrUkBmHPE`}E%IU>qh%FToCxc=<(kgq;0t!#y24wSQ;YGze@Lh1;8lBR8_8hZ$~o z`0Sz1_DzMrjf_cBggzpB9&IhQ$-6T|f6J}$iPQbqcGYo{cr#@u#5@W_t`#^cL__&j zptn$?39t+N`-ZiB)kJ4IQ)lv=9sNENCV)AF2&JO+^yLP_LZ&keQ_C_lqw0zE!Af~<^y}9B(tO}R#_)n; z!?{OQsp4){EqL>K6@homlTcI%|0+f=}i~; zCY-V(jGx3sN8}Isy0sD_I<%iPn05c_a7OgfRhGtS%`Ye0ZHjW{O$hW1BqyYyU-Aci zaaf}h9Uwvepf3*drrHFX^oWhHewU3-)oouN)=YHI(xAM^!| z*4q z*bU;IUxv4eSdy#n+hcU^o=WG{cvF+87SfUV&%^qKN3t(o=wR|Jz^A3EEDl@76FpUV z#FdNkUYUpw&QjnGzN4x(_%cj5y1K5-ZH17DuUY$szS#NlYEuU|6mH66PSx4mHL#yP z^iCg3W@co$_1A;F6s2Qv*iD{HRLQAH{c^g4Y;!xV-P_1`DsB6|^`DD;6UKtsqHt>e zz4U0SkbILMW6Nc+uYdOhPGqbW)i-e}n8O!@B_b{zD&rEaA_}pnqtAU#?fXRY%vQa+ z@8NkVAV$VgaEV13$3+PfFN>>Sd_>U(Uk0>5#*g~(VWO=LD<$v5@1qmj1^0&&MB$Y4 zDbGZ2(O|%2zz1Q{Zs&=V5P7?R6 zZ6U@{Ad*>NgTA<%5Z^kcT@88_=UczCqtnhzSt0W*r_JbbdkGW3973Km(0ZQxq4a^x z3k}>K`bnuzdNmV=5hV<&P0r)6EETqcl{IH|vW1h4wF~bm9Q0QPZ`e=T0g1j#oD!&V z9tNp)TE_;q^?ZxN@D2L4zlmNa;j(8PaFfWNDjc^ zO2;^@)0ZRZiOO>(pEL2;io@`Y`TFMt9ax6F(lfhh-DITA>mJQ8SA@@ERx3QfVOFdz z-8HA2b-1PSfIgJrYy0s^ced5u$N(6rlhD zMMz#ohzKSBs6hjNN?}}VZ@RC(Z&4GKolYx$5+*>L5h9d{)>&JBCEr)FqHj6m`8Hpr zS1t}~Xc6Kqhl{yYnMfW2aUzhoqwcC1DfNVYh^5*gY-3U!4#SI3!}Kb8ARF7>OWPBo z=&zs5x)-zRCA&R>sx7d}KSvV?M`vp8v_ny{!oBk=(eqxz5i?^o-gv_$m-mtOW8pp3)*h3{#eK(^N8dz!%KpvO41-|c3z z)7Y$wCU@ywaM-`_Jx%CDGF5-IX6f1>lUTpWH)Xt)I3-S4;YFuVfKOCmiS4{EYuI}( zCg@K5znQZ@RIq}?e{dH&trvV;c(5LbM&*7 z*3T`vpAK_vgmRL&;EMc!4|J6a97CqnL~wmZkBv{&yv|CqWSO^HwljrSaEaO?8^xcR z!O$t+tdkkxv1@m(`*x!X4r_FR3na4IefiLg@x~<4$T{RFBRLv}vlLQX{sMiZ$i{RieYx@xNuBdg&+kIMiy;+}ocJBvg9H9-SAQ zfPz4ePN38FFN`@9QH98pDe4ic+cAe5ZpY$>n~azneON1CbkXEuUhN{B#T*owCvWW7 z_n2w_Uw`kHM=tc2eu2a4Va$O?G$2Vifv^6Bo{51a-<#*IOJ#%%8Kk*E!QCH@f)jBk zbFP4X!2Z#WY10%S4?QXBHnPA7tCky~#%tJD*~2Xm)$W{GTH} zg59EUB9AWsCo)!xI)*qE%;5{X`G#)?+7L*XI8YQ~i8(xps0Zum%o_OF_>IT|L5Jpxwcx{{d2znMk}^A4kJorqZy+B5{hA-yNd^oG4d#!NE_2JG6IKnhS=Z+ z9)}Ui6$-pj_6Onq3f#fn4+Tf)%;yAjhkgCOuL^uoV4M-#si^|Zb_kpcH|E|PHvbC1 zp=?9qu9@5HmF$W6j$`vRojx}k8euy!>wVJkBKep?d_oG#Iz9US4cq2pw zdSh;PrFL6X)XjLyhd%PZ=QsU~!y28a0Eu5A!`5%^Gu>!!ZfwGb7Ns|Fm;g~B)u#13 zuL>Oa12cQKD%FmYe_yzB<1tg)HIPWv6;R+qo{xpY1PDxna>UJP6O|*myAU{%F}w(o zyT$4^9ih99+zneDM~Ms64^ah5Ql_772IM98L7%UXqbVvOmt83U?A90oiG6p zhIQNB)AVN_T}gYkKkaVuJ{9O`IO30P^jr(M3D$paflF6h-}%|IW^bBSABxv zO}~-;-+BNMGFDIheuVABl8*zo+)|Dqbe=R_aU6R|M?K}z{ex4qir_#|xRD1cfEyVT zO0ZNOc-OCC zlr;d^IBD{)i}U;s(2w}7&2=*^R!2~^g%)^NW==a;VPKry^S|M7VHNE|a2Vd@t2MVe zpKb!Slf?^%;YFy{d+U&d5TsX z&JL#L?!2NGm6g!-UGGT~!5UH0i2T?Y@FQcA)KBcgebsQ2xPH>ODMN^tK>aL1&z}j@ zPg;u_Jh0I3viG39$^DHJH!FG08#SL#KcO%{$U}dYM->$!J?%_Fn+&=AX40k#9MHGRW% z&s)@P!0FSt@?dIxrKBTj2%%OVK|;Anys(Nq`!pX_H3AE3%-0%BCRo+v!|A2Vd+En|jP4Y;WPrcCKDpa;8`8L2f2vre?HXvf*Pf!5MXPN0Od)Rfeenij0KB+3d=i@NE zD?G|wY%negXFBK-s9TuI)cL*o%8?+@>FFUhW8U1He+Wa zTgg+v5hOHY!+zkS{^fI$Prk11&R5h)qr*oj;4pj>reQhWM5T1*`bhe_Zvh5w6?x&7 zp5E_)gRsI2`+*PnDJ&fJF9=i?vX%UF8*mWDvGE90k+6mg4C#v9km;FCIq_~^zQMsY z4<{e~GE)lY8x^1nlLZQgH9CO;5@dnGVgG_al^|QUJ@9us*l(h7PP5RPZSn_+^h#FX zLl!6;_Adz3tr`jx@F5En4*M4bDjL~3esFh%=TANw`0RPIWKHgY{}A*)B2Y1%gf!md z(O{R@0yR65H8_i^s1y60p<47i>H$umPNMiD3lt7(bOHq=$O47K{sn>ZL$<0OplmHI zTx=MTSF&Tv6ZaPg5}L7LKky+76b}0r1nPDT1q%3(1qz2rQlOebVxSO={%`_yMgac5 z;aTPP5+YpG4mA+2FRxA>R80J&n{`fVeO8N`FL1(j3dJc|xNumb6D}Y@7A_q2F9_F7 zWUG{8#+q^;bHns4-8UD6OqhV6YK05e8|Fu!~O-~+JbDwHT~ct zWH|hv7A`tihXSD*0*Bk(q=X2U>9-p6S-nYozvTPo^(G!`E78e%0CSqd4+^Kz z-&o5LN-N_=>Vzc6K3kCfUuzuJ=!6SM%@n2-kCzM_O!< z9eD3Yq)|X_R9~OVH-|yu2+P>8ANVY`co>-_dyAcN+@PzPiZKm`;f1T#a}4=L+W9uX zI0&5Xb8Z2kgd!kvMQhy+Mg`%*uw)|kyEU$_F)?-G`RFhLC0!uO` zN$DauenKlwBfqPUGR&fTsSSC2A}qNXM1(Mo67RJV`2}9`-GxY040_p&*p0$hs+0HG z8!KL2S-vtT*V*2ISE7&}asv3PA4)aao}e!`*gZdDzynSB7C5ZYNfgcz$6^1%3%qcR z97r8u85{NkpHht$`&Y+07zLY#|FSEIV&SlV;RRmsdTm99**$lrwC#^&OZUpPO#1>H zMB#Y7Q+L(3Hxl&HzdUDbJ*qnwIFhkIqGg8mag-4*PO0_Kfi${^NH6d@hYqx}G5Yb| z;AC|8p|IHQ=hwrmT9Npj_-{|%#q+ONIl1N!FRboI2YzHsGy$&L7kK$1JIdYrpI|oe zqJ{66&0cXmWtB1GfK-!Z7pBJ(XmFCqWH=A`R?XRD>XE@`|;~^|Kp}Im2 z_6M!dlL=#Fjy`eMaQD1#SG{mpJ-kJS%m=plIQb$VVCBSSwgo%&6NV=YR#G334F`$B z=|8O_r4FuTyTZwJ}{yUC$SFwq`Sh`D}SZ<%SD z&q%g7l$?CbbRiHUW0H7_PB1cl_C7y@4ExST@rN&_hDG1`24qFy zPJ8-ZKU0y8g0hgK(H6pC{jpY`l47%=^{XuG6*!n(v(#y7V!Esx8#O zkukjT*4n>^f=Yb7igz7Mhrs6w;MyH< zkg(c?><=^H1Qg_W+ADt$?r&S}j=$a$epT3e!cTz>C=lW$uqQNMQHXvjp<9UE%`kk? zfom_ngt3!vIBN$;Q``s>z#Nc32K6#YtvMfeYYH%t_7Qgr7G+P`{S0+Yu4v}hGD|kzytRS4;;Z^4e7LkT@XaEeaMlf zh8s4#GdlLz+md?r`$MpujMYJX2HBQl6Y;~FKL||NlCKCpK+GcDJ|zvhwn97EaN?y7 zDHTz0vM7Wn(Jb$+d1Ghnt(_Y7J2k}y2$QkFJjJrgY_iO7n%QtmA_(Hddkk?bEcrM^ zBY@o8hl2!h;y4#*KiKbTer46QkrQ=y^e((?-MiIK9JUEA#tl`RY`BOZ(<`NfIF-DF zt`VW1btO&^#DmxmHm`7(zH{GhJ}p_bze6{zzJWOG1TJlwkkf`;C;5%AO%&U84hKdW z|Ga4&X41O*(US`Oz;-egNL&yt|FtwAS5aPETLo58|MZKGlRFBj;HW5b)NPl|H?5L+ zS5pr&gV(J#33}121#fX8S`SdeC|GtKe3%~JE75On+LMphOmLVaYQN1WhrhZV=|-1* zVVvVVu6OQ%c>^H*tIPPfS`&vgWbFqwLx2KE_BH?)g_F;7mqLY>3basp#|iA55yilX zjMbu6Bu)i$_yTXf;oE^W2wuE+m56W;z#T-K03=2}Ti(T8MV7DlVHR6HY5cly$EH5iBrq+#4p1_HW;TsO)xOE8; z?RC>-L!<$CDbxV9m9zWbWP4V$RA2{e?^_)wiFd(>JW}aK6{4^u?P@SmId=PQJqK?h%-V&VS)(o0o<5BY6#I84$bm0`$Eo6biSe``0< zJX-K`o5lF{=w&3Lr6KvVLcouV;RToMrq}IAr4O>>R+9agH#E}< zalsY&Wm|4-gb1!V5=gQ8Y%>3w9&u}^rBS*~#QP0J#e;EzTZkgiu=lO8F>89~k%}Vr-zP>h=*8gl64#Ur0tM$w-k-AgMk&UM=ZA{;G{5sv| zamzlfDQ@Vgw(1Kh@VI2(eyD=&dF_a_52enFI;rEZdYZK+61UID#(h>l#>H!0Gl@7i zsFk~{T$!lcjydc~`e63hAkOUBo9-IrIlzsKt$>ShLzSCc|NR|=_jebqtXlhWazfMY zdeLQSW4yH=_XBfaKXDA#JiY}dof3|(I2nDG?YpgOv{d^(r8o>Punm(h6OqN`eTRN% z7288^_r+^}bmH*k0q*Q}xz8)!~&> zq6-|pw(cf1K6~V&1v<&`6NcKjJ${YDB+&^FhLZ15*v6hM{ag)>T{4*8tBL7L$eO}Z z750PuZ#H$8pFCEYk#*3K`NcDLDGqDMP5`hAf+)6YD2Cl}cy_`lGjC4nk2GI%u$_$6 zLG@O*UEmK9Gs~OX%$)Xb)899I#dyy_IAl-% zB#82u`Vth{_OKLQMnD>wJd3N{29X(P36&t9}gJ|+{hTd9dLx3ngWZBz#U*4 z3J_!1FPjljnT!rtV>l+M)bKVtU2D&W9T8!Z;6(6Tw|d)sHT*D0C-9Pga_2SoV*v+) zxJJPyUy!))s*?r+1PiaQso?O+8L@@;&d>14rMt}Z0{6KDZ)q2r%9}9IkcLo%{(QA< zRvS$0r5k&xwK-+qt8X~0(Fre*u$kFzt7B&tb4$=vyThHvvT+!`6NcQISifIr@4x(@z!e(ASb8a&;?000dU#&NI14l9@K&(imuYS^z5H9H1 z@7tmD(r}A;Ceb^~?mNrRTm~Gspg;2H1mMEBOI*01=7d0~hCtymM-z1fdW^-$+Y(#2 ze4lv+M0ZQp_oKgl|K9aUf5HSXhY+qSXkB*RJLhkUbq^@^YB16w!N3OCq&U-KbdteX4OkJs-T2tXxI-tq6b-B zk#-B!4~W~6@3}WO9Eafrt6{hWqI@rZ>GCgUgIn5;AGRKl4r_55Y!_BoVL$NDcw?gF zDBXjW;n5@Dr0dY}vS%7}gJg}I83k-7`mFN~kW#ppX&hXSDl z0>#J_&Fv52j;Q^HBAWMB}lYIM4$ zDpQHhP*PJ;(pFa1QW-UB6kVIr3LP|^I%txEo!wwKlR~NAGXCct!t**D0~Gf)-!Qb- zxm~o3XXdlM+6`C5VRNyxwdtx14IR3=nyR|eC^cm*Z5?eDB`s}b6}q;nvhpY$iVV8^ z4C)|LTNlfP{~T}c>FV-rA4t)6m@VDw71;M4@FruGZ`Virs*;<|)X`DW(Na+xrLCi? zs-mo>tfER+(N<$Jb+nkeI!p>onVCr)G{a(fgRtgm1_e52$zPr!3@46(ZE^tSWS13( z;T64M-D{lN4}5^1AdV7O^*nCzAtY6xs^=rGPoSzNBYtALm`^(7waFT@jg@INcI8nO zL%t`W2^SMOQ<5o*=Z2>R8|T`c=>Kc=D-KH*i&1K}+&ccYx8G~SSl6ZTi|=n8gv=G1kzqgB|8(Vq!39}QO*T5Iwl}ZX zVvNJ^u4VmlGDn=!k}s_HNR?&}%{zHFf*1pJh(Y~yEc-OPOV`(<4aaf}h93b(s zP07qBYY(x5Lr-7!9X8Gaho$qBhN@AJ`s;BfZWoGHw4`6=w13ru7ITYsX+ms|-jE=$ zpEw4#$pJVF4(X-!w7sqILAAFs7Y}_*!D09UTED(7VfO;GvLntqW4>B3Gt}h5%9PzN z9sv*7PaFf=yg}jx^&QtTqLc{q3><|ORC&Zn?1H-F^nu-!NkQ771EtlXhOO#Gm;muZ zcn0u(gb7csZs>VnwDwW=OWE5;_L0V6jjo^q37IXqqxUP!q35Zcy6PU=D+7lK@C-<) z22sWrc;k|92X_PfLF~{Fkx^?}P&tWHvd?4EQ+u5Q0qdvVFnKxyhY9cw>YW!1ZB5lZ z{MwB2*5H`M4e6T+#hW2c;Kl@Z*d_bW$u6d`sBS2 z=Xnbb(dl#p#UFY8G!AQYA_OGJ^QUnbUW6K^RxLv|)@1%P@F35h#$k9NY8Yj zH?taMT?u@wTjZ}2CifH~w6yj$5ZV!wUr23jCQb9$ygK{1`OOMmp(VV%n9G z{Z@UwJ=!2);>@yRA3aY&z7*y$z<#h_CP+QX=J_Rqu^mAou_V7OA6SwxycCgBu71B(2+2nN3PE)oB`!%n zxG6;Ffxrf6vVssvazhVii0%7*`0xBA{mH9LHXm41-YQ|?Ho^pmGs5?~h1LglmEJSJ z^_Z^b%hOXWTJAoL!y26=0g23(UN7!RFEWZYF!68Mf9V7qCdv23Ek}97RXO^qC1dOJ zVOIy{tk|$N0}`h?X#yTo&OD#Eq%?vVa3sWk<>)(iaM(ZpzBn*?)4?z2G=HWuGnC)Y zqPn|w$6@uTvC1QqIDyk8122ywLRI~Q5K&Tu{Iw(?LdO0D84X5ukzYy;q=j*mxQvSY z*nuPJs}nfF=ZI#Qi7lhW_m*6G80VqwIk!c-8#?1J;binSia+vW2RN+J$taK@KX!n_ zB>C7uEV8llX!RFUVwt)J+188XCN0lLkkAYb`+*1fu>%|?$;S@tP^oQ|WCMyfy2GQCbv^?;%8cW6^aIaIpK6XipUoTn$h+l)JLuQ#xOQ(NQXD;9Q!xRXW1yL+|vlWM)Q|TYo*+ zOHn!&4u$>1F|bVzVE=1n1?EY;8z#a28(*8ZoWCE3{fmztgPmO%1zj(d%{AHcYy1~u zlLvV?tPZNRx_$Jx7^Mj7yLWnj0~O=2EMs-YyO<0pRKfhZqfbp zWFSn&B=P8R7P5o<3L9aZV3HgJuzxm-8t}yP9(%+2x%Mi}?#;(x|N5iHVDp`JtZlj; zaoStsBf74>do==w{fmztgPq1|NtD7~nFbzaied6PXMAwj|9|vYNbhcMZpBN;xWKLy zny|UsMW|*IyAANheCo5#MvHu+!wlS1niaScCZJ@k9Lv9p))%-@oUAJ5Y6tdE8);Co z`V|hV1F;nA(PQ4qsYZ_;1Boe4&BobuchdHLwXW-#7M7tntTV(0H&oTi^*`w*4l!J} zBF$OVt=z!PX30VJeOGTV1BmmI=bBcz01hcL{A|OsJQ(Rmd)cS=W(VUijmk3`{*h{1 zM4-8~)~;OrGKG@+x03rS?mY|Uh{Em7!;u@=(!&flJbd<0XZxl?;6}#qzH`G2F+rd8 zqpig@d3T2BZ@D!-ak?Mdt~zcK?}&f|fj}sLKoOGfAjE@){#UU@Xk75yaREUodYS!< z==YsNcM>LmIm8gtJ+z+Zekgrl^FjmnhkjD(lU~ilVGS)pU?UM~Btk%wlFpZ7>i0Y_VCx;2Cd-4Zs=ttF}_ONU27$ zsH#r+Yli@UuYV#28JW^$z1OD;A9TW&+={pEvHdliCx{bqO|aj4b>DN-jX$wGb1X+($z(H6N{f}skDdH%$)?`eG>AS8sjS;VVL*?c4(Svx)HsSC* zK=DV`8XVT>v<66!wFZYZCanSc$y$TM>Pc&m(@k++Xl;cSRY5GJ0b|KZgTwv>r3v$# z5_v~8fe{zK-AH-j0W|a}d8H9Ldr#zP(jb@uy&8E`%ZjZu8r?p}ch>G>QZk`!<}?i- zH(sTITm#`D`g6!qnm10jaJG+GX>h;uz5c^tb)Ym2+rI-OmiO%kgdpYnCr z-{Ua6(lkt8!Ej_FZGUXVJQIb%KQ?3s&YDnm20=orPS_7Tj$E)j<;mE8Mqy3M_~+?o z*5WX{;xr7mr^v?J!>3-$XKgx8-`3fqRliAcV7oB40QLiqp7Y8^{$?wrDy-}uVg1%& z3l3WW2Xn)3VujLhO{`*c&qE5vQj?jNj52%Q+_m}kW@rhD#4pC2nzfK|dOz!AShVwi z`=!8-jN!$$VbU%GCDOCplTv5t6$ZVgUiW<2S%VYB!qToGTsombyA!NKflxVteOSq; zkt9%PVd{X`Lc6+Pc*_a-b7F?pjeF%A+YfH{OqSB%!ne@&oNm?$bec7N)#_QBfW zIIN+C7MWEUYSf2Sj84x~w9%TZx9)k!f0HuyjIisA!y2Q|0uOm*wKncL3)WtDjyqsC zCgB?nt0$pFPj6B*lqx4oLsqKsWIiyPtXDV;uR9H=tDuEs{YQ{cU6r`@>>zc52-Kb; zVcJtt6YUvAcYLr!duN<49-;VK*yhb}H@yj=Lndh_yAC~LhQk`2 z_5cZ=3u8KE8x?h5=V=zX>fs$f9ER7P`tN532T%TjdnC=Mi>%bxhnwx?uZJT@Xl91} zz~SAmn}ed*ogdxws>rk3F`13S@VZm~yx{#D6#mq@_J^m@ddD}MY+afYbZ4D34wJNV_ZZpf>DfLv!*C$G)ug6b?{7Wlypu^3ei=hg z_Q*0QxU@i)nQpD|?JDpiV|bCR|8xVVyw@qiJedBuk+J>(Z-zlGbR z>$xLZw4IK_8lAWTiB6Fd9#3X0n6pl9W=yQk{#`h%v56~i_{IKqcmS)Xwey|Xn;!Y9 z%)ns{Ew0EcPN+^~z*e$2;V`_&G@K^~!bcW+ASjHV#Kp$0DVQjN*ib8khz-26NNlm8 zX!=Fbj2C~~yrxTr%fUUHabg1%Z@akl?MLZR9-3dXIqI{mtSJs_bYcS}&fhIHd%<=O z-F7=~XZI8S?{HXGZu&qParz`+g;FOqrwaGo`E!V(djZSlb1p9I7AP3)B zhVff_e|&z&M;(XZHK$=RG!xl4@MVj*g2=1vyoZd>d(2+;LXgl54f}z|KG(IyD(6jf z4`r(>Gdz8#;jntr9iosDOE3unUtu*wK&sU4C%TJI>!hgn9M$y6^ks06u)+%afybE` zFH_?)%b7bj@A@_5aegZtCP^Whi)>tAXmGOl_;iDvhV2J9ZaH%kY!}9@A%sZibWR1X zj1r!Qz;2u3jzWY8KE5rs5N&Zy%5dFwS7+P2KB2ZnQxgdjAkH8YL3ob-22$F{wb~$M zu%knUf3qgNe&Mh>5Tb^i&Iu&ad$hejV?ama^tlEjBeN+wI1DdDwVwLe8r|N^c%HVa zt(}#vJ<;2MKomFy_Rp&D%nQeW%`z-4x7R278SZ}BdQjZKAIEVRUUX{BgD{g=@`=qX zgpU8HW7)y4sa{l5-*(q8hjAWq6ILMMLSX;Qe2pHyHtkHpgO0yFUUn-GhvCJhemTuX zwxvE$*rROt_{)?L{+>qrj=cn%g>f3qbvAOjWt}KooOd=i9tCm}sz4}5i>*K#JMWgh zcj1A)XLB$EW$V1e+J$N|f04DN3w4t90&6F0drNByWgN+EY*@_# z+HFH@7qK?AH4fb*|E%w&+_pIEFU{(KPNd8HAtxhaWI?t3!_&dZ*2dP}0zG+E>q3Lx zn@1U`XR*Y3q>ihzi^CFQ3rFXX2&)QW$r{j7yugaLUZD+td_OGMkaoAt7)*GFu zT}hRjo=aV=sTMX))@ZUh)q+Z|1G-hT{;cuoUJF#tJ)W;BHdZmDM~q*ZGwbK5ws05} zfA|v=fMD42TYEdS*r@An>e1KslA=Ej`%Cw-(RleJiZ#WB;!1I%*i)#KsT2!}9on)+ z--*#d>sDyZ9xY|izbTwGD#elqry>lFUWPC#WhrN!imqi%aYpNQ=*ob@Rj6nS)?LvV zwvy8OLZ=L+Xd@y`YMrIX(Zm zpM%E@ydP2FY2vFhEoS2dQzaZ0%X4?mjp3zyI^2v^2N?*x@r^Rl%*DdR)^a4_1=O~{ z%+=lXHf^A+L5|*@%)XwP&cKU|^+fSTgi2nzb;paiHnHSOG^p#Q44gG-obK1zAD@LC zTI*E+uhtN$U}(hV9J_01y(np>Rx0D$bT1%B#td-e7!5>@h77u{F;s5h=UdtlGU;QA z(xsubC6t^%&j5%t9?w7?H9rJ)lEk#AfoJfeaCYJ|?YSc-eL0$3mcGo9*E5iUSVaN+ zuC^URCg>TI`Nf~`@T8Wnbi-ldc?O(IOSYZ|62Su;%nxd(7buyXNcy~gaC02?S3S?M zz1F%5?kQ@Ua4tstaEdXp0hyDhq!DoC5^PPo9~GIXo6EHGniCLU6y$)z{;Iq=SE#l9 zm3DAf_#_A_iGY#TCBGNk)`?PlyLRA$!k%!PD4dk2U#-V6*m@&6$j0ByN_h#K$k<)3YIwin-5ehHYWYz4!j zLdym02XZbYpY#^!1mC%QOv(2SbNhZA_LnC2Mkh+TK~>X^Bp|4C_};f6CgnE8r!Q|e z(l0rN!~PQO|AP%G=-BG!?)%}sUbfE7)#cf7<%`ZBNNC1t2*DNlG)o^+e~iH1^L$in z1bV0?h^E+mS1(G;`}=6iCfz&oHFjo;Ojn%X!bA8QZtXMhHrW@OqLYv`W&U78944ON zLaO}L6D8JTgPbdHe`@qJ3y`>LKF_W>`}vE+=zz#LyO~pP*kAI=xoQ2+gPDSoyP3mD z>FEaFTJ>u8C9&H(^dha^AyZ<4D{uYjKYf*R=uWYixTUR@JX@?6jDpRj`0WUK4mk@F;UjMv0 zAOeNTapggJk!A-wEjrSB&NkHBDx8ewp8k_h4htu=!U)E-ScOH|Y<+kadVmc11NAXeSOpa7WhWrUttv$3|oydT# z$suOkGc%3pHI!jFdDz>p0jn1DSPe9V@sha6i0t8* zB3DSD$haYnVtY6v!=Em5)Nxu%FHVXHN!&jYCo&MH$`t7zZ|FZ;#NPGWYq_z2fx{Y| z$lx*y4wIC~;0jiCnHly2hc5-cz8*4GiF@_q@{U$rSD(UR^(ZnzXE4{)!vPL*;jFM! z{kJ8QVO~*B#|A~ zAqxWCAM@5il*tkGREn)k-P4-3pJ4b>)$(?3l9EkkAHoDMM;d-mc!&O$59;*!ltHN6 zw(?6cC7l%Gaaf~MCLnRu(dC2{`{jtcJ(M@!J2$NWhvAjU2I2+<-YENnaDN5v;O>X` zU0`A7Y|V-3KWoGV_e}2-E6kZo9<~$y*SOr(iWLq zZ2<)idvE(hZ5nruc649(*|!#hq;MF%(x?+&wQ4(qtxOGRJqH;-ljt?FHZ97Gi*Xpf zQm7OAv2HoHf1T0=rAymxLr%|K6=1mKjatE|g{EyFT~?yM9(})sbtv{{Cj@-_LysL*d9tD1646k4f$4?2B%(Ikmsf%sLYv(Z^41UwL zLqAdZ`48#LwC_;Na?9w@x>HxbH^7gK#lpq7p`qMb=*FyRp7gx4J*^FEo_=Jk&F+8` z30;8`8Iy!ty9U`IZa$Q_TichL@Pu*;bZdovsuZ%Q*pq={>&h|JAFHE)O)(YLe@=NY~8(=&HzAnHesB$g-{bY7}w+oDYYvVKfOnYns z2O*gA2kW>1jC4NH5-hLmXXiy<^|AZ%V>=GROH-{`LJ6t%RUFU|*>v#BInAHx%narC zv#9Q_-GPfRZjHxhN=6TU2yAfE%6|VATax}ObCHc};%glDAvU%{j|2bVB5@enj^c2cJQ2zZ_lJnKX4dck{Y(IJ&tUhWu~|6 zVb{(25j_k0q^kUe;U%FN8}*vz z??QO2DI()E^1J#d z!z{X&+K|U5!jhW-2Voo~E>Kjk5CuXV1o}+*-Gm5~WBVHTOa;`T>^Hg#B0t*9-DjoX z=}(vd<`6y;d`gq-GvTm?7AQzlBGhP-G430oI1DdP4O8RZMGR}=GXW2>&xFJ9!c=Q+ zd~Ooo29aWXKGQ;!maAJ89@H@~-aG2JP5hnP>)|A!#TNDhBeKtg!|>8nYnCGUOgE8@ zGC}H5HqS2^B)@2#7FDdU6>R_CkR(T8b8qsILnXG))ZEg^;XryAb9dUM9f|$i9^)hl zW;Pv988hWwJ8#{n7F`xTysfYphc&b$LAny5Mv??1^qx5{ky9*V?R2!&9bT^BgTo{# zN#)4KQtI#yw-=QS#D95sCLFC6x7NYYni z?NrueT4Ay!E8*nMBg9n3Y+*kz+Gq7+T)fsblZbPJTDi;0mEkZ+N>U-R@sfS} zp$fL=wIk9#lsYf!RBi8>;BP%)tg0=*=2Ss`9hjh==Wm7J~kRe6)ap=J36_s!O1 z5+*=;6JF96v@T<}BQt%;5?08WZ7K7E_3z@aMkh%?V$rg1_AL2RwA7%3tu8lB$j4!l zl%!qA#w{%qQ#wp}V4U&xW_Yw(*AxU*TUdd|z;^GVTAuC9%nZ#@dHU$XeH>O#k|dJ< zum(8_V~<8|Sx|a}=5xX#mw8+zQB-dGddbch;dx(gQ;K%}gw4wKz>SPaQi#4Gd&pHn zb=(?{5IM>S5hA6Uba8LjuxP(#%z1jw!3Xc|`z~LM6C$X%oRcHB_)A;phK8JY(fh56 z84hc7LIfm!e(yj@4_IMxDF2D_%oAoiahN29Xg{*CCPD-}Dn@qHG^KxM`F-o}b~kE8 zBo33L5UoW*RCIG>=X9^}jH6k{<`fU^{tKC1t;hlovL}VZBq>BVKeRe-Q{ey<7X4XN z{x+d(gti?D#E0*he>N#{#B4Y2cIBcicgJ|{l5i?0LLW{S`5n^~VU09-WUSbYG{u!V z!yL}9)K4AHoY*4Qx)diwWr$uy-0pD^CRcT$HdB0e&biCNVU13RfW%PwBArWmHU`-{ zWY<4iyr%?*Nm7Uwpj3S{^Fd0#Y45f7w~F(>?V7{MRFE^dxwA6&@vZ<5YnP6hZDy`D zIPzo0(=Fy~1`gBUIjL$EQp5D9{6P19(cDGVZB&8&{tExOj3_0}^e$1jksGeSjf_b` zhzMo4f$Wh>H;uPyR-%9O^|i6I{%6A=s=-qtcMJe7jI-ng3M@o{PzQlcHh3eE;E^}P zQEY+Ib%|PRwqdMs=;)*u+43sbcTYo{l6#SGSfdjtTxP*xojIxV=cl0yF|Oc&CBiZ^ z><1p?CIb$uCxPPY%jVkv;~?;LY~vbSaF8f0$-PLxl8i}0s=#&#AXSa87l~uK2$Cd^ z5?7!k!J~;{OH#@hr_Vz!y`)73X1tm4?tTWLieM4p@O?+?-ihIHW^pd8-O=Yt*3Xsl z!C{R~l7PgkW`lnxwK-&br0f2WOM`Ce;xI`{(jH{vV$JBXUUOS8cMtzzozfu$=2BK$ zSb<0HR&#ClxcV`CwWt2d)K%2OVgH6C)wCH0jL2RW4wHl=amM(OebD^=onE&0;L8^5 z-Mzbbt{yX+Gu8$}7G$p$L6pttPvOPanNuG>*WLP_oqFZ)+OdEOlV{0$Ra{?@&<}xL z6-`)2xLZxe=0+F=&L6(rPA`33SyTP^gqws35NCvhL0prYeK@S4C5))Hz}6a#%>fB= zvk!+!Qo@3eje|paX+3RkYkW}ct<1$kA4Td22Oi`Cg2U=b!XWQdJNXbNHt0N|g%$P# z4{{R^he<-Xh-M#*$l;oO&@c7B+w3bA_Jku963id>}jxJZr;0Ji9?&?FuYWe=M+ywpQjbP_v)=`mvUp)_b2R$F+%{&?GRxf{0zvXVQdtmvAy z<2w$+OH}=Gf*Av89lG^?M*GFgDvT@%|Dv&5R8E#3vW_>G`N`fhR=w^0=^E>R6B)w` zQvGlOy9vJuY*{}>Rc>Q!q^|!KA~G}X zS~zSyadWs4=j7gKMMYbM$xzqTP-Cj;Fm$xkG*qBuQz%Uu zW|#yX*2!$?_2QoNBBN*n6aSX|mrmf^AN>F?avBoxKpexn#Kk8LbHm0BLq$bPRY#kl zHcCrdLseB>TZzt8Q_)mYSEDmD8H`b!W7!V1K6Dml{0Wqye71QQk_odxgBY-p%bYX=ZcrfHUzIf<%%pmKwo^QuhO=NKxz9OqN zH$L~8Zv%{nz*k*ALsX&%K6be;Gn> zVmJTGo*n66*Yz9wYIIZU6}nsJP0d;BS0aVO8l5Bo ziI*2wUP#(C&nP4IaT~pfXZqqWNlH>avN7&!ySaLu59#b0b10%PmeW01ZD9o-omQu& zpD?2`(xnz$_KBo@!D00zNg@?inDw>H>%eBMQ@!o&6Z2Q$ zutq0DKqAa@O5`2Y1V&u^b|dA92c&TrUWgj*Ob1X+($I1DdF4ae_(E%<4ixwL!mtOEL8$5pz`-=}p1eq;no6|F;7YRc+w+_>B|J1zAcGE->!o##3yf6cVLg!+&K3PemdAp+ruhFQfH zi0t*(A1N?i-rF>Mx_d{d$)k7$g6RDNB3^|_p5yiNU$kZ|+qU3{*FGG!3>`-VNT)x+ zm5cITnb^l!3f#eWRMiIO(!{NHp_Toe^_6Z63)jx^-y7f+K3b9 zF;e?7=FXE%S*P9h!%1Z9CQnB~C8s9!%SiF&&A^}bDqWVKvbt` zeaAR{=5zBL_w?d%KY$Y%Ylbi))Hf&MK5$E(+Y)fq6795DIAqKb1n~dW!C5i_K1J8j~?gSsm-M~dPU%7!imfybbhCt>v>+&1pLwmo~ zSq$gGiMW$tA19!laxP=vmFRUnzhKepJFOclUi#s_llK^%1Z+x z$acV;;Rl7z4()NF&bOvo zTG%0Ygp96}g$>nV!2+tIt-UkV#eq8C)z;36y1>=m(#6)n-onn-W#tI*>z#1}XLr}V zG|M1k+1RYL|4n*EyVXgoEb9p$d9_kmI zS(VWuitPZLia4Z>)5eD0ss8xOXVF$1!I^+C5baam~XM7MNtaFXHtQcdPB zvbJ=gPO@HL?PP6lY5lj00IJ4kG;e0$+aX|s?`+T!_!ATwNG2R=FB36{#{Y4dI4xV@ z|Fpv+UC$|{0Rt|X-Qmp{giJuYfbQ@)`NFSe^yDy|$-}$%nvTP2C=*0N3d&DpT&&E< zv6Jo|)lPbg-hq&LkAj)^BXHQiC=+03i}~kf8oO<7C( zeI~f=@Src-=Vak>cXMQG!P30eBUs1B4mrDg*At4{FdQa{UJO+fX>+#c?Af7z^3m(U zC%YGnpK1j0SX~r@{fp9UM?cg%>@3?YdBeq~5kGMl-5W8nl50GtWlu+19;76a4r-@gTVwx*~m7rPitiu|?V&5HM| zjJch&&g9PP%UcYH-hL@$=hTW*Td&S)OG_It)JtQ|lF2ws62$;s0q}0(>&qdEJ_flR z?uA+Tq=rIN3X5LY5B4A59cgj2M<=~Q6Smzlr<|<7VUj2Ydy#Fvms0m$d8uuXesyK@ z=0k>v%qgPXEH>@32ddC6?b)khg{fS44lXq za3Y+N`j#umKM;@^;uqn3WT?O*>{yc`+++00wUIVE^!9v9opet2wia&@CZa?d*&01L z&i2Z@RD;MH$Csq+b$N}$BvFJRYi#O2=4te^FGj~g6$V&5r{-4|y|5qbw{%$Ed6{Mj zD`Btlqx|nhS8$jlim*DeO}-%b(V{X7))9k`oov6U9ubw(0Oi8t9ZgMGn_ru~yd}G@ z4R9i3k|@HfkR9K)?lqK+dS#H|F>>(N75y$&$Eg#yx+VHh`@jh(yg=8&209o0yZ4jG z)}Oeis&S7z$sKbdZo!cO;vfPH;vTdXds76Ka1H&ddv+!FcJD|`n79lBk2MJQ)59FAou3q5VxtmfqP}5OSc0-9&Be?SX!X|Tw@CtYbRR^ zI|}$q5Uz2}Jc+ z=s5#UaOUp#E24??b>bcn!##nx!ZaeD;B(Os6uAcy8G#rRA<~@hAU+W7S;yIn`B5cB z8sP+S4kc_9m|He+&lWqkd|#=4I-e=EMWb}eR@x8uMYYZ?F!n>l7@zGJ&K!uGTRIX4 zwnHm=*7nv;D63deIUP&R^`Bk1$^O5cUEb6*yX2Mn`u)fLsJUNeXRLwudrPsiORb01 z$l0ZGMhvKok%hAh)xh4$dIisFY$s!o;XE7$ei9Mts98WGtEK*xsA<^t>o`#qkoDmGRzq(_WjnltO?sJ1xlCpS;PIaQo;xJ-Ft z3y!D^0(Vp%!N0=C=>^)Sc!3pfy-rCl)4BJ^?O#X7!{J~Gk2wJG1+f2Mzn)IZ^-rJv zpzgN6v$0z{9M%JyPUMHMCW-3-@!5hl_&Ci$z%Hx8jmdg}DKzVL8v-s5*a;_y!m0dM zvo7Wgn=dL}tI{tkbZ7~j$e65zI4PS4pQq|;C~6nD1P{o0pHLkqXd@DNs@A!PlNpHA ztabWvu13UT-CRwWvUaaKW!(j_jsj8Y1S_l9`q*}MuM0-{|J{1KBO!g#sat$c-xBTp zmMG?4+q5qWr>m~oGj?v$;5S$0ahN3Z5&ZYpQ6+M3byUuWCf^J0_HLF)W?aaaK-*Zhh8Dt)Z=cfkK#uHlqfR;C@21Q*7OMpnW@8 zL6>z#t=p3z)~+VPQOH@{}=dEl$K% z-9E5C58bmc`uz32^ya2hHaI7C9sh&VjUfuBlxREUnMP?3wzc-l8GAJ}7C4bHq9z7v zf;rW#UuBN&HP}00en;K01LrWG9;03I%Yyrh!bvLqncE|iIR~drc@*zA>3l2TM8*hz z0Iu0koGj42N~uPz$LV$1pw_88$j)W>D!9KePEZ#Ud5Y}2h@FezMie47$yXCQ{Ww=6 z;<0Y7CQMoDu*Dk4F}+sGN<*y(fyzon(JZ#Iww)oRx!yoE;nOtteTxRHT1#jJq#2>C zGRW|0b_TLfj3%}^u`oU2*xMnkahN2ObvUxExa$QqeR|;qcfSuo**1kD4LE}RpTEr; zw$1or4DH*A;G%U|GjLcqLR(qZJj?rZZj{tMnN~ zn-#}21UKNl3Hd@`|Imykla;j3AJ;KxyKCmS&+dXS z;@m1u*sem}+tn(aveA|L9gc4In>K2FMvIPFmnIr>x)R|Ayf-22f+Z*`k*CP&C3Y_2 z+=NKYTBjf9Y7n;&Y8`W&>kwmE#5jiq*CVMM(tx9gg9wn&F!2Yx!nv0hdkEum>z!)z z1D|PUT%?)B_W14~cAxY(lB-oAZg&s4Pr5xP70^#x^k-&mhvvef5e#E%=Y{p(8~wjD ze$ha6dkDAK5PBlG&qQFWiH7owz`8vjG+H8{a_XuK@P1JAS)$&oxZij{g>aD_ZKNkHb=kNI+Mpsx!z%`Lei0nQRYVJqQ!% zR>YjjQ$F;|_=w{*_N^_y%isiIoM0beYpt#0L>wWxgf6>sV}i(99CL_+2$04-NPJ!H z&bcX??MAvywK@1ypS3r`jrXxbwA;z3v$_uvTbHqwBE&Zlc*_KV@h-`_43m&K0lk@! zqT}j>o=tF}>Ra2|EOe=VVdmbtu?-U{a_y!-B;ietzjpJ9&QVGCeJ$cTo;zU+>u^w~6nZ?H`1s&02`0(hadikS%+{xau ztkw6KUlo+UgkWB4uAHk0(~UYD7YpOY50R$?>xS5#+Sb0WC%0LU zLl0zkTf|COxrVp}#6D5_+o0Q*^bJz(sIZNhB!9K^vLPd&1TEI>7K^ai_>f@ZGjUROXG<~EKGOf1n|Sn7CN}1Hy!9W*t^);yITK$XOc1xMLthD?8Ifk1r zDC8VN45M)N6PZPr&r*kDPT{2LM6k~yuwSZ15B9vwelW|d?`)<=r}U?T%@!sRv>^@% zho&vE4ZVCtL9fRkUGFu6MnB!2(-MbC!l8i?(yPr1ZeRX??7atA6VLZOj0HropkNn8 zu^=`C8&*OINvMiq!2&8Giii}uNJn}HsR9Cmpn!l#6?;JiyI8SeK>>R~edp%GVv_Id zN+KA4|L2|O2_$EBXV1NJ=FaTQmX8ZnBW$OrtK=>-2JTcHCFBEtg{f(@wyP@C!W`{f zJjQhP#$ic~^#c3+>iqwBwgQUdOkAD6F*>GxoUit^yAJvVGK-XS247|O0L`&!>4yQg zJ%^jn!^fPrj$T_I054u2wNt~UwQf+0YWPP>7L*1jF;xJ*v4M(Jg5y2yVJU56^-TnR)>w#XdD<}kf-RN)l z`9BHxKel>SpGbSyZu?ZxJqly*DC4k&jYA12;8z>_<4a$8`EbPzN0hs?UguKVAqIK@ zBf`!`9$8!iJ2c0psY?AFFY5ZoO{xhC2y5%S0BqvLrgAvuZ`xEIHtKz38%)dg2|9@qH-`P~=SiQ%|q_$F9G>b+>A) z*V+}uvRhBX#?7gx8S;#>?K=10i%uC)w7@%X5ZJ_v}6Zj6*V~vvH`(!#b{PUKAm{i))^yR6h>6t(HJ~R5`uA2AE2tDQHzXU7y zhW6`Z)os?>+R7T(tY2xr;xDWX{lBzmPkJUDCa7K%UzRll+TGF$&at?c6ZiHL-+F2B z$roi<^@KWh0)=T~Npv5Gi_5#apF@e{@Ql{MI)dUj z6T4{Q{9!rpsP!K9;MryEG+CSCtIsP9VdH3oXPuGg!g5X1340K27GIU!th;2uuDfc{ zI_IWUs%D&F&6u(~qB9N);b8R3)<0f_;wY84Hg!)No4c>zh6@8Pgmjza#Ht=8z68fCW! zE;X8~73+|huk5rk1ISw;yz+R)w@K>0GUukAFL~bG^%~$nk%J~cTnX&@)`^z&U`QLi zluqH39)#3~;jqs{qdenFbj!g?(kMh!b+5LrTX92t4cNqseZ$(sJHY_g#ljJr66bKC38eVK zb{A2C3fjg>-e#t;>N7{_MIYZKdVSn|bFhgQiz5z% z%KTMNt!onqaDhty(%^=ky1@t6>=7}s{L);T25wU9dR6WA_MeMGcHQsF^j$4e8qqtnOld@1{^O{{u2Ui+woGY6ENYq3h$w(7 zjjJ{OuHCaO{YxkO&W)jq;3U8ae-*l}obS_ihjROA&b6;}lNMiXbGrJzF>!ow6mhLZ zcjO55r77p7=Wd~U9QT$^Y@;{`hY91feKO+ap*;H56m0WtaAsLc^0k4-K+kDCPoXkz@Fd z8`=hklb>ommbb7^^}C%ogloEw7=`sfUb5UgJM5kM;rW}*3~~og*tr^q2_tS4BW??f zFGQ3o{bVE=NY9u)9Un}>N$Hjar`~2$o#XUUh^aGb01bH1< zv5d1vB)lbszI2W1WxdzfUvGbhnD*te7eC>!zo~4Z_JAY7lfXFt^VWmlPti5TR5>_T3VSMCt#HEeOsp5nQ#UjhnlM+MW&4WpPSImz#BQ8`#jPCPV*` zZd^CnwTAH;%QD~Nu%*O-&~g5zU2rv9w{Y#SLyVd_kW?;LGHaJ+bGBKch2S2% zhQovrCORT*@jkE)^hG5*$Ory*MLP}j=r7j3GpKMKpJR0zhhbk7j(@NV6iXydHxd}< zf4JCdm8qqznaHniL_Sv-e2vf(iVv6e)QgF?{B|V#nfUrj*pSLT$Rl|F@g+AL1Y52t zgaAd92sa7PW5%H?nMs>MCK^xj-D9S9u+q1$`pC%Yd_0{IvCEzy2Skac&ox~CHCG}?cgyN6T@Q)+4l)h z*#vn6*Op<|a>5SG!Mw%PeT zYOlKAnsav#Tgdex$N^EJ{`(-}S`#Mev0^$gcO}ng<62}i28Riw5sX9J+MbPHJxO#6 zD|6mhTAs1RH{cGwZuB?&{GSB;yY^Q&y>zQDE9ljP6O&dObirZ7(~Y2jUyb08N7>+7 z?D-Nwl!`y(5xoAGN#ps${~ejb{662Ye#zVz%MOvF_0z+{#J0a0bPgx;zR0hlMBMn&_KwaG8affDX(C~_d!EE$!jOL=;&ySQ_u9)p-DzRllx!X9BXWT| z_`1>G@biBX@c$Z=wtHJcPv#--(@#gwxbKa_*q0_Y?#&_pM%NJD;`<2*ynMKZI9Cz3 z>moVsYgw^Y{Z#c`E7G>-!wyt7K_0=CcUoRBb}bk8TVM&>gi831$acPkzh`8m{=Nt6 zv>c7=the>k9Dd7Wm^F$0aLh~y-Y1mNxJM_2T3--qda zYjS@%hgVYo2Z_LkEP-8jb9{HK)4p*>R;n(yR{zaq97artKsg-EqLCKiMfQ?D=b?xU zPK@e1yJ&)M4*D{~y4%uV-Q4w4f0pkF_bj^zJ3~IP4R2w96I^*mHiEHhxsc!L4FcKD zcYm;w5qa|n%d2kRIStPc|HC~wYm5-xK;%{427$x=W`iIE0K&i9WxL9kq&*s;jx*&H z98KW5XiAYlKJe!iJ`N+q1pE9g;pZZ5!WX^^n2gez|Ne3O9os03lEzAasaST3>qHT+ zRncaA%Tumsu2BKwn?k>Z@kMe4)l5!#64zl2LNwf*Oqbl$_10N*CL(>?@vI9tY!pEg z{U@(V_PvuFTau4nIXB|?&K1MpvKaU35l^xP^w!w7r}FW$9(fyKTku??_u%LMB;aq| zv#@PEV?}+=)1;IbshzKJ*mRCUIBaS}IlaYo2-1wkt)POj!xf?wH~`0?3ApJ$aNRv& zht+4s*xDs)yXPe?6KB^6FNSSiZFnPh%RZ!L31XRN_WGW`Mz0;FZMuaFi}!g9#Hnl& zpfQ;AqiPIj8G`S|P$)lm#(gGhr%uM1!*U(A=yKK~(HLZr6z2)5`8&r$KJcG$ZpeU38tVgG7l0Iv7d@4i2v!5ZRWq3WC3*CQ8);Tr?4PQWWoiBkqmAjKE10HuaDJWHQ& zT0$fJxWyyGgbwp=v1f+?m(vSGV;GFAP`Os= zKW0O&nzxN&Kl!zqmvNY|8pG^?2YPO%)#>FNIOnT4xa(A?G%CkKKJb^@m+D`sr=sUH z=BiI+e7p{cc0=K!w^hkz+u8_4EH{I=cM|q zp?N*F?{2%L`Ywq5cZ~t~^EL(?_OCVu;L6(=aF{R}!`#2q7-XsDctp@0Cw%t|3l{FX zGh8ptwjKRmf>Yg^6}ZMAha6u#u--jIEyj4f#NvYqr@M5-Vfe;?8=rzyn-b?Cn?Q;$ zTwU@4R8;12_3+V}@~Y?7lt=70?|mHhg(Gksg{MH^pZVE(Yp6zFqnWDXL$Ac?kHKO8 zYGVMdU&g*xiP7HU>g3mdN+^d-nzproAz|^}!~p#86={ z)QJ@d4l_u&?WyWefMJy)RpXHrr15NV?zwlZTCZsZ_Fv=IUiVMHHJ)L}it3NaJvyiz zKQH}$a*ji&!y_E_f2r{R|9Y+9(a$xE%I;6t5gx~iD8^x}*m#s1*P}pJkbX^Wp&wMj zfsKLdHoJ=z?Eg|@0RFs<0f)6>WBBhH z2t|+yJMq;RfGclfz+u8@4A7JOg~mYHGsFqf7%oP7W7oK#vqRzZ+C08r08ZZwS)~eg9e`Mqm09Z(HNW%H$$z6#S%*W=-Kuq z30EF6=R=%DFy%Q0@RvS$GW*NUU3w93PHa$iPX2(yTCp);7wLdEBq#LgRJykC!uY$4 z;_LPM^ZS0;26%JqlApcBlF?0+ksu$ZzUhuw0NBNg38RsuA^wjPE}Fiuzrjea^_btW zU(s(L94Wx?sT8e%lAeg0AP#&t5@VkiYICJWvi4qfi29scKLFQAMj|KkHWD26f2olG zf8Iud!-UmHVo+rY(n!Dt-UflggwaUWB5s~9f_u%sp+s{pcX?JHIAbC*ld|EDg*AVa z{^z2O3PG;hs8=|DL{)48E&cGAM@I%cxyGq>xMv%Z0%A#HoQ^tj;}$EMmDX!jC!c&A zCXCC95)rpe``5jid!UnUlF7yFfUcL*fir?By9D5$FfHwJRJ+0SCvY zy0BlF(Hj-2t)#bprP(qqGdm4aJJY$Q%Pr03tluOehq8DuS%k~d*V|jIl-1m9wnEk# zJ$xTscO%jSqwk2MJy1o7)ARo!jekiqxVHNBgKLf&ZlnF^HlHy?Y@k-$MYBc6Dt@kj zO`GE%*Gmmv-wN$m0rt0g%FrH1fq!^0uSPXOnN4Rqtz;7%15$Ii)8sZ>9@<8merW8G z#YG-g``LQs!DOMJ#>D2n2>pN>HI>yclSS3L-d0wB`5LnocCvHKR+-tDS*>8h|J8aY z9kdxC0oj#ivS_yr_Gajtt(mE;joAu&Ycm^D8(DiRQ`uD(mZs>^h(=!#6?z{Y2gR9) z3{H&dJ6BC#M%H|KY;;fFCYJ6jsdgiCaX)m-=6P$~z1UAHS8ddE>ae2wxf5yU!CSnT zCvQ!wqr&ypuUl?o21?g6U1!!w(^A&zKjc4ufZejzrZ$}Z_%El)b0Q)`dED|p7E`$e z5&fUUjvcl)qJbW8jlrT27Q+^l(Na6!05d#xK2KF|Z(Ma+L_)bTnFBW}U} zU4Vcm6!QiMeS14=dn7ItKVWzCll^@r`aU1M+hv8R%}QB1xDffw*3{Bsr74Jxh&c$| zXm4g|XF6Ke)Xkv$0fz!{g+d-_cUFpSd?6j#!LyzC9@%A#vZK|j zZ%uU@l#_VF*VT_xSE%n~r%{OKvmZK+M`@yTL#=5At~zc(III==I-G~Nq#Td7NOYVd zIYKSVbh=KS^8@>i?04+Kj<}s0O%ehA3!i_eV6n9PJd%?g-A-;ifWzRyFhu$ln9Lg? zPHz!gvHz21pj;>s-Q*==2QNQv`oi7~{o%3>uJ&VgzO|&c-hDq`!{z?&+V9!JXDEV$ z7_o2Df3UA|D;F#K%%{BJ)oJE%1O-r<*pZV=xl4bS|jOE4tkpKX7 z2WbNOSSnZ+&D-s*Rj69Eo|(a_2AryHNdrR#>ikJZ29l^$zDEWsBT`41YTU3`nENCB z!_By}xWF(5ajoiCHi1FASmxwa>wm=jVkiz1MqucKxXrg@N<7w?-SPP9oao{jh0eco zFXRLNfYMh>(=<=d6xm*pdg#KOoj6RmfngP5D$zIS`n(`d9i;aFn~#r5JUEd{e$NZX#h|~BO1~GP$9_ero*c*q&bQ`Q?&PWQ|M+D^Ys~c zlgho25B$wW-|)=Jeyr``^2GXhw8;=0Cfoq988O|{C9ebhT{JWLMCmws$;VP)-yG|% z=sfKIwd;1ZU6bFu9eJ{7C|Jjf{Zj$pIU@M%X!`uu#Y0p}ybexk*q{{ATw|G9N6)!L zCg}#WHF(^4;`fhWEHC!|LI5y9ZIUzq)Cm#*rf!to6*0euw)3Uz1%(POGjJmSc=p(< zZx87VFEO3NQL}3&CI=43VZsOiT@bfAIsfrJrFPQ~NZ!^7s-DoS=b{1sDzV75yC#Y- zT@ObdlU%;+2M!Z%0N8>Wz#hBBZC<{)$@H=qSmaT2f&EToM4q(wfHnh`@IEaLhy7Cl zpbsL=`&=?Gra8v)J~IrA<;DJy008Dd!aZ^ga4K_2M+R|%+^*S9wEd2GDU%le%MAs_gk6$ux;&~>KTQTqLnuewSP#bLs2`?ZMa zR~d!3&*~Za&Oh%gyHem;)LiRUcYEB%dCy&1>h@ISuqiu^gLS;vKh^eO2K`jS($92y zcDnN9DRH85E50_@*vann@p}T_(+l*s+&;ouFAc`>V*g0n2a_NnhNSVEw2fO+js9U| z!1w8Y=B(c9WTtPW$6J5uA3W&8MO^1U9&wdC5%_S;CsXZ0W_>S<&&q{3Oc()RE8^C_ zyGG>Ug>%&M4mU_U%nwTaoqHi4_)loh`r)%xN3XcrL`hv|q8$zsZUBfzOeeq6SFsk8 zQO$Lh@jYojs#)hYV2PJoY?u44=k$UOMcqih+x8?5`=g04<} zeThfO-Z!#1Oc;Ry)HFn6_!vzo7VVIa)G>`-_HTaYUdRXjX#*^@ANp<8KU}+9?eNWh z$8nf&14ArgdRo7>UPIGNEjm$o!tf;_aFH0Lcpx7vq1UaQlF(0{ng981OxNKjj^MC= zDlqIvq?Hn8`%9gWV;)#o{{6m$>%8U~d&{W(Y`2VKOmCx9Wkz-2JTR6Q`$qx;m;?zi zB#n2Z0l;7&MF249F2Kk@^~tlYhv_EuR^xr6zi${e5*GlJ5m%La@9rGvu}$04x@V_k z-AN~Km@ooB3gRYNynj(u97{Vw?9IT5^SWLBoqHi4_@DS_^C;@-Ep6X-1I|0AXXW8A z;RXPBCa`h52F*VIt9F6-_~G*2Ma`Nj154^k+fLi`c%5cpm-<`QhZ85`uzxB5L?F`g z;-RV+-L^1N*UngZJLR!ObE|Sh-Iw+y4u>>D6y&G4NjZ6gvAozn5&#f0cFIS8Pu_@3 zenhvrHq8BbVc9S-!B-4Rdr}0306|U}oGqVsc^g!z7hLZUkRyE%J7+Kf*}@wbaF{Rx z19T^X1P0*G8yIkya0A0#BpyKm16aZv7;xA>6&Q9S(&^K?zn*Su%JgD-Oy4`iuK=15 zf=Rnj$OprCg8&Zu#{xq*qONjz7i%|T)w126I%GQJX>0&|FBQ!iF#vzw zxda^66Y8lk{r!s!!4yH}62KDPxda^cPX&g3i1dq;(E3UlmWI2Mp30Xe8Z*H2Py-yb z01#IK!+7TsaM-^V7!d6><7aj#_%>bbz^T{ItIGyDf?ZVRk_HA@bo~tJT!KJ>;koXl z)j^|Om|2#Sj$JX8?tlvnlMq+lxda?0jKBbD5*cAG71>oq%{#HA@5j8fS-*2HM@JT9E&(jzolC%B|5RWIK%|#=e=>UWr9t~hpxSaL!-Frt^H2jE zwEz%T0>gOc4RF{$5*P^XRA!L|fBU}rJ8kY9vSo?{!_#w<{gLcLuW^`g0|1yh`OKxgBaKhc zlB~CCw11P0P8yqM9q$`kz&c*+p9%o|5kcM;hcwq%-j{lSvAozn5&#f0b{Zgnxuk)i zvXx0m)K)*&4{cw&?2+Hfn_&D@ z#Myl3iCy+%#vQ2q5tW0|Hx9KvAlaoH~rsaQ8`0(d{4J~5+kX%3WxnoDG_pj2PRza&}sgssvoS7XPJ}tJqk^vvI+7? zC1Z{5_#+*bSPK$;j0>`!x;gh!_wfvQ8oTxQL!4xAs>fl%kPI$jP`Q_o4Dc@+J6b|~ z#Vd`BW7!(>zv+I)VSiIHMD$Tb2K-1lW;)Ndulnwr1Dsyw^oFY-M6}T-(cz$#NR6qE z--~kZ>~$;r00*fNa)aNTiBw7^(iBq46y*N8I^$I$y(CyPk2i%XTFjeVSJ4xuO+!4j zFQ1&^e)E>buA6=QZc4v7jl)Q!)L0B5(w2P*hz85d!b@uhJ0?|lgDc70 zOGpX$*W9RhSp3Flq1rB=0xj<{)s&+9#h`6^h$bdl?Y@8Xo5GuTTi znTl>yk`biC5_foYuDYk3n$OBnn|-76+Yl8CGziJy0w@k6kqp!xN}MJChcx~r&EVSV z*AK3-53ZAeO@AjD;4dP3bMP^{<655T->X!+N)_NR63MixO$LbC;+o5f&PtBjanVQP z=Ui+9_bZdy1bO6=K^JP1c386L9)G^aIQOo|J1u2BDcPf3o;%4}75gTv8OT9F4mUO1 z=zSh1<@zjE;`E&q9EO)nK2M7T1G&;4Nk$(P)oFakY9F=L7m}AJXWg-#Fd9n#on(Oj zT<<}}5!$<}zij#7Yczgk1rEbYrgd$C>7%_Oqmov#n0~smYV%hdU7|o`6XcOfrjF_i zOQ825pE+5qHNPrTJw@w*$&|-RV>#=Oh%z&gdu4)ay%z61r{VZHFhwTJqXdWHCByqv zbHUzW2X1LhTv28g;wE}eZ{O8wa~+ostLn!LGd%{|A(;JX+^6Xu(J=x4nRa1U*UsvBm?|;=YMb*iDVj!CZ$fA!A0iR4=$T< zb7Zh7nN5&K8f9cDB_qfqi8g+yE)X^J)Y|td``g+3cWO9oB|0V=;#zsIG%LzytWI!G zg)x!N2IFv;FeIaoxZSysdnI2j-}*{+oS$mnFYs6}Quh*)0sg^8lP3-6azfQ>#Y%~w z;HeLBm@p)xhPWNR@%nNbmIE!@NBQj(>k7(dKq(n(s*`L3K_v5R;P%b4woRcYBHdBfPBJ(XaF{S8gRAD|NCx=7Nj*@})k6Vn;?(8W1>1^G7&^F**_0C z+vN3O?BATDEoW<@tC*_R8Nl6oNy}=aw;Ytq)iBD)KxHZyyFAfuilwbz6-L$j) z+Upe^OWi*=#kWV!3UDWxdkHB4|Iaq+^@myXgBSe9@B31gtBk|`rj&p)Bpvio`zd$r z!q|fvnZ3q~8ik(z?VS^(k}2&&AsGWfBr_^1LB~jSL-B*4y-5)#L!@w$!A)%AFkwgr zH~9~4|D9xTQo~`wkPNOlQrQG~q>_;wLLnJ}E~2O%a&je;IeP7fr}{yBgN`Z_aTs1QypM0bgf0RDBbySZN}E86FI*?8+KAh_q)F$tuvS|= zn)fX4PT*zAyPSzA1N{44U#Wjv&xNHw%G}?xZM_^0!%L=hZDJs9D&oucmeOLze|dW% z;mn{-YTyq9^WQNA45g5aK=U<@Un+v8=^9D2ak24T60*sLv;K%a7iR(v6NY4P)lB7H zLNdVrq{GtO1Df4;MkmS@I=C!i;jq6c8N%Nu5jXR+^>w|qC+~ig^s&exV=6mK5gFFI zdw7vILoMr~siDik=tCJ)wn83h^vR?ejdQ+V)G0`qqZ2!BHoqx3TerOsiKota(x@N6`n`QB&ePWD`j7g)92NVhukpIVYq9{2iYh zuIu&nH8YaNDD0oYXoJI=C#9CP35LbzzP|r*zI>NX@PL^aD$*{yz#rf>F3$njm`EiP zH-IAg2y}*Z;)}@b3WfWs(TuXyHC?Yi=Bz)WHLwuR(aVO`+zXPT#opfcO8K~P6b{2n zW@n?7oFx;6vj3B2aBcPL2bW~v3@gH-*A3=|wt9(MG}@h&zq=MTC37z!8Q}jg@$r3~ zl<^G5;iheN(36(oFuY`1*CvomAL(1E{l?H$!={Q{8}@PqJbaYYCdea|jP+nD$q2H* z@a<~G?Q*?#MwYkDVlRaC%Hpg)LNYLp*mUFCxO3`XmaleLly!Hf#wr|!mrU!92j(Dd zX{DibEk^anGrIK5>eI%Q(`1BXaAPAJhL=q1*hKhS7fHY>!bfXvzxk}_jA+XNhZW&L z)*`rZCE&;f{6`kP>cL6o=uZ)H*g1Qi5ex z-sNPl38p_6bo1GGMpxM>3h7PoBl@jS9aZl&hBCu&w1MQ0u~{J=>Dr+OTQmrU!lRFDKDT*LtUcap&^ zWZ*EoWLnoI++q)vO^`<_8Mt|YR5GQ4EPHNh7^i$zH7-7Eh(hSzIf{F5l7ZFe+2$&% zX6p8MxH!%rbmD;pcX1erWEyLivt%%`DUoJ0ZNdG8Yq$&@mTT?TLznf<0v;5ub{qOF zlLni^K^qUuwKoxEa4YOMj6^bxMUzq|&EO*Q>j&E=qQiovT;3}aU{kn|q`G(9_mzyW z59_6?(z@PE7d-k%-t?um3^3d5*^Bq(y>HL`0*c zsNXvGTStO%7+y-eL(Y~xv4xZMdmp`XQhnCYydK+kx7|_=4?Ov;lz@NFu?3wI4@au{ zOMj8F-myO(hvB8vx;DX?*T|)b26OL?*7EM6kvpKGcL|kEkVhJQ9K|T254`Y+@A;jt z=C|EX(Ccl>dNYEThG%oVIf#%9PW3npFPTDAIgmKT_#e{vmo$TGt6x93q7N=&z@~7} z#smM_6MZA15Af%`Bn*oYPC)yz4-BQX(k*%fUsd#l_fk6cVd2p51(Qf6V=#z9GA4qY ztY`VuX*w}Q2R^*;ATiIyIe@eN2yej&alpx{;7eL`#ar999!ys7I)TIRlHqNUExRBA zXR(7$jvp~IIa#wX^u6~&@vY6e6%TikkHeZ5Wm?82!r!=w5KxH@`Z)J}<DOPMM21 z&)(~uQmt8CaHYM`-ksusa{vc#!UvZ~qf#6?8mW{@1?kAPcTM}?pl>*JZmg-de|1A5 zXT1`p;Y`3`!jKZK`oX1S?j@uI{7sYMWF&RQm8|-<(W}ST)EPMJZ%T=f1DqNtzD?|> zqLm#vHYIx>-Sh~|Dw5g+d8Cq&MTL<{rVj1Ncl3G3=xnFO>>g~q$;I!>O!cog$;?AX zjqKuo<{Hc8=AOj`(OGksZO36Gl4QzFf1+JgHFSM(7_r6+Z=`lhIP@aazJ z0r8?%UqfMYIB4U6x%MU`1N_^qKPk3=`MKku?jO?ozn)l(!$>64STreh(hM##zkaZ7 zBAVz+gx@h)X4zivS#|mz-kd_mB;V)htdQ5T+TSf_qBMH(Nn7rmyZ{8@X-!-03(> zSW;Rvzc*t9Q+fT7b3L+5_s{gDaxWnz;D2=Y>Mv7t-q=qa;GH2g%+wl(2}?@-+6;c# zMninumQRw|dsg0d1e zQd+37PX-qtn4Zs&u|%L%FI94kM9Lqault*%xzy z^+X~vh~K~a&lQyxqLPx-yL2zqoinogp*w{-Lnc!`oR5$a@V6OuQcX@*uC`E1pSynva%uD^)xy`NJQ32gU+)R3(G93t#9e z4Vk1mKVEzD_F^0+4C!@3+}?j)HhQ=2g*esE#{(-I@)kmMkhzzT9`Mgxt{y&GQ(pDl zn(~PK=Dm;Ou)iriqSuf^+=>U*yQiqd7>}1&d@$j37qpgz-t~#_g(kXzO!YeG)sQeI|;R~{oHmR3?BMp z&I+8A79rCz_g3x=W_UiTbQ&0|CVKfY4#P_cyJU$)}o&IqQI4DdI3a%|ub$;mn%`Qckm9C&7p!}yR4Cuf0dBK*Arl~gds-_p=lh80qK z{c2sp&hJpT1NxlM_*?L8p%0uB?Fl$L%NaNBdZ2|awwdF$x4 z^#N4wC87`TACM>~yZ-S|^&|P`2f3JZ9*x6e;Y;%IR-RvspL{FD2fElQaC>$pH;OCBb|$0*{OuLzo@6lY9%>)2d-#ayWKSH1 zms0E4L^R!Nh+9#nmAt#Ply=cGt(B|89`6F1mLmLS$D1RH)o+}<(_J!OdfClDz`;)V z;1X$6s-luog&IU|rnjB9-7r0>ueeh?oRn}T;4ooG30M8#QZn}vQUd;Ol0CF0 zGs-WOS<(Dz7w$ZY!~Uj}2syk)Us8MB99XLDH<#(wW>4=kt42}T1bL*AQT+V#Cu#J7 z)f2uuvJOXfDi723o-Cr-p=e}!)dienmLU_S&HmEenO43{bke9Cea!+o4r`ud;NlQ4 zvMF&MvI(U4!WDfa5x1~W*Q3sA1nW-LS{*Us!|radFSs8*yorzuoBur8k((OzIZ`67 ziDF5Y6mVGcB-1iB5z)sK5tj}7P*TH;Tz2!Dn8$!*DF)bK2Y80>>GyOUQJLgRh41L6 zT>vMu74k@>1Zp9bQUxlKZz-KEvl-&@wHIr*RBxr+u;v-#TPCqB_nP#1|HK|t16Z z<0|?**)nV7iM%KJo;J!oOnwBh*WjEH9ukuB!}4Z~hQFG2ZsgYoi(&g%WaEyX(!I{* zZ)5t#4{$A1eZCs-%?NLQ(Wq=`hb4@Vt&gu=&m8p_a5A4k9;qZ@Vw_ZxvJC>vnk!yZ z(Rrns`l*tpjP7W1^5xVAAxT_o!(n(y@{U7VCK7=AAmJhs;AHM4BnkW{eXE^qp{|{E z^!U%B+1&$&;V`@;Ti2!>#6Py^na8Q*x2i5jl&>T|IL}rqnN46Xsbu1iDo7=xD#*nr z0Y!duX6YLb#$m#c3pW zeYrC|R8l(CahFLioRn4~u1ar<#1+0BpapqFhp-RJN5GwA?j@oR@DCOZ^jUJOhUJ@DYGe04yatB}LrMvVzucXaX|s=g(hlC{y2~}L zO%~Yn4Sfc8TxyYM@1?m*&FK4Kjow;-li3P+q*9{1Vn9`pD+a9h^e-~dY@Z+ez%7Dh zHuWq{N@j@bqp;maM`^7TleErGkry2>0EgkF)H*{~a33T=hvUHigtqFoGJ2NE))NUy z@%Qda;V`_ETGyrm#I4P0vk&nSFSOjmdMFH>*{46)3N{mV!*9++Dw$FVis&QIrEfEX z9{8?W|60>G&>~w!C1?;%GOG~J$P}~O zdRXWloKVy0LPkBirINXqh(5so;iCIlL+8Iy+t)G0yV5?tJr2W5rgd%lglrlmS)qPO z%ba;6Qex-RwTV!-f=MQTN;0L$3w(E2OHSzbQ7jQv_ga@`_2HA4L|Qm%{#xJacD-s*MO}G!C+H5364zRKl&*4rHDSN zX#B{xl)`nAt=nm8eC%@N$I(tT8`t8bv>I_$IWufh2b!5xmlryFiraPkgv0PsYTcH) z4somc`FL?o|1!PzP&uwSk^%myiw1XmrQ9EO)n>)KR^4EP>0 zdS}3p1v*J3@oBXk-m%|4h$!>lF$JKNQ&Pz|q7wP;m^wW+sFTk(q$iD}i62NxiNHx_ zE#m6=BDmN58%i|ya+hcIfiouJu;xjoWfwL^B5v}tw^%Z|i82!88Bb zcxI)$*GpEs{f7N(?*+@_u;xjoWo#lAHj+_AT7~!oJ(@9Jd)Hyr)#J2#vTq89g^m0R zl@`ZqRCEuw)hh1u>7bW zI$W8`y+p@{>o9Q`UXrb26Cue;WI$TF%nxg$W3)``9nKGq>LjIT~2}$CH{W$DzN)mN}>=cjwF12~npzU5q^V;MvF>I&ga>%GhAKb7W zcPa(j3nVdXs;e$d1R1*xo|N@r8&j`R%-r#yNvAH@i&d-;*UIA=-zKU1%AA{ezT|m# z*K0UT7!rfExtUdyX7v70rs1>s$Gm`~%lD|sy zi4l_x5Sm;**;tzIwN*>+cT#+w#S$3KiTI(12a7)oB1+5YG2$z?_N; zR}EebWO%Q1eK>@*v;x<`K_{Y7c6;Dbqq$nK4w?DNPAfBTn6M-xNc6#Vj5tgflEDog z1eS~>syxy&M-!wcz9qxFzwyNEN7vQ!?*Fj6ctXk!Cz%Z(8S!k-!AgaCK3xsxss*ZB z;xN2qTK8I=smPb=-3p%;MBLFkn40y|y1jX`Zk+`FS|TL_W>=T#Mt^W|*?we3e;kIF zOzYZIhHM)5bW>j|?PGdQcOw_Z95UW1uw+Wn+zz>9P|)RDGKYp<>=QiGP&4At;SncA zd+6gNV}sl~I>UUXM$vrct{g^Ag6fIaI7}FlQ9-^maC$y3f80#%tVg1Ec3X_3Q@NMu zn1KKCOTDxw{>-CA?X&W8QINiY!-OH3aAbh}=bbAK8h#Ytx{;%wsU1jPVdzUa=LW7Jl}yDaiYOzC-k-;} zWX^?EZo0zEUnWz(w)k7&Q0%fT?s9V+hL=q12JvOcz0-Iu-v<{Wm~!|F{5y{;pA$%% z9dVkbkw2lDbsmS|CDXb#XJHHyz^8z{Ztx<;U&|$iwqISy$X8t>u1gd(8GSlwEN!K%^g9% zl??Fjt!a4Ii7saGZR3WdZsOS=a2Q@Ptz#46Z&+A+H@U;UZSm`M0u92yTh_&DgH2~h zaI)qB`;bPTQWS4V$2b9~NWP^s>B|1c9+i@G$Gp+u5@%IKaZ=id3J!L+{K%@6SNFT* zo!Mvmy?7i(A|jzhdRgUmc2^$YA-hYObHD&zNf=3F|VN){q z5*-%sH_|A0X(&>|EH=F%b~CLi0EdxCsa0$uq_hu}{$8a_ax&=1D zYRIg*Wal|gtkhF|cP_Z0|Ag`s0QMo3k~Lc7CzVp1APXUHKT7An(N+2G`{Q!H=+_PB zIO~-#Z4)wW_zQ-+DLvQMuPW84=d_J8a2Q@nt+Qy*SeGJ>=!<-Nvl2JW3+le_)HgmIV|p4eOGLa&K{<| zxA?FPvw%ODO^`<_nF^!|QpuP|3J`rNd@473PS4Q`mL6iXbIjD`ILYAdYr99s5`UePxuzj=?t@RDg=n|u(raZTmuq{jF_9SBV)*!r$9fv*YX`hEe11zJxeII!JK}aGBnJHZch`tKyl{?M-r)vm zhxtLNI1Deb*0l*HCL~V;K3wz3RJ)K_-^=2&GJ9={%qFmxR5I{z5K_q~3bG(U8(`rb z`BRw{9MOA#eR+Q$&iW(9KHCu2Gc%VY*Gnqsd1gu2e2`CWz+rgFv`z~K_d$aB_HUhN zSr3M^(M#zRKIuV7eHh?m?jHgwQVGm9lKKGhNF`Q56_sGg zhVQ6!Zr+4Yg*Dl_sYX*w3mlfp<0Q5n72HmFN!wYGmAY>FPa9r#+1Lh$2}5Fn-j4?S zrx(Qpt$J6e>T%q(gnmpZ9f$o*i6Kht^a1@H(fxI-_}M=6!=d>~Paf7%UPS;qkxHhD zYItoRNL1?ZXz=8VQg)1x{yr%p&QEsYB!g=WI7}Fl!9@~qA-JEY0{BfNA}Rs@iksv5 zge?$KBfa5#c|^^_*fr`=agjd6?s!*v&Cu zFPRS@k5pn6RM&843Nluj?eTDAaoc!ZSKD0;Uhc-&v62Jgy7bhCjTY12Y8TD1)-{gW zk$}VS5-V)1X-@Hikxhv-qiGB7FI;1#R8;zAlPju=3v^Ypr|j)9_O%7PK%dV!&*%Xf{QVG1_IqEDxw zlBxTome7t)ICaG-eo!vp;9&UR5~-9ZZ@7k+u<_l&m4}79p46ag`4{C>%pay%$XTz1 zX)t1Nez0+4=dE=bLAUms$6nZNh{J>-B{&NbWGWK)+cqQxWPBf~S+KGuN_LFM9ULYM zDM9nNVQqWxTkHyr46`4u4GTQ0K_(!j7MqGRKxZeU!|_toEAlNRSqIZ)Wp2i_kaE>$ zW8^>R;iTk65# z+BC`tj3w6+JNJM8a7hNv;KWWIT2)ZLP|tCg+l|$)CQ>dA5Rw7@hFTGeC6xNnv+YX~ zt~_MU$6)ha8ERm6Dd%Ih!B}F%TsU>W%88q;0ANH*bNhIYsk(47(QjR~u*HqX>>wJ5lmTebq z-#vIz0UQ^>><@hBO{5Yo?L!gu3E`Dq`I&c2C@soYCQ2KZ0Dc5-Cz>JC~V8$G0BPp4nOVa=0F z%i2_d3@~5RJ=nUBHa*DS$g-fok?kjN zl7VVbsyuUSn6~F-f90Mz0cpYeaF{S813iTxckSY&hQov*8C-J|STc&J`z0Tae-YqD z?=`Oi*GPqDX&l*hy!S#YtuZ*s;O_FoVa=0F%P#Zc?zE+HFA-&c|Mz`^^49-cpr6z> zw@cTfU4w8~^CZ)NV99M;lh^#tfHIz2O&SL}e4?kw%%g?i7-V6J#>rPQr}U zqw>`l{!_)oFW#Pb6ek&XWWvKN2an;-pLF+Y?AID~w00m4BasZ+8xm*9{~?WkNi(>% z`t^frEK`YaK_&x$|7c~}v6qWGs%5L4-?PGX_8S~VBAHgPi5Lj%N2Nb`*H85G($Tu! zf!?vRKJQ?^T>UPx^>WV?mDA-hwDj>y=AP4cW)H`KOe3LRUTXYCDkT#s3MmQn2JKWo z*NCE-&lv?D=Do0=)DC-1wg=*wXg|bFUgnm%hojcR)BQJ0!(qaZ61d%AbGEIr<5#Am z`MQI8_w1W>wIuLYo#J|+XiA{AW1Y+EpG$|j;V@xH2_z%8&L&N^n=|u}rAqOLt}Zp8 z44CDZXVY$m`2ZU=_ZJTR&U9E23OL9JKDb0GCCcX_m7_P0=)EiMYSbZ8 z`f*4!XNVwL$u7h*zC7q{H`RE?y}WY2iZy4VaF{TpBxqCu{wc3#AF`$oT-p2iv3*Qu z-{Uw;7*a|>+;CAT3gPt2?Z2#l;KqtL6Jl3vdUONG2f_SHsT5t^Mmi>{K>a=6QZmWA zKYUAr40;T23W6;x+lCW1ttPigJPmC@U5zwt%g zvt9W@>@y*8H@o04yk!398XoWzZ{ivg;cf_m9mrZFAsOKRdd%A=%9;zW&hM#lsQrdD zg*Xf^nbx%lqK{I-Y=5Z}a?Aq@%fH{3aGghG6XcP1SaK9mrW6f~_>M9;ea7l8WGpg# zCAPO{o0;weT$J%fCZv58e_5+1IkEa|x>HB5bv8Im7?O!V+>YnI?7YvZisdr#A*gzC}KN{{DVH}2+3~tc?9MF_FRoVnneBp{Rxa+84 zU!(|ZzfVX8H~Wmk@RDg=n{YGqR5n2#X_Rs7PazpuK`!GTxpLu^;-D@J-(F+)IQCrF zpR@jmVX-grKkw7MaF{S8vlemVeYzTzdkM(^|A1$%$4@v~(4scSt6bMI#*j@&tL2Tn46 z$b`&DbbXL6Y$Z{KNwy${UyKZ394D_iD?)pV`raChr<&C~Wmg^NNTOp6M!?Ny4 zAte*^*bly?^li+UyakCBssV#-j*l-97+jLNY&Z_XOR05j zf``FKt>`zhfVO{7x>r*6ps$88gkc|f*yTkbQMJ-HVq9-vpkba z8W(ArY>{yY#fG{OzYZo0V(02^Na~UyD!$u*3-VAe}~o=#37hus5&fF z^sX4bqfCz?DT~gtH|QRCuyCf~fNDpaWI_pUc?4u|0-)4FFP zl8Bp5mH$~+CaXZogXuEhX-yuLdx zlMQ2XrH81;X&6;@RvSxsw+Yxw8fEIx)22wzurdW17H`SiY~EY%vR2}u6MA;qEbMcI zLXmsD`aI7WT3)JJ)Mx1WPm;d#aTs1Qt#jiGqQp-7(3g*P`-gSNYGB2QpZd6W@a_o6 zfP7*b_J)mr2+06{6|v{}JzmJD#@$lAG%H?aFb=~@rgdy0#yHmzSKLiI@PaMeO+I9{ zg2|*(QbmD_R7$0S+!tndUU{Fv1P9${i|OT^WBXxWc^8Jb2CrVr6dS9fo#gxVgW*W6 zDjbHFl6_;1a>g|K#RA9vSy=m3rp>S))G;cpr(8giH zkjz8y>D z46HiKi-)RSblbv6T{~mt?UctBI7}FlQ5H}#xRrDqCJf2I$~^BC2vp60QZkuCC?r!M zh-7v>otu`hP?COhYL!LI;QXIB$wVR(IyO9@El574maZQjqdV-OHx9!~hWA9(utncf z7KHru!*I}M`8~#}nZwj10^9r7Q@NLjGQj_H_NdX7C#N!ke`=Ioy7xLChv6mDx;DWZ zql{u}r)&z{rIy{p^vcjlZP3cKpdAy{@V82kOSP7`8B7>ZZ>#6pke=w~?|B3#8QcYm zIE+LxsB$22mi!;m_?I+;YpY*BxQ4&Di#uUcIB4U6f9;9B5t0G^tU)=4`>Wj4%w9HN zkETiQ7#v0-nO3z4rn_70GIeY8JQmV3rZ_>~s8cg(Y}wSdQR;gXA9-Gui!kJ@KVtYB zjU1G9MxqPLHBBe%L9|(XRdx^#!%L=h=Qd!z#>djbr>={tX5QZJp2~J@QOo(gWPrcN z_>ZSgN=(%Edg5T8dgekZ4#P{Pb!;O1?F;+^5@wH1>Z=>EpEhr{){{+O6TDI9`jAm0 z)51H_UEhTGrln694mju+KDb0WES9BuR219{$oH@~{KowJdB222a+HY%yy|y?8 z@mytW+9yd&mFX{A-KS=!Ya|X6mXrj!xB~cZU>s_&b(y0VH!IybQ0e*+9QHS*L_GJW z991OlX=E!AXQj7A;tJmm(1N@oM7+NmB0Y$RY)3fnqr3n|F#i%WKvOuR(MlFkJ4SB^V8B*ITit3+??B?IrOVjPB-SnJxf2XUKlN3wsy13R@aCGGyw)ep16G)%Du#x2>4sfx-cvE^Z~tS zy7Sm=8QF~Bhj=->__1C}}XZPZel#R$zVd-*!gYzx@bfIdggUe^^_>%w$fdi3@8 z^ie2;2pD}}U`{F}xcr3g=o5T=MkkR$y4rEC`n+DyP3A35N^z**r+tbwEPvSO`8^oj zGge~xIvj?VQhuX{I7@&*KLQbl$zh|!KvAgo@s&$?vdcg z6cPB~(&xsEqQ=5q8aINoPi*?sm@%_)2ew#Y%cJN_8fL~I{ZA&!`w4R(kcdOE&mz(9 z1hPZT`+g^)eb_$L)Fhih!wt-C6GE_SJTy@dja{sWh%Q+{yqy6HvEka5D7mqq|M^Ec zqKu>J?lTcjz8l>7fvayk(md2P=1O$&=~ZKNIjNyDA$E#KwU36#L)X+qvv*b}zz3 z+MoH7+ub*_v(M&@y_uPCC2)JZad(XpS5K}PfBH&GE?6{!NUBs&Z)fh*M}GL`;%`sL zq@5=E&&of0zM-!7xA<8^g@F!*3G)Z>7d>BILG7`5UZd5UR~bz^{J3CWGhRxj>9Zxw z$d$UaGa_vPH`9uQ%Ef#e?+bp{Z$gQG64C84O*Ac!ZC$L6cB848@Ai>5VhWT*n%J;c z493`Ka>-mdeGT8d_t7_Yzb3D-jYrd6alWH*^eRm>9e8l%+!kZy_0u&Ir?shmYzorE zhBd&<=#Wekmz+o{>dI7iy9k~KJ309R9xD%qx=aj+^$C9OwdcT;8R(3cCYs`&{|O>9_01`-UKASDJ~)OjPU@1^*)qbUG#Z`D&B+}y9kt*!|zXUW%h z#3kKnqUqPsl?TuF6VABaV*dK4KN;U3O>9^Z8hgw$nWoIqJ^Tg+{3PSE6pZ=ve^Dv1 z9X3xntx}4p;Gh-g4!$huu9WuY^Xd3&8Ik9#8ewCDt0mZtn2|~etMMS8+QSQXzUVVs zv?l6qz2BE}!Lp-L`U7yA>=#&n+QK5fi_6c8dN8AFM^w1f6p_OJ=OLz2?Y%X7JICCf z?>4g|7mT}7`fLd^%LLxr8HVG4eD0qY>O1A1<~d`{#gG%jTELV`+Gt9;-axWuMYn*R z-(T>n)<*vZX=1~&qf+t&{Exr5^B{MX<{sOt)M#?C&&*nBrKyo$cm3MwEj`y??Edud zM(tRni4Ehfl(^)CU$uqLGT_Gmk1OAV6|VW!3IDkR?$>{|Jupp;2gKhmV*aC|O~?Bu z)XJN8(d??dxL{dXDG`nUY7PxJ;<>7vr|3e1c$>Gq%8Td@PE2ZttI`23? zsEB5XJg@jp-6AuXsF6x(86ZEcT&Y8c^tpT!@;p5Gp!l|BT(In@lnMcEC9XBBDp(xu zyJ6V2uQ%zgf!j{%iir4ctD&CX<$Q#3pNq@a&ASd6$OYrBls;R+h$1uCRZ2+H?4aCR z-fZ6)usn40@aA=sT3})TJ2V)G|FMOOF3Vok^N&|ITKfH@z+7Cg?5LEY0QaAIkGgxf ztk`SEM%NK96t9n^m8RHrb7trtKJ*+XUH0bDjr%W=CN_+_QsR;me$^J3>TUx%xS`}k zkDLgiAz_Vus|FVc7#R@zQ@eqK^Ixlt@5aFY@LW~bSN?v7$AWde3$(~})f?eyk)P)P zi_7dsuY5LFC|2oY(&|v8l?}^@l@;Q-X-u)Dx5mCT>@kixJ)q-8{)g~s#CEO z7pye-5WJI2Q%}qS0+U--2>r_&VV5fTfy$bE>Kxp3=(#=Al6Qe-%K1>Q`X1^aOp5U& zP4cVBcZh%gHGLknUGM6*qWj6sQ;VEk#|6ud+Mzz+rtv&Bf5(MO-kZJGmI-#9v=cE; z3r#2MP3(R4(-_U{!IG$9f6d*BG_hgXVRb419$iiiDKK)b-WN^`7tFp=`bb)6a-P-M z?{uq^X_E<56B(sVLTW{X*UrU)GZXLZUCUP)Xd*ZBkDD}h#~Pn?m)h)KSGiqY+zu{VXxdY`jK_u+b1rok9KoIAQY~DF zKl?ZXE?9Onkw*Y->|-F(O4FoTP46te`^tCktdg}&_k;(KCN?ZPjNntiV??9rHFIAN zb>H!N%c*-K3g8weX_Av$m4hCgr`$Cxvuu7=o(gN=cZX?AzFQ#= zyvH?ucc*HbuOt|O@gxmCvjgHkNVT$Tv1Pw#SN#biL=RYEv`9U6S3i(QFv!Lp+g zTL`#kq!L5?*_9Xz4Qyr}bbn32*-;g6ZMUBml}7xl2lsw4Yupgey$^2;*jm4F z9WGc-tO^iM_Q4`tuS0z)ya!uE3WI_N9tI%}M*Bj`UX%uq20fps71d<)+(l=-I}?aix^4{St4_ zE-En^mvB`Pi6H()1B$xL4L;!&KXTB#dJ(m6a>25riVy>C8R;z`{^x4{d|_s;ewuMX zHIGEMZ1y!5EGJeGi06ffsPEq`3e;~fe~f$Iar_@#uOTtD zd1mYI0kT97F4&i4|0|{_NfY7c3`M1&AlRx4;E^2*k{X~ z0)|f;Og*?@SvlcNtX67;1@UAbS;Ga(j)`rqV|~(M01*GjEgHuMSM6wszxe*uqMy%& zalx{~P`?1&qKi*bU5s04m~i=9<8M2v4M;0ZeWsQB?cx2-?$Zig>Mw3wbwAR?hGpf% zHhi862jMr*m8l`sS9SK;HD-}YBwJP$BQTz%!Dn_r{8!d`JLtPV4*P9gQYKePcT0UP zSawWc;|3&UXOCKTvrbdrktbWZH!Zzz0pgz)nsybtzqQcHqwcdeZ8*~SP*nla#D-;M z_5aEf!^DOKhd%unJo3CuJE zhF7XhOCl`*2#MZQ@`&e^wQslO-!(F5a!X8v@gxmCvjgHka_IYr34YuCCk6H!b^h!3 zNn9}KdD#M^F-=R4ppG=zlHm=Bumdt4aJwB*10nuVJ6n=_lEf~zw9v9%+ z4MiH+u+lkz#@-pAk=N#7qmS3-oq<^Awm-K|G*vI`eQeAx6S^&!ph>LHRPg*XZ`T9g zbLU@MJwUT%neWHAwdcmJ?ac+_v3az*Gjn#H&D#OF56V?9e1ngNYUPTO2@iDzKOoxp zQToF)74{dzf8v9FHwSv|YoO}YZr${sg1d3Scx)b>HIpX0{COkjRA@6r0_!h%F}a8W zBrW)FtvKQDUyPj&%O`%lEa1oB<%mBU#$)H4fxq~3@z3`-B%+SaAS%@4$rQJp8v+o2 zHjKxHIRk&`=i>jvJJtBDhPKuB)oT&Ec*99C;?IWh*e7S;|JnTCJ!fy}JI2QcIz-M` z-}&sDD8!!)g9FcPAz48`djJhJU-G&9&vPlL=14<)!Jk7zXWVRbLW}sbVP$RDGnY6z z1^*1|53lXdczd_l`wWadR4-lR@F4A@Rh0`L-`u70oz_gFMcTXH15dx2;Tt$vGpFl~ zpC^C+scNsDTreKn&(St?p6$o>?u?52S89A0)=wPTa#?J#kL6I@Sh(QOIHz!E@;O)m!h|icC~qK_@}$qucOv=J6Pi^QpASw)Dk(A zqGioaeq5;QHucG&UzUt~strJj*f5@YBZpDMYsoU+ianE&HLeM<$Ljv$IoY?yytbo4 zMhAN_iy&#mZU8Q`Td`a)9!myqV_@d&JWGbH*v3WTY9<9lt{Iu9$Ks`fMrX~W$?g-p5p*il#?NZSBChNfD;JE%VmSl<4Ad-#FgD*<%028qa1-hyTyw5vtgOoiv4W;VYgTje>N-=Td^5#h4T(l;2z_= zgA@m#)TG;4FTil=)4P7X+(+M8q1aRXQXQsUqH9D!5`1-8*IS9#)?GKO&sXZ1^tW-1 zxnSJpeKD412qfoiP92zyf}D4EoS4^Lv|F<^Zo2olV(rs3DTDY2jd^iv%!8%6`G4IS zmTSz7_FOP-^Ug&RMI`wl#FA(B6%UjN=+Vm@7~OVYgt=9WIdY)bE=_WW5Ws*dZ(YT! zD+!Ktr6okBTUW-^xfk}#cdcK^BkMPO+?T5= zZ##3rxOIh#Cd}0qm~6BG9o$f=fjDC*1UD`IC_B8bPkhT#VSZ}{c9Bd*xFecOm;gdA z>&5o#B3MR?QAWeAz*0gC#OI7!?MD(3;0ijCk?4T+o#fwMbVM!sN)7=K;Mr#wLgi zX*6mSGPy>k)*97frP3(U3vjKjHT&ogvoOruU)aa`854dcN|2Yz3YNpt-?1U?K?A7W z9UzmGoYd0Tq>LHD69XMg-k3JLF>QHbTm&6>W7_e?5LM)r7`3%3yv~-GtrdV}Kx>LJ z3tO53dz*Tih5n{K<`e=8r7^HxYy#8h#0HgGFOrEx5`{*ima64)qh2c#t5ssPT5c4m z;f1y!st7vs2vc;3aA0_hu)irRS{NNJj575z!?lsnVs0XA>;d0y>^IOD9vWnh{36X1 zYFvs|W41J5gKKL*vHF>#La5?r3F|3rV~&o7Yg7t}dXZPCt4*R(wL~q`8zeG?8h+(+ zz1FBPD%4to0m`66BNFg`;Y;CTTOCiD#}37%H%CQBh7T0B36F^kG+Pa3N^u2oi%X$Y z%XLPnRHl>2v=XUGrc=s|T9sTYmTPocqd|a;6!HbMnGuoU{VYMmFh>bZ!O`YOA;yG9 zm?KTmmhiAfUkYA|f>)cT;MqE}xD?bM>LaSY6Z)EZm_t((xxPFyl&eJ&xk@Zk$+QZo zPA-*bb$S&DQ6kZ53<|BFIpz(PQ5YUfNeb(|D6C|O7}1bMnj=C@pg$Z!{vyzn4T6!h zEZ9Y}I+0NoxM^(;L$>R}`$U9?nZu%^gu#*Fedv;!LcHk0kQ{6lRV@|EjB2?;rd1jY zT8U04ktk(KD5)}yL8jGf1Wn*2`b%x1p#%n^0cU)(2h`3%!tgL*6vIN)i4r1i|Hq=; zOBcx$XDbCjAB4A)72#-sbxUxgs!5A5fxeO^WOur0Dd<7pq`Nnkdy{9w!_T|>&AeSx zI^xd5^Q7&DA0h*@n;`QJLlb|_-_R{!xo7O2*RnFhxnOMxHt?>k=b6H#3OPZOVZAUv zX&1rsVApf;heTn8>Tam=ypv}1)|YJyZqGw4fJamq=%mOB@o(4dyLWvrZqm*a2|vX) z&exm^MmiT%22_UC;8rcxNEK?eOeRz7GzyJKCsJxfB9%g})XJclA{X#ku*AP@*0ejI{Ep*QpGv!7a23Lp^aUM=8m z`(xiFMUTK$X9@yq=<1r`*1RBd4uK==!#RT4{V%O3m4Cc`M9YyiET_s&M0Q|2NrTVq zfb1;Ws`b*godq6?FV<%9~`L`TL1M#n^&UAYs$uo`UyJWOf_NAhTQDj&9Jwl{M%@UFtRPh>3>e zU_k=SZZa}=?PrcQg@#%Jb>U%A(a^hfv(0L^4v*;>5@wEyVnoTU6W*FIOH?>C|04!6 z;^@inHWB8)m{3zBBZht}0KROAPJV?DX*ej?!C#gJYtYj7yot6yvIbF zgGdC!h|=oX($X(Hx@EW}ELs!Y*&G?3tj1t`TZRmbvIIuyP0=PhI4KlS1geWP!{@Cd ztt67fX-&P&?ah(V<^h;b+imor4A5#QW2Q=XnDu%u>mVPEEG6*$kb?7CS7WMLw^~j2!%Wr1aBQ)HEvgEvfz`d5gZ1%?7b^ zTHEvBw#wBPxK9cWDe}Ome8mMLlMmGEREE{yRwj`uHAbaWrZ6bQFiW6UYc)EZMq||J z#0rsINp)Dsgn|8(1g@Xsj7c6;A<-Oz(A+Z(**?<3w&KV{0w_~pnXc1ZItEnhWj&l zsHH0)US?GMhyLERcD*n8*Oq~6nyx~AppsFFh7XLu3RP_^38epxWG+tv~hC1?mR?4Dp}1loqAncReLV2e8Z z4~I2Fam)+)GccD%2EByP)d>>z2nVl);P6Nx3_4Jgq%g5=OWdx#FfcqkGRP7Jy`88A zLg?TKVN3#C8_dx-YlF6seh;#Oo(#&!|X_{$cX);qvQOg^Xes2{Q0iU;u ziy(`=Rr2v@i=DR$=~eRkHhe>K$9mz?ky;SNr6VM7qBH_rL_>hWC`+G+P#hkh=E?cx zN65%-`9aB|IgwI>GR50y9gqCbdy)!;;g^iD2w@NIl)Xm;Q}mbC>ESY#zXh562Mfxe`w z-&EYkfWx+7G9h-wQ%H3hO^@}$B~`ux$;_L|+6VIJ5Ml`o0sBf1%?bO!XtFRWBs?Y* zY_-{Hv-^jD>>2hNrQOHsESLjra1IhVG8hB9#ooXnlo+gUcvSJ1x2N2hxM@!X5*K zQ89h`KogMfEvvdAADCPoAGhw}CkLaW~#+20ZcUL15an1UZU#fD^g!+`jsvK7H@B>*)YB&4Ua zgg6hCLJv}}B6#(H%AGM+CXh4q04fMd6@(Gi$uwaQd|g;KFdSx`aPk`*VJ&?u(a=JS zs`o{_DfBwfS}s#m5m>ybfF;%{UeY^C>9c%KGu$zC0-eLwKjvGx6k{=m>pXgH`ue+!KEn5fl7)DTXv5E_<^gl$7C zQ8uN5Y9y>qG_yjCPihlkVhM^b4UfOCct;ZP8o1G*6Ozc zBgR%YlN5@PM89vna9I@@L~&Xb_?!b589^6#?{idy8djz%B2X4ojd19GkQ&RuKvdRR z4E~YfEN^cvphd~H7DE9-?zKk7jgpMKc#C)u}! z#3?ldia(=48cKZPU`#8#k2yMWAZi3S8iL^an+Ad^^n*SNHeI8^M;TkI4lKldx~rNs za}PPFIf~0uFtByNZtjS7GZfnV3{%LTR7Td!xa7~KY-eWfy)($3&vc7LirNm z%PCfUrEA#-p$~H+!Ol$y9W>bMV=y7U$n`SG1o1z0e7@$1f4s0;mGxUZ^STV-f)NJ+ z>OCsMYH+KN$+WN_7IuPA%SB>XJ1G+zB;dFt73-yHjYyoT+rV7N#DQCZt5;aGxu-eO zx}M24m!Cxw|DS*8P97i+*5e4smEs=!*t7xx$W4l)_`nEEwX5X2uXQy%QxR3%p^^+u^yt~ZLo#Y}5mT}GPb$#eC7 z@M;REs}0gJGJF86g{OBduv_#*xANJu@F|u(`K5Q+(?dAP?e5n5qe5eIq zO8X$_l71=eUrPJ`Lun_?o-{R#NMdXR?Xd*AT=hEQRrp_>Er6^L^m?QVv2_3O*6Nrw-JgxPFU>- zs76r=!dz-f=bgspJxPrm-yizNkT9RgbIvP=?UT-RE5-#Q4qw!JHZ2y3B^sGV4ckiT zv?>E^P^5$gzCmS>s9^DkN^7JRig3GuwT7HHW0KwL$*2g7bJ0F}srqq!zF$4;ZXgK8 z<>DFKm4n%D8h5N+!~w(i1KxS8nm4r7MKdy%4I_S5_KX!PWg@XrDU-oYT`E|EqgE)S zN~y{qHYg-=8SJozzV^f^irf2YS!yX#GCDilr<@}(Y84u_kEQjF;wJp0$)YnwR?+8B zsf8X7;wnZ?U45YT(cvgEHjMZ;Q6I6D1)W@LFd8IAnaC)S=@qc}M52-!)KDZ~Hx(!w zyk1X(As-HJsFdPCcLbO-?BiUwr5qptA}wTg$fT}SX89&8YjCW~=Ga(jgE`=5*81ptzGU(Ob+FHlIivQ5@EL`0Jlg9*ZNJ`SOJ1w8 z`O=*l+qhuFhlYC3rtS)(RHBh6)iQ(3pp$5g(Ebst6>70wCeq858l@x8nncKo+vz4* zOgY9gCT9t3wW0W_pZu@SI5Wj_vP-)%r%+&QSPLRyyxIgNg?$<&I;BV^H5hdwsY)u< z7}XM$Mg%+k>6HeJz@a}2`aq&1ik*K0m?UhvCJT);nVj#D^7&H0meps~)5uK>$nteT z#RrztpS^xsK6Y7!k`-QZ!R%(~Y+^7d)q15utd<#7dZkVwml)(?DXhy?8(PigaeboK~|?kPG1n`NGJF++P#!yXyN?)_X=Teecqkp4s2Ld z!&UkSg~NssUk&O#n{Z$@N2St27Z|pQ*2?7unaH4(LS1fDs&pDT7&Y`QMW(YoIHqvJ zd6|!M=b7w*;T)Mbt;BSZEo~~$ht7TN*KotHuT8U2C~O#Uk+2tv!6=p}(UQd&xR4t1bfyiG_Vsam?s%@E>zGVltP`a)TyL;jam+m8fus$rN07hBAf#1 zh~>_3H~4&}W5WvfmC9h(8(C+<9|$SevXbTM=*@=#_i@EQmakLWtCB;!!R<7ufTzD{V=SStCcG#2e)^ttO6$dDBb8F4SYd#fZ%_q=4w~Q+ zy+jXVi3TH_il9--1$g)nb8m!hmk7P<*dA>-Cw@k&;Y-URf8wFIr zksO<}sI_G&7o3FBX{{Gqsls-L2sR0k>BM^2=SD7;?3KH?;hZ|2b?zWMl zxZxS;$-yQ<*jYy`(!c-^Y_|&=<7;$swFJ(Hk;^1tFtu{6pc%Ym&5|u3^rWRE7bUD~ z2^RJa3-6B$|H#@t;UHL^=wJ!h|E>L;NsA$ECDIpnSV&nS&B?NaJDWJAYOM_Hr5bjl z(x||Z2)Y1Tkyd4dJ-y{3Xam7{$S|2hWtl>pUxY|_>S8;hjkhR9&}rF1#7%yvfMrq} z9s?Vl3H>Z#DT-q^I+^uilOJ@mwXk6rc<70Y@TZ0%2>V{CM6d<6Rs`cz0$gw-(Zj|$ zRL*r_5q3SRAYly^v7B&(fz{Z4X}qLZ64Qs~dz$2C8jx1GsdV5(DN=}J5}6SO7Bvd7 zM4^*tG}Gny^g<@S&Rd{(yG0cJW`^I^@Ft&5FODC7;v^Sr8>7Qyn}kc@g^ZlA zaSm^opR|jB2gJjlD_1nh^ zud1~0TYJ!u%RA3n2^WlX>8O{e46DJdP9oQcWH3~vld9k>I_Rw{VOU-(f)kfia-&8j zNZHZ*8eX$CQ?aMUxuqX5fr3olsjmTG)9T7=-zLj^3{xl7Jg~(rH>G1pAw?xzxdO7N zZPn*H>i%%bd*Xy@zm;tzug?V|eJm;uD#L1UYXrXyF*?5}HF`LJLakA#WeTX|WpbrL zq}58T=T4CRG3g{x`@7g!N1!(L5dgbAkQFSvC+l1Mn}k1nCMK+s4Q{^(cb7_&=H)qL z+SAfY)8Evl%KDH~+J?wNHjH$9>{+OW!61=Q3$x7Qw2-}NvWwh z8?)%{PzdC~g1KrUBVh#*^jX@&!ep2_fJ)hRkVKTLYleG0DZH**L3yV%fFcBb9F=#H zhIzFs@2I$^e<<7KxnWLG|4Nk>^sOIV924Ug?7o6P2xJ)`a`^7PBYBT&K6+Jce}2^c za>`F!Fw#Y#UZygv2Dcj6VNzz4tHHlTu9NEFuqN=`(x_pJNjT0>sy9&MNOZ@=8`4{E zU5%mPrf65!&*^>$hSOB>a*a2FB0(U)hMYuB&YTbwfJfT{og{rO6Uesy(s3pBxd*D( z7O+8TRt+yh%6p@ds|@ny|2Ivzx2AV5FUH&qR?yXH;mR z%PUeD)k>VoGRnkowx&WZR_mapO$nXRdPkj1estw1@~*CFZI&J=-Z zK{BMui8}$mULZSd$r%_6bFvlsE z>EQ5UShfarx6<%s)SlLXnw7JuN9~sV4TFS6Za;%9fThM(ttcCyerHBr=0qr&lUrPRuCL>!DjA5o;vS z8~ZY9&oL9)j@R0zDofHNX3G*AmQ+apsJ&FDhC@!}aG110ZcyrU3WZXsS84Px#|=&f zBGs2sdt_`cD|>CfE`raHB594YrN~_(>2`N-dPL_J`pP$IuTW}Hm@p6m8}GxqUzt*; zHmI~(19-6;wel~c_BI(ptMoI3NO}WoA%5nlz0x4ksnt5M3`!yX=-_w?u~Manqo>8- zoTW=K`ukDtLD?{I5@SW^B|x*3qbaG3Y2}-l%=M9YdGYHa_3htfnw=g0$d8qJXHCWYm5u zV89-==YnOzs6C@_*lz8*>{S4_jEveN{_IhEE*STyJshpBft@IfGB9bdZbuGneW_Nb z(TXLoQba3O<@izihQQ5?jM^iM*rWDbFw)1Oga+>j1l8al{19OZUao>gPBO6`+G#SC zMhokl#4yq!(@FkaqxQ(cjEveNyVxW2Trkq{LFQQpq$w8ap=Sw=Bbf{qg&EaqtxBqc z5l^)SdM!#gA=-Y>^S?K0k6h2ls6BF+J!;PdBV81Gu4|1V75L!E;b15+oOrI+8DYpy zu7YFFC1QhCt;@-y_IAVcb`KPd@MC9CZvY^nyKsAm;n*slBeNGr)xP!u69WINT8Iyf zK*m6kne4HAE*R-OP+4H6lw~j)VSS4d79*))Aut>oCsU|lJQ|i&h*WY7oGEXw);W1B zpL10^MJJGo+FR_zh=uOHZa+yM+(u$>O3AC_b=mPvKTb8?^TNxz z@JQxb)8ut@RK`2$EHhRbX(bYiD7Ev-!CocXB>j0vtb(<{7dHTXBUIy9W9dYP$C%Y z8V))D+}LqOvgPG8&kbc(E z(W1qdZS=W(whZlXAz2fAJpkaTTy(z;C*W;SxkF=x*K0ZA^`}qiZc%MpQsMU?|Juc8be}ov=fmZia@naJfYYE{^};v! zc&JvcD4Fn3SMUQDES+|0HI&cC*LfM&}w-;Z%? z&y8K%8x!Npd>LRo64tm#T+O6_$TcJL^jN%faQq)!uyom_%q4ZhXOLQR*W%)z+!e#O z<}bbdR4c!7NGcna-G;~&aQb?yOIwllr-M4LB1=2Fy&Qp}0&uFLEIr2exA^NVcdo&b7f`$+?xa@ozVMD>^)-qkr8)v(|$;erX18@5><9!h|Yj}aJmiA z@Nl=PZL7}n+i9BWvqRJ69MdY02GdRup88h3)Y>uLr{stE;y@rU@wL|x5 zl!YxYaj^j%+}IhS$$<3KdvS*j$67S=2PA}S+*HXHj~dJukTBO4Nip%i*7clF{PESJ zmDl)j!O~}lGL_VkfO5WKue^c++CJ#jYfEDNp~6B)9+H_Fsn@z}JYVPK6Q2sD!{FHTZ((BGGvc&%;K`SsqvMjb`^ z*f1VLl&Lbi2n3A3eP;RS_=CpHy%PNI7h5(cHJWmeA)4x_MRewE23kaOd;eYDtzRei zy?fU!Yn?B6CbRGpL$nKor+fT|yg{4GehX`tbieT3{PtY19A$_`1JWN>Rox!`sbj#3 zTw4nl*17{U6VB1oysj*(#Y% zUEb8JC0bW{is29!>>}szWaiR@t!;Be+_@Ozu>)o6HXC)`Ipc`+Kf9 zo2O^@5)&&RO>Ec)E}8^xtcv@#Q`(h?HwIJ!{O1dZ=hEgs%U1iSx)oj;vgF$if?v5{ z1sItm>)2N`l&I3JjN*Qeela;~Ko~P;d^QCMh-b{#v8{S~ZOgYk(6ahyaOedt7`L5b z^PQkz`wSt<21w<`u6+CqxSji}X>2jS;I-HGdrurvV%BJUKP@yJo|X5X)y7TJ71c|Q z*erar0%>By)^h67Zk8^!Nsl}bHFmJ02`4`$^%TXo^0|5Un;|o1$GluU4qr$MO%)d9 zHMH=5CRSHiyKiQ@u04<@Hmo26gJeZmOyfkvu{Aw3;k($m(1gOVd{J#8O#Q>??5vmM z&%kq9==kG6`y%%|_vNZOZ_K1U{*P)P9c)-zPT8>aEyHDn5RfL^$z&7kDx^s`n3A_~B7#WX#>oLdvL^K*a4({-(3qh@cNhAm z2Yr+7#))d!i+~%ea{H~G>b`2*nMQw+qKEmC#>pPY{C3xXkyB@u_1`@5Sp88)%EoiS zvZHa*7x3(SL%gSxuA^r9i6gfo7KDF`xFbIZbMToR5dT*N=C=RyOm6+64_5}Qs~sK7 z1=bfUN@yH4{eYC^@lVAJSyB zoYOcVGC(=$i{6j!zOA`t@shDVyO&)`b$AnLMwx^M?OIvur=z|T&-g^Th3K1e!7{ng za*DPTX)fyo_vW?6s25#ps42ch^VU*|4-VS_lf5GZmOcmB1WbDcs>SJt~|+ z{Xf+)cE-y~9&<*QmE`OG3EdC`WdJVuW$C;}xx76ln)>(MC>cr3@hKp#VZb+nPb=#B zZ^>)8)1~HcDnCe`YB@W3yJUr8zx?4haox_Zy5GBa9(llqWk(|ief}0}+ijR{{?54k zZl5`Irv_osOH(=P?-yNs%UGRuNgu^YI1}b;q=^m7>5Ux3**mCzfoUV(YR0PuZCbj$ z3{~FPu$8(q1`up~hsYa45kN(ZkK zL3$XL&_Mo{5p2B0+cLriZ@L>iwg2v=(&i~;oN#Z%(W`3@nwVA;{j@Ob1@x{K9-@A` zVzGW!Z1WoRW4jmPg4LkOz;|plgUe@)TrhIPT&Z9)wD^R}cA7-ZE35H#JA7yC!g(Dg zK${%`zR2}5#$iDGJ9hbb?g7as&lN38xizc4{}UH16B=<`XxY(J0#bwyXf^wVZd-=| z=9XKl$%cm@&iEqN%NU0N@vl{V)|+xoUkA+fnK}0U(ax2)VDpLY!8+({al_jA%zIU8;GS{wu5rOsoHVg}IF~Zg!$H>eN>76)KfVD0@ocUcb11II zGsEk?K-O<&q5a1}twk1FA?)!d`Z>(&($Dj9i#^THP1-q{xkP#67KBJyKDOa(N|Ln@E z7Tk^Au$l|DkY)mv$+W@?d_^}u)LE%gC5!Gw*ruQPdU13I{|@eGJHkB&ZK;n6MwY%H-RZSD!HgLfRy%c#A zDb?UsBb6&v8ra<(_U(hM!PT(G2pkfphP8nbxm<0OQrj@W=7(l;w9wBKA;dElVUR5> z+L{epOO9o040MHzN?wMhjZuLEVqYKk&)Y|+C6C(B$1^B=bko*!4J!3un zV~_P}8a}JsiXmsXU`{9&sA6^)Fhyh+!Si58@K1nv@f-CwJ=cxd)T+Ux_{Norr0V10 zyyAkw<1H>^p94bQ=NFfo@VUmc7NgO^U@N+@87VHViGS^Xp)-`LG1Y5f$v1`S5?nE7 zQe04{292*aaE71q+^6qejp$lp^&Bo3p%>q^DqA(Ukx6B6$`33&H0X75*caNMFsNaF zJ3Z`mYmmYbP1LHlv*c>DDzwaIY! zpr+=ku{-~cIzn(o)JY*hojT>(@>U+LrT%uWQE{7hcj>?dBlJ>aQ_5BiZsC*(xk{pk z9bsV;W4TBRXUoA(EU^EWPN|g0^-`FMO5U;*PsD-(#-29Cov^74sc86NqDf$mu6A~{ z4P^Ch(*A!AXyb${YDcfm)w&+lsKqbXeT9`HSJ~o%IiZX=*C=2?W?MO=%@M)uGD59& zgLjG&tza=nP>hb)MPJL31n9y=wxp%cw6=tY33!XmKw1Xr?y-y$AIvk^A;x&?An&@;&fNn;cELXg?*M!Dn6~vn?=P53djqhT8H4Kx2{!Z zOIdZmx|7#6w<-(?D73)&y-^dw@(MPlQE$qoxpg+|KP>={fh!#7aH5I`3v*Fu2rYF@ge8QS=WJJtmy* z-cGd}L#n6^3E%v#Q%>73c*hutD6llX$fp4$Q>3-$+VE#(eUx*4U-9>zVH=v{;(|Fr zwVmUYgal#mgqtJ7zS+9oP<;4;8`aqx;f@Gqt9;hA1SZjFr@KCQJ5YY?fHCiM z<%@PR+~1ApMU;fM7@euE=sPUAC zx_(iY{fp}sa_zwdBYZ$f*(_CxmVk2yAw}@5u#cDG_xaAbzp+%uvDbTPDX)a|XiCP7 zBhtca95=IU0c$6q&bmAfB+`|K$lE*N1S3M{LvDS8GzpV2yThj#Pj-8DBY z{^#6JsSf2LeuzJNN{0*Pgc3r`7k-usOdb=MqpOXVn24_=ApE~o5`^U)l!U1n8ARyW z+PLiFvjw{SVSgOzD}8!_DF`B^#+r*ECx*2s$py;}Wk>56^z#r? zsrKHQy`5uj&v%>I(UDGI90tTcaFG7H6;JvYmYY@$etE#$nG5!>R`yO-TC-pr?LC$? z2t<8&n@O>bhCDLVOfpR9|Eo;1Nw{|8#$A6cj#U#B5FHvT!H;mWw)a`DZJveBH0WG+ zrdLexM=ls41K+iom`vUm3x_<01RUx7$$0hWZ++LzdeT3P@{~i|3I2!=GdRzxkwKnx z*Y8do27C72!E{`PW*T}YE*YlL_#Yo$y2GY~n-Wi^P7tfcHRH(zBOF5hC+mb8oejy^ zxx-*wQ^xpxM>>J=i2vzJgZ6hc1{W!4=(phBS2|AEzuKz(yBo9J9W`ceI=wO5?&if> z`HxTYUlexkQfFmQOQNr+EuVPMBkc zagoM!t|=Tb1R2?yW7pY+OXj(EpX%xH`?!R1vkr0TJ1)WU?&E45Cmh_M@LV^p*2}MxHeTm~5e^~yZDP;lfn;2hwq7-F znO=HBJFZrjR^prU67lNf*}dhs+D?7uUVj!PSFG&*;4^~3VUxeGhB*&Eid8Gv|| z3ga+vtrX>gIia*TcPJf~1G1OeB0*SM@SiKNOVMmPQBk5d?3dWSN$8S91#B01n4^8e z`Jv@p9gsPY$3bCB03y>}*naLM zuJQC`6XV(gb1Lg@9kgqL5iXyGn>|lPo!vcPNWhwdw+jyWHnAHQjPL;&Xfu2+!|7}Y zaTI%*KfDoiBA^+MTc@0U@k)YS0|U4J*(;yDZBQA1zp;YTMIL*V`4to5#|a(y%nbi^ zZ4m;oyrww;xRP#dDSNt0*r2K#{9}KeIsEZ8eH*6e2$#>mP2ECI#Z%U4d}iz$SM>62 zQvohmc4|vmz_D2VMJun}zHS`VXk_0Sudi-G%|IFm9r(-)Y;DQ-$cB*qM7r(8Z2!3} z?zXR_Uo>-zq1V3N#xXR0y_k5yee!XNyp{x8m%O@h1|rj~8x^HBb03j4*33EoGOua+ zh|^5nAm;ZhQ2zRM`)hS07a2zu(_TpGTEWBxBOF4yk}ZiFoejzPx>LF+1UH;^%Tu`3 zo8jMmXWUtHgKXpeZ7=Zq^#Ny1jlO4Vy7(A3HQLd2&)Bdv2uC5(g2cxZ0qGi9a^pdt zvOj2M?8~!kO4}PTTrek8yo3ZB4unHCKq@yj9%DK_!Vu0b1T*Q3i>5$9 zwF%6nCq6=8=4^$~zq}E2d_K4an?j?kXXRM$NCtLQ>~g?!nz~-GeEBvSCU1!EzN=0} zYR(GjAheJd$u&FlWll!*W#ZqShfnMDF)hRLjvv2cMPb4@UVVvh)EtY24u87!MR@6Y z|HZmP`InqHJi#OJ?;ZpN`_>-|e3MIb^9>h_dm*P7PS7+O z@x(!`UZGPcH7bc(tk8;d3aQAbl#8-;A?G6?P1xa>y5UTz$6WsrPkygAfm&XRn!~3( zs7Xlvo}{q4VAZ6hR6I-gEsc9eKd%x zh@6LtbxnNEx zC(iXw$G%pfhwg4WgYsz-R@NRJKIt`%9{;P#No)-Vf{P||GSM10A@qwepJmG>7KHy9I zZS>aZZKGqWNz_1yf4FnL?H)ga!LAW<2mta|FV~Mfpx4iTAZ*+&iMu3k*H(v(g7G4Ad6D|9=G)hj5k)B7ox(p=_H8ZKB)P?{sas4q%`+G0~0 zhX=2@gGQxWX%-ebZ5e#KtA6IM!)Jz=k2D+&*AAYwsj4$8(`6Zu8 zhfcq?sN0Bl<`0bq0JV8|llE)nxoI9E~`qbWUM;+VeyRCw!EN-F4ZKhffc3%Vj4Uzvb zsor+Eacd^+Z|SpsX15>Q z{3mXk)o<(G*7XtYNNq44dGObK<)71^{h-;=d&k$$V#Yt`g5|hTisOKM>t^^jDrGI3`llvf%@3))rvy z6{zd*)rGOo*Vp}JfHujy)u~b&KQ7{e{db%ve**2QzdM)r=+S@r?)`mCpz!$H8>wj= z#v@mRlVtf=`>{U^_@!3A?d5p%Bd!BbxjA#0A9})fdW)N{!%u zZ4ql(-a!$=j<<7**t<`+BDOpfcx}7bs$u>cBeh&b>;@=K;Key@B3I4vT-k6y^HFu1 zm*s-}cZ%34P%mZK*;m5v9`fC`zuTsFo5yueP2(^gxzhUYdcV8pZt1nB-KWzhWSx$3 z!E#&?iwES}SNU^*N#d&6a^&OFz(3BUYE%BTMJx&Yp&Qc;vV9;i47M?hmhV1&a&8f; z^vkjvolaEtn_?0ykMuk`j;n~>1T=i!j@eSnOX4@X{FEQ6z35Ph3-;eBVpo9a)0{>}|R|&i*wG#hcX}6ft+F&kuVvJH5Hs>=OZ#Cf6%F=%;wj)nm6n zamEx2NjTLaTED#LkeBmXcc{Y!`|lJn+^nf+)fWE29g@8ECB71al!sOMQj`tG0Wz^mTeic*lR<-zU`+9`;EaW z3mDan+Sgm|pWjfGsW|4u1FH&NZtf)jjxk1#Iwo|b=> zXrMMNr3kswcvJ7ndsSyWrjEb0y6c~xZgIhKTq%kJ>OR*6Fl$_!=x$QxPXnIG=b*)S z2KH%6_bkn>Hk14&Pdwzi^TKk$zG-*t`dw(BG2DS0_ACt-EW2lE_5rS3voyN^|1Fjq z{|p_pQ@cdo-h1km>D7=fq!0hO0=wUyC5m(~ql%Om|7PH>g^8N|>v|-b)+K!;7L#{A zISKsB_?y6dqYrw_efL4C-3 zO#WVx)naph#WX);*zylx`I~#K>$aX0YFw4r=%83M?>QH&A44=YjS|GrP-f0{qTr3N zOO^aUWlcWi1Mtunn`#VDz143^ID2^ejp<7;DaMmD_{KC?w@qVCrFeL3Qv7Mey)9`Vh^(0YbNXD1Ck zqOUsuX=1}TPsI_q(UcN#IQLW>G2m|~-tCvM)rWY``s4Rf_3PY-O)E{|Z}%Sl?!!9W zTJ3=1f(Z?tB28>q09#JJkb7%$bfm@H&m1L;4lxV+nL=aC!th}FA<|;%5o&HA3^aua zW1`GLOITF2*%X8cOu{I0gelS#Z5G19Yhf6k?3rSVC+F}7d4R!@Y}uBLSnf1iwj91! ziwGR=8`JVjF=c{>8aj8%Wbxh>HNyrS4_I9DvQLXw5A9YZ5R-Qw1CwWzTT~^?F)pyI0dsta1K;(ldJt)2 z!!qB*WiFp+UOJRD+tkgZUrMv7%fPM~Wc7c#I|S+81t9@iXuO85C6Jo#=G%euRWH8u zJ@#r@jiu{*#}BtVB8S+r2cSzw-+%MQXxzL`s#GQ9tr7SS7c4t$nFw$TDSF#wGx&5$NGjOZ)oX={=S*c~_L?p9GB@QAnM z@wgy+Wt^6KZiid#3!G0YO{FJa`D;tShO2iE%-mhM(1!g;6C0NKwk>n`gFL|CNVeHw z)5s1u>9%R<-U%ocMtPiT(+buX-qrX92ZucFyyMI_{a-LEXJXU1$`}_cJ8T-49ZF3{ zFdp$=_p@|sg0|@&H$$fGKv)%gIFuqYGgW!w8HgX{dyZA9f89N5>Uq49GH)3;1`htW19*-EG#=x8w5PsuiK% z)X6ZV^4dcs$I##FW%peqfpCX+em52@xpS+H4nd12MSowzbMx&90e>&LUWlN8xRGju z%ZzcsvZLBS#buj+#NCljU_9aI~Mt{oioy5QDwleu8oQEmJQxM?b`@*eJ< zcUc9^)#b-eeRDajG_ef=(!_=lO~yQvi)ZH609;l(tu$$$o_a8#!*K7N?#3&jC3oLN zn%FRA4M5TKFEQrG0}MbCuMNX^q~?Q)uAx=9U`{aFDJ&z?CLk`U zg=C$AlzfCC+B0kTi;Z>)sQdoMyU@I)~=pZm|w&YU%d#76R?OMlI=O23&WS^cYYq zWTn}2(dpU)_6<00JHZMWO^n)8`09v8(`)9w9_qg1^_EljMie;91&!;wSLGXU!E&NeLp*<2zOPq_!+O6h zN4(}oyxkPT1tWTi^d=j%%=M;0zGFbY`q~9=B5iC~<{PxE;S(DE8}|lRKD>9Ve(Ag)j;nLGj!BJAY$IpH7a$Z( z(Sx_b1x4tH=Jb^mY=LvO9E+{yz$zs;eN}EyzHI~6?kM8EIoNw*fsy;CG23CJcZ^$d zmDzFg&LDTOG2vF+FN+45=5xWa!(_DpsXSgbq~dFNE6*i2e|WlF*fLGSe29N=hexVg zXEG#{%!CYNpT#b^JP~%xH7}Kl?V6knw4zzIk&}ZiGlJF-jJiB_d za*I<_Hu%ODy09i7X51U(85`z=Ubk}(yU5=4;?A+@Q)@Y}>A1UkFIwGGc*Y~V0bK~w zd@4Z9hejKk4l!xwybjoL;_B#aTK>g=ADg}V-fK$Y_;#*A{_nV8Uu=3Z2a!L` z_77W?>u7QP4w=z?cZqJzxL`TXraNPsoh%uQAgi#_Js6Shb;LIv&3mZm4*qIzcv20quKy2Sa#F`YXP@i#qMt{ zwDPF?>`fbvG(J?7QhfkBv?PeX%EeOV*6?;dN#(U0-@H%KbHQ?AEr57NHhwEtcyHIl z$?E@pXm(O=E*Q~EWJvO01l#>RbJleu|1lhce{-H*b3okkx!|B zJGr&WamF1{C$=iP>uVv6Y#7thQ#3lgMV>YMLY`o7#FwY6Cf+(a-0?Qd1I)NBr5w zjSH3&jT_?0Hf~(7oM7B=(~4r#n-872A&>8}hmoyK%hx|mt9;mo3~6M;{-2Foc8{N)6*3p27QTdhIie;zsghtICaxKckoDjvwRMx?`yr<6{)+@5B$mn%Zb(q@noMG%LU8n9d53ZeA8m7 zkk*b{@=cBHsPLK7qsWvpN$-Ym!I+ln|9ub@`Ezxx$FxOx4;$jd38Q~oxu-H0EXQ@Y z<3JMC4qSO6Ewyj2x!=%BV)`0Y`Y??JN#p?MY!<3!55L6FCsr*L@~aI z!h8|s_#z7OMO5I6D8d&}f-j;9UxX`PL>az_LVOWr`67z*Mc|Ga@Rw4wMfoDW;)^K2 z7lEC3Sdu4Tw(cs^-5vl73Nr4iz%xD`Mx^L~gTf@#f*Z`M6XTsGjI^E%cpXTGkEBZl zw*s=`1m0JNe|&W)<9#7KWBz!k0SV~vMFI+ogt~BpkJ}iqn(&O@WWGafoDDDxHQ*oP znfY&Kyk8sQV85LIwR8QxO#@Lls$eK1e*ij$s!|j+=?~F%Kx$)>A|U}%P)Fe6ToSj= zo#k^Hy0E|>!4xKDRt6aO7hvRXfDt+{@V@i8xj@r60m{M+iS2v$-o5Yp&h=H!8|!y{ zx$}SNj2k+~CkSBMH|O}3b4&%G&3h>ecHHU8{q8uLL=t@GB^0)ZJBd*A=Oq-j@HL50 z^yB|qb0>8X$YYX7Vv+)~ewTGuLFflZuIg|tuWDh7@viD|Z5pt%k~EF*Ja+@k3v+#p z18S!##mQMo%nHKKAOeK*fS*R(MG5G)R1T2xqK|~9F`4IHOm3zs>_4GE$x(UUdoh;9 zLo?JFjE4j?JOGx9#Vd=f$UH?=@Z!Fo1WGdP$3c{oOuf7)Z<)6uDhHNlL z^H(MVc$3ZvU{*UKz^L9}7!n**mM}hMZOpyI0xC)v_=kb)us|~*QJJviVgdpmki{Gz zRA}gok!eJ#lS`Hos#`@shGC#d7lkaZedk^G3W|OdZ8pZxL}I140!~VqyjOQ zORPtKSizQW2g$Pao<>XA_C_M7)zG8_Y-*%<6qHOeGNNO>zE0A~ zH1~uQs2zDP&D{W_u`;lHuq(oM#~Nh_x#34k;VR*7{8vRMkk;WG8rUJG{vtsaN6x<^ z21{aWRpTceqg8E02_3U0sM1E^qlK{IE@rGIL+E|7pMy@H0EVQpaW6`O!{rDYZ@aHwNp5*D#x%TcXYTVKR37#g5AT>eHj0?X6DZ;Le-Z zFK)bh`g!544Zma^;nB>ritTW-d~S_4tW9Q|Wo?i?p@CTvQw`T_l*|L3*i3^LH}v~w G#o-V08WivV literal 1140264 zcmcFs2Ygh;*L@TLL8>Bx0-<+ELdOEB5LyBWp&K^IhAeEdVRu6aBE1WWbU~CN2qFs7 zEOaS~2!aR*B8sRKLFKQ4fbg9&Z)Wp$31q(?d8?N@bLY;SDR=J7n>V}JIj;U2|K7QC zXFwrMD_&3&pQ8Bpbmq_X>O?O4Vd#-Ei!OfGutr(Pp4s_)%bOj}75QVlwsGW;`n3x~ zHt~td1I9-uzx(~ykH2$l-^G#*AglgO-0Rz-Yp;wfT5a}MV>ei8Lv}9s#M+Y4Q>tzr zdFb7x9sg@l9J03VTZcx6uMIo%*sHT#0hKG%g6wkY+H)5|Xa7~=WYE%(Pa+%Fh3vPP zMYV^(yE@XXV1>17sOZ=NnpO?5R$(o}0)tyeG;0 z+qP1VL{FMk_4f@kf1Xlu9`#ucE8x#(*_J-gldkpNJNQoA z0~gac*Rp3`EqVL7|6kd%ezERsyS0PEo@{k$gI-C@e&+vGN_d>7p`sv{_RggF9|ihR zModCfy31`zPqHR=vAR;Vn-lk57x^O62inrDO(K$Q=u}UicDK45na(7ut4S;}C0m^6 z`y{8srM>n^m-QWq*WQw5)klabZd+0lH3Ut%Slm{p&4OVI$*?%xY1VXiU{I4T35HmA zha)8+C?Pt-t+gw?;PDD9F*eC*%W&t6YkQ|9BUQU_YD9QB?_{^lZgXdA|Hj>%UdoUn z%td>@RP?^bj8ccw+9Nt~kTuDzU5{$?Ts1?Q-e?^cw$notY_qzwNty55E^Sm4ouo}{ zHzCScc1&uv%a-H{1BB*^Upzj*kR`_HKwoD%Eq3;Im?JF%6E)qfCB-f}@T5U6*6p-f z-LUK^XgJ-dhBmfU>O&QCQ|X?W?zW{_wUNzEkLA2kUDhMrX|>oRlC_3~=M|#^>KoW! zvqw9&h;UGUt$6I8dN{bhwtscGPlUW_f9>7P)AVq&{@T2Sb3PFA=KZxlCzbesvpGcD zkrw^~r6Gwf?fk6pIYk&wf~jbY4%O&gLd7~;60LUa?F!BWcAHRe#W|t|rn75qR&|cy zKq+w-t8<`LJNea*Z+WC1-H*5Y()|&o8|Uca7;4oDROpc?icL;Vh_pK_Zt;({Kcdey zQ2~gf(%tx98}iw-HRYKbqIitB!xar9V-u2=Xv1(uCnec4T{cI0m_tl2w|4WfW3!*i zMIp{Q%$@19#@dEkwNCMgw*+9i&E;@A9U0l4>?N`+mmg<#Pm(d?+qDN3qtg$;cxxrX ze=8}5!|6m#ixs}JS9B+10TFg9r=1p8A-bRFP9cp-Pqq%zeqD7Sm@7>PWeMmFt@qVk z$sVnQFuT>_)J8VyYt7MWZ*^;{x7CVHGQBvRa@QsT4;{2JA8#BO)Ecg*XEqO zvB>*-!Nu)7wZqiNusSh=qt^ap<9rHn=`JLIQzbw*uhgjc>Y}4F-HtRkl;jYX%j(uA zNw~#r(S}%E@wCxUtzxHlqG=zA7$rwmxYcfTV??w&f0nw$(xup@yT3@A)t;;s{4l%< zosOOsm*t4HCBrjH$EB^m{O&H=QKIiKW1eaye~#Ow!+FMt;u_dYBh=zfN)^LDsKbr29OJ}L%V29fdcr!4ErPYvGw-ka^-T6?VyNAb zG#LJ%gUzkEmj70q{g)VKvD>54b;qS`KdKcK)eN(w$2kTLv|HnCE?c7R9;4r{S5QxM zq|p{aGZPc-R@ipBHCY?dxK?LT1vsXhM3LKW)w>BHdOd`o6PmU@CnSmj!#K z=-srk({^w+C5FKk-PSON-41MY`*W)X-_eT}31YJ6^laEKGe(J8g-nJ z^IotRZ@CAss#^Dm*9II5c#VUT*umn89*S}?+~^9eRNvzzY59q|tBSSSQ?%QgE|=$u zlNgnb$(?Ma&AG6mxwQ3(oi>Y7qS9?{EO0Ez4&>?QTJ{pviNaa{KMZt)&DhVa7ToFSuZIEJ0DSzS8YJMDFLs*6|_Z<2D z(xoN{TM}})Ul8u=+N{zWh0S!ax-qA1Ni^Z(?MHpiB`vY5!bw*H+4U&m0h!cn(&d`t=NsEhh}3YqmnlGS#5gj@3KVWx?3|{ zR<1?Dfu>n9dc?c5@6Ro-BvzpAj?96n=~fpEBSSm#e%sT+is?Dw`>>R`wZtDstmCFB zF*enaMK8PIyT6_lX3ga<&Jl?P?O4>x1)`6IXV(`A-4U*@l@Op8nPE-Jv|F6SsnKQG z9=*uSBs`V4vNL7IP3_xx7G?3 z4XP^I5a+Zci4L-3KNM8N5yokto?ikwTZdZhF74v7|E=N*r{rN+<_0=2QU#jS?kz0I z`tdG79oYv zP8-%m?a>uKEHf4%4AiB4k+t!Xn0r#&rNtIo?^RFi$i-6$y07l`H+ItwRNIV?rL}Kd zULuxgIM&YC(7BQ<8P>2&_$WM^6v|lps91uKD0ilz*itZQ$>sSU1fa}BB<1XCu#91w zgLLH-wfR4FixW18wI!$Ra-r&#Yy4qvfWng;@MYrh)zL7O*rkBu8nqZ+ZU$2 z7k{WO?G;-h+KJmLc39Zs+F&8tX2(bUITGA3(U&CP2_`|eda>4N)!Kd-SJO+u>+!-% zH}%9vs{?#>^=A$*y_<&~zfj*-Pfbw8y>is7abysWf^w?qd34eBy|lmXR4AsZm$ur& zd#Sxpwo@Ovnw&y~8aD9>QCJbRHy>Smt@_>R`j+0Sq_YP;pPdV!zRypH&css}A1TVc zcY05iy9+d^5w=g~=U25bYUQ=h^Qy{gE06UE@XGC31ikcvLwXPQslT{||q zNiDD9y!>v0*YGxVknLxgojD1G`ITwIsv*lb8~dr$eRK8 zX%v)&b^UEy@z4DV#eN#TP~YKb!DYW~aKGB>%EHBIFZa2*?|xm-*^z{UD0tzssi$JS zO~89>CHBZN8^_$QLENsvYiYNCT@uAT;=M*Qj%PBF)3ROntDIPJBGQw!xr`N!%c8g^@~*n{EWNa11sDB(&*a|P z_Nvz>-!r+7meTt1It`75hoxGR21li+MJ37wPisr|ns%0(<;Qy&hp;b~wYvj{hz_T> zi+<{M#tU9ug&hWlI00v7_}{DCks$?o_>`MIl*dBYZt%#+OWF3^KQDSYU6d=8Q7+ah zFYR4b8vfeAtC`eR-aO8ci=WPV{domwK7dTjJG%$5B*fPj=>>rF+7-B zUi!Tn*}K&<)&}}ESE|_2p%aBW^2(5Pw9WHg>ry115TTJ~0T2$vA3fdX1wLoxR6tMX zR#jiL=U=yP@LFghFR;fnAyc^#MA?3oFgOJW1e1Fwxst9@$y4hEXC6f8iFSe zFWpBvUaIUhy3iE|INb7gcVuzDP4~+65mD{A@-^o*GB)d8`o^Iyav^Dp*H*$O69HTj zL4>t>#o}A|HbFlq>gjOWy{DmlZnq^~GXSM~KNT74Qn=1zSzi7W+MOL)IKdH)nYF+% zk=AhgvGZQj6>44aK%np4#4?6{6i+qX`aJTxZ|ih5beQ)$4*9ZV=3jLudv`i~Iv&^W zW&2Mx>srLSH>7?p+qTLRM+bNhkgluGl$;}HFDsb6^Gc|f$I;Iw;Xw5Bd@tou&+hKz zwS?dRC@sUC?WGjhs?cjqjCRr~n8&kX9*H50PD#NTXo7g;!D=h}a?GIvG za$wa-cctJk!8cQv(s3Vo)xI;Hs_xa7Gi)y(@><)3axNXYVW(x5*RWFYzP&i$$A_zW z8DdV3T+08V^pI%p^6~CUtgNw^r*u zaTgrb$~DSs%=QkScht+~shHF2#xiS-{6&(m{A=$ygIT+llBd~HWMCYwbI@V(C~=!Gq2S^-`M#qnkycv9PU-JuEir8yen{9 zavRq9ZORt$s(M$4Tess}_8#pvb(!L2mHKlJT4)_;bw;HlI?(FX*t*xh|HjK5bhqMl zQ zG3=3%%u@n+KGMO;ml|sAx?DJLbxAqtJnvV=Obr=ZLI`oDZ?W;5J*;5AuXzyVISjfs za`qlQqkcLho~vGN(d!W&DJiX3`DXXAvQ-X>4Rx*?Wo^}`jxj}$ElIrOaA&!8GNvDj zyR(M9T3p2NRw&En!VA=G+t-QRl6v*h0f#j_q)|tx+S`NPUR;cM^p`x^{)$`P6m`|( z;nobi!8;#2Y`G{H?|Sg&3~ijXZ^1$yFnJ#R^cn=+{-+0z>^$N)D{`PmwWIG;-^G^& zccrj1^vBoalI53+9^s4dobA4Lsn+{fcqHewv)49n9kfQ&DH?AU#0{4X*MjTmwZ!?3 zc*tw`?vQeNiE8gIW`_3PcSB$2v7PUpUi*9K{J+I{QEuCJZE$qaaiX^!E{jWBvVZ#k z;aS8+fL=EiQ;+*ht{)aBUU%UY_{GgP19%vA_wHVMvt;N%(XLFq!%BDS#-@GQbN?pM z3SAo8MVoi4+opmjB3xTtWM~-<7I%`Jtl3)0?U{Y4>)BaqmEONnhEIDQi8>?iY)f=n za4>nhZs-D)Mc*$+oFDO~DAbx_;c4=iJC5f9ScD!=NXYFZ9Vg7(6dGCGkSZqg3~i zK)OCpNuI5rz7zDkhf*1wZ7%PlWy%cVehY6EXdBM{GSrX|n}kbFxFO@#woH5DA)2Ag z;YmnnAJH`-KBRk82wuKv?~NSafd{s}TB7VWFgi7ab|_vQd00T!gvQFp~E{HdDI_{QhVa3|=ll}NHmXNy?cwxu$@Jz*5FD;eKh)zty0mbc&ttUqR^OODdIdy^ zzP#uTrr#6g9@h(I5>9lszWZToG09Mh3vQwP&Zm0_!@#k>E1_vZ^VY4x1B07IHf!Fr zMMOksVC(RfEm}piY97%nxMg^=@IdXq8Z)bj-gjDXeIYS(pm;SocWG3Rz=2d8F@4;o z(>_t#yKaFMPx|LSdXWh2sV5)JVk09$JuhI7|2h5+s~3^1->53=*wCNn?=ns+Nl+`q zf_EQlL)S0U@bX4f0k4!(1atxJ!8T1IBn%e-$sZmooy+&Uc%RFY9ZQE zIQg@OkOl9ItlFhIrB@3*^}0h;M0BF1VZ}pSeCILVeCPc`<<9X4Q7q>Uz4c5GHGXKHmK(-<;_e z|Fq2o!hfMrMbHk^g#(PcOS6u7q#E}Zccrvx)4`Su%h!%?7`Tf*I~NVU`b*c=h3yuv zzlDNVjV87`^*?&^yHeV;!TjVwO0u?Y_3fkV*ogGZG%fzq2@btonQ5MvLEVloYA0+= zH!pT%w@fQm!ttZy#Oq|SXV*9G*bd`=ZBdO$xMNHfneQ zoa#u{9{=IMabYt#ifbgP^OFeFE7wv%yf$I7TAhy3heytr9Z9~eLl>Zq>Z>Z#v&|R zkKC$6H)2HucY-wAymRk}GKXQmA8EG?bZJ|Wm{Pg$SvPIgQF1L1S(C&q-kBI4;&Yk1B zo~J?zPk^<@vKJkomla;zV?sCI{{BC zM7(zNoD+1*>f})yGP%YOT4tmZHv*IG*<$r6v}b<_Q7p~^wdH?Yh!i06^(JNk*mdd0Cvl$f`2U0O*?@!#pEl+^3cRNFp(WvX73@qAP(wC}$t9_{*^ zQmUg+t=x>q*K@V^NoQZVv_>1gpDWAM-MBcr(k>o6(TkH1dA!ahwbgBEZm)Kcr;YREA{lINIF>o=t0dQl878hdtY+U>Kq#G{57l=i%Ov~=tjLp_Q) zgRL}4BAr)`%gS54aLweHgM7_geZlrQbw9jpQnxS*|WTZ#(u` zo0n+n2n(O5^?9z7xH<%Z=e6VH)4eRLIb=Dd^jIBsk@E~f@fva1z7zk@O&~50Iw!xB zQJmSlULgLu`nxuqvc?yMgBLX)&vxtka6YgrU4-s11}vHX zoj~AQZMFHS6z{IX?tuz!7HBIcP5fEU!R2J!xB<(#j>#9mI8;*S3v&8kKe)VX;kWc0 zJS877b@F)jP*gf%ydCq&jrjGVYO0U9KftVrc&g#sq7{(auuDftk3_z-K+mf`uW03J zEWX9Ax1lOW%WWvnDTZo^dvWR#lJG~*-YNc{o>M=w*G6VW6&L-ME@uSp<1YWYMMu4& z*zanGCoXzR$5$sZTBC}CGdM=_^jbT;{@ageZDPP?47oX3v;**BJKr@kEfH^Z7GJB} zm4_a=pJr6y69U+LyEUvnXpNqlD{o&}Zj z)Q*oYxrR%JLBW%DZQff48XD4YAd<;%F$}fh8N`uf6G2>T!BcfK?kbDUuP}W07(-pc zv(qhUwj^v9+}fGP3SF<0Q=B0wLEUXm;HW0(bD~}LpQULuvSvp0#8`R3DXU!jOEg8P z6TxL#b4}>;q@m3bVkyQBGS-T_mt4NrEZ-EQcc$ns)!qnk!))Q#57nn*mqn^XIlG>= z9=>AeE_h1OonmMQd^7h)eF#OdNb{Tr@CDb7gvK+uZpnh9QsPpr=@HxxmuX*MFRe_b zbV|oV?N<{*3mfVvzF4CCi#Fj#Bk?FKGw_I9R72bKbhU2`Rq!Mv=*e$?cx=9*3QU%E za<0im%X2wZ$Vo}~|2#6>o<3w%?OaRYxN?(^EgOzW`2`M_cBRSuGc|M7_IMuUCbZb# zAvNjTWsCKv0&UH^<x_mnO)Ec&+)ji(+}sq4Mx{v@orlE7JcJe&iYc>P?w z-PX3>7&x5=#wxoZEg>u|Lz!U57hd_zVDQSHVDz;X&Y81wNkRu`&Vyw`Mbh2JGmo@d z@UIvokz_oTv9B#%SkzXe=+#umCYz5nZfZ#LI)mAq95tJ}Z2g=E7tfsGR-B&VI-{~~ zUb0N)3Xs*}m1*2f+;ydG($9x~VELUflW7t;&#^A;ktzkh;v&Q}eTg{szsrsEVx&ag za?lcs|9yn+&*w#&7CY_I98LklJ2P$J;nOoY1#(_?iA||~zR+R!vS@+ed3Ppv4@)*I z6fWC%1o>E)E0Pas_k69Tjs34~L+&Yfs$*AU=+Xv`aMk02;5qCWGGgs60qgr@y7{M7 zt#wUDMyMk>TZ`MZyf}9;_xeWH&tLUF$c019Z2f8DV%JB7FU}F=Y@^op-!qyW#F;7I z#b{gpiF=uof-=wBH0{>rtAFbSs~2Zle2s$VxFX?_s95Ksht0{>3(N3q@te;cGlmWD zJb_$Zdo_qnRRWLqsbw!bh5pqy0T27!|KK+6)8*E*$VI`G5ZodmIJ{Zw@YbO?>1p0H zA}}Jjb*pCKtwUM`wG0kv*(#!0h!$9UQCZr5PVrbOQ@91|Jz>F9#*~~>gVYgyhjV~c z9#4wL8FWcokWII)G|=v0*&bIk?rMd9jcxTL)aZEjO|JyI!!5e-)bm|axu@X8@25u9 z>D5pV^E*cgLCq5)!dkWpZxw>}G;0wY790^C7!nrVqIF=?<}F&c3~$~-n>%BAN$>wulG`YTY`xMeC-`TZRQ|H3zO-&s`Q!WAHu0 z4?b=wzTDNt$~}bG&HmGUNKrBRLL{m>t?K$sTqJd^7|eT&(Z~xgKEsKq3v=vj z3eynzW0UYDB<8NYZ2BWq7wu<+J_!4deb zu{M71%VWg=+R{0I6&}7bl*<4ft21#c#)=n3*jMlIS?E;78(umtZRNnWr$l4! zegUnu`eW5dF*Q^gyrJ$We|@w4HZjnK6eMbOP7eQtTZP=;AZugFtX|7aE4FV|t###y zr5qcYlgD91F6^)9gf*rLB=`i+6T|I3>HOMvvOQk zblpe99cE<8@x5=Y_;Woik(()X@;abq!vAOwlnHY`{BGgZGeqbQ>3WE$+bh zjT}Os*Xvr>z40|@5O{>Z4H)slj}M`EVsdF?mvgulZU#T`s_= zL;u#VwbQ&iTma<}wEFU4$f@-gIS4sNhc0d1xUjCQj{HK5XR>`3nfN-ZWB8(sC++nb z6Q|PJ3~9!;cc^kCobx~?87}b4Jq24YIW)lAlrZIdsB2+rW=pf z+L73`!i;c`sBdzpIq`GcyGz?D(6V}g_8sQ65bNyBQDW#e!8^g zPp$Zj<{h1dUjfkGs8cMPwUpns)LiW+m*-nM85bKK+i?9+l-b2$M>%)4cuJK@>N_~v zqK0o-38yb2`uW%srSF^titBm}ie2n}r( zf@QN+%ixx9yOCj`VL@Rn!kdRh1~rRl-83vjYj(7wcn1^Xw54ID3^jb6;>O-dU(s%1 zForLq>o)L7(PGiGE$_6P6|G8Y@o(t_MY_u+zh&~MrMmbcC8eyP{JxF$-L4{irMCEP zuYMqW%2DM5?sK87ON~dQ=O+%SXUsyc=h8mTdgwEnu*$+-({N_|3g@K~@<$NIk#0m{Jy++VK49QXftX~w}{H%wKdMn_<9OXLU&%8WBa6OY%G-F z>uf36d_K{NE<7rp1Mmp$un)B+_r#A_B;m&v#M%GpLP?W3yX5ovLf4$H^h)Jihh65b zK9&7qxYd=wZQGOaH!9HK`pEI>w&caVgK|sht$loLS;^c|`e;dqyDYs61#|Z5%0~*{ zl|y{PuXx8fTXRe4t!?f3$I0AM`e?~Rs$}XtUDPsJ47*A(y7;y)zS34NCQBId_o?Gv5QFH*f*C~e zI9L0xNhQ&}u@+cByv>@WU-Q&PeD+&7yIsipI2>sqY0!6T36D?zoIWEK&vRDoi>}MW z*|fMDkTZKbJdvEhWk-nPQgITOjtflU6;|~NMK;i`^tZU$oljoM;)K)RwqjN0;aaEi z<0rE}V#8u_{|4`Jg1$bohrZqLj%<6CqT-9{@@9;_a*TQA&ugO6R$TmXJ3OZxUsOF% zS)hnJZ1P7)md|MPB!^Ky-LNK$Gi>dNs&hNCk94WN)!TRa+4&qXUB*pbg-4E5%8_8M zX~!!^56yv)M;#wbxzvi|?&3GQ6P8Zzs8`PG-JQ0z)yx+;xY(R4M;@xb#;JH( znzd@(x_L-Y%dqg!$jIgq+Od<4o?_IPMep6TUDqp$exoRkZ|$m2aqbWe zaHP299*I{lMlCtDM0BV4hQ931XUgpOL+J9vDQB14`R8AkiR$7jo3<2N5?@jW{Bkyd zOJuD48mDK%I7zdEyRTlvbuH`19T^6%UrR0>}Yr&Sk1K3KHq`!Iayk=6TTgRPmkKt@|=|^+5*K{f`deW`zC0l!X zr?aM1;oO{EZEi1FOGMR@s0C`T-_m=9rX-x+xKX8F6s^DePNvrVgYWnAT*2oarQ!Ed zK40JNCLe=+H1wANTFCg%UuTcIGSkHMH`F7UwX4%^e=|`#elIuY-A!`Xk!BphIKJA~ z{>xfchZ9KHU)-z$Vv8iV5-zR47e#llSEayc9}6PyY-3l%S@68>)T| z)uD{ioLjm~{RV_sVfA0G=<&~wYuQn{g6JrB@Ro`K5jPqW_)Yr+^{}S>v*>U(uVC@A zV}cErmIVsFK7%(zIa)6~J-H=MR6SaJRg7CT@Ync?f~TtQ`p_cy;*b%gqiX;XAWMjFBbls-c)xC z23_40T}Kw7Ys-`boTuvd>T@z#wOyaQyo+Opr-^iJ%(^3^=^wpUm=8KPT`z{0UyQqY z&fTC8RUF!z-)nog8glyC{@{Yqufn3-8zc;H)-to*v%LsMeE5C{~& zo^-V->Cf%+l78zsopZcWnK716b%_l(ug??>$jKZXjUQ%Wk`;yxuiUi5Hm=Nvj zbS}<$CMWxfrwS)?R6H*Ndj#4a7I5O%Ys8qiv|0^o-O;u1J68M-_P2fZ{>TC7nTos9 z;_^hxDxc3|PxrLphk~*^FSvhc)My+BS&8+-ijP(-sYo-{rQ)GT+i|m3QUj07mC!t) zSx{h5Adj*Fn*~M&hDJ0G4G(PEG9)apb@T9u@Q7C0YtA{}vaWhD@;&(*FYF#bf27|u zsMf#lkc(m!G~m(`@)XyA@2vr-9^3r=Kp?20orjJUI(>cSpzr)jhR&Eg%ArnaKgwyIhfWg8>6`~vB6PSr z`496xmC`k^z=51pU=(D}s=onQUXIq!$gRX=q28~Oa)Z|?l%hfc*j{5!x`l0ibA3BZv&}r<4PO=|5GyKqb)eoIne&}rULq~jfJC8BloJTn)FkWTy7mEAlxs^J#@1difTd7m$9y;o|l{$6rp`)H#sZ;MBI{!*}Ds+DL(NX)u zu5ujdn^e%(M;Uc^0?p6;ba*<-&;4}xhJc^@>F|h_pZn?XoSL8e>8NLg`|0rLnxFgW zs6M-&j(T>vpN_Jr`|0q^nxFgW@X(x}`|0q!ouB*Z@J${+_tW9aTz-6YrbwgVvz1#{ zxv$Qqd)T3|oC|*FjJ${cF_!asYD9X_9S$)nEH>6(WQ=kjttbZ+~hQ!|2QujaMsKAwBMEgIIkFRzK}RKOu(68z)|+L=hOUe&#MNUGqODyyYnCC zJp+y!pXfdLkJDfJ0M4JM`j^B?D11I|8)^P34cCk;4jB+mLT z9=tuf4gQ+@HJ;(q6gWPANSpx&%)w!ki1WL|iTTnT9In~Kxgl}d9yAAs&mP3NE^%5P zG6#p#hB!s#oDKTQ92`Ca5vQ@lX?55f96m=8rIbseDOC`?#K>WP%wK+J%AYCO0 zKCgPt5tr}$ zX^F1mPkYq@{ld_ zlLyDSW$A;YCkG|1sR2wX!YPY zHvz8dM?2U7BTzU!r62t^+8i8?6YcGcJj@P^GY3cQd%u=ArTdtJqxOmYWxt(GFb9Xb z4))t6*`BuIdN~AsesZ(7-0Xn0Cyw|TK=As5%xRC>zqOV9R&GfC;;;?0YvtdT$n~^a zX8z)^G$W20pR2?27l+S_#8Gyw+H+cbAs&f-e)6&d&QId_+V#k>`P&{o*Bkq7xU_>) z6V1U<{!QWZ5I?%-XQx3euYObQQRAa<4!vSdd)QsH@zc^DM9nq_hs6^|*;{S#b9xZ? z`SG{kl)b5SVc#Ni+N1pFx3b?>EPHUA8)&5J4vx#tT>Q?cRp#KRb0nK=Prw>;aMZdT zA@@5|J}?J|k5{y}HPT-n{M;NI?&F9vOZuG`#4ou(;O8edyUxuH_?0%|RF&gX>WDe* z;kQ4Y-kbZPk^SojL7M^XCPL z^XW!&aMb)!?RoBFb8yuBQSEtun>jdq3L%ziPkr%2GkzKY)cmyr)}A=3Jq!2cZ+qAd z`U5pj>&bcg_yKcp)cjHJW!fG#2S<%hOWB^e-{db2OEdb>!}22jmnY4^QR6d8&eJz8 zn1iGI=xB*k`HDF>$_|p{{ewkU&B0NARPCz@6yyn`|DU|(DQitTP<~YH58}lymFFK0 zYi+c*337aXDv`hK;j%^?)o-Qb{7Efi4vtzERKE=^Zw`)H7ZgsRO6K4wzoT$wR51sK zcE>g;oXR!w7l+4Sv;*aL%1S$Ur;a%|yjI2be9ei3&nFG@7l-cIIDa=nGlsK#9_$=&X4o<4X z`9#`vWQ;jDHXob<;%8qW^z)O~I;ZB(Ae2XYQ|;N(-<)a4&2U{nYgQMQlDxAhInS=AF9G}B-{=7NE931sNSUm@4%rOT? zJ^v_syY!klIO@H#TIXgjG6zS!cb+Ki?aESfaQIt=oTqc79k^GTgTp_1N1Tr&&ckcW z!BOwGkI8=9way$I^?qBe3-dRdgQMPWD}Q}ri#a&z{kGa)TX&j+6CmwCJqJIv*BqSc z5=Z&bCHu|6sUdONOM5H#l{q*yC63zn_Ws5koLW9Og-@D;Q(NL>%YJ+RdvkE=NF4Qk zq3$_zaOz4Nwf=l^-W(iu7yYPOPm_N$2dAFIQTBG`4|8zpOB^*mQ^ntjgwW5Azt0N| zP#*j3ZysFXQ~8ED?P-XzjpI|UAfF)o|M=UUMkvyVGrfp8IE^Jvwp_Q1l`scK-3w55 zJ*KodIDtO>cI#1daQNFH93RzhS?a|jWd3~owFCZMC2^GB`Qs^b+QVZI;;41|HSt$& zAn^0!Z+rOlR^ntzd#h5*oc1)6IBK6btDZSHEhUcH$J?5igVRdlsPXx|nK?MEC60RD zcDFVMr;Wr>`?o)zH3#QuiKF~ZVwgEN>V1hihdtfi9GqumdwR(EGpma^IL}F(B@*X+ zH*;{>N*wjPJtf{8oOTjN+4WC-&A|zgIO@4^zyNb_!X%E`S1lHQBNIYDKmPjbaFj=X zt?sEd9b`^>A|#HQr$3~bgVSE(D7)_KGzX`H56-Qj=HNt09ChxpNctx{YX_ZB z9_>Kk#E&+oJ)I@aGU<0pPcR3ki^Ngu&j(Y?!Rab-)VfgP6?1T+C64l=-_AA%Cq|8r zd~eotfjKzpeZAUO9aCSN0lq&Uf9<+E3Zq>sJLtE@9QFR^%hl%K#7UfGa(r5> zGY6-K#8Kxv--^F$2ce%If5#^t_pRo%r>DeG=ddMqnS;|y;;846`FqX5QTI^P zJ;?L}=HT$}9C3Wq^XVD!r;s7=^W(1_@NXp%M?L>cK59;T`b!)&PfLDl4o-r^QTw-{ z-xX|b2gf3DEb_cJ=DayLi4sTow{@4z!AX)h%HHDsG6yHw2j|=C`HRDA zoW}cAcDb*5{y%eY)cvYK5@&w_-W2fvlb1i>eE?&7)I4og#2g&eo)NM=i%OV-quy`# zm-DA$8FO&h4EoVD*`A^0&B0OUiCrYlPZiC;pZneKWemV)gEOBsy)FG`P&|vm$BdaNPBxfDt~eKwvRZf z-&A`Zj>%sfu9~^EXJTCb;_zOl5l5X@{m{o89Mx}XKRPDC92|}l=c#JXW69>=uvFrx z_H0Zw2S?pcR5%^d%)wFj6V>{2YKS>F>fWHjNgiqrj=DFf?BMcnb8yssJ~cisk1_{G zt#hBsb-UVlb8yr;r~2*OWOH!T{!QHvnK0cP9QEF8r(72TXPSef&J&d#{5jto9ChxZ z=Fj*=`HREnIpeyZ?sb-2`rtU%efGWl8}Vx2n?b|FXX%Ou$GK*};rQ=0;56ih1fO#6 znuDX(xjJ&5KKH&kIBH)NAaShg9~|c&L%*@uedsrGu5(3YzfIVjzc}275J%a;rxIt{ z$L8RuepBs<-uB=)fBW>?XNLC7l*b_PJM$NZ(}g(7-fqi&JO5?=;?Qjx+oRt9{Bk&d zacEMMx6Q5?=1K(e{txijX3Ie>VwbbFAn#+MjT}a+J*eZp&1)-4s*cp zx&2%I;;=L$&Iq|~ANo6gap-r9IN$IK6ZmwxmA^P#PmMTFN`D>jC~M&V2QJ2QW~6c% z{SKcKj5v*@KX|%A{^IaC!H6@NjvF6ar3c6P%g{zn%g<4^^4DrT{qxEE#i4l-hs~f# zmyrGTL_q%H(C--A^DiAYJ~e9OFAn_Lr)ZP>#i2hi;;4Spg3ZBEc5qhq+po>?7l(ew*q*Y|-ac<>4vuP% z8lRJG9vtU?2ERi)+i&m(C1rcQe%2fu)gFcOLpyVD=uhe26wc)^b8zTSjW{k7yIXKFXDm!>S)*KvPdm9{|zc?(7cA&;b{hgs< zz0JW<{ibjh^?Pufs|LTr_2&z;N8x-V_r1Fk9vtUS0}jhSVDN7RD8T216mxKtU00Mi zBL?L!4(Cj6?U|FFzc}1i<%ToYnZG#PR~d0szs(z(zc{ovBhESL-_{P#UmTWZ#8K^; zJ<=Q;?!BOuun@XJL7ny@Yzd)a=+Vkq0=HT#@g*d7`-z_l* zhou^EO21_e4(-l}6S~429Q8g}^;_mjb8yuAV1={t9dmHh@6{-rQ}3FCqux6!oKo+b zgQMO%E1ZyZ=HRIHN8z~Fn}eg?Z!3TB_C|AX)bG`(_FUa;4vzXeDGI07$L8QX;o}c_ zZ7~O@qQp_-^U^kRaMbVbsD3-P!yFv-`#TEf;ZM!MQNO>V`t6xL=HRH`-%&V|_L+mD z_KB+Bj(lzoPE{Yfe&~QXH~~I(-Rht@IO?22_1n0w%)wFnYlXAvh&ecFf3588!clW@ zxYr>moMy+(!BO{WRKJb-Hh*zA{<-brKR9I$j(R>-{r2DK{Kesz7~AuLd|v4AgE=_9 z?fLYqIXG&+qx!AX&*tFx`qAFM<}VJPuZ-iP+B5BfIXJ%KbNo{N;_x{xxAs)OVh)aK zkMaj;f8;L?OUtc2i?5o4quMiz0emj~We$$-`N7C*=HRIF12sPD{xt_jogb+AbMB@& zI4sq;&NaDh4vz2n!ElWd|35gIy6b+3@w|$)rd|7<1?#)IXKlMj`DAN8<~Ss-KRbE z0?omx;nSXe!RFx9^l8ubX6E43@@dc27Utm8mN;tu^k{7kP8}bd#ZQ}qQ`cvFE{9U&3tgC_csTpxx`WPbVq_YI4ykIQzFqE9Q8ZSsy)xCKY$5*e?I=6@2KBbR(3rl z#hmu2-&a;RTT;!zc?O+h++Y7b$Q&Hs_h!}8%)wE=udMnl&0!9X`h8`Evv`O(IBk8# z=WCZaIPH9JiVQUeC&UM*^)PdALVa-T!_C17lQ_!nyg9-g9L`aadOp24(i|M$_rYDp zn1jRn-fWNRx6$MB7l)X-8u zhvQ;w&l=gDc60II7eSF2S@n>)t>&N9~|eB zPrn^E^ji~lBtE~4&tDv_2gFf!kR@@-Pk(Tni-z{Fv=fH*ESCOy+MEZ+xnRJdKR9W? zDb9hyr{O|#aAY4$iJK2Z!5t+MAlEcQ%-V zqxSL24j%r{92~ZVbOAnypMO3!2S@GWReR2CF$YJThg6q#aA14>;;^rb{<@yTxw0#N zaoAr*9Mx|X_L_sE>^f4mr|{?bi^Fj-wx_Z5I~@<0gTvxERtjg>!TiPHxr?zq>i4Tw zd}R)fYEPi-x7A;pgTvuxztxmDr@qNw9Nvd!zp3`9eaM~T`HRDSj&XeIO1o}+${ZZk z9)%PCy*W7Q-g*SnIR68{R0Ga0I*j&d zKHz+1z+t~FG~m1-aaLI$yx&*?+d*4qm{W$s&+k@q{bt{B_r`wYddp`ct{*f-&a*#} zm-VBZrDnBPbRW2kHTe2Sp;i4|oWO_lgPJ7W5P-6wxT~ zFz`L#5#T|f9}(UHdIPir#CyUWLGK}47jzcko}iyV?Lf^SYY*N6yaRYk@F?&P!5f3~ zZ_qRcwF0#PJq>yW^epH(P&*L+e#|ZC@-8?3W@lGWdr$}{6ch#u2Wx?T|5L{7R0}8+z-?r^gJj5Gyr4)T>x>M{{!6yaq~?ZD1v;v8_hAV zhww&F62eu%lfn77Zmi%d!2>|Cpz5Gh$ZVh*2oC}u462533iv?KYJ}eb#esT&;z1vP zR)HQydQtFlpiLk<;%T6C&}WG61Mwa;?YbDkZ-N{MXMl!)-bLIA?gF_%pCeu$bQbg| zh`-~z2E@L582lo5OHc!Z9|M&KWg^aZIK>fu9K_$s9g28u@K)f9!TDVk{`O--&?SU> zf@gyd2W5eVfqFsq6X+a>_wU%Y65#X`yodEO=oiqhpb?Pu2JZu6d5?fE1-*uFE%1@x zUx1b&yb%01&^w?*pi!XJpszryK>q{10-6C@3hIYE13_~Tehc(2=o;t^(CeTtK|x3l z1|3G&3H~DJRnP*^LeO-`kAfC~o=5x}@D<<*pos_%08a$1L^uijI{0PK8qf()AY@}f z<3O*0Qb9J*V2~Y@21*CDhA!`W?*q*O6@Y9B=tYEUf-eVO0eTyB2JwHvFMz)Xeja=- z_&m@z2p<9e3-l-GP0)N$CghDkLqS=f<)FooF98ih_;2uKplpO+0&fhy0DL(33!tkA z{{#9Q^ap4JWCcOx5PlR?9`rb9E$9Q#de8=t1v)994-x(dGzj61;GcmU2v-1q0`wNb z>%g0Uj|WWz{f_u?&}4*@K~~U6&}h(1$Y+D5BHS0$ACv)l8nRD8yFo(`-vjOf9}7MM z{1fmkpc|kGh`$Z`0kjG6E1<2Q%ZP6SKMcMd{0R6C@UOvlf&T{n66jfkUj>Z@O-KA? z&?}&6h#vqQ1Wg7VgKQM&eS|*-eUI>F@Rvb5K}Qk)8hi|BFX#l~(?I(X{uX>D=orE$ z!DoTSA$$saHfTJ;-+@m6KMg(yG#4}p@p<4=z~_Tc1^){CIq*Z^&ww8XZwr1A{1WI2 zs3PK(Ku?060=XfZ0(uPL_26Sb8$gpl#ULvQ-V}5b;gg_mL9ZkJ1gHY26yl}88-cF_ zKL!3B=rrhi&>7GVph`&F45|oP3u*`%m{ywq{69VqLAMLm>&oCmw=1d>Veuqa1Oj3 z_>-VWP#?sbgNK7hf~d>3)CXr;Wu!%bs(?C^AbSct2)rnWx(&chNzZ^S`3F90W_Py`eu&s?jQJ^Luw&z3WQO-Ei0;PPLlrye$w?h^VV*j#^%+I#` zD0PDoz6I(i({@5$1mUKj5D+_!d7{Ce1F@WDpt@4NN6MN*M!g=0CnC%;T7c3)<)rRD z@J&*`CFIoSI+%$t%WWlPL&4d9l(m+!M-We!vNi@;nv^|lkkJpYe>lG;fUY1;EY3NW zNuR+u{Re#qbvY+Fr#T0i#(7FP=jM12=O^WyuPmb-$bonZ#D7AVvJen$gnicra*lT> zi1rZ$qD~kn1Nj)I?NAmjWwgm3r7Qyc4e0CuZ2?h__Qt$ z3C{MgF6}^^ORYe$5XFIdfZ{=HKj#hS5bcol=mO%r>IzO>${1!_nZ`2M4&o7;bs%mp z5OrffoR8hWi9s2|%+EApGe7fC#{4WxjT_6SoS14%SPzA-WGsg=maSyOql`F|5vM1J z^=yVZokjR(5c`hxrLK~(4(wajw>OABs1T?Qh+{!pVmJg`jk)qgOz#U~c@IJ7d4v-{ z13(rK>(LKnOdlZS{S9*FQTi-{`pn0&FMwDMbttEdd6j&Cl>6$lJYRjbF;U8!gV#fy zDNB;FWbloU5szW!uZnm)h&t>)D~LLKK`TKYfZhQyPYQ^6sv#Z#8i+W{C#Rh0%tPH& zDXT7ZZHQBsoVrX`x`U*whSVL5ICaUX%XI1%0=G+<@^NX17eyN5oJ+(`2Ql6P{4;Q- zKa8*g^d`dfLFv%VKzs=3UBuUboCp(_a^g~#c_^cvuZ;Rm=uyW7A~reonC1qZMH!Sc zOgYm(hm3WgJX6Z)t1p5YK+bU(3M!89Vi4EeFTm-$nTP8g%jyML1B5S0`LKJ)xkggI zr;k3@Oka6H$X<|gwtEDq1oHh1>WVTbdy$0r5>QPL=gCMA%j$>tK+ufS>JIFr;r+flvH0T)+@#lglp9mtxb@0oe9U!)25{PoHl{2MmvXmWz z>>$Fd;}j_y1lfGhRK!05v22D}2IWkrF3WyN%K0qvkCaW5vcJLifLQi)Dcb?gz5h}0 z{UD~Xk689j@B^SRAhwBP^a_Y+Gr*UE=73U=HX1~H%9+kFq%LKzN*UMlT_DzQj&UnM^}?42X3lKIO!k3t9+bdx*<8)8>Iwk1~cS`vy8p zXW8?mjAdtm8p-^xK~5W83aSO7?gFXH{(S+|7{q!Im*s8;C)Vqry&z&T%(OSasYm@q zQuaLZ+d$tS{)tSZ9`&z*4?xUjkxXSU<*@PCd&12C)tdEBRt6 zg=xyJruy_QKC^JPPR6?_CZ%YI9yeF6S1i1nj-!dnx@)9t z9CTAboR`#nPs%Sqb{<68`%?BX_+}9EuLbeB@)&r3@RK0Q*MW%j7UJ_jO+YN;11YC( z`w+xFUN2?az*#QkERXsdKrDyPjZEj5Zv?SC`lSqT`Xugqxd$!;*(S=7=WWDU7naF5 z=Ox=fJj#hfIqO6}LOC%Rrkp;6I+U@^lzlJDV1C*sWwc%P-4<}_l2guf`culbN*U{P z1!3lAd#J}Y9)?`ii*tr@j^`1`)g0L&IZBox03B4SXz!WwD)mLHj@_ zpvQVsm+@(cGc66AX~bv!SjJB9S0I}SJ`Th*+C9_$0sjL;|HOGg4EkmIL;6DY0qaYf zrasrl*FbL}PJ4GE%<>M%^ihZ(M3{K&Bi8RrnMRwO3V9HSIMidAlfjvvx`(8UK7u}d z6yntVO3Gh_ED=QA!v-1a5e#BoI44=||G@tOv2C2Q%){|x8qZ69M|dZQb`occ68$42D%2^{9W^AUlKb_n;p@ET3VePrX7Q>QKfwb$&3!Sti@? zqm+e%M}qo*sCyQ~HuMDV1tR`WQdS6cd=Jze@pd5Up94|99(X4Z%l=u)T0>WrL-{Wt z)~g%K0F?o;j9(4%^9WOyoVrX?x7+haeY_?+76=pGKlgu;9O@XO8FHj-wIAYaT!E?+6eV&JIRpI zJ}Kv%q@45fDv0xya<0vkzX3iB`m}G#sYCfP@NCGLpJTx}Kso2kHH0}gR337sQHSL+ zjcw;zO!;DPmc=qzk7*#5$uQGj0;ewPrtpZtw70;ymtfhfE9-b2#5As@^fjt){+06O z;AfD=HIe!^q@4bK0%Y`qlyk1IoRi?3LrsxJySN47*+?*Wdk})+{SokOhUWd$JP9+~@xr69@*%5V_)P${EbF9Oldd&|6q5vP4BTV*{TLY(&27vX-O{*-}= zKvoYF2Z{%M03sI8Ig28khHyHl5U3d9Z-UlH9oi|Mw^|~Nw#)MP>|Y$Rp$PMNsTYWO z`3y7yyf=7RaJG$Y#@^qk}<{pg#k=HFz7))1bbHvz{fv+2{0I zPe@rQ@Xa9lsD>Z}#rZJx#k_^!7lb)aSvU3z`-k(B@p1^a0N(`8_@m%#_kK`8#2*7^ zyP3v$$}ro{@*hWdF^K)}B{=mffU}O&XB`=4y&10v&bqFZ@k%njPR5@EuLnJjE%l#5 zygqoSj8~TNE;3$4#$#l>D&id5WW+f>0SL!}QV|{mN&&IlYErJ^)eU+~uOZ{i!*$0SzW|Cf_DHl zlQP;V?KKhcjo{R)5AFbWgU%w%HgY^@oAjR?D~=I$SqIjK{*>6%Z3ND_G#}yR;0_RV z`E0}Z0)$t9QW?4p8@rRyahPNqB%Hiq7^vHqnvu}5T^g2PD{o?p&-Vo%Y5`PjJHO( z6Zp?E-UjifK_N2Ea0d|O)Mp*KfQZBRv*4XT&&fDBW%OfAZ;Nn85bMc0vMvm>UaAfu z2(x}1W9DI)>69}b2HqYN4q_SPlx+hA$~+MWb3UjtBM~PKaiWn!?rRH+sJ;PPG@iWHPch&u zhn#YjPn~Y$Ao{3ZL6mVHp=9R~F9PB`?g0t_RR`4oaUN4Y4!j76^Pf7DkyFlm%@HSd zJi^pVMwmK15iSnOMtHcC^^&qI#D_^4{dft`K~NtM%Oa=zR}jnU3;qbGKPUrK6taHc zOF=UbJ_H>7bA4#4@PMd}|SA{CR{~#v+7SW&*;@^93jqVaf)8zXsyk&NZL;EQk|l z1BmfN@UOuC2V$Ni#7BXz2CW29CmAvui2ESMtq7-rj>~uo!ml8_8N{{>M7$PgDZ;8P zQxG2mVmk8<27QC@8W79-1bhNG=RC3OAhzu?i1@7AAaJ&M3c^!CtP9JbjAb&;e2lXU z#?!#LHtqv4o{o5HaQY&~>DL;8CW08}c(9-8!-zQq;W^;bL7z&Q6EgPmGI07T=5rxD z0(4ZyIc^-&$so3gW5O|d6Jh$)*;0=_wjhXgpk5X@>rcIGaO$%BVF+_9|3sL2Or!4K z2rmP1Z^`-&hip0MC4}jtDSH8NmPa{dERS_%KGyqT@E5^}OWWW&RSSFxi0fEQ@RvZ$ zHxis}S})_Hz(<1)AdTq^(-tUaoMTRVpuMp!W5GG@E5NxfP&N)>6{kH=HeTwz1wIeN zvS=S1=Nkw!&N1WoQHSwK;B!EuWjgE0abTU9P8(!hRNbc{%r<|CG-9%i?1#5O&&o2U zAsc8}u^5ESH?}(FimC3c~D<&t!ZC;=~z?ILmkyVP!jR5&jlb473CL7k(B&UI-Kessri(>I5?Cyn*9_?P~6-1crw}3boh__whaojjA^Z~RBjwS1?(rJsdOZGj-hdz>HU@U|4 zkn^4MvN4Er)|k$@Kso0M$DH%S*e|qC+UjM{R+PO7^c%t))0N;>a2seaXdtK{Xcgoi zfEa#9>M*?8Ab%HO_BCx_jSRE@S?+t_T(f@yy^nA&aOP*2Y0R@0ydtO}!nBcf2v-6% zLiiMj<**K{3vr8pSXat9CpkYkSC4_dmU8-yF(8h`_n-|@z7gSiAm-l-o&?T5+=Or% zIG@cvL%1A>&n$Kj_Xe90XPrucSTCM)u+FUihv1FD*)GOELi}UUZkf*TCm_n1&Tuq{ za^~3r9wGB?MYuh}s;q5@H$gmH>TU-Ql)AKi=Hr}TxjVu6e5~?vjxddJ(x(WsZ0fRZ ztPkbv^F0VR1Ls(&{Olk06Z?#L_JOlcR66^K{l&hc>~nCpOy7?%=N!xa0-STLHaPW2 zoOhgqEcZ)rKErShGJX*JXHaht^B)3#2K);6XmHBDLijoGOW<5{S>|Dcx5@AkgtyD^ z*9h;B;iCxeM3`lKgYZ0Xo{fACA~tPkGC1vuI>*7=f?ovR4NjdC2=4{oC*$8DPXDX+ z1}70ehPd*JmD8`_CI9|Q~oQ6^`MMl z%KJze@y;W>1oWQNxgg`Lvy!p@*pKYb-BOQZ$1&tss=lE=qMu^>ST=nX<7_kWX#=zc z+QevZ;|C(`5Bx)ZmH*u1!=&P%P z!~)u9GmDCXn5{gs<)-LeUTLV6qN+lO%g(Usl9;&OF%bz}9nLh1UEJXG=ybKDSzQ^H zBu+W~QfE|JhTWQGO?O+9qwtS21&JI~pTc7-?$mqNjCGL>vL=VwEiRXE)*e{zv^q_~ zEKa*6&f&1Tnnb5N9hT%SmJCmaH1T9}HOZ|X8s{cV2&*H$KM-SaqAhwA=<7wOPLtRq zr!B+HlHE4D&7IviBH4z%@1e&+k`S&V?z?uixNSqN4^qk#K<%2D*4>(6w=*#nsBt*h5u4So2%hMSyyNm zmN_1@zAAqY^jHRZnEf>bW#3D#MoiV6`$PRd)lQYO0Ip!`DgVDwEGct!6QdlCe#}JM zQ&Bq?4jBsIVxC^=z0!-ybXCLLd$*X>%D^URFv?E`N`UUq)9A;wU8IC?h`mPlJv zZMavu!oPnTO32#Aq3*Pg6mZT7j$iS7YKf{zN7Or1*kPg=g?q_WomBdRS^;rm(XxRc zeGViel+%OvN>{Vz{ykVq_ELmENW@Iz4CskI)O}43&i%_#wjT{Eb%^?@lJB2S*+ED6 ziXplGF-C{WDQYy2zgbzZoj*jdo!~$SJ>!U*)U5RQamm z0%{^GJ597y)lKo-=bN$%Rfe&Ia(>mKkJP%mgt}PT=qFrahAB_xhBOAF!L=X}eWA~c z4yZFn$R+xSJ|!@hm4$gD(8>Ww8wx*^hWuP}QsI3wVgGEo8;>q|>(oW9AN8w!su#G{ zxyAT9;FUOv)lhfh*~GsE@U;ouOWnW6RVr&tdm4n&R5_u--?8-tuqp7Tw8~P;w?C@k zvU3VvFsGnTs$sL9hTdkm3?~{;9`_4H`R;+D9M-x3zRcrK{Z#K6eIfge-mn_x0sXt) zUbQNz{>j~5)yy!KrYdcQ?vK}^-=4tzVj)7uhRT~ zdZi;;uWWu0`oV!3M8mSvF^efLfUo8FQ=S?{Un_8zI)?Rz>PaEn}Y1j5lZT51}HtA%Pr}a){@89(d|F%E* z^etND6W-G1{?Za1UT$(g9v)iS>_yusn*P1Hae?H%zgZa1KGF1n-z^MzZ!2Y?b5L-9 zwqxAg-yUxDsC40E2#wdg)cOyPKhb&;$?86H-}l#S^`pGQHpXAHjoIM|-`dAoR=)6R zNzkhskK%)0)82d87NwJoxa^X)A6$-l(GqLDU-j9`SD)n@mZeKt_3$liIj`E;HDmWa zGs}y%`7tf^`8;fij60f!@D0WBl8Rs0p04z5 z-?&6+^!|~hWL{{$J=}hOtXYJ}?xF>X8O^TmUa|VF^Q&mglg*;h(ROjC)8F;oD_8W7 zwo}E`=^RdVanZKrWsIjCN8$I9ls7MN$b+r*{olYEevTePY2OVEGu_<&oNHwkH#R$S zQ(F?ex#6ALnr*qM{ajdnep~zdmiGJ2?bDmv&$;E3x3<3*ZRz}M##;VyY76_U9sMmW zKYq-G4lXwB?KWge@7`7faIUrV+A|tcS%)__>3@1@$-Bjve)btd{VxpE`)(wUGz$RJ zyl&zR?rll(TiSyBq9yXrW_BtD>AmJ@gMsgES`MR)JoA}DBdv&NI=)VC(Z+f%qp+pVaISr1Wt6=JA#zcwhVXiT0)lsu1b@OUo&OJ8a*tdroc9qNkT~ zMgRR2H@csj=Yt9hCPT$vZhvy)iq_G#y1u=u_4{%gnZM-+L|go8a$}2Ttnvud4=Nn46zImhzO-^rVKaj+QhFRaR^h_7pH#fH5F0_K9Tia(h zEm6qr?VVfN|1K;g`3*z#%2V9cbV39r=g>#9Xay;egwmmoji>>V^RJ?vE0~ecQK$xWBrX~qDv>*T8)TH6|CL=d4G3M)+ zc$6I7xJ0Ap+VhL%0Y~PukVtH#%$HmX3n40eu=#~WTdGYGP`| zAFXwtxO!?|o91lVhYLfkR zqF=wXZRgtG=a#nbmi8}ecXRvpmL|h&-Rs+%izeeEGF(~3K7&&bz9BTc= ztEV=zW9ymm%H`ZK)Mm}+W}Al%wt71fyPnG`8Cuu03r(vYY8LlP zoAyrgxRt@{-&au5Vv9x!iDS5P-4dC{_R zBf2|}Gj|QOS$Y6T$=U=-!A>_dDZjn_+|hg}J9Mu7$lt(H*Edb@8N79|{VuwB#}K{k zEcCkl=`%FtdbdNLH$qC^+?*5VV)j%V8 z_fTtvX)ZJ_h|i%kl7J(J%QkB5x9Cn0{0mkz7Oey=ec#=VHr{ip{=_~S(-)mVJNon9 zp>|3V)g{1Xl`q*<7xBfb7R#!iG>1_(Tjt}!a@`n~p02&~ZAImpcC1}JNdkY~(70-K zW_#5KVmDT6V>Q~(Z9RFg{lF6!o2RlSCOY9k7Hy?|L~ct$tb^Cu=R1~^vX-_u_>!S^ zD)yYV1F@#+Y|&aA=}q~rX)E1I-GAaX`dWd!h@YeNrsAOU?a2pcy#bd$H0uqB`+c+C zAWvlN_;J+i-oK3aKG^6azOeTFWlJe}|4=(6`}a3%sA3D=R&^+fOvVkD9+}nF`nq^f zR=4;c7;39L<~r))jbubO;~e#sBU~$VAuhjui6}%b(8UdHMbo=^f)rA$^fTMA=R5-v3fJ_|JaOu%bRRQBb|ev z+a%ArSt`Ut-N(;wd6U~)#3?T$7LC{7C9DF7Q02p9&g5;xsW&aXi0qoRfphKOMcZ&a zLhmK3r#43+gV<$!eI#Ew)bd>Z{Gy>&OWJO4ytURWO8TmyH_NL|?Tfd6@zC4lrMf-w z?pF`JTYBF$q*tUa+UBm2d8#%ls#~{ZzjUaLig>Gy^NoMvghe~_WnLc=$*uR{YlhnB zeMlR<4_`a<{)<;n$uXuTQ#@y#`_ATpE-fu<>VD17FCS|2MSI%ZY;n;xz=uyIOFd?m zr@h?t&Q24RhIcM|2TN7-x$lV!?dep^Z?<;WDuk@RBrbZo9e=TCM=_1eRO#M2(%sjC zMLURKq}8%b)|F(FWy;RA-*0N;_OCTa85H@lJKDEapU$`6WS`}ltybOI{Zw$lSih1bub)(#_!MIApQ<+Tsj>G@ z_f?zx>Y<*Lh3m4kXom}q@T>f}^{PjkJkp1(7zCyK+M!m;(oJh77H#`#deHwa85^y6 ztcq)XWfT3pakbhM~5~0?J-pZc&XL zn}?GwA8lWIz+E5)96Tl+p5)y z%zLa}Xl1kdaB=Y4hk8;`=ssOt9Q=-<0+a&8Y#6%Y@+pHYsTUbt7R~N@2#eZS6<(KzopUo##!{VtBTsH z+=XSUH!MH7v9+h##iz1oMh|n4Aazi3X>VB4`&}z~9if$1T*pFhX;$;`r3_d7NPRM0 zQ=QIVaxXBaY+33s7wx#|5e+!558pJ@N=X6#lUcpJjXHY7d)?T6?r40ut^Iv#&UDWKaEL`Z*J{qiIf}f&25y%L$Zul zm6hrU778~bbMkn^3F~P^f6)$z8e1R!(J^9??uV-n_F(tRAUgm+aHIz5O4)h!#{~Eh+*mita zNm#T)$mYzAnNK9Hl8t=g7zD&aunYL5p3pumR>EhjJe+h#qxHv!=xyf;ZfI>}b?@f3 zZ^+IRSpjQ*)IjFI+t(o0uIai*^uM_YwK6e9b6c__S3EQ%}(|Mw>BT|K{H1 z+WzJCc4=VtpsD?@+~r~8ojoOwwx|BwicYQ0?XDbp=`+3Qdvn!CXJx&&yqTq2w4>MN zXgGhKd<|(}(d8LoM0KrvK=wp<&ZnjEu$?$zaqt(0=v7S6d*1o>9YZaYW=>bNr#xP? zgI`BRK9wFTN%BO0ap=v`>7I%HOGEEftWqZ|)IKovN#y1)uUgrTmaDIJK7FuZlZV=q z-#J9H`g(t}`w&b!S8erPkK-yYImMuTH!msv`3?EVdgg?iiru%r`L3Zp?UrekQ|ee? ztg80kr2JQh+AsSCoA5?FI;%y#lO4H!`6=wm-v>*G>-j7a&eMyo{@M_|8qdC}_)R|b zderY8YQN^kZbh?j*m}HZ$KZ}g`S!avwDr;$3=(t}6aXKw4nF5Y zcnbLN*49fl1--vHiyqt~u1>Zpcmgd54B|lFT(VIxqPUfHGOIk-q8*Vv!kZeOm0$P{ z1#Kjjhx1rI<74IgFVV8^eGbp@kc)P#^c;F{5vk-?c~^K=@3k&2kf*WIEOri-(wD>w zW@6Ef&YVLJkKiyl3^9k*qpWS?uxLbf3uOoxaw~-I**7#=e`iH6RM)ExO2XEyN3E(B zeiEbhN~w=uwO6YSzo4Pi=@VA;U$A|6Eg{&};ux3B+w&k)sZOkeAH{_U8a^w&=?J*1Bh{nLGz{(FadQZsy< zM10?>wUYMvIj2{yS`ar_G34Jy1Uiut}%t7^K5n_tgq7F z-=3dV8~*(vo^%_?p2-A~yWl?Z#VYcg{^cpnhS<*v0!ic%{4Cm$(IYbW39F|@#{3V5 zS}e^R;q{_jCEBYrbd~ zw56q^=~Z0QE$_W8TQeQw4-U0c^Peh%>A3&J(EAmk_4jc(@zK9rwNUdtev(1-eba{* z4k)X3C2&AR<5L~nl_#l@u$a9-qF+b8nNi*{k*NK1uern7VJ68+d$|M*t5 z;bL_r_i=lLiX-w-;exoeA|A-a+PC;e?n;D{NDCJd$$3In^M{AV@iSLX?Th-^n2hLk ztrxgfJnQlQe;T4xNT4z#i+0`Q2&c=E*9@hW>%oQ-7wsaVkrry!yHDyF%%ImrySj3u zrOJIxTY@Ocv;4QAR%%3rqUBO~^#|MAKeB2ey?K6Egil=cc~|9Ljj=}xi*_Bw2(L>M ztX-)U$m*F&5^FRv_$uG6*vM%(-^BSgP<*~g9_2!#_5TjhD^1wtQAS7hqeGNlvU+OT zYOnY{Y$LU9K8>yx?V6$yp3R+!|31{}&ssgzIpaj==?Nm&HLIW=^O5%VLoME&j;!(& z{RE&_wf6qUs?Cz~`O)dF>ff%HN3C!ehgGa6TOVFH8C!k!KUbd>A~+gZt1;lGcqPBx z)c(Xv)e2MULrJBatXx%Aqf)wSV8F{sa_u4%1c*cGb`Cmmz^A`#CV{2 z!kVw?X-}8hTQ6AUvW{-Qv{rV|N}P4M)Xb>$xuN}$O|=d#U&za4T{;y4B5`@{+Z(-) z8lqRa)W>tQ>>0^N54Bw5>~h=ByzA6t@LsUwX+2-_K(h0V-^vH|HxHL}F11RaUmrWv z(zQ!!i^i#bLgiE!>EOf5S)Z&>df5OR?o{gU{G#hjH_!Ea(EIqce z1Z}3KQ}$k+r#yl9j!w%f$R^Ni-_l{(HgAdNe$o)VpRtmsqj2b^OmqbLaYHoDt!PX& zXZ<9s=uT|l9P7BP%RhOjM=xIW=8GsP+|JMyw!UYnFErufhv=8w zI642)QeT|b;6%FI`ZLWB{?wrsr}o&53Vl4q+vF8k9CnJ``)PZ}^?$7V^Q)IPV$|+$ zzCGuu(DNsjCu3h~)*zK_S#^C=lS=6D+Gb^~#ip|2U2U!7QafGb`hzcS)i%>_Zd;y& z@z@f-d~nZOH=O9Lb0>Q1#uL4D(}~`?`9yEsa-z3xJ@&25tk$Nyys6bK-qU2&i4%6W z@DsV~!8h+-R#C|%-PC6B3n%}3&2p87EF}LMos$86Q+syv^k7=3YSmscr=Y;(eFg4v zd&jy?t?Bsp+GSPRhnA8F1-qYN_gj50n77WicCBQ|$EU{a={@hQQ`7%c8aV&`$vy9^ z)8gytx0Re-R5tf9(4OfV=H^nf4%_3}e)D{bVeW5~5@Fxfs6MdN(Asl0(#EcNj@`JY z_22m4v{M$=pSic4_{6%A6E+7{*wykwZ8kQguUq3z@%U%%ZGLcihM<)|RAma@w!$rM zYM;He`N_ApXYXC{ITb3`Hoj#SqbkRH+MmaleV1j(Jv))$>}Ipf|ROD!5Q}%a1rGju>+IK&* zZObiAtdDd18M3{*z2l^L*IV{kIy3u2OX=G!amU*%IJai>q;0Iv`bk^al#7$Lvn@F% zZE2TmowTh@={spVoAPURi%b?rB{bX%PoQ}uYf2mlJL}aI_8^oTnR0%TUS0yW-dD@9&Bx` zzhNKWHWFR8I@WAH+}g2vQ>PN1Z~uGGvL}ykS*h-U-qA4X(@VSeK>NGSirchm{du!( zT&eA0-#4GVt$io!<*EMOE+4Z#2JwPu%-M+U0ENb?KW+}v7WBVKFMfE}TUlF3yYbSS zy zdgJu+t?dn-|5B4sbRKH>i9AAx$MhGCafYv2+5dWUNt{=w}0VzhL)?&Q9_eST2aubpUfGqKmleEYIf_R&M&W*`Q0f`4s->A`y!u+N zlV3A??{EFAXV*V{$x!brvY*nqx5?7`n(a^htr~u)*eP-&{J5q)=||<1N>l5MDysab zy0qs~B}sOCS;A8|Cc<;` zU%0V9%R*-1ZMXW3aIV%Ex(#&`UET~&{axBNy2ImTEB;Jtj*>BrezI=Uef^2ISRi}) z^JM<+l6JmXC-wtJ&&6-_Yp& z%prP}2R>>%pT25odk$+A#VyamNR-%DQyKyy^a+u+G~x*nwAxu{EsH9UspA0t}nE)zHEqI ztruk0jvDRDhuSOKh-W$5>2mAKD~8^!v6H);h?Z3-8EcjK_Agp*wrdC{)U;=(UiNgd zaVkd_2d`Yw+m^Gkzt=UCnaW3Z=)xaPkAHL(Wx5B~opzDA?N%y3Y_*kNmoc=m?Tj9H*y~QW6{I8is z&#nRcHOZuXnpPKN_Uu;B3o8%Vr;&Ysu`a1CGly=Q3ug-%OjqRc4a-|=qMPx6dzc?@ z_E2`;%~zYd{T2tGG1PwX&khDvO?H#0bD~LVD|3dQPgG;tF=AcRI%qh^h8np$=SId; z2y1gZ8I7@QkK{9lS}v*H#OB+ltGP)oeJy$Gr>5NBM&f5(H{>wIXvfL=bxYk@N8Q&o z36ZB1i#)pYUzeAh^z6NRzLSM;ry1;!{M+T$=XuW?!^n)31gLFu$AG=ssTr^)4ky{e zLK65++C#3{W->s(>~Ep5*ALMvYfA!Dd8?gzs{PLTOwUGMwD#xq-zhw7A6-}TU}aFH z4HOuiSFPp=dwgiF{nWJBKD9-AYlL3a7^eTz-uIY!(OMm8tD~<+ntb4Z``kv}EUPh% zBUo?J{&4d<@^Vn%%|oqS)1LGri=PT5oZ?&Jb=}-V7ObN>yEmtf#B!>~W-W4V!YwO$ zY0uwtv19EH?jw8S@_tUb;tcry`4=olDTZV>-nWbxaIh$jK7Z>h9;uK~$;B^|rPS8g zO=gb~NwWKk%=w?s)Pa#Zd)mm^>xbx7j3G)IANw1I+AbXw=Q@qWNsS~q2)xeSdw1*W z8_%%4FKq37))}_v{ISm-YOnO{?xm%1qPsiAM)a&W)!%d$vzW|D53E+svvIT7NP89C zrH%C#K4++f+I=9uB-f)Bk8fEV{G6fpOV{bKxX8&Ks&&b+stH&LqJ*bNtQudktqvac zOnub(M(_MAdMYAeB{dst4EsxiR8ISwHO{WrR936gph0l0QeA+`vWS2_J z)OTekiLuEPq*9r+3m0gwY`_hT-fc7KWp8dW4=ey&6wiqoTcKh_kJQ@1RQ7shkKwsS z@Ag^rRH~`b%dSQh*)S%b%~!`l@q>8EUqf%uni@9z$O~Unm+UogkwED7KfZ*jtXDZ=OZZILHPL z@pUTPaWZx6J|CV>1JO z!_PZs(Mzt292ygP{JE$(wUBf?XA$vbFdtvWD$r2+_j6~_BLO+z#7MHYI;R(rP2Z6Z z89Vce7tTdvkMQ_>qxY5-y}}aDhaD)DO%;VaG1*t`Bcs8|csP>@FUvg(AzxMj?dTxB5{@tx7m8Yq7la8hr2cI{@y?LB?=TMv1tT@9Xs?uZ?opr&! z%Ie7ak$gx&v=(a*t?;JywfkNc=k6hTH52>t_ccR3cYn`NyOqJM_pQF%*U%!ICTsn! zp;k(I?rJ&m541O}9lP0WM5AkD=bPM(RL{HhE$x=n_xNcv+g}meG~0i^$+PvMrqkZXQ+k3?zIZocT9iL(EBxFK3Uch3bKO(X6LhwHG8LX+APco=Nc)WlHA?-Hsbfr zqUTN6DCg&)9@K~9bdr~X{h%Q_?5q`93O7Jai&j}V!r>a9F^RKb0hU0uETpWKTTBA^ z(tOXs+k7EJ1`XbWv ziTh^JOTTjxBV0m1&0)9~%MJsQ4{=HI^f~{`tS*}63qQ*$Js+@NWd`|K**E#k;J~Su zeP9+RBN;(?GVS6?u>hH*5iFi;e4rML+$V9jn;D?mD>SF`g%V=ae#58a+8F#nf z9D1T_r%I9E>{|)!bh1W_NWb4{=a1Vv+wIt^ z+PjYpQ7LU@ui}IJmYhP)WP=&3lCo|7&?6q$tifjx1xxn$ir)6BUE%KDKM|K|c2(Gm z7KumCpHF&FD?FPkrPCFVOKogFf7UF(Yfy%~5=)YNVdh2c1a3n;S;c@nNHfnYcPOj& z{4RP)K9~L*DINc^S@hChh@X$; z|Mh?b!?`R;B150@iadc#HPoO-Zmx`F*tRJZlcpMLaq#7fHza?|yF4T-U0mABgb{1?pPSz<-{jblzdG&5!+r&Q2$d`li${1MDS?&TjB2VXHn zZ(nbJ;n3SvNw;2kJLQ&JA~Sbo8+KRFly|H;*u}wDuHM_8^ZMkljq(=_wf@oVNk7T( zebuoo-`k%3#X~KZPgBb*JLo=iHNMa}Y53~Bv?^OTtpw=r{gNT-#WiOhs%Kdo{L-QK zs@E4=)X@9gssFN7E6<)5-P!nM-;0w3o^Io)9E{JMwbQ@(nxPSv?||y$4P*#dmqY;c zNZdh-a*qeSVyEaE1kYCSHj9I=9imryv^kDnKJ<3wtWt}(u0Oxx)N`?G{UG&MyYBAF zdbMokdOy0Z_a~CO>~*HUa%i+QHzFf>1Rj)^;bRl2!8|;@EVF2lf9HqIUc3av<5tNL z+fpYAlJ(lrDaKm2Y}Jg=n@%zc~19L%h9a#amThu|)Dv zY)4j_W1&Rdys1cEWj|Yy99H=qH))Q@N7bYDxjag~-K#m$YN7loA4;0tl{wM|tL~@w z>};fLTSrOTH?I2he3Z6L?|rF_=XVY9xTGyv9#KPKH0VrjM4p0dv87hR;F}<~Mq`W^H2+~ZKJ*t@<|$h&rlC) z_8?7j6yL_X$)}kq{x310m1%1>uql)Qy~;SLQgN^6h(;DYKGo`#+?Gt0XeRbZ#8T@| zSGG5Sljr%Wkqk7c7HPKqf1QMK*s=awxFe*cQfc8pTlQZh&yzHO*KB^SvV^wS_j z|5neZC$as3y|n*rJ2jJZT|Ik?C9g9{a;nIaO-gp14tDkIt%q98PR_u%diK`+%hmR) zXK&@4vh~xA*ruyzZ>hK5cXAAjN@Rzl9pKUzxhlX128UCDTStor#P0spqC-w-= zE~JyUrt1Z@+p^9DbL(|l+(ucI3C_7nX-g#fM~C`QT)No!lrymQ^``gbkIia%v)W@f zwse-2`>IFyRwo@*MxjnO+ud^ZQ*NTxZy%ym2*00!HrC7)FMsiD^T+J~Ce=#Mx68h^O`?acJe*4;}z zGJ923T4%CZ3+kt`^^w<3n3BuI!Jipw{}pYNeuCrnw_bPZOwVxJHL5>5M71QPsIFU0 z>tO0R>Z~{SP>=Acw6j`uD%kqTY;x4ov)SB0J<@X79&5l4G%x+3HmBrp`}8(G9BXXtXXB1*b0?T<$GjB>}<`tQff=}$F0^Q^lFA#Nw&l;5IBiN zaMBzP@U5pqe0e zfT)&}p_S*erjDPBgTK0>7n|ho(v#Edq>Am`uBX^MQPG;);-KnpHorY=WAXi8o5d3u zKaylup4#`+i(2QCt+w8p>VfDYy~vLCtPbMIcMs94wT#VPr_XlCe@nO@vZItUqke& zj;xRNZx6j!Ra(Upz9lFB{hgur3n|z8PQHDz_4@A)yt^2y~8)~I&#V+izIQaXkHcqa?hmB``MsyfgtYF;J#zQ+V zwW=X<_Go**c0AQHFz)tK|6pj$B@JfS8j}?OSj74O8)@yDSLdNrwy5pNz95#E76-X3 z4*uZ~y{gEozVGV!KN@PO^kDOJp~b;Jp7p-mkQm8|K+Zz_CqwU-9q8}J4t)R6+b>+n zf;+5ova&m#qrcnHc|CnY%fjc+;^3bR(J6bgi_br>YT@J({qof)MkG2ruQX(}~w zOUzck_d7!Etf@~A+i8P`%e^-Bi94C+*f|)U=doiT=e&^ERL$CR$NoY7k$s3@I9+E&K{j|n{KNtpMKWQk?>7o-r_pMFn!khuW7yb zmqWZMD}(R+3cka4e2%&~SU@!lL})(=tZYZPy&KlKt$Sw|$G;k)SMkuCvH$C#mMd!~ zme}M_Fy+4)YNvGENn`(Z^+tWx>od#7ZJu7@KIZ7a$#wVI88UQti|p@jI?KzDh;3Qg zl#L#te0ZYG=axC2&)m>xpDqsm{Se-5HyNMfO)={LD!BH#bVAr2JBRfJ^MGu#d# zh+*yfN=+;~Ywg$nv#-Z`y=q(;j`NL=|Mw8RlKE+`)88LHH9uLbaRioV|B>ZRsi$|y z{2eWNdVGl-+%1rnx265HP1@f#dGbFEaiO@L6MrM$StZLU93m%}jb9`8DtTmGH8=_bF_v1$TBSWoK z@2kR$EzDjOR?xl&c^4J(*^{R#Umlbdm94Dk+}+hLSk6=RZ?XD6na?+VD|$Kq120q% zg@)hZEH!4h6%M8n4BzY^U?~t!~RrOt}ilHI)7l!hj?`~-$ z{{M#PRgSerQsdY??*Bg2W<@A!hV3c5+sF%d;z56conLG>cz_ zWN?ypvT6R$w$oU76BtJ%iKv@>!F_!JX!fo`O$mZ7z^w4-+D#u z`=0ssu$>LRj(0wGh$CeMcvt*23o?)VlXVdL2vY%VwJFum@wE01`NPB9)W-J0A$o-s zMn?I+47FGz$cmvXSx!D+H^_$Zu+u7W{U!qe-DUq;@)Ine-T0BAlj~jeWn`W!U(x5a z|F(OEWn}t{+xI*o^VO%U9cG7&Omo@!AO%)AJL+O*eM|4G669nFcWaN(t1Ri!`Z=xB{ZKTo%ex@Sw?zGheay>r3-wGKQ}g>eEbl-%Fb7>*T?izhuSFK zzq?WWX|vw=!uH0CR&ShKFKgGy$lO^ksj8VL8^_#|D^tAB7MHwt%{*);$G>SqS3hBB z)FtmEne1lw0KC8&M?)bmRyuytx&iCPazp;H;BIjm(bZ3B-1Ree%%3>adX0vcAb~I+ zT@}^osTE1G$Qr?(G8ym}?~{H0r1^a7-zUwY2P5R<`9$Qbgil~V7%Vs9WS>iH3iPLE zqDh(Om#pZWT;i(AZA9YU+T_joe03*RqHH%DhW>gKeb{bDus?qqS-VwlWWH-gl97k5 zae?iCOht&Pyb%eRHOLtfHz)C;IC!!3>r;m4RVHlT2wytXO7)tAM_OQ#MAbZkeN6Jz zsT`_Pmf(Tx*y0D&%eZZC4wtO9rUjf5|K$8AydjyS#S`*waHtrOOp6`kb$-SydaxAK zn_bvEnChVB|c~U$N0=7duLwxv}8HOZ0_uvLk}-m(wsB_Czvxi7Ey+I^NlFO zdaDt7gN*t7LZkQTv*^(txt8=h5els#Lq?QyNj#Aq$fOp1^B@*>AK;wvX_M4NbLj)* zj-w=kT#!UFh~r`_^Ow~h=s@OZ4m~;qcd--la;ZflLGXva(Sf^I33Ez@#1Q04HtuD! z=xKpd0 z5Pr~CyC|=3^jXq*)Y{@^X3 zH<_N-%%Z2)Y_yiyEOJgtNMX*_gbB?p^cYk~qUfbrcSB+1<>a`=K5IWCxTYe&X~bYf zY4iU*zxCmUglgqGYnGc;2wAiIj9Gjm+YmCz$_g1zBz|O>d>cG1wuFpi{_r=}PR--B zL-gu2lJRkW=1{wZe`1SR1r~uU#P-picrr0?P@D15WuBd;L33_NJnj6?$z*M>X$9F% z^Bjc`gJ%z$gs$f}uA9lB_`M()c>*5E?BfGnz%ifG8rDHxh-KwHFEkEaKSZyP`N#-w zcvgAdVyG>e|zdoLEr-=sm-lqO`Yo~06Rn`uZ2qBBaf z;D*RK@}gxiM$V{a5oMfM0iTjyvI`%I@qOWfM#$2I8 z)2)s|4&+5NPQLKL{gWf(dvSZxPwj%@)cy1crc2O6^Jt=vA;N^wCH zZ4UW@M8b(L_=!XpqAD85-ms;K!|78r~p3*)1ragL9F{zniZ%DVB zAxCDpc8J}xJb6@Qr|j#Shu-bH;jP(1Q4qbv0dWu;pNt4;PE3@FhGceZ;Pvj34 z<9EXozQkwzKc3+Y>&N1X@qEg!kz0Iv>kz%NcD?88Rk`cqeA`f)C0n#L`#RLX&}MT; za@cZN6NroyiEC&dNoVKC!}&Ibx6h&n51|8pL3r`pEN&1xUqJd`(_kf1#p2K%vV7Ny zUdh(;;e^$Sf86x^XybUvYj(SK`FqDqUb4km=i*C)O<-9zlZ8ku%CECc>^UzFX9S&n z-VnX*(*SvKvQ8>;OU(@}(zpImKm9a7@kIZ0->sYP9O_9$VrsM>ZMM5}a$A@09%^xP zX6_kkt+a}sq%MG0WV`uASO;>ZKctWs)OiAH+4R0nR}PEUfhbxHFmFd=4GB zopPO*SJoS?uWavI!>{>RU&CL|M7?_!pWDjI8pYF5PUp&;4Zmsb#`*d+~`;>oo zZH~xZS?l9w=H69ng%Rd!{G4ivs#998NmX4H`t|*^ZalTEUotf6ERIvY~jJ77RrykXW7CRw$VSeeEXr*+s}@4kkz`^W4aDe(lPzsUC&j0yJ(e{ zBePY~A>Rl?Kpx@?ITfA}MocV1CZG>kP(E42CPv8$rkgBB=#_L#`#tUT`&X@`tzJ97 zIHR1hc=F7d2%mpX=F!SP zashBXi!BErkC&*-?UN%jS@hJa1kbZ9SzC~MlyQ~+=bPf6U|2}Y|3z^k3uyI&v*^hi zL25i6h1rj8?i-!H@j87iddw7*9uF6$ek567p6fC02eJ0`> zs{^s2ZmFC@j~<#MJc3psF1sb6Fp)FrvWfISR3=9N*(QG?m-YB8dL$s#9B@M-4ANju z$&ER~0Vr9|U_)aS#bs6CiCOeuYhx3&BtvR+ybW}d*d8sjHMXernUZ z>{?b?NC=sc#g^?7>&jH%qrR|fskV?+esUH)8F2V3*?%@uCW1!tyXa>P%UED%oKDVO zj$1zQ(kyyG?6P;XiT)Xz(UO&n$oRARgQ{`Eghp+Z?D9-{*{L80CDWbkJ4r}YYVvwk zuSjHiK!%eIHogzdqDKPolf0l7=~{` z2enA+XoI=aGt}v1;zvmPsaf>mNwbzi-|$nc&zeN;={D=;6B*m&v1yUau^TJr=tJTH zoJk#**(8x!$$HWYg@64N?W;L-Nuyt~V-6)~k-7Vm8IDpq=8ECl~kLPAnNSq1@)|jla zoa_$lMEk54{qiAtpR(dyAA#}Ukxb3&Hb&7;t@{;2tye7i1+7Kr4?NxwM&)|7f2mRb zl|wBRU*g~CB3&V)@J?zDX+Ar{>hR0#stAjXBz=B&JL!lFSC#@_9&fl$?<-4@9M-QI zYNz@g{Gdmym-&h}rC)qK`^KmG+)5*xz=pGYw8)L7BmI8KYCi26cOHoI^zh#K4RVpr zFpf?<)jq$}K67{JNXs>n#EvYVez78Y96QaT@#SnuVlsZz4DrNljT!hgL-cAT{La-l zY6LkY@UZpVNlor`Hj0Oz(fY$SJ~yh~-)8NRHd@l`b`JNM&KV~pj`xYE%ogN8?${{v zlE_sg#>1Jrc*CqdEDnC%EP9XvK0h)Lp1^=+TDce{e_JD9ceK zni1dljK+{J7%sSvuTyRCb+hR4J&-TdNWT4sLgE}!L8dEvnEVY72hFk4?n0e2KJ-YL z5yXPAS9D*CY(81@ckp7?Q&M4}x?*wg^|R=)jC_gNBg?$KnKQyfhrEBJT!e>_`{C)#s%(5SUMTq2wN_E_^iPD*-T`(9<$?-=S!`Br>}!A0O~33-JA*#a>JxrP_y z%!1<0H2oq;B9PxXM9-}FQAbic@DGTE4vgVTDWb@-i6h^Jvq_$1cRO`~)8$p$8-6vZZnJ$%o<9tkTIamqscDE`|;d*VxD1z zZ=FRioFSidI{zb~#s{4kzkcvJib z%s1v!@64rJJ?F>^O@?b~cC;95$-lAmvFmIP8e|0)gxcdvzik#hZ$&5AO!LR8;3X}m z?L2xiF#L5aK#(skFAn~|EPA4Ea+b9X(xUgtN+w!jKlKEP;n#R}y)v7y*B_iokHsXR zI42jvOQH{T!kj3;fV7{^m~RpToAH8wXcj$M8!qatJT5MoJF)|Jnk(a_acq#erU@`S zdVhEpJ$h%}MF_Nk4K-)R8G9B>LgRzZ;7u84R+hg1ky-TQQnkZg(Rh&^jU)3$$X~?b zWFL(&Cj*sPbeq~7eNd%=TV@eLl~KUaNQhY#sj%7R4Htvz@q+X&4*u9Ida?gJPE`kq z5cHtzCk~T;{v8*{FnM9?)KvcQS@iVU4-1y4hJ=vHNFbRcw?<>0X{$dhAURqbeETeV z^r%o$dW^sL$ydn97!RE@W|Cx1;bwZnAN`40^hhP{#Op*_P$K{67)RpU*qm50JeDuA zXXsDPqDK~?2cw|DFc7{)-)TfFI-dkL#cSa|Tmv8fsaf>m*La!ax6F?9M{>JNFKPw}|)DzT#sL{`sYDOnu4%1)E5 z#ld&XqQ?ryi)tTcAvxrRe;1|E3|hjz(F@wg`al3A<^P;Tk7a^iSrQ&CI0>gkCA?lD z6}mz5Sk2J$H+p|@MXx0D`A}C^C){n;T;J8?-aYej6YjN}qvMHxNH(iw=J1d=Vnbsm zVHC*1oU*5E4Vy;B+-o;NZ@vC{dtXe|Uz;zsjf_lp%ZPB}4X~R%cMkPr zjEjF|sI9JVxI&h3O%%XN%R2RU@1DiUpdN7!yJQY&T;u=`Nrz9(9c#_c1S|0|Ec0LA;N<)&{yDej z9DVP{`X0;Lhw$MxV|9Aa;lbu@CvFg&BYUj8Y&cwztUvE1P82_hLZA=WF1Va-@hLbh zgYWji5qh;YI%mXxYpCVYqC|Y~C~RovMW3P^-c0_&H{v!QYuhPt1&mbS8NPxjLDz*hlS?20UezAQYMhlaVNQ7S7?P5s|o9Qd-L9;g~jg z04rpyYr>-&k(&AH=g<#8|n8BwOQH&)hBltIi;`WUJpe& z^r-9(PiLfXt-K)Hy*T*3S@d|%cy-=d)`R5OHk#{@G+T4x&}${VzIr+waQlGvU?@x z@DnYb!V0Pp&_g3k&We@NgVbBV9H1n9Q=z}^k_Py z&g+K?+(k!1L7YT_`3x4GjiL+e1if{Kg^R#4b@iXKHBayTxv7Q_{Ib{VQ74oY;d?en%I1s1*FAo0WEPAnK+RO-9J+1SSS~M0k zX>a*5))oSgm2x-b$m|q9^V5Eux5B3v~QU9~2;Ehd#&$a6Q zWTn2Kee>k9#(3B5)1UB6d-7XHKl`6&aZ4Pg`XSdeirn+; z^p97tx(-cwR>T{`#t)Ol|7R9G_P{DiFnsVRuf!+Og;*4l51%Cm;T?8OzuYD{!l@cx zaw(CHtO!^uVk`B*IQ>l*6J5lXvM+eScKzrqdaNFwA6#U7M&UCWO;+`Yb!Jgi+VIWc z20eG{qRq*Wu>8g|r4KMIeCuzcG+THX)D1V_8eAA08EZ>t$=CVT(hFwMgP%~q zKfg!bdE3-Q@Y!@uMom1XZ?L{T`F+u5Z_fCPi=K&M%@uz79~mJXFnl7M%rLFcFIvHa z;N~29Fm|G#NCG{8U*ID$;!{|~Z26;4?5JL3d>=E59vPeLAgO1TMvjoS}QKM(C#X_;Aviv`3 z7QI9z>@~k>#MVSqvpEShpEHP;d+T7#b-KZ_o#m>eaoAa!H}9bCj&h>&fIhSL?&!m1hl;^3#Q=*0_8cjncp zQqvu>?|5dMk#ikhV88cE=9XmNZGneqR44ETkdiqO%+F`_cuL- z21z~1BZ)AFOpr?KPnkszVoT0dltPA}v>*<$jUwEbd4yp351yH=V*_3~i=LPwQo-ZK z?(kCaN~n|A=r_D2kHvf80PExi#yK*}TCSS!}rjQp%FCZZw{!fE;mv-^c02 z!Os|?_oDWspO>`^O6m2bMxpkhrLOa3?TJqvYOgRnoI`(L_V{%Dg89e@k3kxYk}dEI zee^xA!6$s$5WR{hx{bC|ZnOXHPn^Sj*oV}TCy^+`l@*8hZ}SZ$XMHU*CGLV`{cmyb z=|lADbkENF?Y^(?>)YH9>E^^aBeT+GUSP)L-h+eVH6X_1_p+W6Kdw%ZEXxXr(njdX z68O1ux%XdI-44agGXUJ?YQAb$qNmhVzQ5(?oG9S)4=w+H*z$h&wUa}%LQbD*zdhN0 z@B2Yn-j@yatz=Yo6gOy8a0_jP&frXXXWtK=m{&aGH%Ta)Bkp_oEP7%Ba?U=&DJ(|j z!+N!z#HN`8aY}qOO9}VOW4&S)Jvc8l(TU1QF{%(BWU1BQB7d{WB2k$$R-Dax5Aa?o^BTjd)$!!4JZ1qbI1>W7Av2)E7=7-(o4F# zXm4y<Gs$Bt1g-@;$#dO0iyj(mJqr*_ z%-;vin>7{&HI|iy^Gz~~S&?!p;GFTXU-FYiqWz!_`on6&J}fk>A)haL$r%gA%}==% za1K53p6V=G%C6xjbkD=#Zul(6M>5$r^3Jp91%AG97CrGDn`~@+6#eR-u;F+}BX|pb ziUze`~R+&@3~+wPBm ztm1(V+bw!dBzkc9DGrzewf$?eu*mVMXLy_Pf29Imz5eV$y$$aqWEtghjFa8~NeMRsr< zoF0@Ujy6lyuJ|e52vSoa@_9q_DwA>42;Vu>QtgYcDz38NxIAa%iFw33{A#LLv-$@m zio9V#C@nk1j6O93cq1mcXBIs;6Z#Z!CDS5vMwg*J8BZ}K{D-@!!;gN%KyqyFnnjN$ zi4Wjexd~cmwo~tyOoEugm{VU3?}{R_GO;-L{2_YNnXRmsOxjc?zhJ1P7q>C`xzJ=d zx5l%;{l?;&X$W?4@a~~DOU}u+s6sT6x<@jfS^*Y_EyAf}IN4kI4)F&L$rXL!EPBbq zk|L23ok^t{34r(6X*9`0Y+ycT$34oN!{_3*pNa==U;51Zmg}(h zH}oL({-Rm@gM;aSd~kA3tc~0yuaeALvX?SpsRptxYsE<(!(DJA)}ZoJ9mU_-q9(ZY zbxi_z{`FCO@y4vok8NJp`sQc5_00^zX0?Cjb^ASa|4%hPm-tLn_tF)O^6d2voOxf% z!bowKS{ikhX~oAtQ;T}>*#wEZ#L zk2T(vy&Rckcgl^7tFj2|xviu5zG&8dr0tR#HrUEDE1SHkY(1T}{v=l;KMC#fOfoTi zVfoX_s&xRD;$ELRIMiDrA+(!)b76>8}%MOzmwvKi?~$V=BoT`NY(eMcJQ z3}Isk0j7W>#9uI0a+8m)=sll2cg0e7FC%SP>jxVjlE0BR`OwmbKQ@b#_yPUEJ8-9& zgF7p}4X*YH{0p5~lgJ91S$E6Zh@|veL|!uFu!EQ~HRk@sG4WQk5f}Uqije)V5`B4yUfH7c-qx5tG}K1*Sud;z zST!K8@Q!>8D`}>Z;~=}qfuw4c6|&YQTK@1XdRaG1Z6V!A1gVM)zi5)U-1-k$AzAvs z8nQ+-=&2RGlgrJkS}T4=R%GAWB*wbJ#dd$;hnnnsu;IIYzDWN~ooiZsUwh{9_9U{hlDNV8J+Bw}!l&fm#bYAur-$ej8XX_)mk+hu zrHpMLGyJfgvy_=#T9ZmOb&Vv!N)l`YPqCm@$9};qdSodX#AJL(HH5~C(nBj(ILIeP z`*0d=fbYesUonfG>`GSRQlU{EUZkf2k2I^Nh;HG7xSb_PeWu&p)~(_5p^mk%7}i8i`*P}mt$Z*p%a-M=tItjq{B(k1Xwz&$MM8`GI{4!zH*3O>FQ?BlY^|j z|DvI`M!4`*&%@d6Jn9%^8$bQxAs&?-V9l%%i<7eAXDvGOOXGO~_Kq%!zhy_D-_&Wa zXJ36{PA1}eE^;I3oonIfX&Owy?W7KI*T6r zoXTOCFFEtXDOHbKkxH;c=GZL9Z@bNIjvZi=lS8EWY9#nKzD@3!)k}R->%nM|9WP^$rx&HSnVApdh9x4)%tu4gWe=CZ4`=QqB%Z+=gBR5ZRT^#(1 zA#RqXAhl#X7D4o&zLSKL#r^TwVVsIJHC1y}q0LIXsdk+QCn9MlA}LYauN|USxx8tg ztH;0Y)Eq568sVranz{+;$<;d5?YdS%C zVeqUh(ed(aIG@T~@(mq8(y)Tt`$p&$k~w;uzv0w8pA%QUvsua93i{}Z)5TdbkZ*C? zUai>O=^G{6^-g9&&R(l|@9TzmQ*wg$>?Z3;$6*LQpZ_*HWIJ`}V$Q1Ig2>IyO|6f= zafn_;n$yul>T4{UXUP=&)+b!?fCTHd~DmS_iq_$yZE0K zaa?D!MUxOP{{gqjB$*%I=e$L;AmLdwW&ZQ7(MjdjGar{p4rWmg5GMVC_j(F~F86Wq_x$jinB2>igJlxu;GwlhQy$9>9{?4IRYmVs_e_}@YlH^Be7mmsQ^B-~p_yu#z z5XghbCEwQi^^HUHYQ<}Rbz~n;uZsL#Lv7crxnuWz&DvBo`0pNidza6v+bq6msD)Z@ zRKxaU`x9ID%|q{272BmIN%9nKSR3&leg0^rS`yW4!FKXWvj1$LycK*D-L}1RizUCVb1ReyTb* zKAxO~fhtAtsr*j$J*gLi!u3WKF3Rzc>u(*RS8?>4+w7@(HUAKa6-fKu)Cv5)p_V!# zSZ^t--qqIcA8M;h2hVBEk$)5qCmNA^H2+PZt>|sbbA7_Y{NY)>;!ov8Qbm@$f;CV!nFWr{<4@++{vmOc*~{wa zA6e1s@o`zneZH+Mbgw<`^~38G61|G&%I<79I?jJd zKRRm`pv#;9MHjL@5ZPc|pnV+oyZ^Cou&KA$;)|_se{8R8ylmC`%^LdKmOexk{_A#* ztg7?++_(d6MB)oa?Bdt1R=<6y)zaJGaBB&)h2~h>U~Sn}(wRNZvB}V3vU9cG=%%xg zQ4~GAW-C}WH0dMjW|qtmdS-;a@L5)Pf^)L=;ij`W^z2VeENw)*YpQco&nRNdu5o>k z;mnR}pGS+`bQXH!8d?63Z`pqzOTN7__py|BEBV;2rgo#+96s{3nHl=S##w!1<=J&S zg(}!u=!Fca?W9w&aBfr^p;xte-B$IA!=q2R{If&tm$xp?q!MDi(tL67=Z4y!W_=@$ij}D?QIt zb1D1PcbK|qL2M@*^<;Zq#YXn2ltrDkG4(v_?YMDmL~_f*Ri1+$_+yoUC6)bPJyRhC zXIpu+&cFsHw+a=waczWNok21k#avGOr6Ecs3F~}G-pJ13FKd1N%R?2wet8V>FhWcc> z4p&&B-iM3pE*ZB#&FTMoCaPMTw)c03+Uu4Mb`$fnaF8RPpL|}{+r+6NG?7Z z`@I{N@BRIu_iDzn)?}U%c~@pt?p2fyE$3tbD_6-1S!a~P&#tb2FpD0P4e5)2{hLe| z3E}nRc%1{FLI*OJ@qoOo+>jIT_dlFTFBy?kw~;h8BFQMrkH`U#Ou03f6&Ga2Q$?a8 z@E^^hCm$_RNri!)^Xf(`YJq+EcKTuD#w3dIiE1=ikAFOio@f=OP90Nfnv4WL&8_G~ zhDd~K)^Jj$1-E4w++Z}KaV0Nm$c=$kTNe+fWN_4?p&UxVJgNurTkg&uzV7>H(NnFJ zjF%XKZ80{jvm~-5=#tWK0+!OJtW)3C=>5}K^t43cMWW=KELtzg{N*$;*&DNpqghFW z*|JB&4MubL$xh1JMFSI?T6M{Ku(*m{OnmHrqG8!zv!0ciA6U_=997T4)+fCFKcCer zIe^R?-e-*^r-ai+{ALMcg;gFVCr#dhZ|x!Y!CCZ3iSe*H$ws3OE1OHQh6j=7n0sj67%`gX_gW^Vu5 z*1~$diyMBzsqK~uV`_<)-Szgrn>B9sAySzfm6fpMAbgGk-AGLIn7yK(?&8V#f`9#8`Z#)G-0Rvqex|iMcQ4N> zvD)?M)}2`ux8?R1+4;LyE9ByAJNuqoJE=xYR(;xjclY!Ec@`H*JIS=KB)dw2B&{~e z4hQj=yWpNw!O@f;On3B*NJ&K*+oL$11OIi1LS+w}xAS1*+kYE+t8U$#o)BoK^3$y{ zGMSGbS+%omb1QP4zFTj8UR!mMg?YM3o||??cvS6OT$6$A7Tu&X(q8$5E^R#@OWtIb zesrj%>RDf3QGM%V8hNUR8^=lRL#@64Z>YV>Al%;Ga!$=*lf8$Q=ioXgs7CCDn~`x= zYw%^->#g;%yT4|nwaPBkZr9Ik8hW{n?0*iuT^X7wS5&w-mGynCm4n4dAF7q!`^tzU z$66bA!|H`x7yfF)Ia*4Gn9_{8} zAqO?Byes?w_XH6^B6YqxPin0VvXCoEteOf;5z7nr_Oa|AUzwkEiLov|r?313pR4kd z4+)xrIrK_Cf_H`kf^v8tkpUddFT0f`^tR=p?Ad3waqjEwPn^};>{!fxMzIgfVm&l@ z3%v9{H5X6~^as5pnzf=SyO`dd97EK(ac^#xkVNI|?x&m0xZFNT7XMN^1MNmr9xGX`mlBi$kfDAydgx)H(}pR8*NAs3K}OHT9|Rggr#gJspvs zS~=|f-!;mgGSpVhNLr939_c}8!iD8Z)&q^tsa-5S+BZ7VPU*DjSp2t=qV}Rrzf;BV zMB~d(8)~hh-fnMRH1uBCo}6|}lAI6AUVXyQ`^Akrn@l<>(8}LoTSu%j%$)!-!i}l| zoURDLv?K49zOVOTy`@hYYN@#Kj#f|TBth$u+2#9^q4!I>>U}F~W;LzAd6{LEKO-Y6 ze^MISag{3akrs+K)xxfo@Ry#bC41Ga>-O_x+|n`9r{Z$;>CPrIq9C_!jJ#i~F?THG zO%Lc$t$}{(P#e3DQ!J?!QD=OQ^rYrzid`zM_?fE~PHypQZFw3sMv}H~S?>1G>S3L! z>n^I$@82J`RnzGcpFT9w!Wgmxas=5UlkB6~9xDv;gLXm(SyZH`qK@a3)_O~?8EUDxkdfJ;7@RL>E3cXiWcHRojGhaU^t*@#53F*$c15qW zcU+o8*ZV60^X-+b1U!n5pD~M%G*vd*K9ay}5Q4 zJ(k_Nu$7AB|466!M|RqLrhZrEn0&K9q?#9i@ZIwAs8E|F+Mfx@i_aj5Pa7_;X%E)*UCTtyzJReaDyV8~1;{!)(Q? z-#kRGFzv4K+;VD;zM^r(&lEXLci_qU-@nYx%89?Ro$BQ@!|7Q~c{+dh+Z8sSJ3M%G z)1}Kx4O6@Jnnv^1q4Afz=R_LoQLL;Cl|Ska$XK{tyGrDxtQVyc3p##%qxbqDdWE7k zM^HN>You=&YOQ*2*7b%Kv1#lWjg&>BkF?Ut9*>)USv6Ld&AYz!{*ANfv5<0ksW`WK zubr&SLZAGD^}^^d`Nc=KL?k|No5&pNz|P~hoM*3skoSz2$XaM@kyYPRzsciSIhAkv z>{;~0FWRPI@wa@RUhoUnGmRv58_9*Cq)N!Q7aF}c4bdx$vz`@tb26ci_+%|Q7U;fD=c}cI@oiZAtSu1PkCQ5LW<(; zbMFqTCT{#WL-Z;S=3WCgGAvsABXU(9)QS+hVdTlGX7BO&_UWbeU9wx%_JyIg3z6To zv_`q(gKySK&K!NL_4Br&wu+xnGk?HJ<-7%QXeAxLtd-+%FbZ#MWt%+Gc$UD~&Le#3 z^t8(Vvk_(}6{o5bXcdnOlZjrkU&&K2BmIPrF0Sa6H-0|g_VR_X!PC=l+$=JOf5E0~ z4;g2dv!_bTO}=p}Rb4D8pN^lYB%&?qZbR?+$iMZt=kAsdb=S!p{;6+acOmnvC%~LM z98ZS3P-svPGzb&Hr|gQi77bUA(5o5W)#IQ0Je+~DJ=+pI%_YBOh&N>mWHCsqI1Iu} zB`hiBALRmB1oK6XtpKqBu(_F&$$0A!y*j5Rd42wky_}9D`FX1(ZyRc{Mxa-)2n+<9 zkSXIKPdqv;rGcy+YzOV>zse|{-i<9I(p1=PI)Z8cWpnlZuA$bd_u^Z77F@*B-&`mZ6<$yVenU>vs>eUVOqI z-jJ6K;!WM5HDUNWXeW6sbI5<2C7fgF7cDl=yp)ZfAF+G;riI>u&@Wxt(ooca7AdZlm2jqD4C zTB~{GM?_Jn!)7h?mHemToxc_rh!o9cKIMbN=pw;)&!Q)?Kt-g6YOoc0Y!vot9_}N$^2U$6ibK}d|lP{V@kDLXKCfD4^lH7N_kOx+nGxPM)Kb|VaWi?9dzIf$bvwOh8?xS-9EzM% zYQ>=$BV|n&Et@unQ|yfh99>x)`CJhuoycws+F6-d{vWm=NqWgrKQN1)k-_z;)FPWu zqxe#*GDb8)+YlRh<|~8h&60av=8TV3;aSiX9m9N~=Myw?mU(uIlNqrzKkj=z`k`6$ zpaJrf-3U+tZy&78Pq5jvFxBVyU?*Iv`OTtRVCIa^93@7A(T&qwl6O5}$F<78;2w0w z^TKag^H{We&m4NZ5C1{K!~wC=W(^0kW&$Moz7|+^Buv zjK);a+no*T-rczC&*qJc{horOpZfBHYuXysHEkZ=)3S-zG~WCDnl@|KwEO3;Y4ei* z-?;k!O{@Rky!!twtN-7+`v2>f|9_}i#xHIBe{k8x^(zY3t^QXu?8LdIoxuMYYm~{& zJld>t-Z%^DMmT5Wvb!gtj&s{%FFua)T{JbNeyQDGarsETzo+4rO}aNMXXvO=v&2(6 z`(}8%<++l?c8pNcTWbiB&)u@bGo-D3{Ddz@sBMp{X8r72CK*T1MM+6%ACEX4#i$g# zcSUEH1z^FeALfu%V5jRdoZYk_wz2Fk>_}Z`YiN3 zS2TFXdah{jw6xM`<_gX7XR{9W(VC;2}Vo=>#(hGyY++qF&UD5*QD<$C70mbbMP zN=>g|z4R2)ug{7D5MMsK%H`v@yzYZwp>S^h3>I%aNv2`%ymK6_T{G&P==@PLdh;`O z`s$1x$K~}Ig||0nR6JatWe&%^oH>m3EZf;XfvB~&j;KUTHOFOdj-Fg=RR+KsC>(VzVEapM^GH0ydN^K^XM>%HDRx7Y2M+mi3D zWvB6xn>{a0xe~3v{u%wcGOcgx*l9Qut>^n^Q|{OAo8NXl>fdChc8%Le^6m7!(DZzI9e$L)c3)IbGx&3xnE}a@XI&Wz%sOD{1Tc*FQ<`#}VMV<>>8X<|4aU08wc%oh2y87N{%SwUOcmN z(j1$%wt01S{nvhJULV2Pwtpr0um9UKaJK!wl88Y6yG_}r+r`1DPb!^_*C{_a)w^w7 zps%!dOxMqXnh`yF)VkK4oRj-)*mi`3pQWAMZ|#baJXv~nwAZ?FQIbBCBz0Y{{s&oE z^(uLv&VT7xq-{5kcFS9}wx444X-e;S>E8A##&@N3X&1F~GyLZ1$JW;(PQ%IFGq-zm z$LnslCP&G|?$(dj)zh@zrFx$wI8E!N$@^#GG_99D>~FoE=u*|!KKAR6=inOlU#Sy|*FQSX=gG1$(>2RN44IAfoVIt4w;bF0(O376){k{` zkJ`2+f!TT=PK)n*26T?TZ;q$Wv>BR4Ub|3BR*g63eRs5N?_is{I*>wi*%*@;8i~x z?3WdWU3PblpY3!1TuuYJwto`7pPbU^=b>m{ori0li2&x$_^x@FXaAndIRC2sI}7_aZ@z0~=4ib; zt2kpFZ(g16vzTw^2Pbx&=5MEUzun)BR{36;`JUF{ex&3PI^yeVpM}{!60-=srgS>n zyR$}iltwb13+?VT&bzYmmYtel;H?)y@@Yv*2B-+HF9U%j65sCaBw-RVeG&32{h7`^>+y(=2;yRxRJ z$4S^{9iNTMb?X22SJm{Hc|OT?D*D!I1^P%vWo%bQeV2qe4{KAR&$cowyWLJZp52uY zyGK;Ewj(6F6S@ry4}DgedX!%7(~}f*b*(tPKvd(-rG98Chzj)S@i$c2&+Uo4q|FsBP=R+1l(8+;RMPcH8WI_H?|O*SwcC ze|F}5J?^|(&CA=IWdyhD1h2Dgzr1S41ZUg+w*H@O``a3Sn)Xlc1Ixc0t$)w04=l`e z9J*VN^0qnMKPmJ*+VU4z}ZU9*t%5Y0dBy#q-!B z(XRK)9vqG0Jz3JVo$cI*HcI!pEvq(a1$f&xmmEbG_92bu%f32%GuG@QJMDQU*S6Nk zy1z4b&gSWR)DlhY+YOg*$%Yohg6bKZecW3hP5XDb<=bo9d(Nx2Z%uE+B)x^iJ^T8Q zZ=Kl*5&K~|yx&_Ok^B3QZ%Z!vTO@1$Tlu!*JoLOft=hxUlE)q?)4Tp@MX;Vddt^77 zQ9`}z*0UQ!cMZ;5PNVr)rIW_bC)-uF@-BJkCnt1y$a(oe2~+IgHq0^X&`%OQ zd+bos-?`F1Ih~d1?d+T1liDvFJ-+p`lb$O}>%Gs>$pxvgj9(u+F%I9)4r8gva4)N@ zxpkY4Fvido3_;68Pq}Bbw=jmT)HS3H7z@JcEktIIMpxIiUPD#9K>l??PVi3r;RwR& zHmp-8ai_&tu|PcY)E4cIW4aYT+BcDa^0H@di>|z0zxS%HUDdVa-6dzOYlUW}y0+`Q z5qPt(@Nv2(Vl0FZiy#Il#ChBe33+oj+S7|dA7}6RPrCY12yH)-++O=IlCnr=KN78< z#QU$0q+9so;-o&i`^VB_j__$t>xGH-w?2-^cH!T?20hh--9D$UnH;YN#m_6@bD|+f zS0fbPD(*>UCmJ?y7ETs>k4N5T>EZCCP9~NEjnu?)UYRqAi?2l^S)g4gEVUN9F;aaO zYY`+if+?rZk08kD^CNiC^WE<}m)Nl1ebe=njFo4a#;M&R9IdBwRvgCjZ+++AZclc+ zb?*J2r>R%2Wt=|VXKmV?O&d^|*{M&FY1w6$`&m2F`QDvx?K>EsoB1vz^c@;yK;Hcb?1G#p5sP0iejwtZ1a+CR35T&$v!Jt zI%-6$@-Cg(RRJc4TXtb;BS+6%@P2XPXe`r_)aWXpwmT2@&BMuOKHhG99jCA6cUjYq zK10bN&Y6o%dG5P@JB^xyn(MxTe%wrNw_Y(;Z(XjuM@JdKF20?HY9B$()Y$k zPBo)C%?L`4d+Vni!C7M0LXdj74<+WitgF@Yv4^`6XW7cE`qvv*F>2kL7>-y6Bxk$1 z-oNb@A1e0lx^3BYOB2m3n?AL_qr3ZPabeuEw!dAsN~8NH(YBK!QN7+}r82*u`?94~a@A10V_h>yA^D*7oI<9-uc>Twd?rlm^-?h~31_`d&FF$m0+tGJB zbqZ(Ix}KgTCO)lYN)DBse=aoP$Ae``jX?7BQ_HkFitjmuqvxYXz0W>|luJ6vxA7n zRm-=Tr@*_?h2t!rXUlpY&F3p+`AWie$09Y3{mAS2Zu!_Kx^GX9-%8`>X|s9kvG_jw zw4E{TS%=Wuw}Q9sHBhT)cmK@P%$BVhw;k)$NM6Zkr#4;T3HN&K{&Bq9MhkOo6AH(p z0mi_Fb zVnxdL;c5Kg_^7sRI)AWjOMF^byXR!>e5q%T#zEdMnLRqz_GC%lcK&_0&FDPsoT)a7 zDv9>H_a-EwiVLnIa4F~mhttE!)=IUd8t1p{vt$#OvEfe2Rt#(M+ zJ{pm{&E934`R?kz*+f#CGfOuzAU|+vaVlnpB?ai~PWzmnG@2fWT%UAUV?C@2anrzr^n@|1{FaKCQi(p)3M}il z`NgxXVtDUTf1mw~;{0=B@QQCbo19`+$*%6=#m(ss30yA3*fqkZg=e(i6)X1VP3^sRZ=&zof#$LVdZdCZAN z|9|$r1kjSAI{P6w5cdVgpePT-fJOuXL2yG55k*9aM#s#U5gxu#U~py-H{!%4n#6ry z5;vkE?&7XdK-?lOaZ6&NaU~|kCGn3*Orrn!>h#yAx~rfXNZzBhD3Pv2KvRp->% z>r{0&AkxB`l%hvc)t6FT&vNDI@AJXH6TR^2K#3KZ6uL2@DESR)?0Z5L$ds z9pVAX8@Q=6N%FN%Tf%uGA`FvMj81!u#~uDtyJ)4hlNzqN$M(c>T-Q{p##Y9dpC8vX zAxmQp9vA%(WCEO&gQ7bkYvx{(ji-IAE8j1L;C ztZsb>^Xh9M=TOQA^Yg1!AFdgE;0$N=<~k?0+H1!@*j}ZP5BN5c<}S-4g3wPRyT-`C z=G3WNsO`k+<^y^qmNq9rDf3B|`vELskedy~JKvQC`Ex_tZ_z(?o+fJg4$D zK93>abwq5T8S8ip9dXw^>_)qbj9LH1d|3O%j8#2QthL?6TT?XO2XBmQwY7&Y>)#Uu z4~b`C@cwLk>jZDXwm!h`bRT*bvH-|cz(ZS5 zO2>?A?A>1|rOf*|E8CCXtzYwugG0ZczptT58&V*x!_&YDZCxoZpfzhP7Tz^^VecVa z&3ciW87$X=+@3?3hfn8RqTj#U6E@v+hR@E+IRd8D>#`Y#6+X|@KSE_eLFZ8u$nO8D;0FL(7WY7hpSO3I(X3Q`1UU{yQ zv?q+|qKa|7b;-p9?Wmw^CCh)$XID00T*-~%OWe4(6aC=}N7U5ZSt6b`)%O^H(~uDBL%n&- zBf{tFU3>!)Z*Ie`0n8E+Tk5<`qlTQBqG_qYM#M7RT(Qh6*p9I7SZ(wQ#x2SkIHj>k zbFQA_721(uj^zmLcicx<)T@@Z4_16+A+(k87G?8md*@QO{F(={Orq_su{@%`Um|aw zVbo5|0`i|yTFE(GDV;ga)l6qb8Jusm^B5_ATu%2%A%%16Qa*4NKk`A}T&!_rDaS)T zAWKLYw>KpO8lnngbY_O5P8rZ0aHSc?+di|8Cq5paZY>YVAiuQ zAJNnhU_+`H1X7RllF56IeNkh$-eYguo4of>l0a$N2Vat6@18{6y!p;7Bnc92e8jI~ z7us30*qh!br&d#r0H1SXlOvQe+c&K&p)bRh9vY>zqeDP2ZS*0uwGB`y7qnL>BmYZv za9Ayg$+5pD8e_z~9lFo)0(&jR9(`trSKcB5y2(*oj&q{&VJ#M7`nC+9j55&2?>I*& z&Ha|e-Yq>Jj!;VSeH1)fn_`pmWR^Y(5@(oF>!;;-(>liITjYPa-I`vWD7kAzo+hVN zn-ilfHCMypvP4hTXPY2Dj5}6dmH?5yDsG!l!~6-gyDd%Oz5D8Qi| z1%(jtjd*`;A)d<#vs5;JvAAot5aZTtT8kOVA=Z>>r+hiIrwA=-!HCIK{MJ~;o`AFG zV}^>pZj?^$4TQ<7r0F zuMzpZhw@UgXB9HSXtrBk#yzW$tJ%NL4ze-Knk43hWo;#N&U3)PdSAP~hcah(7ICDoH zgAmLX#&>Ff&aB%_XT&wMRyMP+JeKVdLrsheK0LIAhzC`_CjGKD@uh{#r&Ze`T9!Q> zAx+-mWwVJx&z z!;b~Mo1CYt1T^3s*)Uz&%ha8^NB7sKi&4*|*LyI~opP>uRnAQ_u9!ArwyyfeaY4#rBcp7VkBpLP^qh80u&JA%9x*l;kd!v{ zCSMBy4Em(m!BAaB)GphPO8ruWL9hHmD`VT)1_)OyCU#>{W~Ip%A24qLgeG-&Qw z#tebp3|2s6nx-G4#M3*&mr_E@d>Gm>Cdh|IZ=tZ5*KKEo+n!8ko2Zq7RHi?WdPo~= zKB$DbD=||Vw)cah24ez?LoJH*qtLbRKF0i*yh$m`K$y*>%+W`}PB&*S?foq=zK74< z`A>V$mxZwCx67p0-*21ln;b9e8xgAEneKfu%+WjX>f*uVz0*d_rgvJK+4N4yn@#Vu z5$WDZJF~C0exOnmlYRAWO^cMXhA<>F$Z0diHW^kcIV7|&N-c+$&Vht^gtDBPuIqpr zeR+gyT23v;l84f~I&*66v83gx=>yk(P7QC7P;IwZ1`!T5+>d6|*7fVcEY=Y)3p7g+ zi+NWv9sxFHrRdj(%}3cgLe0la2O+eDWjn?FcabUwU==Apn$yr2+Ajs2QaRP`b)@*3 zI@*{dkoLw6g*I8_8QLpAv%U#!IzBXQ2q5G{ag1jePvqOIkne!V=qpF>3A@_|Vk9OF zlk?qQKLn;0YsK^)tCF03nx+`fa^)e{<^vu_xf1Z=PmS0c25qiItor6CF?q25`sKlY z6X8nOfu=mzdQaRwfIp!=+4#!o)znw?Pw!~_AGUw$<}CV;%hPlgEiO^C8YWSxmFwI$ zo?$(jy57A*p?u}qEC#K-m8cCdpWmlpZHdWS2c*=N_YRD^XKa(Mi_JD(N3PDOoTB?Q zxQCi*@JhKFlX6?BH7QTU&-RRCw;#o-0P&t&%9~cxo{~&i&6R&15;_`MI?%@AyOj4v zTiTa$eL;)1zSvW4<{=1yF_%%X3})Qswk0u)S&{9Y#;e<^r7xXkL;cyEtp;~X=WL=p zfA$uO@?!7v$&-}Hc^2P0mLr{$!}OzFvxmdNjM*`pP56=$&jVOCem;_7HX|k}&>8Bj z#ZUdZW)vvXZNQ7!6MJ)v*^^vdZpIHO>oI$&us7QDONG6EW*$=EzuP7z6>-hY&PO^JPsO93m6ndUm7g`YXg71XMGHC~Zkat@ zt-3tie19Ig3oW31>XQc4rQce4X#jMa-NvK=ds~U0+1lyy89DxU8VQJ5Q}Z=B9N`RU zSWlXd3+y?Y+8-N;&A&eiul$Oh8MXXn*G2t#T*nE1m zm4g|Ri@b4`@R$acSX}Hco2Q31+m`F0r?FSNrp3jMGv%SL-i2HExl6stuTJ!hV#H@gI3Tq z&q~ymOu8Q#STp9f-cia?Q|n5erEhwp=9?{OorWBNS%~R-pI%;wO}B*@R zmlxO!N_UP&$%|WNhXt2X;HEQDBwXn3zumdmyGt8`n5`R3IrnSFD$ zroE@^8$Ydtd7j*!Lu*`0XU4^=na;$KtKRMPi`d&C!ZmNBa>@(B=jeQ@6w>s3;Ot>F z^C4F%SFgM)b^D*opRZl%lfwMxZ&jMREY0Mwrj>dB322RV;?KyByuddd;2F|<4|#!= zDn{Dm1K2n6FI1L&l3U<35O? zbiyJLMvin+l2=+ffoJy&05!(kB|NI`DCC!rn(yU`%`w1B@^uKg4y6pTP1}+qWt7Nn zDVxPi6PTJ5sW&puf}(vOk%sI%Rt2?iZcDl_CueN3IpFT-vLMH2dd z{GAcGZ=N20?h8DLQGD);8nkt03(Wgk+)Rs6W)09MrEC`c$M;1Hhkt7JI{TT0z1hu| zFpD;P2~*y#_N?P%5=1>S>9G>#4sv^*)?#8OZ_b{!(PFkOCTt+>j4#h|i>bWsm*?3; z^!}P_ETZ@Cr{f!1J&YO|wf34)I@j8ar{eqiXK&${*{6<8KA!2dj#-@59H&f9pC-S} zy3IniLS7()MVP*3+RUcuX&AS6^I{g72~4}Anbn|~q@_hpLrDg#B5kO7!{ICe`XsKy z^dFP9l4k}iXE_gP8=o1V?Pt`}7yHNfZ5dwQx}^L*Ak4?_!?rM&6Q3)^tjlzHs;1?i zkEfr;e#H1~Z{+Uhx51u=e%lOdHSv2`iHfa@4ZruUY)7}vVY|6L?$EVdU(-?`t3yj^ zp1K`*SX|dy=h=g>nm+9_v)4TY3NfLrAz}WDggF{qmlv0zQo5rh%5b+6H)xW(?kRIhpC@fwI%Bo1;8{ zPFQR0m%h~{4_N0Q&c1z!XUXkLO~c89y>9?JYLtqc%ONk#GGJ=@7+W1@E7Kk;(S9e* zOIbguT*;(8L%-?O(|D6ZsEr5_l7?T5V#?wHP%^YMHpZbPIkl6ixz5iqTD(IX`$iX9 zxiYEt-`=5e6@OZ<#LA6QJxX=lA51RQh=17HY&B*Dq_rQ**)we2wi@keN7l|xa$wyb z3r=d4(Yx8hp>00arAhI$&Cka@w10TIfWFd~lp{R(F~4eSE`5^XKi3TUK*IfJjbOvI zjFEik)8nx{b~O)4ljf`omb+hCEZ(ONYVVwj%^YHHvB`m!&)?=)K&gJ&>>o>h9BLd+ zORLQ?`@D5H8hZY8@A$FA>=>s4Q(Mx&6oPNkQl8D|Krwh zW$hK9QR;`{LsQEEfpj$p29t6`KBeq$+Gd4(hnF=Cr)Ns*y?Lym<^Z{R4@^1oxI9?g z=Tpy*fKn8k{M`u_Rjw3Fz#$h5rtQ>Xj>X>RT;^-gr_q`AbGZJ8eZ`SA&$}Tu$nrpR9NnRl!{&Xdq3EL8AiUao>pp+PwtnSkC4cT5ny+|0Pw9Q zA(_{YMYw2VHHNU!8{Imuj_%k6yt_rQ;%`7Zc7ZW5o*qLD^)=1f7s`{*dRL=~_Fey; zzB2~amu)nriML_AgV6&r+bGTAZPfR5-P0@v_8Q}@q=+$&sd|Q;R_e#v+g(TszWa(k z5SbuTq_}B0D3|I%^VEk(Yn|613yfCCAy^;E;Zz@b_Yi@qJBLA^qa;QkC(s`xERBWU zwYbqBE8kO)^{(GeVWPf{>;M@LD6Cm*-xu3%8GmL8%yae}fL_$kZv8?{P)PSNwDk+L zVHq%G&HM;+xX1{&kWv=eK_Y-5@Sirei?1}>66 zXiKd`qZ6CumqpXok7_AAX_J?e_B^}~XwF6rPhviuoT%N`zMA#~o&?ZF|Drb9tgm{X z(Z6h7ID29H!jki7pia}j*u3BD4QweriP;-GK}HMPZEt4bUjUspaP|0?X|%e@iMV$e z{%I!Ak$&1Z9``V)YtgmpQ+(Yz-@~9!TE{R~9p^0Tn_st*)#_m|PG(UI?`iqjlo_J} zz09=zZ>(k?Yr)fi!mv_m@sFt@(WZCgz5bcZA;K-ZHy<+z*uNva8H7rHtY=1@$4VPS z>gWTr2h6dK@OsdAKGlQX1qRqBf(#|}pxHx=BRV?Zpm#A7(peN@g2Mz0%%!Z>{N^#> zRT$T%{Y+k5JN!GPfG1={=L^dB=K2_(0Hzl-y&ldFpnvmo)azmUN3S}<;royKF-Rjl ziOs{vW#%UE?mm|F%@o496DUU*=Gjs*h8RVuFppRUR3Z;zQf5(^FJs7(u$B6~N!KYr zm03zLRz9ikHiBurQ`7s!C2bl_iOUqnVKNoZZ$kbkz1=c3+h}Pvk;ld{G7z1G-i(of zMHH~1>CC9!?apwPT5WpgZVj8w40JN9ZQgdY*(+hQ;cw{M%x2$7{E?NyPV3%TtGn_N z1x!sk^5Xz&GYg3VkLbrNR%1-s7niNPk498PtB}KQj%4Ne4H-1vtrmVy6EUqkw@coh zkCBnyE6?rm?fJ8@9+)3dJjno07 z7JKQVR$ISkJ8O(b2h+|PLynic(FQgoFHFygcE#r&_`h0f@6Ce4h?q$|$Anp$VnMrm6+A@7X8%JlP^^yW0k z3$tO}@-k1ooK#wdl*3RjOYI*sV5^tTtJD4=0;DF}%mfjH#T&FskZ0EIrt|n+p741% z(8TO$%66NFDYdJ!eA*87zF*&`!JT%}{Eop>FPCqpLTiGoC?S}Xr`BC8*6x<_S!D2l zDRpf1#LsIj-vY`p{_5xV5p~^p@Z0vf#Q6e}tN6dGve3ZR9{WcxW#9N|C5%II zdk!-yrSmz?FGo6;ztNkt^Q~BXKBv^}_jLsuFG!Qnyx(+=fQ< zaibak$JhCX&54!mEA^jp*O)E-oZBq84NU1P@*|XKsMY31EIt{o|6S!-fU@kLtr)Gm z{Q#zxUsic;KE*U<|6sMSMg_lu`B~gwFr(*32ljXbq{M)_0%Aw5^+cv#1m%MnpWyp_+`D<+Hu zX)HBqZ~DiQ6gNtsh5UdQqE*iE=d9b!kKz3}@MMG$x0k447M1ifZJyS8p?_)}ek(s< z)2x&{n#?}JCxjMwxDm|D{+7)V5D}})cgtAG%y*n4Kq7T+>CZPP#nZ@GXj4l4E%mya z-}CjilWH`rHz`f~S#FI&I+taX@UFq3^=iy0aeiwaq0M1R_n1+_n}z$=(h$!u>dT2p z=zY7b$M6ve@T8}TMN4xaVtV zQ}@^YbLf`)HS3aE#V|kLZCz$FBgNN_C=<}3V;B1OXCc4Y)(4- zGYMr+E?Ml>&GqrgC6&ru@5!aISkL0_Zh4t!tT*YKLCgcEJV}1fVZ2mIXGZj^m(G*= z)qXnX_Z-q0)|-~x_j(qaHDl_$xyx+4-nc87UOPAQ7~{9CP5Atd@71u~0Nr{u8-CkP zk$9AE`+jE?gT$hoY4YOjh&dMHOw)hJ?=m}T`z*ToJzsxCThHuG{@Qbs{{5EKR`<$b zP0tI?1XnXJaxGCg<#T(Up3a;VjdU)5{*|=zeF-vhIy?1ahr86JtC`N%6x+fK(pusL zvSZ{=XR>0cEs+e2e}OS@%kHnIG;&wl#3TWKs$t?K6Yd}I0CD6eTVXj#o( zSjo!MIWH$NPdd}W)3@o@M%5<{?MbJB75dRKnYVrEt5@cyp--t6Oap6rUQoA3ULf`x zmKVr{GKTl(UZw&5+zVgwRc-I)#VmY3FtzwGwpxi*JoFAtsJKYYs zvR%pcJ%euPEU{MOu4I#`R1Sn%H||Q#+m&1zo6_!eOZ7bG3FaATQKzwPv?(chn+{s& z17W#256tm_l=p6a4DSPhCt=5ZAZl35MEZ?6H@tU4Jygn%4I3qdGFGbd`v=a9~2xlQ}xT{oReB8Ij7eBhAz^SG`}V~s+7m+BSc=5BtEdKG><0hCtF z?eme?1IDPao6e(NDMiaH=t}4nct|Up!|(a!iGZoi@MC$R*nY2RtWa|{z7pJk?$L7j z+=%VAL>Z&mmDj%Ujp59MP<#4xdpe&6Zm)&;VJ8T%h{{Z$X;u6? zsh~6cU$<6aF3Hgj{d^kwrln2OB!6FbliKjcW=T1FG#-%Rq#5V>?R}K7e0uDOjvQ!{ zjs=u5%qJg9ezyL|S`X8lv9*^ztI*^OMnmaK_nuFy(B?qCIp_3s0XaQJec(It=cr2= z=+*^%n~oCItqbUr9u7HUg=8Fz`E|gKX@egRq+~WfugB{*! zbfnjV>UC@kz(McAs^Mv8d=CIoA8bB3fm)=0lT%!q)4OH`Z2Zdi6l}fgw^Nv?uOq{I z1@fO91^uas-8wg$Io0^&sJ#aQGEMu}XU9WJ3+qO!WtJ8)&N;KKz=P|oyYgHIrrj1e zHnRerwE44GhqT;+?+IrMGxogA(Bq6t3S)a;QY;c}N(!kyA4y^K5MP;qEKz5CzO|!y z)}cph$ChSMX`$gm!srt47*F`{Y@dtCChcmUE;nPc_`HAiQURMltu(2CU*kBMQb7so zmWo+NYUH!}WPIg_CEy=yD@)3_z*atwhw6DHqRXaC#YQu%W!pGLv*KyTX!h&{>{S>t zngvZcM>V^I2-`|^K7tt};vLn~Zo4##Xco}vXX4&!jBA=UG~97fGJl4Y`STt`y5zn| z3cgej_h9tn-I6kE54IBCV6@I-uE8SQ`B`Usw@0_mjnljWCRp>_@cY-~OmJE3j3-0J*xB;vTyH=|$j<`|J9A!})|vik zw9d$_jO%o2XDzbSb=7g5Zu0^&BH=n6-mS~boXuBLnGIXx@7B55#Lj(B2&|UO2BKR= z$`(6w{$G{@o?oO~l8Lt`GrHws){!zZJ7XqZV^3Jb*!odOr(xrXG1oKZdS;XBDS0LW zzKwRc+b+%bnF!*@tV(-bnES8%RpIa%etL0#mOwp+9l-Z;CxsNQ--EWyUHfr^twH-M zwMU2*n%}I>R*&N=B6;sxn4Ee!vnxcYoX=Ry!1e9Em?7j3MoOCd{E4qv9UJ%`S%$rkv=niU zu$6JcO0?hAx90)!LXAk{&GlT=*32CuDch;mr-@Cu0wrlB`(e`lPyQyV)NG;Y2RKH9 zM;!Y`7fN-RKR%+KYj#WZJpFM<9a}N#qfe9jrW2|8$TYB~=LNmX$O}YA^W_DhuU=k+ z@z2_N4@Suj9?ah67Y|LcgJ+sprD?U|D-QVDFujDur;N(V>|)$YO*4Yf7UEqAjG%I& zEyg?D`d1Qd+0$%&(H7`I53M=t{x4SnPma&{!BNn&Pp+YHDVRM}U&_pD4n5XTUhrKF z>U@s8P#3!8W%&2x08he>$L4tMCX92Z(XOU_K>yTxi)n}L-{ymqf#Ld(Tc6=2J0@c# zHc2H5IiGGBn}tmRkIQWmS}~3>n?zYD^%0i8n1z(#i8<=K^{-F#(H84Ww&aPZrl!Ot zZ5m0A%M{09b}O~t)PH(gJq@Ib98!;kSU7*32KI>aoY2puER;RhKOF7X(wYOP22J5k zDb2jZp10IB&G`Ny-aABe6%i|*(uVE#pCVN*$9krRKUUgchKoM%BrBfpJ;K{P59x@* zM-O@z7~l<^SO)~pn?0xvPvM|<50RdZaBcAvEPUMItK>=6vJ8hG^>u03JTn|?dnQ*F zso8rNy1nQasUgxR^U?74W26SVYaXym=f_A*BdangyQW5JjK90>))=X&-9j`Kk5ae~ zU3bJl_84_(mLwLJ=-fcF!egYyeFv*OQiCPt{L|(_h*GUoBW*mTiQL${a=d`fTwQ#Q zH2Ge}G3TedT`9G&3)lk}&YeLi=1_Cw1-1jdc3b4(BT3*%ZxELj)S!&pj2d`ye3p-) z+^O}0Ca~`^zYLhvpi-Drz z2ctl#58qYaUj^zh7nCCvjLud%q6D56FUDj7HB4%B=7&8}X0z4j*)#HGGJyU=nZt^i zl}-l%QcbS}XxiIwBZ#l=4e!BVwS3EiNTEc=7~OZvSV>%%yN?){c1sz@Vf?WY<(G}M zOunoia^6a&>lwQrpfRxKX}mdZf0jjkDjNx?XgZM^jcF4hLjD=)bwLcDB*F6%#NS3Z z?AkbBkRAr3&7*KsXh&*vjVgTV4K2~4$+u}o6-MLm034b5fYge-%^14%6TK4q?zc?? z66pvTP-$mLJb!@addp=Rt#TwR#KIgBX?>p>B=_B!+0B|MAto~zGlDG)5mJVrs-Y3zDB#L`g+%|uhuD5U+<#6jtnpn z0mbQOcl}5l+`t{sG~G_``t8C9zHD6|tIj#I=6SB`uLfTk+QYJV1#8MVbROdslWyt+ zG(xoz8mQWdEA*x9_sk!lRrvG+xJED5XKlmylpeaovybsgla8x1Ua|Sp7_ao{&={}y z-v`k+YK&LfG_h#LEIOhU#7Ip$Zr`b}c?F^v%Ax~ z-DA8m=2sXY_QjUre4;GBg69@<<`ZLn1v3S3L;W;n1!;}lSk;Qn_mM4uP0W2Cp~ACO zrZK-l`*_XDuQ21>?MKIWW!iX!v-)m2kMT;{`nBWoF~36V4G)s**_%`x*MpFS!!AzJ zuUkLIcx8-Nns43LIBLwVtWZc6VX#&>ZGHv2mdE@`+g|J6ltD-x z?D?2qY5Qir!6LR}g!laYCFA}TNRdiY**XQ@*PNrLqaPjpC?#z4qxsp4>HTQ#vjF2h z(9w^Mew1q@I;W1s53|`rs|H-c z9kgrhjmV|?$6QG_zvpS^@SKF&h`wDU&9x@etW@SSzvob|u!EhkT#jB*vb*VAGB3;3 zD_}|rt|qK|oy)m=BVHEB^>EOSOK=lQDrB>TJ%}XLE zzt6T-`ZE)J&#F6u>etlOuu9*gKkO{6QrCPm$HK(kE?{qIwBGSPID^RiOGhat(9&HqI z$eII&t=%}r`w}InEcx-cQYdE8xYLF2kyCnVM4zg^w&VR$8^zdkv{9pt!rHsWt(;RZ zz8EvwV@4a^81@t~emu6cyWMdV*83@8@b#2AduF&f*W;|B+eV>R&U(9dDHt4kpR|4_ zm~&?JD36FdO<0OM$2n`||mtVU~0U9A+oFa4*^K zhCcJ=4fEZpO4*=?nEcx*)VXxVU~*WY4wUjDFFqQ1f$RkAxLJPs3zX{Y1+#5GH(g?n zpcgCQ2LOjFs9idZdbI84!%#{~Y(5O7l;LiBgqpO5yfio z@7B$WQR@#7+eE9|=SSKaIch!jaj*WEaW$-k!MbV|l`}lwL*jV}+H!cx<~yrs+o{uK za*FS*P{LDv!&lM!mh}$%LJ3Iq9(pBvCbbV*=#{Wfn9&4Qp+TMIzJAmott>)1%8QyX zR?ryo%f7lT0TBfFnf^yei4a+WQl*DqrgIA^_%-!JIXPj~Saj!j(*Ui_G z-H5qQ0|HY<=<$fyo{lnF!DmwzK_$p%{?n6f-(-0Rg8;lZN0=UheQ(VmOgDy5*YU0$ zND87#(_~nyIL~RrR-Wfa3x2dYah?Nf<1c3klxX7z$B>!@#q=@UpA(-i49y>W*_0Ax z{6Q&4(bP%uvYS8f7v%5Ib5WyriUVfH`fOBF=YX|I0DDI%{Udoixwp-m*-kTpehJO* zJ=AB=f}AyZK`ANc%Zu#<>Xw(a=$jFvKptS(W@kT3=}qpB^afx0^gonue5KbU*_E{S4hR=tTdNuWiV(uvH(& znH$Zc_6NZhNG}jN_b?i^yJ4r}LqqRj#atejEF9D4FJ!VHY?me}3ZU zgMg`KZ3*4pmw;It+Ye)%fTziv!fxk4Exz!nr{4+JSw~7Tt?x4V09Gb})OK)@G^IZ` zYfmXb+sUL7En`w?IfOLSNk^JzVPd1S96=v#L+ONUlae{oNzLr`oh7pi_-W2qz%75B zqUk+%&9`~Pa-O6zrHqriXEx)XsObX}9_!Cd^06y%1(> z^aFi7Z$}dvZ8q~lZ8}k&C}Sn_p(ebzB}0aiQb)Ni$y$cCtK?gwSdl07y5)HMb{BR= zQ|tO9ZFW!bK;GdQu+I*8GstIrr#A1EzcGwDMHuRTV$ag>Nu92H<5N8GH-;e-PkU$n z2Bp+UKLS>+gXevEYHOR_5ilUp+Swj?mc(b`{yU8=>ZGsHC?&L*O|6Nostx_*8zpx( z+5t;$8aSPH93osmY>a=w5%B!zO1mK+>fK}dWq09|&;z6h`!O*uQwpFCq$zG8?Cv4b z4!qU3&uYfndQeWMaL~J$nPcvT|FFOH2*JR5KrEfcLGMy7tQBN2-AeD;USz;STi~f< z#!7ZPj*qWu+isU`9h*fQ4@@Cd8jb8aFDCg5s_@!}i(=YJ@(_ zaxhH~M(%WL*IHa-zDtJW!Mf+kLC6L2JuTPyy@xY~vQ-+aBk4GHJwC#dQcAmM&AGon zDb<-a*N!^@9BuKlGrV}Y?RANa#jbPP|aWkEE1b}k&{mqEs z7-#9)wHbwQHWZ6uc&~h>q`MC_Vwv`hEbui)iEbfcLo^7BYq5~}p&0gPM=yoQ1bf2p zgwiB&ARuc5i7$~LcJgO$IdLF*K;{*`7=7R`@&K65D-wh@(Egf^Db4BOG?K?&W%~|G zw~oys5(IQmY1fJbF{*wqM*C21G1?YY->a@POwCmD-+&eKnSPW5ymgm5G&m+twC^h; zPx0A%Km9Gj?6c4zz3G+G{$TRnZRh#$z3XhgTT+ITOZ)b4dL*G-#%CpJo11e4`(|oa z|CC14Gk6V^+dj^Rx&V9`4fwV-KFhXs-{Ew@UmvCwr?kVyvkaJWoN*mNj@PX3be1EW zH3B|q-^Cx)%i~5<5792vL-=GHlUgd{SUJCup(1sS-*}HBVf*twTlwwgH&&PP;#JgC z>g47viEWzZliDWmlW|45_mUNzHb*UkmF|CX>~nG^`Mrm>0W&I6-(KXnE)#0F64DmZssL*(d!JYBIY(-c! z)yk^UygB1uUAYHfI85%rpXICVXpXy`hw$q|0>i8e?U3H}>&NJ7{p(%Sw=(EK8iL+6 zt+jTL@N_%9>$g*w?Rc88hIudOH1)3Ozi7$3{TDQwy4~%;kiny#=EgdR&O#fH2!tbn zZeq4t5|wP6lU8sILb9kiXFgfo(MUk4bdS{spX!f}hCBAUB42gUMKqwy3AT zya!njL{t6>Z;t+eQ^+-8CIi{SN~PhDqfy8xVxKB{!V?`>ZCo8Xh8YMFAQwBELJyd;yGn{5E5CMycPxpzGN5Uj84YAa;*y`x9q)ySQX5X+|nrkBd`nARvL+1H?O-c1WZA=Wx_>l~J27O)n zIXcb^%;xwz%n{vSE&z+ejB$6QGtYVMq)`qi#W=2HhGhBvuK5vm--TI**y?j^?HQCu zw9%honBB^=t$xpjI!(E?b=EXA+s)lYdEGJL>x8Y#&Z6%y-n0_cqfp0fy-i1wx1-Wl zkJ96qbalq8Mpxgo8)fu|G{gQun!9?ZHZm8{rjpI!IP(L2Lw*CE@j#>Y(60A$B@J(0 z@d-wyzK}bRVzXu5!>%igo-Nd_$6F{zyY7|lMDpwB@bEA{oweWQK zXz6Ed={57M8flguP^rC5OV4*n~{T(|MxUdoujG6B?I>IbvQdFwXFUxoSxX$h??N(rS& zecHKh>SHG)c{=oSgXo)*VYakQrAgP$te+J9C+!({hZfr4DR(E$7ovBw^s~U-FrB{l zP!7wifPKNJTMkDnuzg|4&B1jxscT9h^^seo&oCRD%JgfE{+ZjD=|6iRM*n8SzALZc z!Ya|bOdE^DGW}TZ3Hzrcm&H0`rhnVQ`C=_}1#v#_frV!we8eB|^-Imobl>yWTs1aN zt)S{%zdoXic<->Hde^V7{xH?Q-bH;K8Tx>yPD9YUvsu&4->0K-U%!D4>?1(h(Eqp)_>EB!h{@f4sLIMS&OqR|J^dFd9CF_Qg$J> z%Q1XQ<#4+k!@j{!;17SD&Whx&8K?I6TBgZl27Q_&Y1F3A4ly6mJx8C#E&*gwD4+3+ zJg_EyX?hLC`FI|6x^Qg ztUJC=1}$QQVe?g%l*KbCo=^M49(;;VsggIpVSHSl?AA(1KDB!246empDT_O4julu_ z159pEYPM11m|RP!^Sma#*Y=y=AOp;qn3Vv982$Pge|?iczm-51YkGNsR{9=}RPU z>RUn8E0n$&1ebCS=T$5MGJShti4NE~Jq!o&J0q z_w^}L<$AyO94f|+`$_apjq>G?@pnoF+u5(!EH{jg0L?4}C2-i--H*}Z&$Fect z5Ofc&-av7BE7q#?4kJHv`c;_HEx&8BTXX@Y5Fy1D4<=;I#}MotV6Ef zXhKNYf*h-tZ)roRK*U11GpRrZoa1QvDoRkdRG?S-jc#8BNQ4h6tK_pJZVk|T%tJJ- z0pT-(Kr7n4GLHmWl*bT&$5wstG#iRNOBjDMA6@zu8(0FsR!ZU*plcpi-+a}E(7ack zAxEzmDf>|_Hb=pGN{Oy}YLC^LsqV*WgCly^uMe4xj}G2`Y8Z>KOZa>W`vEy<194##dyEwSI0g9tSh^rH3xQ+kiM2Ah7Te4kmR zKHX{B(b@GpxfPhq>VS&jXoieJ0D<TXYjXF(Y+b;pdDt1A~nKNR;j@N(o}2`47y zgXQFWXv4P4GAc`+BqKMf~RkV2nRs(t8%;X<5N;{Tqt! z{;U_6nh#Q`YrfGk_C&sE(e&1<84&wx~N;qh5dXkd*cI2Iw!cZ#8e1+xkS4Jv^ouQcgPamrx|4ds8t-=bRJ&CRTr}@yf z1}h({mH7(uD=WkI(N|b5JGI(1%SgV=SLj*{=7sZ+j?q`FR$oESwK7t%ntcU!;I;LY zvDmKXD>$;1;rr+-)|Ri}UW0i^$LK3o%2!~8gLx&JZKl>eY}KV(Dptd~2d!Ir4iQ_= zjjeJFneUCSX&{R-l;;5idUVT?44E?n1jClQ9fpMf81%%1Ff5f~nXBn$i{Y%jM7uP% z#q8GV*Dvx1)&sNZc6K9`2XD@)!DpMFlhaBIE9bnu4`%L69#F%TMTKhRvw#|E=1M>f zwRL!?q4bx0<5uw@b-Ja0Txsg|X+v;=5;JlF`NFo{$;nX0pVltd3C1z2nG>|sU326x z+MBw1Hhzp-gn!fu^U$d*6un(0ya?mGREJxXl-Uu~OP1yDn*o?ZwDji_4=;C@YwtY%!!Re>FE%-d+$4Q?703~Q|x~w-T zfV!}^Igv_eYXOZtrJ<2`gq8m+QfPhgMsz|nPNS5P+2%FNyLpXwku!!EdIv80w%H=R z9_5uDZ&Hru+ICWnT$qgG7>n8Up~r&WjV`I)`{V3f&jNV#Noo0=bRPhEr|hSD&*yun z4X|c7)z6wfpp1~4`hXlIW74i@q-2+vIVOjpV7C>tqL{~O<=#H*%*EBL7TbX|}PW4-;_Dms7!Dh_RB^hRwX%~mI5wn+! z(k!5T-=$kJ=AQ)|Hi}AR2NCr^XEnC!jybRvqBZ;cN2tND*Y;+-oEeh6i>{kfLu6}# z9qbinM~a`)B&NYS8q;!m{C*wIjiSQU7llcyYIb81S^Y zF+Vb?Jpu%_HEIn90Z)KaAFThOEndhS^Fu2O)jT}8wGv}Bjao^lW)Tf)(?*i>jBcPe zmSyU*k1?+HTaz}-_S`c!9#C9EOJcNEOW1~oc_S^uBqL;7liP5>R0SK_Dd|%;9_;`VZ~JaQ(+;DAV+xk~5AX zPtItuy5(#Zvq;F@BwxmzhGtEf0tVC{vqD4mzcN`Rr6eOk<2$^WmHIkvW9;TT=8}wx zx-ASwYBdSV{H-4Lh7-0@y2V>*tk8Au5Wy7hfx>PCJf#aSqCHd6{}` z!j8+>QzV&kiolv1VX zZ>^u9*-l;eKqfmUJAKj$ndV}rC@*Q zO)L&XDXn$e;?OpC$AN2ce~lNYoww5}zV2!9ipFexux$1N z+XT*`9rj@(vQ^#gpTp}647RN~3o!pPSsZ<|=f6~?_mz-Or^7Id-HcUAIDj?>2s5#dC%bG&x6~&$DVd- zTZjDKLy3WV+!L&I3P+_#^D zV+5`du6m*7oG159`Lp7`<@@sa-`1E(?Kh|ravquc;UKJ5zFWp}K6<}8`EEHgjT0xA ztd-(>{+r?<_zP{e`_5^kQQ&IW|}5ByB?R67R(@9BuTmCnoGVFYHFSK z&wS}@`nUIzr~Ak3Q6ovN+)w(Pg6;fEL!)dFmOb&+H&+iO8f(V%@FuIEE1@)F&C0-;%!-v*&5Z-@s|oEGs7xCJ%E$GIHcnT;SU<;(fqSe!+OS!yCBuU1 zSKGneJR3$G8*NzW^GdLZptB!2vjp06KyBextNj|%o=~%AVL4Q;efu<>{Xooilz3(R z+8%abDE1chq#_WFiD2mwOJg^hKBemSkP{^xB0b=355NTT9>nX1dswKyO<|#Tv4;wg z1>TN@zRLHKa|ecveyBK#o;uG4*<42H3*Q1NLc8o~FwAevS}CTma>LDfsJ+8SJG1I} zwi%b^EUiBpBzI`<<}*W^r6tl45yEs<2pX$;tCpbjX%=KrU<0s23OeB1k6assC)AL~ zfflKiHCvElgJ69C8TJ&ol+NX5V}WSLn^6!-DWQH|5aniVx-3x1nz_F+r*dNZ#sHCJ zI%@!}HI`8L?R*UHt{uyyW27HQ$4HjJ?aQwo*>g0Q%rgY8L*TKd%b5Et5Abuk!!dX^6&!H0=o!zC? zjcExi4fA)YRa4ZV>{-lft4M8s1MSu5w#(nlQh(0c0Go`zNfFAhZ&~8IEr)&AiDAI#1bER`aHV8Y zp2xl7bPz($W0jAxmBV+y&(Yvn@Ey3Cj;$W9Pq%}msp%`jb=98|eYf`=jrwje_jKAg z56+kE{`1Gz&G)tFv9TY8Ixs7qVuo!VVHiIVTJh2ujoJLw%hgH!CcT+))Jimd$nSXw zN;85UDShmM?L@#FKx4Sn(}*GMK|w|z@%adHf{aTonn}$@ESgxoyqR=1f)QD6jdmy0 z1lm8#s!(40@+wX5Wl!vN>0KMzq`TVU?=R(ifLcB|v{3fS{pPMa(@n*w)4gXmq&cDw z`*MTnGwcTE0nPjZo^{Kao!E{`+m~c-m9Ra8*s;m}AWc}?rVh1dr1pl6_&!(Ew-vh* zEtzyzGGGvYgE!5aGMYM%KB;5F^dFM}P>nRtkpX)qz1yk}F9X1oa#<<^IXjOhwU%p7 z4w`bNtNgU?^kvh?@i1~m|2oQ#)H0|$KO_i)fCRmR-Wg;mA)lk&xd}GOib5@ zhA|6$4{es&O!_IKuF5mUMc-eRS3?9wxiXtOP5+qtgnK`<1o;-7(;vIg+=-`m=*jSx zew**u1@2_jU3}DEovlH}ku$-}mGa&l(kNRFec>mK^&!oolO`q#gHWc9}f zs@nBURDN};<zp06Y44dq1LYs!;*^UvPV`2EPL`QKL8nuOpSj>lFv0vdB5kEtrWM(Znl z`TZc0=*HEL8&wr4Tsx}ksxS5+WEA+GMg2zP8d zf2n54p{<&=f}uKxo0PeWtJcLb_saXd?5ZO-A9Mc?Uvif-@BD}x>^8N`eX>O6fOT8u zs3uOWPZle;ZO7uhH}BZI0z#)m9EA=dmmzewnpEgscIqqd`Gbe_8=3|e& z&(uQqtrDTb*xEwZFm#Z%#oyWdsI!+wnFF!pST%<3-IL1PL%#8{m*47PFT39}7Y_XU zbN=$`y{DGBFNn-l$S93yr1h`x-?q%%j8zcRoP6%~9h=WRW9iJr2P|!0UfMo;$=hqR zc4Ppq|(!m!3U1{`Ef`8>r>8q>+_#*%Wr#R# z$y;O(`^t~w&);(PnOn|%^x`Q?k6$`_@jhp7-MVe@KAX?jv31+*h0ujvW1L5Rkda9t zd|MS)77O8RZt|Z;-{ArGJM@;1y8Y`u`{V<6FBZb~+~U(EE*Apa7Q%-4JAKEtrKKH< z57>O(;=NWz@<#JlHp93_C8NcXcfXH+=L4_5_shQg)%6E`le;n<{H-S6?PAIMzy~(&e%?v{ z_2gIo*_7#|Fj8R_H z*X~}KH|8V}jpLwSSlC_uSZsN}$I>RY8o#GXEi!lMGUVT_DzWgws?zuKUf7ZZ3a4Wc$*#6Sm4kcH8-9z`C7&#)(gty0=t(@X`g_w(MAPll1K;pY=OWJa1_Nba!5U z!t36B*EG5d3%{R4_m;WnBEA;Vp0f3VrR_UT+bZjk<(S^)*N^+esqcT!6-mN&VG3h} zqgSi2taak!Wl`&-ZJW=Vfc>9(<#j&!l@k}!qI$#;M`K(DF8*z;DqI+Gah^LSqwN%-u}?dXKy*P9OIwf zakmq{bk#TR-606aB{AMVm&AyT9&+B9pl_89yYJGLM=wtxxM!Yu@s*$X(ZOkvIP0vl zk|J?%F1`pAPCj?bjx9peC)GGthF21I#Xk2Zd;a{&Bi{9@w0Gz-x<%fhiaMQLm_UNB z_wtjjeBBj~n+(yS;DC})QB?w(a!jA<3aAd zaK(s?-cbcesQ=ok5iXyv%DKg&4xIi??mnxk7~DjohslZKF?#X--B|r*6vt)S;(=DzIK%c_keS}1{k=hw4hHrYBFId zl#?_nOAO!K<)&WL!K7mr9K!)LORhHb0!9U;Swl{+7((kz>krLjBe@e(8rT@0j?kyO5MQos~WTHYAo-gHwha3`Q4mudeExRM3hdtd!o{aX_X zNi^Ppjd(%z2Q1{q%H6Lz96In`iT zdErq40I9Fr$@LUDZ!aeX^#Hk^D(9``_i1u{kesK;?-S*`xBR}3oZpf2bUA-V&WFhP zP&w}-_czG(UUD8GCnV;ca$?WQ@$%=%ay>z=pOou~a=nwB-;v+Yn%BsAnVdlOesY3Y z2g~_g`Te_ceoxNhzb}8^U(N^030@<9d$^pplzRusd8M2mlJmoIend|A=O4)ZKbPw}<$ST6 zIH*%lIULET?pn8b+;P8o|GVG!(ofv&#dmq|PmZirOd1u5#UjASQHuq(07ECPmg_&s z`9nExB!53h&Iij`jOvFk{n~$>aq6?a@UHtE@#gCvwfoN}M)eMY362_71Xb4-lx{5N zBjoq*$%*)Qlbnx~^Y`W4EayMVS&a4#zH{t%{_xb--TlISp7zGq9(UizPmDHsS)&c> z@qcpuN=}$VZm@og{B9n_NPlAg>s>6>2e+*=dzS-k@Gh48-skTocqh~v*h|{ zIo~S3FOlAtNcDs&d165Hu-y-T(`@)L(b32-?x|ZyK>%C&cBlL?Q#|m z<>dE2XTM7>KkDR5ANVJadjEspcGroAvM5;LsD}c(^c#ZGzo1ag-7wtIy4WE7EwNJbMrF&0|Dx4sW8r8k!kLw6p>*f5MoR62ke@m`V^w-Jt zx8-`3T<;*~kL367%JqqIeUh9P$O+|pn3R1_&hN|lc{z)R_vVwXv;U3%_peTV-{($! z==rboCUQ`dRD=0l#(ENg2e<0`8a{iN?PmwZ2PaEVcM)`x++x$ISUGBrfXdesl-?lcE9LiX<@yJ5{hXW^$?sRo^q_N6vHQJVxpsE9a->e6gInN!jb=yik50DAza2 z^-XfVS`&L_z4|B&lNaz0Uh|EXN>DA!lX^+|GlvYh`ezkea;XXX5voKKOmYsq;N z`F&G4Zzkt@Io~Dcd*r-S&iBf>S?Zi6=LhBYhva;W{C=NYKO^T>`F(S_{-&INA-~@( z*F)v{3_1Tu&Y#NPet%BNid?Ud>%YqNPvyM3{C=UFJLPV1zmw~W)qt~H*&qFT>nL` zKa%q&a_%F4-$Kq?%DJzcJEZK7<=k6-Unl=HoEK1)vEf+IT~zUy`G_4)O8d+;ew z|Nhf|@y<)Waf^vf$AJpiOvheQaD74N2s!^pet$#GzmxON^-t6D5o_H7_GLCu}g3-ba<)6E_ z;#eZQ7}@{$@=qUs>ZkTTjd6?Whu)4{aKkS`5z{20%a_*U1FIYSayTG?E+_tKktqvzIKj!Uk-+24`U3%bt zH@y0nPj3XlfRP;UyRO$YUP&t?#|!gZG~OEn5ggZ-^Q3KC&p-D}-Su8R+?QPa?Du{6 z=J!1AkKX)&Z+_*gFaL@!hk%eA?xGl@Bzt$>sDr(WA}K|~g~@XVe9~!Kw=bTD75T+G zEp9z)amVt~;?kLqUMe5?Cy)92cisJ_FS*a3KKvCAd(5{tHu3;~mK^z)e)a2LCrAFX z|L9jzhVojT6a17&-?L~{kDGp;#1%9x{uxZ()S&+vrPufLU06jO$Pewq->lfj7rJ|9{o2Id|)h z#k02TD5utQPx|r4PCnry-~7SmOW*fL@Bfph4MVNt)^$+p_y4;?qP~6I4r<*0pn>3guxC3tGfYZ;GorK#Rg=D|L0p+5y>4`sh^Jn+E z{P-9B>N=Oa_e1M%IM9&0bms-)_me}$Bk}DaBXD+y_^E}{pe)-LIpp#YZ+zK{zq!|& zK7R81pL)svd*&Nn`|#`$-$?9xlF2`l$S%p`^WYz! zCu`h5=drj&E#tD=FtxaJ?$+}ky}WqN=Ep8Ao-I27ommhGDJRT_x4iiJhu`u#r#}0D zudn~wjX&{$HeuR-1IOQ$lX2~TR6eM>EZ_=>#T;9Yx(CL$>xD2l{3a5Z#+v-DI5IZd zqpaCu91Kmd5gH((7fh;gK*vtmynV-_+m*a{^7cjDKZhg=4oqD9{Te71H&-3?z;;{M z?bo~Qc4SqI3dQg575UfJdT@y_h z^;{W|i+YCVK-Ey#1PLn~K9rs&pU8(of&Gd{X+nFOgNuIvuSV=aLNy|X@w7?MgB-?F z*yLj1AV(nyGNIJUr$8D|2vKjiCV-MjKOahF6OsUwYd3+e+EG*Pp+Y%ALh=ho#(2owPiTuq6E@dd zH6&%O537x054nF5ft6_Dn-YmK8t5fV32BFP8V-&E*N3?h{!@?W0WCWRWc+3cNJQ=z zRfic(Xt*zlG)XWPMwsU0EsWG!tq=t)!T}lAq9m^AO(d@fLNP98Hg1& z0b+$sAOVGAfp}&%AuGZCwh|<`PgVl4%&`#4C#A`rau&)M^rWB(9Af5Js54kJ#^FQx zwkyFupk?i*e#diDU#_b7%@Rue9j_VOZ(DB?&HPE^l@TPZSp!KlV_@;gNHZeb8k+_d z3}W6C86BY5Q4@ttE|z<3(kGe_z3)ew7SiH1GRH<0!J;+}_K$0V9F)W#xdzQ9$kW(SqlY{VpB(xWFq6ZFgl1K-{HmJ~ z(sxi_4!;Q#NITt~y2(2A}e&Y)zzqf-1RltE!EWc1H2DAxAuzu5q zJ+VtEXrDvCp!*G*PPv72wqYGMJZ;+GNPCfV-e7@Wu>7VNmbU^z>y?9@tab?a{cTux zcWJt5!vi*LP_8{%{^YUm+XUDu;FiPM7erS8qmBd2Td&C9-WBLS4*BCjn3q66!unu({HHcTry+E`ELW%bk`J9=WldZ#{2@zlWlg5^IXl72&nWCN$V zC-&{CpeGhsPfU2#0R7=APR#4nRs4eGKP66n|206+#L;QfiP(9G!;$?p)gNiH`#@ZG zf3MB8yR|KTn@;4jQ*LB|$o;A@)J&MicU<`5f(dL(#DO+mFu^XG!2~MSsQZu*O#GM=6UODJnKK-Rolgi6lh;aT z8`eERHWGNjL<2mWKMR_{1WVh&1j_?>uE6ha!@4~Lz6j_I9SHmbGI1J(f!z@^16S$` zX0tx$PpE&FlY%ZPSL)ZQ$c0E5M@?(LK)H&%3~=)A?E4PEDd1`VcfE#Zm{Q}Yf%pZ> ze;{4$cj!r*&sjS3g!8xW*m{nQVjdJ zyPOT<%K|mNr$6A48X&(I1C%2gAe;Rao7C)%1x@=)AWnCl?>g@6`WID|8dJYu`H56; z42S^tTU^-hk@7fG6;FKI>tXpRY~XjJgFyBbM-9m@Sbmx`+)rpiccHGx@5L$qw_O+7 ziP7fTez!oC1x?yCT$m4Cd-}B3w*%%EEMLfx`7x=XAOVGq3@EUmi2@M|`Zp9BSONtW z^r5h48wC~^3IRR+{%tVo3Z*+3V+@7`uBVVqVK1OA@pirV1&-N4-*o}eb_L&-j&ML~ z)~iu`mMf4)n8^_)=}||$&)vN$P80kB*RS8EhD@G09lk#Bmjhs2AAUi+4?l2GT<@!W zEIcHQ>wXm+RB>?pf;b$XmLj5Oek@a&`QI<>v?o>abGpH~QGLPXNeO zM`v>E`(DbF-|NAy&3Ckl!{s1hnN1a|8w>lsJ;wiP?!ZNZ8gIW~|NW{yG>?lJ3Z0IF z?H4HA!=(y{>)&ycnQ(y2ihrb13apMfDfJ6nXFf_YLPu`^XjmP;Ae>mSs>8)~%3YlG zz(yOTCR_o!ZWN$v7T9nbonW{uXbzX9+7M}KcIANi1(p}T%dvQyNK+fACv zk)a5T`)o)J%rGPt*pPgDwINi2^&GB#fypSL`7+98Su)DXH9aWxt^iDH6o6?g=#z(_ zYa&~B-6%lUEHL5`m}>*#vA~Gez{z+6#V|zZ#t20 zUF#1pT#e3!6IbI!f*6kI%rU^LE@%wSm%O?L^{6fY6qqOnw$sA88prL11_{M*H9CEW ztMPCkk?I4kxQaJ#tJU1U&cVimT0g<=h6PWvPEHJK{ic0Pd05C$G0$VWLQE#PSfn4{Lle;QDT6N|32nKRPhPQu% zP3}>3RnX+k73S?GJ6T}6LXI_YE-P$i${$sjjzqP~h9?}gCv{MU*h8RJkCl**w zK6YVG8WEGR=<2>0l3(B&`B=Jfkg;_Wzo2eHbT&A7KEB>ZT60if@wln{;N~LAt-hyuE~~mLXmWXZlPk)b05OoR5V680KrFM#W27pMf6z+f7ZmJpZN*ZZnOmObvEf1+=CP)dkcL6liqm z8gk=OUGFl5>E0LaYFyqfxWX&&dZKY@^aP631?Z_!fSy=T<-sXqXtexNn){E-UpN|F zvA}D|&a7ns)9y~~+*AiXf0D!6`<;=mnh%kLj zTuYFH0KAqgTCQ9A{kfLZfEG+hS`#J(7o{~!{B|uj?d=>MZFyY@t=QLwJ%TzCoppP& zMQMMeoH&>!gxuo5^+s~aJH6o4iSLa zJA#}VJ&x+rV3HhuLySs_Q=^JC=@=D>fgl`*4=J-5aGanSI6px%ka~h&= zv9;OVF*ZW`LMJo`LQTo5J!lwP8(IQMKd=RoZQ<%blJlaABS@kfJ8C4U)p&0p4qvc( zv^v(L134O=s}xWJ5~1p?8oAK$wB@4*MHrrTlMb@`#Ar85KqAROjCPYAk^{N6OeCOC zXk$$>#)D>UG0K3{ZjuS9ZPqd%#hO%NB9~eoHi$;~JSwCfc+_svA+SEAHYpNg@};5O z1b^F6kBLygBP5ro3b-bq_|gz-5`l7>P>u?C1>{r?9}<77oYcrQ6%g+@Z8uDyNJ7M# zBna_L5rVf!a;r+W(1tA%qF-POZ9vJt<2JXtu#KSU}*;)q)?3q3z~SaC&lAVt~P_VMS*`CIqiTjfVS+b?wsA! z1svbu)+LLa;d5#4TcMf$!cF(5*MOaRIPAP<<{w@+L{{M%NDM|X0Pw?ghZ7y&q7*rk z$~iC!xX9z{I~RGbhfd^xA#{s8e!+9~p8I#-^QDFvf1lV}uC;I+eTt9B!M9^6L&!zx z>Y$_jQjXGbfG!o)YL=3mt^lC~Fs^H$0LLQ!0clVWG-*IV4f?IR34)D9IptvLGJPZ^*C+1xWWLyap1a_oG-y2?x=hCqL7fyn4W1ji=^7I0LNy}^Pr(A{^Wb) zZXmx;Upjl~j2%m7F1l|VJB~^z@bTXuhrc85bi)f<2?%el$I-@5OYv_#tgECM12_6< zzu95d#&3oRGNIAw_|1T%9W^w}blHp&9d8D%*UdmghHh`Fy7il(vK@6ZMwY*W=e0ilxZiLigK=F6g$)5`~ev})BihG8B->PH(PRHX)KH>u9kPVut+d3U6l{ojhU^n?gj_TsBnAk*ep;X~mlY}lJp+jACuDAsW&D0JybP+1dWx$g> zgC?~df~dTc7@G>S2|g!)0~egW4aAdbC!D`+8{T?debzZ;1OWwpK#y8|NjZ8r;(=>o zN=OpKnj|O(63`r7T%q7Y0&;fL$gv3@E6iv@3-#Z7!S}?-8DAKS8J#IQ- z|F|ZaQ0f>j`%MzGYo`%`pWm!@-45}3R8ypXeVKr?`Op$F@frtQzgp66!sc3~M(~3o z6C}q!Rn1uySJfm@4R^0@hIf&W$v=!VV;6d>Zl+9T!*@*D@SUX%sl^|OG)%|{o4hN( z3F-L3NRtft_`qb%J~Uag_m?%Jx%qIUSwdw#Co;lj@5yiG$6D`AHY3bhw7w$H_#U21 zBh3;Fpuu@xq)9?D*yP>$O(+?E8EKM0%(omLEo(;6y)4o!F(x*-yu8U3`Aw+!--|Tq zv>1OTXy1EJd56&}b@(n@YolHbp1#>(*?9GkGr(GA&CD#RXwsisBXk9=DSr^dt)dh5FbphQ~T|h@v7tqbr1#}{H0bN90 zK;w@BZy!}KqRZqyj=JIH`nMHa;T2RChn5(PY-f^R(XqfcwPJDfy;XkOk$<2q?C?tQ zFT)2qe0*M38{)fX^2kbZ?!iSr3=9XZ(DRO&e5}b{Xj>n3$c8x;gQ>SwAbd#T>+AW4 zmsMkvbFQUbwwvr^fz9ICgsz4)a0L`QYUJ4D;_6;T6NWceMVhd=-m0PKglL`I#aB67 z9``n=jD|!T1-3PwBtxmUHJ%99t^I;{V1lX^n2>`gZLRd8C|v2SAzdW5ak!Qem^jmg z0gxiNQ3WRC9*UfA_X{-6TDQBjb-|Y3aS=sSOZ=__SV4a|yX^5b6UNM3Nyb2N;F=I! zHo3j4s8xHKaO&`iNRx+2*-nBrX~!dSZ1#LlNl+7iGIx)>Rh_#(ea92eUP^xQ1dt+m zD?p;uzp?`oY{u!!ThBlH%*7M7p1Whqx#y=r0m}#|)f5`0uS+Ey96YW7B1dIxY8B(8 zFxDh7_hOSvw8sXNL=&2ew?vvGEDTxn)kqW2+m3oHKE1zI-ST+ft`6F; zNdtU}E(#A{evc@f%P%{lU*YTE`t>B$@BZ6!Nou&ee%CV5+a$#s*8Q>kyJ^F^d%25R zOIjL0bJo%?a6QqepvH!EihpEAg*O8Rc)0>97CLYRR2vkmuSh`wN7+7$mrG~2t!n#s z_PsPojsOZZ%|Q|BXdLVJwn4c-6+y-27jPK2m%nhJ)IBzNEl7$SP)j$A1_0{{)tX(= zXVhKop3xQ6$aVE%!VIw5JF}}AtGcTItD9wXMOAZH)ejm_b5ZI@1CkPA6;)8znl1hQ zTuXo0UP~xj*peV>n1GLJ^|S^3vuzcN`10%;1_eH2W2$;^R%m@~0nNAYKe!^TZ!cVE zEp_y$%{QAIRn^UCLf>+)2oyNTmk@|W4gR_s-@@%fvSxco;~F`-hJ zGrWQO^HTnBsVj!+k&f(a4?SPrK>;VFQ0l6Y4s`)Xi2^KfR!g=V1&X<3`;LkrlfO$m zz*GP_b9{?x*nluo3VG&4X|3Hmeoj?j&TS_n}f)l-P zvIUaxeS3=!+_vS>Th2|+wxG1vmQ#-!6qbY@Qx!hf!>|qNCQ|40r6u{a=Z>w5gqZ|} z))8PjXQ0r2un*k%=g1dpw{G9Qc-pqDXP$q?jwCo}M`RlqDgU?C_<$7-ToVlQx2T~R zP%Lc52r;7>_)K%eXw`3qaoJJxjN<~NOa$AI+Rb_(ffVhDNG1i*vp=THW{{r3W*|o< zl5KLdn`Mv#Da}j-De#|@COG_N2}o4Qf6x|Qb(cgUabcH9tR-UCPN2;KD2hT4rt`lUqz5i@QINA zH`1g7K|+E=v<+krq<=4iLG_XUc-6_J|FO=|~rZ^KIvgz^q` z&ul`ne=0(Z1Qa#_Vwu*?M=Y}mp+Fwm{-_5rjHPh+Zzvx=5ZhBuG7;Av#LxsPP|yU3 zWsb!c&^D1f*S5cM-ILEB0O*p2124-?(BIh@2BiAt|HoH=Rl|uV@Su+|+Zu;`amLLa3>iZE$Y_7LjB1Kpi zMH(hxvB@VvKsneyu8Af-dTp|^x$CPf@stc$^GwNL6R17VVgDWIvB?|qp>RZ3OA{PE z6#mvb9RzQaqKA5XWRLyh%HL5~6k9&7$I7^NL}5OIGf^ZYn3y)v6MBU>mV^g;+szWh zAf*4(5!VF3m@*(iD%w7z2hzVpARShf>7`~do|NO5AWVg0`fdag(_=f`y&BT#0*NyC zeYw?E4zgN%teZ6#wIRH126r~3WWZXqAttCuBq6*-u*hf#Z@Xcp@MfY&j{Q`L)exzk zQC$^j(n&$WdV@5~ltWSw+-i@g6PC}dOi5%DOqSb3PmqFq!d$eCUI(8@2!sil$Pp5Z zOq+Hcs?TQFq>Y0#!!;AZHnbj6{Dp&)4arBaP4o-|KNf+OK#)ZLczzQi2coZ&)2Chr z(SIaO+7qOVW^arjn9&SQp-sWeW^K{!XhteRblW6J5T1I4)KDA2L=zGo5pE`O2*243 z>WH3wesu^Fn;}$fBbXqC4-L{W0h{4k+t4~(E0O%HG{fPKErFz;E&HxCX+!I9uVnLO z040YHEx|K3xm;V6G`S+b3CRHJwIw5idT7>`jErWWUK?5m^@t>zwV`!1BL&|e%?fo3 z(K>2TX`!r!eXI>8`% zZ_>Msh8gI!VL_lG==mdRTc$)4AF(!+1Y&-ZHk3q@2OYk!aOYEGm+GnVLpExia#I<= zhIK~@&2)dM?ipo%=eIy5(9_~iHE_S6%{J25^~zZlTDI6GB~7-mAY>cw^s)`o z=?L;di3@AGHZX#K;6OF7?R4BF+t}V?Tcfc*oS=JQ+qI?khINnFufeu;6*SiXWM)B= zZ3NVQDwgE|yr91g>mDNm*;H*#rU`TOsNa3g9XcqzwVd@fYVH)m4cD{Z9-nrR|2Lh2 zjZz!dJzbt_Nq+0a?FHvH!Me9V;1R9kK#lb$z5pDMBeOBrn_c6`mh!g=`{P~tE!{AI z2T81t+5VNo#1l@xVENUQEPnuDPr9p{tDnGgx!ynR_vc!2d!QSR$mGKrDERGVBf9+O z^pSaJ)OQ{D1*&F6M7gFh#}V;MLOU|v5z#MLemU9P$t>57E7gvB%J-|m7&%b1{Csxh zb18rbTl7%!-ES{ix0jS}SodFx4YSg~9cG0EW>$QFzFG0h1Nm_Uet#R*UA{XY!vJ^! zNLyKVzyiT*41*drf}=l>%gtE`BgM3e*dnT zFY&57+-z5m(l1zk8GG{k*M{5-S2y$vmj9Fu{q7Pdpznsr`UN%^zkk;gx3mL;>J_=S zm7hH9Z5(Sk;6MhW!D+uBe6I&+p`n}eV}XP63v$C1*AsX`vs6nQ3yevA|ANP7j#pv% zQN@&6So{L_VdbDtX)W)Fghu(|pxuE6;&x0m{emV@NIQ=x+`&;J;}};9$Eh{6Jc}Kt7u|x+;Fb^7FKdil^?r4??@(eu{cLe!=n| zaXkJg14z~MmdlcLS3bf{4w$#AYxo7re?nk^fetOt8)W22=hZ#=1& zF?;zv`2|iKwM^bfxS)M@89+0^WPQxNIJpcy5?(@eb@CHauc-ad>g5XG5V2L zJzT(X_&Dju%)cx5iMG6#*oh6&Z1TSm(l6NmwYVjR&S2gozZ!M@0-d`^BFW+F-|@as z9vhnfL2~!3onPQO^HJivRQ*c&$WaL&4L{N$+79M zK!b+g@(Y?oArOx!fg|w?M*m5QIeFQ2{HJ?2O5i{L`Gz7&C~f%9|MW{Kdal}v`%i|b z4mx}l3rhVb*;;>l+PBM7`cL9y{*_^b8-Z^B=4pdj?0 zywmcZEauRBPnhjroIVPKaH$b!%zDKme}-}?`Z8a%N2al z>!_OQT`fiAM>Da>QrFUl2);jpeD~W+V)I9`sJmg^F?-kP#fvfZtGqv*x6{If?R{^D|+$mD)V!lSXutW<=#U>Y@4t%`lzSG)ym2gN#*Az-^G& zFX%$V4I?m5enGCYay{|+*_t4JLGznk4Rm2yaiE=A)_-?@d!+RXmY>Ds#{XyUDFCB5 zx;`k@AO(tiSV@2ar4&x~WPw6fBSe7UQV0-8AS4iiLmQw-ad&rjcPZLZq&THWky4;Y zOAA!^-`m@{+uQ6Nmk<)@pMl)%y&ZWrZ{EC_omJNVI!&@YMglmwpnXsQh@M4oa_K%& zL7d~~gg*yclmO?XUpWX!Jx5u;ow|977NsmofHNkitY6Be9B}M4VHR}nTyP=)Cr--x z-PCj!Y9U=$%Ay3g&V5P!&%BB>QQ&(J2z$^sd)D>m@js^(}?KNRY zo1h?NQ39kex}%^=Hf4iS4&`jyUiBlWng~M5q69<_C4EZS`;%c{uL%X61OCdxpOi%j za7tcTze4g0u@odnX(b?f0l@?7#N^1PY{ZTSMtceSBs`P=XLwmzzmzR`cp16uLXi^S z{py7aGItc%xm&#;ZQAL87h=iO2{f( zQY`0^#-%*U0aB7Aa+(+)DTfjuu^yIA=Oee#-jPSHk(i1j2vjMT3e%KO$mS%2Ja&zR z72?C;3loB+Mw9^Oc&5Zl%9eaQLvxSGQIitjYX4obDfuf^tyFIp`%eV*iuRwh?zI07 zh-Cj$G<{39?HI*DdXuw%xj0V9OagH2U!7*hjKpo;mDhR-p3Q|y^W=9}1CP!%{AbJMrRZ7lCcqkiDygEf$TFSRas$Eh4UNvB! z0$`_T9zb%yp93c)!0ACN3rcM%_i4*}_?4h!c_e_cZgetItYnD315*?aCItKkcW6tt z5hvPNWf~0er7@p?Kx`d~RnUD(1hXMrP8lEQAsKe6)E)`cYJ6U~AbA&`e%~z_!Ca?C%cN#yT}o?> z{{|{2T~8uY32?g29yQ)>`;+a9RRS{i-Rg8N-?Xa?T&LXIKs9j~E*#E?T%Fzqfk=`@ zM}Poay$w>6!rM^Jo21f8K#C@6$_TVnlM;}AA#Xytgo1KZa+-N1iBdMtHpc3Hhh{};y!bw@b(+P7yVIKa1gg7~!FlGJ8sB_|!OD-s7 z!7>Ek#7S8{sEl%pw9ANc7fKU=>zta@38fWtYBG2^k?~O@Ljc;yxFHJzxGv&X0-OsA?$kOL6fg?`IJHh$zoS9I8+%O;pdcp1Qp%zPxNgWM^-I~5PM8xXGNwAv zCIBZ+%KD{j%D|w#CXAc7@JR`9Mii4#r(}XuwK85|uNvd)m>lFP0WS&Y6O`;VEwESQ ztVs!oUPxwy%9)OYld{1g(Q`;XWoaqjE_MCnm?5V=VHYPeSgDK>;Oz4rYm&+#2?U^4)>@2p}Vt30yeyi-J|IVIr4o zn#%-)2$wJsk;J=DG5W%(TqYo`JHtc{h+X0u0S)`THYR4*+(gKrT3U3?-U0xVgV%OQv#ersIq=gzGS;YT=WHFmXz}wyNs0ntfMCo1K`>dNd1bQp!8>@(n>(4gX=I5N(VI4!9}xx1HID4&UA3U zAZ|ID0~Z(j|A&K1jEpGWFfRwCi9L<83sW+PoljIz9Z@C*?Q zRw+5vN`SO@(=^8pxM!aaDQ_mrEj2-O1M8Dt=$!DVJiX#m?ktjkI*y4T2g)uqC3&m*x8eAN(fQ z_FImYT+cpys!`Alili;Fos87~(zeJ!p~OK@7JNxt7v#LkBIH_=F47hbyO>C3{C3lp zlJ)9Njk;k^SlGcsWW5z20XeZ}$}hDhxK@Om(S0C?^djlea(OHw=`&G5%;xB;O>_Q1 znpRe0UvpJLysg;Yr`=R*Uw$LniHJyiQUam}0luXWr&2&8u?|GdBoZeO5=n>DB(W6M zZg+f$t~nZ10-^_cRb4VfC4dqyc_p7{se~$SyOg9s_C{)=3O;{T-i|6!RR^j{fYZ5E z5&)$qarV+g`5dK{04X&0a%3dBl&wktB~|vei0Ma)q*|2#sSKJF6eMDkEJrexl-7Tg zN-Gsn0<OCX}wMu|?rOF)Im3Fe%>8w-<(5_UOBUz>PA(xD9s31}nB_LU?a6&9tK8bNkRg>7F z1UL#J&S|cDE|sR0?zvQ&R=P(j1^dvOOM$+Ta*~H6l~d}6#BL=(o88JB$)qn;s?-mu zQYApUQe}>0m8L|c2#Izt&N-oo#2b)^$6^14gVZ!MWRNKPm#&WN`H?YPnp2WY1Xx1O zR7)-_mvw%%mT!=wnsbp`M4wy98OV&LAjyyqF34+`eZwLFPM1BWa9O@!jK6o^o?)ln;0GC+qzp!Y}=T)_PVT6 z9k5qdZoq-;av3m4ZZSFcShsh2ySW3WL%Y2b;r32_H+Qn=8o9mG!0jF4b-9%i>Hcad z6_Kmdp|~7U;vy5H+Q%pKN+u~nslAj#QVeGkc{6Xea5P8JEXx=fGiS959A_3pv&Ez< z1_el^nbLZxw1{0*OREr(R(_?l>cq#yC3a0Ft5}j*`gX`lZ)7RTCYp>CUKlJ4BN~kq zEmAgvfo6H5j)weo;$wTYkB{^1EL9DiD>BiyZB)CMxG1Tkb&g7i=@gY1m5?dRm&%fO zUus$6lv_$TcL)<~NL&dRftO%QFm z8jdQ}0`iTC^OYpm)wg0yJKv6R@jc=y`^JOyOz08QHOjYlR6_hmnf5c;z(L$ywG_2` zWJpx^sMzE^GD=&VR->60XfT&HtC^x0fiWB5leOAR6vqpUpff@_dzHz=nJGlV(=3kA zgWExnczS9fzDMf7KFP*+i)-7}H#8FV%VDs+{NZD!|7*7=At?UmdjdwMH33r#U5 zR?pf@MxHX-%&f_1vRJJwZ8O?9lbKE?x5%EEa&vS6XMfuuJJnYC+Yv*=d3^;LNaDSY zo1J}N%IofC9ay_5CpR@q{w7X*Q>o(tu(^EkpE{YxSo zk&zL?pN^ztb1qZ$B9n`~TYKBP7Y42FdFvUnSq&p|3#kIBLO-}<^)}YRoAtECDo`S8 zqZyjz3^ucw;>>2zq*8i$#!(v!%26<1JIp624uUyR2|hk4pF(8WAk*iTuWoNh#3cW4 zSPQ&mhT1>;rpM-l;5Fi+ziO0fzG$JeT7-?t4ZGB!WNd{TA>nryE%cwfaes|3*k+@U zv1(XnWofBGKY;L@jirse!AjF+iZ)qn2ElBz(ngV@ImT*aq{Af?vjEg#=T9FE)8XUe zy?3u^DwKFSrZFx+4?iT9;(emW$cnap&&mzCaxZv8-X+`K{d0!oOCg+X-$Ea=*DrXC zU-aU}k2-dC$La!DAtbH3v|wHA*`?1clBbpzu4~71g#3#n9pc0`tXLE(iYuBlk zGfw3-np0P6v{HiJ$Xj6y*HgTiV?|nkxQp4uidMl)TP5roLtUW5uVk-~5cHPyRrHQ; ztQC_>H{t;hdZAga&HZCS$9;R{{1Mh>m2$xc%1YfWBo2`bs&6eF(Sju?%Kf+HZP8me zGYf7nWnn0*0irTiJ^F1X8)IZGR)Zw(CK5Z+N!}tfcJ*xIzYj0EAa09%y!G&nqy30D zQX}s=Sz_Z)?YkAQdCl^LE%KCYjCH7CWD0Jl6F>dnkD(1L=)549EF#50^xq`v83QL+ zD28QhHqOPA!o*x@N+Wx|+?0BraHo?grF~)oayJVOo_qM)rk|gwCoO>>i%OPzwx#wT zCj)1ceNv@PlPl7$B(1KcG^OggupTum4qzm`Azdq_a`w`c+Ki$RoOzSU%y1MXT3EA< zr38VtiAI<#(Okxu(rmMqpXu17aNy$GPX->l{P;GJg;uxFlD9IyT1T|>Mw)}lh5p;} zhG-}!a;({+=WP^A89?5&jW(EQi)d!dFponICf!ZxlzJU}CQNt{vUEu&p-kP@iAwpY z&7eDZN6LjdkiznJ^40ikvJ*>!RnkUe^=kZa^ll)fd^O%*#;}#_43gD&AA5!NO~-tE zd_wZo2||NCr&Nz0T%&~-1fxN)*f@$4V9^jR86(A-t(<6LcwH69Wkp5o|WtYhjg^ zXLwlprA@qG6RgtC3nD;=)FdayHxk|@|}^g(iE&DF&q!eqZSq;sv>LVb(diMEL0b%>#2*; zb<%Z%KVSHjpo@Y}UtPSe9en2Y&F!10iw2mlt~KO|(Z%Z8!e^YWJwV#QuXy-}fl9aA zf&bsmH=bv)_bByz!(}^gDC`1Gh>461itCyf8P`U`gT+XsGf8#&!EcZy2XlPZK*1Ip z+6 zps9Duc=7PK7l8|svW~7~IC`FRBvb|xYN!O)Prs&S&2LdTWX&((&2A5vX48UA!9sF! ztYzucE9%GzmqkHklcYF)%bKkON!Kn*Cb*<~x53P8ouYP$%Whi=WbZqL#avj}T?Kd_ z@vr;A%ECRFhhZC59vP|k%U4Yc=C7m3IcCQ&jdRaJL}FxOOdDUEfB1&C?f^R&eCtKEi%N*XuIb~GvJgxbi)_{j z8;_^yjs<)mhdzB_^e0_5vcnVf#Vd9cP69u?kn>C}>#N9GW z_t~Z6ckL+NY4G_i(nc?26aKBrmWA2%(BFTB^+dCu@3(jtKvF_J@AHeleKYXI^X9q2 zW_D`XsI3-^ghHf3SfRvw8&5-gANDruX@)WzAl%D{R(MFnVzOGyu%}1bEg}a(N}moL=qooI<{o1nvZM{_cDj6O#4PwXH+S-@9x^ zIFUrYo`w7y36?o?Cw{fyvlo~8l6?=z_3tjO+4?biJP-B3<(+?jUZ|xOj07{VPN`B! z5)i{R(N?2{Gw~uN3RYNs5y1C?bvpq9g(ib!xSb&meB8_1B8mpaCiOZ zhdokC;PL1%-N)-k1#Y_aZpj59?X#l<)G!inz&f20u$efH<5@=J^ss@_1U-Wl!1QyR zV1fs4D61p^m~P6mpa3ZA_(k?lk=baCI-= zM!^Oso1TN!2dmXWN#+~)BF#V;C?sF2S>~AXy>tSfPVB1NA-0C4^^M>$rVC|%JCQ9y z$*w#4(mwt77iLy>4$YSJ*GKt~U1}JaRU@OETE+^zXf%VPZHCc~H|kj)HtJa!i=H*; zDI4r>@`2pWxppn(F9*v~G-*yJc74C|^FMAbx*srgZrsQF8jUZnWY-VbhQ?CEas*90 zI&MVc1BUs?E;WqIWZ{;AT}E)iOt3~`0ha)_c$jDdM;Qe(C+Y=W4+|%D?ULuW-#X@{ zj656l(TUPbGg6lbjP=o_-K;g8xVq|m&wEuWi@{^gt~k-KUyNDF)$0xR|2k}D-N3nH zFO(Y6y?!0!sv1V7lCE6kEJmwn;fyAV7bslApiPX(@~njwc~*o?q6Hy8nF2azfDu|y zr!znbIOdF6j&QO}U3JMule1~!?MfC3FgC#7&B0^eozvqyKl=s|1E$Vqsh7p zL7!Z|8WG-qTIiJEQHv9h#gUi+QV08&}| zoW;t+qurS+#2}Giltc7;_LQ(bF(4vW%62?Qe|1Ai&g= z(VJ{=HjP=Ixnk^;-zy1^%x%@eb1|>ZS*%)o#J#p-BRT4RaIJ@UJ8Zmxhc~RS)0n4h z7Mh1gIXGB6wis=2P)!xcl(}LIGnZHBcVwQe7M*LqOW}&KjW(KKwV%SXpsZG&ra4-$ zur`aC7EN&4LgtDw>36SbJS5Y6wNTS&#h5YBdW*pd!7A7m$J2~~VK~+#iab1A!ZB>- zim@bKFV0->xMKV;yQdXnXyWy)7_SrmD!Jm;nSh-udvASm@!crmUn5;U5^->LEPPM@ ztL(Tx17`?R{2ra!e{WM0Em%gZ7?+1JWO7WlfV0#SaqK%&8(nMo?ioZIhZbpg!5DmuU!tq=ztQE6*k%8c(6`qw589}c%aB#dD zY$P?k{VT?VWk@pqxmy87p0#Z~edzKc)xzdoYjSG$rI=+}FcKG$>UHpuhqDC1*M^gM z^sp(#!r3fFgN^4*28yS7%F6sVR)8g%;e+tf-HI;qEn#tZr%gz+)R`Bh3m{m>$B&XyoCUV^K1c&XB@?a)nmS zX?H8J$W`u0=?e=BHD(7k{h;sZXIJ`a!N@$`mD3z&(9;Hs*=jb~U` z`(!d28Jomu=j{H?Ux}409njbd{+54Ubm7UTBg1#FeF_I}9`FoFcbEh>E40YEi+|-^ zQ?gAXc4zdqq~#&EPin!)oEqztDwS4f8F*5~0_U>AE?g_bB4Misqqo6hW2`~2T17qm z)~wJHHueDOJh9Q;$}O_2?41kMcMRo)ZMVyQ{o~5GZZl>EPCeCvC8>567Sw z;m|~QV81Z%M)PPlx9fn*<$b7RJtX-`jI=Qq>P>zJ%?l>=oy-%tb(F~f`zvW!{xiXf zgV9Kfu74u5H%|C_QCxnXePI18NYWrGEH zj^Y^$%i~r-6G#l#{W4GFPS(R;DLze(wNuM7H_?flaN*`jH05C(ib0Tt=e136u9%)O z+u%tw%Ep)tCaVb+_$(}^H_(|UawBimcKVg1I8K(9T8i2|Qa&F~y-eh0m5((+G{H{5ZYLK~Ns-$x*(#&TfP#pMRorIY24}Cvw9{ zp){=O85uo$O3~Wm@Bs{ncO@d5cdDJzqx&$(Bp~RYo5P&;r4k#{XZ{W zyuQ^T-MWX{2Tiyq%&ofmbe?;E8kDO;#8^}Y)vUn{(sv6ya(@4@yGzdJ{qh|xSVo-4 zoew63p|?5)EMt$vx4Lq5_NeUVq**zBNEg_zG!o)p_u`)+)#le0#*8SpXTzuOl+%Jq z4{DL}QiXo-i-S{lVUM543I-acV`iHuGJ1HL1cJwUc<|Qn#-GT&21prr>EGf{KByJC ze6Nr-INNd@StXXejBU55E(JcDbG!ENIg6=24QH8qqF;e?779KxTwAo`} z%6nlYOU~$0DX{>uPz@s!AFR_}p&wkpd!9@tngcrx0bjG3hlAmbV6YAFs17*2@JJ4B zad$kC`rkQ`n{X7lo^4;`jyge1kI0A*Rz`ovenJ>T^5Ach$U_y#VgJQ*|7{um{zrce z+A^wHtv?TG!N?RvDlb*&2bZv6iGsI`;M0>dI5ZqnCnd8SYs>ToEq9rgyEq%9E&AKozV%FtSyy9V7{ zcKQ9E#tj`?ZYnZR4I}=zRIihP0WE3Fy_jaC`P4o@B z^6$^4jkwBB-g7PMu$j$kTwQ|Xd&APo3*$x%U=nsU_j!NX<3_C)B1_dU;wrnc)C!NI z3lKSnSUJ3i4R(9m;7wkPSx;FZVh5+|yG(rEmXmXpEG^P3Afl0frRagS(aY9s9nQKo5KVXyh@P>)xl=}y&0>H>el|0DE=$;p2`KUG z)Duvb?T8NhOGkmX5eqDpn<+DNBhFxk$1BVb_yGVVAJFVv{ErAekUELKmqp;pb&%qlpvQ{f&wCG_85_ZfO zX?W9xiG}TQ@UR7IP8NmDjGj9M3iAdMymY&mOr`{0$<6!dxfRaW*TbnY3=dnwZSayK zSo4QdQ(zA%&NB2uGPz|&&o$+iy6AZ;PtkKhwp!N?p7vdiH)oEr)7`Xj~w zuWbP@je-{-F%(RZ1Rh^S4gn!JFQ*`6axlp;^D=2c9qc37)X~Y;^*&2^9a@KPrTwtX z#HatO{%82q+7pKSe4wfHYCmLcYNG1MMs);T3q~eHkX^xAS}&T+u!E9;84MhpVzCJ( zc=HrQ*x}iKhULtzfy)10R2{jVny5N*SRGZ@f|03^pSG^Uu%xilqMlf18T7r|SoNerv+% zdK(v1iFG;r4)Z7zS-e1&sw3`NFzqNjJisQx5$gs44tu6xJ>O>5v*4B(EhfQWgcszx zD)(Czg?~rp7V2*g)6jyu{M*pWa{Rt>sP8j9-ntBbL%ykAWJ}12lAjNZnA!Wv#bF5l z5&nwItaZJ<(5}Vj?=_t>ms>m!;ZTkAhu6xa6ofi*kAhIc$oxR611pst*5CvYo-EMA zmNko>f~Vo&WM+7=GtAMSXnvd*LNA9&?ogkkh zIaq4sX+6aX@Rn9M*&J*MJedhv4KIE+n&3fAk#%9|+ZN47mZmhCKTwtjdCL_!C_ERj zO%5K)7dhn{$=)G<5l(8$A>T~)T7jx^Y2xs@ec5~+aK7DcZJ7h1s}#ROzTN4$Q3d|j zKX{|icK-LV=T{LF5Tk4|T6ma*>GHt$1{MA+Xw>1X#rnR#q@xzBv&=0l<~&z3UWO`b zmMgY@xxL|%%lSj9nlu#z@KS#W7BajI0_Toiukz>552` z8ur$i6(pkT>N%fX=d5E__t`SosBcqP3#M&WO3B7XsoH60R(63@J}5Q9Xc4PNKe^Rl z;+?qc2MB~#>Xzn4zT@6cbGcF-7f27JgL?Yt;JwJI@$dsSg7HT}?#}4c}S}<)huJ&xx);rt{ zQaQTwfcRYiUFp3nyJuI-}ge78x;c)r@tkwP4z2T#Kd@ znQ=r>nOrP@aXt=3uTF&H-9)cq{peLO&V_9s|9=OjEmNp_*yXUjEi($KlXi+l)NM` z{8r{s!d*IICAg!0jR7gFRRJ+Bh`&&v#rH$X^bMYP`+A{D6|N*{!30g;N^M+_CMAjv z6?Fl6_~Am+H9&me$o`+5i~UHLb#g?%ulb629>`0L3*z6d%pZ%_jqVma%ChK-PsY@n zss-aUY0C5$fqkSe>++ZKU_z2oV?rJU?a&trj$fCr{_opLtQ*>1srJNQL<`qSUT)p&=ckVL)`EFw>eJSb+zZsD zG|GsQL;Uv?EIVkFI3?=&*_spm?r|NpU>V^@VyDtKjOh|36ra#NBLA!-orgR{oV`)N z69ef+U4=#kv+v)!^0$Q>pCV0a*qi7_rjxgbyHqd{JL}e4d3V@ozD8>w;;4Utjy>*iZA@ z)od7|1#h4j>V~8XoQ_8&dh*neFv+7uJY6t_9N`2h=b8#iI(+E-V}l!pc8$8GV|c(J*(@ z!7F~qK3EE}x>G>n@+1Cbt8E_MB%pqt)lGG)hXhxttOZ-9&|;@o|N7ix(p*ir_;u;Z z69xYrPuY4~BvvmF(Kzx(>Pph3Gn8$Y+M7Hm6d2=Y7W(vp=+ zKUUf&dxQ2*MQuv3>&hSlx8B=7ufeL28z*Nruna#KnqLYdU}1L^U~P#1H;qHZBY^`S z=o&qrl>LvvIkjMeF|(YUG_{u@?ofA(38bj{8~yQik+EH)q=h>B70Kgl1|Xj3NT+cQ za6jA=7NxA#NCrr@jl|;^3!AG&Q34p zzov54dr5`+Ki7h#=TL@tVe$s|EeAp8*CdP7VWMD(^h2lc-}BgeXj-}&4pav0^39DeNKe09g9N zYh@z77vg{SR5e3UVS0}xw;m1N{#~AnTCntA?u|1Y}t zEZnp2CT?N7E2BR-EPfq)81+Z*z&bla#8EB@(gHHf=s{y21|quvuNh)oDw$VA|&L^^W_8 zKq~kA8V}pM+7h^8=!d_5yk;#vDBxCD#9Si&pM-y=d$F)$*oN%Fjb`P(c%cQ$h>+zb zpsD7EgXvk9tJEI<$*~2KXKu$uIJY$6JxqxI>5ZjUPM!3RxU})dCz=$wmrV+g8MgH8wJ-J%$Z$Id;7)@S4+0k&&n**C(h@j&#>d~UzkjB$au6WCm=!91 zc+4j@s?if+#kNwW2Ag&l(Sp5o#s!HeRWaN@_C>h=q^7%$&G@9pE-je0ae2MI*t;O= zPhwXE?rwW7XmkCa0{`;)#pCRi7#GC9*`ZS_SA5Y)T)Fh08lRWRzD*03-W?G;Af|5c z*EhW7z;2JO5+bq-lR==KlGV!!RG1xxP^N@R|>rfT#@BFYAg z?38_sL72FB-;^G`SFYBAX?IYqy}oG|sO}E96{v2p%W8wWt)AcaXb?0PLW9m zMf_XVIQql?f_0(0Mkf`Tov(QXEtsIWk3)+lY}JvJ`r!b2xR3&#L{Rwd#7>uI{n@r% zccFjIHU*CCUw#zJx}%BIi}<&{`1_@w>gNbv8F6Rd4~LH|*Mhx?ds8xe^!M7hJoI>Q z1?X4WE@iGfRKQfKe-UxV{9Ef<_M7~jQnQHVp+WHbclGFzZLCEY_kEpnvj@&=rv-cK zEDsX#Rllm6Ti2-+KI+Q>d4_iWpoA7o+w!RA9mmr&Op^z?4GJpcXov8+3qNWF;v=1D*FE8ct!J7Zk?(c(w*zS4qaS{``XMjla! zK1h3KkdZ`kZrz$We|tD^J_)K#Tg$`E`nTVSGX2B1Bs7~J5n3xZ!4GjImZutAFPwF{ z@TiK5gU1d%Fym~+l`phl>1}xsN0L(I^B@t8=@NU!|6MqA{HhMKb**BbX~8ne@)V7V zoW<4rIBdqgq1n$={ZU$tb=OOYrXl{^d)sern|dj1)zY;uI%jL&L<^P?mZuXS&*xhI zm7j5Y*ob@)_1UppEDF#aO?VFz;$Qx=#JP*Ycd;W*XC0OAT9pS{uuRMIDwfBi&+{09sDvOLv6@G&KRGIk4|(@zL5vNZg-dAt_vt+PBxM493j zgFh54Mf~pS7BBZH?V|{lOA*;6lI0 zgMQy}HRS6?TCg|K^1NxwYPyOZ0yYodPes5czoEpxri)E#uP?i?|M@IkrYcPcSyrn7 z5)^lL>E589Nu0R6@r6k@8g|iwWyG@DAi(X$_OJifyVL+?`OMPqty%H{o|bsIRwDk5 z@+MU%A>_k$L{^Yn|87q8(Y;iWwd@elbe zV&s4^>ub+Hb?8iy#*-K=SbCd!w0b0^%E?3``t)CwqiUaGwP(~U*6&pBUc0qm+NNGB z2$gn$wc|it^`(28B>Zno_#7^*?LOhwM@TFZtt1>_n24!I{NMR_ZY8?y9${U#7+*d# z`#dd}_OhB5O)kwT`?1un{6SFif!`6a@tvdUN4D>(%%Iqg31D|rkP?XT&ZW6?{5tz0 zJLgKhX~&vvzM}<8@Ay5z&lCO`9!m3iA+0m4ZMlup>z}@O@u56dCg)<|4hu}viMZ`Q zouB76jH_wc)G2()$G(^Sa^fo6> zDpDDzM7${F$&ZkzF4A%ul_2G5etJt9_>hOYe?I6mTryr$5ksK&`5+0wzx`r~6{> z^e&$0!h3I;_qC>+hi-VHKq|bi+BfyRKdQMjWWkAbYnL~jl3&>kiT70#IHC5wv|t(G zeGLTMEZDhE(fc)e2pI)qb@v^vM zdG5=#Zua~VarTBLwfBWIsbT4DE=dnW8dBwbArWftOADrLF10+BwDZ1B0ClPHz7T)4 z_oW4UP2Lwg;Gk<16W2DrN1fQnxK}uq32|2YUs|yAHv52g z^Pa_!wQ$X`O#;T>I}k8*{GWelnfF@2r{e|vmpyIWIqa*3<>ply`f#@vEF;W2+PxnC z9{TH>ljVbV_uE+aa>HqPQLLV%iuV!!d-MC2_|sfBaPHMZ4;J{=xu6Bh2=o36AYWw5 z)f>J24dR?@Uw%KUcjR=$*&CW#aM7`fOy0%Y}?uu#7P8__pJ|=G!Aa+H4l5w%_?YPh7{to`glbVZ{INz>WjHo4JzT zekrNY(w;#}v|z8vyrb*J#dnQ-g^4v{`)=W`o0gTG7dS8K_QaKwx$9c6H_@=C$He+P z>``!gesdx0%#et^b-PmB8A7IRC)WO8>ryQ)qafX0?*UGQz^2AcuAC)}5Dv zqdKf?O0N^1Hh$@JMeTV>1)!c>GN#EIb=%V}$R)C;Gyv7{+g0IhgFlWtJZ|iYs)Zlj zA}A!^)lRtMwiCDV)QRUnr%Q1se!B7abtBtz{gjpu*LAC1h}b>Awm4Tp=rT}COs0Eu+=}FJ2h=MA6*)0Qo~-s*pi}%j!RPNjmr)Afq1Kv z(-y)VZwUMO7tIqkSBtZeu!F4H2Ec_i7se`%s75ieYN6gFF;QTZ#80mYG=Z||V zQvU7)WD_>&NJ@MhKo1u#s$UZL`Xl$l?<@J>GDBkgM=mYqo$4cTjULrsmm^?y*7xz;w^+{%i8FEG*_-? z`|=OQB+lD=)Loa5RZc3Su1l-_uB35jBa0+q3_sM4>DnnOF``X$RHsNCD5ox>b8Jjv zotQW=AtoxWZEP=mX`UFL&?z!eR{?JKfm?h`*Uqt#(w%<3ed;8{C&sIw5~1%wc2~H( zgHyuX5AO1eNwipKR^Z@em?Cep=>@CV0x#*&TNptwnsgZ2s~45nEg`O9WNf!6T_LP8 zd3)-5^)`kU%~rFK*7Fp@u`I_LELJnT@W*7)TTPUdKNMb@gejS&Ym^dk6Ddel$sdjm zK;|eYj;hO+Y_8(}_^ZHAbIh(#X7fYLD~W0UrOM+&SC?sb{$bM3Z7y9T@UtZz9x;Uf za%f2Red7kMX?cRc)oQJU0D)<>s|8EUinZHQhN?z}Hf|rW-w3_*QqPSx)gFk&0z2jS|7Cs!>P5_ct ztBf1bNRmhSE#+7B0xej#Of5yWNv!mPiww7(UTP^vGo0BV!fORB6lFG0HUkCkjW_e0 zp3+lhBQI%b6GlnoG-Iv1G~0jZvs!L zGpKG?YEy+v=Ql+)-VkRn!}Ze3VOE4rLV<3>Ov*xuCM#pn>je{Krr|~DHnZ72%w~u) zs5U+?a|YGDK&xkT$<$Ib0*+z!ZP8Mb!0TC_vzX0-Kv_70jj_>2@DC|7_=PNI$T(*( zrCO@C$*84jSVE?jzLi=^>uFlg85x#?s1e5);63P~(a13Hx@eolX0oN9Ge~S@5M0a< zN>{&8yZAS^i_Mzy<1W((WGyDtJa4tveGonELgg1ch02RbD0>kq-}8ZoP>vxQ zbu(lb>rpC#2)o1C{P~;r>_Z_bi`|?KvQ9l@?4p z+@C(Qp)cQ};M(cK!t-wGz3|c4o&OupBORV-%ka*+Q69gDX1ZP1^3Ug?v+jXq{uHlk zwXGW3Z-MPSe$k(;zrQ$c&254L@(h&;6EaYIRw+KO=|afd6S<1+y7grXEm(SYR;8|{ zsyp%0ExeG)6>-RMI{%0lAw6 z2hTnHZPU-s)RSiAp1LhogcMcyIp>o7Gf#!>z9Rg-AmZoJTCj{XN!I|!uuIcQit^Iotud~W^|!98x@ zEUGj-WWSOCTsr*QjXUprP%~ij2W6|B>onm*Em%hESDFQ?x#q{p#$^jzgl}DSHqK2bFFyaHqg9Bn*JjmTYlJdpJKz=r_s<~7d2T?duiaTNv*bK%c@kOY{)oBxc_R) zkbt~arJEDzYj0EAa09%y!G&nqy4mC z8SSyL?OW($_WA{n@rz#E_)*8sD3q6VQlw)_y$(JTCcFq)x}=j(rf%y*E!dmmv6U?M zY)kDwP6o~>`=m;pCRa{-OXa%k^MB$y9^}@VKd@x|sd0CtQVq*!k8M%6epii0!}--) z%m!iL&_*w#E$uwEL!LagujDR7dcE7JV&|eBJT`yu*xJZ7rOjIzYwpb(5^<|R(8v$7 z+&-~&kjwr^9L6wVkm2LMgF@oRd=$3n(;f-J*2n}cSVp*W*gG#@9_$klwzARa>lHU& z>bMgh|9@$xMf_ubTUWNH?HRvm&dL3ouZ)|k1xrtNP8O{08eBZRRj*>b5wYUprB(JC z^wS=DOVd9^eeMTUom6}DLCdEv_Oc_9CN(S#Mi10=M9GneUONDa3qqFyC*(MG zGWUs-wSN8^jr(}R8fhOCbcV@>KD&okHQ?n9?s<#VzSXkA zd~xE&a?NJfNsL0=)iCX`PmTMvl=K}J9?Cx?+zFfh24G}#rRv{@zZl#u*u3Vey1BMu zK2J2M$Gk7)irsGece}HHw2Ve}IUwQnp+G^KMwDK**Alcod|2yE^;T3TC?tPIfmjx| zBc{h^=~MN}`j2}Tco3MlCU95L-IYh1s|OPlkWD#cUIoJU(1N1=UfB-9nyy=Oj{W4p zFIupS7!>jSj!WvjI9In#X?Ahjh0FK(J+6Xid(sKKkNBV5Y}=Lh?3s`?x*8?h*SS_m z3ziXsVi4f=<3Ov~bnRm8;rAwXx>0Nwtbln((~lQ_K1Ho;$!yKaE-adT_I0F54SR(_ zkrYLAT#{06TyDS*x#PHiQ)HBo2=+zU)8AHE#jh!1$lh?`!KqrX9*UNn4X8JAdHuRP z7lai*T#OO}Z9Yxl9&HL1SA9Fmu=v?G8}X4QuM}`VvAY9{gq*7pU2ertTbbBaNRt{S zNnUQ;Nz*GCS_PNnidD~UKz~3 zCoal&`2OS%s{f@03y@7HmUGbbYI`ZMDhw^S-Iq@A#?DnLpu^}#?N5Zy@AdbDn~P`7 z$HJayQx76iU=GTpd=NqR57R4*0lG3CW=*LY1BwpqvHJYNdCZ{DuYY?{@{6;|zDyn* z)3Qlgu#6Z3P{q`?9GUD%q}UYw=(Nysq*ris-1P>xHeVWh@)qXwhTvV@&fHvgb419(iT%$W|K2w*60C+9 z6c{*cj!r!`q-c{bqKEv`SN6sKF4uSulcTA3?7tfdu&5k8fh*7YC`_dQdNailv$-~Ej7`CnG}`0DWVmO zHXF~uvz-QpqIm-?T0}~37GN_SJnqR;sTZwPZ!}S~0k-JDGozvznlal1n~?{p3If0t zTS?z=(W-koidGGy-aOHY@T81|;w(nNVx$<}01qRIyum8K^A@zg*^H?dtwnER4K~im z2__>v*l4uTG)IdR1>f5i#ZD%t8LD~uZB!luB zaW0p0wD>ejiI9ys?;Z@#Q*w(IY^$c@uO5UW(j;m`@bd=usDpQ#9)GWkIQ;g7W9uFq zYlOI~VUA6t{SC&C`s4g)9o@jRpgJAA#1t6ZtP|r_9xdylMlbo^~lAUdF9a!%+ z0+w4YMfA;WnCf9E4^xyexzl=Kr_W#On;Zc%KWpfqYNhVqoJR0NE}(0RDH#5$3~YXF z$FZYf+cs{tG2`Y?TCj|mzu>$7P8AO;wu8AIUc6w^sF2RtCL+$BM2`0n|8b=TUT?E& zM9|z%Kkrg=+!Iy{mJ#z8jLS7#q_h1|;UT-6UJ$imbkpvLvo|!IoBgQTg;s|`M+`ih znV?rV}tr&Bn`G^Moi+q=V^=tH; zgIX}?I*#OQKppS-4p2zD<9-hSlFhdr`0Z@Yh=93Q*jasV94m`RxT8s$G{SwvKQ2$j z)gL@=!VKE@d;Q#-v*p)<`DmH_WOJ|j$X3EGY~GzblzA{8NfNur%~f#GsNd3WbAIw^ z_=3Qs9e+|qzQBxlpX4D0@mon#>8}kHYA#wNY@hi1@Fux>KSP?-Fj0%9ELw6>w&Ip1 zmrRNuE;M0WZp_zL$A1?f>d*J-y=qaVVf!(!JDNy6h<|LUs_iE(Fb7PyYAu^D^x`2c znD(O1D-Utbks0Kco-Dw|VW)NUJAB#`}o>0{w%B%f(YQUR1ueZdJQKzSM#xVMTJ1dXRMe$}}OT zeC2BGU(U+mw>Q|IzH@7PUFLqaEdjfRkGxX2J7TYf9e+I%!CG6|(Uw0`jQtkhMZqEd zrysSq)*tlvqs=Q3do^shCic>U`;eP-!R;w^E^lD0or#;*8GiOOiv|z7cQsqD$@sLxBOc>%BbadL1$wxMa&)YS&>(D#Z!?a+pFxHcz z1V6{OQa>C(`65jSiy0hf>~iKGX7}KTZLP%Ie;{FMm^5vc8+CF{9bZb@4FLW?-L9y9 z4_5VAz-|AoqhHd(6T=Y&BwCAb89hnS{#WSy(&C?p{*$WdPJj4In|4T(8ir5tkmRK4 zl~yRQIxrY7Uo01)?Q08u`Y~jQAuy?YWR`y7!j@Rr8`_%RJEoPf4=v(AsXJ$^-WdwulL4o=SF|u>q_FT z%^cFDhE2taup&%NKK%$!x09^TScBP$(QWaC3_X23AR(}sON zK-$!>`~2wW7dvMtYoP1F2G7kc)7=YGrPVj;Xw@@Q3p_#b)x`?I6RhlY$VS#vdAXy8yS z*fd2YPW$+JX%e8#q#K(a7I}U@Xc`l^y~L702@CvCpp%RSGmqPPzOs(n403z*ZZ zeV$WVuvr-(r%Hg^KEL?eHv?ZhZ=Ne`W~Y{o+9Cno(DX|kd~Ae!mnZ$3?Z2?-xtk1K~@7J`}vrr9#BmVgVCd7aCpU^sR4@ zCQoXD_mQ|M(b=jblw81XA6$6TisvmCYr(XGBI>C`+8+pyxSY5b`zy6EudsZik(u9N zk|ZmH_la1LE4IWk|50=Mo~ig`=P7rzA{>)eU0Sd=@IZJA9=&R2je^z2QzjbreK4FT zS{bX!$nbiGO6?h-7Mh`L9Gou)d%q|v!_fk7Wki!1j>=|@7SqpyIqgkL}BrsY8J!7(E&_VI3(NeXo#yZrn z?wK|g)%2~?Ql4fEa6UO~QPo>0y{Knlk2;*MEV5Q3&B0OeioL0?_HYw&#$&t|*+)`p zv{da_VjXJO8+cGWjArP{!C}|DkpfG>noXS1WHNGk(V{n7jj44K8Kc2y1#eKK75? z=_JAg3)I_6b9y63*(_#wB!)2v_@)K30p?s*#UnAV*?>u`0~Vr_7{233_9lCZ_>VX@ zGS8$Z{YN8fF=-hkQqG>k^%L`}dxsV*^8k5?Z*QIU@)j#R@?)`5dKi9b*2Yp4Zxl>C z&xi&yC9sO8eqOWoD)lZkTB^3ySce*xkZEI)&2OKUQYNd(WH7@MYG#V%EjD=H3~w`9 zY@!~1vi8Rg)8%bK#8%=WY74PlNqX=5{!?1_sgduCFIFLIF{MO%-3Q&%F0}6P0C}&^ zq|Wc@d6ZVE39Y{vUg_7C4GsitsyL8HQ>2Q5rL{q6Vp|DIC}sZ_(X7eUfzKLqY$squww*QKyVp}U!~cNz~)*bN|$5=;-1 z3!5c3!adRLz61Y97V_u7+Ifl>^3UGMcOcq#d+kLN{)iSU zo(WZUZL*M${82CDYr)c>Yp3l({s*8BsaeQJ;?%(`Etq!qc>N3ch>Lnn3qU%At7EI~ zx&*>8Y1O3#djl8pZ6=YoZ~{b71vr4kYGq6iS%vq!SqvtQhqtk(Hb!gYDWlndQ+<}F zIM!$rIF{BMZM>d0m}#^8GSBpTvpb4I%N0Yoda06#RJ{;H;A*udYJm4iA~3CXwP2YG z`4Z9q^2ymO21~{)aLHWANAB7K#ONeu zxL$hcBw9q)2uCUkEbR59j3(UGY+;QYV>1gZE9f&|As?MYcMJKbd1|BdGAB{pJG6RC z=0ZL&_AS(2+QPF|GweIDSSSkYKFiu*W^XjYmql-~*oWUHcG_NP?E#g{>wR>o(NeXo z#yZrn%!PcrB=PfYvau$C;ou}ucw9l6R8QUZ|yYE_nPfpX5O^BmnQu+BuE)rCky#FmZ=x=wP0xw zT2IkJKFXP-RK2QDYmnB0W#mFWDze&jMWV42kdA=A)d}fPN2#=6Z^lACQmGX^_J&IJ zqCHZnhG{Q?ywYHb4EH#g66xT<23lsy6Kxr8lE%xco5UWtUC77d=PSyYlbyVDB2Ow- z`+_&Om?-*pdh~o#y^#ePgm)(>Aj9#rU`)8?y6msWHShW7ZqmE${sq;p{xehy_STss zB%*zRZGK*v4n#qjB-}}dOznmQ#9zJ8uLbL=XxYg$!c3()D>6Ed&T|1Oe!xCG z&!?3W`m{DlU_IW*tU-ll^*-hQX#VKtq}Bbt+`j?oQ^T~4>Fbr*Pk_f~{JeYXE94H^ z8n9qf*@2t7zKo^}H=@N5Lr6sAZjERic*~VrBicDN8#K=awpkjT^l|NJ#{<3$_;bUr z1O-Hg?1sV}W~Yl4{HbJCkz4t}vKu9u&G}vn_SP9ut*vufFl{56K3;*=c0&}-%Q`92 zp*~7T3#Q#k(}y-ZN=1Dn*vn}9k95{Gsp+hRo&e#64$K3ey`%UYckcdak) zY^o75rIfIx!1RZq6`3(wu=MV%WY9tRrfL#~M5wppYr!(Iv*JEubsP%`epzQlI@IU2 zX~8nOv#QUydl_y2kR>dSumtrFUmVxssHs z&Z;$+)q-VYXVsejBhfGGtVoA?WYvOYbZ1o`+W0cs-k#2y`JR+0jc-`T+HKQbEMy4WUH)E?hSorTpy zd)N4Eb1sYxxupy5VL}>eKH}OG8kRL+R@R{f&K#dKN(-jlQD09`i9ES;9dPrhO(*@b zuUzo_pYv2)vg)tBh%=r*m-z5;Ks#>i#p65mLobR`7b6^5uV6od94S3IuE(c=y^h$| z0ekN@*mN~D5&Hwdp-)SNmONpM**JVax4g%c9hXGx8w01x{+M@6wvgS`doHG@UgVpe z(SoHx$4%cwL?mL}kMA!q1YdvBpvv%pA&YkYtOfg@LsgU=_w^_^QBqX!rhBZVhPE#d zK6&)sdwc&pKMK+Cq{w(5@h{PT=!44vTex$5o^M(5yu%?am=!b2$!UyUFHP7v_1k`U zS}FW_`>O|!PYnrtxD!$Eh9>pncu12P))Om}lar=5KYEX}6d5@ApB}*D9<$Pcrk~pnfS!%k9av8rc{E?7Uu2f|CVV(|#7|nV35ph+4X7WB#8;&#GCG%XT!0>a zNTmsGCE#KT)i3U8V3h|gIu_Wxpk=Oav8+3qNWF;vytc=_S`#p8t$$R3K_icspRNTf zLL3{&??hWoQ=^p9glAssEBoSq={1q$nxN-G<2yjis&XGB^awn7@PRpL@&7`T3SdTW zXf(7Md(=13T9n%ibG~zh6i?7u*{fgYukj zQ8etwQ6nQ-j~-n6_m7cAHB8$?r{54%0SIaG^OF<7!2zR&ELxN_=Us4N}k?-XC2ymPlQ{-$=m#kq6dhzcZ zuJ}Vo#NQjCwF?gV`s&`sLDPc^mhU|7&^e?{4XcEe$;rvQ^jSE+2JIf2^JSgTLp{Xl zW9I!+>H3~`5fyJ}yW3!9woXyI#AUZF1+w>@!Xj;I*c7ZxP7d0#s2zmRlsX8cO7iXE z5FkIFeof7q-=cEJnqR`3-5xN_h8aE4r*`CKu3o45oY`=OR|x zz4z|pVW6m!nk9>G!Y8l)H6*B<{_3p%WA7^fn(F@d(O2xi#z3)K=`gpkQG*dGA{GW> zpjar1L6?9iDIJ2OASEbeCkA$RVPS&`{Lg3aE{yx0jWL12_y0S}?%i|G?)^L`p8Gj* z&kcFl%{P)T0W2bnpNIAXJ(%`+YOKDpOs8Pg1e41+j8G9F1ctFE@4Q^V0|tTa5nlKJTAsuRX-TZReV7 zSySd)!1-|&xnS)C3sE4dEluw3ZWvnnId~!A9WZu zle&HOn(+lLskh%sB1j-^r4`;=vsmvQ+gZxm56m~&4cy4s4-tqk*bjkU{``-K>JwqS zK!ucPla^~wQCz<0gKJPl<#wE?E>Z zopf=@;k`Ial%l#A*|=4|Z(=X4dtVYq-OMz;x^Xzz&QFlwIPgdcma@^)p;~?#R+&TV zcQpxz{hz2pYKe&r;@n)=O;7+{a^!(fG~S*nS}m1lA8e^Go@y(J@ZhI>v z%~d2!0JDguH8>J8PCr`MTer=J1wo5k!W51@z+p`-s$e4#gc4PphlIn}t_9~x)lD+7 zrs@B}d6i&FU6m4ekejbK3_o9?X}IB<{DN|uyUb_(TJ<$AyM3I0*yoGJP~b+!L_KH( zZRFy0n@%iay_tAlO4j?q`8g-+;wN$sPhc_f<|jsl!gzS8!CA`LTA>@=qFD}UcU@~e z=1hnY+<=!{RercitLL%cQ56S6;}-YCVJ%LKfCRZ;35SVNjD)SQz=P~H;V@B(5qKW+5@jdDIC_~ z#0W@``&V$7D8&fZCxy(ev%&%oawj(q6Qvm81_qGX0&&}_>!6sa_dF*}ywY!Q<-j(; zjf^!1F*<$p;m#2n?U{LHU-nu&vA9wfzyA?2l0khT^`5_Y%V61ZL%pcb?j`Cmy0O3a z;>2h%O2BMW+udGjW4_D!d~q07no)_vnp%uF5)RobT;CUvAdf!bFj0z;uoV_~ko#P4 zm?*^v*G~nR*^2WA`?vr+u7(60l%a2tnYQJkPq$^+>;g%~nu8dfOj+R_NLeeh&MGPK zn#tEX9|;h-7%hR+M}bfRo_$7zsJDq{pHT!lOTERY)NF~|7RtyH>QL7p(~Z}*5+;B- zL^Ev(+LyUH@lKXrtE-N00@A2Om6|xL#fcG+SRb@kbv5hPA>WYoKE2}He&H~@7&ZPw zX^P0ccg2%s`!a&J#J&3LeC%@PdkCttvI2*tr@Nc@vkV3lu`c;_k-7L7hv9{&L3k;! z*UOXvYuTZS*nw?bVgt5z>bLLI7uM&E+6UJpYR|kahr>iIHe(PG@4|Nr6B%cwi*3Ie zpLWS`S6%!>E;e5U6&o2eZJ9{2HqU!)_0;N48jmkZ*cGb_fiNEgv%<8uZlMG1xn@J#zjcp8>RwW$e5Er zTC$B}5RqTrh+IH>bF3%Si>J3{iZqRW*$aAn&C;SAeazkbv|dO-Y(vzO*b;~byYel@7s|x zTTk&UVJn;+S;Y=!=+kVSW3iR`nZmxKr@9uV4Y$T&qIeDr?npUmhH)d*=9LW}A(Pa5 z590(F4e3E74tysEu-{8t<jc^h{ z2=@)myKbaqCvLGW)1kbr;YuJ(#yqgDU4yibW&Wmp47RS=l-Bc<=Do!7taeB3mwD>r zuoA5OWS0)~v=w(+^U4$MIFQUlsFf#iC{|u#?-`n!y%z4;I&=Tg?@I9ykyoA&(gXHS zUYdH5uDg4+o!cq97ixRY;;>s-PPja2I8JHE_}7Y@LaP%oO}ip z#8P!a$Hwo_kG7Sllmt#>Y!a4JDzzCgWtf3j6D#D6L?{NpHE;n1VPG}#CJw`8(O#H*7~#d>HRj22HVNl!)9bV z(f0^;o(?Gd`ipkw*~=x8p&O;6=i{(P&D8dw@CB-tnv~#g9n530hRGCz?PTn6GqpWR z+@{rO?Hv{qR&L1K(XPK5*iOdY3S_%Ulb82N3wND)r}nXI&W*h2H?7aD2HVM4u0Xcy zH@)p{xhehif?P`t-ba~Du<2lmM^y0XvVe2 zK7c-Ic`&>*2O^8St0Ie&u|zWPY%xgldu)#KTZq11@f^c`sd}%nWJ2RYv^1`CCrp5J zX#*c9EJuGUzJ6%^DZj9>}wJq-1ZO{ZYxw*1(0YxZOPX8 z^q_easXdN4*zM54VT8EDg=@?s-}oE0t6~T$u{N8Ed~+$*$s;awPF7ATcn8<#SCHX2 z*l!gb?K6b>aps-x8-nv^jva!-@PkT?%Sjp;e{SoUFP^O4&mIOHEI1{#L!gEL*x$L+ zK$%$j<(|W4?XxZW^=bwV6RcyRVe<(j?9cXoNw297rd5m$3i2^=u5&ddkqeH%eWMcm zCL9YTI4XKZr#tA)dAoj0N{U{T$$ah#P6!U9se<)c|4g+lr{v!j9dTE)`ijF^oZ#RJ z3l0-S-zcs^p?s)QaKQe>5AwPAh8SvEg#E!Z+id=dG_I336`8uY* zgz$CdZBw7OSZ(;*uZLt@Ubl8A#YxW!lz?Pk2Zyyd=>ZaCUk8VY!q*v!3bHW14%koj zb#Pcq@^!#|vaf@~1QVc!^>tPv+x|cGb%YWe${7QxFFL=zOQ!~e>^i&tDNb-8P079v z4r_6OgDWgJOccHju0o-FsM9+D`^kO{4r>{{4p>h1b#RzqQq%apPC~lskuEyXonN^5 z7o^kA$<~!)Eyvf9;OFaH6~@pb`^mlz4iij(8rIiYjcohh^>w8A_3H>FI75vUeJs@O zeQ3RJncIbPE)#Hq18GY3b#PdV6C7M&!C|8Cb#N65{mbMcqM;|X=Zb0l((jgv%Ex$ z?mWu)cTx!rhl%oe1;_vhb#=ai-5)IrHSWis(D3c`ddA}@DOnuW5}r!{yB8_zMN;*D zQuZvLF{F3MvQ9Xxxj&ZxHiy$@rv#gMsULW`CUCU(vJE&)FyU<2=Mu6|fhv05v%kdk z*Sfota@w1|x_uLw%eS00+$7*nIRz5bq&^t7PmkMD5m_v-PtwH;{?vz;=uIi|Bz|BTd%I%Lh4r_$Dy~NQxS_ep9@;E=N^=n?l2(mze-tEmM)2!*#@JJWtvFJNzaTs1!lt>e1E(vQp zLFGT0)j3Oh8m;F9z09qhr%JC=t2472PF9K#7oM^bKqAglR%}s3p0bjPE>Uk;v7e`2 zc;Luujol}Y{O;kPJ(|0C5MI_=l%8@q$(|Ka$FvW{$rq_m8FDzR5oCoZSVWG(_CLA$ zy~BQ^4_E)8hgIC$mNascEkxo~QsEc`u>Zx*Yo=a>V>P^k%cdPsH4n#OjUX#^a#BLJ zZSYw)qP1ODYO=1!6?=cPqhPZjoE}dseiB#GPkn#r+?jc6CrkxSWUK*X1&TA6R2{g> zO*P18r&cDOL(GaDMjRz9OG9TCPz9kua%_Rn9>30uK#3HU(468&9R?eOws zUsu$J>nsPGqbB^cBiI+i>E8yW9{MZo8KA!&<-QMGSBVK;ou{=9e97 zV;Ki$jy%yLY|L65_64UoVq_hCE~xFq<=HlHeF$Vb5g+WVh}vpzxbcQs;+cfUY*Ys8^=K2kM^tagDzl}VW^G+(W?*Hu zVJmwintfLIV5cXMzDZ~&dj8Y+he?kZ$!&X;%HMaL1d(`=gi- z>i7ea{}kXbPj>8oKWZ}auW#<)&~Msc^;eHofKg!b^D9%X8mipV43}&hXO??97KaUl z$ed6^gRB=%>zh}^DT!^ZtVu?B@G`KX?1V1WE^T0r`_MnJNf1$xtkF%?p{$LupgLU+ z?DSyJ#9ZJ+#;9;2PN?BTE`LV_)j;A@kTopJwPwV3_O|By=qoP*#4o_u4kz3n%S5DT z`zod1ow~UD2OOq`t3dyGPv6Y?5+KYVwzV>4142ip&a$#)?NhTgDwcg;n)w7G3c^W@ z;{2l|W`jn^i~B#E-sao}PGn3MFixmRw1%rM)fMNz7eR<1EaqqD95ughKug~KiF$ip ztQ4>yW7lvw^Pd;b!BcF68SE{gd9^^UFB8%JXv1l;oTVnlYfK|nofuE6*`-!T7$a8y zUl5n8Wf`w@;r4r%={{8Nl{8juPw3Qywi6>{AYI7V^+rvX>cr5fPJueor5?W!I$d<9 z%**j}yT>@-HfM9?a5Gy-7cxeJ1m=XAgx|_Rc@_(v2RNtdfVPU<>ylJ|`R~OLB1kTe z(^!?YO3Gc`W#GiE1*%R%fejhM_X+-W9j=(bHwe>B*afY~U_F#J~eMwwab4AII1p)(Tu}@V+Q2=QIv$fR<6yK1&EB zhUFi$>7Zw?XM17xR-1MYN8&J1OaXzWxouLQ551&B(^WpY?A_xx-;lXHD4?J_M?+dLxsrO#)ru5FjVJ%L6fW)rWgOjBWWov{at?n?R^#g4j){^80>>uMT zKSABlpAq5orgsPLsZsG!eI>{RFIzRYZ4#a_7E6uyMgn=TEFIXcLE#&kRUhkaaaWL z0~EjJ0^~a|yYqo7W_7;9rMLrk9B!O_YT_W=amgJc5E+gWao{@CH!M8!SLO<)oG344g(yf2a!3Ux$<~% z-T%j;fty&->Q3US&p(_29%Sq?&Tnnx_r4S9#;Z(8a3X-c`?u`6{QOq5W>i=|g-^ea zOvYi8xe8`YUi`K14ed4LYO^Pd!IlWsmjFNz4)>nMi;q;j%-XkV>41XB#Ax6^#;|i! z|I^VZ@Q4dxYrVW}ScoKixr1Gpo+4yk4 zE8s}R4r23(tY?kG5qLllgv(QRC+pIzY}TQ%K2yamcaj1wWNbXP-ZVchx{kjWR}NdC zlOxw9q~Guna=?X*#kP=qiOnDNvvnc@*WMu=jg(MRusS z2IP$|4{JZyoaK2;{>Ju_Dj%?&j74JefowaB0CBANcO$5;Lj0)KuLY?OcKPLt&U;Uz z$M%oC9H=u(0c?dQJnz8*SFS_+iI9x@|^vExBf46G}*iXi8V3nu&-4Q~z zcUtvNyEvU=t7RVAy&lfKBapG;X3jn35eL4L1Mumu75!|)lOfti?`inQj$*FCVPCP8RJ6?=f(zKI zDC2lhDq*0mZM&5f9{GOOIP6<9=dgNhuXmq5w5LS$X57m?$6!}1GKTGYZR932k!+h# zI=9wRHYHkdW&iT>v_Pn&@L1oX~qd{+WAawQ6_q0l6wA+LL7!4NooAa zB1GQ76mqlix7-e=KWDl)yjXW4#B?aw&ySzT#b^n~dO`_!j-pWbJujh;Xx3Yd+C7}) z)aSZ4E!)ZH(f0=<)Cm(H%?L5Ff)kq@pO!qrP|M-H*ok5NnPNDssl|xMbFfvY1*w6= zcD+Sk78Xp?@@jpgm8(%7FC2y!qsD9Q62w3#=AA80PTI9bJvqK&>dv9!0zGdA9HfSo z`S*IVo0aJK&6#P`vpo*O3sK|qDna(CE4S6K?C7o+zP*!qyPvvG5X85V!g1gbzG;4| zl8?8w+*c0Db$NfO4-ONx2#rG-_@r&nYF9-uEyt{&;}T02Rf7GHuSDL$cka+|k7hkY z9bY^LY&|&FC+ay*sYyk~)mu$mV`t4PE}N+3UjBIfkoV%)r9n2M6Bqw;^6r%%b1C~b zs;H@EE}DnKMDb8nN0d67q?h#6kQz;Q-adNri~Tw5K}UWW2bl==&+weJO=pF;W~BFB z)s>&NmEbT@JX95djK6+;ZL9MO47EdaHRRX0mkk1&1>v;vpBt-6lP%RF4k&D5`gAM< zPGqbBR3Az#m{c8z(pe4g*g4MmVXa^DA_h1FAkn6aLD?=ZFZG<^DGG-RvcBT5qeR08 z#jm*lxr_Xfu(pFK5ZI?CY`chdem*yPIC?{vy1fMLR_grziy;ymC*r_&asd0grhYJq zn99=i+t9vE_*-L39HxWg)C$-ATPH zqjpu`FuY6FG;Jt&ns4BNVbYe*hpT1hTo~+N+L`azHDnwF;E}kqZ_KqaPrY24O>gZZ z_T@NCnH~Gzj~d}=8gApzW$*p&k~(nd99rIrqqd1Uudjh6{3(dDp* z*1?REKl+S%Uyc(aYm}znVk>S&bg|NL*FGaVqss*o9M z;_XE^OcKQ-LQ_{*VZ{h|BrfeaF{saMTI}MGNsC|VSK=^Hi_w%w5B(?oQnefc^RIh& zl`evGu1k!7hjN0!EuA6?HFy4)sV;FQ);O#=h>^p+{pnqpi!?(c&7(a}B=)b1pUB0i zVLT&Kl!x{9j3ON;xH7WkS*cRf|0L^H%)p7!R+NBb&j^P#wHR?E9I{uq&MF{5_Ka|t zB>NKoel)ch%|R?pUmPDaR6<$DB`09($>dk-z>>NuEbt(EMmS8=Vx)F{@ZFeR#xw_$ zLECSXKi)1VH?n60+{jpS5Tg&jR7MyXlxv3l%Kx!T?b(mI_=#MM8pbn%XEW<9Mt=89 z!W8~=WVxvQIdA$??*>kcV1W&?XN1FAoEQNKvS)o)Hdf4q{YsPSU8idKfMEyQSuw=a$f#ZJ8DgGc6t z;IO6^BV<-}5Na3?NSvKE<7Vr)cIx@BS-o#fT(lF1VV`?wqKR4r!@4{nu)DKPhn?eS z{u=4eqbnX+$tdEmmarx_*zMVWf5z=i8EOZY`?O&H)cHh8IoptlWlKlbayI&-RAvDnHM! zt2`cTK!MO4o?YcK{9Z+HRhZtXu3Np@Kc1}2NHFTMW}U^}T8lWMetC8PCw-L9sLD6` z!IZ#nr?nrmd>nCDBaAn45{6^QzZ-VRBMx*zJFHIUrYxf^>lmv?JCN2r`z~DS0{5*FIMXK39IB(OA2sUBaAoV%&Nr+X4WZMwf44UtFbvUvE| ziTC9pGA~ZViNO9V{^Py{1%1^BTjH=sqx%H!)+q?;{*8xCF0J6BL_Q zks*EvBu3Ik7U!>YQTIP%-pyl;lMfE_le|{&q z{_5#g`BBABwdO!+W?9&wvx{ptO%RY#bP-%okwp6zLm z!wB_YPs#%apDD+(TxKQ)yR#N=FgM%8y^BDx|15&tw9{FDgs*R0rN!+~`W_lHGw9dj z`8ezet}y?n3EZ$g1uUqOo_cYYeOgDkjM<9)Q59^1yg9k({q2Zyydp#l;qTjpMn znRQt^y{P)qD5wywpuh9IQ)a#h{;8f*5P5Xp zB`Zh3`4wb14)#BI_r7Se_$3{Gm1w(_r+w%+3}2}mm(x;Yy!!Z;dd`ljnmOZgUvK{N z$PH}f$BEpZ$4&(F8=k%b&nAu+Cu!^5#7XKmqWf#9E-Vkv_#DPiqh!JaA(}W5!}xd_ z-aXNahd4$a;cN+Kft^P6uHDL$Oe60k>C^U?PS9TaGg)S%+Zhn^E^q$py@0YKe@?UEM0HB|Uf&DjBkA1bY3Z+D3Jas>>ump?! zg$ffth0E0n+~ua$0rZ7aP;0?#B_j}sfQv*Nw?#WvWxJMU=@&9m7pJ7A=IO7%VR2a3 zirih(uw}WgfcB>SzBsE>_{g|kDp4wiHzY@ zn9S*NgLFX=xATX{_(^H2rSep+X?VLmjhp|W>M3x#g7BpHiZmz6Dczj%g8WK@2Lk~A zi0}uA8hgXUPcj^3Bb@HX=1KvMV4nFZa+m5GScd{pa(TK`5rg?Ca$zqaTq@(qRy%IB zovRZzG|^dR|Mqr-31AK(x^`$k?$XfTW&J1Wgx_)Qb+*09T^vT#$QIM~0}`#A~ zz(lV>I^*+j*pJ2`0zM7Tbst-CjI>8vdEc84k($UQ4>{QN#R46nRo|F>}$uz?}Mu%gnHi@tAX9k`T8H~7T*0DSmy6uGia z<)l6#Ydn?pYCk^8D&0v4Wqo1Xu{h=AFg5=nX0yBG8?PozfHWfo2UoAWehv6Hmf2}?ORoY+3#xk9Ip9U50 zqx!At{Kfi3GP}I;E70gCV!&g_sXr4kdks~Kpc~!oOq)0shc(jd!&=H(>kAkMf$h+8 z3ceVOm2IT9-O!<5gqCZ3#pN6^KOoMx+QM;QM3yuhhL@(s&B4}SAPT3^pUhl(M=Cx1 z;_9pU>FJ%!o&#=&{>Zls!1?7Yx#=!^H-9m5fO)p-^EvrKr~ywwlHu3**6%KaAYGv( zdPyzIXM}ht4T*izc0OSOqzo|?#{umJ$E4;aNuFjo{d3oP$)Aazaabd?ufYs*s8y0P z(b384(&zNmJChy|V3{kuB~b}}z%N(fIM{#x(|SK!uVp&U9m>o0I!-)|!y2J|4VNc} zTAZe%qv{3gH_zT7ukM#;|Gmqbzz$=96B%oO8wV6; zFsV9lmz!#k&rU7E_fc*+ORR{vJYy66K)3DRf(+-3g5L^~iFcCMPI-4_3hls^ph3qK zcI^bhWNav*4d_^n*@m-YBS38=k3(OVeW7;PN?Bz&Ovx)2hRhXAHwX* zf8SDFv&T8am2?Q<#e;|pHcNV4k9^cFU2pG_vYsY~2OP&?Ik>#}&#LAP^ZG=>HbHFf zd&lCqVw)oEJsnPTn_@ZX2-r@>JctvbZF9?m=636f7{teyHbpK=y}O3RuVqXv6VqkH zZE>}@WtXs@yJ!=)E=QCzo?8w6S$Q&8GjT%V7#YQp**HuTx2{vjwmsGw9sLIal^&FYvL)+SZbrkS#=4dk z2+CV$|hWKOFXdw=OY(TV0fqd~RK-XvnkPx31%TW%p=b-K4%ZzAC?H z=LId?tqV8GhQma0>#{|qj66DtpgL6#?0<3Wl;k!kdun3n;BKjLRZ=)i6t}La$TneG zU0}c3j!y2(XY16%wfDC3li5ncVa@K=1*2&Fy1)36{wY%Jj(XcYEI zWs9FHExpI$;^9iIB!Dm(6UD8|A8{&6A2SousMjsn)9to+ee?lVGSUbO*>;4NMyBleEp#9DxGjGz1{6cte=6yL^*0) zhHTt5MZTL`WGH?28%lP{a(_?A6{MN$KiJ0w;4%B`D}yy(L)1Nw`R?92`QAMo_6^sS z(?lcU!0qnrrQtozMlr&Vo*$PrzgwLv4**x-;c@8ud6hpI>Y1`1=SkaH4a8xh97u){ zRkbga#HH5`vI@eBT`a!;-Ve45l5g_yVm@DsR%?e8lm_j4Zuc6vkum&e4Y_-?aR-tM zkzJNX)2lkZaMVndO6f3q;oUC?;>%IwVk_`Ka%z7*VoMRG1##foj8=?|&o$zdPHf7` zc(2bbwrwEcP;fzi1~H2UuWWr*D}~y(O`B^oZsV{PC$>Ps+`#e3D(y|IfNQz4=ek_p zgu_HRklY#7&S{r=ZoTrVfE5>fv0Gfhlpx5Ix+*R3xUNz#&PgdlC(Q809P!1EI^nQJ z8c0Ty8pP1syeG=AgBb6jWZ(ip5I*MXbW3{`cc*1PLDTM-!5i6mMZ)kR)VM>&U^|3; z=r8Pcyn3w0*ezfBJUG-T$-2&G-$gDy-kiHFQS*5Y8kh2$#bPVW{6K~Lv1KZ4%rufi zmd|zcc~xr`3*qUxqBQkSZ#71IvW|fs12CY8*?C=_Fkx;RyW5m?-rV)--T7 zR+Q-aNSqopbA61X*RTh5acepH`J^2`=k2!;&(^lN>+`27f4f?eX2d|N2Yy$%3mKuG zZYTj;FP%W6q@1B089sHXK?&m?4r_7x2_zhTZm=+q-bhR8f2#fLl?#sHutw5PLTrdF zlv4<`M)g*qTKQN)J4I9b+47{W4t`@O!~GyqU6mDhwDOKJ7$4J5cYgwPwt>crEjUaR zf(o`n2t+$BvOmt8>ZGXW{$i(9{Mk$KfD6LyovZW}Ez_+!{@tY{e)W5J0l1MdQ41|} z(HeRFy0l~J9;V$)g?`7CXA9(b0~f+-`Nwz(@}kbZl=5!F%U**x3oUI{GQEN&Aol6rf$qC zoJyDgX$ArS0m@63;kJZ|Q(m;l@w>z_Q=TltVJ%K*fyB+B%vX6EA*pLFNaN~ znA_m67AHnP;!T%Qljl29SbP1>TyY&gZ7~i@=Hw3~Mol}g@s|hMhOXOJwM;($sF7Ai zkKeuTT1*sZ*(2aE#&@vliykX=4=KFwcq!%cVH}39tWDFs^#j>BPU5QCWesz!?4VA& zUame+3h4_;&6V5$RR@uK4FdPA+w$w)N=3D}-m`Pc22xZNOFq*N{I(fxarEg9?utry z4KN6;Tc~cbJ1~zLEEl98woTdwhqbth3M6{I{$XPD>=oVTBP;FN(H&E9m?*u5@5sj2 zZ8pi&Rg<$N~3jlb&? zbhF`Ku;DoH`KsLRpiQKu&R+e13X9S(CJqzjQt<@G^=PLrW99=p^|mX2Z(bkMt$jLZ zFW<@w$AQnyJ_F_7-%8ZT`2LFFlS^NS!Wxv z`3coT-aMeOd~u@$NO0t;yBm>J%j4LtcjihlyHn?U0@1wM_)&M}C?X_>nPD2rkSy@9^g_)j0Mv zElDpRRCmNv=mFrHXCfC|D`YeTLhX2V%1iJY{ggrX?|OT<`U=4XlT~yz98*3I9jUE9 ziZB7pA)42F(0)d_OIqlzwwi~A-!8k^E_4wNYjJ`LB$5sf57?ixK`nMgLcGeA7nwNh zpx~YnCnq8Ks$%$X>eRmRYBx8aJ(%kwkr@)|WoystDZEn)t zXPqQdecv7hEyCsQo;^N->2__8eD4hJ zM4y9z^GXvqCUQaR4c4JRs0mL&lR+B8v&k-vie$Y7E$`i~1BH*2)uY;!-CA2Q#)>cj z%pn8~>eAAI{Z=my{-EpKbFfF@CBHHp*5U*WNW4>?J`-?Q4kv#g zQEEE&$xWf=u~a(P&&=2`aktH9wZkRy>t^Sk4Z~rL^iV(tbouHDezm?p;z6iMK=g%Q zwS>rEIa$VWm|#-XxQ_wgZiT>sA4ic(kHBM!w)~`rQYOSqGB4-O#$kOA(;OI5(`LKJ zz2=r4LjL!n^qcIdr@emJ82Z6i!HJumS!v<07AHMGLguu&{ftSb8UX>r#daMJUXQ~> zHKsTX*+*r0FJAxY4SoOXd*V*lCtpSo-@**XfkUWuXS&m`C5!;A*3&;;OK5|`@D;Xc z#uUL(SiSgh=#fr$Sci{m^;eM7r67neH<4FVfgg^%I*^Z#U@J^7lg4<~KU*nlek+#Q z$6No5cjK<8M7KUXhH!GlB1sd*-V>i+J`T~kN85d!(0RwKvUX zq9G0w<-?J}E~yJV)U~EWK6x%h*&JRmA;xb|)f*L%rJVBcpI1zP z%Tw>>+mod)oJ{teR6lxSbyShE$9bGI`=Ar6UUStB)LgzO@MpW!ok!^FaabcP#zK^R z?)+m52ys9L?TjidZjo~|Xw2D(tyE^+H;bdU{iY3wu>6)tXle^lbnR$Cy;;=?o zjD;|rC#QWVhR=%CT5TulFk?J_eV;i-;|WBDAL4!t#~^_Hlyw#i}FJ;Dc+u z9LDy#1$G0Ux;PmP`e40St|K+$ROP3oudhA^PGk(P%4ALr^NI<=-n(eW@W+^Elz;TK za%Wdvxu`G~X0q_*By#^&;5l>p{GLY_YDKFm+Wdz-)z6xn*u03hO)p>)B@NOHZs`!f z#mbyl`QaK(b6oJ|X&xGhFYjS7PHAQLC!^tq#(rHOk>_CJI!;e)P2E8tMBt7D5g`y5 zkQikUY9hxPe0u1YVf&6~Gi`C0DCf+?Inn4 zhyKW~CIKAsk5?XwT$Cn~?mav^=Eb`6X>wNv>g4BtwD=rGy9*HVA`1sn)23Qs3vd_gd=%M z2yi50c)@BKj)ZUpBfH3R8-XLtBfMEMfb~wZG^XRquWn<{yzB)yKkgzIt}kF63WRF# z6t2>4e1r>@>8N*;)HUk595rth-DfQQEM=XjByyMP+$KF_@b?S9-Mm z%1ujGG&|np#Up?>8T*dqO;u5rRgsrbl2wqGQ;<=lQ0TluEEEf~$ z(Q_AXX%f~P%@7Mf49H7#Ac(Kx!EsIa z5+nCvs&iuS?89uwDGEz!&rgOwk7c5n*3Y?4G*KB^vpu32wY|NSA@s9=P>u3e(S z-0}r8{BWuc<%Ya$5)Nx|stzQ`%O>G4ygT~W?JoASR}Hjm5|~Y1HVKC*b4oC5YWfrY znhMc$B(}s=YA%5gesvIj0QQoXO~PT;5SbHdE?~|!? z}V2YWEjAKj)Qp_(+?qVTzlV5hg&IL1lmdeOjFseULt%lc8}m>)Bq) znjOhFti|akkofWE)aGBSkLkG0=oR*PN9HXYCJCv)2{jeAX$rKkeT={(eDtzwZEgKD zJ>&KjI>h7$;4o1LDp6Utpq&Zl!>$~1`J$F-v82i%yw@2>W;jm7f$!u1Je1$*sjh1) zMai_6@;qfV?iCKh3sKVv?F2+Zp^bK>$2J{S-fL4iH66uGz=a<_!NtgtlPo-)Io|#n zCvn9&US2w9E5SKqFt5ZPZF$I}%f3ytsPi%6`pooRgbDxkJP94)DP@J|8a$=!3Gz1U zEoH?cx|J(-@}_2&r7oo0$}T2M08)gM!5Yu6_qwlc^Cp}c;=4#{`KTO!9QGGdM*NhM zmNgr0duq^s_izbbqckWEM8HKNFd#9KHnKQ>rHi`%8S`!)Yn*&=7_={lP;&utj}}ZB zZbh6LqVuzzI34$veQM$aJJ8Ndjs5dG$@N!Hx5|$yeyTMGBExYa4)>3VeXxH-xKaDN z*LTux1PaP_fE zvJW)#ZhlV4=~r$8yvW!ZPPK${R`Y7r_`F6S0=-V1N-y8#%G&?&Q4{K!_lBX>0RY)`BVeAml{FagXVga?+(oAJEZ zX;A!RTCUyY?ERC5w#8wDdNkFL2q)FRRN=;HfkelB`I8U!TtF>QI9+TPIXDxCNwP2T z??-iE7Hj;%EbJmg?93^RwKsgRRxRFhm+>vV7jtnK-hXO*UN$J_HvWn6PN^8fIJ)e8 zu=E76`;fZ)Dk&TX4rlZ}eWo+aXdwsW6-F-b4aH%i_MIjoB8dZ6GM{>F)64p_gqC%? z{|T_4A3u?ckid`J7xv^MLbixzy}h4~l3z2rMNVKwjs12c&ilbIZV@7eH()4p8F#$|y7d5ses)*K$WFF>{m^T<8$A&&#%u;%c{J#H)&a+qJ`h2y}7yv7L* zbHaH>Vq`D2-gAnf2Thngb82{ zA-GUZ$gk$YVJ%K@fdu*0TsTaWPoIP#8~3$OI^1jaBi+pRw*$fz`X5G6ogxH0$gk$Y zVc)PK^w+(D4fpg37)^c;7Y=Krr%xJ|2w84{2pJPhHtT&`fVP;x3q0U%SLpYAOP$DN zG?P=52@T^Zqu%_c<=CS8XT4?AXwPHKqY4EY`(EFtr|XIjCQN`dBO1@}3f0c@-_KeY zXQmnJ;Geqb^LQg1*3>e}x%q&p!Zn_O#Cgjy?YZR_SW)*aH1~Hlt;AvY#`9lG4Ww_K z&xb8UEQ7vUI6k^If)-^oN%Fi;rz{}M&o6-Ez+>TtkAIlXrBwGVI~DzRNi4x(_y+V} zbE~C3wZ4FH5ZJvCL>8_@J5Q>f&(9cekrBHiA#3QIXL=Ax5SEgY6<^PeRHq+enXT$( zxTO$Sk}#IpumwXYKn(!0j0N+c)xvbn3X%8ZlmB zpEoXvw*#CXXOT;lz|Ui(qD<%6&j)KY)LW|FOH4_iYyDt(JLFc z&z8~g%S-E_^?IE;4r^+uf_x={P)%$gQI+vC=FppVtmq;A9Bih{_rYPJl&YV|Mq$=4 z1|Gxi$4xOf{*&orJRi$64f31zofd2$zPZSEY{} zC!SJeiW-ykmMYCpUsmqv+F9L8GA;1-m@1rC1tiG#I~+Eh>q=GZ%fUzE-jj(-3OlU>cqArCRjxBSPEB36!~SVV z`bQi#gSZfi-_+cMoz?+7E__*hf3nzT4R<*)*;CIpmf)}zgk!_atyR=}a zrzC&XzRSu`J@6?g#NQC?1`V@+ym@oyZKd>mcM{CQE(Oj69EulL5d)|?h+KFD_7N$l zY0p!5ZG{ouHlE@+^r8f<@K1{;4SU#OGPm#&&DjW)Qc)J=ZhOS_7|zkND(_gVJ&MDc zT6n875bX%%BLWF><-lR0^bv7_g3RVypy7A~`lB*W1$ACyMf2sT(+~dH9G> zomJ_^bE8hJ)$-lr@vEfmCvf!yV!2u+{O90>?bM?u{5Ct>%l8nlBx87)Y8nZKxhQY{ z8B>+qB}MmG|AW4lN8hF+h%YyhOOn9r*?FUf^La{Ap)is(M9KDMapyjC@0c{#_vL{< zxFv~L&ko8<)h`o|=NkJd1vBQh3-i_Qh{IZ(BmoKXeGP|+YCSug4^UTOhU372T)}ae zC@X3NvXLyA2x{IHwRbBpQGiC947#23tf=ddUsdl$+y2r;-mGs+s38l=-FIL8MB%Qe zgzpfAO#8F=Ow`S!g`FA8IIE#xkvIAJQ*{v0A7 zxXqTfi%AY4ab28xw(MDnuk;+A#2GEFkm4FOLA`tuq0!mkSd~h{zUe) zxE>Zsj`f5d@EmQUpoiOdH{8Ap@#JBl@zX`)o>*$QjXeJS@TANogb7d{PbF$CHIaqNF%?NsCM3n{xNJ)r9z8n}#|k0cB)OijZPc>Dt& zD1dEyR=iz&)~%mjfcfVc?vE3o)yKy5QkRN7(z&b`vSZ}&ufB{o1pc61)S8H&PRkO|KivC{>Pa|c2Qao50MTL>o)PQw225VS*8R%9rut0~CHC@>Ucr*~N-VPDCx7M_h&rRP}n45lud&lj?F4wjF%)1;6s*Ee)zUf0{gaE?(<8tK(oA4yP zjKWigEq7B`IIP9p^npb7V&}F`SG?7Bo%H*~;F;~^aF{51Ya>x9pEl^YhRL3njOdl= z--n01v4qTk!cSBH_)ZRB|4ql;uk0sZ(bzqu+wuFqeTL((meE@amXlo_945-!IguM| z$sxIrkURWx?0-ahN`;XgtNsI!G_2T~-|3=Km zv=oQ6IOzcr&&C!lert70GwGAdoDThS|KKoDNY8LoVn-Wnwb1M)t{F8tLT$_awlLG2 zZ$XCRV80G^M`XZ)T+Ix}S0>aveG?qkGNcDAC$~UwSaXpca?1{Kq*+VPK#sFU)O(&? z9ekg9H5C`4_w_VOmuZpFj}c=sRQAIm|M7$gkYnE5uBbpNHMY zVNESP#O(%b6{@QPNUX1V*mL%U1kJQ*-oL!JjrGA{f^~H?>=-q?zp3qYuS2Jvio-l!Danh53 z(yziBHYw>al*+dt!*Q^`TU?h8u^)cX_Ow>9>2{vZ#9=K%dcg9B z#Z$)wGeR2@F^a$MC zvgNnPP@yo=)0!#ooN>4V%kyX8OvT-gUf`q$ZouT`77lB1(gP&O%`F_(lA2p!Ke@Su z!$jHKDn>R6)7%0cWKR%>2_{4h+uQpeHY}@LNb{0Xn50!|^A?A-xQYrSW^edsn)$#DH0QTF z`=4#M)DMT@J%q-4s-93Fc>fkf#W6WoWiQjV)Zs(b!r@MJ6=paN91hQQUm0-3o{^C| zcx}cI)?OSYN-tpr;`Ziyr-|Lx-qk+PyHAe~`mNdXulQ9|g4?^tliXNs$7?%1e)(8! zzef>pBV(czp%2KOr#?^23+|28+;?YslCe9>0&M5UP2?iv2iBoLC;-nRVJchIF}^&)hj)ZU2*~lRxjwTo0MUuRz0b;87H* z+}TXbP%G(xZ|Ja5##%T`6hZ{{K@fyPjL!a@gL?-t55Ll>xbyI9A#fmLc)>AeU!$g0 zalY1UxXXGCTC)dTs{*~2?F}Lle@A!C)rrxp_=z&_`bo56*ByTRL@qi4ztGpV10T_$ z{1IZ-eZ|qt@b%l4>ZZ53l4{`*wvjs{(9kwJq@Yjo3w?1|Q;QDAJoZMYCJK-szt9(l z;a}*hsHUi-s3@x@f897yTML9(knz}Nr`M%H>IFeu9i^K3Q^kvA&$k5ajWEB(@ zl@-)fR2Pz{Z&;3 zQ&%7y;cN+yk^QJgy&J@XzE9{7vL;{CRci8(K{6KEKUil9X2xVQm*h}xF zr%QYJPB;vP3yDxuMl3lf_nC=U>@Cj&=qT42tAE2jHF3ZP?a z*&n;>+f~=ZsbIPwoO+ah&F$b@sJBOV>E_6iszJbsjQz#!oA@c1Q!5CSiNqNMAr_YV z%H?$I7m7o+d~xjK3*tbGjK$$HOH7G_5++`$uYwU~65Cn@Z~-!2>Gvmtm1@kx1t+R< z4Z80g0TBh^l=G!PPs8I2GqzoUnoDW}>0fFLSy~o)$xx0Ok<# zd>HK)*rjBQYEz_T_t;%r(eSMa4kKz9+&0;d!!qSqmdni8yR#N=FgM%8y$g~4Q^4Wv z^Xvn}2e&;0hT96|TLXzc|yB~OwF}(0JT?2m-;&<}LhG)Uo?=U^T4!mHW zbQrutzWhWkLIN*JB+-$N2&MiOqJclVC@yjc)m78=YAdU4;jM?&|mX`y1?_%Z=xV(qeufc zSZ17}tlF^Zl6r=B|6^<~k{>sbi;uwX)3ol)M|`AF8?)Zc$hUbed4n$eVdUS`95v=< zS{rWhA)1ltC{0)ISZ>XDW5Dz+SvY=LMYoYStf|EZnN=Nx5+5L;G-B$Fiq7LGNs958 z-wYoqi^H13`!w^Bt-`!d6ZjmmpQcdNeLgFl#k{0 z4|j}pCc2kZ+66rJAESUEf%sL<9Be&0d>$or1g+EFHhVq;KQe|FUNXOieV-=ud049y zO;Gu>Kr>rr*TSn0GoUrhmy^f^SK##&psSqc7&1i|!F8EDH6cyqCNq60)3p2M;KSU4 zOL%)3DE$<)#?3A>OJxK^?g-vlcB>x_YihwIZnBWSLJ2OAIMV(5r+*ml^pbQo`sOlH z!*N&+*Oh8q6mmgs*r}7y@C#T|)J5Mvk{bHn%e}wYKsO-D&vSs|VE?Wx+e2pU?bYK( zRSowm===(YwTxNzV7X4YV(Xahb9MaEt<)t~7qrGK@i^@``;RKxGK#@p7gtmi8bt)!!6sqgb8{R7lt2I^_+Zl))Q{+BAmrc zlmVx11;sv7UwdPO^P6KAN3?y7!$dLW06i0=!hW1$m0t@jEsq5%mE60=Sf!#_fie^pP|xo6kcmz z0J4H`ve+E8Nc`{=on!CgUG}>5i~&w$46n+KGv+`{kH3$MUn$!=baOW!-9v-ajhsrR zs{yC02v3TyNOPi`(#ocsh*IKZR(ae>>BzpOpA9wa_0w5|5{}VsKX;!ePup>H2i}{w43O+tBR34fkYp zU^(M3qDHouF$y5j*WV%f$*3th_C*GiDZN8Oa2UROu<`ry52C^xJEDA>*XxtInUQ^3 z_oS>G3xyoPSS5pF5P-u^r=%#8KnwNwD%Jwso@2{#7`|(;@p!R~Lmz_JFW=QSz;2#C z<&cfltg}luse=7v3@=EHKNcYf4BJ{M2+S-@F|A6a(Rl%I$>I&pCa_{*igJRBl~avI9V?E17QM~Ll_Ue zF?ah*4_I||fbPCeLnW$~wEl*}TAZi=i3;EGyS#@Q>%`G)MvuJWch^5<^0D&8+yX^3HK9Az zKl<0fSjH$d^MGE19C$Fyx<=2@ zoS(au^73H%{U@|5h-L(}ucsz*WLP6s23M5swagw&-zVDvsW$+UbuSH&6Hx7{c0 zE|bDxjnwZ)*iLL~ap2Tju^fahYD?`qjkTt?hV0jaV-Blcg@}T1BM(#nH!>!evNmon zAa0(ToD=Sg1A%BG$fB+IbFP_UiulBs?^UXir1IN>^<1k6M0w>g{LenTK zj5-+3s<^ahcRcl&`;L5D{U?fGN?nx}cr4ADbEr~FH+#^H332|FJ$!K(-sSsiZVf)& z1Z*dZ7Y@UV&|mW*gq7Gr7C>MZ2cjV21Ro;t%PWzKk2mMmO4NLw?M_qFPsF?3Da^xc zcaxbwHg7i$YijWU8;Ky4 z_yCEBK|Sw$h_KUiuFSaDe)MQ59M(wU!>*tz)$_ry<(lBfulzzBF#AqIk*%T1Dy^W) zE^j+t%zBE$8cAyi+lehvb+(fRQ0y}S| z5`6TN(oTp67KUGO9vzc9LO01<#$l1tl3Mx+l>x#r^tUv(Z_iK%3q8M9WADB*^r*yP zO|73qc?KJW(oZ0h=HH6&BiqNb#T6h$5u!(pPVtiOji8Co}R{7Y&26!|LKD^2#dk?9)PYtKr%H`hV=Y5`Y?zziEf2qaI1gn~qpIfrLw_c3Ln9f@kUy5dLta$uz0u^AP+3vK* z`JS3v?A!ZSChD{xVU4b_f{5nDTNm^_Fw^j;cjRaV<-NU0ST@^8rFy_myNEU_Q%CciF>kTlK`5ofg`i;-zIZ_L0 zhc9UP_Byor2ZDHN6uI?e@;mjz^Ol3$@3pX=`|?-&T`+p5c_1pmR3fX8cpnqo(W`rV z$n_qh*Xt)`ntPA$u;&;F6Snn0z2a1>Qy0>$$|Q_DP7rQjlWzA0@ijGG(4+GC(;=T+ zI(_#mxyfTfRb@yR`4mRD8m}QSGuKCGy!{rS@BTX{)Y{V<+B07osZU{nMk@9%7!+I> zqdwhMlg7qlP*-`K$iO9Cflp+5Wr>}7yFXX|@S2BHj((mgP8u6QpG-9<5+-beg0_iM ztqcl8P@knBVgG_bl_9P>ANac;?l;LeyIJs^Ho1cWL3~XH1$w9kMZ*3CgSuWzg91HN zGa_OCfhr5YCrYjnm1BB;hi!u|#0x`DWg zJEyOy^szKZ+umdA=^Ya%BB(~=0zFjYB4Pi6aoucEyHh{VLp3fE_AeOM7Q~fw>UW+C zj*5g?$LQ-nN#w>g9@wFTU4!ejEq64i;yPV!`mGjoR&NsDE&jfBy@|)#-wc%rCCxAe zpo6E&Pod>;)*}>F#*Nh4kreZ6e%j5}B&^XH7l_Dll=xL{Vrdw3eq%e|A;UOI2kGLQ+Q_>R1&YihV`Ilk=4V9OsTt!&)9I>J`ePiW3?NI%u6W(2mXGS4EDs8RHO`7F2(F;0Z^lVg8 z@+446#YAacSR=e^Y3a!CDyjyV8eYmn9-j(HVqQh&rBUP-#rF%mqs(ODE}AWp*m zg%^0`qDr8S9}rZdMS-4=YLW+5$2b{nGY$RaP!VZJ!v2L9cr8J#R94&U{stWh`yb1e z>}%H|^)tU3Z*}f5s_b@xZrbPP+Cj(Z7NC)eZEOm;{Y^|~WG>eE(gEKu@H&f*=U`{_ zhr4R|s>4$^V{V@)%`R;9~I-zfa~`KUS5bt<%a&J zbeee4Lc?Y=R@{o7Uy~;41JaNOq!w)T^A}-#a(xE+pLlaWFH@F7-E#fDMW_3x_SZh> zURYl;gx!YAdI`f5 z1}mrx$O6v%Xu7F>?4y%g1T8x4k>3U7c}$&DtPVXZ-WBL@B=(-3V+HyLcvDlgVWKts z2y^?k-a5lHS3Ak-NK(=X(*;mjR4k6I#aADI`o@|1eRF>RB0qb-pMJVy7o+&2ms3Kb ziobzael#sT-+p<#*H$CnZ777hqg|C`aMl=*|b3BXZ>gT?NCe+t0Upr-d$EC0Wty%lTgkmVe{fT z6Phc_!#@?!Aq1Xg7{2h}jhCN87)iHXGy^2W+%W~9!+bmfeV;>rJM+ucg2OK8xznai zKR&CS2MKF{K`YRpCXUF>M{8YzH9Ak$K0Rx*xzhf-PEFUs4mCwC@Q+(Qw^`qkbc2L( zTMm|7Ie3hOHNc=1=uuPk5DTs0hx?FYO$|0~d~0;#vA4C{`R@;bI~A*k{tUvFgDZP{ zaIE0+4@YI)Mam-FKO7o#V})jt!K8wY$-g6EKYj#Hrdi)#^Txs0TQeo(PfD^K2&Q6v ziG2apW|*hha7diEX=2|7ZwucXn&4&^>ghgg#7z@(aDmnXe>cl(t8R>(L=Wq8rO>ud z%bz674>Dt=>Z-6~A>61}Sqa{i`YnL~or?X`q%1!+C_P>h;r?s z{^=>3q)t3KI5`v?^*d$rO}%37^^~JJ+t#f%34GB^lD#>JvkDS=7#ZtsgO6&&_fGWN zm-^)W4HFX90KFf{fH=%&Guq-+QG~mO)C=Qm@9}+39-KP>Xx9|@q+XMRH9+rIqb6v8 z)X@gNntYzSUXf`bLkpI6p2)}^Q3{%$?WRWRO=pUN8fY`&!f9|xJ&;h-Sq-MhfE!3YCB4K31r4G~U_e!NF;&%6tM$7!+PZ@uU}V_CXpL1-!I#8Z^OfIEs;SAJZF<}b9(sQq1HxecH!?fUM(F=GTaNO z01f)w9T%sb z%$~jJp;nnq!d5W1{`(=!b8X-c=@wd8wf5zdgr+@oqrNJS_11jc4{(0;6(r=XI1_cA z;k&b2lz4}}ADMMW!N>+HoVbibIx6LdmbZ-Qsk`@b+qefQsmzOxytGm07j&R7P~tkj z(7;pR(Y!7px}(q)*iIF0pS~rZIe_6cUL{3$-BT@gJB1-Aq>Jd!U3@~;$VcwNY+xrBr@z$5@1o|>u~J6gjJcQx6NVy9=Pj52cOr2I(rwFK@|tRA|z`kewV zLdvY~>@-_?V5i>x;VUM14w`_j>F_5wrQP)0PSRq!QISSlAE(eNK`<2)#S}O^PF0&J zaNwV2yCS7y_(y|{nkoT{V5js>wdSG*PTo9hbJRubsDUZ%i-^V5sP zv+gc9!8jCSAy)il*B27@FHV62&yz|Wb7amA(%pL0vRm}mePJZ*U!DRN`MJPquq%{s z#BslVi-!AySQkPvSv$dKicK4GcX8m*Rf(NX6-Zd9)w9DOf@WfKJKr)xBk+vxZ6n9B z2PA9)tEl0))%1ij=9-I+ZT33kPTXh}y@25TS^Zbo<^m6(#6}Asjs!Xq5_|r3HqX;Y za$f84C_MEY37g24iLkZpLdRaBm-5rab21}(VxsdlrCV7bf*)-cKUm!xBlcd`Pf1Mi z%ww0=ppA+xAYL;RPQAq))UkuYH!FDuA^YVF?G3nJ`h zwhwadVyLq{(A?o@=Wz@YMxKPB&L%eOFKw+yYSnI@87%ukQg_EPpN^5|60d`BUV#nk zK~Ji^&Zot;m2~gbYO2enI^H8;kn3yIqhr+%U7(*jJPK>VXD+G!9|t z+{(YORVU<6M6+M5H+q9cDn>Rd;b_Fh1vC5d9X}Qfx0-7bwfk#{i}cK8pb?&lre2)@ zoR@Zy8&@c>LkYVESL3ooXDM7qjHPI_C9rY%KJyHS>Yk+Mr}6sTJGUqOF$JK5jq3_p zmYVxk?m~8&?$M0L+h~i|9wK4FHZI_ZQ>{jfAmYowduD>7}>al zGxC6IA8qfa#_o{y*Gn?IAHC`&19ecm0~*$Yj;KL4*CgD7^#bCy=X<8A`&)h9w+r zekksx3krX^=-<_JE)O~=5h4lqd+=WLMvN0LES0p3R9t~StjF8H|LjTRX7qu@3_Af=GcrZ@c5pQ#)7rd2 zW@)nQi{1B?G(*J>S}?YZHpLX6eDLWjbZ&}!!Uv~zeaATTa^A}&^p?tPJux+v@5KYJ3nt7ovn2wN&w zSIobtx+l6kzy6zqk%ySnz^>o7(c7WgY!Nh}$lLF=L5$my z_(df_gCJ;m1v0D${!dp<9DF+SsmZ3LqdHjr-fm37$V1D9)ifKCPffbC-XlfAaLd=| zVTsaPo&aZlG+pR)#O&$ruR7T|F-NywcJl&FRE$3Zs^5BAk9ZteKI5Xolmdg)uAw&- zU8QQAvk{u7`o`)8~;%w9BDVOR5n_OC%y!XW;&;jf5Ht;`t5_v;?&SHjJ3D=Qu;)=$4}@^l6XBaaRm zUKd>2GN&JXZ6;Qxf5Pgv#GQoFtq^d$8Y!#?4d+bC-_x~iHN#^^DG!*lBZ7pH4M=#C zPD)5fLJxbxM_X2zWR%a-%(&C-6!7PzPvj=V_x;nkZFr0pK%>AW)Mw$eJ0DGV7-k%J z{rb%P@{8;ygeRR~xJA8xnuIkv69N&``=?15*@T4CtA0crYjgiJ=%C&|O~S}VBphv@ z5XaiwKMgvl_fM0s6=*x0sz-UkGo#wxKh3Ns%DvJgjBK{Tsk;PJu!7z{Epnsf`&S8* zdhsw?T8CN~?T9Ha#Dkhi&^)%T&dRgA^PAmh@n{cjsu}mfx8GW=A9PgE8>7*`jN#p`q}|T zPSkZDhtEHDA&4)P)VJk>N-9RSB5KVw?5`E(Azsv9A*e~C$Svs;tA?;2a6JJ{lHp-V z?vk~zr1F~=C+kgFWwQ0)n#z_53wB}(P-b}ScM~lS>?RRA!0iOx^W`~ns}_6DkuYIf z5{_%&TC2MsKtx6huNU_v78*tAoA|frzhoi_6XpBjT#!mP#i;An+Ck5UT_2deV&mF$ z5Denk3ji?o1UjbXKcBStW4KPhu^s*^#}pTnuup7P*Q)Kd&f^ELCdCm7%*33@sP+5e zfb{0WpD&F5nWmGj_->Zm2Dct0tN}f?{)A9}EeV8Bv46ov0}wCjOQ{jWGwMWcqkKPh z;Ed+#xL)CNMt7JAd>|g=v2VQ=b8qviyRq zJr--v!$wPM^V`{ee|}jdLfkZl7WcK*$%v@5{c^astV9fut|^Lv|7%4Voin<(O}6=OdTrTa-T@N! zFFtw$7puJq2(_b`(Uk=DxhAz_r@Jj*S*_UQO_puIlvoB^JiU*7Wzbm=({U5JG}u@0R4D&_YPW~?=H5~=C_6B zmY&KZ^($7tB4PDlmI6I`j6D&!)@mvRL`+@UY`k5MrJCNa)^*F5v<@a=0=*qRIlG$haPvk%Sm&`vwv+cB*VV;c!mgUnc|x=}Xl z7#VA`MGMVs)%Tp#`zljWayO~J?7s6rg&%Ei9**3^kQipL@!_+FTDvx10c})_Ja!h2 zHkh-16jW-LQ#?d(``rnN)BP9@HE9#M3Bg@Zkgx-AH6iJaJVwwk|0=Kvjo(%_J|Hkz zH>01CMu|)CZcG8_U=zBFmUA{7NgLSwivEU&e&Q;VU(F<8!Zsn`h*Pah2t>#)UYa1+ z&O<-NLH)$Qww`4qtP4I0`mS!Q4R1ow2hv7+9XdXGo1uG!=i5IP{Wb!Xni?u-xYj97 z{aj&$Mxx@JDHlvUf=C$Igc@EKoa7E0rIGh~c1z7v&5KdiUX$MOt7}#aUBfNA((q^t z#Q}r-kM9CqRE%su4L|B+HDfUav~c>%(#N}R+%*jN*yEx{Vsd6p`h;OZcX^G3l=vM9 zIU^}tXG3$5bb(E1pz)ZmYhKMV3hxyDg7!wWJ;{WM&{1E91|67`zfxnzt*l9b8(Jok zuzD~dC?=?`s>IHx3M4Ezv3BIx8-fA{2Kzo30};z|j5n@zkNO;+fxHF{y2V@;*xI14>cm$EfHw!S zR97Kk|ANzmcutKd9+jXS7r)C$aneC_=~MJh!*hOz@7tuoFu9Iuq){&`u+yk@{}kUv zv#&|T#I_mJ)O_68od%)?(mnL&l&LUxJpIaSAG43!`d#dOlZ4fS(+GEd2ShCI-&t0k z;jrhy8egBvb+_J;FtXDKXRcs4;z&CX^Lws|%-|mzv$o8d_%$CvJiAU<4?2!rvOepn zeIQ?EO^f*FY58kO7};@zqpcKiEE;ZpBiC?qp2p5D9xeM#ZigVgwDp?%b>tt0Op46P z{^7P|PTN5n6&HoxWhvWr^Ps2qlMq$G?X9Z#bTW--Gq z$8`=X37sTyHCpG|813rQ!&^w2sL*CCjm{ZUpnVuqfO5h^ItY%+UlYZCo5(6W-tg3C z?Sr+$Ntm#Wmc1@(HHQTvGGy)4r|7PGzT@WP^w<#&@+7P=8ZGFMR#a}YL2LfnTP|@2 z9mXbnBVi3>wCL$gF*Sv%8>S(YYJFEC(5Cto2_yTC@O+iz^@uu8UlqCcY@u2SOT9&UA%z7>ifp1}<3 zLBrc$cLqf=x;(n$^*hHQYzl*fk$tD(bv;D&$RxS9ay|hf`o~BaQ6W5^z`g-GTmSxqvhnLneXmCXTFn(AARXV z&-BdHKV2|iN+-=$?b~(GN5#k{+wk>Pin#PXYY^L9H~mz8s4IK@Qd;7=m5iBwl2l9H$U=KnnA*Z zZLWwGGu31=z?EuFB#dk_!W+qvj2#5>(kF7WvEg?lC-<9&*}yxC1U4J7(SDIM<3-=L zuIZZYdN_6~$!wtGZ6CM3gQ~9BL(3a>$9;BwZA!u#o!Nkhi}ya7yX2 zwZRvYBE5AVAAwiU!ZyHFaZL2wc=}28_tRTPexBx&Ny3^m9DlXC z@~4jIfIk%@n@YWuKk-)&SbaZnL=5H5t6oHICVb!9c@-()Iwd7n8#9^X*)GAx#3?b^ zBXG;2&Vw$H%%l_@wM^A<{R-OU-1*A;V;>qn8B4+%otc0L>M)mtiE89RIwe4qc?L7A zFGYVpW6s;mrBC>nI@M?I$;T;oNf>$LQs=p2n2s7%Pt#FAn|gVGgpvKG&QkDH8vaIX znCTCEV$UI6Qo-x-Hq5=)K1A+0UHKlspvy5_J*N~+9SJ;uiH?7iJ$3mQlgKt7*0-4X zhj?ehBUDzY{qDw}@r=;gq!O2Fak5g4gf%+P0TGPHDTADRXBor?^?Coi*hhtgkv&H^ z0Zm672fmbyI~{SIk@HadQ>@v`-VnP@SbwlgN}yxE+uBm4izf6VSt^R!p1#vaSOfVE zZlw4dQ{-r@ItWb>-}{8V=$uxvN-x!>Po^(}4f)ZQAMIsooWERW_trhXhCI$~3EHTb zD2-?);xpes|4eD#bp7219R@gW&%aZXHenbM&)Yerq2y7*BM+`~;-#H<7!myVw!lWT z-R)4i+s=DhJLmQdw!dngh$#Ra2qH+2(ceI^Htkw&6xR>ynC{=KN$+1ItR9R=pxZfF zrN-n~tJ^t2L|V_bB{K$eGETG59~qG)rbWWYMwHZ)dE}~E`}-f;Cwp14!BvZ`(UO_* zTunE72OE1wJlpVhHM7CuEo*9+z`2#7y8G)>{S5ZLY&|IM@Q*waMmC)~>%cVeH;36w zL+FI}TGk!?n(9V2^=*HvFk}mC$d9I(xoSOq?b@4!2IiIJeZ9K{G*L0K*)*)C>4-x5C6gT#vr{fpp^6Q)7maFkw3olN{@#Rt^Lr+U~GlXt=qp zaqwp8XYvIn+mf&bav=1gJF$_vR*P*%YPq?%IxRM~a&{TXE{bj92*EYASzs=E$uQn_ zoq}$LOP`UuzKn?{VWRM%W{AAU^HrtBN(LI?6P9Gp`l;F$l=7n~Wcl5F9VIu>H<)_J z+ZV|CgC;5_3LiR*$bTDi;)C~n39SgnY0m4lJMeYw4fqcpKd>bHx2K7(*0ktNmrNB% zSQHcxD^+($b@EmyZuFuvv5{u3R<8EeBXQ?f*RZpo?quhVI;AwOZK7L$GAo`LPcLo?M=w7*UF z0!>tmE&@$7#N(FQ&~^(x-PH_ll{WTjnuGy@cxvL>{Q>{R)BQ=KF*etkfN0cR3Echt zxH3EOnWn|a$)ArWeN9{D%-;Rsn^K;lGHTmt$3$KIuYU2TJUrzpSGtq1M%Vp;h;0L$ zEDvj@omMbAb?DQ9!Ocln19gAR(c#em9DP=&YGXiHO|2BTrj|rTB+^gnIC#wo2rvqC zB4MKF@SrCM7-?JaXMT}Zq-@#Rf%C8Q0-5}1Qjq&%J6@ZiJEEgh{GH6?m!OG?iK4?Z zL_Fw2w2f^IR`=F;IAz!Md$XBuIpIgsc6Hf7mU=sOKl8gAve;Mu4``xdQ3%7SIuPpI z;o&UtH#2MC3<>IK%;&3DO&=ejXD=F{s@kplb-;OPYCMKXljUKUVzrsE_<_sZW4P=}#^vN}>X#lQE7U4}bfd|&xFz+BM=F4pl3WLOXU zT`NB5&ez&jTzEpkw^(P_0TLz(6P<>*)n@hr_$wT}|80m#rCsT{!d*ss6(>lTC`=S) zFS>8=Eici{(z>&{GApifVLpO*){`&{hvy>;-C5HoxV3YgBF#ln$aREPfn*9iLVHnR z+22P~>d^gTUt(rTX1HMrP-fV0o}=ZBclYaio9vHC)=D@ub>3hD5>^j}Biv`hK*T-E zxem=4&tD`)1w_O-%$!QX$cEGKH#)YYLrc}I|(D3PQ&Y(jL7HgT=0Fg(L1*>J^YWz^tXa{Iq;>cbY+u` z-gM2VB^@tCE16&O0$o&$Y&;FG3odnBQH-k$)QvDZ+bRPZDOxG8`Lz9U{eha%Jd@262Ok{W+~qW;0CceVyga{n@($!utsMxq+lUoqB0p$!>TEmVLfR0eEQdyBgRT`uYMGU zwd}U~ED38sli_)rYHde2prKu;VMvNzS%ugzugIt40>ep|sLTgOIIYT#m^?O)ZYQ_M zEQUTe=@ZlkFZ1C#I}T?(B6p?*Kp!P+3tWdkmgxE~S7&l=QH$YEkJP3eCK|jPWnFag zkb+%CUrYh$NWce5uh8G}L7hLH)emmBv$7z%qO)u~32SuD1R}0GyPmRPyc}__r{dQ8 z7p9#iVPt2rgR()1y~zF|tWT~hSnHvD=UX|r*fLA{?-I^{W8%jGp)+iPmN@Dxe%9{Y z?Bt*i{5|3bTFxFVS=V2;h2e>BAGSG^Iuw#HvO@_^pC#hC(%4fa-Q-Djiumu~-oJY= zhu*weG}?t3n5PvUS#)AV#5nxO3Vq(fsR;B@F|tz$PhWc^#P#@kQ-;o~MITMCdMTzk zo&)~;=zCm|*wss4TsNa*sc%2?BxTS?#iAfHR$>MYbGc6XfEqP%#N=GGR>rbprj>Tr zuanm&c}HA-;SD?Rqv`aK1zUI092K115)-b?{J4c#XB3QlExBPeSt0&c!$S`!(3dNW zUw$d5olVy7nly>L^XLN%QNnJ+weyfeRl~LOh(X@!`?^Mqw95(c|3%^=(GEgp;sF*Li@5(!ja#KFwP(LKwFv-kDdXO2WvU zN5fA9wM5nZXzAHI&6as{tacrY}GklLDO~JNm!$ECJ^zqa&&+5 zN#FG%D^Gq|ul4u~2_rjGow`^ESiXm~E78X9r_M1t?zdVaaL?9VAFmwngA8hNDA4lj zd>8XhI+2>YKRfA7d*Za5gpnOec=}c$o@()vZW~>pX&j$Dc$`n%%oY6VtL!=C!}Irg zCLVw8&Aonf({a#8#mEjOJblAZMV%K56~Ekef@Y4+gTZgwcI?NmKK~(IbR0XD8oH-< zY~8t=-y6_J#Y8czU5b={&}a(Uw~~F_E@K@o?)?8!9?r3P1-BYs=8`&hBAe<88ary*4DD zKYDcLbrRO-Iu8(GQaY&T^v~)B2L>(Dn0dDQWfDg2JcRpu)$xdH$@OuAL$lxNZHnrg z?CoZ5il7=h5YTgWN=)SD-|@zWq_^G(zyC^tgpoTC;c7gHxUT*@c=2R~&l(xpcHgd6 zUQ*##KG3Z-0r4?+0TFKnEMtTeO@wH<1>Y@IgOjG5yrBk4@A`Sfev2 z5JCM>BN9e7DB(QZdRe0zJei%={gU?nwecB!r#&`-jcOXdgCeaDv;^yG2N*d~*L@s5 z|JX&s$ktS6mC!=C{&X&IhXiw()E`a=W)VK`}*gPz?O9LtE*I86JO)F z@|c*8JrCX_SrYuLk!AF`LidkuhP&6u`(By$S(Ah{I!gi(t>5@eo+Gu8cKCvpZ?8j} ze~>V;B?-5$g`4+gndvTj*lnv`c&{scQp_q7_6ciu9BFQ}_w~}rRyVcNJBGObsvPA&*amBsBvKyflj3pyYrdO4uE^j+t`1^Dro9^i-|D z26b9)DB}%%e#Cn_i~Tk-p8l8u(7|J-aX?ayk&UU&+Bk+u9RJ`N;}|p9pt@Y$^2%W?edB$qd3N!|MeAWFp3N54 zgCgpfiG-1@sm?0-8Z+HM99spdMA|(s&`)~NIyJIXCJ4CyZ&;FZYaW)Aiw0BzTT*lD zrA`OaLUi_~7KA1CbAL>-BzT}AFL~_Lx9z>@k&;~(JS>t~M8bq^Nl>pi)yk4Ugzht! z#qDIj8t!(srw^}`@gZTNw4^VH*PJ^`L0K&5!Z%>NiZn zFAQqAL8{$X5++JZx_~$qICdB+V}DUIJhl9z%fikz&Yp>Ul*IRI^DL!!SW>N?hEPq) zlKrB%S^vng+|wmyYcfcd1i{hDAuJFlefYuK65r*ENJa!5mrGK_c7F*g zdhm`@FZz@znUOGI8xeGzIMr%w1R{QZ??i0nCr_6SfFi{%OUc|9BMg%&3 zkL)zsRO7p$-?#qm_aawBkT6ji5u7evy)&{)n%4yF<87K%=pBE3V;rsj`49w&!AOZZF#tF( z%_27_Ibetqb_cE#+wevnuD80{t0`93+m3ZPE!BY{ZXB>MRndq++75 zD&P(Ytg6w?BFO=BlxnmjX;isfEeY=C7TA)K$1eReq~IkjVoUm)8E;F{F$JK5ueE(f z%if8hab|I@hI^wfRIIlU_aR}8&XPdHt7e1$9BOmK_*l0CI|>Hfp_4FCT2eIPxM+0L z*WMPAI(vuzuubl`<1m71Y^`U2i>%FUz_U1C)^=f7?d^jw2y=d+rn_S z1@&92(>@SEJ?$f5qO>r7#BuPB-s(>~*c%^KE^Br9$opgv%qyT_J?Nk|5E9lv7RJ{^ zILT~)J3rc}r+A=^iiyIw@M#}hkt3bNM>vuU3Z@UJV=NLTY=c6ys#2{C3Pe!HSR_o81{I4q)@Fghm?*7^G#d!o z;2JDx?8Qs7IqZni!oOctpH0L(VKroe{wY5-AJAN#LE-Y&mCff>v)V~_n!84(U9C7flR9-ra74bw%id_ij22!m?n^8*iqbdnZ_$6rL^wPo&_%67Tn@|)C?Bvr zwLD4K3S!wPDXVI0X^qy@Qd3t`R#hFPsi{a;RoB*37^S48qO79MESnk3Lkh8MrshAN zwD@DVPQbAp{wv267h}nSl#R$cFgX@$?08%|Fn6>e*ZEBM&$W2C$@kS=3xhGMwKCLi z_7Z!dT05QCz}?KFkyFKz!9ffbzmSuymCnFzOqf) z`@3xUbUnnoDGBR>kAl9d`=~k@0OZJ*0qjE?-k037IQr`_!{|2mdo1Z;I0ANthR&<8 zgAQ%!PA?w1pU}@N()I1Ms)-Z{BX?wV*2Xcs=J*H5L*nSJA0jDH10TDVw3@A*peAE$ z+oYE-Y{ZYsY}$JhsiLj4;I<00-b-ii1C>;a+_lwNC0{l83W>;%J-M*MX}WRR8U5YP z-&5Rb(k60C;(LBFNtTBtm7<&H1U~)$`s`Ro8=tS5VWopcD!_i@UX5vL zyMi7x*F1ZzUxhdcYjlNUdI11#YAaD9*EEVHTP#^oGoIcmOXs7ODk$m zP1;0mME1ZCCF}xR$3_*X=D3cHyf<|fBc6UT zsk02%-_r1}ygK%`!#jAVaE%QXw4CW+y-lLS7QKudN&f^XkFz922Dy+$}3L1zwoJv;Oi}C#e6K zCM-a6NL&pfx;qbpa7LF|1vZGR^|v0$XurI_dHD1Voy4c8vKs`R{ricucwITG-Z1&&J>NhjY15<@*(6MbR3BohEEI>*6G0|oNwhd(Oc!x$)79|#+<|*_g46rW ziZXTOYd{7370m6I*lKs%vCK?5@`AI^Hxj0Tw!^8qKB$_&81PoiZ!DGrWc^d4CWx`z z4)Pnf=Pi}M%0j$L+R(RI*7#Wq1^tW-t2Nu4~I zt0sILZrlN1%-Xx|*Kr=9dXQknTQAl(x_w(7CSZ$D)zU`kv0(QfvxZn6kj$Mb6R5##Rn}+t|BU&2zA|k+X8Nky~!>;DFY+ z%FVNtv$k?T@Q7CQrB-%wPV?u>IomtB$hkVn&2zJNu#ubZ=4kC|@8oFZVDGwegy8+o z_<^%~&+bZj&fTjW*n6V%1*<$s5?0HGgewvb$xjj}7=fprO{{lsi(uVDM*XDZa@v=Xuz#^3 z0ndJAA5}hPzt#_-75kK&*PTGZG^qyG7wu@`y1;g+hPA8H(pJn*Ig@z{ZLMA9Cfm-p zU25xSZ7bG;`TyJ|&Po0Df74 zfB^+&#q5!RZ31dv!|7AfrC-f7l0vkm4DZoK-D%=eNy1dv1{|>#%xtZl z9Bo`$={Pu9xz_QzK4i>uo*6cPRFgk&oyD;1%wrY<-jgTrEQaH?%&BW>fAY7r9Ul03 z*PKjJbOYbhOLAI|Fw7e_w>{+RtQm-wlz6u?V;q_m_;^s}y+tRskucE2>KfQa{SB)LW&(!( z)Hib4I+&3$e)&@EY^$YE2)ycvYcnvd{PTzF$kr5fHvV251I20-?lk;s}}6Xp6U#UKj3=_0d1s z@qUPnPf9Rs$g6mn>(K^zdn2rl_w1~DWa7@dmSSgqgC;5_ie?alc=#5i?7Q|-Q$Owc z%I3|74B=Z-c>7rlTA>H(&w&+u)ABCMMpqan>{EP{`~B)Q5+;f!tcbWtpWgOp;a4leWBTtq+kYE% z3^?6zYS=jVxnlm%Mg!mLHi7(B46pJdyE|XWktWsHEC+c z>TdBIYG2p^rBWyeQqo|7|DFBBVf}`+t1@fLGpuV)_z+ARz#CyOkhRfj(lG&h#v=Nk z=~)-n;T}_zNV9T+Tds-8S23^oTH0*wO_$0G_uSF(d``&#E7jwc0rgbsdMD zDcz2kCvexXvbI9=xyDwmwoC1;9K^s>A)RN@WZrHE0CScZz2rj7(B5USt*e>!0^7w_ zOq6ar-^$Iwm1B7>YxldXZ#+jWCJuR_w1~ChKLw5JcOh$o$iLhFJw95Vgv$wjd=-*3 zYeO6e_?if=bB>KTK(uBJb1mUxB&E>sAc(ms=EyZ#yjgn-94+5hs+`N!5#O%%acU6l z$A*PtZz0KYTBCmfZ5=`!nr?SCc({fx3c!czBY;V|9^X5uH)IHUp!7p z-O+&s9?$;jtSN5kkU=||>8%v1FA;>v0XJL@%}}{S&Ap^NYKA`}STba{_8^0~Bn-w$ zI8}|^>vmeesu7$k^PA(8Gy-kmS8Sabs&h=f!~HAqn+l6fVJp~?v@?Ol^+jR=M87_TB z?)ow&9yaAi)8T%-mM+&jcdlH;{XiFE_x7NPighN|6ZIjiX@ZV`s@42m;?Oh$VS8+@ zY)aDIl1#I0zcHY2z;4)#A5E3Nnsv3*w)?E)wJNPpreh1xM8%qmNRy)Fwu^FlYO_COAjLF;(X%g2EHSwOQx-W9Ej-v3_#n<*YqCnFp+Xbhq}-8V%)u5^ivMmBA$JII9w&_^bV~&c6c= z*|8@MFM*Sjur`7DHw`@RM9n@Lo;+nP^9%#1u+d@PpScYDXHJvV8>m0ZDeFRqWUKfI z0VHe!+n&PGG#PR0Bs0y{T4R>Zf(|ZWtJh2!2Q+wT0?WhYU*{5M793VyKe-91^+Odx zs=4)Z9an8dCqUfi3DHV{edB>EMtj6F>0?u9}UGHP}00UMKpvfpc`8o}d-@Wy10K(IlSs z%>9wcoWs+mK8p97e6b~HqGEVF0C@^a(;RfHk8(z>$Ln_8sNA_S(7|>1DmXqbP0$zP zn5uIW!GRj>xT+q{SbdoVQ731mp|c3C&MJqBSzu>vJ41Z*di_xeAEs^Czi_~+wIpYi zK*Xmx=u15@n$+^tg0%1xWkXt%Fi|+`V8pGo+a+Z^jVqTn_>~7{*XnKdgu#HOGHCDW!eUKuO( zRi#afFa#C#?-ZG9KrGTE~(wc!~t4YE8svtJ$`!8WG@K zYx?HUWR7x5+FP_YNN>~Qq7A(wHN~%8gACvR><6J{3jBwrH<_ZKc`;8*zwMrx<3DX6 zVUlc_RBIwm6|!wvH%%!hr+!DH+W(=cu1}Zjlvyyzm^qaQ2Vg%4yC!f}98)A`6)1|B z2f?*j=lWyjhRd428XdW68wVK7S^5uU&8p*dbjet zEzdO5FVoCodVY5jcutyn!Rxo6(>>HV=?*w(+M)$BTL*M6EV_bWZ0oY1;b)`&m#$y% zI%}%OzI_Wb-0Rl2qnP2^x96gG61ZA<&9ej$2ag_ zmsixf*BTvK*v&=Xt}b!cBVlp45YXP$eFn8D7Yf>xIk@1gF<(antcX6Fqj=<(@iFHc zjJwIL@Yvwhdz2{qo& z*rD0Jm5O1HAp-j{u~UTd#)-X6V2u5n>dSBwGBcq!6N+iMEk(~JxXS6-+S@HacOtW7 zo@W)*|J{f1x2RP(&)5qaLs_%Rn|7#ttM8t5%US1SlO{ta%wDq+cH~FX#22#bml%ec zc62n3UpY%D05nmtUTiF?HBlX2pvRopN~tPy4o!#97Cna#k7}x$tNNojYx}a6-)GjO z3G57)f1OL5$q*~AvsPwqynLe`uZwME6)uh`?!F=LNG(YI^^`XAvo*Fbx-T?LSh)rt z0%``g{+8(Q74m_Kon&_E9Fi_J+WtcM2MKF{*3S|SY^oARR1HO2y!r7+N6$~fC}a1e za+Uqt2EdlEBWY)x3-BNAa9A(L=8k^mlqY&WTD|^A!tfb0>{s1V>Ku!h2L9&I1n-gQ zImm?O@W+G}GV|n>@Zrl(!iM~4dbITHoo36tH9U>wE>E+wwg*jAERn5Xsx{U5S`pTQ zzd1C$Mrdi^+<2entr#JU+Y|51D^rCHd1->ykITQ#CC=20mDgD-GdDa;#beoE)&(Iv zY-K(+gEzvUC2J$W$FjRvgFAu8vab(ZElM@%WwIf#^U~pd59|dV%Mzz#p!RTLcMXiO ze^bY@9q~%Isn%?PlN)-|ftHh_tG%Nedfb*3p8q$P{aZ@-PUM!j(BM>b%2HHPxY(bu zBI7@|2M5+RWc3;4>$y&?9_)FU^4d5HBB4Z15R`bOx z;Lf>$K?8rkG~G?x`RS~|Lq?DnYz^!2Ht;_+0skkC&)>&tJZiRPjCjkXQySRzpq zbqXh6kRc{p%>z?r;)uN&Xp48x+~>chJ3jA!U{vBet5gHn3U(yz4C~<34!4s!w+!Y% zaD>)RZa6mT91TovxK`?156s-&unHBQOrPfG3DqsNenK^i6;cA9OdkyWw(@AiL5-Zm zc?Yc$lYR?)W>n{{ntEo0-tzJ{!IgV6x5aW=OPyR?^XRrnO97Ux&)UwNEg!TV0ES>5%2p0x#B;FB-QcXpaH!^Y`^9&1&4AxugR zGl#;3wl8`A6T+V7T|+czeMcl^G-q zUj=~-s!vp?Exms41zwA|6(987ZDny>d+!iyugt-WOK^OCG;Mb9*<8_vrk%OB{iac_ zP1}PeDuyRQI5pLIbOhP4CuVWs^9KvyQSRUW;qz;T335wM+;~}J1{?20cyhi}8w0Nd zqmYN;wlSrtd_5%ty6$U+8(kP%L_3miFn;vTU9CwNGcy*e>iVnmRVa3yuw0cj{DY{~ z7<=MPpQ#*qdr)`3ho1hBeOU*AI~Cgn8L?8;0qXX%eKU_qqu< zP-LSC5Jv)CKU!%dKkVCt5!WhI_2G{9AtdZAZWL(mhSrMt!o3{%6XxuHFFk~@DOqai z=RwRLxZq3E_{%aY3!mpO;&xwZ7nd_O3^Y-(G9hZhhgyVqBp75bJG&=RH#xD#sdeWL zjDZUAL4S6WyfPOWxH3Yo9iKYGr@$3(C=2-GmOz(LY2bM;eS@PiKKhiuy9NO zWhAWngBwvgeJhtR8G6Iu*h>$I)_r$ZfDV2%-CgG>ZN5XCw%5>jg=@64GULLJ|oqKhMefiNOYikv$HDM?t z{FJZwt&tDxKob=U!v{inR@YO*YJvcquHHR2=w~P6pu-EJ#4H`Y^Q)=Xa)q`xG>g~# znZ3ie*zc4iXrf|~BB-aaNI>6i#RmO#R6F;1BX%I6Rqs~(Y6=;8YxjA2kg=NXf?WeY z?`#K}sMvJAHNjD()acr8ilLHRfndTXdl&qoFQc3kCa*?5RV7zJOX4M z1dqh(JoaMdhQ~T}9^Ei=!=sP-;fDM7`pFIVp!Jg*?z`$IH{3haPj1+k>+D+0I>nAy zKe=Hqs-N7j3y^Z-XpJ?sd!|w$o$#+>Sr_J1ixd7*bYHo^r|s(s-Nt&9zcJo7`$m&< zFCNUo$A^N#_gb_;1)*gTcd_G?l{!AB{5!@rQRq#=L~+^z#Zz2S%2^kAp!qX`Rwq`Cx)B&cW7SJ<&Ei45*Ea^Z*|vS=W97^xiS|yhBM)a z+p{hw=nlV^GPXP%)+thI9z4y&mnOMK7T0_vzv~3tjn-3jOOXXlR1DiYla+Ut*?KAB-eq7(2s(58qE-O-~U%=n^`6AtT%?nPJ4@;xAh~H^K z!j7 zhXb=8oc$nxV-0m?%{&P89b?QM<#G&UtAC~ zyThgmlWp@%xBF#T&&3%5C0ttV&_dhYot^j23S`7fMl>&!yYiKU2{W>RA0*(2c`^aY z2elrA@vb+n_lHWO03F1tvHx6$a7WAquD&(1M>jR6_d3z0>A~$ZhyKmjs}B!oNN-{z zVQ`fMr>aIQ=EOqTbH-aSzqzj9*sA)UD&qkNUZF*OgB{>-P&PUMaU|e>MKP{2P&dNt zaOZ```pnsBOTrGYHMeR_b?y)$R|V$N5(-tcICMQnaOuh>8@=h8QA;{ridHhe#@Eel zprKXS5tGNp(e30GnZ?lOCVe7d)7c6~n7UpfUF|{*LsIn0D#V6)MLr!D7!D->bl4~X zRF$Bxa6Qzygsz2(B*GQN%TRm5YUc=f1ydaGF!a9gApu$E6AdUq5U5~FfW$3(G^wIRHmtvaZ zITA+vp>VM}-^c&%pmVEr|PEv%}+(N>GI{AhG1GuNh&gvOHs_m~GI9ZlRyzvv~mK9#7q%hwH)gW|?b zp#vh`CMoY)o0+e)j+zZgf75m;jf9D!DZoRB>zA$Qv|>$$*1q`<11<91?*MmRp#tlH zztW98VQ-om==xhNUy`ikK__82q+p-w=1rYl66iOlAuDR)2>%SkZ9;!<^~jPDhC#!x z#D+#3V?HOqOB1ZaTcFq_bTr&ztuR7?d8;*i9XB6N!bH&sh9YiF z&&MoK6<=wPGO9AJl3)W%2|6cfSV@bmiRtuL;;x)!sK(kl^ zhkuvBzwXFB@zC5i`l*9Nu7K<9=qs9yUuBdg%o!>L&8K6{?Ulr zmBIdtuKn@W2wAPy2Ao+Ub|SD=OD9E@8472IEgZ z^@#|Z=J!XRgb6eJaVL|BxJ}UTKIJv9LVJ6jDSh{@{rezH0B`nw*wyaMyXgDhRqHOl z?#*bxAw=MhTLNA8(*o8mHoSdLPNpKg+~nOg5{4&4AfM`HK^;3VZ$w}}6npWqDlotN|V*4D(3JfTFNH7)4Owp})_%#h}CUAJlAD?1=RPV=- zZZl$z%O8EA&mNxmK8)^&#>Nd+bM6@X8_mq$mALv;@?{b>6w^fC+^drL>?GTkRr9Ru z7_Vgx4};rcyk87_n%qN{ejuvo$@31G@LsPP!xQ*BcRJQIM$h_v+OvIe5i;xFlCaUN zDu6tzHPv}A02NFeuE231!C~1B&BWM0fa^}>wT|EPMwHK4)IKwIZVP6eP%&cjYC?7H z`h7{w3`8{3_H9WZz4KbDChd0gkJ%Ms5t$3x4(cfYlIGh^P8Ey?Cbg zr*d`+M#SQ|(`;%gcvuho$6x5%qk#VL#s0A;;})9~m6Nc4wJ`wK2U_<(9ikib^|7Y~ z9PH|oPQu8IfmA0@DpiR+45~mL3mgWei8eg1qkK+^o_NasvDqHUsdt$V*doeY8~6rR z=JnPX(B&wB8-sj7AG6`+@&-r7{hZ*|-eC%RDd3)=CsLt)vnX)*l5|b~r3&2!Ez-V5 z!bH^=CiObhX@y1wBkjITp27})vd^GhU56pg_c%6Gv9sUB(L40e_OVs!m5w#LT`HVEDrOnLPT zNs_f_4AFxh&urcEi%Cu%&EksO{b!`c&tzCvgWa=hkv#LyEb0{0BlXB@aUfRW(R zOs8behKhyOq{h%275s@_@4e$RBW5W|%|5*6T$`38jNBMV<5LLLs>FWCDv-wlN0&SW zWtB8fD|DFlAlik6g}dVIWKY4qa0HH{P%;GmN#C4T1=G8lPoOCVUyn8!PQw1x#sFNu zk9eydVdO89Xe^f0Vqf$AB#hh`NOi(dKy|7U7^iA@`DZoPRc*WOe0;>D<{cWMXOKpx z1zaaQbAQyLF}MwE@nN0GfeU2;=0U65^*zE~3V4_#hYG%@xqSLL4a3Yk*Ye#e4aXFug}{R5+v+j zZ4AKm{K|750vMehmxLY2In#5k3kefuW5DsU0F}Ml|6}h>;9~mz|M5f#A<8agCtE6% zwP~4VrlwN%wNQy9WGC%u)uPfuds-=_w93AO60%daLR82a{^!-Zn`z$XUN!H=`24@W z^Dw&eJa_JWK415FUgz9BD#~v#?XBURx{V?EhH`^po52164mTyiskWgVED)7e>|@AN zH6B@B8qaq7UQuh+dQZ#V{54|jt$mTW#xoeHsQ4J$v!mMS%Tgbvq}%x0Ji%fAON|Hk z*J}BVt<;!T_(*AYU^pu%4~Oxw@hCQ4Q1*`tI1g?igvvPZ1K_&T`s)5%)osbcFN-Hn zNjmu&hyBUM1Dv5iV-TLPV*3(};KkoldgeIT?bZRDN|PPTfJ!SGgArw8_{u|1Qaxvn z<_?yee_YY-gUQ0{x8fSZ5Tt^;G2pQOrN#jKxf=rx<6~p^=NbsEYn=bF1hsKs9^lH| z7;u;%8Uyqsf1oi?_6*^?G={6eE}7kF<7*zL3nva9Gv*wwF$~2t1|0Uk)EIz2cVoa| zd~6H~|D|UDuH20QhY6xFKz9EFjUnYb#Zw&0(BocPy~FLIqxktv=nrlG?zDpIQ|r#+ z8pALYcB}BHlsYPzsC^P6{Uqu`yh{muRaWm8kTGB2Gb3SBF1UGzO z8dre7)Y-FXU-swl-o4rV~5 z6~m_jbOw}kN8AW4tJRHUvByibIZ~rpQP*ukJ|C|gh-)OnQINSC2@d;TY9zp)yOH29 zJ~R@v=ElC_pYz%1YeQ*vv@HlhyfhNfz}+Blm>?R78RF*p(y#aYQU#iGk;98xpBa-t zIRpegxH1xAgv!4z>L}*rx{X@7%O_Mtm1s#Bp97t*)c{})4aP~PXf|Z5rlf+A2}`YdPw`h^w{+m zoW6cf`;NniN4lVg4xp>7(MMZBcl|1p8_zDl`;TabdCum!+@Y zY`IESbDPOZSu6DL{my8%CKyd4qWpbuz*wa7qtkqbvgjbK@T(?^P8I)L*|1tzHB68c zh=t>|dbe*m)-3PMcX~|B5N$W5p93djqBH;1DuUfB3joYcn}n4Au2dAs_AB#u@LF_ z^mN|CQ5z4@?IqMoQiqb!$Y4|nQqav>$tMVr89|_ahM(VHdaN8 z(luUZ0uG124dJi^V7;lVH3|(VZ;XYx35o?op`oHFg6KdtS4{pz??1%^E~;HV{qlpp zEFpIOK3l1t{}2|Yz&YPbKr#|&DY)2(5>f~JS_$=%4P_+a`QnF;?Ma#l-B4>< zwxf=dFAn2FuZD|Ivle|2%@J*DATd%c)p)v2rv2m1of_Vz3qQpDxKWZ2@LyP2SIlB* zdAY>K+B%)xl8nRPxfewFm59t5AcBxv z@jFZV=sxoDG+eRIS^Go7Kp7UnL5%oq(_c`sFV<~kfZ90~=7()Axu!XXaaglHyCeGf zKYjKuR?X=Bx6TU3x0%>QX#Iors%Ne18N)vQY=?oIspu|H)Dp2rD+Wc((0OrmM?c%R z6KlS11hL$hK_i2PM8qK$25-1W@9;@3NPRd}Hu__x25(_vhI5yMyZnvz1jRxu9aLjr)+H#MxL2|%IzOPz)E z1T+8WNm~2MrVQ=IzIOp;YKgiygP*r&uar?cyecN~^x${nK^-^tS0w-j61KM|UA}7Q z8qJhVSsi`GRljPf*z*R9EP5E{YlXh>I(<=;I5UU zTDG2flvM#Z)wU%~48^GPCmk6`pry8YWS}xKevGk3srka=Ka%QhhhM}chS7*?S^q*M z2JLF0om=(36J}TaahMcO@7Z^{wVPOn*CnzHZ!7%HJWvlx7S6dAD?vYdd9(V`WQKqC zG930-C5GdOv@=3Q}TI*8@Q{*uH1 zlAs`l4WEWDT>p_K097=iAx!|qyxdqiqT))Tow0*DpHZnP6!es13AR?t@*34 z5V7g(_yMk49^MR@io*nv0M?_>b$dB#@mdLG?Ze&Wx?3Ln`U0X!6<(+Z{w8BfT~pJZ zYP&c*vpOAWGz5nUHUYrqOL@ze8AUkyVUkhdHZhk z+1z2EjvM={62KEg@Wsib`ET-usOGyJnOwg?0Sy_ zZtVXL3BU-oNzw#R!%G5~xNUlDPym{mD3q+qBA!E5(U5@I@L1fP;v zvHS-P<3j=fO-*|QO%sI7X6iO0G|YNQyH{^-Gu_Mw<+@Z|X?XiFECN1c1(a|<7Y>L0 zRS7@}k>-8^83=5NSnj8Tfmm+rFG&C(2MX@tYJgM8B^?=r^KxTmdyx)XA74+Py9}iN z_?G>>+3RnJ&L4Ni1cwQt?Zc61?z2|Eiy+hk|BFI_B3HW2R69w3H2QTnsbM%wux1j!dQ*b<)#!&?Brq4e*nxyNc`l$04o~XMD=nd@|O~Vb=CG|E!pU!vv84wjgc; zdT0b^EHqHd%&3>LneQ9_yYNCi@K@@<`r)xdM>ns+NI_j^k~Iz!YyyBs-A#F|r(z{4 zt$N&E+Vkw@F)iA+0VQruhq^v;yrk=UETlB)f$&)z_E#l<7({yfw(jkMObeNT_B(<{ zTa74#O@(06mIC!4Y^{gen2Hb^Ew>1z(PA^d-Ns>mNdf>lP~b8Lr&R}B7c<3cWpb6h z2JANY3^h+oD5dprocic-q#d>ojw^ z*50woh@OJO{;CAvk4TRa^H;sdd2>>x`DDY(Gv!%hYPw196hdWp16b={V{fuEjFN(zA&C4!>y+vi$cfNOZ{c3Hz z)1{7Jj~U1#E!>F#hY2DvKzG7RVgUZ!i2;WRHZj~m=HVqVfD-P+fW!W(#IPTcPMY51 z&Gb#iOgE;>^r#_T+0cX#-0*>ETmfO+NdSlaWr+b^2CQ;@FY5rqboqf#9aC&FH8y}e zD!HU11|zCt30AzENTB}=5e2Gzo7j+N`T_T8dfqn#KtvAp0*af?O_z@PhA0uJLtVgOA| zdkRexguG_z;0d(697_Nt+{Y4d*k6?xq7dnqasIV;rCA!z3c4y^o@va0s6f2nLsmc- z_pt;V_O~SlM0?G|nH{sgO;<}k_olL@XT7-Z4)Go;57cuEYF?8&Qr$2u@m zEhe8TF_!Ac*-DAC3<`)V_pt;VCWyoUZW0=4CK=pKMa?}rzu(8q#96-!FVq8n?qdl! ztS2nLvHVJQW{n7Ew1~MH{*qRpT3BLJK4_XCe%>rGK#t?(SOO^FK5l@+{;I^_fk-cP z|1|IImwN3JK58rM43E5os6f2nLsmc-_i+OpX3)5h|K+QXz0u7MqzRymmyy9U2olgX-INZ}f@hbS{wq;7uPciev9Qy?jO0YqbXLRu=8`}G|l zmK*y^5&&VSzC6e!9T^n#q(}@kXxPx|(~rGallC}I5N5kiIG|A2anTUY#6a9~rGzBZ zEztZl(JWin`R$a#ZUrGhI4p(Gj5g=5MwH%&axNLRcT*v)Xquz>M6;$d9W8y#jpS?P zJ;Z5#J3nLwc^{#CN_s=LfR+dRSBjYw$Oc$x9^JcR`m#(h102R8f`ES0q^TW$G!d(U zCrHF^-?LY3b)}wvhw9}|yjIvQp@=-=<41iH-S;!vtZa z(I|dmiqm=r_Uojb-RZ8=(QPljKuF2LOIQi`AF6ckACf*y$MbyqX9p#8O>x+tv=U(l zcr?PTj-BU!D*M6O{~~3|;V1slRGOfU)G}7+jz7|2i4`x|XK{Awb0_=W>K?B9pC8(B zx*TU2oa=FzAS{E+7*ydUECc*=$B*qIw(_;c(Nk#}^S`k_3grJ&(iiR>D0dwwZ8F z_i{#oY`R%TrivDoZ?e1k$j)f>oNH?b+r|{T!w+E%&DPSmG{Q>2zpAvjJnyYJE%LL! z^Ob&~SvU-DCH`tsL)^3i=k_sRzV_2FUgUV?yBKBX4AMv~Q{0`(GQ4zHVm7ZYRrDIF z=CNwbHqX$kcAVRfunaDN;xN2r_%lu*?11ZJAcRm)%md$vLRbd)3(4Lde9HQ?maF>r zGSzO9**FYu8UAY0LDZI1U6;34u+8rWbowb=Jz0OXa9EK^>`OYN+0rTg;WbNLiiHUxt2LczD>Whxe$$OIQYHH5?`g%ix+Ll_pBdl%WwW zsb$J|*^}xWR8uzT$ue!9o|~qPz5KuwXBjwFQlxrj)rV12G~yiC?76i;hBypw8UFVB zY{YGW(R!t8H2Yl%`>w@{I%-{@3NK+9-0>eAhPMoVH7OxY+{ewRG*MbcmeMl3Jd$Wj zT}8Htp{v&6*J ztCF;EFV%iu)TzQtSO)m}&6_fLVAnIMZYx)H@%5Wpj>80DnVE=NM(LaD?N~OnG!Mmh z%2vgc&4AJ}R#ZFL`n*`?#h_i=X6;m_M@ELlIQ00i7iSrq1RN#^%iuP1ODqHY-^M2w z_xxe6?I--&?2z=z6*x=~mQh3khEC0NU#K-l{OBT~qb{uRltX$-%Scd-WvqDF$+q!& zu@+qel96@7#_d$6t@b#}%tGNkGW&McbhYmRBhKoE_U!Vh7>D64!{4DI3vt`;esg^Z zquQwAS^5Fj><=gt|9+1N_-j^N_gJEv^KPi_gWS`lW8dL0yk+>S366AsUopdb@rRk3 z2`A4>m8ZUcO{EFyNQb|&RC`QDyjUjf=P~<@nSB`vQS$lyZw!Bdvy3VVZ$*iAXzF4Q zhG)%z8$)LqT*YB6vy5Qh+)H#!z@PgNAP#GpW!gp)v4@H~ObWJu<2B~a422E1zSB-R z8)h5PyL<#3Non}NG|GZJXHiJb! za>Z-n;V*^96>->~v=VTJ!ayIjpF?k68Gl40rT0XUdH&~rd*=kHWeWOISVo^0%Zv$$ z)S0KcA@8woR7}v>{gOD#;0|o#FhN)bckmy={yWRytcJq`VHsR=q|yX+q?VBwLSY%6 zE~2O&a&{GyId*N`bG_V&CYe~vsH6Bt7ice>!N^tmQBdIbxRc5x9EP_H_v4zcp^Lyk zWK-dEX%k2>(d?+O7UH%pX7Z)&tksrJ=Dx_h?{l5xy zbJ*y)bpO_koZFA+b8!-Im>?{J+sstqB`gE{&)O_Io~+qpPiXYe92jQntf8J#yGMa zc{nHawj!y^B*#PQu@lV3PrBg|hqICxVCw zi}vdH4V-yYMap3>!~>$%EOG!g7E;TE52VOGJndnf`66_$SniQ(D5G$7RkvGDIkz9t z8t91U*yY2j9{Nhs4&6KaTJiMa5FCcL%=Si=oJ%HzHvA>6Xg1fcFU>3iJFr3Ky-S%J zgmt60YqY;O>cLu=l`Oo3Wq^Nq^wUQ=aT6J~BaGYarpGMDVR*~%R})yKuhgCR{^RJX z0aJx;4u7@Mlu8rSky^%TFqLJ*dB`%~ZXCT=q}zU;#XXZlR|0yca&AAuGBA$VT6%NB zCG{^WR@*E}eXvKv6o=t0!{70MF5;G0;7`|LRD8U^rl(Y#Up$s7yo6zTO)`~0TiFuaxcd-&`i;#TnTUP(G#I@y=z z?qfLQ{64Di5>~>U7R6zBEAdAYVI|zDW6%VLKNocO*m8lb@Nh_IXr^U+FlDoW-;i3# zis~5|ww-velF0Ji3skaoc7e*Au&kuF_ohOwICW z?uEzoKX8`8xgLk%EyJIdO4tFHF(8D$vkdM;1{Nby0$OH+R~r`2Uro4^Jye>Yj?^-6 z^8%@53V1o~xwU?R;ziZ)h=3t-{!s?-$eiUhn{i;Vr}8 z3lX5ha;*M(?7E(b_v4(^PQ$*X(5S*oWEtEUb{vM!GW^j*xD!t0a$lJMn&3i`iaz1r zS1|(W)=QNocDtR#d-kE+Sy$y{XFY7(gRWmu{}UE%Q*@dpp@y@P4w5jcRLE{;zK}+K zZvS=8cTV`>Fuawxhn#J@V+%X$4?nu6$9t@yxjo(7W7GDE2Q9G@@b5J~TRb`=SaqM& z7fGw#2@yC9ZzcX}f<3R%%cAw?JRGa#-c{rHz~VmnRGOfUH2c_!Qe+>vA+*)Q<*#P< zoX^l}Hx>3__$>=eYxd?KqBY=LkHhem;ZI9NTfCv*G6qyYJuy$ijE(;h*#~z?7!Jc* zhQFF{m(2lvGEGoNY8ibQ3d0<#BYTgS|H{%fJq?_t`SPYg%;q zJ3DtAiIsCZgTwHa;ck&_dqRSR!Xek?v6?ylAKVv;?P$@hc(|Q>9EP_He>4$I z6n7v5Y{5Vu`+lz-dh6VtzIs^FUgaScMu78VrEv5s(y@;$N=>cKK5whvI>_pbS)!CZ zFW`Cdf+U=k^w3(rd7S)OpyntWGr~Gf*kJS;9EP_NZfFVOn+oSDn?Q<*W_wsUXi?WX z>z8*>GndO`Iyk1~EQb4QNyAHIAK))>FhS*}M(DgQi=2}lh&Y?zFuaxcqlvH*T=MmH zVomN)ow1z`n#o7ROgAY4P5OxQ>?rrR3eAe_k`D8t_K5iy01nZF53Z1ArEs)1QY#hk z(vj`zmRM(_XE=4vA!GM_74^}a+m(=plYqknVI|z=hmewmm#`A>H;xIHme84yZ~ASE zThFiYGjQ0Sv=U(l*fo%U7u{b)D=m0@T-sr}@d-ASCa5E|j4WChsby-=FI$~`-ZR9l zwU|Bp7H@U%`Z81fE6y^r(OQGM?z?c4<#0P}Np@)JoaMW47~V4c9Vc`^++sRgev{Wc z@_difzz7k`ul`iwB`gE{+pj+>x`6q)lT44gqycXx<>4^AW%#3sXrgdwz*Kl>(8I9w$eh4h1xrHSk-0A-#CAe%wLYP zk|E-{XS9vYMxBoPLJH>F))%Qt<1oCHxW^9-7juGoqHwN~z^MK<8xze%ONvqN+9QW; zFuKRF`#Cy8rcgedkFXN(-#EOq#Gd|n^rFPES?644jKpDhEAdAYIsw&CWDz&%c|(t% zr)g*2z8+)$@ZzR8s2GCqijT29JF1<&EcIbZx{bfh6TpX(;DbqU1h?LL-so4PSnn}kA2uXFy^4OD(DL@e92ZAGFf$gg!Z;wc{ofE))PhCK73w2 z_5k}zxa#NAKE*bf3t@ARg_p1%@K0Hx9ynHWleNN-BKWROpLzF?>@&?s9 z$Eh7$Jh97?Ba!F3qH|e7LeR_>y0I3Q(EX~@=O}wwGzwXWkHID z%+-EICNZ9L&rh5wg^-4mfWrh~CEVt3iIs5K4~GfDO1K^ZG)+REk$a;f%UK&27(JSs z?LqIu`;#>E(Zbr+O0!0ddEZ6tYk#K$NBoBUFj$GR(mZIvQFo*K7_Lw5+6_9SCUX5c z4#Qgsd&&|mv8iybvI(S^Xx1S@R*Jr2TqUIXLEX+z(*C@kcr^SLR=~LuVtGVX0{(9Y z`1=mfoBHBu)q{kGigj{03~wd=YFdTJ>V`>bEzp|fQBnWg)h_3-{E%`M^dmTY8a#&fptTIIIt+j*8IB|FQFPW4WLUn?~7Ex)nm3B=$@V%bh1ROo z0Z;dWrbP(9-RbtoJoVDE_j^cWNiDza132h}53Z1Ar7|ij74u@Hw}pB%E4uL9U4}^^ z{lx6rQP-9QG%zMA)GMO~m)U zJ*Yt2YYx+?U09zBremlyK^>`O`ALTvW_SAC=O@4PZ84Wm^(VD>(ySKlT)@ z)j=cc4s?g#LipjsT?orG@SjUNaa*G{T~f#~S~TXG91d%lW!gp)k$sjT;<5pC`Blu| z<+s0yx(tk!WPlDUz>j*K|3KFfk&eBV^PYa*0dO*{P)BMda0{uGiqRrlZKaEa8;3Z2 z?aewM*+=1cK&2Gtb|s`OK?}}LcI~amic?J&U%0zV4DAsP!&?b=I1fZN70y*QffN(X ztQ3j3%@}k_Ytg>vno;Iyb;Cj{*TZkg!b?~Q_@|{5?y)~6s_peDd~A}0*HavZw-SFe zp>w4T1qOAmr_9;!|0RQ#dHih6oj1M5K?R(CE>t0sU>CWc{pk=e^o{2wQBsQyEH{~N0Xf=r#}cw;#wOH!&{Pj z9MU$K0Kx|amyrM`3ol_w;6M3W^=xx>?bMT}f9B5a;WHeE;VsEuO(}@~q1+cP=VITf zI-F1}iG6&z!L4MPKrg9f!jUUTEu+fI#V18|)m9QYKv&*=%yGRqKGk81bf zk6&EZPL$o4ccb#IAr8Y^W;-ZFg>%XOAdUZ%Ry3RI*Oz8l3_3&)3m1=?uBw`uQ9WE0 zt%ZBQtYqOOECc+5-&;67x;|Vja^8f#m;Ab9;4r*p_^SzCb9-t1XV$_mmvtlWTQGve zjebyRf;v*ml%dl%q?R#4zif5K*FR_V`IHCRTFJv~=bTbD=)$@Eh%B=lh4-o0mlaF5 zpJaOHdKt{pTRa$t3Bodv^t(Msi{9VIospvbAbdxqE_%Su?=1uT4POP^j#Hk*@br&8 zF?^dz0S^0ltJ5fc5kVUWz{3lv>9>kd2(@y*_o$WA#TQlD|)@Q z0vy2&ADHGYq*f9_jfd1qWoR+2wo*R>Y2l<5_H=&D`rVS=zy5aPChajbrmgMn`NtRyQRged?38-%iK9j^XW6LDMJn8Qf`^dGuyC&An>#zGrCk(E^-I zE7Xx%iSmj8RbH+bunHTHtFPH1%kQyM5X)rhMVyt45!WXH2TqRBS|uuBl@>QjWZ*y? zhPM)bhOQ7kD7+5Gf&Uq8)t!a(RFxfPB4Z*RK9a;?cq{Q&Q##_-Zna5WM3g{0JMT;LN|QpETonx=t7ZwYS1EDoqcBdKK3+S|3=f($2?6%#a9MrnH7jI1FzY{*Duhk?7I;WmKN^G-n@Cs_J~@Xl+AFB?~W+eSm-YqDQI2 z=D$@t+$qle?&hoxI1FzY{%U%UG>wrcR==iY#yk<+WzX}q(XefKvy3;DWeQLfT5Xx7 zXY~5Y=ZmPjtxL45`(!;FXPK2~!Su1u^_(457+GU-E4I`>a>ZeI%kZ~F?m?k^@Ve^i z7LhAD0m@N!=I8u0sKQHF2KbBK@H%p~XuOuatILA@^7nmk7~V4c(L{`W5|MxnKOaiY zy_~=}HpBa?_YOHf&=g04BPp%VKJxu2vX3enKepORfjY5P?KL$%b}jjFvUAmzwKyxS zLR?iY44>SQW@6d(rA}C0`%a&57~V?!ZK>vnTiMU2OVS4vYR2wP$QUyJi5`TVEWCu3 zfd9@;SC6PO*)fw(nI+u2yQdQl!&`~JnyL~1O*`5T>yQx1PWig{y0}PRODauJN7`Y@ zQd!2E7t5rXDa&iKAGcR_3QTnFUlD_|j0p}GOH1{ z%DOJ&yIbC6Mfd96^NqgnKC18%mI3}9OjIKC8J{F;9^OeA-Y4cF4ikiB;JtCF3*F2E zGwn6gb7d^k2kY{Fj_fnKs*Q9HOX3?3hXk`T9_Jd+cio+PUM|V?)Mj~{WlT|cho7wc z{6@X+o^!#yLS7jdoyK8!%Wx<6g>8Dm1N>olCATPEf0d@^qOAC}-ghUo#4^A?e$n7g z@73ZY-d+uH&C@sEg~RZc;jgAlB;fo0v3tCSEYOL`k4UWU_#RwDnmM74G|PCSGpD4M zu|>aZb;s2Csea9wQsg_$`95{XUUpfWMgE%)8ERuUHYA zHzcfm=r;<7wahYYqlq}N5sA24?)UJ0GGo5>-VD{%6SR9Z+!S7f@T@C$%}-aUurq|U z^7_6gX*g5}$GG|)_hTLGx{jT6vL??U?U5^jgj|tEgKyU+T+tt_eQ>=`wA8o@w*a?8 zc=zdV?vz%Vszp_faQYFM0@sm{#tiC6Eos%A!jeY3+|zGVS#p1#a5jA}&8%|NwYk_s zj?lT>i=J+FB&R?-Byia4Ee4++;V`@<`8%#yi?})b+}XLGeuR$agrD-^s{`Qe?-VV?YPWrPXxdxQl#D*O4iPs9f%$XLXS3`uFE@$K zI=N@OXrDTnc>?Z)Vm4f1gU|Ij0Xk_jd*04=8h#CM1Y?^q)R9`!h{}>>yqq{;iyaE` ze=WoI@zeGidTodaXUZb>OkjvCr?=wRxE@{T5s4w&ChAOCg~J44NejfSG9s^N^4Kq` zIWmuSyzkKa3WSg>yo4oj!+sq0CoPG(z=i@RPL^$aTd(b0Lv!0|Gbvz?#0sc*gFd)n zJ#JSD<|m5*)R9`uit4IMBVNXCgD0of?PTiS6*aRxV$``S_F|Pai0j?cN54&0_msXg z^>Th?567E0Ob`}>b8|DxCeP?oSE%8!?Z;g2nClOz!b?~T_&=6l9c8edm?m{|@E@%@ z%pZsSNsAFp8hTNOPa7@FqBf}|^*<{%*L*1?Fd;YeSu=dE^WqAYhW*{em&0}}=Dh<= z`A%_~m#1u1%6?GtCc3Z2k)vYLo$fuycA(HnC9<-%oQpi9m6|m0w9Wa$Q*oG}tTf|_ zR{HQTPK0PmQen{*%gKC&^iZ)T_mO)9k)s{In>}p@XnTDD{ z$1+Bq73rymvy3GQ@7SYeGc|JOGxw%5(j!&Ryuo3Du#5@{rM_L|+^h*RwNsyn+&^GG znobp7qGJO7E3Wm{p7b-57IN6q%Rx@66o(1IGH~`}^XEM)GxQ5IQ;d(Mq~z(ZrqTp; zq#ct!db$>=W#EnDt+vd8WQG2AI%l>8nFl$kOtPuKS!O*7uhXgnu8W!CwKBQNUITU; ze8ypT%fOsaIG6kn()d4V1*&iSZL|5C9iJM9=2+|DHl`xPM$0WiX|&kPZ6n~<~ zGP0d{u*{`^yIV_`S<9ts*XDi88HPP=YlS3mUv7@W@Rs3k66f{8Sl}-{p~%38HaqA% zO(RRGf^`{(;Vr{oO~;W1+U&wueX94++oD5Otjtjn@((&-li1j)?`hnjqY7S|G zrZXfsnO67>Y4#~Vks$4`ywM_CZKcU22~S<_O3-aH#|Cz}s49Z9(nhpkKWB@Ntm;wf zUf0}H`tEudfy3}tf(xyna4z{Dr15{!ie_{D`qHe!Dn$60$SuiB5-zY(l_yTkej+y= zW+e+RVI|-{Pb2%4p->ew&$v|dc4C<~4#QiCKbimBM*B5%TV%RMuOz%6HEn*Rw>v zZn(s`T?uKMkhBpm8P3M^-tFznYU-$)D<|(;O=X}VR*}M zC;hfL^-0(PcW)V0cnQk@|A4?VLS`4zX=$asLrbT;{eZ*pmf^3ay@=ZcNxx@{HN{4Z zUS{WDR`a5oN)x4JB&be2@bvna&z{vTyYF39&FM0tzp|NJFwQc#I}30a-ZK1ck+{1u zsKQHF2KckG&3$FuUuhkieMxjl?tlY03~w3!Xd=#Sg&_gBJ3I~`{A2yuEnnB>=(x_3 zI#j#+cqwRw2SbjWeQ=S2uFSb1?}qwjvb1dhhh_yITp`U$@LqD#tYnMsFlzOf=)JW_ zpsm4D?HFYTUEy(Sv8PYBAfBK7Vpv@cy<{G@pD_C4wqaLr7~W$4X@?gVon~VqVZ?33 z#H*)z>Fa5GzcQ@6(^PgvEgWfF2sb84C^6GBfI>Z07sM<1oC%_^SyHOh}yZ zDPQx+SUZPV+uQuJV#B#DGEJbD)H3jJ5K_y?^KwFhHqhKX_@^SvFR0JJ%|!z|a9L?9 z;(B4`(%4!FIbGM(E*tAc#n$66yk+>)f+2iR#L>jJ&a~9WL)z)abq<{TczEBb0&Bfvb9$Yfs1Q3`#74>yi(jaqeG)YhNj8RuKz5R)HB6$7XvwOBD#RMk5OwHWPyrpHM2Y$z4f6_8U zR;oi}aknZ)AslyW<2!`^n9xgEpY}!D?elQk`-ir{r9`ALfI3o(6;oZqox;mlX|_xG z=se*Fw&SL~^={6Kv16qjXmcz(SGUD{`aA7h11t98klm3u3~#aY#x2chUJ%(-NGqD= zXg<+wtQ3QmzRjpabxAf`HBC9H=lD0~@RB3a@DdgS{(V$FE9PgxT1hS$FmxAt$n%a#q)=2=5TITLfTFgcKgR$wutYj(eS;KV0P%r z0Ye-n2rI!}5HE)!f&ZrZ81JLsM{8!UstS=ECv+c&3BpRyJW8!L9r<=>rN&W{ACC14 zTr0p9V5K%Y6seE)PDqF21-u-Jl(jKlUg)%#w!cXA#kf&*x;QJr;l7${z2_zNnxlI} zZq4YSOApxLFuawZJAuNvbCEOuQ9EP_Ne>LF_^MU{}O;AUgeXOV+He-c;+3M_5&}mM6jcTk~-kNjL z-P!MIIkz8?eRdAYsk1Q!?&c|VR%kW1NYVr*w5^+1S zHrHm@5nZ}n#&(AA?Dq}B>mXD+LTyAzzPSrM;JjIPk9AHBchwF@^IP9pEg`baO)YZ6 zMwvku`!?Ll5J9q>-6YEyMzS1tgs&;y6sq&>v09pS;N~8Fle2*+g0amK>PRhI(3c|X z>GN_6<{Qag2QM<7jb_Z-9bvbVsln+d!ooJdb<3pGY7O^Ma%orcYc34b#bGVCFo+#4-rfC?r5z;xu-G?-uJCgb{FW@dgoS~>s6-uemEN3}Yu2R4%k7pG z$6+nEa5KjLNmCl))_GRS=D?ey7;ZhP9-Na-U{h&=I#SEX52Ub60WX$WyEIqzS-mmy zXzlnVLgqzRIkgg&*@Gmc*cJuG7^TrY^GfN7O1)pefiCzar^mRY84HNmYeW{Z0GS@qSX z`|g`(k==W`F4%%h6V#DfMwKed@MIa`>IXOI+8rEsuCR$v5!!VIXBpTm3U@D@8m{en zeV<~lbnisJ!#GS3mf45G#mim0z@OV{I7|?h!8J#)1y7cdr#cQ*@P&sPz1O_Qxn!#v0yb9~>d6TIv-tk4h8Nk!G3j9uyr@I4=hS?nlm8Jtj+yv2UuV z*wuTJPU0+Mk0g|*+PI9c|HMwvNYEN{vU(5>!&`^$z-6?-i$VzUUw= zY2wm3m-Or#hT{+mA|5awXCbwcktBtcczT0&yq9B8?#xO?cHP{Un8>ZnfL0AdGZnG_IlcMccrmfk!Bf1Yax9Dm~;IFFen4GKZqitK` z@aE^TVNN(q5LN=q3|+S|QMS81^O%K7-pFnaRbY=~^qIS{{S32#8`Yd&+VsEBaiu@t zU?ce83aOPSpNmw0QdX-E66`kadqP?FeO|YD9fPHw?hnOfB}c?FqR97Mchv~S!^|SD z;x!jSaF`&h#A{Xp{&8<+AG4wlTGglW)M2K*=V=@!2rES+Zn&%zh;aJ#4qw(kc47rx z*l(R@d~yTW2f?kkQUSWUjr0&@G3xJIZ6%}3Ma?|2N~_JyXGqjbj})tjWP)c+2ot6J#HS$l3cO&kSWI zFD&~0sEgxVDos#FY8m;V6j`PK4UAfyWzzeOXD?(dGJGu>mAlh~t%S=mE=WS+SFu;s zx)PHrE+*M^a$C0%hY7+m{)pS@nhzIKJVUJ z=S{TMoR7l#T3F=6*j4gW3G3i)FmY2);N3U8~lIPo%;n{n9m~F3x130%IvGeGP;?Mnb zFB~Qa%a|c<+)r1d3NK+9;P3sy@$?y6b6Uu@@YSiu2L8lhg0Kvncu*-HZLlk;FU?_% z#DU3cG#*oFqO=UG3(!mcC{jxl{4HeWni` zhv6;5A5BD7Ka9A=9P-jx`JofbX}rndyk+mvV-wKJyU?fFuiF>dnd;2QxVL&Xsg5Op zlWB!I(hke27loCK&|^PZZKZGHE@Uo`s(yzx}~rJ2V#w<{sd194sI{%PLZFZJ3d zeAHIh86J6w!|+z(?_P%j;zqAos~p*X6f^7dyMx_EoH;=iUcySi|K;6-wzMu4>@4RQ zgY)B;kHBGgEAdy;1tdUnW&hFHv;>(Xx0tl2wKw#rG(jDyWeWOGSjGxH_M_F7xts22 zKjk=!nR#x2dH;`lu@8gsMB)7uBGqA7?oMX5!{n@c_SbLWFuY~>`$&UnC|u*Rd-juN z%ZmhU9p;m0ap5>scnQk@|0S_*%;T1QbrQ0#9194$_Zf%bEyEv8L=!!W1mGS9@uso>AF}Lmwj*& zaF`&hgxma7;U%mD{CnH!NAI=VKu`CUd-mv4K_m|QlU72M8j3CYA7>?~C+2CGk>fv7 z%M?>thNp`z7TY{3%bT}fHOwUUX57jC2XU6!hjGi1RyblmL+NLaCAw+4+E?`M z)B1rsc(V*uho#zuhb+@GSJGU3_6BzHG@;%eh5?=}Iwq*axJa#3z{`DM)|V9z>nqu?L(Qibi682ZedV1m;_0_~EmL&7j&_Xa z*E++|T4gv4Z>9B(Dmn97Gqt1@Xf9lYn(eH^1uUyq$S%`hsKih0W_QfQ+haW}9e#-W zF<~X(UmoB(NX%_BGw&L6g-kpBN*so_5`Q&aM%-;hW}cW(ZmOP=Fl&sN?UPqjnxKx< zGG$aZ?ZE4!TRkkc+tFd(o#nQ4|9b~TX1sjMg* zWQ)TDVVQ}D8!yjJ1pXRkcP01Fex)6Yp1fFDBD@}l3Bocd$O10{h6Ntfy;3Np_uSJ( zOc9Mm$eRJwky@sP^27tWHMP~2NmyQ=;I-9D&G(af@1nxmBAjLRqwpq8@9}2(CS#@> z(`9;BFVPfX8Q{;7NzWLd za$7TP`M@wuqdo_57~V4c)s%{Ow%KLsR#XqR3+LsHI#rX$7fuxpQ4f=U;(C2(kRj*x zBZj{RPbm_`+Ow9AOq>QPa!o8RhTabW5EthuMESV`^H^-kDi zg1xpl2yr!CY}_|SRF%0;wxVy<9>-uDCMYZMa&ZOl=YGT#4*Qc!L7HLK01U$dVEI~QEauvq^o}<+NXQ# zIhW?!9gq~Bh09jKi0kg3QoS!_?PPjJ40OyN)=wBg9H9|Cu9r>^3u}E*ByUN-@Pmkhv6;8Uriy1o6>!W0g;cb)dCc> z2S`;s)~3<~b);D-9GxU5wTuKWmeJb&;B|TZd$z6h#qkljFK*&2gOh;61YsH6W~K@+ zVHx0WKI_V?h47etU|>#aC2tg+R%ai-(=$2?$*{G6;`VUthaKy8)Zi5o7^LeV9~g0VnMXVUo*%S#N8R_ zAvVqCC6;H7>qmeN({(cKA8+m?37WXEw;X|K($tQ>+i4_P=ZhaY zwkK&KbVIFa*^W9+zAe>M@bX?sI$b*1m*(zcIOP03(8P_6Z3yE(|NYX0+fE!aQXFJy zHrKB&&9)OHfY?(O?cDWjwN2}pxdr?D;9|TMZ70X-ug9+InRq|WS?x6JTM7*{abx3t ztyk!mCjK5v(MCLGo2i)2WcMsz60Yw*DS1J|JKquf+xB$RNqT1pTh{N-mtsHKbP z;P7Tg%!p3u5ZbD%v`6gey6CocfPBKH=cAuQ<1j&VO67=~Cwrxw&%tgwVf}(Pz4TkM z0L=J1BR25AvddU%9*dT@X!FyM8T%LDFnp)OZBpjl(GjKYJ3Jw+?XIbB^btDeE;la`$03cG6xNvdVAge z;VsoPo^7O&=&R32zHL-}CRNP^G;w42P6@Z2V69Dsa}3r5QcN`4P6dd^y=9hNhlv&H z25qa9tI1s1qQL|3XIq85?mo>`H+;B=$e{q4H8|`~c1nb1M2)iZ0iK8ZGUQ9g2C8Mb z$9OvKbFRT*f3oud&QR*n$MI^i!%Rj&g}C;X1Ex8Sv4H?u(mnkYuAY4x5`=JZ7;Ztdtsix6fB zb@gSBj3^u?h)ziiaqIbToQzP|dYz*-8DoyAKSY=9{N9MbKVzs$$l_a8^!#@1#>`x@ zYda3ZcS`?x3pZ})ra#S+9cT(z)js`mW|m&GMcSU3qf%zIRMYu`hwduXjn)lR86SDX zW2G=?;>HBgDZw>0m)ANxKhtL-^F(TAyZ4hnoo}fo+oS`28n0e4_9{kwe*L)e18CyL z@SPHFJ2k}|COGZhtb*iA!**&saw24fW*VA*cxNX)dp+CBbGPs8_;3XLZUg%45td1o zK5{}UG-++8S;7xkfFs(J2_JMZwwbpJcwMKR)?Z@a)s#339QHSMR>1R^vqWUM%NNaD zx^vMs$pjM|CWy{T5^)=nI6K)q%2zAi^I_hpu?t%?$ZNaKDj%ihwmqz8bjyGu(A zSfOk!#dU6<2jMU)G#^nKno+|S{_GWO)N{q)xq@ZXxS?)9AH&g>YYt7+cdt|#FzLG%tI5H}j* ze8`E?JFGNTVsF#V9$CP=C7P~|c3*q_r!y^Jr@|(i+Mwg0i5n9{*6EFSEWWm@lYNke z4tis_P{6%jXIrAF?Xu4Q(8+{`Au?=jqWrFjkmfmCbTJd@**pC@9)`%%bsariP9$h2 z-7!3wBrVyMlNvEZjzHY^UON_Zy;6;tUb4MI2RS)^943e%ay!KBRMbJ^Tjs3|X zGHeGZvFLNc*jcoE^-I>?3E!T{7>X$X4)w%5@SVE={~gM)eI%l8s2#4=vocuMI|YaR z$)Pa8cQ+zCJZzrW-5WM)ekW=pSA5vx0{mN|>0RZStWi4#u|3KT_hwml9S@qgF+p@z zm54{-$Z1Q}^jK<68AAEr9vKd8iKhR%ofSlfD4ab4fpPvN?W|t{mUldyD$VrXptRm6I=I*R;n4mhV&>o9*Rg3Jk;`d*R_K59H`JgHy%)p@bUVZ<$LPMrDm<;R!@OHZv!jj?Xgo)z%t?wD}cpX{uN<2g$Z zxBO(+-ioX^)pYTNySv2D9)Z7%5&k6Lz{xRMt3)NN(&9#m3`B3X`F+9%UEG}*4iiKt z7KHfo(uo0o?hXrw{mD)YwgnVKjdD=YcAeG9Hb0(ow8N#jeST>@JOhnw=oDOw;4EX`T$MbSOP4lu{3R`cKq=eu__-l!TpF7paAv6JdKo^{Q>^8 z)!T*^y`IgA4cs&P!pGNa9QOaZf`+gW7ux>zirrRs1>XHAx&l>nS6i#k3QzXRR$0XI zFnOACIAd?$Jv(t-0q#-qI7|>-0q$}8un~S|Y2ZJ^bnScpy}KBBuO4qZE;nH$4*MIs z0^rI0Vi6qn6oSxLno^7qe^ZPjS||4lS%3mi;h@vV>enCOFOiq9s4N`4WK;C*ph?IU@Glv0 zrF6gW7TVrb!_HdkPalKB{>Cl>c$QjiI`Zw%N{yo?KOE~9xK`jWL39y25w}hCG2TbN zkJijyRTUyTPUt?g2?SGi5x{?l#)xs6k}TRW56M#+y*IzbVS?x)#v^XL>@5KQZAK-k zOS0LjY06PO$G%Z3r6V0+oWBAEiYZcw!0BMyuG(Dd}juaF3znS zgX;=n(dOrV@e~ddL{|XKv^9^XC#((px%U=u*x%R{08j3{1so=buD~8~<9?|u#2mqt zDF*m+?=9dkL39Q3h#N0^3&5Xy&j5!BqAPGf+_>LD+tTgCy$1lAxUv6#cLo19ug*eO zp^|n!WgmICI?GN|*w=fIo@zj^j#DS>I^FD*fy7x0c+=t_wtXyV2Mk*MDw9@afPly5u6YP#KBPQQO*@V1s}TIbXE{;SGGsy^a(woaTN za}qRhV}J6*Hf#qddFa#Op7-h@hZkvQJ0DV(SBjDW9O{XA;5&B#{;|Wq?C`2M!#*C- zTUb)nTn>i`;skaEBHJgxA*yWTG#&e^vsI_{Iv5K4TcRmjqVl+S>^aqdV@JHo* zG6A!?aqb9+G*XH~9P<);&0;X5mhIVY7?fQ%IUa{$^I1FY8+zuW6Y=ec@WC25SJ}A6 zhCiJ1aN-SVo~SfIHLIk``z_cZtP55kCj^- zZjGr=!C`36tEv3zUvQe5W`hYbO;884;BhO2O)!(&^d(Pqr? zmu{-AhPTX2Bm4tB>p>$oCIt&?EWd*IXEm-x>*rOYsQa`zlhr@;I)6etuzc_7-Jp>h zLvMs?DuU7oH_WtFBWccqK_6+(D@L_#JO0dcHy+ZJb>8`g+tN@sTD%-*W9`@&*?1K9 z_8k+4=+V-nbbdG{mbfIY#bNlIhdVXbb~*1D;i$Gs%5Sl-?!NXdH&mb8W(Z;(z5YTD970q`IcO_|&)iW@H`J1OD6? zK8Ljlf5rdG|H3zA*W;RVhUAZ)WgB+%>O|nrjp6fCoACe7@y|Js*XtR*s$l*`zvM;N zKW_s5+!%V{c~kji&^F<(@L%KK;m)dI_L_lRu2@+3m5nb{1OD7tpCUL&_+Uvv8T`#6BmVRcynY4)UE*zK>^V3=BNjtFQ@fFV_KV{aK z;V^ve$Bi}GF89ND*KfedSenj3x%l1sQMM94`oiW$lqqvR@L$z?qP@79b;sxd)$WtZ zt4nYgKKJ7^!CIRNXBeBn#tEPXDNTN?{CN3>GInC)#D5?Af(9Lrxe0QtOWP|;GW?#n z%o&8k@O{F6*43>+7aGU6t)eflvkl*Ael=p=bVyoyYUp)P#Es#5iN94*)by)A4yrHp zetY^xgnhM|9w_3*@cqW$rie6?@ji+z=H(vOaNF~vzA`*@h6c}ZSnXuW+*QuH<^*mqbF7P&L90x|}IDKi=H=N`r4FnlJ%X@a#j z70xg=fsGSD?LUuVfh+eY7Kh<8R-5qWxfh2x09Wo2D-Ofwr#9jLpGJYem3zdB!|>VY z@8HipVg>%(7#~Nm|Jgs>BUa$gjq!05%kwCl^dN;d5SNemoC{;nO=#Q-et2KSC_= zo%1hRvkdLgFFkHtn6OsC;Dyv6@wc85-$M|a%r5$sIelo@o!U3hQW!UmGM?f zS+>bWGm}-aw3XKDHwvw6obO`eU%g-JLQ@U02croM#VJY(G!-><1$CN|l8QP_nXWuV zQ9)Ble$tf5G{q@GaIfw^i??2FB5P@~Rd(G!t1*VvY!VV~jNreBt2VCKsd2^sj-(oC z%?^?pw1Y`nV@O&vhoq*R(0tOGxui9O6-l?)jK-gGZ?UFP0JH%$<4q>A`o=5Q8k?EO z>Kd;z`PT-sXk5%cf0{O!yr!C_#zY!@qNaj|5?xbKO+iUnSzUoXQC*29KUqOVNCo|1 z4%$>!jSK((+B**LrmAk(P=+8I1X39SR>&Sep_$z+d#i*tZ3Asmnv^A@>@9l>l)Yu| zJw=iEiwv0}C@4b|0TuYqd3iT|d3i51C55WouT5Ug9q-<=-nr+Vdta)_ktFP6OBePs zSsg-$O=vguG{biTp~c)t*f13C-7vb3(Uu%m4IvoV{RaKN=QAz7o%_9ROD zEY?I}E3?A^-*yj*hLbAPw~L}OsaUEtN)0M8NT3eLsnhF~8m&Suk?M^qg;>CUhd07U zQ^%z)!)P3PC70f8ccj_+2wU0G)8fodh3QGIcy4kjq#~(OERu<&2C+;g)2nn^gHfdt ztEHeXC0dmLjTCYR)S0Piww{)FqL}SMQ-Z^sCd3?DsyWT%u-L2(-UyzD;ML#}JlA9v zw}QsN^N4!h38PG1&B-1j*MpmeVxw4Y6swF1rP3%fiqu-MN})2S)k=d=ELAA=f~MFu zXhxwefua;X_w4wPC1gZJnr2Q-HUa-|5cv&31s(*=plQJt&36fns>4M~vlY>IpDb#YcLLrw*WHOOXD%WeoYC)r{ zJGF9v1jeBPXWX+ZJe}i(HmlIi&=Bw0h1j?MFljf^BI)sNrPeS9;hkiqdfQ;#9Kxt- z(NvsEe-mZikv1&_c(e>ApJ!tQ)`xv?;6az@Dc5UB2mNsS46)s?G2)p092#%efBDx% zJ_wFo6qd2`k*vZ%E?5ld4b*ilMS6r(AttbOS7P4M1*9(+ExNMYW-bu`ww9>7ruu^p znqixMZ(V##L23g$R^+NoTEYIe`S8=fdYoOaogxxG&uCbFBaC#v9?PcXn4CG7mQf>RCTJs zK)94B^)i`Qtxmu?LOIfVeD-1HQ!L%}+UaT~#HBzHeqmdZAn9I>nozqkg;Dic+ z0O@g#^fYq-cL6xGo7RYgIa~N5{y45>7*f^R1QT~hlqE6A5p7CsX|~&v)6pypmdF)B zvFVP~bVr-E_D-S?gPlKgNhYh+oXp4)^Jhu;v!wi4GX5+%f0lwjOUcfPHh~#zF(s4f zQgGeY=H7_xR+hfz;JWRD#UhC;r~~y?FDNwK0mVUs#F>L-WbHcI>@X!KTjF#!tK9*! z+hEtKc1v4&Vv^Ntw==Tj&INCc)nd1S`JdW{kw-6vw@Nj~r6-%x7&&yUSh%yrkyV8( zG6&Ha(I$I$S1nhjCZ($djF{NCxa4#@5Y)3o)|f%m(a#y|0r|L%9dKezOg3j_nS%)W zD5noq(F5|a-ke}cPj&=plg-xnXj{BFSQ}-C(SHnm?vZW|>Z(ajw)JY=%hn2~C!~5X zD$$^>F}Ac6Q!=n4{kyfvng~NdfYFp}hY|$)43G=$3|JPv89;()2FQ?NvD+;@%?ywW zx2}7-AolKza%?nbW$7&m3F&qw;ygIZIZy^_Jxb6+_f~}9!dn>^a=aDF!j`vE1byDh z5PW(oL!&brMUcO}6=RdYOIepNqnt~Ea4ePtOI%c}K3Eh4pRLTv;PVG*p}1OSN=A`% zm?0;qYpB_ZQ)V;Km2KM6?1{#Ey2Bh#G8jsfX4mGHo;F8wo5kwTI69isY*}m!%C~t^ zAG;;at~WVMZg3(Lb^_IG%Y3dsW*&dM^{(x5De zw5tWD%t0X*j@RkXqX=2_*ZXBEz^FuA!?*1#mP*;b2aZsem1gFksR zSo*vuwTy~$OKN^eRmu7whYjN7v`*N*&DGxhEM#m#QmI=;cpc)K>OM}Ls zQmBt?-_0=oaHo%ZjH$5(vC4*#g#dS~>hv<57WU$b7GShGId}nJ(OR!G z>NIMd0B^%y9%$yS9ldfdP&FYx(cZLi&Fn`{1#4#I|!KmwOFc2VOnNcb-h{Ou1!3YaoVzp7MF^IGh zk-;FB15*oL?6EgNGhTiAS)5E4%Yj2aPp~wO6q9G10|^Ep5hHUEZIDQCh~O>wK?)I| zg)ZcK#K>Nrg)<@E6BCAXI9*OcYCa)^`LZx;!sM~avY)C&K9IHA&~aJd*==n}wF__y zJ5En{Tf`3$V35vP|BraJM$t~Q8TNU)^|!RbIPlET8e zt8kmP!Z@2PE#6{<*^WI(2ooG3_#_~-!R)|Q8`On#J!lGMGO)q}VJr3|{$n#Sk#>xpq*6)vBt8})I8i*r8)Y#oagk04 z*<7R}&0?!kD5DW3!lcNGcM&F=dzzDRmE7Dr)t2UPF5{wL(o3o+j%F|6W3N^q0Yx+l z*kpU<1ih0TfdmY@++;$WihEFXB0V1G7Z+9e1d`b{)pR7Z(JsjnmjwEicFhS>z?&?z zC)v`IL06ldI=fdA(4L{Mk=iNFV8J}7gYyu{5y6<)I@m47jJQ4-&+ImBJ;>hA*%JN9 zMfSRo$0f`hzEw)7+a;NSkPxtBBeZ2aw!sfcJ*7>A&?wgYS~{-?^(%kM8fb#BDf})W z7g~G7hs~g{7pv?TsY-owQCb8!oRlUvqO3nK{up;b{vi|x>&t3`kWn5xElc|2Xy?1I zYagLKJtYN9K)zZ|cEKhsR&dx0v44zcpEs=I5jNF_rZby$&`hFIIryX&H-yychS1~? z;`)Y%YFJE{cYbj(OdZJLWEl3^i2%(#!X~teN69Bogd_|xPQ?Wm>`gCQ8ayRzX%?6p z1i?4L5-e$U2T>ZxKUB1r5UhT4S}%*;oc9^wl^X^m9+k}qZaV>}VL9v1`)w!4^jEB1m>&Dq&)d?5BArRJ*VsU_lXs`E%ydH8M z=afqiBLKylN+_{T@{-w+XUy_Jx@=Yr_Ea5%?KoweYC5asfl!V}xQnvHb|;IBpu`~$ zL|2#qOSHli8XhE!jfv_YH1#xDl1*Kc&B9)286tDwlfeX&I*ew>nkEE+VM+aT*|e11 z$s67NYA1Vn$WRQW$;(y&RcW{Yb%Aq<8lJ4wZXiNY4>j-&sY88pJr3$a4kxQ{ErJV1 zW!>83&JNDGA4KZ7=6-~Kz;%;s1D5Dz0dJ3q+FeAsa1w-IST+#0PO{itOa+e->w6BI zY?xBPB>;{cU_Fx+EDmS102&|h&VUy$A-exr)@eqQo6S1aXt)5PbRh<@yIJUrQ=pz5 zh+^ab59WEXEy2q?Tu~B&j&O6LZD_NzClyKIe2Cc7Ve)CR3uzcUQXnqdPOJ@JiLTJ` zc&9c(+Y-Eq5ch=22Cb4e4;zn%&1@cSz{w$%@G$|gBW}!q?pSBs3V4j2VJ04ov6imy z{NmCoGRWf8DsVe5Au@taQ14|}gmNoW42SuBg2~a>3|p__;;3ZVulKCcv^nGR#quLE+HV`8CLY zmOEzBL}hb_o6icl!xereq~p&#_+u{Jl=F*=Kk7jiAAh*oC(XBp!k!!g;?FQhlSxb* z__S;(W=C2d`{!Mw$khTElKk%HdsM^AGYPHS)E&nr&N+Bw z0~3*c|Lyu3b3)UXZ1sMTp-7&d@U1TSF)0pV7MInkWv+|T4%%YQ`+ z|1bZF&Vn#J*pDM1-xT)X!^IT{Kx|SN#UG5sWV?5wcDJmg&Fm93r_Z#xBS$Pn60u># zte~2p8VrO>olc|B>oroDL`bt@AGEA&zt=|^lmh7((upT?<064 z?R{ZN`ew((n;jGXfgKYrt0!BA5h;yE&`wK2zKh`pgWu{yG+5J90s{OPMkXL`12Vna=Bp8kGfvp;2wk;P z48q)MO5q1TeCFak$v^h9Mvj|tMmb=&bY^gAqyig80=}rbxVTs%mWtFWy%x^eP|4&f zjY^`IC{5xSW9S$Gbby&o_IyT&qc@Ry)cgJ<>Tt%bOS*GZWqtt zsT|CC)5ybZQui7@@BLTk(pmjmoHZk2*)S4k<&IdnN(qOnsU>>3TqhG7wQ7ytAeHGf zVhJ42p;H;CeGDWhiaYvhA++eVgeRh3NBER~C`RoPV9hYazhO&xfB*!Ui0q`XovTlc%3K(9xY(?~v~H`pVDY2^erFLt zAya8ZYPnRafn!$m8nsNRlPTfL2$8y3fjRS6taqtI$KGPMQ{o|A|{1u0Z2rBS4l8O36? zobpdP(MS9sX`}%J)s(jTq`lijVhf%tcNof zsbwBq24+STaRri$gm$x0&OgL~#o%~nP$Fk6h<~V)@Dg^flQhm{s;~c8EbOi?v~A?x zHFIkQNPkA+uwf)t!<{%HnNBQGDvWBa9-iS!g<2xk;kk5Tkx~fs-zGB zR;3I1zNdY%vvrT)csx#%O8E9SZMr2H_Jk*LpQj&2mvnw*@q|>R(d*&tNC{|0kxm2F zgBr|pky5Hs=+#D*0AD`DJR71beHZ?iu$A=s`hPAS2p=1myv75$sHB6{bMjS}7b$E7QV3`67Jj0h~#z)a!JV#YY+?p*(M>#rvL$sWgJw z)G9~NkDeSCwWz&io*Pb*Nnz^SMJpv}Q?*(mfd`sYW>AVWYB)AuuLH-jNMkUFl+;@) zn%k25B;vjxJd}?P#exWa3v4IBAZ|Du-vXg|5UE9nWxb&#FD>U%nD>;t;)Fa!;3CY7 zr)_wMn~julC!q*z6Pegx1ZzQ)(bcOk-dGwzOX&f%NDTztp1!tQzCm38HFb-cuJ(1o1E~H9~m6zZP0@=0~dDS z&?LD8)_JsArC6`li3Jj<=WNo0oNtIoaGKBciZ)(ROywaW9`Zvalu4~E9S%AZMq8{N z;`kw5%=zWgs469_Yf8jgxl|8Fj2mDsr-q3fyuC@Im8oSSy#P1dNc3=U4%Kp9*o0lr zNl4g3MKmY8!oaC)-xx0*TVhgZyt9RmlWwNo*`=FIt<|WcV!24CG{AHmUKFEI>A}sY z0pGe(sZ)5+&D8r1-CQD&C2zb@$g$p{kSBmC&Krds^7Q%h+>1i~^tb8-ehCZFjyhju z&Djr4kI6DMj*Y}RuLbcAPJQd6$&FH+|I6V_dM+jEG&=BAiDQGGfAoIlN%r z(k+AM2UVN4Bm|Y=;^M|}{Zk^p{Z3f+{-%4ecTZtG%qL~I+QI%0`R-Yjht-=!uiR(I zA5n0ngbPNdbW|HugMo0Vm&xH3EfS;L09J=cB2hv3hCwbe%D|wM>2yYc=S1&)sOB?m;=-e-Mhhbi6UNrsyD_)`#bY=^YLxKJl@LX(YdqLm_lx5Z zV@3ylSFwe>J{OG4v8Xnv1_R+zDuvg=!2yUG9mKuB%R5vWr9lC&z7a_bu)3sGJKsA& z=Er1`M4j*ALLGs+&_@7ld*D@|@TROsnU6Amj2x4>RQ5^Rxl$Z1j+PoR{@_T6u7dkb zJDZ1VdYM{PU!8PZ`vDh>Onj&&s0IV!5}v2<0z?HIB?+@ii3Zk!6yVMl8R0-l2*`l= zcdqGB5>#{{&^bj4(4?io4kDPdw1thyuyg;VBep7nS{UAF~!cf-d^$vZOc zi7zU4dSICGR?Iu^eAc7BqYPpQ@8EV91VSR)01?ACb{{NsMDr}XM%yz(eyXH=&IKb= z6sj`SU?5zIEvpu5#D?UtIbBWN&!ZWK@IC}BBhM-BheF=2q^Eo3@|3!Opbs6 z=Px#YW^ei-=tGZ+7i+v3)DQ#$G~^_5^3DlCF&qy4Y6`l9k0BF?wqDYaZ|@F?Q?Dre z`|6RxCn7EwnI}+paiJ0xFr_M)RIY`H7MVdO(!eU1QminF#B!NhX_UG%Fg<&Sgf?6Z z?1W{7!udWO@J}RMj$SHG;!Y4@zdxBZ_NspR-fQ_s&*|Lc>M|}EvD4j=2ycLsD`c?A zLSmH4^k8Nyv?{$uDN@7XvJx4*8IEPWBTr@-^8p+p9}tjztDIBBsSc8l7x5%YCA>R@ z@FBcEgC2p%3hx|a$+rNO#@kuVmnfc{$`S(LZ{GH z?Lz7&4N;9>v3A>pkC6my7%{o2>QsY)a0!c3unG?UO#y7J zbt3^7;!F~ldcT+i-VN+LNP?in*0F;%X}dcIl%4gUUDw5kF2ojvG5oOUlRq)IJH!ygoWD=PIxCKl@qgHE_=(HjT3Q)fB+S9bpnn3Y7EQm$Pp7^@$ z;&nYEh*9V<|BZ6vHi|a`0i>2Ij2fL<38oadE#Q5{TBRO@TA{@^PitV$8pdgmM%hpD zH*N|KHw7_X+0^of*B;`HH3o@7u9U(H)*#$ZBbIBGazDCIGc*x5=qs3DwKp0e3K!n@u9axjGObLmhAV>+Vywglg#sRSZ@l(S zLBY>_f|np7nGLXs$m#vfzSmwUQz|5|dZqtr6@-#1?S zEP?_>U#LRK6e3%6%f8oM1iM5uN|iyXSHm1cCD!V6DljV{#?b&#B676{-MmjKcuz81 zNsIr#HB=;LUi%Ed3a{6`G?u-?35!YEGem07sQnB+^Q? z61@SOP4wdaD7i4WX{c70GNgk3XAtwf;{$snu& za4C_4%T6Z}OTcBP)hpedo^%k?zsPHkSkH;q9x=@J+H=9k6vZ9u5;3?#jUsrV8LY~w zVR1yKhkbb(kwK!>C=_COUiR9%x#``0P-BD-H--8g05ZD>w;Ce9m3%)Hq=T$i1bH4w@4ZRk?VfCRZj{OP`qzpll(R?c+z}vSGxk$2OhR zLgcDdB0X$}FzO9jg$$xGKw+q1!AYW&X~F*iTZjHjK7J%YPJH}`Zni(43zmYYCyAmv zk^o*O2U{VH64=SBl!0eotx(7ym`Q3hzz%K5bR)sP-N%n4@YTn^l0s!xyuF4-aTpCJ z7F*md55Pp1FK1#8MVSR6ISMv&YcDl%wJhgxgD%zu%1<)I0R6&py1>7l+D*<$@x@?q#W;tSf|L za*+yud<%WD9jPbWJ^NJX+$}4s+zD*i0^!*i-%v@dzJHu=6uz=W$49$<9dZcA$A)n$ zqTHp~|DgY)uAf{qZ2CUqhHjZLKb2lc9hB{DOnFEVP4H$BoqUo5i)d!|KPm_J>=3eR z*Q$jr3nxrr3O`Xq_-xSq@}oSc)%oZ-b;^c(`|0eqT(CT)hz3EYpDwMj#rC{??Be{J zN|xGFikcC7qcn0i4lG}i`QiNHw?c;%e!G74rj@F4!SawIGC`LQM238F)VNOF_rQY1 z^DkX4i$lrIP&Znx{Mo~$!jjX<9*WggxuVE8$9Rg`_oPQ%)HFQOT*eS!-J{PxM?Y-~p8guDXD zXG3Pu&E756Mb^1hZO3$7bgI}fVK3p9(bvwR-@P)F2{okf* zxvaLX)8ksTMXSn>H|*zvea&fY=kA!$+BT;SJ)LemytiWACL{N*uhl!dW7@T)rJ(JS zUSW$*6-?~%_LwR-CN}H=*O&wfmR)(>7rTSb(b#DUJPH(DZBBvPjj3 zB^M;k|G1st8!i~mu1LzdK_MDSSm|0$`+k$InAJ4g3>#@FJY`l{$xSA(}ase0@T-|b$kHb*n^skLGN=GNGytF4`Oux6M4#WCb zk*hLk8~cA?YN0=u8P`uzyjynA2I1qyT(AY4yu>yF+xtQf(go(X+nDeKwXun!=`A9! z-uS5BxVLSon_;{2*O)bY?9P~=vO+qa zt-cf29`;k#eva)A&7ZNN$rnaFJ%9cw7YscgBvCg&e1%)>4ojj5_Ra(}2Mh{hyLN+} zG{TnV1aq1hUepA8Xb=o&oF>Kloxn6YkDwAn?$L-}p*#902;*V&FxXcul2jp$kj$nhPSxABab$48 zUWd7Wk|Ei)dfd|mJ0d<`COxKtP+jbNcE(g<6)%`jluQOx00zV#8jgxj<-u zbke`|lcUS#rkZ*4M?~&ec!j~ZYY$h?z0@Fb@(0HjO`o%)KK7jr%bpoQx_~WHi7BcCM!pH!$#49o`VMbnq0$j3 z@$h*2jLE;B3!O2nqNH$_=Q_-I8{m@vEtvIl{)o^qrd~bPNe1f?u7Lj!Vm}f*UtBk4 zVexXHVFo^!!+!K~uymfM(0L5bwvEvEgZ+uW|V zx%s9**}x?1GgjoPjCq)_|Fz$p`nXc#N3k;_r;PaNP{((;V3Rm!GHYollLMUX(x1E; zkk8dEw=rSxMNYyNvH#muJ@yYB&?a)$!*YFgj+}Lg3nu0q6MJ@cE+=yi9KOvL69l&t zVZwek)ePT1wCjDtqi^aIT|Bxq(RjkTf-esV)(VLF2-aBwy|6GmlWD#U7$%+-0r zaN1m$HoaQ=X%WK&wZ2Q)b+a7lg6HljB7wZmhb}d}%w= zSTAkbF=W;O&EoDSo~@X?OGWyJjS~EAg*$cLe(1Mvi?j-ze?>dD-w(%Xa={4tux=K^ zumu?HaJuVQ(0e$QvxNJnn-G9kLa=%Mmpgj=JvS;tHYxPZPunuEINrhSE(l~K?0?FT zdv_~UO^KOSZRuw>9BYbd`_1p;ucJ2B!*ModvqKnd zN)_Tealq|mbvT=0bIIYHKG&$`;KNNUwnH~ZoxX1vpj&oR-{9McHEVBphy}6t)Clkg zN5bL1eLE~8EGFY{x5l=ql@|9q$p!O+SRjkJ^?*qtw+#5f)n~T>AA}NRuGC-uKsS7S zi=eU78@^NOg>ex66Bi^NuehxAySQA1+wsmJGIAm=0n2~g^PA34spf?6Ib|Q0sLP}U z5f|jCzM}&BOpaEbe*WphL7m@THiHXB#!JzVB3vL`DvT1P$RIX~;BY^gR;t#h;ebtp z1m0exg?%XSwqOh;&k`4BWwwwU@r7roCRiVCJhKBjH>=IkvyEdWO>Fu6#Ehz2E3U%w z*k`KWtjgpkmvC{x{2(MgX$7u6yA7C2x#6I^4cLD|g2dw$l4&$@3FE!|Gi5Eb$SWim zH0JX&B_g_Ox%Gwv`!uzdj@b5x{UGTpcAW?b^3?Hw=GO{pE%mpA4;i{)N2hjNFfv|h z*c9Oc;ZiR#O7yVPO`(>-U74CmlD-8xXXkDo>iUa{rh-_xDJL|HS7V&IDszE9n zKA7DkFmK;(EE5Y&{WW&apL?}Kg^TMrmgR3*k1}fU4sLg0wa6t~TrfY#h)+s^tIuu& z=F(_5Hg5xF%LsYL2(R5$jAoa0^mj#qJq&Xq^rhcYXt7xZykcXg$K&&iWu$mt!Tuqg z4Wo|UJF(!baR^}&UK6c(buZ#10_E+qINi{-yV$l<$;d@x%S>$bcy1Ze1%hq--U;LD zu4~cJQc)ed>eyw?wJQDMxL^biScf7fUgTpxKECzqA2s>qeH(%_w@X?u7zS=Xs za#QNIcx$}iNNi3a6GdK5;idd4nst1pe9gBXDTAUT8dmLEKl95^Y84<|$iZAy1P34S zs@M$BRX+2?oRw+23WN<9)<=43-jy!qmQ0=?Ds~qj_t>f8Cr?HGX1MzJld<>OX-jg! z2!@ah{5;`bGc*+L^|WHZo$!X!BF7(A1V7)W9f$Wve&FK?%*X!kJ3D>P+}KAYM)d45 z{Jph>+i}7Cpe_j-@wQZA;+Vk5H&>rsxWqzy14B5Q*>gS}#gGhMN!US;h>U|*g$ZhV zVb`_bTJf1(M~!T}|6okvFY4?{TCwZz#p$FAh#7+C-GGYf)yBf>@fs&RyxC^zt-o5F z=Yo-8U|r|yrkv3ndW#)HGw`@xJ7pwmFdCy#Yg3}#`Mw&wz?82V3lS8M%A!A*-DAS} zuH7Dt4WX2MP3A}6>y#7Me6n@8L=;yZEAnvwX%xqrxYBmNVx)4$_ly77Ibcnr{9G_U zu(p39cW^+M^l))-z(<=_8_Ep)Y*Eb}1BP^rK)AO7vswPtSpvi9Zu|T^c+y9Hc(1Y0 zB;{{yCWrhrs2gDtUNJgZ%ZnH_FPQ@|D%dn+#&m6G@rmDJc2An!i_;R=1LON@*CFHa zP<8#c^6i;dw?sf!E*QZBQp%;NJS+kKIw3Ls$olNu^xaW2ep*+q{fNumv{amcFPxHd z<%nb9RgNoII)Rs}SG{csyPA_{x%$gv)!HUB3f*%4oa6l>=AMMHkTOI$?gbQeNDLh? zYy7nERqgjbZx@kY#|0z9z`DH35%>~32quRm4&PkqRFhf1v;1#hwb13LS6sfxGk47I zR^y2JgICYnc{*(4;6{TU^|`wX2jz`dFdwmU;UjCwT1Ah>%#4wbnYxnS1*io54rX#dT6F1gzW*k>>4aKQ-rkYKM$n_{fqgUKzIZ`E!%zoXXr zd4Hb%>V>Xc>>u`@y`;kh^MiyC^@X>k5);P+M!u2J*~x`V%;1v*g#WuFK?q0K@=h2h zzdk#7N_%fSfq9s)|8afwpDw~d*KPlGUWS@<0lP!@N^k%!R(3xX zzB#PK$)JvPr-Y{`JmZ3qVPIXCiplp}_K((T|7>Hn zi#KETs^5*-HdoKqE^=gI%v|f~a~+lO&ABAu5O59KnB{`K%I7I7jH8C$nI z4?;lDh_|H@6UPKbzPb3=g-a~NH!y^=nLX!E1)n_RFaK1S0KMnsYYa>BnXhYn+$8MI z_Bvs68|&f;Eu$&GLntOs;@E(?lOP5ayFF zjWg$TXtm4w0lsOSm#Huh6W88NE|?#r#lNm}+@Qza{E7oYX~BQ4#FnCIbfIkfR4^oo zN@y2^njKNLUS_+4Iv<=rE~zrz9iJaBhu-afc6#)Zm?_#a0rJRq>Jv`qb;#^3=tbBv zK{$LCwy(R1Yu@|4k#XhT8P#;x_PLp01j}E-#m>7!PVMO3FLuSg>&5$hy!=Bh7{LP~ z(53kD^`V;~gQL*P{NT-?3&EK21)9{}5Bw&{&A`Aw^Ih_3oBLLXi5?+1QR!xB{u-C~gWucFyi_Bee>H1~kkOqT$)O>VtJ#q$)fs6xxGZULza_-rv zM&H6`eK9R&X0sb@-_g&VveD3OcXuP{LN{hV;X3ODIlP(#txI0sI0>0P^F~!^tpW#S z4K*{){9ed3Y0wEKZ;;3KQ5gB7>uoR9O`B^RTw43>+Rjx>Trh$m99NbmVY~4z`!Yqr zrr3#Un)IzF*wem$8*EiVOdFKf03WOsO zX+q*pkA&kITz1{Q$ckTRChsn|aD3}4>0B^BJb1|vTzz2T-UXyDxccnEF_z&Q7{b{? zFokY3+Yeak-O*SHLTB&++dR#dYEElu>&5?gokAcXiDF4`q-NwyUFOf&vW za(Mkvbvzf0-~sEp2$nAqe?nrm?1a#tycu+UVfaokCEJ~+pF6Ke1JrFuKQrNCqPkw` z!iCov#;uv&W&3+osWmIiCuK-Q^8GsaWqeNgWy~L82Tthp>CLT$MvdCKxFo?GFTbRE zGsiMu!tXP`2+v*aHBYy{$o!)RMu#r{qbunG;*;R`7+jnYY#iP_Vy?AHNbJy)EBkHZ zf)PAm-7J1#@1ThGixMS$s{j{&PFgwRlfTP{uOD;xMo{qOF{JOL4E|;&Hjm_d>idc} za^Cmm(#Ztg@R|H~+9s}lUM9dWdhfvg$2*;Gz$8CW^2Y&>^2T)^7g8??+4Ny4(iA|vPUaSt|x!{52qT6cJA*~pzYL*tXCT_4E> z^TVUoze|T5pyTPH)(6AFF0L;)KYH_4lX4Ue$lHMZCocX8H1AT!%R^HH?Bw4){G%6c zt86@8Gj#TlzUz9_ITX(&A}0WUjhFB1kXC6zY^E+Ie!t;nJuX;YjY21)jt-tr27O+* z;U|?NKWkdK|LMMc_8@!Qh4C%eR@QMYqk8DdCebl#s>Ek2Xbf?%YWdUk!$J;5Z+o(5 z_p=rkt8&5oASeEfPS1crm$)4gye+=4CUZ%hVYac4(0lxkl9P;@UgRY8ZGX$j$tDBG zkE**RY}Ui;${TyS59X4SlN@rw1zGc#V;B#`*|`ID?rNjlnz+enM%PI z%;)0Fc02t>Mc&nEGH>*GPWRV$Pfnj7o*242vqf^LqVa7BTl3oJxQm!~PPaBEtJbY! zzbsMw-M1q*ef4BfN`|Bq=>j4F7>7!y;G*NeIhs3<$AxD++cQ0G$nd*dFoFlH#BZaw z^VLR2t4S0j#6RlwwB(xV8@Uzf>uvzZAO602#9qCA_AOz{M$;9P8yxdV8B&pa|I3*M z-wMRbG(tdv&z5~rLBS*S+c%5Y9lYRh)v@QLTugJCgK4;6d4Xxr4tc{gC=M{sbEdUm z>+&)U?q2knX(}%Na_E!K7wfi`u2)?CUiW)kO!Geurs0C+1*X{xhcYmu$B19GlOMT^1@(O z%jG~TH7`Bl$XBD@jT%$7RE;j}|9H;DVBZ3^*>8&Cf)P9*VO}MJ5x2}pxGxujZGir> zUjvAJ^o5af?)>(TH&0N*3+3@d2LF2Vh8^Ga@sPv2qc&FwlMS5{dY#D@1l?x=fBob? zj;*&vZk(C8>(3I_?nk&_dEHCV3|QgNxdT1dRcoY~H}c82s+Y=1kUeh0_!ivnX%7A( zIA+Y|sXaICYFQuQ-q;575eL7{R^FL({|n95?pxo#pFZjV7c9?tDGoyC(~gwswPNUm zsF4$YJUo2Nu>>5Dw*j*iZqDW86~{+*so+JRO2d%-D^SncJX~C2Pl52o4d1D{x7y{m zxCH7P+;vXIgVlBa*ITz>W!g8h4fCl3R6)!&gnV%V@dQMO?~^U7XC3@6_H6|ujbUrXJ1TM)kaY>N+yTp6t860!3r*k@<7N?ST3Y{>_`n+~bl zv?3Sm-y>pQ0edMcPP<^cu|I0_o)6dmwP9qJ7jYcsBUW1eQSbYZ0?osBwt0TysI0>w zE?AxuvB}W+w$<!?3d@_7v?Qlu-w94bZ2>h+xJ6y1TkBEH>99P+Jpvv(_AH^MvDzf8TuskPXxP4^XgFUgKV;@8= zDY8d5;{Fq#BhLOYhT_#gFCrG=_x0h>CMPzOo^~{L?6`Ur`+hZ@bNASHz&OK8CuJUQ z=Fl&CtKaXlTDE(S3-<33F*K6is?jVaq21c>-OC@A{Aot9Y|X_GD;9D2IX&N+9Q}E9 zW7}c3o9eh=c}~Rqv10s>5iy~+W8dx<^S7b6|Jk1H7amw5M~@!(%ZVe43voTgE&}6J zs#UqB{Y1mC&wlx1MYCI{`f|bkJt8&~M9i|`*M%F0&kJAEvq#$r!k)wNsRfAe`V>Q~ z$fds*E%Cv^$TdBx_E@8De})T|=S1v3}+OEJjb`^SGrdE)<;p}E)^Gq1PnOD zB}JEjH!7F;;lYM`n?iS0OBIjEcV!M2?B63r!$4Ye{fm!|{65t_`z} zrQ!PS)pn^)g-#fCZCU3#&#!U8@|+Z9!028!1n`xFHj&kd++U?RS=fukcoNQO@_Fre zd#kb0vGeo zwa}Cz(^T;It;$0Qfjt-{n?{plAS-0E+B3RlCQwUy!XC$TngxH zSg9;)Hs`B8k_$%gfOWGNsSn)@vt=ydO1v3#2@Jt_;kM!@P{>fa{Et^Mc7<;_A3Cyp z-+ZtJ<{SeV2mWTJ*TO6$Qp0Cv@j0M!0w9i;S@u540keo!X%n7pzNQ)3_v*OFz!IE? z0$v4d7a3Oky^DX%i5j2HZEP>V4qkt>j4)m zl_BRYjuO~tD6?f}yYwe-hFhtuA5_!iR(Q;0@^9;F_EtU7Z_Ye*V9S+B^RX!AlQQ_5 zov{DoqT}jMoKq@lUgcT#Ta!Dt=YoArSQQ#@jp^mye9Z0&{&pJ^b@*#!oq;7go{gL) zT4BFY@B2kqC_7^sGH%dEXOrt0=AIhc|De8ZZyXaFM)=irW4sWs_l*1ZtvF)1gQ3ia z{~PgczlfuGtxr?a8hKpFUlsTdD0`Mld?)9*&6(3uDtM3L0-|cBEO% zJXO-;lJILc_wTK`HpZ7V5FE#YwILhhqv8!B@mVOJ<#Lko>lGc?0Pq3_vp_RfA^5gohi zQvI|em3JT1JGiqJR`A9`n2-G*GJpTT8Ykkl%Pa5rzHspKAzZLrP^mD)nQ{_0s{AH{1dSnjL1+{F`xj2F5|6oSH#) z|NCsd`FsjOCRk{^imo|~$7l0x@0l8Be~&u+aAC~_tGiDh==O>nqRXy>OdR_AqsK<$ zhE-CfDzi|{xIejIxuDD3NJal}(`7->x1_hO=NmllqGox&<_QcJ2XTN2hD7~SKUg2HL#L4waD3KjKA!}X;cbUS zj&xe_`obHUsDy;1Upj6*`BAUmnDaxT)3{`e3-&s68kZhImhi?Sn2-Hm^|f?Urnd2q zSCc2LUH(&-#$2#hsnf7un6lINrcq@^9SlFPvD~9k+wNW{wFLXlh7rERHnVhB?(cZP z`(et?IF>XXdhRWa@=*RNgQl*n;wX>fV8e1>U*!#)uyt3?0~ql98{SRsD{1qNi2BPP zw%Z&u1+S@<3LBt&Hnpmxe50?WRT!6-7Tx*b-E`NPSIAZnIZGuxmPekRe?mq~O4#t# zHxmcfk$%brdmU=2AM|iT()p-Oj&d<;gFfgcQQzK!oqmx>VE>0b=vi61{Iq7iP;Ucc+@x;;J4-A{VbyoR~yINdBIOdZw_?w-u|3%h5c*k-qPB;J3 zt@N^WwKKS2gfFT3RD*$VsTLXKI+@;}ld8osg;Aq5NK{&_LMM@Fj53i_O}&ma>trbB z&DriXpI%SS?mzx^v!ju?j=mG#dV2YG%-qdS_p7%}`xpyhpQ(Q14~~R`9=yK8$+O4y z>*wdY@N9#A>KZN>Q{OooL_~;{TCqwcgM+dpTA5TURjIT}kwl}D%EdaFPOf1iBG-L# z{zWQsmvL+C-s61=MGm=M>z8)VK0k~&M1qCoNtDUM}-@!1x+RFW9Nf)}Y2$YS(UNb7NTG#QG#3{gIsVc4?2d`85O7Rv7~y1W zlM*nz@K|8+ud?FO+IZLO&`Epm_^saU21aZPF@7-Aybtf-kg`ee|5wI8|DY4?V%Z&I>Fi7tWWGWJ7w_{(3tLRSq ztepM$LcLUPQCvAX%;8$!|B2s^u)b4t=HGkl<-hF2Bm_~;T*`tAmJ7<6m-ZxsOQ9mO z@bLuZVZ#2OpMUIcWmt--?rz)0TlIRj=Yr*eawc7OcEtIaEq*2yu%F8-oUOh$^3&Gg z!}86m_(j6|Trk41STE}aY%|=yr<8VtzTI6iB2*c6;`mXk=F@u}2JXT8x84zV`V9l&e4=UX%HLPC_EZj=rL2&liPfes+4r&RwA&Gqo~t0RIGc zJ^Ehb54Euo+F_doyZ^e}swNjK7ql{AX684gV4zD>nhzHbembzNZr|$BW3Mi)5aB4< z05dS3l%Wc;KCu7t*h)KZw|*M2J$hA@YHxpQGc>f&kyEtm*fEwjzMXtLU_4M4O-}Yi(vNOK0 zW3#J&8#O*`^RR|%r+<{*8pp?m<-Uf_eOw_vFnPlX+p>HmN{z%f`>fP_j`J46*m;%O z+TU{!x;wvX@6t(2%wcm+)akvu_Yv0{tPs&esojFR4r(x|R)NdOAzL49JbrUfu~S^I z*QM0P)^7a6yc-Xrc1-29~4fn6i?3ub+BL|vd| z`it0uG5+cSF8@y*C(+(rEV?2_p!q%%l z^bHXkGp`N(-`u{Y*<7&Kp|Y9*eScZluj(Uti?I1uzqq$Z*gRWqKJ0%&yPs9pM%|5F zUBA6N(sK6<7c4KTEbJ%yh%_$POCJFzsK#2eCBlT?RARCVfqDC;G$(YQN_adQ`zSli zz_WgK_hKqyLL0jIrJ8LYO<+Mj48!z zrQGJLRsYF8uEL%pF`3)MN)|7Y|iyc6|JrsOcrXT@jl;@-gC!4fDgS z+rKZnI0z$reaGYZN2gDy?M0{K>FRMbyKkYtiLpqDL2X(Hv;8XU^rsEhH1228%y<;L z_2|V%zc7WA=yZG;#DfjN7aCr;WZb#3_@!nydJpA-y$+p@FR*A=GUL5!0hL2H1?|p! z$J)F+@;M@hMiBn=NZ9{H4O{(us7WP5=96~=J0@0s%mvGfIvxATemMshEU)YIlQ0hU z%Z89pNH_fFOE}ibzxDpI$zPv`k6%8jO+b9iUtF*^Iz0=6h@U2V1}x2gsEmHA%owuc z?GKx9!Sb9=-vncL^I{exq)X9X^|tQS{BaJP5y1<4+%J25mVWcRl>tAE{_r^SDL`)f z3viI5%vjagp-T*-&wp(EZfjs~F4*gM3M_@bZ7==PrV>jIg-lz&=3vA9H7M2xuvblj z{a59)RJb;BU@$=Az97{ zcKCbl?CVDSW7-e@=D2&Y1@`0%o4hOPhIH+^76{J{eaglDP(Z63Y20c*x=GnZUmM5B zhA}lgHAcT%t;w{V8xWB9DM^tyr z8I;j|DVK7)0~lv3H!j%gQf|LAYdAfjMtj5bvwuIF`}Jw-iP01En0mK`{PZBF(1dnR%BeT|FUv>-5yp! zJukCyA^3@Wo^aRhYrAvs#E+5N(}tG&>gO_XOl?Fa-1wH#@#i}=-1^{7_|gK82cEic zP0a;+9onb~aBfZ}+}QtwJ=RXkn>{gnx})d1;ot22h6|P#wGsA{{nl76SYDrSbG^wI zH4zMt`p0Xogkx>LvG9b9_KL_ET}zFxu=cNhTrj4l`mZ}t5kD7KhEAMY=zw9UICI!{ zOLkV{g5|jhcLs2Pug3*4l~^#;e+veWO!Yo~KtjdlNJ}>h&^?K;F7S`ZmGKmQaMpOn zmw}Ia&Kd;(%9&AuFQXV=MmfHWB77MY_%Z_cGD`7fVAMGLc_OheU&h;f8AbUr%JOBD zRw$+kR zN5LqoVZh&ma`+QpP(acoasl7(!ar8+#i%cY-`GBxhQXx(4{Ra{IfbOUaDhM9FkrRd zH{O$3hdMYLV3=ycKjt&rU&W|j2lDWxwak2GTg?8?WYn9%xW0oopwlmm>(3b1Z~!#r zfg)D6OL8AF8sZ}oww+yqVp+T|A3-rcy9C9u*cKl_F(13%1ur1E28BN`gGp(G;f?t) z&7?Gz#rjN2BMdvkqz;qPB%j$nlhT;~DkzQjL8o7iDUDeC2wQ>V!YJxkOhe(nVg336 z#f0^RIvbp^m6jgou-L3Zdt90&)e%IU#sy2Rab}^zCbXxTdRc{Wwv<$x)ogXxg(hpf zFy1D#!2w=ra4MH0J+%SVREX6Er*q*lEgs$#52tqtb!lceu}cewe5IyYtPWv9x|O;U zmTxFf)BOP(Uf|Y`R#ZO(6=~i_{h~`Y+3jX~!%%46mxuw5UhmXfMB7aCm;+?GfPeebiko!X?=tV*!Liz1&%zk#C5k=6NMJL z&}_wX&*GUlL87&W5;;JE2&(#cXQ<)ilYBHu;8YwyWOA~_4tyaX<7x}JI4&e#G3PCM zC7G?jFE9ubuF4B-Fv?_8DsqXFK`3yLFah$+y-g{p$!4KRi0k>lJiScGP83*y&rCu% z87?u=oJMg|F(Xz${Mm)nJ#17gfL)km>WM9MO}07F7e{)@bB`p8!+~fv;oXvhfMLzT z_rffW_vqH0cXLu(m&N2D4P9XX^w5Cg@whtYh$yBLrli{)&dziVHCxSiGF_~5>=a_` zC>ba|XmjCrB3+1Jhph!?km~ejs z_?;!y6jLG}3%eqz>=cJ*2|@#=Frze41Z@uGb3jcriWt=Na#tw$l249T^>{;#?d>u9 zqQ^8UD)ytj0IN;rW1h=2V4D_rPj7Y#wx1m%7K&xde#(wG9QPiRf(;-MQ&X) zL$PbXo&1~V+gGO>Lf)lP5S_ssWk0%*j4ne8lTlN~;sdBi2Jymz4d}a&7F>A4R+zWm JH>CdD{{yNBj2-|0 diff --git a/Unreal/CarlaUE4/Plugins/CarlaTools/Content/Python/generate_tile.py b/Unreal/CarlaUE4/Plugins/CarlaTools/Content/Python/generate_tile.py index e68a03b11..d0ae1126b 100644 --- a/Unreal/CarlaUE4/Plugins/CarlaTools/Content/Python/generate_tile.py +++ b/Unreal/CarlaUE4/Plugins/CarlaTools/Content/Python/generate_tile.py @@ -30,9 +30,10 @@ if os.name == "nt": editor_path = "%s/Engine/Binaries/%s/UE4Editor" % (ue4_path, sys_name) command = [editor_path, uproject_path, run] command.extend(arguments) + full_command = editor_path + " " + uproject_path + " " + run + " " + arguments print("Commandlet:", command) print("Arguments:", arguments) - subprocess.check_call(command, shell=True) + subprocess.check_call(full_command, shell=True) elif os.name == "posix": sys_name = "Linux" editor_path = "%s/Engine/Binaries/%s/UE4Editor" % (ue4_path, sys_name) diff --git a/Unreal/CarlaUE4/Plugins/CarlaTools/Source/CarlaTools/Private/OpenDriveToMap.cpp b/Unreal/CarlaUE4/Plugins/CarlaTools/Source/CarlaTools/Private/OpenDriveToMap.cpp index a3049125b..42daea10d 100644 --- a/Unreal/CarlaUE4/Plugins/CarlaTools/Source/CarlaTools/Private/OpenDriveToMap.cpp +++ b/Unreal/CarlaUE4/Plugins/CarlaTools/Source/CarlaTools/Private/OpenDriveToMap.cpp @@ -293,11 +293,13 @@ AActor* UOpenDriveToMap::SpawnActorWithCheckNoCollisions(UClass* ActorClassToSpa void UOpenDriveToMap::GenerateTileStandalone(){ UE_LOG(LogCarlaToolsMapGenerator, Log, TEXT("UOpenDriveToMap::GenerateTileStandalone Function called")); +#if PLATFORM_WINDOWS + GenerateTile(); +#else ExecuteTileCommandlet(); - +#endif UEditorLoadingAndSavingUtils::SaveDirtyPackages(true, true); UEditorLevelLibrary::SaveCurrentLevel(); - } void UOpenDriveToMap::GenerateTile(){ From 6ffcdbeec9eaaa6586c5e8a77de13d449acc55da Mon Sep 17 00:00:00 2001 From: Blyron <53337103+Blyron@users.noreply.github.com> Date: Tue, 21 May 2024 13:35:07 +0200 Subject: [PATCH 27/99] Aaron/fix dt windows v2 (#7680) * Fix OSM2ODR build * Avoid remove to root in windows --- .../CarlaTools/Source/CarlaTools/Private/OpenDriveToMap.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/Unreal/CarlaUE4/Plugins/CarlaTools/Source/CarlaTools/Private/OpenDriveToMap.cpp b/Unreal/CarlaUE4/Plugins/CarlaTools/Source/CarlaTools/Private/OpenDriveToMap.cpp index 42daea10d..d1bee7cb7 100644 --- a/Unreal/CarlaUE4/Plugins/CarlaTools/Source/CarlaTools/Private/OpenDriveToMap.cpp +++ b/Unreal/CarlaUE4/Plugins/CarlaTools/Source/CarlaTools/Private/OpenDriveToMap.cpp @@ -363,7 +363,10 @@ void UOpenDriveToMap::GenerateTile(){ UEditorLoadingAndSavingUtils::SaveDirtyPackages(true, true); UEditorLevelLibrary::SaveCurrentLevel(); +#if PLATFORM_LINUX RemoveFromRoot(); +#endif + } } From e2ccc3c5190049d2f8972207025039b7050a48f6 Mon Sep 17 00:00:00 2001 From: joel-mb Date: Tue, 21 May 2024 15:05:12 +0200 Subject: [PATCH 28/99] revert patchelf version to 0.12 (#7681) --- Util/BuildTools/Setup.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Util/BuildTools/Setup.sh b/Util/BuildTools/Setup.sh index f68dd378f..64774d017 100755 --- a/Util/BuildTools/Setup.sh +++ b/Util/BuildTools/Setup.sh @@ -761,7 +761,7 @@ cp -p ${PROJ_SERVER_LIB} ${LIBCARLA_INSTALL_SERVER_FOLDER}/lib/ # -- Get and compile patchelf -------------------------------------------------- # ============================================================================== -PATCHELF_VERSION=0.14 +PATCHELF_VERSION=0.12 PATCHELF_REPO=https://github.com/NixOS/patchelf/archive/${PATCHELF_VERSION}.tar.gz PATCHELF_TAR=${PATCHELF_VERSION}.tar.gz From 7b2ff04496f4981d15c221abb3166b1851c6061a Mon Sep 17 00:00:00 2001 From: Aaron Date: Thu, 23 May 2024 14:29:09 +0200 Subject: [PATCH 29/99] Not tests V2X tick --- PythonAPI/test/smoke/test_sensor_tick_time.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/PythonAPI/test/smoke/test_sensor_tick_time.py b/PythonAPI/test/smoke/test_sensor_tick_time.py index a7d144610..b98c04007 100644 --- a/PythonAPI/test/smoke/test_sensor_tick_time.py +++ b/PythonAPI/test/smoke/test_sensor_tick_time.py @@ -38,7 +38,9 @@ class TestSensorTickTime(SyncSmokeTest): "sensor.camera.semantic_segmentation", "sensor.camera.dvs", "sensor.other.obstacle", - "sensor.camera.instance_segmentation" + "sensor.camera.instance_segmentation", + "sensor.other.v2x", + "sensor.other.v2x_custom" } spawned_sensors = [] sensor_tick = 1.0 @@ -64,5 +66,3 @@ class TestSensorTickTime(SyncSmokeTest): self.assertEqual(sensor.num_ticks, num_sensor_ticks, "\n\n {} does not match tick count".format(sensor.bp_sensor.id)) sensor.destroy() - - From a2ae705126151af29c5169e56afdfa6507063973 Mon Sep 17 00:00:00 2001 From: Blyron Date: Tue, 28 May 2024 11:53:19 +0200 Subject: [PATCH 30/99] hot fix ignore spectator variable on replayer --- .../Plugins/Carla/Source/Carla/Recorder/CarlaReplayer.cpp | 2 +- .../Carla/Source/Carla/Recorder/CarlaReplayerHelper.cpp | 7 ++++++- .../Carla/Source/Carla/Recorder/CarlaReplayerHelper.h | 2 +- 3 files changed, 8 insertions(+), 3 deletions(-) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Recorder/CarlaReplayer.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Recorder/CarlaReplayer.cpp index 64e208b55..0a2474e60 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Recorder/CarlaReplayer.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Recorder/CarlaReplayer.cpp @@ -808,7 +808,7 @@ void CarlaReplayer::InterpolatePosition( double DeltaTime) { // call the callback - Helper.ProcessReplayerPosition(Pos1, Pos2, Per, DeltaTime); + Helper.ProcessReplayerPosition(Pos1, Pos2, Per, DeltaTime, IgnoreSpectator); } // tick for the replayer diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Recorder/CarlaReplayerHelper.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Recorder/CarlaReplayerHelper.cpp index 9bfa120f6..65f37f975 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Recorder/CarlaReplayerHelper.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Recorder/CarlaReplayerHelper.cpp @@ -296,7 +296,7 @@ bool CarlaReplayerHelper::ProcessReplayerEventParent(uint32_t ChildId, uint32_t } // reposition actors -bool CarlaReplayerHelper::ProcessReplayerPosition(CarlaRecorderPosition Pos1, CarlaRecorderPosition Pos2, double Per, double DeltaTime) +bool CarlaReplayerHelper::ProcessReplayerPosition(CarlaRecorderPosition Pos1, CarlaRecorderPosition Pos2, double Per, double DeltaTime, bool bIgnoreSpectator) { check(Episode != nullptr); FCarlaActor* CarlaActor = Episode->FindCarlaActor(Pos1.DatabaseId); @@ -304,6 +304,11 @@ bool CarlaReplayerHelper::ProcessReplayerPosition(CarlaRecorderPosition Pos1, Ca FRotator Rotation; if(CarlaActor) { + //Hot fix to avoid spectator we should investigate why this case is possible here + if(bIgnoreSpectator && CarlaActor->GetActor()->GetClass()->GetFName().ToString().Contains("Spectator")) + { + return false; + } // check to assign first position or interpolate between both if (Per == 0.0) { diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Recorder/CarlaReplayerHelper.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Recorder/CarlaReplayerHelper.h index d4379dddd..42a27c85a 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Recorder/CarlaReplayerHelper.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Recorder/CarlaReplayerHelper.h @@ -52,7 +52,7 @@ public: bool ProcessReplayerEventParent(uint32_t ChildId, uint32_t ParentId); // reposition actors - bool ProcessReplayerPosition(CarlaRecorderPosition Pos1, CarlaRecorderPosition Pos2, double Per, double DeltaTime); + bool ProcessReplayerPosition(CarlaRecorderPosition Pos1, CarlaRecorderPosition Pos2, double Per, double DeltaTime, bool bIgnoreSpectator); // replay event for traffic light state bool ProcessReplayerStateTrafficLight(CarlaRecorderStateTrafficLight State); From e6ba65db2190856d319491687d549070a87609a3 Mon Sep 17 00:00:00 2001 From: Blyron Date: Thu, 30 May 2024 14:59:57 +0200 Subject: [PATCH 31/99] Uses switches depending on line type --- LibCarla/source/carla/road/MeshFactory.cpp | 145 +++++++++++++++------ LibCarla/source/carla/road/MeshFactory.h | 10 +- 2 files changed, 113 insertions(+), 42 deletions(-) diff --git a/LibCarla/source/carla/road/MeshFactory.cpp b/LibCarla/source/carla/road/MeshFactory.cpp index 8d7019ebb..0c2d08515 100644 --- a/LibCarla/source/carla/road/MeshFactory.cpp +++ b/LibCarla/source/carla/road/MeshFactory.cpp @@ -206,23 +206,33 @@ namespace geom { size_t PosToAdd = it - redirections.begin(); Mesh out_mesh; - if(lane_pair.second.GetType() == road::Lane::LaneType::Driving ){ - out_mesh += *GenerateTesselated(lane_pair.second); - }else{ - out_mesh += *GenerateSidewalk(lane_pair.second); + switch(lane_pair.second.GetType()) + { + case road::Lane::LaneType::Driving: + case road::Lane::LaneType::Parking: + case road::Lane::LaneType::Bidirectional: + { + out_mesh += *GenerateTesselated(lane_pair.second); + break; + } + case road::Lane::LaneType::Shoulder: + case road::Lane::LaneType::Sidewalk: + case road::Lane::LaneType::Biking: + { + out_mesh += *GenerateSidewalk(lane_pair.second); + break; + } + default: + { + out_mesh += *GenerateTesselated(lane_pair.second); + break; + } } if( result[lane_pair.second.GetType()].size() <= PosToAdd ){ result[lane_pair.second.GetType()].push_back(std::make_unique(out_mesh)); } else { - uint32_t verticesinwidth = 0; - if(lane_pair.second.GetType() == road::Lane::LaneType::Driving) { - verticesinwidth = vertices_in_width; - }else if(lane_pair.second.GetType() == road::Lane::LaneType::Sidewalk){ - verticesinwidth = 6; - }else{ - verticesinwidth = 2; - } + uint32_t verticesinwidth = SelectVerticesInWidth(vertices_in_width, lane_pair.second.GetType()); (result[lane_pair.second.GetType()][PosToAdd])->ConcatMesh(out_mesh, verticesinwidth); } } @@ -548,12 +558,28 @@ std::map>> MeshFactory: for (auto &&lane_pair : lane_section.GetLanes()) { Mesh lane_section_mesh; - if(lane_pair.second.GetType() == road::Lane::LaneType::Driving ){ - lane_section_mesh += *GenerateTesselated(lane_pair.second, s_current, s_until); - }else{ - lane_section_mesh += *GenerateSidewalk(lane_pair.second, s_current, s_until); + switch(lane_pair.second.GetType()) + { + case road::Lane::LaneType::Driving: + case road::Lane::LaneType::Parking: + case road::Lane::LaneType::Bidirectional: + { + lane_section_mesh += *GenerateTesselated(lane_pair.second, s_current, s_until); + break; + } + case road::Lane::LaneType::Shoulder: + case road::Lane::LaneType::Sidewalk: + case road::Lane::LaneType::Biking: + { + lane_section_mesh += *GenerateSidewalk(lane_pair.second, s_current, s_until); + break; + } + default: + { + lane_section_mesh += *GenerateTesselated(lane_pair.second, s_current, s_until); + break; + } } - auto it = std::find(redirections.begin(), redirections.end(), lane_pair.first); if (it == redirections.end()) { redirections.push_back(lane_pair.first); @@ -564,14 +590,7 @@ std::map>> MeshFactory: if (mesh_uptr_list[lane_pair.second.GetType()].size() <= PosToAdd) { mesh_uptr_list[lane_pair.second.GetType()].push_back(std::make_unique(lane_section_mesh)); } else { - uint32_t verticesinwidth = 0; - if(lane_pair.second.GetType() == road::Lane::LaneType::Driving) { - verticesinwidth = vertices_in_width; - }else if(lane_pair.second.GetType() == road::Lane::LaneType::Sidewalk){ - verticesinwidth = 6; - }else{ - verticesinwidth = 2; - } + uint32_t verticesinwidth = SelectVerticesInWidth(vertices_in_width, lane_pair.second.GetType()); (mesh_uptr_list[lane_pair.second.GetType()][PosToAdd])->ConcatMesh(lane_section_mesh, verticesinwidth); } } @@ -580,10 +599,27 @@ std::map>> MeshFactory: if (s_end - s_current > EPSILON) { for (auto &&lane_pair : lane_section.GetLanes()) { Mesh lane_section_mesh; - if(lane_pair.second.GetType() == road::Lane::LaneType::Driving ){ - lane_section_mesh += *GenerateTesselated(lane_pair.second, s_current, s_end); - }else{ - lane_section_mesh += *GenerateSidewalk(lane_pair.second, s_current, s_end); + switch(lane_pair.second.GetType()) + { + case road::Lane::LaneType::Driving: + case road::Lane::LaneType::Parking: + case road::Lane::LaneType::Bidirectional: + { + lane_section_mesh += *GenerateTesselated(lane_pair.second, s_current, s_end); + break; + } + case road::Lane::LaneType::Shoulder: + case road::Lane::LaneType::Sidewalk: + case road::Lane::LaneType::Biking: + { + lane_section_mesh += *GenerateSidewalk(lane_pair.second, s_current, s_end); + break; + } + default: + { + lane_section_mesh += *GenerateTesselated(lane_pair.second, s_current, s_end); + break; + } } auto it = std::find(redirections.begin(), redirections.end(), lane_pair.first); @@ -598,13 +634,7 @@ std::map>> MeshFactory: mesh_uptr_list[lane_pair.second.GetType()].push_back(std::make_unique(lane_section_mesh)); } else { uint32_t verticesinwidth = 0; - if(lane_pair.second.GetType() == road::Lane::LaneType::Driving) { - verticesinwidth = vertices_in_width; - }else if(lane_pair.second.GetType() == road::Lane::LaneType::Sidewalk){ - verticesinwidth = 6; - }else{ - verticesinwidth = 2; - } + *(mesh_uptr_list[lane_pair.second.GetType()][PosToAdd]) += lane_section_mesh; } } @@ -725,9 +755,20 @@ std::map>> MeshFactory: for (auto&& lane_section : road.GetLaneSections()) { for (auto&& lane : lane_section.GetLanes()) { if (lane.first != 0) { - if(lane.second.GetType() == road::Lane::LaneType::Driving ){ - GenerateLaneMarksForNotCenterLine(lane_section, lane.second, inout, outinfo); - outinfo.push_back("white"); + switch(lane.second.GetType()) + { + case road::Lane::LaneType::Driving: + case road::Lane::LaneType::Parking: + case road::Lane::LaneType::Bidirectional: + { + GenerateLaneMarksForNotCenterLine(lane_section, lane.second, inout, outinfo); + outinfo.push_back("white"); + break; + } + default: + { + break; + } } } else { if(lane.second.GetType() == road::Lane::LaneType::None ){ @@ -1131,6 +1172,32 @@ std::map>> MeshFactory: return std::make_unique(out_mesh); } + uint32_t MeshFactory::SelectVerticesInWidth(uint32_t default_num_vertices, road::Lane::LaneType type) + { + switch(type) + { + case road::Lane::LaneType::Driving: + case road::Lane::LaneType::Parking: + case road::Lane::LaneType::Bidirectional: + { + return default_num_vertices; + break; + } + case road::Lane::LaneType::Shoulder: + case road::Lane::LaneType::Sidewalk: + case road::Lane::LaneType::Biking: + { + return 6; + break; + } + default: + { + return 2; + break; + } + } + } + std::pair MeshFactory::ComputeEdgesForLanemark( const road::LaneSection& lane_section, const road::Lane& lane, diff --git a/LibCarla/source/carla/road/MeshFactory.h b/LibCarla/source/carla/road/MeshFactory.h index 42bc60ea1..00d3a712e 100644 --- a/LibCarla/source/carla/road/MeshFactory.h +++ b/LibCarla/source/carla/road/MeshFactory.h @@ -129,9 +129,7 @@ namespace geom { const road::Lane& lane, std::vector>& inout, std::vector& outinfo ) const; - // ========================================================================= - // -- Generation parameters ------------------------------------------------ - // ========================================================================= + /// Parameters for the road generation struct RoadParameters { @@ -148,6 +146,12 @@ namespace geom { RoadParameters road_param; + + // ========================================================================= + // -- Helper functions ------------------------------------------------ + // ========================================================================= + + static uint32_t SelectVerticesInWidth(uint32_t default_num_vertices, road::Lane::LaneType type); private: // Calculate the points on both sides of the lane mark for the specified s_current From e7d13e6c0e873eb26c6843162706635d937b4e9f Mon Sep 17 00:00:00 2001 From: Blyron Date: Thu, 30 May 2024 15:03:31 +0200 Subject: [PATCH 32/99] Removed unused variable --- LibCarla/source/carla/road/MeshFactory.cpp | 2 -- LibCarla/source/carla/road/MeshFactory.h | 5 ++++- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/LibCarla/source/carla/road/MeshFactory.cpp b/LibCarla/source/carla/road/MeshFactory.cpp index 0c2d08515..92627a79c 100644 --- a/LibCarla/source/carla/road/MeshFactory.cpp +++ b/LibCarla/source/carla/road/MeshFactory.cpp @@ -633,8 +633,6 @@ std::map>> MeshFactory: if (mesh_uptr_list[lane_pair.second.GetType()].size() <= PosToAdd) { mesh_uptr_list[lane_pair.second.GetType()].push_back(std::make_unique(lane_section_mesh)); } else { - uint32_t verticesinwidth = 0; - *(mesh_uptr_list[lane_pair.second.GetType()][PosToAdd]) += lane_section_mesh; } } diff --git a/LibCarla/source/carla/road/MeshFactory.h b/LibCarla/source/carla/road/MeshFactory.h index 00d3a712e..aacb07584 100644 --- a/LibCarla/source/carla/road/MeshFactory.h +++ b/LibCarla/source/carla/road/MeshFactory.h @@ -129,7 +129,10 @@ namespace geom { const road::Lane& lane, std::vector>& inout, std::vector& outinfo ) const; - + + // ========================================================================= + // -- Generation parameters ------------------------------------------------ + // ========================================================================= /// Parameters for the road generation struct RoadParameters { From 317037a31eaa1d2e96226ee5e342b912967ded06 Mon Sep 17 00:00:00 2001 From: Blyron <53337103+Blyron@users.noreply.github.com> Date: Fri, 31 May 2024 09:42:30 +0200 Subject: [PATCH 33/99] Removing useless code MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Xavier Solé Nogués --- LibCarla/source/carla/road/MeshFactory.cpp | 7 ------- 1 file changed, 7 deletions(-) diff --git a/LibCarla/source/carla/road/MeshFactory.cpp b/LibCarla/source/carla/road/MeshFactory.cpp index 92627a79c..b01828915 100644 --- a/LibCarla/source/carla/road/MeshFactory.cpp +++ b/LibCarla/source/carla/road/MeshFactory.cpp @@ -763,10 +763,6 @@ std::map>> MeshFactory: outinfo.push_back("white"); break; } - default: - { - break; - } } } else { if(lane.second.GetType() == road::Lane::LaneType::None ){ @@ -1179,19 +1175,16 @@ std::map>> MeshFactory: case road::Lane::LaneType::Bidirectional: { return default_num_vertices; - break; } case road::Lane::LaneType::Shoulder: case road::Lane::LaneType::Sidewalk: case road::Lane::LaneType::Biking: { return 6; - break; } default: { return 2; - break; } } } From 6aed213f3622dff6dac8bc6cf96193013b3188de Mon Sep 17 00:00:00 2001 From: LuisPovedaCano Date: Fri, 31 May 2024 10:01:30 +0200 Subject: [PATCH 34/99] fixed lidar in replayer mode with vehicles and walkers --- .../Carla/Source/Carla/Recorder/CarlaReplayerHelper.cpp | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Recorder/CarlaReplayerHelper.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Recorder/CarlaReplayerHelper.cpp index 65f37f975..8b1ff4282 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Recorder/CarlaReplayerHelper.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Recorder/CarlaReplayerHelper.cpp @@ -202,7 +202,7 @@ std::pair CarlaReplayerHelper::ProcessReplayerEventAdd( } // check to ignore Hero or Spectator - if ((bIgnoreHero && IsHero) || + if ((bIgnoreHero && IsHero) || (bIgnoreSpectator && ActorDesc.Id.StartsWith("spectator"))) { return std::make_pair(3, 0); @@ -227,7 +227,11 @@ std::pair CarlaReplayerHelper::ProcessReplayerEventAdd( // disable physics SetActorSimulatePhysics(result.second, false); // disable collisions - result.second->GetActor()->SetActorEnableCollision(false); + result.second->GetActor()->SetActorEnableCollision(true); + auto RootComponent = Cast( + result.second->GetActor()->GetRootComponent()); + RootComponent->SetSimulatePhysics(false); + RootComponent->SetCollisionEnabled(ECollisionEnabled::NoCollision); // disable autopilot for vehicles if (result.second->GetActorType() == FCarlaActor::ActorType::Vehicle) SetActorAutopilot(result.second, false, false); From d5c37f71b76462d23df9736a8efacdae30311d76 Mon Sep 17 00:00:00 2001 From: Daraan Date: Fri, 31 May 2024 12:04:04 +0200 Subject: [PATCH 35/99] Corrected information that Sensor.is_listening is a method (#7439) Co-authored-by: Blyron <53337103+Blyron@users.noreply.github.com> --- CHANGELOG.md | 1 + Docs/core_sensors.md | 3 ++- PythonAPI/carla/source/libcarla/Sensor.cpp | 1 - PythonAPI/docs/sensor.yml | 13 ++++++------- 4 files changed, 9 insertions(+), 9 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index ed7c3b58c..d04ec9fc3 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -14,6 +14,7 @@ * Added possibility to change gravity variable in imui sensor for the accelerometer * Fixed ROS2 native extension build error when ROS2 is installed in the system. * ROS2Native: Force fast-dds dependencies download to avoid build crash when boost_asio and tinyxml2 are not installed in Linux. + * PythonAPI `Sensor.is_listening` was defined twice (property and method), cleaned and clarified it as a method. * Added V2X sensors for cooperative awareness message and custom user-defined messages to support vehicle-to-vehicle communication ## CARLA 0.9.15 diff --git a/Docs/core_sensors.md b/Docs/core_sensors.md index 4ca9c1603..0a3ab237c 100644 --- a/Docs/core_sensors.md +++ b/Docs/core_sensors.md @@ -96,7 +96,8 @@ Sensor data differs a lot between sensor types. Take a look at the [sensors refe !!! Important - `is_listening` is a __sensor attribute__ that enables/disables data listening at will. + `is_listening()` is a __sensor method__ to check whether the sensor has a callback registered by `listen`. + `stop()` is a __sensor method__ to stop the sensor from listening. `sensor_tick` is a __blueprint attribute__ that sets the simulation time between data received. --- diff --git a/PythonAPI/carla/source/libcarla/Sensor.cpp b/PythonAPI/carla/source/libcarla/Sensor.cpp index 779738788..020b71592 100644 --- a/PythonAPI/carla/source/libcarla/Sensor.cpp +++ b/PythonAPI/carla/source/libcarla/Sensor.cpp @@ -26,7 +26,6 @@ void export_sensor() { namespace cc = carla::client; class_, boost::noncopyable, boost::shared_ptr>("Sensor", no_init) - .add_property("is_listening", &cc::Sensor::IsListening) .def("listen", &SubscribeToStream, (arg("callback"))) .def("is_listening", &cc::Sensor::IsListening) .def("stop", &cc::Sensor::Stop) diff --git a/PythonAPI/docs/sensor.yml b/PythonAPI/docs/sensor.yml index d1f118978..06e78c2a5 100644 --- a/PythonAPI/docs/sensor.yml +++ b/PythonAPI/docs/sensor.yml @@ -23,13 +23,6 @@ - [Collision detector](ref_sensors.md#collision-detector). - [Lane invasion detector](ref_sensors.md#lane-invasion-detector). - [Obstacle detector](ref_sensors.md#obstacle-detector). - - # - PROPERTIES ------------------------- - instance_variables: - - var_name: is_listening - type: boolean - doc: > - When True the sensor will be waiting for data. # - METHODS ---------------------------- methods: - def_name: listen @@ -44,6 +37,8 @@ - def_name: is_listening doc: > Returns whether the sensor is in a listening state. + return: + bool # -------------------------------------- - def_name: stop doc: > @@ -60,6 +55,8 @@ - def_name: is_enabled_for_ros doc: > Returns if the sensor is enabled or not to publish in ROS2 if there is no any listen to it. + return: + bool # -------------------------------------- - def_name: listen_to_gbuffer params: @@ -83,6 +80,8 @@ The ID of the target Unreal Engine GBuffer texture. doc: > Returns whether the sensor is in a listening state for a specific GBuffer texture. + return: + bool # -------------------------------------- - def_name: stop_gbuffer params: From 01b1ede51ac463fb59192a7a6bea8f6cda818b04 Mon Sep 17 00:00:00 2001 From: joel-mb Date: Fri, 31 May 2024 13:36:46 +0200 Subject: [PATCH 36/99] Expose Telemetry Data (#5153) * expose telemetry data to the client * CHANGELOG updated * minor fixes * Added new telemetry parameters: * Exposed omega instead of rpm * Added tire_load, normalized_long_force, normalized_lat_force --------- Co-authored-by: Blyron <53337103+Blyron@users.noreply.github.com> --- CHANGELOG.md | 2 + LibCarla/source/carla/client/Vehicle.cpp | 4 + LibCarla/source/carla/client/Vehicle.h | 7 + .../source/carla/client/detail/Client.cpp | 5 + LibCarla/source/carla/client/detail/Client.h | 3 + .../source/carla/client/detail/Simulator.h | 4 + .../source/carla/rpc/VehicleTelemetryData.h | 123 ++++++++++++++++++ .../source/carla/rpc/WheelTelemetryData.h | 120 +++++++++++++++++ PythonAPI/carla/source/libcarla/Actor.cpp | 1 + PythonAPI/carla/source/libcarla/Control.cpp | 123 ++++++++++++++++++ .../Carla/Source/Carla/Actor/CarlaActor.cpp | 19 +++ .../Carla/Source/Carla/Actor/CarlaActor.h | 8 ++ .../Carla/Source/Carla/Server/CarlaServer.cpp | 26 ++++ .../Carla/Vehicle/CarlaWheeledVehicle.cpp | 50 +++++++ .../Carla/Vehicle/CarlaWheeledVehicle.h | 4 + .../Carla/Vehicle/VehicleTelemetryData.h | 78 +++++++++++ 16 files changed, 577 insertions(+) create mode 100644 LibCarla/source/carla/rpc/VehicleTelemetryData.h create mode 100644 LibCarla/source/carla/rpc/WheelTelemetryData.h create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/VehicleTelemetryData.h diff --git a/CHANGELOG.md b/CHANGELOG.md index d04ec9fc3..bde484631 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -14,9 +14,11 @@ * Added possibility to change gravity variable in imui sensor for the accelerometer * Fixed ROS2 native extension build error when ROS2 is installed in the system. * ROS2Native: Force fast-dds dependencies download to avoid build crash when boost_asio and tinyxml2 are not installed in Linux. + * Added API function `get_telemetry_data` to the vehicle actor. * PythonAPI `Sensor.is_listening` was defined twice (property and method), cleaned and clarified it as a method. * Added V2X sensors for cooperative awareness message and custom user-defined messages to support vehicle-to-vehicle communication + ## CARLA 0.9.15 * Added Digital Twins feature version 0.1. Now you can create your own map based on OpenStreetMaps diff --git a/LibCarla/source/carla/client/Vehicle.cpp b/LibCarla/source/carla/client/Vehicle.cpp index 4a0c2ebd4..b24347e07 100644 --- a/LibCarla/source/carla/client/Vehicle.cpp +++ b/LibCarla/source/carla/client/Vehicle.cpp @@ -44,6 +44,10 @@ namespace client { } } + Vehicle::TelemetryData Vehicle::GetTelemetryData() const { + return GetEpisode().Lock()->GetVehicleTelemetryData(*this); + } + void Vehicle::ShowDebugTelemetry(bool enabled) { GetEpisode().Lock()->ShowVehicleDebugTelemetry(*this, enabled); } diff --git a/LibCarla/source/carla/client/Vehicle.h b/LibCarla/source/carla/client/Vehicle.h index 2fb7c2925..b9fe883a0 100644 --- a/LibCarla/source/carla/client/Vehicle.h +++ b/LibCarla/source/carla/client/Vehicle.h @@ -14,6 +14,7 @@ #include "carla/rpc/VehicleDoor.h" #include "carla/rpc/VehicleLightState.h" #include "carla/rpc/VehiclePhysicsControl.h" +#include "carla/rpc/VehicleTelemetryData.h" #include "carla/rpc/VehicleWheels.h" #include "carla/trafficmanager/TrafficManager.h" @@ -35,6 +36,7 @@ namespace client { using Control = rpc::VehicleControl; using AckermannControl = rpc::VehicleAckermannControl; using PhysicsControl = rpc::VehiclePhysicsControl; + using TelemetryData = rpc::VehicleTelemetryData; using LightState = rpc::VehicleLightState::LightState; using TM = traffic_manager::TrafficManager; using VehicleDoor = rpc::VehicleDoor; @@ -46,6 +48,11 @@ namespace client { /// Switch on/off this vehicle's autopilot. void SetAutopilot(bool enabled = true, uint16_t tm_port = TM_DEFAULT_PORT); + /// Return the telemetry data for this vehicle. + /// + /// @warning This function does call the simulator. + TelemetryData GetTelemetryData() const; + /// Switch on/off this vehicle's autopilot. void ShowDebugTelemetry(bool enabled = true); diff --git a/LibCarla/source/carla/client/detail/Client.cpp b/LibCarla/source/carla/client/detail/Client.cpp index 72b9e705e..49cf59e00 100644 --- a/LibCarla/source/carla/client/detail/Client.cpp +++ b/LibCarla/source/carla/client/detail/Client.cpp @@ -481,6 +481,11 @@ namespace detail { _pimpl->AsyncCall("set_actor_autopilot", vehicle, enabled); } + rpc::VehicleTelemetryData Client::GetVehicleTelemetryData( + rpc::ActorId vehicle) const { + return _pimpl->CallAndWait("get_telemetry_data", vehicle); + } + void Client::ShowVehicleDebugTelemetry(rpc::ActorId vehicle, const bool enabled) { _pimpl->AsyncCall("show_vehicle_debug_telemetry", vehicle, enabled); } diff --git a/LibCarla/source/carla/client/detail/Client.h b/LibCarla/source/carla/client/detail/Client.h index 064cd2c86..ffd3c8fba 100644 --- a/LibCarla/source/carla/client/detail/Client.h +++ b/LibCarla/source/carla/client/detail/Client.h @@ -29,6 +29,7 @@ #include "carla/rpc/VehicleLightStateList.h" #include "carla/rpc/VehicleLightState.h" #include "carla/rpc/VehiclePhysicsControl.h" +#include "carla/rpc/VehicleTelemetryData.h" #include "carla/rpc/VehicleWheels.h" #include "carla/rpc/WeatherParameters.h" #include "carla/rpc/Texture.h" @@ -285,6 +286,8 @@ namespace detail { rpc::ActorId vehicle, bool enabled); + rpc::VehicleTelemetryData GetVehicleTelemetryData(rpc::ActorId vehicle) const; + void ShowVehicleDebugTelemetry( rpc::ActorId vehicle, bool enabled); diff --git a/LibCarla/source/carla/client/detail/Simulator.h b/LibCarla/source/carla/client/detail/Simulator.h index 7dea3ced4..0ff8f3c17 100644 --- a/LibCarla/source/carla/client/detail/Simulator.h +++ b/LibCarla/source/carla/client/detail/Simulator.h @@ -525,6 +525,10 @@ namespace detail { _client.SetActorAutopilot(vehicle.GetId(), enabled); } + rpc::VehicleTelemetryData GetVehicleTelemetryData(const Vehicle &vehicle) const { + return _client.GetVehicleTelemetryData(vehicle.GetId()); + } + void ShowVehicleDebugTelemetry(Vehicle &vehicle, bool enabled = true) { _client.ShowVehicleDebugTelemetry(vehicle.GetId(), enabled); } diff --git a/LibCarla/source/carla/rpc/VehicleTelemetryData.h b/LibCarla/source/carla/rpc/VehicleTelemetryData.h new file mode 100644 index 000000000..7be84e8a3 --- /dev/null +++ b/LibCarla/source/carla/rpc/VehicleTelemetryData.h @@ -0,0 +1,123 @@ +// Copyright (c) 2022 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 . + +#pragma once + +#include "carla/MsgPack.h" +#include "carla/rpc/WheelTelemetryData.h" + +#include + +namespace carla { +namespace rpc { + class VehicleTelemetryData { + public: + + VehicleTelemetryData() = default; + + VehicleTelemetryData( + float speed, + float steer, + float throttle, + float brake, + float engine_rpm, + int32_t gear, + float drag, + std::vector wheels) + : speed(speed), + steer(steer), + throttle(throttle), + brake(brake), + engine_rpm(engine_rpm), + gear(gear), + drag(drag), + wheels(wheels) {} + + const std::vector &GetWheels() const { + return wheels; + } + + void SetWheels(std::vector &in_wheels) { + wheels = in_wheels; + } + + float speed = 0.0f; + float steer = 0.0f; + float throttle = 0.0f; + float brake = 0.0f; + float engine_rpm = 0.0f; + int32_t gear = 0.0f; + float drag = 0.0f; + std::vector wheels; + + bool operator!=(const VehicleTelemetryData &rhs) const { + return + speed != rhs.speed || + steer != rhs.steer || + throttle != rhs.throttle || + brake != rhs.brake || + engine_rpm != rhs.engine_rpm || + gear != rhs.gear || + drag != rhs.drag || + wheels != rhs.wheels; + } + + bool operator==(const VehicleTelemetryData &rhs) const { + return !(*this != rhs); + } + +#ifdef LIBCARLA_INCLUDED_FROM_UE4 + + VehicleTelemetryData(const FVehicleTelemetryData &TelemetryData) { + speed = TelemetryData.Speed; + steer = TelemetryData.Steer; + throttle = TelemetryData.Throttle; + brake = TelemetryData.Brake; + engine_rpm = TelemetryData.EngineRPM; + gear = TelemetryData.Gear; + drag = TelemetryData.Drag; + + // Wheels Setup + wheels = std::vector(); + for (const auto &Wheel : TelemetryData.Wheels) { + wheels.push_back(WheelTelemetryData(Wheel)); + } + } + + operator FVehicleTelemetryData() const { + FVehicleTelemetryData TelemetryData; + + TelemetryData.Speed = speed; + TelemetryData.Steer = steer; + TelemetryData.Throttle = throttle; + TelemetryData.Brake = brake; + TelemetryData.EngineRPM = engine_rpm; + TelemetryData.Gear = gear; + TelemetryData.Drag = drag; + + TArray Wheels; + for (const auto &wheel : wheels) { + Wheels.Add(FWheelTelemetryData(wheel)); + } + TelemetryData.Wheels = Wheels; + + return TelemetryData; + } + +#endif + + MSGPACK_DEFINE_ARRAY(speed, + steer, + throttle, + brake, + engine_rpm, + gear, + drag, + wheels); + }; + +} // namespace rpc +} // namespace carla diff --git a/LibCarla/source/carla/rpc/WheelTelemetryData.h b/LibCarla/source/carla/rpc/WheelTelemetryData.h new file mode 100644 index 000000000..ce7df7b10 --- /dev/null +++ b/LibCarla/source/carla/rpc/WheelTelemetryData.h @@ -0,0 +1,120 @@ +// Copyright (c) 2022 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 . + +#pragma once + +#include "carla/MsgPack.h" + +namespace carla { +namespace rpc { + + class WheelTelemetryData { + public: + + WheelTelemetryData() = default; + + WheelTelemetryData( + float tire_friction, + float lat_slip, + float long_slip, + float omega, + float tire_load, + float normalized_tire_load, + float torque, + float long_force, + float lat_force, + float normalized_long_force, + float normalized_lat_force) + : tire_friction(tire_friction), + lat_slip(lat_slip), + long_slip(long_slip), + omega(omega), + tire_load(tire_load), + normalized_tire_load(normalized_tire_load), + torque(torque), + long_force(long_force), + lat_force(lat_force), + normalized_long_force(normalized_long_force), + normalized_lat_force(normalized_lat_force) {} + + float tire_friction = 0.0f; + float lat_slip = 0.0f; + float long_slip = 0.0f; + float omega = 0.0f; + float tire_load = 0.0f; + float normalized_tire_load = 0.0f; + float torque = 0.0f; + float long_force = 0.0f; + float lat_force = 0.0f; + float normalized_long_force = 0.0f; + float normalized_lat_force = 0.0f; + + bool operator!=(const WheelTelemetryData &rhs) const { + return + tire_friction != rhs.tire_friction || + lat_slip != rhs.lat_slip || + long_slip != rhs.long_slip || + omega != rhs.omega || + tire_load != rhs.tire_load || + normalized_tire_load != rhs.normalized_tire_load || + torque != rhs.torque || + long_force != rhs.long_force || + lat_force != rhs.lat_force || + normalized_long_force != rhs.normalized_long_force || + normalized_lat_force != rhs.normalized_lat_force; + } + + bool operator==(const WheelTelemetryData &rhs) const { + return !(*this != rhs); + } +#ifdef LIBCARLA_INCLUDED_FROM_UE4 + + WheelTelemetryData(const FWheelTelemetryData &TelemetryData) + : tire_friction(TelemetryData.TireFriction), + lat_slip(TelemetryData.LatSlip), + long_slip(TelemetryData.LongSlip), + omega(TelemetryData.Omega), + tire_load(TelemetryData.TireLoad), + normalized_tire_load(TelemetryData.NormalizedTireLoad), + torque(TelemetryData.Torque), + long_force(TelemetryData.LongForce), + lat_force(TelemetryData.LatForce), + normalized_long_force(TelemetryData.NormalizedLongForce), + normalized_lat_force(TelemetryData.NormalizedLatForce) {} + + operator FWheelTelemetryData() const { + FWheelTelemetryData TelemetryData; + TelemetryData.TireFriction = tire_friction; + TelemetryData.LatSlip = lat_slip; + TelemetryData.LongSlip = long_slip; + TelemetryData.Omega = omega; + TelemetryData.TireLoad = tire_load; + TelemetryData.NormalizedTireLoad = normalized_tire_load; + TelemetryData.Torque = torque; + TelemetryData.LongForce = long_force; + TelemetryData.LatForce = lat_force; + TelemetryData.NormalizedLongForce = normalized_long_force; + TelemetryData.NormalizedLatForce = normalized_lat_force; + + return TelemetryData; + } +#endif + + MSGPACK_DEFINE_ARRAY(tire_friction, + lat_slip, + long_slip, + omega, + tire_load, + normalized_tire_load, + torque, + long_force, + lat_force, + normalized_long_force, + normalized_lat_force) + }; + +} // namespace rpc +} // namespace carla diff --git a/PythonAPI/carla/source/libcarla/Actor.cpp b/PythonAPI/carla/source/libcarla/Actor.cpp index 26d678460..62dbe05ea 100644 --- a/PythonAPI/carla/source/libcarla/Actor.cpp +++ b/PythonAPI/carla/source/libcarla/Actor.cpp @@ -195,6 +195,7 @@ void export_actor() { .def("apply_ackermann_controller_settings", &cc::Vehicle::ApplyAckermannControllerSettings, (arg("settings"))) .def("get_ackermann_controller_settings", CONST_CALL_WITHOUT_GIL(cc::Vehicle, GetAckermannControllerSettings)) .def("set_autopilot", CALL_WITHOUT_GIL_2(cc::Vehicle, SetAutopilot, bool, uint16_t), (arg("enabled") = true, arg("tm_port") = ctm::TM_DEFAULT_PORT)) + .def("get_telemetry_data", CONST_CALL_WITHOUT_GIL(cc::Vehicle, GetTelemetryData)) .def("show_debug_telemetry", &cc::Vehicle::ShowDebugTelemetry, (arg("enabled") = true)) .def("get_speed_limit", &cc::Vehicle::GetSpeedLimit) .def("get_traffic_light_state", &cc::Vehicle::GetTrafficLightState) diff --git a/PythonAPI/carla/source/libcarla/Control.cpp b/PythonAPI/carla/source/libcarla/Control.cpp index 98a0e9bfb..f0e8f5e5d 100644 --- a/PythonAPI/carla/source/libcarla/Control.cpp +++ b/PythonAPI/carla/source/libcarla/Control.cpp @@ -8,7 +8,9 @@ #include #include #include +#include #include +#include #include #include #include @@ -116,6 +118,33 @@ namespace rpc { return out; } + std::ostream &operator<<(std::ostream &out, const WheelTelemetryData &telemetry) { + out << "WheelTelemetryData(tire_friction=" << std::to_string(telemetry.tire_friction) + << ", lat_slip=" << std::to_string(telemetry.lat_slip) + << ", long_slip=" << std::to_string(telemetry.long_slip) + << ", omega=" << std::to_string(telemetry.omega) + << ", tire_load=" << std::to_string(telemetry.tire_load) + << ", normalized_tire_load=" << std::to_string(telemetry.normalized_tire_load) + << ", torque=" << std::to_string(telemetry.torque) + << ", long_force=" << std::to_string(telemetry.long_force) + << ", lat_force=" << std::to_string(telemetry.lat_force) + << ", normalized_long_force=" << std::to_string(telemetry.normalized_long_force) + << ", normalized_lat_force=" << std::to_string(telemetry.normalized_lat_force) << ')'; + return out; + } + + std::ostream &operator<<(std::ostream &out, const VehicleTelemetryData &telemetry) { + out << "VehicleTelemetryData(speed=" << std::to_string(telemetry.speed) + << ", steer=" << std::to_string(telemetry.steer) + << ", throttle=" << std::to_string(telemetry.throttle) + << ", brake=" << std::to_string(telemetry.brake) + << ", engine_rpm=" << std::to_string(telemetry.engine_rpm) + << ", gear=" << std::to_string(telemetry.gear) + << ", drag=" << std::to_string(telemetry.drag) + << ", wheels=" << telemetry.wheels << ')'; + return out; + } + std::ostream &operator<<(std::ostream &out, const AckermannControllerSettings &settings) { out << "AckermannControllerSettings(speed_kp=" << std::to_string(settings.speed_kp) << ", speed_ki=" << std::to_string(settings.speed_ki) @@ -264,6 +293,54 @@ boost::python::object VehiclePhysicsControl_init(boost::python::tuple args, boos return res; } +static auto GetWheelsTelemetry(const carla::rpc::VehicleTelemetryData &self) { + const auto &wheels = self.GetWheels(); + boost::python::object get_iter = boost::python::iterator>(); + boost::python::object iter = get_iter(wheels); + return boost::python::list(iter); +} + +static void SetWheelsTelemetry(carla::rpc::VehicleTelemetryData &self, const boost::python::list &list) { + std::vector wheels; + auto length = boost::python::len(list); + for (auto i = 0u; i < length; ++i) { + wheels.push_back(boost::python::extract(list[i])); + } + self.SetWheels(wheels); +} + +boost::python::object VehicleTelemetryData_init(boost::python::tuple args, boost::python::dict kwargs) { + // Args names + const uint32_t NUM_ARGUMENTS = 7; + const char *args_names[NUM_ARGUMENTS] = { + "speed", + "steer", + "throttle", + "brake", + "engine_rpm", + "gear", + "wheels" + }; + + boost::python::object self = args[0]; + args = boost::python::tuple(args.slice(1, boost::python::_)); + + auto res = self.attr("__init__")(); + if (len(args) > 0) { + for (unsigned int i = 0; i < len(args); ++i) { + self.attr(args_names[i]) = args[i]; + } + } + + for (unsigned int i = 0; i < NUM_ARGUMENTS; ++i) { + if (kwargs.contains(args_names[i])) { + self.attr(args_names[i]) = kwargs[args_names[i]]; + } + } + + return res; +} + static auto GetBonesTransform(const carla::rpc::WalkerBoneControlIn &self) { const std::vector &bone_transform_data = self.bone_transforms; boost::python::object get_iter = @@ -507,4 +584,50 @@ void export_control() { .def("__ne__", &cr::VehiclePhysicsControl::operator!=) .def(self_ns::str(self_ns::self)) ; + + class_("WheelTelemetryData") + .def(init( + (arg("tire_friction")=0.0f, + arg("lat_slip")=0.0f, + arg("long_slip")=0.0f, + arg("omega")=0.0f, + arg("tire_load")=0.0f, + arg("normalized_tire_load")=0.0f, + arg("torque")=0.0f, + arg("long_force")=0.0f, + arg("lat_force")=0.0f, + arg("normalized_long_force")=0.0f, + arg("normalized_lat_force")=0.0f))) + .def_readwrite("tire_friction", &cr::WheelTelemetryData::tire_friction) + .def_readwrite("lat_slip", &cr::WheelTelemetryData::lat_slip) + .def_readwrite("long_slip", &cr::WheelTelemetryData::long_slip) + .def_readwrite("omega", &cr::WheelTelemetryData::omega) + .def_readwrite("tire_load", &cr::WheelTelemetryData::tire_load) + .def_readwrite("normalized_tire_load", &cr::WheelTelemetryData::normalized_tire_load) + .def_readwrite("torque", &cr::WheelTelemetryData::torque) + .def_readwrite("long_force", &cr::WheelTelemetryData::long_force) + .def_readwrite("lat_force", &cr::WheelTelemetryData::lat_force) + .def_readwrite("normalized_long_force", &cr::WheelTelemetryData::normalized_long_force) + .def_readwrite("normalized_lat_force", &cr::WheelTelemetryData::normalized_lat_force) + .def("__eq__", &cr::WheelTelemetryData::operator==) + .def("__ne__", &cr::WheelTelemetryData::operator!=) + .def(self_ns::str(self_ns::self)) + ; + + class_("VehicleTelemetryData", no_init) + .def("__init__", raw_function(VehicleTelemetryData_init)) + .def(init<>()) + .def_readwrite("speed", &cr::VehicleTelemetryData::speed) + .def_readwrite("steer", &cr::VehicleTelemetryData::steer) + .def_readwrite("throttle", &cr::VehicleTelemetryData::throttle) + .def_readwrite("brake", &cr::VehicleTelemetryData::brake) + .def_readwrite("engine_rpm", &cr::VehicleTelemetryData::engine_rpm) + .def_readwrite("gear", &cr::VehicleTelemetryData::gear) + .def_readwrite("drag", &cr::VehicleTelemetryData::drag) + .add_property("wheels", &GetWheelsTelemetry, &SetWheelsTelemetry) + .def("__eq__", &cr::VehicleTelemetryData::operator==) + .def("__ne__", &cr::VehicleTelemetryData::operator!=) + .def(self_ns::str(self_ns::self)) + ; + } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActor.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActor.cpp index dfec0bc43..764f7849d 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActor.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActor.cpp @@ -969,6 +969,25 @@ ECarlaServerResponse FVehicleActor::SetActorAutopilot(bool bEnabled, bool bKeepS return ECarlaServerResponse::Success; } +ECarlaServerResponse FVehicleActor::GetVehicleTelemetryData(FVehicleTelemetryData& TelemetryData) +{ + if (IsDormant()) + { + FVehicleTelemetryData EmptyTelemetryData; + TelemetryData = EmptyTelemetryData; + } + else + { + auto Vehicle = Cast(GetActor()); + if (Vehicle == nullptr) + { + return ECarlaServerResponse::NotAVehicle; + } + TelemetryData = Vehicle->GetVehicleTelemetryData(); + } + return ECarlaServerResponse::Success; +} + ECarlaServerResponse FVehicleActor::ShowVehicleDebugTelemetry(bool bEnabled) { if (IsDormant()) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActor.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActor.h index f7edb4b4f..dcef99905 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActor.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActor.h @@ -9,6 +9,7 @@ #include "Carla/Actor/ActorInfo.h" #include "Carla/Actor/ActorData.h" #include "Carla/Vehicle/CarlaWheeledVehicle.h" +#include "Carla/Vehicle/VehicleTelemetryData.h" #include "Carla/Walker/WalkerController.h" #include "Carla/Traffic/TrafficLightState.h" @@ -322,6 +323,11 @@ public: return ECarlaServerResponse::ActorTypeMismatch; } + virtual ECarlaServerResponse GetVehicleTelemetryData(FVehicleTelemetryData&) + { + return ECarlaServerResponse::ActorTypeMismatch; + } + virtual ECarlaServerResponse ShowVehicleDebugTelemetry(bool) { return ECarlaServerResponse::ActorTypeMismatch; @@ -527,6 +533,8 @@ public: virtual ECarlaServerResponse SetActorAutopilot(bool bEnabled, bool bKeepState = false) final; + virtual ECarlaServerResponse GetVehicleTelemetryData(FVehicleTelemetryData&) final; + virtual ECarlaServerResponse ShowVehicleDebugTelemetry(bool bEnabled) final; virtual ECarlaServerResponse EnableCarSim(const FString& SimfilePath) final; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp index b5c20a919..215780a27 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp @@ -65,6 +65,7 @@ #include #include #include +#include #include #include #include @@ -2245,6 +2246,31 @@ BIND_SYNC(is_sensor_enabled_for_ros) << [this](carla::streaming::detail::stream_ return R::Success(); }; + BIND_SYNC(get_telemetry_data) << [this]( + cr::ActorId ActorId) -> R + { + REQUIRE_CARLA_EPISODE(); + FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId); + if (!CarlaActor) + { + return RespondError( + "get_telemetry_data", + ECarlaServerResponse::ActorNotFound, + " Actor Id: " + FString::FromInt(ActorId)); + } + FVehicleTelemetryData TelemetryData; + ECarlaServerResponse Response = + CarlaActor->GetVehicleTelemetryData(TelemetryData); + if (Response != ECarlaServerResponse::Success) + { + return RespondError( + "get_telemetry_data", + Response, + " Actor Id: " + FString::FromInt(ActorId)); + } + return cr::VehicleTelemetryData(TelemetryData); + }; + BIND_SYNC(show_vehicle_debug_telemetry) << [this]( cr::ActorId ActorId, bool bEnabled) -> R diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.cpp index 22a025444..dbcc64449 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.cpp @@ -814,6 +814,56 @@ void ACarlaWheeledVehicle::DeactivateVelocityControl() VelocityControl->Deactivate(); } +FVehicleTelemetryData ACarlaWheeledVehicle::GetVehicleTelemetryData() const +{ + FVehicleTelemetryData TelemetryData; + + auto *MovementComponent = GetVehicleMovement(); + + // Vehicle telemetry data + TelemetryData.Speed = GetVehicleForwardSpeed() / 100.0f; // From cm/s to m/s + TelemetryData.Steer = LastAppliedControl.Steer; + TelemetryData.Throttle = LastAppliedControl.Throttle; + TelemetryData.Brake = LastAppliedControl.Brake; + TelemetryData.EngineRPM = MovementComponent->GetEngineRotationSpeed(); + TelemetryData.Gear = GetVehicleCurrentGear(); + TelemetryData.Drag = MovementComponent->DebugDragMagnitude / 100.0f; // kg*cm/s2 to Kg*m/s2 + + // Wheels telemetry data + FPhysXVehicleManager* MyVehicleManager = FPhysXVehicleManager::GetVehicleManagerFromScene(GetWorld()->GetPhysicsScene()); + + SCOPED_SCENE_READ_LOCK(MyVehicleManager->GetScene()); + PxWheelQueryResult* WheelsStates = MyVehicleManager->GetWheelsStates_AssumesLocked(MovementComponent); + check(WheelsStates); + + TArray Wheels; + for (uint32 w = 0; w < MovementComponent->PVehicle->mWheelsSimData.getNbWheels(); ++w) + { + FWheelTelemetryData WheelTelemetryData; + + WheelTelemetryData.TireFriction = WheelsStates[w].tireFriction; + WheelTelemetryData.LatSlip = FMath::RadiansToDegrees(WheelsStates[w].lateralSlip); + WheelTelemetryData.LongSlip = WheelsStates[w].longitudinalSlip; + WheelTelemetryData.Omega = MovementComponent->PVehicle->mWheelsDynData.getWheelRotationSpeed(w); + + UVehicleWheel* Wheel = MovementComponent->Wheels[w]; + WheelTelemetryData.TireLoad = Wheel->DebugTireLoad / 100.0f; + WheelTelemetryData.NormalizedTireLoad = Wheel->DebugNormalizedTireLoad; + WheelTelemetryData.Torque = Wheel->DebugWheelTorque / (100.0f * 100.0f); // From cm2 to m2 + WheelTelemetryData.LongForce = Wheel->DebugLongForce / 100.f; + WheelTelemetryData.LatForce = Wheel->DebugLatForce / 100.f; + WheelTelemetryData.NormalizedLongForce = (FMath::Abs(WheelTelemetryData.LongForce)*WheelTelemetryData.NormalizedTireLoad) / (WheelTelemetryData.TireLoad); + WheelTelemetryData.NormalizedLatForce = (FMath::Abs(WheelTelemetryData.LatForce)*WheelTelemetryData.NormalizedTireLoad) / (WheelTelemetryData.TireLoad); + + Wheels.Add(WheelTelemetryData); + } + + TelemetryData.Wheels = Wheels; + + return TelemetryData; + +} + void ACarlaWheeledVehicle::ShowDebugTelemetry(bool Enabled) { if (GetWorld()->GetFirstPlayerController()) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.h index 0f5b4fea8..ae10be15f 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.h @@ -16,6 +16,7 @@ #include "Vehicle/VehicleLightState.h" #include "Vehicle/VehicleInputPriority.h" #include "Vehicle/VehiclePhysicsControl.h" +#include "Vehicle/VehicleTelemetryData.h" #include "VehicleVelocityControl.h" #include "WheeledVehicleMovementComponent4W.h" #include "WheeledVehicleMovementComponentNW.h" @@ -240,6 +241,9 @@ public: UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) void DeactivateVelocityControl(); + UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) + FVehicleTelemetryData GetVehicleTelemetryData() const; + UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) void ShowDebugTelemetry(bool Enabled); diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/VehicleTelemetryData.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/VehicleTelemetryData.h new file mode 100644 index 000000000..b5c5aeb0e --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/VehicleTelemetryData.h @@ -0,0 +1,78 @@ +// Copyright (c) 2022 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 . + +#pragma once + +#include "VehicleTelemetryData.generated.h" + +USTRUCT(BlueprintType) +struct FWheelTelemetryData +{ + GENERATED_USTRUCT_BODY() + + UPROPERTY(Category = "Wheel Telemetry Data", EditAnywhere, BlueprintReadWrite) + float TireFriction = 0.0f; + + UPROPERTY(Category = "Wheel Telemetry Data", EditAnywhere, BlueprintReadWrite) + float LatSlip = 0.0f; // degrees + + UPROPERTY(Category = "Wheel Telemetry Data", EditAnywhere, BlueprintReadWrite) + float LongSlip = 0.0f; + + UPROPERTY(Category = "Wheel Telemetry Data", EditAnywhere, BlueprintReadWrite) + float Omega = 0.0f; + + UPROPERTY(Category = "Wheel Telemetry Data", EditAnywhere, BlueprintReadWrite) + float TireLoad = 0.0f; + + UPROPERTY(Category = "Wheel Telemetry Data", EditAnywhere, BlueprintReadWrite) + float NormalizedTireLoad = 0.0f; + + UPROPERTY(Category = "Wheel Telemetry Data", EditAnywhere, BlueprintReadWrite) + float Torque = 0.0f; // [Nm] + + UPROPERTY(Category = "Wheel Telemetry Data", EditAnywhere, BlueprintReadWrite) + float LongForce = 0.0f; // [N] + + UPROPERTY(Category = "Wheel Telemetry Data", EditAnywhere, BlueprintReadWrite) + float LatForce = 0.0f; // [N] + + UPROPERTY(Category = "Wheel Telemetry Data", EditAnywhere, BlueprintReadWrite) + float NormalizedLongForce = 0.0f; + + UPROPERTY(Category = "Wheel Telemetry Data", EditAnywhere, BlueprintReadWrite) + float NormalizedLatForce = 0.0f; +}; + +USTRUCT(BlueprintType) +struct CARLA_API FVehicleTelemetryData +{ + GENERATED_BODY() + + UPROPERTY(Category = "Vehicle Telemetry Data", EditAnywhere, BlueprintReadWrite) + float Speed = 0.0f; // [m/s] + + UPROPERTY(Category = "Vehicle Telemetry Data", EditAnywhere, BlueprintReadWrite) + float Steer = 0.0f; + + UPROPERTY(Category = "Vehicle Telemetry Data", EditAnywhere, BlueprintReadWrite) + float Throttle = 0.0f; + + UPROPERTY(Category = "Vehicle Telemetry Data", EditAnywhere, BlueprintReadWrite) + float Brake = 0.0f; + + UPROPERTY(Category = "Vehicle Telemetry Data", EditAnywhere, BlueprintReadWrite) + float EngineRPM = 0.0f; + + UPROPERTY(Category = "Vehicle Telemetry Data", EditAnywhere, BlueprintReadWrite) + int32 Gear = 0.0f; + + UPROPERTY(Category = "Vehicle Telemetry Data", EditAnywhere, BlueprintReadWrite) + float Drag = 0.0f; // [N] + + UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite) + TArray Wheels; +}; From a06ab08c4c213de1dc64801ab4ee11ff0bfcf96b Mon Sep 17 00:00:00 2001 From: Daraan Date: Fri, 31 May 2024 17:37:10 +0200 Subject: [PATCH 37/99] Named and type-hint supporting detection results for the python agents. (#7174) * Python agents: Created NamedTuple for Detection return types * Python 2.7 and <3.6 compatible code * Updated Changelog * removed print * Added file description * removed unnecessary line * Added Literal type hint for <3.8 Python --------- Co-authored-by: glopezdiest <58212725+glopezdiest@users.noreply.github.com> Co-authored-by: Blyron <53337103+Blyron@users.noreply.github.com> --- CHANGELOG.md | 1 + .../carla/agents/navigation/basic_agent.py | 20 ++++++----- PythonAPI/carla/agents/tools/hints.py | 34 +++++++++++++++++++ 3 files changed, 46 insertions(+), 9 deletions(-) create mode 100644 PythonAPI/carla/agents/tools/hints.py diff --git a/CHANGELOG.md b/CHANGELOG.md index bde484631..d743c9c7e 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -17,6 +17,7 @@ * Added API function `get_telemetry_data` to the vehicle actor. * PythonAPI `Sensor.is_listening` was defined twice (property and method), cleaned and clarified it as a method. * Added V2X sensors for cooperative awareness message and custom user-defined messages to support vehicle-to-vehicle communication + * Added named tuples for BasicAgent.py's detection result to allow for type-hints and better semantics. ## CARLA 0.9.15 diff --git a/PythonAPI/carla/agents/navigation/basic_agent.py b/PythonAPI/carla/agents/navigation/basic_agent.py index 44e6d0351..aeddc005e 100644 --- a/PythonAPI/carla/agents/navigation/basic_agent.py +++ b/PythonAPI/carla/agents/navigation/basic_agent.py @@ -18,6 +18,8 @@ from agents.tools.misc import (get_speed, is_within_distance, get_trafficlight_trigger_location, compute_distance) +from agents.tools.hints import ObstacleDetectionResult, TrafficLightDetectionResult + class BasicAgent(object): """ @@ -265,7 +267,7 @@ class BasicAgent(object): If None, the base threshold value is used """ if self._ignore_traffic_lights: - return (False, None) + return TrafficLightDetectionResult(False, None) if not lights_list: lights_list = self._world.get_actors().filter("*traffic_light*") @@ -277,7 +279,7 @@ class BasicAgent(object): if self._last_traffic_light.state != carla.TrafficLightState.Red: self._last_traffic_light = None else: - return (True, self._last_traffic_light) + return TrafficLightDetectionResult(True, self._last_traffic_light) ego_vehicle_location = self._vehicle.get_location() ego_vehicle_waypoint = self._map.get_waypoint(ego_vehicle_location) @@ -308,9 +310,9 @@ class BasicAgent(object): if is_within_distance(trigger_wp.transform, self._vehicle.get_transform(), max_distance, [0, 90]): self._last_traffic_light = traffic_light - return (True, traffic_light) + return TrafficLightDetectionResult(True, traffic_light) - return (False, None) + return TrafficLightDetectionResult(False, None) def _vehicle_obstacle_detected(self, vehicle_list=None, max_distance=None, up_angle_th=90, low_angle_th=0, lane_offset=0): """ @@ -347,12 +349,12 @@ class BasicAgent(object): return Polygon(route_bb) if self._ignore_vehicles: - return (False, None, -1) + return ObstacleDetectionResult(False, None, -1) if vehicle_list is None: vehicle_list = self._world.get_actors().filter("*vehicle*") if len(vehicle_list) == 0: - return (False, None, -1) + return ObstacleDetectionResult(False, None, -1) if not max_distance: max_distance = self._base_vehicle_threshold @@ -395,7 +397,7 @@ class BasicAgent(object): target_polygon = Polygon(target_list) if route_polygon.intersects(target_polygon): - return (True, target_vehicle, compute_distance(target_vehicle.get_location(), ego_location)) + return ObstacleDetectionResult(True, target_vehicle, compute_distance(target_vehicle.get_location(), ego_location)) # Simplified approach, using only the plan waypoints (similar to TM) else: @@ -416,9 +418,9 @@ class BasicAgent(object): ) if is_within_distance(target_rear_transform, ego_front_transform, max_distance, [low_angle_th, up_angle_th]): - return (True, target_vehicle, compute_distance(target_transform.location, ego_transform.location)) + return ObstacleDetectionResult(True, target_vehicle, compute_distance(target_transform.location, ego_transform.location)) - return (False, None, -1) + return ObstacleDetectionResult(False, None, -1) def _generate_lane_change_path(self, waypoint, direction='left', distance_same_lane=10, distance_other_lane=25, lane_change_distance=25, diff --git a/PythonAPI/carla/agents/tools/hints.py b/PythonAPI/carla/agents/tools/hints.py new file mode 100644 index 000000000..475d93d3d --- /dev/null +++ b/PythonAPI/carla/agents/tools/hints.py @@ -0,0 +1,34 @@ +""" +Module to add high-level semantic return types for obstacle and traffic light detection results via named tuples. + +The code is compatible with Python 2.7, <3.6 and >=3.6. The later uses the typed version of named tuples. +""" + + +import sys +if sys.version_info < (3, 6): + from collections import namedtuple + ObstacleDetectionResult = namedtuple('ObstacleDetectionResult', ['obstacle_was_found', 'obstacle', 'distance']) + TrafficLightDetectionResult = namedtuple('TrafficLightDetectionResult', ['traffic_light_was_found', 'traffic_light']) +else: + from typing import NamedTuple, Union, TYPE_CHECKING + from carla import Actor, TrafficLight + """ + # Python 3.6+, incompatible with Python 2.7 syntax + class ObstacleDetectionResult(NamedTuple): + obstacle_was_found : bool + obstacle : Union[Actor, None] + distance : float + # distance : Union[float, Literal[-1]] # Python 3.8+ only + + class TrafficLightDetectionResult(NamedTuple): + traffic_light_was_found : bool + traffic_light : Union[TrafficLight, None] + """ + if TYPE_CHECKING: + from typing import Literal + ObstacleDetectionResult = NamedTuple('ObstacleDetectionResult', [('obstacle_was_found', bool), ('obstacle', Union[Actor, None]), ('distance', Union[float, Literal[-1]])]) + else: + ObstacleDetectionResult = NamedTuple('ObstacleDetectionResult', [('obstacle_was_found', bool), ('obstacle', Union[Actor, None]), ('distance', float)]) + + TrafficLightDetectionResult = NamedTuple('TrafficLightDetectionResult', [('traffic_light_was_found', bool), ('traffic_light', Union[TrafficLight, None])]) From 696d11f99533faf045b4b4dafad79d0af646f204 Mon Sep 17 00:00:00 2001 From: Ruben Abad Date: Mon, 3 Jun 2024 13:39:34 +0200 Subject: [PATCH 38/99] test only in gpu nodes --- Jenkinsfile | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/Jenkinsfile b/Jenkinsfile index b7352cac9..509b3090b 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -17,7 +17,7 @@ pipeline //{ stage('ubuntu') { - agent { label "gpu" } + agent { label "ubuntu_20_04" } environment { UE4_ROOT = '/home/jenkins/UnrealEngine_4.26' @@ -207,6 +207,7 @@ pipeline { stage('ubuntu smoke tests') { + agent { label "gpu_20_04" } steps { unstash name: 'ubuntu_eggs' From 68ce217d26fb98fdff9d91f1064d850464994a5a Mon Sep 17 00:00:00 2001 From: Ruben Abad Date: Mon, 3 Jun 2024 13:40:18 +0200 Subject: [PATCH 39/99] master and dev branches do documentation upload on main branch --- Jenkinsfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Jenkinsfile b/Jenkinsfile index 509b3090b..b3fd05fef 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -316,7 +316,7 @@ pipeline tar -xvzf carla_doc.tar.gz git add Doxygen git commit -m "Updated c++ docs" || true - git push --set-upstream origin ruben/jenkins_migration + git push --set-upstream origin master ''' } } From 3654f6bb24a0cd6bb9574e1164a481c64ce42337 Mon Sep 17 00:00:00 2001 From: Ruben Abad Date: Mon, 3 Jun 2024 16:06:15 +0200 Subject: [PATCH 40/99] prevent test stages to download repo again --- Jenkinsfile | 1 + 1 file changed, 1 insertion(+) diff --git a/Jenkinsfile b/Jenkinsfile index b3fd05fef..3cae36aa6 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -208,6 +208,7 @@ pipeline stage('ubuntu smoke tests') { agent { label "gpu_20_04" } + options{skipDefaultCheckout()} steps { unstash name: 'ubuntu_eggs' From 6898225f5ddc768af4136df6c142e30259487a00 Mon Sep 17 00:00:00 2001 From: MattRoweEAIF <125647690+MattRoweEAIF@users.noreply.github.com> Date: Tue, 4 Jun 2024 11:56:30 +0200 Subject: [PATCH 41/99] added UE5 build instructions (#7743) --- Docs/build_linux_ue5.md | 91 +++++++++++++++++++++++++++++++++++++++ Docs/build_windows_ue5.md | 79 +++++++++++++++++++++++++++++++++ 2 files changed, 170 insertions(+) create mode 100644 Docs/build_linux_ue5.md create mode 100644 Docs/build_windows_ue5.md diff --git a/Docs/build_linux_ue5.md b/Docs/build_linux_ue5.md new file mode 100644 index 000000000..62a270441 --- /dev/null +++ b/Docs/build_linux_ue5.md @@ -0,0 +1,91 @@ +!!! warning + This is a work in progress!! This version of CARLA is not considered a stable release. Over the following months many significant changes may be made to this branch which could break any modifications you make. We advise you to treat this branch as experimental. + +# Building CARLA in Linux with Unreal Engine 5.3 + +!!! note + This build process is implemented and tested for Ubuntu 22.04. We recommend to use this Ubuntu version. + +## Set up the environment + +This guide details how to build CARLA from source on Linux with Unreal Engine 5.3. + +Clone the `ue5-dev` branch of CARLA on your local machine: + +```sh +git clone -b ue5-dev https://github.com/carla-simulator/carla.git CarlaUE5 +``` + +Run the setup script: + +```sh +cd CarlaUE5 +bash -x Setup.sh +``` + +The Setup.sh script installs all the required packages, including Cmake, debian packages, Python packages and Unreal Engine 5.3. It also downloads the CARLA content and builds CARLA. This script can therefore take a long time to complete. + +!!! note + * This version of CARLA requires the **CARLA fork of Unreal Engine 5.3**. You need to link your GitHub account to Epic Games in order to gain permission to clone the UE repository. If you have not already linked your accounts, follow [this guide](https://www.unrealengine.com/en-US/ue4-on-github) + * For using CARLA Unreal Engine 5 previous builds, **ensure CARLA_UNREAL_ENGINE_PATH environment variable is defined** pointing to the CARLA Unreal Engine 5.3 absolute path. If this variable is not defined, the Setup.sh script will download and build CARLA Unreal Engine 5 and **this takes more than 1 extra hour of build and 225Gb of disk space**. + * The Setup.sh script checks if there is any Python installed at the top of the PATH variable, and installs Python otherwise. **To use your own version of Python, ensure that the PATH variable is properly set for Python before running the script**. + * CARLA cannot be built on an external disk, Ubuntu is not giving the required read/write/execution permissions for builds. + + +## Build and Run CARLA UE5 + +The setup script launches the following commands itself, you will need to use the following commands once you modify the code and wish to relaunch: + +* Configure: + +```sh +cmake -G Ninja -S . -B Build --toolchain=$PWD/CMake/LinuxToolchain.cmake \ +-DLAUNCH_ARGS="-prefernvidia" -DCMAKE_BUILD_TYPE=Release -DENABLE_ROS2=ON \ +-DBUILD_CARLA_UNREAL=ON -DCARLA_UNREAL_ENGINE_PATH=$CARLA_UNREAL_ENGINE_PATH +``` + +* Build CARLA: + +```sh +cmake --build Build +``` + +* Build and install the Python API: + +```sh +cmake --build Build --target carla-python-api-install +``` + +* Launch the editor: + +```sh +cmake --build Build --target launch +``` + +## Build a package with CARLA UE5 + +```sh +cmake --build Build --target package +``` + +The package will be generated in the directory `$CARLA_PATH/Build/Package` + +## Run the package + +Run the package with the following command. + +```sh +./CarlaUnreal.sh +``` + +If you want to run the native ROS2 interface, add the `--ros2` argument + +```sh +./CarlaUnreal.sh --ros2 +``` + +If you want to install the Python API corresponding to the package you have built: + +```sh +pip3 install PythonAPI/carla/dist/carla-*.whl +``` \ No newline at end of file diff --git a/Docs/build_windows_ue5.md b/Docs/build_windows_ue5.md new file mode 100644 index 000000000..70b1eeb9e --- /dev/null +++ b/Docs/build_windows_ue5.md @@ -0,0 +1,79 @@ +!!! warning + This is a work in progress!! This version of CARLA is not considered a stable release. Over the following months many significant changes may be made to this branch which could break any modifications you make. We advise you to treat this branch as experimental. + +# Building CARLA in Windowswith Unreal Engine 5.3 + +## Set up the environment + +This guide details how to build CARLA from source on Windows with Unreal Engine 5.3. + +Clone the `ue5-dev` branch of CARLA on your local machine: + +```sh +git clone -b ue5-dev https://github.com/carla-simulator/carla.git CarlaUE5 +``` + +Run the setup script: + +```sh +cd CarlaUE5 +Setup.bat +``` + +The Setup.bat script installs all the required packages, including Visual Studio 2022, Cmake, Python packages and Unreal Engine 5. It also downloads the CARLA content and builds CARLA. This batch file can therefore take a long time to complete. + +!!! note + * This version of CARLA requires the **CARLA fork of Unreal Engine 5.3**. You need to link your GitHub account to Epic Games in order to gain permission to clone the UE repository. If you have not already linked your accounts, follow [this guide](https://www.unrealengine.com/en-US/ue4-on-github) + * For using CARLA Unreal Engine 5 previous builds, ensure CARLA_UNREAL_ENGINE_PATH environment variable is defined pointing to the CARLA Unreal Engine 5 absolute path. If this variable is not defined, Setup.bat script will download and build CARLA Unreal Engine 5 and **this takes more than 1 extra hour of build and a 225Gb of disk space**. + * Setup.bat script checks if there is any Python version installed at the top of the PATH variable, and installs Python otherwise. **To use your own version of Python, ensure that the PATH variable is properly set for Python before running the script**. + * **Windows Developer Mode should be active**, otherwise build will fail. Please see [here](https://learn.microsoft.com/en-us/gaming/game-bar/guide/developer-mode) for instructions on how to activate Developer Mode. + * **CARLA cannot be built on an external disk**, Windows does not give the required read/write/execution permissions for builds. + + +## Build and Run CARLA UE5 + +The Setup.bat file launches the following commands itself, you will need to use the following commands once you modify the code and wish to relaunch: + +!!! warning + Ensure CARLA_UNREAL_ENGINE_PATH environment variable is defined pointing to the CARLA Unreal Engine 5.3 absolute path. Setup.bat sets this variable, but I may not be set if another approach was followed to install the requirements. + +* **Configure**. Open x64 Native Tools Command Prompt for VS 2022 at the CarlaUE5 folder and runn the following command: + +```sh +cmake -G Ninja -S . -B Build -DCMAKE_BUILD_TYPE=Release -DBUILD_CARLA_UNREAL=ON -DCARLA_UNREAL_ENGINE_PATH=%CARLA_UNREAL_ENGINE_PATH% +``` + +* **Build CARLA**. Open the x64 Native Tools Command Prompt for VS 2022 at the CarlaUE5 folder and run the following command: + +```sh +cmake --build Build +``` + +* **Build and install the Python API**. Open the x64 Native Tools Command Prompt for VS 2022 at the CarlaUE5 folder and run the following command:: + +```sh +cmake --build Build --target carla-python-api-install +``` + +* **Launch the editor**. Open the x64 Native Tools Command Prompt for VS 2022 at the CarlaUE5 folder and run the following command: + +```sh +cmake --build Build --target launch +``` + +## Build a package with CARLA UE5 + +!!! warning + The package build for Carla UE5 is not yet fully tested for Windows. + +Open the x64 Native Tools Command Prompt for VS 2022 at the CarlaUE5 folder and run the following command: + +```sh +cmake --build Build --target package +``` + +The package will be generated in the directory `Build/Package` + +## Run the package + +The package build is not yet tested for Windows From d6078abdbfef8f8d4aab703109212152137d2e37 Mon Sep 17 00:00:00 2001 From: Ruben Abad Date: Tue, 4 Jun 2024 12:12:57 +0200 Subject: [PATCH 42/99] reverting previous change: repo checkout is neccessary to have access to makefile --- Jenkinsfile | 1 - 1 file changed, 1 deletion(-) diff --git a/Jenkinsfile b/Jenkinsfile index 3cae36aa6..b3fd05fef 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -208,7 +208,6 @@ pipeline stage('ubuntu smoke tests') { agent { label "gpu_20_04" } - options{skipDefaultCheckout()} steps { unstash name: 'ubuntu_eggs' From b69f892537766e8135cd80690a150067e0ef51af Mon Sep 17 00:00:00 2001 From: MattRoweEAIF <125647690+MattRoweEAIF@users.noreply.github.com> Date: Tue, 4 Jun 2024 12:28:12 +0200 Subject: [PATCH 43/99] Docs/ue5 instructions (#7747) * added UE5 build instructions * added links in main build doc --- Docs/build_carla.md | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/Docs/build_carla.md b/Docs/build_carla.md index 1ac943002..d0e1fed62 100644 --- a/Docs/build_carla.md +++ b/Docs/build_carla.md @@ -9,7 +9,10 @@ Build instructions are available for Linux and Windows. You can also build CARLA * [__Docker__](build_docker.md) * [__Docker with Unreal__](build_docker_unreal.md) * [__Updating CARLA__](build_update.md) -* [__Build system__](build_system.md) +* [__Build system__](build_system.md) + +* [__Linux build with Unreal Engine 5.3__](build_linux_ue5.md) +* [__Windows build with Unreal Engine 5.3__](build_windows_ue5.md) * [__FAQ__](build_faq.md) From dae1d5821149278dd709e3c852a97ba2a438154a Mon Sep 17 00:00:00 2001 From: Ruben Abad Date: Tue, 4 Jun 2024 15:23:46 +0200 Subject: [PATCH 44/99] update credentials --- Jenkinsfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Jenkinsfile b/Jenkinsfile index b3fd05fef..fb0a2d5e5 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -311,7 +311,7 @@ pipeline dir('doc_repo') { unstash name: 'carla_docs' - withCredentials([gitUsernamePassword(credentialsId: 'github_token_as_pwd_2', gitToolName: 'git-tool')]) { + withCredentials([gitUsernamePassword(credentialsId: 'carla_test_1', gitToolName: 'git-tool')]) { sh ''' tar -xvzf carla_doc.tar.gz git add Doxygen From 5287e239a38a159ba0cd355c4152a8129cd9ef17 Mon Sep 17 00:00:00 2001 From: Ruben Abad Date: Tue, 4 Jun 2024 15:41:49 +0200 Subject: [PATCH 45/99] reverting credentials --- Jenkinsfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Jenkinsfile b/Jenkinsfile index fb0a2d5e5..b3fd05fef 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -311,7 +311,7 @@ pipeline dir('doc_repo') { unstash name: 'carla_docs' - withCredentials([gitUsernamePassword(credentialsId: 'carla_test_1', gitToolName: 'git-tool')]) { + withCredentials([gitUsernamePassword(credentialsId: 'github_token_as_pwd_2', gitToolName: 'git-tool')]) { sh ''' tar -xvzf carla_doc.tar.gz git add Doxygen From e2574609f91f79875bd9152631d6faa077f5d44e Mon Sep 17 00:00:00 2001 From: Ruben Abad Date: Wed, 5 Jun 2024 12:29:36 +0200 Subject: [PATCH 46/99] doucmentation is pulled/pushed to "dev" branch --- Jenkinsfile | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Jenkinsfile b/Jenkinsfile index b3fd05fef..2eb130419 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -132,7 +132,7 @@ pipeline dir('doc_repo') { checkout scmGit( - branches: [[name: '*/master']], + branches: [[name: '*/dev']], extensions: [ cleanBeforeCheckout(), checkoutOption(120), @@ -316,7 +316,7 @@ pipeline tar -xvzf carla_doc.tar.gz git add Doxygen git commit -m "Updated c++ docs" || true - git push --set-upstream origin master + git push --set-upstream origin dev ''' } } From 18035969feedddb1124fbd2152a925c92326f33a Mon Sep 17 00:00:00 2001 From: MattRoweEAIF <125647690+MattRoweEAIF@users.noreply.github.com> Date: Mon, 10 Jun 2024 17:02:53 +0200 Subject: [PATCH 47/99] changed get_required_files docs (#7763) * changed get_required_files docs * fixed overwritten user data --- Docs/python_api.md | 116 +++++++++++++++------------------ PythonAPI/docs/client.yml | 4 +- PythonAPI/docs/sensor.yml | 46 ++++++++----- PythonAPI/docs/sensor_data.yml | 112 ++++++++++++++++++++++++++++++- 4 files changed, 197 insertions(+), 81 deletions(-) diff --git a/Docs/python_api.md b/Docs/python_api.md index e0e0aa72a..a7ab163a2 100644 --- a/Docs/python_api.md +++ b/Docs/python_api.md @@ -421,19 +421,16 @@ Parses the location and extent of the bounding box to string. ## carla.CAMData Inherited from _[carla.SensorData](#carla.SensorData)_
-This is the data type for cooperative awareness message reception, contained in a [CAMEvent](#carlacamevent) +This is the data type for cooperative awareness message reception, contained in a [CAMEvent](#carlacamevent). + ### Instance Variables -- **power** (_float - dBm_) +- **power** (_float - dBm_) Received power. ### Methods -- **get**(**self**) -Get the CAM data. - - **Return:** _dict_ - - Returns a nested dictionary containing the message following the ETSI standard: - - `"Header"`: _dict_ - - `"Message"`: _dict_ +- **get**(**self**) +Get the CAM data. Returns a nested dictionary containing the message following the ETSI standard: - `Header`: dict - `Message`: dict. + - **Return:** _dict_ ##### Dunder methods - **\__str__**(**self**) @@ -442,25 +439,23 @@ Get the CAM data. ## carla.CAMEvent Inherited from _[carla.SensorData](#carla.SensorData)_
-Class that defines the data provided by a sensor.other.v2x. This is a collection type to combine returning several [CAMData](#carlacamdata). - -### Instance Variables - +Class that defines the data provided by a **sensor.other.v2x**. This is a collection type to combine returning several [CAMData](#carlacamdata). ### Methods -- **get_message_count**(**self**) -Get the number of received CAM's. - - **Return:** _int_ + +##### Getters +- **get_message_count**(**self**) +Get the number of received CAM's. + - **Return:** _int_ ##### Dunder methods -- **\__getitem__**(**self**, **pos**=int) +- **\__get_item__**(**self**, **pos**=int) - **\__iter__**(**self**) -Iterate over the [carla.CAMData](#carla.CAMData) retrieved as data. -- **\__len__**(**self**) +Iterate over the [CAMData](#carlacamdata) retrieved as data. +- **\__len__**(**self**) --- - ## carla.CityObjectLabel Enum declaration that contains the different tags available to filter the bounding boxes returned by [carla.World.get_level_bbs](#carla.World.get_level_bbs)(). These values correspond to the [semantic tag](ref_sensors.md#semantic-segmentation-camera) that the elements in the scene have. @@ -618,8 +613,8 @@ Returns the client libcarla version by consulting it in the "Version.h" file. Bo - **get_required_files**(**self**, **folder**, **download**=True) Asks the server which files are required by the client to use the current map. Option to download files automatically if they are not already in the cache. - **Parameters:** - - `folder` (_str_) - Folder where files required by the client will be downloaded to. - - `download` (_bool_) - If True, downloads files that are not already in cache. + - `folder` (_str_) - Specifies a folder to look through on the server maps. Leaving this blank will search recursively through all map folders in the server, which is recommended if you're unfamiliar with the server map folder structure. + - `download` (_bool_) - If True, downloads files that are not already in cache. The cache can be found at "HOME\carlaCache" or "USERPROFILE\carlaCache", depending on OS. - **get_server_version**(**self**) Returns the server libcarla version by consulting it in the "Version.h" file. Both client and server should use the same libcarla version. - **Return:** _str_ @@ -710,23 +705,19 @@ Converts the image to a depth map using a logarithmic scale, leading to better p No changes applied to the image. Used by the [RGB camera](ref_sensors.md#rgb-camera). --- + ## carla.CustomV2XData Inherited from _[carla.SensorData](#carla.SensorData)_
-This is the data type defining a custom V2X message. Received as part of a [CustomV2XEvent](#carla.CustomV2XEvent). +This is the data type defining a custom V2X message. Received as part of a [CustomV2XEvent](#carlacustomv2xevent). ### Instance Variables -- **power** (_float - dBm_) +- **power** (_float - dBm_) Received power. ### Methods -- **get**(**self**) -Get the custom message. - - **Return:** _dict_. - - Returns a nested dictionary containing the message. It has two primary keys: - - `"Header"` : _dict_ - - `"Message"`: _str_ - +- **get**(**self**) +Get the custom message. Returns a nested dictionary containing the message. It has two primary keys: - `Header` : dict - `Message`: str. + - **Return:** _dict_ ##### Dunder methods - **\__str__**(**self**) @@ -735,25 +726,23 @@ Get the custom message. ## carla.CustomV2XEvent Inherited from _[carla.SensorData](#carla.SensorData)_
-Class that defines the data provided by a sensor.other.v2x_custom. This is a collection type to combine returning several [CustomV2XData](#carla.CustomV2XData). - -### Instance Variables - +Class that defines the data provided by a **sensor.other.v2x_custom**. This is a collection type to combine returning several [CustomV2XData](#carlacustomv2xdata). ### Methods -- **get_message_count**(**self**) -Get the number of received CAM's. - - **Return:** _int_ + +##### Getters +- **get_message_count**(**self**) +Get the number of received CAM's. + - **Return:** _int_ ##### Dunder methods -- **\__getitem__**(**self**, **pos**=int) +- **\__get_item__**(**self**, **pos**=int) - **\__iter__**(**self**) -Iterate over the [carla.CustomV2XData](#carla.CustomV2XData) retrieved as data. +Iterate over the [CustomV2XData](#carlacustomv2xdata) retrieved as data. - **\__len__**(**self**) --- - ## carla.DVSEvent Class that defines a DVS event. An event is a quadruple, so a tuple of 4 elements, with `x`, `y` pixel coordinate location, timestamp `t` and polarity `pol` of the event. Learn more about them [here](ref_sensors.md). @@ -942,7 +931,7 @@ Initializes a color, black by default. --- ## carla.GBufferTextureID -Defines the identifiers of each GBuffer texture (See the method `[carla.Sensor.listen_to_gbuffer](#carla.Sensor.listen_to_gbuffer)`). +Defines the of each GBuffer texture (See the method `[carla.Sensor.listen_to_gbuffer](#carla.Sensor.listen_to_gbuffer)`). ### Instance Variables - **SceneColor** @@ -2315,26 +2304,26 @@ Iterate over the [carla.SemanticLidarDetection](#carla.SemanticLidarDetection) r Inherited from _[carla.Actor](#carla.Actor)_
Sensors compound a specific family of actors quite diverse and unique. They are normally spawned as attachment/sons of a vehicle (take a look at [carla.World](#carla.World) to learn about actor spawning). Sensors are thoroughly designed to retrieve different types of data that they are listening to. The data they receive is shaped as different subclasses inherited from [carla.SensorData](#carla.SensorData) (depending on the sensor). - Most sensors can be divided in two groups: those receiving data on every tick (cameras, point clouds and some specific sensors) and those who only receive under certain circumstances (trigger detectors). CARLA provides a specific set of sensors and their blueprint can be found in [carla.BlueprintLibrary](#carla.BlueprintLibrary). All the information on their preferences and settlement can be found [here](ref_sensors.md), but the list of those available in CARLA so far goes as follow. -
Receive data on every tick. - - [Depth camera](ref_sensors.md#depth-camera). - - [Gnss sensor](ref_sensors.md#gnss-sensor). - - [IMU sensor](ref_sensors.md#imu-sensor). - - [Lidar raycast](ref_sensors.md#lidar-raycast-sensor). - - [SemanticLidar raycast](ref_sensors.md#semanticlidar-raycast-sensor). - - [Radar](ref_sensors.md#radar-sensor). - - [RGB camera](ref_sensors.md#rgb-camera). - - [RSS sensor](ref_sensors.md#rss-sensor). - - [Semantic Segmentation camera](ref_sensors.md#semantic-segmentation-camera). -
Only receive data when triggered. - - [Collision detector](ref_sensors.md#collision-detector). - - [Lane invasion detector](ref_sensors.md#lane-invasion-detector). - - [Obstacle detector](ref_sensors.md#obstacle-detector). + Most sensors can be divided in two groups: those receiving data on every tick (cameras, point clouds and some specific sensors) and those who only receive under certain circumstances (trigger detectors). CARLA provides a specific set of sensors and their blueprint can be found in [carla.BlueprintLibrary](#carla.BlueprintLibrary). All the information on their preferences and settlement can be found [here](ref_sensors.md), but the list of those available in CARLA so far goes as follows:
+
Receive data on every tick
+ - [Depth camera](ref_sensors.md#depth-camera)
+ - [Gnss sensor](ref_sensors.md#gnss-sensor)
+ - [IMU sensor](ref_sensors.md#imu-sensor)
+ - [Lidar raycast](ref_sensors.md#lidar-raycast-sensor)
+ - [SemanticLidar raycast](ref_sensors.md#semanticlidar-raycast-sensor)
+ - [Radar](ref_sensors.md#radar-sensor)
+ - [RGB camera](ref_sensors.md#rgb-camera)
+ - [RSS sensor](ref_sensors.md#rss-sensor)
+ - [Semantic Segmentation camera](ref_sensors.md#semantic-segmentation-camera)
+
Only receive data when triggered.
+ - [Collision detector](ref_sensors.md#collision-detector)
+ - [Lane invasion detector](ref_sensors.md#lane-invasion-detector)
+ - [Obstacle detector](ref_sensors.md#obstacle-detector)
- [V2X sensor](ref_sensors.md#v2x-sensor). ### Instance Variables - **is_listening** (_boolean_) -When True the sensor will be waiting for data. +When **True** the sensor will be waiting for data. ### Methods - **disable_for_ros**(**self**) @@ -2343,12 +2332,15 @@ Commands the sensor to not be processed for publishing in ROS2 if there is no an Commands the sensor to be processed to be able to publish in ROS2 without any listen to it. - **is_enabled_for_ros**(**self**) Returns if the sensor is enabled or not to publish in ROS2 if there is no any listen to it. + - **Return:** _bool_ - **is_listening**(**self**) Returns whether the sensor is in a listening state. + - **Return:** _bool_ - **is_listening_gbuffer**(**self**, **gbuffer_id**) Returns whether the sensor is in a listening state for a specific GBuffer texture. - **Parameters:** - `gbuffer_id` (_[carla.GBufferTextureID](#carla.GBufferTextureID)_) - The ID of the target Unreal Engine GBuffer texture. + - **Return:** _bool_ - **listen**(**self**, **callback**) The function the sensor will be calling to every time a new measurement is received. This function needs for an argument containing an object type [carla.SensorData](#carla.SensorData) to work with. - **Parameters:** @@ -2361,7 +2353,7 @@ The function the sensor will be calling to every time the desired GBuffer textur - **send**(**self**, **message**) Instructs the sensor to send the string given by `message` to all other CustomV2XSensors on the next tick. - **Parameters:** - - `message` (_string_) - The data to send. *Note*: maximum string length is 100 chars. + - `message` (_string_) - The data to send. Note: maximum string length is 100 chars. - **stop**(**self**) Commands the sensor to stop listening for data. - **stop_gbuffer**(**self**, **gbuffer_id**) @@ -2385,8 +2377,8 @@ Base class for all the objects containing data generated by a [carla.Sensor](#ca - Obstacle detector: [carla.ObstacleDetectionEvent](#carla.ObstacleDetectionEvent).
- Radar sensor: [carla.RadarMeasurement](#carla.RadarMeasurement).
- RSS sensor: [carla.RssResponse](#carla.RssResponse).
- - Semantic LIDAR sensor: [carla.SemanticLidarMeasurement](#carla.SemanticLidarMeasurement). - - Cooperative awareness messages V2X sensor: [carla.CAMEvent](#carla.CAMEvent). + - Semantic LIDAR sensor: [carla.SemanticLidarMeasurement](#carla.SemanticLidarMeasurement).
+ - Cooperative awareness messages V2X sensor: [carla.CAMEvent](#carla.CAMEvent).
- Custom V2X messages V2X sensor: [carla.CustomV2XEvent](#carla.CustomV2XEvent). ### Instance Variables diff --git a/PythonAPI/docs/client.yml b/PythonAPI/docs/client.yml index 3f4e40388..2977c9337 100644 --- a/PythonAPI/docs/client.yml +++ b/PythonAPI/docs/client.yml @@ -352,12 +352,12 @@ - param_name: folder type: str doc: > - Folder where files required by the client will be downloaded to. + Specifies a folder to look through on the server maps. Leaving this blank will search recursively through all map folders in the server, which is recommended if you're unfamiliar with the server map folder structure. - param_name: download type: bool default: True doc: > - If True, downloads files that are not already in cache. + If True, downloads files that are not already in cache. The cache can be found at "HOME\carlaCache" or "USERPROFILE\carlaCache", depending on OS. doc: > Asks the server which files are required by the client to use the current map. Option to download files automatically if they are not already in the cache. # -------------------------------------- diff --git a/PythonAPI/docs/sensor.yml b/PythonAPI/docs/sensor.yml index 06e78c2a5..5885217cd 100644 --- a/PythonAPI/docs/sensor.yml +++ b/PythonAPI/docs/sensor.yml @@ -8,21 +8,28 @@ doc: > Sensors compound a specific family of actors quite diverse and unique. They are normally spawned as attachment/sons of a vehicle (take a look at carla.World to learn about actor spawning). Sensors are thoroughly designed to retrieve different types of data that they are listening to. The data they receive is shaped as different subclasses inherited from carla.SensorData (depending on the sensor). - Most sensors can be divided in two groups: those receiving data on every tick (cameras, point clouds and some specific sensors) and those who only receive under certain circumstances (trigger detectors). CARLA provides a specific set of sensors and their blueprint can be found in carla.BlueprintLibrary. All the information on their preferences and settlement can be found [here](ref_sensors.md), but the list of those available in CARLA so far goes as follow. -
Receive data on every tick. - - [Depth camera](ref_sensors.md#depth-camera). - - [Gnss sensor](ref_sensors.md#gnss-sensor). - - [IMU sensor](ref_sensors.md#imu-sensor). - - [Lidar raycast](ref_sensors.md#lidar-raycast-sensor). - - [SemanticLidar raycast](ref_sensors.md#semanticlidar-raycast-sensor). - - [Radar](ref_sensors.md#radar-sensor). - - [RGB camera](ref_sensors.md#rgb-camera). - - [RSS sensor](ref_sensors.md#rss-sensor). - - [Semantic Segmentation camera](ref_sensors.md#semantic-segmentation-camera). -
Only receive data when triggered. - - [Collision detector](ref_sensors.md#collision-detector). - - [Lane invasion detector](ref_sensors.md#lane-invasion-detector). - - [Obstacle detector](ref_sensors.md#obstacle-detector). + Most sensors can be divided in two groups: those receiving data on every tick (cameras, point clouds and some specific sensors) and those who only receive under certain circumstances (trigger detectors). CARLA provides a specific set of sensors and their blueprint can be found in carla.BlueprintLibrary. All the information on their preferences and settlement can be found [here](ref_sensors.md), but the list of those available in CARLA so far goes as follows:
+
Receive data on every tick
+ - [Depth camera](ref_sensors.md#depth-camera)
+ - [Gnss sensor](ref_sensors.md#gnss-sensor)
+ - [IMU sensor](ref_sensors.md#imu-sensor)
+ - [Lidar raycast](ref_sensors.md#lidar-raycast-sensor)
+ - [SemanticLidar raycast](ref_sensors.md#semanticlidar-raycast-sensor)
+ - [Radar](ref_sensors.md#radar-sensor)
+ - [RGB camera](ref_sensors.md#rgb-camera)
+ - [RSS sensor](ref_sensors.md#rss-sensor)
+ - [Semantic Segmentation camera](ref_sensors.md#semantic-segmentation-camera)
+
Only receive data when triggered.
+ - [Collision detector](ref_sensors.md#collision-detector)
+ - [Lane invasion detector](ref_sensors.md#lane-invasion-detector)
+ - [Obstacle detector](ref_sensors.md#obstacle-detector)
+ - [V2X sensor](ref_sensors.md#v2x-sensor) + # - PROPERTIES ------------------------- + instance_variables: + - var_name: is_listening + type: boolean + doc: > + When **True** the sensor will be waiting for data. # - METHODS ---------------------------- methods: - def_name: listen @@ -92,6 +99,15 @@ doc: > Commands the sensor to stop listening for the specified GBuffer texture. # -------------------------------------- + - def_name: send + params: + - param_name: message + type: string + doc: > + The data to send. Note: maximum string length is 100 chars. + doc: > + Instructs the sensor to send the string given by `message` to all other CustomV2XSensors on the next tick. + # -------------------------------------- - def_name: __str__ # -------------------------------------- diff --git a/PythonAPI/docs/sensor_data.yml b/PythonAPI/docs/sensor_data.yml index 1e0e477e1..cdd394a56 100644 --- a/PythonAPI/docs/sensor_data.yml +++ b/PythonAPI/docs/sensor_data.yml @@ -15,7 +15,9 @@ - Obstacle detector: carla.ObstacleDetectionEvent.
- Radar sensor: carla.RadarMeasurement.
- RSS sensor: carla.RssResponse.
- - Semantic LIDAR sensor: carla.SemanticLidarMeasurement. + - Semantic LIDAR sensor: carla.SemanticLidarMeasurement.
+ - Cooperative awareness messages V2X sensor: carla.CAMEvent.
+ - Custom V2X messages V2X sensor: carla.CustomV2XEvent. # - PROPERTIES ------------------------- instance_variables: - var_name: frame @@ -878,7 +880,7 @@ - class_name: GBufferTextureID # - DESCRIPTION ------------------------ doc: > - Defines the identifiers of each GBuffer texture (See the method `carla.Sensor.listen_to_gbuffer`). + Defines the of each GBuffer texture (See the method `carla.Sensor.listen_to_gbuffer`). # - PROPERTIES ------------------------- instance_variables: - var_name: SceneColor @@ -941,4 +943,110 @@ The texture "CustomStencil" contains the Unreal Engine custom stencil data. # -------------------------------------- + + - class_name: CAMData + parent: carla.SensorData + # - DESCRIPTION ------------------------ + doc: > + This is the data type for cooperative awareness message reception, contained in a [CAMEvent](#carlacamevent) + # - PROPERTIES ------------------------- + instance_variables: + - var_name: power + type: float - dBm + doc: > + Received power. + + # - METHODS ---------------------------- + # -------------------------------------- + methods: + - def_name: get + return: dict + doc: > + Get the CAM data. Returns a nested dictionary containing the message following the ETSI standard: - `Header`: dict - `Message`: dict + # -------------------------------------- + - def_name: __str__ + # -------------------------------------- + + - class_name: CAMEvent + parent: carla.SensorData + # - DESCRIPTION ------------------------ + doc: > + Class that defines the data provided by a **sensor.other.v2x**. This is a collection type to combine returning several [CAMData](#carlacamdata). + # - PROPERTIES ------------------------- + instance_variables: + + # - METHODS ---------------------------- + # -------------------------------------- + methods: + - def_name: get_message_count + return: int + doc: > + Get the number of received CAM's. + # -------------------------------------- + - def_name: __get_item__ + params: + - param_name: pos + type: int + # -------------------------------------- + - def_name: __iter__ + doc: > + Iterate over the [CAMData](#carlacamdata) retrieved as data. + # -------------------------------------- + - def_name: __len__ + # -------------------------------------- + + + - class_name: CustomV2XEvent + parent: carla.SensorData + # - DESCRIPTION ------------------------ + doc: > + Class that defines the data provided by a **sensor.other.v2x_custom**. This is a collection type to combine returning several [CustomV2XData](#carlacustomv2xdata). + # - PROPERTIES ------------------------- + instance_variables: + + # - METHODS ---------------------------- + # -------------------------------------- + methods: + - def_name: get_message_count + return: int + doc: > + Get the number of received CAM's. + # -------------------------------------- + - def_name: __get_item__ + params: + - param_name: pos + type: int + # -------------------------------------- + - def_name: __iter__ + doc: > + Iterate over the [CustomV2XData](#carlacustomv2xdata) retrieved as data. + # -------------------------------------- + - def_name: __len__ + # -------------------------------------- + + + - class_name: CustomV2XData + parent: carla.SensorData + # - DESCRIPTION ------------------------ + doc: > + This is the data type defining a custom V2X message. Received as part of a [CustomV2XEvent](#carlacustomv2xevent). + # - PROPERTIES ------------------------- + instance_variables: + - var_name: power + type: float - dBm + doc: > + Received power. + + # - METHODS ---------------------------- + # -------------------------------------- + methods: + - def_name: get + return: dict + doc: > + Get the custom message. Returns a nested dictionary containing the message. It has two primary keys: - `Header` : dict - `Message`: str + # -------------------------------------- + - def_name: __str__ + # -------------------------------------- + + ... From ec7d8fd0379af782a3e953035044feed8f7c4071 Mon Sep 17 00:00:00 2001 From: evilzs1 <152964022+evilzs1@users.noreply.github.com> Date: Tue, 18 Jun 2024 18:04:40 +0800 Subject: [PATCH 48/99] Fixed fate error about number of wheels (#7800) --- .../Source/Carla/Recorder/CarlaRecorderAnimVehicleWheels.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Recorder/CarlaRecorderAnimVehicleWheels.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Recorder/CarlaRecorderAnimVehicleWheels.cpp index a79162061..4cb890ca5 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Recorder/CarlaRecorderAnimVehicleWheels.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Recorder/CarlaRecorderAnimVehicleWheels.cpp @@ -37,12 +37,12 @@ void CarlaRecorderAnimWheels::Read(std::istream &InFile) ReadValue(InFile, DatabaseId); uint32_t NumWheels = 0; ReadValue(InFile, NumWheels); - WheelValues.reserve(NumWheels); + WheelValues.resize(NumWheels); for (size_t i = 0; i < NumWheels; ++i) { WheelInfo Wheel; Wheel.Read(InFile); - WheelValues.push_back(Wheel); + WheelValues[i] = Wheel; } } From 4da0c7415499981f29874b899edd00c1368df06f Mon Sep 17 00:00:00 2001 From: Daniel Date: Fri, 14 Jun 2024 17:39:30 +0200 Subject: [PATCH 49/99] Rework of BasicAgent's set_destination. Covers the 4 cases start_location=[None (default)/ not None] clean_queue = [True (default), False) --- .../carla/agents/navigation/basic_agent.py | 31 ++++++++++++------- 1 file changed, 19 insertions(+), 12 deletions(-) diff --git a/PythonAPI/carla/agents/navigation/basic_agent.py b/PythonAPI/carla/agents/navigation/basic_agent.py index aeddc005e..2d0b9b91a 100644 --- a/PythonAPI/carla/agents/navigation/basic_agent.py +++ b/PythonAPI/carla/agents/navigation/basic_agent.py @@ -139,30 +139,37 @@ class BasicAgent(object): def get_global_planner(self): """Get method for protected member local planner""" return self._global_planner - - def set_destination(self, end_location, start_location=None): + + def set_destination(self, end_location, start_location=None, clean_queue=True): + # type: (carla.Location, carla.Location | None, bool) -> None """ This method creates a list of waypoints between a starting and ending location, based on the route returned by the global router, and adds it to the local planner. - If no starting location is passed, the vehicle local planner's target location is chosen, - which corresponds (by default), to a location about 5 meters in front of the vehicle. + If no starting location is passed and `clean_queue` is True, the vehicle local planner's + target location is chosen, which corresponds (by default), to a location about 5 meters + in front of the vehicle. + If `clean_queue` is False the newly planned route will be appended to the current route. :param end_location (carla.Location): final location of the route :param start_location (carla.Location): starting location of the route + :param clean_queue (bool): Whether to clear or append to the currently planned route """ if not start_location: - start_location = self._local_planner.target_waypoint.transform.location - clean_queue = True - else: - start_location = self._vehicle.get_location() - clean_queue = False - + if clean_queue and self._local_planner.target_waypoint: + # Plan from the waypoint in front of the vehicle onwards + start_location = self._local_planner.target_waypoint.transform.location + elif not clean_queue and self._local_planner._waypoints_queue: + # Append to the current plan + start_location = self._local_planner._waypoints_queue[-1][0].transform.location + else: + # no target_waypoint or _waypoints_queue empty, use vehicle location + start_location = self._vehicle.get_location() start_waypoint = self._map.get_waypoint(start_location) end_waypoint = self._map.get_waypoint(end_location) - + route_trace = self.trace_route(start_waypoint, end_waypoint) self._local_planner.set_global_plan(route_trace, clean_queue=clean_queue) - + def set_global_plan(self, plan, stop_waypoint_creation=True, clean_queue=True): """ Adds a specific plan to the agent. From e349dc79c92f222750fde1dceca88188eacf8a5a Mon Sep 17 00:00:00 2001 From: Blyron Date: Mon, 8 Jul 2024 09:50:31 +0200 Subject: [PATCH 50/99] Add wheelchair variation --- LibCarla/source/carla/rpc/ActorAttributeType.h | 10 +++++----- .../Carla/Actor/ActorBlueprintFunctionLibrary.cpp | 7 +++++++ 2 files changed, 12 insertions(+), 5 deletions(-) diff --git a/LibCarla/source/carla/rpc/ActorAttributeType.h b/LibCarla/source/carla/rpc/ActorAttributeType.h index dda52939f..9ecf822b6 100644 --- a/LibCarla/source/carla/rpc/ActorAttributeType.h +++ b/LibCarla/source/carla/rpc/ActorAttributeType.h @@ -12,11 +12,11 @@ namespace carla { namespace rpc { enum class ActorAttributeType : uint8_t { - Bool, - Int, - Float, - String, - RGBColor, + Bool = 1u, + Int = 2u, + Float = 3u, + String = 4u, + RGBColor = 5u, SIZE, INVALID diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp index 2de3050a2..0876f6160 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp @@ -1613,6 +1613,13 @@ void UActorBlueprintFunctionLibrary::MakePedestrianDefinition( IsInvincible.bRestrictToRecommended = false; Definition.Variations.Emplace(IsInvincible); + FActorVariation WheelChairVariation; + WheelChairVariation.Id = TEXT("use_wheelchair"); + WheelChairVariation.Type = EActorAttributeType::Bool; + WheelChairVariation.RecommendedValues = { TEXT("true"), TEXT("false") }; + WheelChairVariation.bRestrictToRecommended = false; + Definition.Variations.Emplace(WheelChairVariation); + Success = CheckActorDefinition(Definition); } From 8ba08e1f7efddf6513ee3c3a4b97db991f812950 Mon Sep 17 00:00:00 2001 From: Blyron Date: Mon, 8 Jul 2024 10:07:32 +0200 Subject: [PATCH 51/99] Update size value --- PythonAPI/carla/source/libcarla/Blueprint.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/PythonAPI/carla/source/libcarla/Blueprint.cpp b/PythonAPI/carla/source/libcarla/Blueprint.cpp index e711290e4..9f3c04664 100644 --- a/PythonAPI/carla/source/libcarla/Blueprint.cpp +++ b/PythonAPI/carla/source/libcarla/Blueprint.cpp @@ -37,7 +37,7 @@ namespace client { std::ostream &operator<<(std::ostream &out, const ActorAttribute &attr) { using Type = carla::rpc::ActorAttributeType; - static_assert(static_cast(Type::SIZE) == 5u, "Please update this function."); + static_assert(static_cast(Type::SIZE) == 6u, "Please update this function."); out << "ActorAttribute(id=" << attr.GetId(); switch (attr.GetType()) { case Type::Bool: From cf3cef936be7462337c1396780e19e862bdc19b3 Mon Sep 17 00:00:00 2001 From: Blyron Date: Mon, 8 Jul 2024 11:34:40 +0200 Subject: [PATCH 52/99] Add control variable --- .../Actor/ActorBlueprintFunctionLibrary.cpp | 19 +++++++++++++++++-- .../Source/Carla/Actor/PedestrianParameters.h | 3 +++ .../Carla/Source/Carla/Walker/WalkerBase.h | 3 +++ 3 files changed, 23 insertions(+), 2 deletions(-) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp index 0876f6160..823859d4d 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp @@ -1593,6 +1593,12 @@ void UActorBlueprintFunctionLibrary::MakePedestrianDefinition( EActorAttributeType::String, GetAge(Parameters.Age)}); + + Definition.Attributes.Emplace(FActorAttribute{ + TEXT("can_use_wheel_chair"), + EActorAttributeType::Bool, + Parameters.bCanUseWheelChair ? TEXT("true") : TEXT("false") }); + if (Parameters.Speed.Num() > 0) { FActorVariation Speed; @@ -1606,6 +1612,8 @@ void UActorBlueprintFunctionLibrary::MakePedestrianDefinition( Definition.Variations.Emplace(Speed); } + bool bCanUseWheelChair = Parameters.bCanUseWheelChair; + FActorVariation IsInvincible; IsInvincible.Id = TEXT("is_invincible"); IsInvincible.Type = EActorAttributeType::Bool; @@ -1616,8 +1624,15 @@ void UActorBlueprintFunctionLibrary::MakePedestrianDefinition( FActorVariation WheelChairVariation; WheelChairVariation.Id = TEXT("use_wheelchair"); WheelChairVariation.Type = EActorAttributeType::Bool; - WheelChairVariation.RecommendedValues = { TEXT("true"), TEXT("false") }; - WheelChairVariation.bRestrictToRecommended = false; + if(bCanUseWheelChair) + { + WheelChairVariation.RecommendedValues = { TEXT("true"), TEXT("false") }; + } + else + { + WheelChairVariation.RecommendedValues = { TEXT("false") }; + } + WheelChairVariation.bRestrictToRecommended = true; Definition.Variations.Emplace(WheelChairVariation); Success = CheckActorDefinition(Definition); diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/PedestrianParameters.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/PedestrianParameters.h index 86310a6d9..7572e9b3a 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/PedestrianParameters.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/PedestrianParameters.h @@ -55,4 +55,7 @@ struct CARLA_API FPedestrianParameters UPROPERTY(EditAnywhere, BlueprintReadWrite) int32 Generation = 0; + + UPROPERTY(EditAnywhere, BlueprintReadWrite) + bool bCanUseWheelChair = false; }; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Walker/WalkerBase.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Walker/WalkerBase.h index 676569ed4..5990bceeb 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Walker/WalkerBase.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Walker/WalkerBase.h @@ -24,6 +24,9 @@ public: UPROPERTY(Category="Walker Base", BlueprintReadWrite, EditAnywhere) float AfterLifeSpan = 10.0f; + UPROPERTY(Category="Walker Base", BlueprintReadWrite, EditAnywhere) + bool bUsesWheelChair = false; + UFUNCTION(BlueprintCallable) void StartDeathLifeSpan() { From 4952c747297561e0b348dd8faa21d256b41f6406 Mon Sep 17 00:00:00 2001 From: MattRoweEAIF <125647690+MattRoweEAIF@users.noreply.github.com> Date: Thu, 11 Jul 2024 14:40:52 +0200 Subject: [PATCH 53/99] added cpp client build docs (#7942) --- Docs/adv_cpp_client.md | 142 +++++++++++++++++++++++++++++++ Docs/build_linux_ue5.md | 6 +- Docs/cpp_client_cmake_windows.md | 68 +++++++++++++++ Docs/ref_cpp.md | 11 +++ 4 files changed, 226 insertions(+), 1 deletion(-) create mode 100644 Docs/adv_cpp_client.md create mode 100644 Docs/cpp_client_cmake_windows.md diff --git a/Docs/adv_cpp_client.md b/Docs/adv_cpp_client.md new file mode 100644 index 000000000..e1eb0b163 --- /dev/null +++ b/Docs/adv_cpp_client.md @@ -0,0 +1,142 @@ +# C++ client example + +To build the C++ client example you will need `make` installed. Before building a C++ client, you will need to build CARLA, follow the relevant [build instructions](build_carla.md) for your platform. + +Navigate to the `Examples/CppClient` folder in the CARLA repository and open a terminal. You will find a Makefile in this directory. To build and run it in Linux execute `make run` at the command prompt. In Windows, create a file named `CMakeLists.txt` in the same directory and add the contents in [this file](cpp_client_cmake_windows.md), then run `cmake`. + +This C++ example will connect to the server, spawn a vehicle and apply a command to the vehicle before destroying it and terminating. + +### Include the relevant header files + +For this example, we will be using several different CARLA classes, so we need to include the relevant header files from the CARLA library and include any standard libraries we will use: + +```cpp +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +``` + +### Connecting the C++ client to the server + +Include `carla/client/Client.h` and then connect the client: + +```cpp +... +#include +... +int main(int argc, const char *argv[]) { + + std::string host; + uint16_t port; + std::tie(host, port) = ParseArguments(argc, argv); + ... + // Connect the client to the server + auto client = cc::Client(host, port); + client.SetTimeout(40s); +``` + +### Load a map + +Now let's load a randomly chosen map: + +```cpp +// Initialize random number generator +std::mt19937_64 rng((std::random_device())()); +... +auto town_name = RandomChoice(client.GetAvailableMaps(), rng); +std::cout << "Loading world: " << town_name << std::endl; +auto world = client.LoadWorld(town_name); +``` + +### Spawn a randomly chosen vehicle + +Next we will fetch the blueprint library, filter for vehicles and choose a random vehicle blueprint: + +```cpp +auto blueprint_library = world.GetBlueprintLibrary(); +auto vehicles = blueprint_library->Filter("vehicle"); +auto blueprint = RandomChoice(*vehicles, rng); +``` + +Now we need to find a location to spawn the vehicle from a spawn point in the map. We will get a pointer reference to the map object and then choose a random spawn point (ensure you have initialized the random number generator): + +```cpp +auto map = world.GetMap(); +auto transform = RandomChoice(map->GetRecommendedSpawnPoints(), rng); +``` + +Now we have the blueprint and spawn location, we can now spawn the vehicle using the `world.SpawnActor(...)` method: + +```cpp +auto actor = world.SpawnActor(blueprint, transform); +std::cout << "Spawned " << actor->GetDisplayId() << '\n'; +// Retrieve a pointer to the vehicle object +auto vehicle = boost::static_pointer_cast(actor); +``` + +### Apply a control + +Let's now apply some control to the vehicle to move it using the `ApplyControl(...)` method: + +```cpp +cc::Vehicle::Control control; +control.throttle = 1.0f; +vehicle->ApplyControl(control); +``` + +Now we will relocate the spectator so that we can see our newly spawned vehicle in the map: + +```cpp +auto spectator = world.GetSpectator(); +// Adjust the transform to look +transform.location += 32.0f * transform.GetForwardVector(); +transform.location.z += 2.0f; +transform.rotation.yaw += 180.0f; +transform.rotation.pitch = -15.0f; +// Now set the spectator transform +spectator->SetTransform(transform); +``` + +We'll also sleep the process for 10 seconds to observe the simulation shortly, before the client closes: + + +```cpp +std::this_thread::sleep_for(10s); + +``` + +If you wish to keep the client open while other commands are executed, create a game loop. Now you have loaded a map and spawned a vehicle. To further explore the C++ API [build the Doxygen documentation](ref_cpp.md#c-documentation) and open it in a browser. + +To build the C++ client in another location outside of the CARLA repository, edit the first 5 lines of the Makefile to reference the correct locations for the `/build` directory and the CARLA build location: + +```make +CARLADIR=$(CURDIR)/../.. +BUILDDIR=$(CURDIR)/build +BINDIR=$(CURDIR)/bin +INSTALLDIR=$(CURDIR)/libcarla-install +TOOLCHAIN=$(CURDIR)/ToolChain.cmake +``` + + + + + + + diff --git a/Docs/build_linux_ue5.md b/Docs/build_linux_ue5.md index 62a270441..54de572a3 100644 --- a/Docs/build_linux_ue5.md +++ b/Docs/build_linux_ue5.md @@ -88,4 +88,8 @@ If you want to install the Python API corresponding to the package you have buil ```sh pip3 install PythonAPI/carla/dist/carla-*.whl -``` \ No newline at end of file +``` + +## Additional build targets + +The procedure outlined above will download all necessary components to build CARLA, you may not want to \ No newline at end of file diff --git a/Docs/cpp_client_cmake_windows.md b/Docs/cpp_client_cmake_windows.md new file mode 100644 index 000000000..e4af27c83 --- /dev/null +++ b/Docs/cpp_client_cmake_windows.md @@ -0,0 +1,68 @@ +```make +cmake_minimum_required(VERSION 3.5.1) +project(example) + +link_directories( + ${RPCLIB_LIB_PATH}) + +file(GLOB example_sources "*.cpp" "*.h") + +file(GLOB example_client_sources "") + +set(carla_config client) +list(APPEND build_targets example_${carla_config}_debug) + +# Create targets for debug and release in the same build type. +foreach(target ${build_targets}) + + add_executable(${target} ${example_sources}) + + target_compile_definitions(${target} PUBLIC + -DLIBCARLA_ENABLE_PROFILER) + + target_include_directories(${target} SYSTEM PRIVATE + "../../LibCarla/source" + "../../Build/boost-1.80.0-install/include" + "../../Build/rpclib-install/include/" + "../../Build/recast-22dfcb-install/include/" + "../../Build/zlib-install/include/" + "../../Build/libpng-1.2.37-install/include/" + "../../LibCarla/source/third-party/") + + target_link_directories(${target} SYSTEM PRIVATE + "../../Build/boost-1.80.0-install/lib" + "../../Build/rpclib-install/lib/" + "../../Build/recast-22dfcb-install/lib/" + "../../Build/zlib-install/lib/" + "../../Build/libcarla-visualstudio/LibCarla/cmake/client/Release/" + "../../Build/libpng-1.2.37-install/lib/") + + target_include_directories(${target} PRIVATE + "${libcarla_source_path}/test") + + if (WIN32) + target_link_libraries(${target} "rpc.lib") + target_link_libraries(${target} "carla_client.lib") + target_link_libraries(${target} "DebugUtils.lib") + target_link_libraries(${target} "Detour.lib") + target_link_libraries(${target} "DetourCrowd.lib") + target_link_libraries(${target} "DetourTileCache.lib") + target_link_libraries(${target} "Recast.lib") + target_link_libraries(${target} "Shlwapi.lib") + else() + target_link_libraries(${target} "-lrpc") + endif() + + install(TARGETS ${target} DESTINATION test OPTIONAL) +endforeach(target) + +if (LIBCARLA_BUILD_DEBUG) + # Specific options for debug. + set_target_properties(example_${carla_config}_debug PROPERTIES COMPILE_FLAGS "${CMAKE_CXX_FLAGS_DEBUG}") + target_link_libraries(example_${carla_config}_debug "carla_${carla_config}${carla_target_postfix}_debug") + target_compile_definitions(example_${carla_config}_debug PUBLIC -DBOOST_ASIO_ENABLE_BUFFER_DEBUGGING) + if (CMAKE_BUILD_TYPE STREQUAL "Client") + target_link_libraries(example_${carla_config}_debug "${BOOST_LIB_PATH}/libboost_filesystem.a") + endif() +endif() +``` diff --git a/Docs/ref_cpp.md b/Docs/ref_cpp.md index 075b97a7d..41e03c99c 100644 --- a/Docs/ref_cpp.md +++ b/Docs/ref_cpp.md @@ -1,4 +1,15 @@ # C++ Reference + +## C++ client + +The C++ client can be built with `make` on Linux and `cmake` in Windows. An C++ client example is provided in the repository in `CARLA_ROOT/Examples/CppClient/main.cpp`. This example shows how to connect the C++ client to the CARLA server and use the API for some simple tasks. + +To build the example C++ client, open a terminal in the `CARLA_ROOT/Examples/CppClient` directory in the repository. Run `make` in this folder and then execute `./bin/cpp_client` to run the example. The example will choose a random map from those available then load it. It will then spawn a vehicle and apply a control to the vehicle. + +Please see the [C++ client example](adv_cpp_client.md) for more details on this example script. + +## C++ documentation + We use Doxygen to generate the documentation of our C++ code: [Libcarla/Source](http://carla.org/Doxygen/html/dir_b9166249188ce33115fd7d5eed1849f2.html)
From 5c2d2978a8fe7a0602f35ad82605a6b40b2cf96b Mon Sep 17 00:00:00 2001 From: MattRoweEAIF <125647690+MattRoweEAIF@users.noreply.github.com> Date: Wed, 17 Jul 2024 12:33:47 +0200 Subject: [PATCH 54/99] fixed IMU units (#7960) --- Docs/ref_sensors.md | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/Docs/ref_sensors.md b/Docs/ref_sensors.md index 5e1fd5e48..142798920 100644 --- a/Docs/ref_sensors.md +++ b/Docs/ref_sensors.md @@ -186,10 +186,11 @@ Provides measures that accelerometer, gyroscope and compass would retrieve for t | `timestamp` | double | Simulation time of the measurement in seconds since the beginning of the episode. | | `transform` | [carla.Transform](<../python_api#carlatransform>) | Location and rotation in world coordinates of the sensor at the time of the measurement. | | `accelerometer` | [carla.Vector3D](<../python_api#carlavector3d>) | Measures linear acceleration in `m/s^2`. | -| `gyroscope` | [carla.Vector3D](<../python_api#carlavector3d>) | Measures angular velocity in `rad/sec`. | -| `compass` | float | Orientation in radians. North is `(0.0, -1.0, 0.0)` in UE. | - +| `gyroscope` | [carla.Vector3D](<../python_api#carlavector3d>) | Measures angular velocity in `rad/s`. | +| `compass` | float | Orientation in radians. North is 0 radians. | +!!! note + For the compass, North is 0 radians. East is *pi*/2 radians, South is *pi* radians, West is 3*pi*/2 radians. North is in the direction of decreasing Y in CARLA's global coordinate system. East is in the direction of increasing X. The compass value converted to degrees is equal to 90 - yaw. --- ## Lane invasion detector From 29fbcce198534f4ea471376d615e5eb0b451e26c Mon Sep 17 00:00:00 2001 From: MattRoweEAIF <125647690+MattRoweEAIF@users.noreply.github.com> Date: Thu, 25 Jul 2024 16:02:13 +0200 Subject: [PATCH 55/99] Update README.md with new TinyURL links (#7988) --- README.md | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/README.md b/README.md index 8589994b0..72f85a537 100644 --- a/README.md +++ b/README.md @@ -19,12 +19,12 @@ environmental conditions. ### Download CARLA Linux: -* [**Get CARLA overnight build**](https://carla-releases.s3.us-east-005.backblazeb2.com/Linux/Dev/CARLA_Latest.tar.gz) -* [**Get AdditionalMaps overnight build**](https://carla-releases.s3.us-east-005.backblazeb2.com/Linux/Dev/AdditionalMaps_Latest.tar.gz) +* [**Get CARLA overnight build**](https://tiny.carla.org/carla-latest-linux) +* [**Get AdditionalMaps overnight build**](https://tiny.carla.org/additional-maps-latest-linux) Windows: -* [**Get CARLA overnight build**](https://carla-releases.s3.us-east-005.backblazeb2.com/Windows/Dev/CARLA_Latest.zip) -* [**Get AdditionalMaps overnight build**](https://carla-releases.s3.us-east-005.backblazeb2.com/Windows/Dev/AdditionalMaps_Latest.zip) +* [**Get CARLA overnight build**](https://tiny.carla.org/carla-latest-windows) +* [**Get AdditionalMaps overnight build**](https://tiny.carla.org/additional-maps-latest-windows) ### Recommended system From eeb507e5854bdf95a4712c6f6210c5dcb779f7f5 Mon Sep 17 00:00:00 2001 From: glopezdiest <58212725+glopezdiest@users.noreply.github.com> Date: Wed, 31 Jul 2024 10:37:32 +0200 Subject: [PATCH 56/99] Added inverse transform (#7999) Co-authored-by: glopezdiest --- PythonAPI/carla/source/libcarla/Geom.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/PythonAPI/carla/source/libcarla/Geom.cpp b/PythonAPI/carla/source/libcarla/Geom.cpp index 4c0281270..57e3941cf 100644 --- a/PythonAPI/carla/source/libcarla/Geom.cpp +++ b/PythonAPI/carla/source/libcarla/Geom.cpp @@ -237,6 +237,10 @@ void export_geom() { self.TransformPoint(location); return location; }, arg("in_point")) + .def("inverse_transform", +[](const cg::Transform &self, cg::Vector3D &location) { + self.InverseTransformPoint(location); + return location; + }, arg("in_point")) .def("transform_vector", +[](const cg::Transform &self, cg::Vector3D &vector) { self.TransformVector(vector); return vector; From f2695a17d17432fee31bccfaa28bce33b0169b94 Mon Sep 17 00:00:00 2001 From: Blyron <53337103+Blyron@users.noreply.github.com> Date: Wed, 31 Jul 2024 13:10:11 +0200 Subject: [PATCH 57/99] Aaron/fixwheelchair (#8001) * Fix OSM2ODR build * Updated fix wheelchair default value --- PythonAPI/examples/generate_traffic.py | 3 +++ .../Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp | 4 ++-- .../Plugins/Carla/Source/Carla/Walker/WalkerBase.cpp | 6 ++++++ .../CarlaUE4/Plugins/Carla/Source/Carla/Walker/WalkerBase.h | 1 + 4 files changed, 12 insertions(+), 2 deletions(-) diff --git a/PythonAPI/examples/generate_traffic.py b/PythonAPI/examples/generate_traffic.py index b3b646abf..ef1ec66b3 100755 --- a/PythonAPI/examples/generate_traffic.py +++ b/PythonAPI/examples/generate_traffic.py @@ -279,8 +279,11 @@ def main(): for spawn_point in spawn_points: walker_bp = random.choice(blueprintsWalkers) # set as not invincible + probability = random.randint(0,100 + 1); if walker_bp.has_attribute('is_invincible'): walker_bp.set_attribute('is_invincible', 'false') + if walker_bp.has_attribute('can_use_wheelchair') and probability < 11: + walker_bp.set_attribute('use_wheelchair', 'true') # set the max speed if walker_bp.has_attribute('speed'): if (random.random() > percentagePedestriansRunning): diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp index 823859d4d..dd657d6c2 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp @@ -1595,7 +1595,7 @@ void UActorBlueprintFunctionLibrary::MakePedestrianDefinition( Definition.Attributes.Emplace(FActorAttribute{ - TEXT("can_use_wheel_chair"), + TEXT("can_use_wheelchair"), EActorAttributeType::Bool, Parameters.bCanUseWheelChair ? TEXT("true") : TEXT("false") }); @@ -1626,7 +1626,7 @@ void UActorBlueprintFunctionLibrary::MakePedestrianDefinition( WheelChairVariation.Type = EActorAttributeType::Bool; if(bCanUseWheelChair) { - WheelChairVariation.RecommendedValues = { TEXT("true"), TEXT("false") }; + WheelChairVariation.RecommendedValues = { TEXT("false"), TEXT("true") }; } else { diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Walker/WalkerBase.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Walker/WalkerBase.cpp index 598bfd4bc..9bae6381b 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Walker/WalkerBase.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Walker/WalkerBase.cpp @@ -5,3 +5,9 @@ // For a copy, see . #include "WalkerBase.h" + + +AWalkerBase::AWalkerBase(const FObjectInitializer &ObjectInitializer) + : Super(ObjectInitializer) +{ +} \ No newline at end of file diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Walker/WalkerBase.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Walker/WalkerBase.h index 5990bceeb..1ac0014f4 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Walker/WalkerBase.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Walker/WalkerBase.h @@ -16,6 +16,7 @@ class CARLA_API AWalkerBase : public ACharacter GENERATED_BODY() + AWalkerBase(const FObjectInitializer &ObjectInitializer); public: UPROPERTY(Category="Walker Base", BlueprintReadWrite, EditAnywhere) From 1ef3f55c9555de401681cb26ce87f81718943624 Mon Sep 17 00:00:00 2001 From: MattRoweEAIF <125647690+MattRoweEAIF@users.noreply.github.com> Date: Wed, 31 Jul 2024 15:23:11 +0200 Subject: [PATCH 58/99] Docs/unit updates (#8007) * fixed IMU units * updated autitwheel version --- Docs/build_linux.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Docs/build_linux.md b/Docs/build_linux.md index 704aa8447..e292a71d5 100644 --- a/Docs/build_linux.md +++ b/Docs/build_linux.md @@ -129,7 +129,7 @@ pip3 install --user -Iv setuptools==47.3.1 && pip install --user distro && pip3 install --user distro && pip install --user wheel && -pip3 install --user wheel auditwheel +pip3 install --user wheel auditwheel==4.0.0 ``` --- From fd44ea0ca1a100a0d7de16754be1807452c47606 Mon Sep 17 00:00:00 2001 From: Minokori <73998474+Minokori@users.noreply.github.com> Date: Sat, 16 Dec 2023 16:08:10 +0800 Subject: [PATCH 59/99] Add a `*.pyi` file for auto-completion & hints. To enable auto-completion and hints in code editors such as VScode, create a `*.pyi` file. This feature is compatible with `python 3.9` and later versions. --- PythonAPI/carla/source/carla/libcarla.pyi | 5403 +++++++++++++++++++++ 1 file changed, 5403 insertions(+) create mode 100644 PythonAPI/carla/source/carla/libcarla.pyi diff --git a/PythonAPI/carla/source/carla/libcarla.pyi b/PythonAPI/carla/source/carla/libcarla.pyi new file mode 100644 index 000000000..c332a0dc9 --- /dev/null +++ b/PythonAPI/carla/source/carla/libcarla.pyi @@ -0,0 +1,5403 @@ +from enum import Enum +from typing import Callable, Iterable, Iterator, Union, overload + + +class AckermannControllerSettings(): + """Manages the settings of the Ackermann PID controller.""" + + # region Instance Variables + @property + def speed_kp() -> float: + """Proportional term of the speed PID controller.""" + ... + + @property + def speed_ki() -> float: + """Integral term of the speed PID controller.""" + ... + + @property + def speed_kd() -> float: + """Derivative term of the speed PID controller.""" + ... + + @property + def accel_kp() -> float: + """Proportional term of the acceleration PID controller.""" + ... + + @property + def accel_ki() -> float: + """Integral term of the acceleration PID controller.""" + ... + + @property + def accel_kd() -> float: + """Derivative term of the acceleration PID controller.""" + ... + # endregion + + # region Methods + def __init__(self, + speed_kp: float = 0.15, + speed_ki: float = 0.0, + speed_kd: float = 0.25, + accel_kp: float = 0.01, + accel_ki: float = 0.0, + accel_kd: float = 0.01) -> AckermannControllerSettings: + """Manages the settings of the Ackermann PID controller. + """ + # endregion + + # region Dunder Methods + def __eq__(self, __value: AckermannControllerSettings) -> bool: ... + + def __ne__(self, __value: AckermannControllerSettings) -> bool: ... + + def __str__(self) -> str: ... + # endregion + + +class Actor(): + """CARLA defines actors as anything that plays a role in the simulation or can be moved around. + + That includes: pedestrians, vehicles, sensors and traffic signs (considering traffic lights as part of these). Actors are spawned in the simulation by `carla.World` and they need for a `carla.ActorBlueprint` to be created. These blueprints belong into a library provided by CARLA, find more about them here. + https://carla.readthedocs.io/en/latest/bp_library/ + """ + + # region Instnce Variables + @property + def attributes() -> dict: + """A dictionary containing the attributes of the blueprint this actor was based on. + """ + ... + + @property + def id() -> int: + """Identifier for this actor. Unique during a given episode. + """ + ... + + @property + def type_id() -> str: + """The identifier of the blueprint this actor was based on, + + e.g., `vehicle.ford.mustang.`""" + ... + + @property + def is_alive() -> bool: + """Returns whether this object was destroyed using this actor handle.""" + ... + + @property + def is_active() -> bool: + """Returns whether this actor is active (`True`) or not (`False`).""" + ... + + @property + def is_dormant() -> bool: + """Returns whether this actor is dormant (`True`) or not (`False`) - the opposite of `is_active`.""" + ... + + @property + def parent() -> ["Actor"]: + """Actors may be attached to a parent actor that they will follow around. This is said actor.""" + ... + + @property + def semantic_tags() -> list[int]: + """A list of semantic tags provided by the blueprint listing components for this actor. + + E.g. a traffic light could be tagged with `Pole` and `TrafficLight`. These tags are used by the semantic segmentation sensor. Find more about this and other sensors here + https://carla.readthedocs.io/en/latest/ref_sensors/#semantic-segmentation-camera + """ + + @property + def actor_state() -> ActorState: + """Returns the carla.ActorState, which can identify if the actor is Active, Dormant or Invalid.""" + ... + + @property + def bounding_box() -> BoundingBox: + """Bounding box containing the geometry of the actor. Its location and rotation are relative to the actor it is attached to.""" + # endregion + + # region Methods + def add_angular_impulse(self, angular_impulse: Vector3D): + """Applies an angular impulse at the center of mass of the actor. + + This method should be used for instantaneous torques, usually applied once. Use `add_torque()` to apply rotation forces over a period of time. + + Args: + `angular_impulse (Vector3D - degrees*s)`: Angular impulse vector in global coordinates.\n + """ + ... + + def add_force(self, force: Vector3D): + """Applies a force at the center of mass of the actor. + + This method should be used for forces that are applied over a certain period of time. Use `add_impulse()` to apply an impulse that only lasts an instant. + + Args: + `force (Vector3D - N)`: Force vector in global coordinates.\n + """ + ... + + def add_impulse(self, impulse: Vector3D): + """Applies an impulse at the center of mass of the actor. + + This method should be used for instantaneous forces, usually applied once. Use `add_force()` to apply forces over a period of time. + + Args: + `impulse (Vector3D - N*s)`: Impulse vector in global coordinates.\n + """ + ... + + def add_torque(self, torque: Vector3D): + """Applies a torque at the center of mass of the actor. + + This method should be used for torques that are applied over a certain period of time. Use `add_angular_impulse()` to apply a torque that only lasts an instant. + + Args: + `torque (Vector3D - degrees)`: Torque vector in global coordinates.\n + """ + ... + + def destroy(self) -> bool: + """Tells the simulator to destroy this actor and returns True if it was successful. + + It has no effect if it was already destroyed. + + + Warning: This method blocks the script until the destruction is completed by the simulator. + """ + ... + + def disable_constant_velocity(self): + """Disables any constant velocity previously set for a `carla.Vehicle` actor. + """ + ... + + def enable_constant_velocity(self, velocity: Vector3D): + """Sets a vehicle's velocity vector to a constant value over time. + + The resulting velocity will be approximately the `velocity` being set, as with set_target_velocity(). + + + Note: Only `carla.Vehicle` actors can use this method. + + + Warning: Enabling a constant velocity for a vehicle managed by the `Traffic Manager` may cause conflicts. This method overrides any changes in velocity by the TM. + + Args: + `velocity (Vector3D - m/s)`: Velocity vector in local space.\n + """ + ... + # endregion + + # region Getters + def get_acceleration(self) -> Vector3D: + """Returns the actor's 3D acceleration vector the client recieved during last tick. + + The method does not call the simulator. + + Returns: + `Vector3D`: m/s^2\n + """ + ... + + def get_angular_velocity(self) -> Vector3D: + """Returns the actor's angular velocity vector the client recieved during last tick. + + The method does not call the simulator. + + Returns: + `Vector3D`: deg/s\n + """ + ... + + def get_location(self) -> Location: + """Returns the actor's location the client recieved during last tick. + + The method does not call the simulator. + + + Setter: `carla.Actor.set_location` + + Returns: + `Location`: - meters\n + """ + ... + + def get_transform(self) -> Transform: + """Returns the actor's transform (location and rotation) the client recieved during last tick. + + The method does not call the simulator. + + + Setter: `carla.Actor.set_transform` + + Returns: + `Transform`\n + """ + + def get_velocity(self) -> Vector3D: + """Returns the actor's velocity vector the client recieved during last tick. + + The method does not call the simulator. + + Returns: + `Vector3D`: m/s\n + """ + ... + + def get_world(self) -> World: + """Returns the world this actor belongs to. + + Returns: + `World`\n + """ + ... + # endregion + + # region Setters + def set_enable_gravity(self, enabled: bool): + """Enables or disables gravity for the actor. + Default is `True`. + + Args: + `enabled (bool)`\n + """ + ... + + def set_location(self, location: Location): + """Teleports the actor to a given location. + + + Getter: `carla.Actor.get_location` + + Args: + `location (Location)`: meters\n + """ + ... + + def set_simulate_physics(self, enabled=True): + """Enables or disables the simulation of physics on this actor. + + Args: + `enabled (bool, optional)`: Defaults to True.\n + """ + ... + + def set_target_angular_velocity(self, angular_velocity: Vector3D): + """_summary_Sets the actor's angular velocity vector. + + This is applied before the physics step so the resulting angular velocity will be affected by external forces such as friction. + + Args: + `angular_velocity (Vector3D)`: deg/s\n + """ + ... + + def set_target_velocity(self, velocity: Vector3D): + """Sets the actor's velocity vector. + + This is applied before the physics step so the resulting angular velocity will be affected by external forces such as friction. + + Args: + `velocity (Vector3D)`\n + """ + ... + + def set_transform(self, transform: Transform): + """Teleports the actor to a given transform (location and rotation). + + + Getter: `carla.Actor.get_transform` + + Args: + `transform (Transform)`\n + """ + ... + # endregion + + # region Dunder Methods + def __str__(self) -> str: ... + # endregion + + +class ActorAttribute(): + """CARLA provides a library of blueprints for actors that can be accessed as `carla.BlueprintLibrary`. Each of these blueprints has a series of attributes defined internally. Some of these are modifiable, others are not. A list of recommended values is provided for those that can be set. + """ + + # region Instance Variables + @property + def id() -> str: + """The attribute's name and identifier in the library. + """ + @property + def is_modifiable() -> bool: + """It is True if the attribute's value can be modified.""" + @property + def recommended_values() -> list[str]: + """A list of values suggested by those who designed the blueprint.""" + @property + def type() -> ActorAttributeType: + """The attribute's parameter type.""" + # endregion + + # region Methods + def as_bool(self) -> bool: + """Reads the attribute as boolean value.""" + ... + + def as_color(self) -> Color: + """Reads the attribute as `carla.Color`.""" + ... + + def as_float(self) -> float: + """Reads the attribute as float.""" + ... + + def as_int(self) -> int: + """Reads the attribute as int.""" + ... + + def as_str(self) -> str: + """Reads the attribute as string.""" + ... + # endregion + + # region Dunder Methods + def __bool__(self) -> bool: ... + def __eq__(self, __value: Union[bool, int, float, str, Color, ActorAttribute]) -> bool: ... + def __float__(self) -> float: ... + def __int__(self) -> int: ... + def __ne__(self, __value: Union[bool, int, float, str, Color, ActorAttribute]) -> bool: ... + def __nonzero__(self) -> bool: ... + def __str__(self) -> str: ... + # endregion + + +class ActorAttributeType(Enum): + """CARLA provides a library of blueprints for actors in `carla.BlueprintLibrary` with different attributes each. This class defines the types those at `carla.ActorAttribute` can be as a series of enum. All this information is managed internally and listed here for a better comprehension of how CARLA works. + """ + # region Instance Variables + Bool = 0, + Int = 1, + Float = 2, + String = 3, + RGBColor = 4, + # endregion + + +class ActorBlueprint(): + """CARLA provides a blueprint library for actors that can be consulted through `carla.BlueprintLibrary`. Each of these consists of an identifier for the blueprint and a series of attributes that may be modifiable or not. This class is the intermediate step between the library and the actor creation. Actors need an actor blueprint to be spawned. These store the information for said blueprint in an object with its attributes and some tags to categorize them. The user can then customize some attributes and eventually spawn the actors through `carla.World`. + """ + + # region Instance Variables + @property + def id() -> str: + """The identifier of said blueprint inside the library. + + E.g. `walker.pedestrian.0001`.""" + + @property + def tags() -> list[str]: + """A list of tags each blueprint has that helps describing them. + + E.g. `['0001', 'pedestrian', 'walker']`. + """ + ... + # endregion + + # region Methods + def has_attribute(self, id: str) -> bool: + """Returns `True` if the blueprint contains the attribute `id`. + + Args: + `id (str)`: e.g. `gender` would return True for pedestrians' blueprints.\n + + Returns: + `bool`\n + """ + ... + + def has_tag(self, tag: str) -> bool: + """Returns `True` if the blueprint has the specified `tag` listed. + + Args: + `tag (str)`: e.g. `'walker'`\n + + Returns: + `bool`\n + """ + ... + + def match_tags(self, wildcard_pattern: str) -> bool: + """Returns `True` if any of the tags listed for this blueprint matches `wildcard_pattern`. + + Matching follows `fnmatch` standard. https://docs.python.org/3.12/library/fnmatch.html + + Args: + `wildcard_pattern (str)`\n + + Returns: + `bool`\n + """ + # endregion + + # region Getters + def get_attribute(self, id: str) -> ActorAttribute: + """Returns the actor's attribute with `id` as identifier if existing. + + + Setter: `carla.ActorBlueprint.set_attribute` + + Args: + `id (str)`\n + + Returns: + `ActorAttribute`\n + """ + ... + # endregion + + # region Setters + def set_attribute(self, id: str, value: str): + """If the `id` attribute is modifiable, changes its value to `value`. + + Args: + `id (str)`: The identifier for the attribute that is intended to be changed.\n + `value (str)`: The new value for said attribute.\n + """ + # endregion + + # region Dunder Methods + def __iter__(self): + """Iterate over the `carla.ActorAttribute` that this blueprint has. + """ + ... + + def __len__(self) -> int: + """Returns the amount of attributes for this blueprint.""" + ... + + def __str__(self) -> str: ... + # endregion + + +class ActorList(): + """A class that contains every actor present on the scene and provides access to them. + + The list is automatically created and updated by the server and it can be returned using `carla.World`. + """ + + # region Methods + def filter(self, wildcard_pattern: str) -> list: + """Filters a list of Actors matching wildcard_pattern against their variable `type_id` (which identifies the blueprint used to spawn them). Matching follows fnmatch standard. + + Args: + `wildcard_pattern (str)`\n + + Returns: + `list`\n + """ + ... + + def find(self, actor_id: int) -> Actor: + """Finds an actor using its identifier and returns it or None if it is not present. + + Args: + `actor_id (int)`\n + + Returns: + `Actor`\n + """ + ... + # endregion + + # region Dunder methods + def __getitem__(self, pos: int) -> Actor: + """Returns the actor corresponding to pos position in the list.""" + ... + + def __iter__(self): + """Iterate over the `carla.Actor` contained in the list.""" + ... + + def __len__(self) -> int: + """Returns the amount of actors listed.""" + ... + + def __str__(self) -> str: + """Parses to the ID for every actor listed.""" + ... + # endregion + + +class ActorSnapshot(): + """A class that comprises all the information for an actor at a certain moment in time. These objects are contained in a `carla.WorldSnapshot` and sent to the client once every tick. + """ + + # region Instance Variables + @property + def id() -> int: + """An identifier for the snapshot itself.""" + ... + # endregion + + # region Getters + def get_acceleration(self) -> Vector3D: + """Returns the acceleration vector registered for an actor in that tick. + + Returns: + `Vector3D`: m/s^2\n + """ + ... + + def get_angular_velocity(self) -> Vector3D: + """Returns the angular velocity vector registered for an actor in that tick. + + Returns: + `Vector3D`: rad/s\n + """ + ... + + def get_transform(self) -> Transform: + """Returns the actor's transform (location and rotation) for an actor in that tick. + + Returns: + `Transform`\n + """ + ... + + def get_velocity(self) -> Vector3D: + """Returns the velocity vector registered for an actor in that tick. + + Returns: + `Vector3D`: m/s\n + """ + ... + # endregion + + +class ActorState(Enum): + """Class that defines the state of an actor.""" + # region Instance Variables + Invalid = 0, + """An actor is Invalid if a problem has occurred.""" + Active = 1, + """An actor is Active when it visualized and can affect other actors.""" + Dormant = 2, + """An actor is Dormant when it is not visualized and will not affect other actors through physics. For example, actors are dormant if they are on an unloaded tile in a large map.""" + # endregion + + +class AttachmentType(Enum): + """Class that defines attachment options between an actor and its parent. When spawning actors, these can be attached to another actor so their position changes accordingly. This is specially useful for sensors. The snipet in `carla.World.spawn_actor` shows some sensors being attached to a car when spawned. + + + Note that the attachment type is declared as an enum within the class.""" + + # region Instance Variables + Rigid = 0, + """With this fixed attachment the object follow its parent position strictly. This is the recommended attachment to retrieve precise data from the simulation.""" + SpringArm = 1, + """An attachment that expands or retracts the position of the actor, depending on its parent. This attachment is only recommended to record videos from the simulation where a smooth movement is needed. SpringArms are an Unreal Engine component so check the UE docs to learn more about them. + + https://docs.unrealengine.com/5.3/en-US/using-spring-arm-components-in-unreal-engine/ + + + Warning: The `SpringArm` attachment presents weird behaviors when an actor is spawned with a relative translation in the Z-axis (e.g. `child_location = Location(0,0,2)`). + """ + + SpringArmGhost = 2, + """An attachment like the previous one but that does not make the collision test, and that means that it does not expands or retracts the position of the actor. The term ghost is because then the camera can cross walls and other geometries. This attachment is only recommended to record videos from the simulation where a smooth movement is needed. SpringArms are an Unreal Engine component so check the UE docs to learn more about them. + + https://docs.unrealengine.com/5.3/en-US/using-spring-arm-components-in-unreal-engine/ + + + Warning: The `SpringArm` attachment presents weird behaviors when an actor is spawned with a relative translation in the Z-axis (e.g. `child_location = Location(0,0,2)`).""" + # endregion + + +class BlueprintLibrary(): + """A class that contains the blueprints provided for actor spawning. Its main application is to return `carla.ActorBlueprint` objects needed to spawn actors. Each blueprint has an identifier and attributes that may or may not be modifiable. The library is automatically created by the server and can be accessed through `carla.World`. + + Here is a reference containing every available blueprint and its specifics. + """ + + # region Methods + def filter(self, wildcard_pattern: str) -> BlueprintLibrary: + """Filters a list of blueprints matching the `wildcard_pattern` against the id and tags of every blueprint contained in this library and returns the result as a new one. Matching follows fnmatch standard. + + Args: + `wildcard_pattern (str)`\n + + Returns: + `BlueprintLibrary`\n + """ + + def filter_by_attribute(self, name: str, value: str) -> BlueprintLibrary: + """Filters a list of blueprints with a given attribute matching the `value` against every blueprint contained in this library and returns the result as a new one. Matching follows fnmatch standard. + + Args: + `name (str)`\n + `value (str)`\n + + Returns: + `ActorBlueprint`\n + """ + + def find(self, id: str) -> ActorBlueprint: + """Returns the blueprint corresponding to that identifier. + + Args: + `id (str)`\n + + Returns: + `ActorBlueprint`\n + """ + # endregion + + # region Dunder Methods + def __getitem__(self, pos: int) -> ActorBlueprint: + """Returns the blueprint stored in `pos` position inside the data structure containing them. + """ + + def __iter__(self): + """Iterate over the `carla.ActorBlueprint` stored in the library.""" + + def __len__(self): + """Returns the amount of blueprints comprising the library.""" + + def __str__(self) -> str: + """Parses the identifiers for every blueprint to string.""" + ... + # endregion + + +class BoundingBox(): + """Bounding boxes contain the geometry of an actor or an element in the scene. They can be used by `carla.DebugHelper` or a `carla.Client` to draw their shapes for debugging. Check out the snipet in `carla.DebugHelper.draw_box` where a snapshot of the world is used to draw bounding boxes for traffic lights. + """ + + # region Instance Variables + @property + def extent() -> Vector3D: + """Vector from the center of the box to one vertex. The value in each axis equals half the size of the box for that axis. `extent.x * 2` would return the size of the box in the X-axis. + + Returns: + `Vector3D`: meters\n + """ + @property + def location() -> Location: + """The center of the bounding box. + + Returns: + `Location`: meters\n + """ + + @property + def rotation() -> Rotation: + """The orientation of the bounding box.""" + # endregion + + # region Methods + def __init__(self, location: Location, extent: Vector3D) -> BoundingBox: + """Bounding boxes contain the geometry of an actor or an element in the scene. They can be used by `carla.DebugHelper` or a `carla.Client` to draw their shapes for debugging. Check out the snipet in `carla.DebugHelper.draw_box` where a snapshot of the world is used to draw bounding boxes for traffic lights. + + Args: + `location (Location)`: Center of the box, relative to its parent.\n + `extent (Vector3D)`: Vector containing half the size of the box for every axis.\n + + Returns: + `BoundingBox`\n + """ + ... + + def contains(self, world_point: Location, transform: Transform) -> bool: + """Returns `True` if a point passed in world space is inside this bounding box. + + + Args: + `world_point (Location)`: meters. The point in world space to be checked.\n + `transform (Transform)`: Contains location and rotation needed to convert this object's local space to world space.\n + + Returns: + `bool`\n + """ + # endregion + + # region Getters + def get_local_vertices(self) -> list[Location]: + """Returns a list containing the locations of this object's vertices in local space.""" + ... + + def get_world_vertices(self, transform: Transform) -> list[Location]: + """Returns a list containing the locations of this object's vertices in world space. + + Args: + `transform (Transform)`: Contains location and rotation needed to convert this object's local space to world space.\n + """ + ... + # endregion + + # region Dunder Methods + def __eq__(self, __value: BoundingBox) -> bool: + """Returns true if both location and extent are equal for this and `other`.""" + + def __ne__(self, __value: BoundingBox) -> bool: + """Returns true if either location or extent are different for this and `other`.""" + + def __str__(self) -> str: + """Parses the location and extent of the bounding box to string.""" + # endregion + + +class CityObjectLabel(Enum): + """Enum declaration that contains the different tags available to filter the bounding boxes returned by carla.World.get_level_bbs(). These values correspond to the semantic tag that the elements in the scene have.""" + None, + Buildings = 1, + Fences = 2, + Other = 3, + Pedestrians = 4, + Poles = 5, + RoadLines = 6, + Roads = 7, + Sidewalks = 8, + TrafficSigns = 9, + Vegetation = 10, + Vehicles = 11, + Walls = 12, + Sky = 13, + Ground = 14, + Bridge = 15, + RailTrack = 16, + GuardRail = 17, + TrafficLight = 18, + Static = 19, + Dynamic = 20, + Water = 21, + Terrain = 22, + Any = 23 + + +class Client(): + """The Client connects CARLA to the server which runs the simulation. Both server and client contain a CARLA library (libcarla) with some differences that allow communication between them. Many clients can be created and each of these will connect to the RPC server inside the simulation to send commands. The simulation runs server-side. Once the connection is established, the client will only receive data retrieved from the simulation. Walkers are the exception. The client is in charge of managing pedestrians so, if you are running a simulation with multiple clients, some issues may arise. For example, if you spawn walkers through different clients, collisions may happen, as each client is only aware of the ones it is in charge of. + + The client also has a recording feature that saves all the information of a simulation while running it. This allows the server to replay it at will to obtain information and experiment with it. Here is some information about how to use this recorder. + + https://carla.readthedocs.io/en/latest/adv_recorder/ + """ + # region Methods + + def __init__(self, host="127.0.0.1", port=2000, worker_threads=0) -> Client: + """Client constructor. + + Args: + `host (str, optional)`: IP address where a CARLA Simulator instance is running. Defaults to "127.0.0.1".\n + `port (int, optional)`: TCP port where the CARLA Simulator instance is running. Defaults to 2000 and the subsequent 2001.\n + `worker_threads (int, optional)`: Number of working threads used for background updates. If 0, use all available concurrency. Defaults to 0.\n + + Returns: + `Client`: _description_\n + """ + + def apply_batch(self, commands: list[command]): + """Executes a list of commands on a single simulation step and retrieves no information. + + If you need information about the response of each command, use the `apply_batch_sync()` method. Here is an example on how to delete the actors that appear in `carla.ActorList` all at once. + + https://github.com/carla-simulator/carla/blob/master/PythonAPI/examples/generate_traffic.py + + Args: + `commands (list)`: A list of commands to execute in batch. Each command is different and has its own parameters. \n + """ + + def apply_batch_sync(self, commands: list[command], due_tick_cue=False) -> list[command.Response]: + """Executes a list of commands on a single simulation step, blocks until the commands are linked, and returns a list of command.Response that can be used to determine whether a single command succeeded or not. Here is an example of it being used to spawn actors. + + https://github.com/carla-simulator/carla/blob/master/PythonAPI/examples/generate_traffic.py + + Args: + `commands (list[command])`: A list of commands to execute in batch. The commands available are listed right above, in the method `apply_batch()`.\n + `due_tick_cue (bool, optional)`: A boolean parameter to specify whether or not to perform a `carla.World.tick` after applying the batch in synchronous mode. Defaults to False.\n + + Returns: + `list[command.Response]`\n + """ + + def generate_opendrive_world(self, opendrive: str, parameters: OpendriveGenerationParameters = (2.0, 50.0, 1.0, 0.6, True, True), reset_settings=True): + """Loads a new world with a basic 3D topology generated from the content of an OpenDRIVE file. This content is passed as a `string` parameter. It is similar to `client.load_world(map_name)` but allows for custom OpenDRIVE maps in server side. Cars can drive around the map, but there are no graphics besides the road and sidewalks. + + Args: + `opendrive (str)`: Content of an OpenDRIVE file as `string`, not the path to the `.xodr`.\n + `parameters (OpendriveGenerationParameters, optional)`: Additional settings for the mesh generation. Defaults to (2.0, 50.0, 1.0, 0.6, True, True).\n + `reset_settings (bool, optional)`: Option to reset the episode setting to default values, set to false to keep the current settings. This is useful to keep sync mode when changing map and to keep deterministic scenarios. Defaults to True.\n + """ + + def load_world(self, map_name: str, reset_settings=True, map_layers=MapLayer.All): + """Creates a new world with default settings using `map_name` map. All actors in the current world will be destroyed. + + + Warning: `map_layers` are only available for "Opt" maps + + Args: + `map_name (str)`: Name of the map to be used in this world. Accepts both full paths and map names,e.g. `'/Game/Carla/Maps/Town01'` or `'Town01'`. Remember that these paths are dynamic.\n + `reset_settings (bool, optional)`: Option to reset the episode setting to default values, set to false to keep the current settings. This is useful to keep sync mode when changing map and to keep deterministic scenarios. Defaults to True.\n + `map_layers (MapLayer, optional)`: Layers of the map that will be loaded. This parameter works like a flag mask. Defaults to MapLayer.All.\n + """ + + def reload_world(self, reset_settings=True): + """Reload the current world, note that a new world is created with default settings using the same map. All actors present in the world will be destroyed, but traffic manager instances will stay alive. + + Args: + `reset_settings (bool, optional)`: Option to reset the episode setting to default values, set to false to keep the current settings. This is useful to keep sync mode when changing map and to keep deterministic scenarios. Defaults to True.\n + + Raises: + `RuntimeError` when corresponding. + """ + + def replay_file(self, name: str, start: float, duration: float, follow_id: int, replay_sensors: bool): + """Load a new world with default settings using `map_name` map. All actors present in the current world will be destroyed, but traffic manager instances will stay alive. + + Args: + `name (str)`: Name of the file containing the information of the simulation.\n + `start (float - seconds)`: Time where to start playing the simulation. Negative is read as beginning from the end, being -10 just 10 seconds before the recording finished.\n + `duration (float - seconds)`: Time that will be reenacted using the information `name` file. If the end is reached, the simulation will continue.\n + `follow_id (int)`: ID of the actor to follow. If this is 0 then camera is disabled.\n + `replay_sensors (bool)`: Flag to enable or disable the spawn of sensors during playback.\n + """ + + def request_file(self, name: str): + """Requests one of the required files returned by `carla.Client.get_required_files`. + + Args: + `name (str)`: Name of the file you are requesting.\n + """ + + def show_recorder_actors_blocked(self, filename: str, min_time: float, min_distance: float) -> str: + """The terminal will show the information registered for actors considered blocked. An actor is considered blocked when it does not move a minimum distance in a period of time, being these `min_distance` and `min_time`. + + Args: + `filename (str)`: Name of the recorded file to load.\n + `min_time (float - seconds)`: Minimum time the actor has to move a minimum distance before being considered blocked. Default is 60 seconds.\n + `min_distance (float - centimeters)`: Minimum distance the actor has to move to not be considered blocked. Default is 100 centimeters.\n + + Returns: + `str`\n + """ + + def show_recorder_collisions(self, filename: str, category1: str, category2: str) -> str: + """The terminal will show the collisions registered by the recorder. These can be filtered by specifying the type of actor involved. The categories will be specified in `category1` and `category2` as follows: 'h' = Hero, the one vehicle that can be controlled manually or managed by the user. 'v' = Vehicle 'w' = Walker 't' = Traffic light 'o' = Other 'a' = Any If you want to see only collisions between a vehicles and a walkers, use for `category1` as 'v' and `category2` as 'w' or vice versa. If you want to see all the collisions (filter off) you can use 'a' for both parameters. + + Args: + `filename (str)`: Name or absolute path of the file recorded, depending on your previous choice.\n + `category1 (str)`: Character variable specifying a first type of actor involved in the collision.\n + `category2 (str)`: Character variable specifying the second type of actor involved in the collision.\n + + Returns: + `str`\n + """ + + def show_recorder_file_info(self, filename: str, show_all: bool) -> str: + """The information saved by the recorder will be parsed and shown in your terminal as text (frames, times, events, state, positions...). The information shown can be specified by using the `show_all` parameter. Here is some more information about how to read the recorder file. + + https://carla.readthedocs.io/en/latest/ref_recorder_binary_file_format/ + + Args: + `filename (str)`: Name or absolute path of the file recorded, depending on your previous choice.\n + `show_all (bool)`: If `True`, returns all the information stored for every frame (traffic light states, positions of all actors, orientation and animation data...). If `False`, returns a summary of key events and frames.\n + + Returns: + `str`\n + """ + + def start_recorder(self, filename: str, additional_data=False): + """Enables the recording feature, which will start saving every information possible needed by the server to replay the simulation. + + Args: + `filename (str)`: Name of the file to write the recorded data. A simple name will save the recording in 'CarlaUE4/Saved/recording.log'. Otherwise, if some folder appears in the name, it will be considered an absolute path.\n + `additional_data (bool, optional)`: Enables or disable recording non-essential data for reproducing the simulation (bounding box location, physics control parameters, etc). Defaults to False.\n + """ + + def stop_recorder(self): + """Stops the recording in progress. If you specified a path in `filename`, the recording will be there. If not, look inside `CarlaUE4/Saved/`.""" + + def stop_replayer(self, keep_actors: bool): + """Stop current replayer. + + Args: + `keep_actors (bool)`: `True` if you want autoremove all actors from the replayer, or `False` to keep them.\n + """ + # endregion + + # region Getters + def get_available_maps(self) -> list[str]: + """Returns a list of strings containing the paths of the maps available on server. These paths are dynamic, they will be created during the simulation and so you will not find them when looking up in your files. One of the possible returns for this method would be: + + >>> ['/Game/Carla/Maps/Town01', '/Game/Carla/Maps/Town02', '/Game/Carla/Maps/Town03', '/Game/Carla/Maps/Town04', '/Game/Carla/Maps/Town05', '/Game/Carla/Maps/Town06', '/Game/Carla/Maps/Town07'] + """ + + def get_client_version(self) -> str: + """Returns the client libcarla version by consulting it in the "Version.h" file. Both client and server can use different libcarla versions but some issues may arise regarding unexpected incompatibilities. + """ + + def get_required_files(self, folder: str, download=True): + """Asks the server which files are required by the client to use the current map. Option to download files automatically if they are not already in the cache. + + Args: + `folder (str)`: Folder where files required by the client will be downloaded to.\n + `download (bool, optional)`: If `True`, downloads files that are not already in cache.. Defaults to True.\n + """ + + def get_server_version(self) -> str: + """Returns the server libcarla version by consulting it in the "Version.h" file. Both client and server should use the same libcarla version. + """ + + def get_trafficmanager(self, client_connection=8000) -> TrafficManager: + """Returns an instance of the traffic manager related to the specified port. If it does not exist, this will be created. + + Args: + `client_connection (int, optional)`: Port that will be used by the traffic manager.. Defaults to 8000.\n + """ + + def get_world(self) -> World: + """Returns the world object currently active in the simulation. This world will be later used for example to load maps. + """ + # endregion + + # region Setters + def set_files_base_folder(self, path: str): + """Specifies the base folder where the local cache for required files will be placed. + + Args: + `path (str)`: Specifies the base folder where the local cache for required files will be placed.\n + """ + + def set_replayer_ignore_hero(self, ignore_hero: bool): + """Enables or disables playback of the hero vehicle during a playback of a recorded simulation. + + Args: + `ignore_hero (bool)`: Enables or disables playback of the hero vehicle during a playback of a recorded simulation.\n + """ + + def set_replayer_ignore_spectator(self, ignore_spectator: bool): + """Determines whether the recorded spectator movements will be replicated by the replayer. + + Args: + `ignore_spectator (bool)`: Determines whether the recorded spectator movements will be replicated by the replayer.\n + """ + + def set_replayer_time_factor(self, time_factor=1.0): + """When used, the time speed of the reenacted simulation is modified at will. It can be used several times while a playback is in curse. + + Args: + `time_factor (float, optional)`: 1.0 means normal time speed. Greater than 1.0 means fast motion (2.0 would be double speed) and lesser means slow motion (0.5 would be half speed). Defaults to 1.0.\n + """ + + def set_timeout(self, second: float): + """Sets the maximum time a network call is allowed before blocking it and raising a timeout exceeded error. + + Args: + `second (float - seconds)`: New timeout value. Default is 5 seconds.\n + """ + + # endregion + + +class CollisionEvent(SensorData): + """Class that defines a collision data for sensor.other.collision. The sensor creates one of these for every collision detected. Each collision sensor produces one collision event per collision per frame. Multiple collision events may be produced in a single frame by collisions with multiple other actors. Learn more about this here. + + https://carla.readthedocs.io/en/latest/ref_sensors/#collision-detector + """ + # region Instance Variables + @property + def actor() -> Actor: + """The actor the sensor is attached to, the one that measured the collision.""" + @property + def other_actor() -> Actor: + """The second actor involved in the collision.""" + @property + def normal_impulse() -> Vector3D: + """Normal impulse resulting of the collision.(N*s)""" + # endregion + + +class Color(): + """Class that defines a 32-bit RGBA color.""" + + # region Instance Variables + @property + def r() -> int: + """Red color (0-255).""" + @property + def g() -> int: + """Green color (0-255).""" + @property + def b() -> int: + """Blue color (0-255).""" + @property + def a() -> int: + """Alpha channel (0-255).""" + # endregion + + # region Methods + def __init__(self, r=0, g=0, b=0, a=255) -> Color: + """Initializes a color, black by default. + + Args: + `r (int, optional)`: Red color (0-255). Defaults to 0.\n + `g (int, optional)`: Green color (0-255). Defaults to 0.\n + `b (int, optional)`: Blue color (0-255). Defaults to 0.\n + `a (int, optional)`: Alpha channel (0-255). Defaults to 255.\n + """ + # endregion + + # region Dunder Methods + def __eq__(self, __value: Color) -> bool: ... + def __ne__(self, __value: Color) -> bool: ... + def __str__(self) -> str: ... + # endregion + + +class ColorConverter(Enum): + """Class that defines conversion patterns that can be applied to a `carla.Image` in order to show information provided by `carla.Sensor`. Depth conversions cause a loss of accuracy, as sensors detect depth as float that is then converted to a grayscale value between 0 and 255. Take a look at the snipet in `carla.Sensor.listen` to see an example of how to create and save image data for `sensor.camera.semantic_segmentation`. + """ + + # region Instance Variables + Raw = 0, + """No changes applied to the image. Used by the `RGB camera`.""" + Depth = 1, + """Converts the image to a linear depth map. Used by the `depth camera`.""" + LogarithmicDepth = 2, + """Converts the image to a depth map using a logarithmic scale, leading to better precision for small distances at the expense of losing it when further away.""" + CityScapesPalette = 3, + """Converts the image to a segmented map using tags provided by the blueprint library. Used by the `semantic segmentation camera`.""" + # endregion + + +class DVSEvent(): + """Class that defines a DVS event. An event is a quadruple, so a tuple of 4 elements, with `x`, `y` pixel coordinate location, timestamp `t` and polarity `pol` of the event. Learn more about them here. + + https://carla.readthedocs.io/en/latest/ref_sensors/ + """ + + # region Instance Variables + @property + def x() -> int: + """X pixel coordinate.""" + @property + def x() -> int: + """Y pixel coordinate.""" + @property + def t() -> int: + """Timestamp of the moment the event happened.""" + @property + def pol() -> bool: + """Polarity of the event. True for positive and False for negative.""" + # endregion + + # region Dunder Methods + def __str__(self) -> str: ... + # endregion + + +class DVSEventArray(): + """Class that defines a stream of events in `carla.DVSEvent`. Such stream is an array of arbitrary size depending on the number of events. This class also stores the field of view, the height and width of the image and the timestamp from convenience. Learn more about them here. + + https://carla.readthedocs.io/en/latest/ref_sensors/ + """ + + # region Instance Variables + @property + def fov() -> float: + """Horizontal field of view of the image.""" + @property + def height() -> int: + """Image height in pixels.""" + @property + def width() -> int: + """Image width in pixels.""" + @property + def raw_data() -> bytes: ... + # endregion + + # region Methods + def to_array(self) -> Iterable: + """Converts the stream of events to an array of int values in the following order `[x, y, t, pol]`.""" + + def to_array_pol(self) -> Iterable: + """Returns an array with the polarity of all the events in the stream.""" + + def to_array_t(self) -> Iterable: + """Returns an array with the timestamp of all the events in the stream.""" + + def to_array_x(self) -> Iterable: + """Returns an array with X pixel coordinate of all the events in the stream.""" + + def to_array_y(self) -> Iterable: + """Returns an array with Y pixel coordinate of all the events in the stream.""" + + def to_image(self) -> Image: + """Converts the image following this pattern: blue indicates positive events, red indicates negative events.""" + # endregion + + # region Dunder Methods + def __getitem__(self, pos: int): ... + + def __iter__(self): + """Iterate over the `carla.DVSEvent` retrieved as data.""" + + def __len__(self): ... + def __setitem(self, pos: int, color: Color): ... + def __str__(self) -> str: ... + # endregion + + +class DebugHelper(): + """Helper class part of `carla.World` that defines methods for creating debug shapes. By default, shapes last one second. They can be permanent, but take into account the resources needed to do so. Take a look at the snipets available for this class to learn how to debug easily in CARLA.""" + + # region Methods + def draw_arrow(self, begin: Location, end: Location, thickness=0.1, arrow_size=0.1, color: Color = (255, 0, 0), life_time=-1.0): + """Draws an arrow from `begin` to `end` pointing in that direction. + + Args: + begin (Location): Point in the coordinate system where the arrow starts (meters). + end (Location): Point in the coordinate system where the arrow ends and points towards to (meters). + thickness (float, optional): Density of the line (meters). Defaults to 0.1. + arrow_size (float, optional): Size of the tip of the arrow (meters). Defaults to 0.1. + color (Color, optional): RGB code to color the object. Defaults to (255,0,0). + life_time (float, optional): Shape's lifespan. By default it only lasts one frame. Set this to `0` for permanent shapes (seconds). Defaults to -1.0. + """ + ... + + def draw_box(self, box: BoundingBox, rotation: Rotation, thickness=0.1, color: Color = (255, 0, 0), life_time=-1.0): + """Draws a box, ussually to act for object colliders. + + Args: + box (BoundingBox): Object containing a location and the length of a box for every axis. + rotation (Rotation): Orientation of the box according to Unreal Engine's axis system (degrees (pitch,yaw,roll)). + thickness (float, optional): Density of the lines that define the box (meters). Defaults to 0.1. + color (Color, optional): RGB code to color the object. Defaults to (255,0,0). + life_time (float, optional): Shape's lifespan. By default it only lasts one frame. Set this to `0` for permanent shapes. Defaults to -1.0. + """ + ... + + def draw_line(self, begin: Location, end: Location, thickness=0.1, color: Color = (255, 0, 0), life_time=-1.0): + """Draws a line in between `begin` and `end`. + + Args: + begin (Location): Point in the coordinate system where the line starts (meters). + end (Location): Spot in the coordinate system where the line ends (meters). + thickness (float, optional): Density of the line. Defaults to 0.1. + color (Color, optional): RGB code to color the object. Defaults to (255,0,0). + life_time (float, optional): Shape's lifespan. By default it only lasts one frame. Set this to `0` for permanent shapes. Defaults to -1.0. + """ + ... + + def draw_point(self, location: Location, size=0.1, color=(255, 0, 0), life_time=-1.0): + """Draws a point location. + + Args: + location (Location): Spot in the coordinate system to center the object (meters). + size (float, optional): Density of the point (meters). Defaults to 0.1. + color (tuple, optional): RGB code to color the object. Defaults to (255,0,0). + life_time (float, optional): Shape's lifespan. By default it only lasts one frame. Set this to 0 for permanent shapes (seconds). Defaults to -1.0. + """ + ... + + def draw_string(self, location: Location, text: str, draw_shadow=False, color: Color = (255, 0, 0), life_time=-1.0): + """Draws a string in a given location of the simulation which can only be seen server-side. + + Args: + location (Location): Spot in the simulation where the text will be centered (meters). + text (str): Text intended to be shown in the world. + draw_shadow (bool, optional): Casts a shadow for the string that could help in visualization. It is disabled by default. Defaults to False. + color (Color, optional): RGB code to color the string. Defaults to (255,0,0). + life_time (float, optional): Shape's lifespan. By default it only lasts one frame. Set this to `0` for permanent shapes (seconds). Defaults to -1.0. + """ + ... + # endregion + + +class EnvironmentObject(): + """Class that represents a geometry in the level, this geometry could be part of an actor formed with other EnvironmentObjects (i.e.: buildings).""" + + # region Instance Variables + @property + def transform() -> Transform: + """Contains the location and orientation of the EnvironmentObject in world space.""" + ... + + @property + def bounding_box() -> BoundingBox: + """Object containing a location, rotation and the length of a box for every axis in world space.""" + ... + + @property + def id() -> int: + """Unique ID to identify the object in the level.""" + ... + + @property + def name() -> str: + """Name of the EnvironmentObject.""" + ... + + @property + def type() -> CityObjectLabel: + """Semantic tag.""" + ... + # endregion + + # region Dunder Methods + def __str__(self) -> str: + """Parses the EnvironmentObject to a string and shows them in command line.""" + ... + # endregion + + +class FloatColor(): + """Class that defines a float RGBA color.""" + + # region Instance Variables + @property + def r() -> float: + """Red color.""" + ... + + @property + def g() -> float: + """Green color.""" + ... + + @property + def b() -> float: + """Blue color.""" + ... + + @property + def a() -> float: + """Alpha channel.""" + ... + # endregion + + # region Methods + def __init__(self, r=.0, g=.0, b=.0, a=1.0) -> FloatColor: + """Initializes a color, black by default. + + Args: + r (float, optional): Red color. Defaults to .0. + g (float, optional): Green color. Defaults to .0. + b (float, optional): Blue color. Defaults to .0. + a (float, optional): Alpha channel. Defaults to 1.0. + + Returns: + FloatColor + """ + ... + # endregion + + # region Dunder Methods + def __eq__(self, __value: FloatColor) -> bool: ... + def __ne__(self, __value: FloatColor) -> bool: ... + # endregion + + +class GBufferTextureID(Enum): + """Defines the identifiers of each GBuffer texture (See the method `carla.Sensor.listen_to_gbuffer`).""" + + # region Instance Variables + SceneColor = 0, + """The texture "SceneColor" contains the final color of the image.""" + SceneDepth = 1, + """The texture "SceneDepth" contains the depth buffer - linear in world units.""" + SceneStencil = 2, + """The texture "SceneStencil" contains the stencil buffer.""" + GBufferA = 3, + """The texture "GBufferA" contains the world-space normal vectors in the RGB channels. The alpha channel contains "per-object data".""" + GBufferB = 4, + """The texture "GBufferB" contains the metallic, specular and roughness in the RGB channels, respectively. The alpha channel contains a mask where the lower 4 bits indicate the shading model and the upper 4 bits contain the selective output mask.""" + GBufferC = 5, + """The texture "GBufferC" contains the diffuse color in the RGB channels, with the indirect irradiance in the alpha channel. + + If static lightning is not allowed, the alpha channel will contain the ambient occlusion instead.""" + GBufferD = 6, + """ + The contents of the "GBufferD" varies depending on the rendered object's material shading model (GBufferB): + MSM_Subsurface (2), MSM_PreintegratedSkin (3), MSM_TwoSidedFoliage (6): + RGB: Subsurface color. + A: Opacity. + MSM_ClearCoat (4): + R: Clear coat. + G: Roughness. + MSM_SubsurfaceProfile (5): + RGB: Subsurface profile. + MSM_Hair (7): + RG: World normal. + B: Backlit value. + MSM_Cloth (8): + RGB: Subsurface color. + A: Cloth value. + MSM_Eye (9): + RG: Eye tangent. + B: Iris mask. + A: Iris distance. + """ + GBufferE = 7, + """The texture "GBufferE" contains the precomputed shadow factors in the RGBA channels. This texture is unavailable if the selective output mask (GBufferB) does not have its 4th bit set.""" + GBufferF = 8, + """The texture "GBufferF" contains the world-space tangent in the RGB channels and the anisotropy in the alpha channel. This texture is unavailable if the selective output mask (GBufferB) does not have its 5th bit set.""" + Velocity = 9, + """The texture "Velocity" contains the screen-space velocity of the scene objects.""" + SSAO = 10, + """The texture "SSAO" contains the screen-space ambient occlusion texture.""" + CustomDepth = 11, + """The texture "CustomDepth" contains the Unreal Engine custom depth data.""" + CustomStencil = 12, + """The texture "CustomStencil" contains the Unreal Engine custom stencil data.""" + # endregion + + +class GearPhysicsControl(): + """Class that provides access to vehicle transmission details by defining a gear and when to run on it. This will be later used by `carla.VehiclePhysicsControl` to help simulate physics. + """ + + # region Instance Variables + def ratio() -> float: + """The transmission ratio of the gear.""" + ... + + def down_ratio() -> float: + """Quotient between current RPM and MaxRPM where the autonomous gear box should shift down.""" + def up_ratio() -> float: + """Quotient between current RPM and MaxRPM where the autonomous gear box should shift up.""" + # endregion + + # region Methods + def __init__(self, ratio=1.0, down_ratio=0.5, up_ratio=0.65) -> GearPhysicsControl: + """Class that provides access to vehicle transmission details by defining a gear and when to run on it. This will be later used by `carla.VehiclePhysicsControl` to help simulate physics. + + Args: + `ratio (float, optional)`: The transmission ratio of the gear. Defaults to 1.0.\n + `down_ratio (float, optional)`: Quotient between current RPM and MaxRPM where the autonomous gear box should shift down. Defaults to 0.5.\n + `up_ratio (float, optional)`: Quotient between current RPM and MaxRPM where the autonomous gear box should shift up. Defaults to 0.65.\n + + Returns: + `GearPhysicsControl`\n + """ + ... + # endregion + + # region Dunder Methods + def __eq__(self, __value: GearPhysicsControl) -> bool: ... + def __ne__(self, __value: GearPhysicsControl) -> bool: ... + def __str__(self) -> str: ... + # endregion + + +class GeoLocation(): + """Class that contains geographical coordinates simulated data. The `carla.Map` can convert simulation locations by using the tag in the OpenDRIVE file.""" + + # region Instance Variables + @property + def latitude() -> float: + """North/South value of a point on the map (degrees).""" + ... + + @property + def longitude() -> float: + """West/East value of a point on the map (degrees).""" + ... + + @property + def altitude() -> float: + """Height regarding ground level (meters).""" + ... + # endregion + + # region Methods + def __init__(self, latitude=0.0, longitude=0.0, altitude=0.0) -> GeoLocation: + """Class that contains geographical coordinates simulated data. The `carla.Map` can convert simulation locations by using the tag in the OpenDRIVE file. + + Args: + `latitude (float, optional)`: North/South value of a point on the map (degrees). Defaults to 0.0.\n + `longitude (float, optional)`: West/East value of a point on the map (degrees). Defaults to 0.0.\n + `altitude (float, optional)`: Height regarding ground level (meters). Defaults to 0.0.\n + """ + ... + # endregion + + # region Dunder Methods + def __eq__(self, __value: GeoLocation) -> bool: ... + def __ne__(self, __value: GeoLocation) -> bool: ... + def __str__(self) -> str: ... + # endregion + + +class GnssMeasurement(SensorData): + """Class that defines the Gnss data registered by a `sensor.other.gnss`. It essentially reports its position with the position of the sensor and an OpenDRIVE geo-reference.""" + + # region Instance Variables + @property + def altitude() -> float: + """Height regarding ground level (meters).""" + ... + + @property + def latitude() -> float: + """North/South value of a point on the map (degrees).""" + ... + + @property + def longitude() -> float: + """West/East value of a point on the map (degrees).""" + ... + # endregion + + # region Dunder Methods + def __str__(self) -> str: ... + # endregion + + +class IMUMeasurement(SensorData): + """Class that defines the data registered by a `sensor.other.imu`, regarding the sensor's transformation according to the current `carla.World`. It essentially acts as accelerometer, gyroscope and compass.""" + + # region Instance Variables + @property + def accelerometer() -> Vector3D: + """Linear acceleration (m/s2).""" + ... + + @property + def compass() -> float: + """Orientation with regard to the North ([0.0, -1.0, 0.0] in Unreal Engine) (radians).""" + ... + + @property + def gyroscope() -> Vector3D: + """Angular velocity. (rad/s)""" + ... + # endregion + + # region Dunder Methods + def __str__(self) -> str: ... + # endregion + + +class Image(SensorData): + """Class that defines an image of 32-bit BGRA colors that will be used as initial data retrieved by camera sensors. There are different camera sensors (currently three, RGB, depth and semantic segmentation) and each of these makes different use for the images. Learn more about them here. + + https://carla.readthedocs.io/en/latest/ref_sensors/""" + + # region Instance Variables + @property + def fov() -> float: + """Horizontal field of view of the image (degrees).""" + ... + + @property + def height() -> int: + """Image height in pixels.""" + ... + + @property + def width() -> int: + """Image width in pixels.""" + ... + + @property + def raw_data() -> bytes: + """Flattened array of pixel data, use reshape to create an image array.""" + ... + # endregion + + # region Methods + def convert(self, color_converter: ColorConverter): + """Converts the image following the `color_converter` pattern. + + Args: + `color_converter (ColorConverter)`\n + """ + + def save_to_disk(self, path: str, color_converter=ColorConverter.Raw): + """Saves the image to disk using a converter pattern stated as `color_converter`. The default conversion pattern is `Raw` that will make no changes to the image. + + Args: + `path (str)`:Path that will contain the image.\n + `color_converter (ColorConverter, optional)`: Default Raw will make no changes. Defaults to ColorConverter.Raw.\n + """ + # endregion + + # region Dunder Methods + def __getitem__(self, pos=int) -> Color: ... + + def __iter__(self) -> Iterator[Color]: + """terate over the `carla.Color` that form the image.""" + ... + + def __len__(self) -> int: ... + def __setitem__(self, pos: int, color: Color): ... + def __str__(self) -> str: ... + # endregion + + +class Junction(): + """Class that embodies the intersections on the road described in the OpenDRIVE file according to OpenDRIVE 1.4 standards.""" + + # region Instance Variables + def id() -> int: + """Identifier found in the OpenDRIVE file.""" + ... + + def bounding_box() -> BoundingBox: + """Bounding box encapsulating the junction lanes.""" + ... + # endregion + + # region Getters + def get_waypoints(self, lane_type: LaneType) -> list[tuple[Waypoint, Waypoint]]: + """Returns a list of pairs of waypoints. Every tuple on the list contains first an initial and then a final waypoint within the intersection boundaries that describe the beginning and the end of said lane along the junction. Lanes follow their OpenDRIVE definitions so there may be many different tuples with the same starting waypoint due to possible deviations, as this are considered different lanes. + + Args: + lane_type (LaneType): Type of lanes to get the waypoints. + + Returns: + list[tuple[Waypoint, Waypoint]] + """ + # endregion + + +class LabelledPoint(): + """Class that represent a position in space with a semantic label.""" + + # region Instance Variables + # TODO 类型未定义 + @property + def location() -> Location: + """Position in 3D space.""" + ... + + @property + def label(): + """Semantic tag of the point.""" + ... + # endregion + + +class Landmark(): + """Class that defines any type of traffic landmark or sign affecting a road. These class mediates between the OpenDRIVE 1.4 standard definition of the landmarks and their representation in the simulation. This class retrieves all the information defining a landmark in OpenDRIVE and facilitates information about which lanes does it affect and when. Landmarks will be accessed by `carla.Waypoint objects` trying to retrieve the regulation of their lane. Therefore some attributes depend on the waypoint that is consulting the landmark and so, creating the object.""" + + # region Instance Variables + @property + def road_id() -> int: + """The OpenDRIVE ID of the road where this landmark is defined. Due to OpenDRIVE road definitions, this road may be different from the road the landmark is currently affecting. It is mostly the case in junctions where the road diverges in different routes. + + Example: a traffic light is defined in one of the divergent roads in a junction, but it affects all the possible routes.""" + ... + + @property + def distance() -> float: + """Distance between the landmark and the waypoint creating the object (querying `get_landmarks` or `get_landmarks_of_type`) (meters).""" + ... + + @property + def s() -> float: + """Distance where the landmark is positioned along the geometry of the road `road_id` (meters).""" + ... + + @property + def t() -> float: + """Lateral distance where the landmark is positioned from the edge of the road `road_id` (meters).""" + ... + + @property + def id() -> str: + """Unique ID of the landmark in the OpenDRIVE file.""" + ... + + @property + def name() -> str: + """Name of the landmark in the in the OpenDRIVE file.""" + ... + + @property + def is_dynamic() -> bool: + """Indicates if the landmark has state changes over time such as traffic lights.""" + ... + + @property + def orientation() -> LandmarkOrientation: + """Indicates which lanes the landmark is facing towards to (degrees).""" + ... + + @property + def z_offset() -> float: + """Height where the landmark is placed (meters).""" + ... + + @property + def country() -> str: + """Country code where the landmark is defined (default to OpenDRIVE is Germany 2017).""" + ... + + @property + def type() -> str: + """Type identifier of the landmark according to the country code.""" + ... + + @property + def sub_type() -> str: + """Subtype identifier of the landmark according to the country code.""" + + @property + def value() -> float: + """Value printed in the signal (e.g. speed limit, maximum weight, etc).""" + + @property + def unit() -> str: + """Units of measurement for the attribute `value`.""" + ... + + @property + def height() -> float: + """Total height of the signal (meters).""" + + @property + def width() -> float: + """Total width of the signal (meters).""" + + @property + def text() -> str: + """Additional text in the signal.""" + + @property + def h_offset() -> float: + """Orientation offset of the signal relative to the the definition of `road_id` at `s` in OpenDRIVE (meters).""" + ... + + @property + def pitch() -> float: + """Pitch rotation of the signal (Y-axis in UE coordinates system) (meters).""" + + @property + def roll() -> float: + """Roll rotation of the signal (X-axis in UE coordinates system) (meters).""" + + @property + def waypoint() -> Waypoint: + """A waypoint placed in the lane of the one that made the query and at the `s` of the landmark. It is the first waypoint for which the landmark will be effective.""" + + @property + def transform() -> Transform: + """The location and orientation of the landmark in the simulation.""" + # endregion + + # region Getters + def get_lane_validities(self) -> list[tuple[int, int]]: + """Returns which lanes the landmark is affecting to. As there may be specific lanes where the landmark is not effective, the return is a list of pairs containing ranges of the `lane_id` affected: + + Example: In a road with 5 lanes, being 3 not affected: [(from_lane1,to_lane2),(from_lane4,to_lane5)].""" + # endregion + + +class LandmarkOrientation(Enum): + """Helper class to define the orientation of a landmark in the road. The definition is not directly translated from OpenDRIVE but converted for the sake of understanding.""" + + # region Instance Variables + Positive = 0, + """The landmark faces towards vehicles going on the same direction as the road's geometry definition (lanes 0 and negative in OpenDRIVE).""" + Negative = 1, + """The landmark faces towards vehicles going on the opposite direction to the road's geometry definition (positive lanes in OpenDRIVE).""" + Both = 2, + """Affects vehicles going in both directions of the road.""" + # endregion + + +class LandmarkType(Enum): + """Helper class containing a set of commonly used landmark types as defined by the default country code in the OpenDRIVE standard (Germany 2017). `carla.Landmark` does not reference this class. The landmark type is a string that varies greatly depending on the country code being used. This class only makes it easier to manage some of the most commonly used in the default set by describing them as an enum.""" + # region Instance Variables + Danger = "101", + LanesMerging = "121", + CautionPedestrian = "133", + CautionBicycle = "138" + LevelCrossing = "150", + StopSign = "206", + YieldSign = "205", + MandatoryTurnDirection = "209", + MandatoryLeftRightDirection = "211", + TwoChoiceTurnDirection = "214", + Roundabout = "215", + PassRightLeft = "222", + AccessForbidden = "250", + AccessForbiddenMotorvehicles = "251", + AccessForbiddenTrucks = "253", + AccessForbiddenBicycle = "254", + AccessForbiddenWeight = "263", + AccessForbiddenWidth = "264", + AccessForbiddenHeight = "265", + AccessForbiddenWrongDirection = "267", + ForbiddenUTurn = "272", + MaximumSpeed = "274", + ForbiddenOvertakingMotorvehicles = "276", + ForbiddenOvertakingTrucks = "277", + AbsoluteNoStop = "283", + RestrictedStop = "286", + HasWayNextIntersection = "301", + PriorityWay = "306", + PriorityWayEnd = "307", + CityBegin = "310", + CityEnd = "311", + Highway = "330", + DeadEnd = "357", + RecomendedSpeed = "380", + RecomendedSpeedEnd = "381", + # endregion + + +class LaneChange(Enum): + """Class that defines the permission to turn either left, right, both or none (meaning only going straight is allowed). This information is stored for every `carla.Waypoint` according to the OpenDRIVE file. The snipet in `carla.Map.get_waypoint` shows how a waypoint can be used to learn which turns are permitted.""" + + # region Instance Variables + NONE = 0, + """Traffic rules do not allow turning right or left, only going straight.""" + Right = 1, + """Traffic rules allow turning right.""" + Left = 2, + """Traffic rules allow turning left.""" + Both = 3, + """Traffic rules allow turning either right or left.""" + # endregion + + +class LaneInvasionEvent(SensorData): + """Class that defines lanes invasion for `sensor.other.lane_invasion`. It works only client-side and is dependant on OpenDRIVE to provide reliable information. The sensor creates one of this every time there is a lane invasion, which may be more than once per simulation step. Learn more about this here. + + https://carla.readthedocs.io/en/latest/ref_sensors/#lane-invasion-detector + """ + + # region Instance Variables + def actor() -> Actor: + """Gets the actor the sensor is attached to, the one that invaded another lane.""" + + def crossed_lane_markings() -> list[LaneMarking]: + """List of lane markings that have been crossed and detected by the sensor.""" + # endregion + + # region Dunder Methods + def __str__(self) -> str: ... + # endregion + + +class LaneMarking(): + """Class that gathers all the information regarding a lane marking according to OpenDRIVE 1.4 standard standard.""" + + # region Instance Variables + @property + def color() -> LaneMarkingColor: + """Actual color of the marking.""" + + @property + def lane_change() -> LaneChange: + """Permissions for said lane marking to be crossed.""" + + @property + def type() -> LaneMarkingType: + """Lane marking type.""" + + @property + def width() -> float: + """Horizontal lane marking thickness.""" + # endregion + + +class LaneMarkingColor(Enum): + """Class that defines the lane marking colors according to OpenDRIVE 1.4.""" + + # region Instance Variables + White = 0, + Standard = 0, + """White by default.""" + Blue = 1, + Green = 2, + Red = 3, + Yellow = 4, + Other = 5, + # endregion + + +class LaneMarkingType(Enum): + """Class that defines the lane marking types accepted by OpenDRIVE 1.4. The snipet in `carla.Map.get_waypoint` shows how a waypoint can be used to retrieve the information about adjacent lane markings. + + + Note on double types: Lane markings are defined under the OpenDRIVE standard that determines whereas a line will be considered "BrokenSolid" or "SolidBroken". For each road there is a center lane marking, defined from left to right regarding the lane's directions. The rest of the lane markings are defined in order from the center lane to the closest outside of the road. + """ + + # region Instance Variables + Other = 0, + Broken = 1, + Solid = 2, + SolidSolid = 3, + SolidBroken = 4, + BrokenSolid = 5, + BrokenBroken = 6, + BottsDots = 7, + Grass = 8, + Curb = 9, + NONE = 0, + # endregion + + +class LaneType(Enum): + """Class that defines the possible lane types accepted by OpenDRIVE 1.4. This standards define the road information. The snipet in `carla.Map.get_waypoint` makes use of a waypoint to get the current and adjacent lane types.""" + + # region Instance Variables + Any = -2, + NONE = 1, + """Every type except for `NONE`.""" + Driving = 2, + Stop = 4, + Shoulder = 8, + Biking = 16, + Sidewalk = 32, + Border = 64, + Restricted = 128, + Parking = 256, + Bidirectional = 512, + Median = 1024, + Special1 = 2048, + Special2 = 4096, + Special3 = 8192, + RoadWorks = 16384, + Tram = 32768, + Rail = 65536, + Entry = 131072, + Exit = 262144, + OffRamp = 524288, + OnRamp = 1048576, + # endregion + + +class LidarDetection(): + """Data contained inside a `carla.LidarMeasurement`. Each of these represents one of the points in the cloud with its location and its associated intensity.""" + # region Instance Variables + @property + def point() -> Location: + """Point in xyz coordinates (meters).""" + @property + def intensity() -> float: + """Computed intensity for this point as a scalar value between [0.0 , 1.0].""" + # endregion + + # region Dunder Methods + def __str__(self) -> str: ... + # endregion + + +class LidarMeasurement(SensorData): + """Class that defines the LIDAR data retrieved by a `sensor.lidar.ray_cast`. This essentially simulates a rotating LIDAR using ray-casting. Learn more about this here. + + https://carla.readthedocs.io/en/latest/ref_sensors/#lidar-raycast-sensor + """ + # region Instance Variables + @property + def channels() -> int: + """Number of lasers shot.""" + + @property + def horizontal_angle() -> float: + """Horizontal angle the LIDAR is rotated at the time of the measurement (radians).""" + + @property + def raw_data() -> bytes: + """Received list of 4D points. Each point consists of [x,y,z] coordinates plus the intensity computed for that point.""" + # endregion + + # region Methods + def save_to_disk(self, path: str): + """Saves the point cloud to disk as a `.ply` file describing data from 3D scanners. The files generated are ready to be used within `MeshLab`, an open source system for processing said files. Just take into account that axis may differ from Unreal Engine and so, need to be reallocated. + + Args: + path (str) + """ + # endregion + + # region Getters + def get_point_count(self, channel: int): + """Retrieves the number of points sorted by channel that are generated by this measure. Sorting by channel allows to identify the original channel for every point. + + Args: + channel (int) + """ + # endregion + + # region Dunder Methods + def __getitem__(self, pos: int) -> LidarDetection: ... + + def __iter__(self) -> Iterator[LidarDetection]: + """Iterate over the carla.LidarDetection retrieved as data.""" + ... + + def __len__(self): ... + def __setitem__(self, pos: int, detection: LidarDetection): ... + def __str__(self) -> str: ... + # endregion + + +class Light(): + """This class exposes the lights that exist in the scene, except for vehicle lights. The properties of a light can be queried and changed at will. Lights are automatically turned on when the simulator enters night mode (sun altitude is below zero).""" + + # region Instance Variables + @property + def color() -> Color: + """Color of the light.""" + ... + + @property + def id() -> int: + """Identifier of the light.""" + ... + + @property + def intensity() -> float: + """Intensity of the light. (lumens)""" + + @property + def is_on() -> bool: + """Switch of the light. It is `True` when the light is on. When the night mode starts, this is set to `True`.""" + ... + + @property + def location() -> Location: + """Position of the light (meters).""" + ... + + @property + def light_group() -> LightGroup: + """Group the light belongs to.""" + + @property + def light_state() -> LightState: + """State of the light. Summarizes its attributes, group, and if it is on/off.""" + # endregion + + # region Methods + def turn_off(self): + """Switches off the light.""" + ... + + def turn_on(self): + """Switches on the light.""" + ... + # endregion + + # region Setters + def set_color(self, color: Color): + """Changes the color of the light to color. + + Args: + color (Color) + """ + ... + + def set_intensity(self, intensity: float): + """Changes the intensity of the light to `intensity`. + + Args: + intensity (float): (lumens) + """ + + def set_light_group(self, light_group: LightGroup): + """Changes the light to the group `light_group`. + + Args: + light_group (LightGroup) + """ + + def set_light_state(self, light_state: LightState): + """Changes the state of the light to `light_state`. This may change attributes, group and turn the light on/off all at once. + + + Args: + light_state (LightState) + """ + # endregion + + +class LightGroup(Enum): + """This class categorizes the lights on scene into different groups. These groups available are provided as a enum values that can be used as flags. + + + Note. So far, though there is a `vehicle` group, vehicle lights are not available as `carla.Light` objects. These have to be managed using `carla.Vehicle` and `carla.VehicleLightState`.""" + + NONE = 0, + """All lights.""" + Vehicle = 1, + Street = 2, + Building = 3, + Other = 4, + + +class LightManager(): + """This class handles the lights in the scene. Its main use is to get and set the state of groups or lists of lights in one call. An instance of this class can be retrieved by the `carla.World.get_lightmanager()`. + + + Note. So far, though there is a `vehicle` group, vehicle lights are not available as `carla.Light` objects. These have to be managed using `carla.Vehicle` and `carla.VehicleLightState`. + """ + + # region Methods + def is_active(self, lights: list[Light]) -> list[bool]: + """Returns a list with booleans stating if the elements in `lights` are switched on/off. + + Args: + `lights (list[Light])`: List of lights to be queried.\n + + Returns: + `list[bool]`\n + """ + + def turn_off(self, lights: list[Light]): + """Switches off all the lights in `lights`. + + + Args: + `lights (list[Light])`: List of lights to be switched off.\n + """ + + def turn_on(self, lights: list[Light]): + """Switches on all the lights in `lights`. + + + Args: + `lights (list[Light])`: List of lights to be switched on.\n + """ + # endregion + + # region Getters + def get_all_lights(self, light_group: LightGroup = LightGroup.NONE) -> list[Light]: + """Returns a list containing the lights in a certain group. By default, the group is None. + + Args: + `light_group (LightGroup, optional)`: Group to filter the lights returned. Defaults to LightGroup.NONE.\n + """ + + def get_color(self, lights: list[Light]) -> list[Color]: + """Returns a list with the colors of every element in `lights`. + + + Setter: `carla.LightManager.set_color` + + Args: + `lights (list[Light])`: List of lights to be queried.\n + + Returns: + `list[Color]`: _description_\n + """ + + def get_intensity(self, lights: list[Light]) -> list[float]: + """Returns a list with the intensity of every element in `lights`. + + Args: + `lights (list[Light])`: List of lights to be queried.\n + + Returns: + `list[float]`: (lumens)\n + """ + + def get_light_group(self, lights: list[Light]) -> list[LightGroup]: + """Returns a list with the group of every element in `lights`. + + + Setter: `carla.LightManager.set_light_group` + + Args: + `lights (list[Light])`: List of lights to be queried.\n + """ + + def get_light_state(self, lights: list[Light]) -> list[LightState]: + """Returns a list with the state of all the attributes of every element in `lights`. + + + Setter: `carla.LightManager.set_light_state` + + Args: + `lights (list[Light])`: List of lights to be queried.\n + """ + + def get_turned_off_lights(self, light_group: LightGroup) -> list[Light]: + """Returns a list containing lights switched off in the scene, filtered by group. + + Args: + `light_group (LightGroup)`: List of lights to be queried.\n + """ + + def get_turned_on_lights(self, light_group: LightGroup) -> list[Light]: + """Returns a list containing lights switched on in the scene, filtered by group. + + Args: + `light_group (LightGroup)`: List of lights to be queried.\n + """ + # endregion + + # region Setters + def set_active(self, lights: list[Light], active: list[bool]): + """Switches on/off the elements in lights. + + Args: + `lights (list[Light])`: List of lights to be switched on/off.\n + `active (list[bool])`: List of booleans to be applied.\n + """ + + def set_color(self, lights: list[Light], color: Color): + """Changes the color of the elements in `lights` to `color`. + + Args: + `lights (list[Light])`: List of lights to be changed.\n + `color (Color)`: Color to be applied.\n + """ + + def set_colors(self, lights: list[Light], colors: list[Color]): + """Changes the color of each element in lights to the corresponding in colors. + + Args: + `lights (list[Light])`: List of lights to be changed.\n + `colors (list[Color])`: List of colors to be applied.\n + """ + + def set_day_night_cycle(self, active: bool): + """All scene lights have a day-night cycle, automatically turning on and off with the altitude of the sun. This interferes in cases where full control of the scene lights is required, so setting this to `False` deactivates it. It can reactivated by setting it to `True`. + + + Args: + `active (bool)`: (De)activation of the day-night cycle.\n + """ + + def set_intensities(self, lights: list[Light], intensities: list[float]): + """Changes the intensity of each element in lights to the corresponding in intensities. + + Args: + `lights (list[Light])`: List of lights to be changed.\n + `intensities (list[float])`: Intensity to be applied (lumens).\n + """ + + def set_intensity(self, lights: list[Light], intensity: float): + """Changes the intensity of every element in `lights` to `intensity`. + + + Getter: `carla.LightManager.get_intensity` + + Args: + `lights (list[Light])`: List of lights to be changed.\n + `intensity (float)`: Intensity to be applied.\n + """ + + def set_light_group(self, lights: list[Light], light_group: LightGroup): + """Changes the group of every element in `lights` to `light_group`. + + + Getter: carla.LightManager.get_light_group + + Args: + `lights (list[Light])`: List of lights to be changed.\n + `light_group (LightGroup)`: Group to be applied.\n + """ + + def set_light_groups(self, lights: list[Light], light_groups: list[LightGroup]): + """Changes the group of each element in `lights` to the corresponding in `light_groups`. + + Args: + `lights (list[Light])`: List of lights to be changed.\n + `light_groups (list[LightGroup])`: List of groups to be applied.\n + """ + + def set_light_state(self, lights: list[Light], light_state: LightState): + """Changes the state of the attributes of every element in lights to light_state. + + + Getter: `carla.LightManager.get_light_state` + + Args: + `lights (list[Light])`: List of lights to be changed.\n + `light_state (LightState)`: State of the attributes to be applied.\n + """ + + def set_light_states(self, lights: list[Light], light_states: list[LightState]): + """Changes the state of the attributes of each element in lights to the corresponding in light_states. + + Args: + `lights (list[Light])`: List of lights to be changed.\n + `light_states (list[LightState])`: List of state of the attributes to be applied.\n + """ + # endregion + + +class LightState(): + """This class represents all the light variables except the identifier and the location, which are should to be static. Using this class allows to manage all the parametrization of the light in one call. + """ + + # region Instance Variables + @property + def intensity() -> float: + """Intensity of a light.""" + + @property + def color() -> Color: + """Color of a light.""" + + @property + def group() -> LightGroup: + """Group a light belongs to.""" + + @property + def active() -> bool: + """Switch of a light. It is `True` when the light is on.""" + # endregion + + # region Methods + def __init__(self, intensity=0.0, color=Color, group=LightGroup.NONE, active=False) -> LightState: + """This class represents all the light variables except the identifier and the location, which are should to be static. Using this class allows to manage all the parametrization of the light in one call. + + Args: + `intensity (float, optional)`: Intensity of a light (lumens). Defaults to 0.0.\n + `color (_type_, optional)`: Color of a light. Defaults to Color.\n + `group (_type_, optional)`: Group a light belongs to. Defaults to LightGroup.NONE.\n + `active (bool, optional)`: Switch of a light. It is True when the light is on. Defaults to False.\n + """ + # endregion + + +class Location(Vector3D): + """Represents a spot in the world.""" + # region Instance Variables + @property + def x() -> float: + """Distance from origin to spot on X axis (meter).""" + @property + def y() -> float: + """Distance from origin to spot on Y axis (meter).""" + @property + def z() -> float: + """Distance from origin to spot on Z axis. (meter)""" + # endregion + + # region Methods + def __init__(self, x=0.0, y=0.0, z=0.0) -> Location: + """Represents a spot in the world. + + Args: + `x (float, optional)`: Distance from origin to spot on X axis (meter). Defaults to 0.0.\n + `y (float, optional)`: Distance from origin to spot on Y axis (meter). Defaults to 0.0.\n + `z (float, optional)`: Distance from origin to spot on Z axis (meter). Defaults to 0.0.\n + + Returns: + `Location`\n + """ + ... + + def distance(self, location: Location) -> float: + """Returns Euclidean distance from this location to another one. + + Args: + `location (Location)`: The other point to compute the distance with.\n + + Returns: + `float`: (meters)\n + """ + # endregion + + # region Dunder Methods + def __abs__(self) -> Location: + """Returns a Location with the absolute value of the components x, y and z.""" + + def __eq__(self, __value: Location) -> bool: + """Returns `True` if both locations are the same point in space.""" + ... + + def __ne__(self, __value: object) -> bool: + """Returns `True` if both locations are different points in space.""" + ... + + def __str__(self) -> str: + """Parses the axis' values to string.""" + ... + # endregion + pass + + +class Map(): + """Class containing the road information and waypoint managing. Data is retrieved from an OpenDRIVE file that describes the road. A query system is defined which works hand in hand with `carla.Waypoint` to translate geometrical information from the .xodr to natural world points. CARLA is currently working with OpenDRIVE 1.4 standard.""" + + # region Instance Variables + @property + def name() -> str: + """The name of the map. It corresponds to the .umap from Unreal Engine that is loaded from a CARLA server, which then references to the .xodr road description.""" + # endregion + + # region Methods + def __init__(self, name: str, xodr_content: str) -> list[Transform]: + """Constructor for this class. Though a map is automatically generated when initializing the world, using this method in no-rendering mode facilitates working with an .xodr without any CARLA server running. + + Args: + `name (str)`: Name of the current map.\n + `xodr_content (str)`: xodr content in string format.\n + """ + ... + + def cook_in_memory_map(self, path: str): + """Generates a binary file from the CARLA map containing information used by the Traffic Manager. This method is only used during the import process for maps. + + Args: + `path (str)`: Path to the intended location of the stored binary map file.\n + """ + + def generate_waypoints(self, distance: float) -> list[Waypoint]: + """Returns a list of waypoints with a certain distance between them for every lane and centered inside of it. Waypoints are not listed in any particular order. Remember that waypoints closer than 2cm within the same road, section and lane will have the same identificator. + + Args: + `distance (float)`: Approximate distance between waypoints (meters).\n + + Returns: + `list[Waypoint]`\n + """ + + def save_to_disk(self, path: str): + """Saves the .xodr OpenDRIVE file of the current map to disk. + + Args: + `path (str)`: Path where the file will be saved.\n + """ + ... + + def to_opendrive(self) -> str: + """Returns the .xodr OpenDRIVe file of the current map as string. + + Returns: + `str`\n + """ + + def transform_to_geolocation(self, location: Location) -> GeoLocation: + """Converts a given `location`, a point in the simulation, to a `carla.GeoLocation`, which represents world coordinates. The geographical location of the map is defined inside OpenDRIVE within the tag . + + + Args: + `location (Location)`\n + + Returns: + `GeoLocation`\n + """ + ... + # endregion + + # region Getters + def get_all_landmarks(self) -> list[Landmark]: + """Returns all the landmarks in the map. Landmarks retrieved using this method have a `null` waypoint.""" + ... + + def get_all_landmarks_from_id(self, opendrive_id: str) -> list[Landmark]: + """Returns the landmarks with a certain OpenDRIVE ID. Landmarks retrieved using this method have a `null` waypoint. + + Args: + `opendrive_id (str)`: The OpenDRIVE ID of the landmarks.\n + """ + ... + + def get_all_landmarks_of_type(self, type: Union[str, LandmarkType]) -> list[Landmark]: + """Returns the landmarks of a specific type. Landmarks retrieved using this method have a null waypoint. + + Args: + `type (str)`: The type of the landmarks.\n + """ + ... + + def get_crosswalks(self) -> list[Location]: + """Returns a list of locations with all crosswalk zones in the form of closed polygons. The first point is repeated, symbolizing where the polygon begins and ends. + """ + ... + + def get_landmark_group(self, landmark: Landmark) -> list[Landmark]: + """Returns the landmarks in the same group as the specified landmark (including itself). Returns an empty list if the landmark does not belong to any group. + + Args: + `landmark (Landmark)`: A landmark that belongs to the group.\n + """ + ... + + def get_spawn_points(self) -> list[Transform]: + """Returns a list of recommendations made by the creators of the map to be used as spawning points for the vehicles. The list includes carla.Transform objects with certain location and orientation. Said locations are slightly on-air in order to avoid Z-collisions, so vehicles fall for a bit before starting their way. + """ + ... + + def get_topology(self) -> list[tuple[Waypoint, Waypoint]]: + """Returns a list of tuples describing a minimal graph of the topology of the OpenDRIVE file. The tuples contain pairs of waypoints located either at the point a road begins or ends. The first one is the origin and the second one represents another road end that can be reached. This graph can be loaded into NetworkX to work with. + + Output could look like this: `[(w0, w1), (w0, w2), (w1, w3), (w2, w3), (w0, w4)]`. + """ + ... + + def get_waypoint(self, location: Location, project_to_road=True, lane_type=LaneType.Driving) -> Waypoint: + """Returns a waypoint that can be located in an exact location or translated to the center of the nearest lane. Said lane type can be defined using flags such as `LaneType.Driving & LaneType.Shoulder`. + + The method will return `None` if the waypoint is not found, which may happen only when trying to retrieve a waypoint for an exact location. That eases checking if a point is inside a certain road, as otherwise, it will return the corresponding waypoint. + + Args: + `location (Location)`: Location used as reference for the carla.Waypoint (meters).\n + `project_to_road (bool, optional)`: If `True`, the waypoint will be at the center of the closest lane. If `False`, the waypoint will be exactly in location. `None` means said location does not belong to a road. Defaults to True.\n + `lane_type (_type_, optional)`: Limits the search for nearest lane to one or various lane types that can be flagged. Defaults to LaneType.Driving.\n + """ + ... + + def get_waypoint_xodr(self, road_id: int, lane_id: int, s: float) -> Waypoint: + """Returns a waypoint if all the parameters passed are correct. Otherwise, returns `None`. + + Args: + `road_id (int)`: ID of the road to get the waypoint.\n + `lane_id (int)`: ID of the lane to get the waypoint.\n + `s (float)`: Specify the length from the road start (meters).\n + """ + ... + # endregion + + +class MapLayer(Enum): + """Class that represents each manageable layer of the map. Can be used as flags. + + + WARNING: Only "Opt" maps are able to work with map layers.""" + NONE = 0, + Buildings = 1, + Decals = 2, + Foliage = 4, + Ground = 8, + ParkedVehicles = 16, + Particles = 32, + Props = 64, + StreetLights = 128, + Walls = 256, + All = 65535, + """All layers selected.""" + + +class MaterialParameter(Enum): + """Class that represents material parameters. Not all objects in the scene contain all parameters.""" + + # region Instance Variables + Normal = 0, + """The Normal map of the object. Present in all objects.""" + AO_Roughness_Metallic_Emissive = 1, + """A texture where each color channel represent a property of the material (R: Ambien oclusion, G: Roughness, B: Metallic, A: Emissive/Height map in some objects).""" + Diffuse = 2, + """The Diffuse texture of the object. Present in all objects.""" + Emissive = 3, + """Emissive texture. Present in a few objects.""" + # endregion + + +class ObstacleDetectionEvent(SensorData): + """Class that defines the obstacle data for `sensor.other.obstacle`. Learn more about this here. + + https://carla.readthedocs.io/en/latest/ref_sensors/#obstacle-detector + """ + # region Instance Variables + @property + def actor() -> Actor: + """The actor the sensor is attached to.""" + ... + + @property + def other_actor() -> Actor: + """The actor or object considered to be an obstacle.""" + ... + + @property + def distance() -> float: + """Distance between actor and other (meters).""" + ... + # endregion + + # region Dunder methods + def __str__(self) -> str: ... + # endregion + + +class OpendriveGenerationParameters(): + """This class defines the parameters used when generating a world using an OpenDRIVE file.""" + # region Instance Variables + @property + def vertex_distance() -> float: + """Distance between vertices of the mesh generated. Default is 2.0.""" + ... + + @property + def max_road_length() -> float: + """Max road length for a single mesh portion. The mesh of the map is divided into portions, in order to avoid propagating issues. Default is 50.0.""" + ... + + @property + def wall_height() -> float: + """Height of walls created on the boundaries of the road. These prevent vehicles from falling off the road. Default is 1.0.""" + ... + + @property + def additional_width() -> float: + """Additional with applied junction lanes. Complex situations tend to occur at junctions, and a little increase can prevent vehicles from falling off the road. Default is 0.6.""" + ... + + @property + def smooth_junctions() -> bool: + """If `True`, the mesh at junctions will be smoothed to prevent issues where roads blocked other roads. Default is `True`.""" + ... + + @property + def enable_mesh_visibility() -> bool: + """If `True`, the road mesh will be rendered. Setting this to False should reduce the rendering overhead. Default is True.""" + ... + + @property + def enable_pedestrian_navigation() -> bool: + """If `True`, Pedestrian navigation will be enabled using Recast tool. For very large maps it is recomended to disable this option. Default is `True`.""" + ... + # endregion + + +class OpticalFlowImage(SensorData): + """Class that defines an optical flow image of 2-Dimension float (32-bit) vectors representing the optical flow detected in the field of view. The components of the vector represents the displacement of an object in the image plane. Each component outputs values in the normalized range [-2,2] which scales to [-2 size, 2 size] with size being the total resolution in the corresponding component.""" + # region Instance Variables + @property + def fov() -> float: + """Horizontal field of view of the image. (degrees)""" + ... + + @property + def height() -> int: + """Image height in pixels.""" + ... + + @property + def width() -> int: + """Image width in pixels.""" + ... + + @property + def raw_data() -> bytes: + """Flattened array of pixel data, use reshape to create an image array.""" + # endregion + + # region Getters + def get_color_coded_flow(self) -> Image: + """Visualization helper. Converts the optical flow image to an RGB image.""" + ... + # endregion + + # region Dunder Methods + def __getitem__(self, pos: int) -> OpticalFlowPixel: ... + + def __iter__(self) -> Iterator[OpticalFlowPixel]: + """Iterate over the `carla.OpticalFlowPixel `that form the image.""" + + def __len__(self) -> int: ... + def __setitem__(self, pos: int, color: Color): ... + def __str__(self) -> str: ... + # endregion + + +class OpticalFlowPixel(): + """Class that defines a 2 dimensional vector representing an optical flow pixel.""" + + # region Instance Variables + @property + def x() -> float: + """Optical flow in the x component.""" + ... + + @property + def y() -> float: + """Optical flow in the y component.""" + # endregion + + # region Methods + def __init__(self, x=.0, y=.0) -> OpticalFlowPixel: + """Initializes the Optical Flow Pixel. Zero by default. + + Args: + `x (float, optional)`: Optical flow in the x component. Defaults to .0.\n + `y (float, optional)`: Optical flow in the y component. Defaults to .0.\n + """ + ... + # endregion + + # region Dunder Methods + def __eq__(self, __value: OpticalFlowPixel) -> bool: ... + def __ne__(self, __value: OpticalFlowPixel) -> bool: ... + def __str__(self) -> str: ... + # endregion + + +class Osm2Odr(): + """Class that converts an OpenStreetMap map to OpenDRIVE format, so that it can be loaded in CARLA. Find out more about this feature in the docs. + + https://carla.readthedocs.io/en/latest/tuto_G_openstreetmap/ + """ + # region Methods + @staticmethod + def convert(osm_file: str, settings: Osm2OdrSettings) -> str: + """Takes the content of an `.osm` file (OpenStreetMap format) and returns the content of the `.xodr` (OpenDRIVE format) describing said map. + + Args: + `osm_file (str)`: The content of the input OpenStreetMap file parsed as string.\n + `settings (Osm2OdrSettings)`: Parameterization for the conversion.\n + + Returns: + `str`\n + """ + # endregion + + +class Osm2OdrSettings(): + """Helper class that contains the parameterization that will be used by carla.Osm2Odr to convert an OpenStreetMap map to OpenDRIVE format. Find out more about this feature in the docs. + + https://carla.readthedocs.io/en/latest/tuto_G_openstreetmap/ + """ + + # region Instance Variables + @property + def use_offsets() -> bool: + """Enables the use of offset for the conversion. The offset will move the origin position of the map. Default value is False. + """ + ... + + @property + def offset_x() -> float: + """Offset in the X axis. Default value is 0.0 (meters).""" + ... + + @property + def offset_y() -> float: + """Offset in the Y axis. Default value is 0.0 (meters).""" + ... + + @property + def default_lane_width() -> float: + """Width of the lanes described in the resulting XODR map. Default value is 4.0 (meter).""" + ... + + @property + def elevation_layer_height() -> float: + """Defines the height separating two different OpenStreetMap layers. Default value is 0.0.""" + ... + + @property + def center_map() -> bool: + """When this option is enabled, the geometry of the map will be displaced so that the origin of coordinates matches the center of the bounding box of the entire road map.""" + ... + + @property + def proj_string() -> str: + """Defines the `proj4` string that will be used to compute the projection from geocoordinates to cartesian coordinates. This string will be written in the resulting OpenDRIVE unless the options `use_offsets` or `center_map` are enabled as these options override some of the definitions in the string.""" + ... + + @property + def generate_traffic_lights() -> bool: + """Indicates wether to generate traffic light data in the OpenDRIVE. Road types defined by `set_traffic_light_excluded_way_types(way_types)` will not generate traffic lights.""" + ... + + @property + def all_junctions_with_traffic_lights() -> bool: + """When disabled, the converter will generate traffic light data from the OpenStreetMaps data only. When enabled, all junctions will generate traffic lights.""" + # endregion + + # region Setters + def set_osm_way_types(self, way_types: list[str]): + """Defines the OpenStreetMaps road types that will be imported to OpenDRIVE. By default the road types imported are: + `motorway`, `motorway_link`, `trunk`, `trunk_link`, `primary`, `primary_link`, `secondary`, `secondary_link`, `tertiary`, `tertiary_link`, `unclassified`, `residential`. + For a full list of road types check here. + + https://wiki.openstreetmap.org/wiki/Main_Page + + Args: + `way_types (list[str])`: The list of road types.\n + """ + + def set_traffic_light_excluded_way_types(self, way_types: list[str]): + """Defines the OpenStreetMaps road types that will not generate traffic lights even if `generate_traffic_lights` is enabled. By default the road types excluded are + `motorway_link`, `primary_link`, `secondary_link`, `tertiary_link` + + Args: + `way_types (list[str])`: The list of road types.\n + """ + # endregion + + +class RadarDetection(): + """Data contained inside a `carla.RadarMeasurement`. Each of these represents one of the points in the cloud that a `sensor.other.radar` registers and contains the distance, angle and velocity in relation to the radar.""" + + # region Instance Variables + @property + def altitude() -> float: + """Altitude angle of the detection (radians).""" + ... + + @property + def azimuth() -> float: + """Azimuth angle of the detection (radians).""" + ... + + @property + def depth() -> float: + """Distance from the sensor to the detection position (meters).""" + ... + + @property + def velocity() -> float: + """The velocity of the detected object towards the sensor (m/s).""" + ... + # endregion + + # region Dunder Methods + def __str__(self) -> str: ... + # endregion + + +class RadarMeasurement(SensorData): + """Class that defines and gathers the measures registered by a `sensor.other.radar`, representing a wall of points in front of the sensor with a distance, angle and velocity in relation to it. The data consists of a `carla.RadarDetection` array. Learn more about this here. + + https://carla.readthedocs.io/en/latest/ref_sensors/#radar-sensor + """ + + # region Instance Variables + def raw_data() -> bytes: + """The complete information of the `carla.RadarDetection` the radar has registered. + """ + # endregion + + # region Getters + def get_detection_count(self) -> int: + """Retrieves the number of entries generated, same as `__str__()`.""" + # endregion + + # region Dunder Methods + def __getitem__(self, pos: int) -> RadarDetection: ... + + def __iter__(self) -> Iterator[RadarDetection]: + """Iterate over the `carla.RadarDetection` retrieved as data.""" + + def __len__(self) -> int: ... + def __setitem__(self, pos: int, detection: RadarDetection): ... + def __str__(self) -> str: ... + # endregion + + +class Rotation(): + """Class that represents a 3D rotation and therefore, an orientation in space. CARLA uses the Unreal Engine coordinates system. This is a Z-up left-handed system. + + The constructor method follows a specific order of declaration: `(pitch, yaw, roll)`, which corresponds to `(Y-rotation,Z-rotation,X-rotation)`. + """ + + # region Instance Variables + @property + def pitch() -> float: + """Y-axis rotation angle (degrees).""" + ... + + @property + def yaw() -> float: + """Z-axis rotation angle (degrees).""" + ... + + @property + def roll() -> float: + """X-axis rotation angle (degrees).""" + ... + # endregion + + # region Methods + def __init__(self, pitch=.0, yaw=.0, roll=.0) -> Rotation: + """+ Warning: The declaration order is different in CARLA (pitch,yaw,roll), and in the Unreal Engine Editor (roll,pitch,yaw). When working in a build from source, don't mix up the axes' rotations. + + Args: + `pitch (float, optional)`: Y-axis rotation angle (degrees). Defaults to .0.\n + `yaw (float, optional)`: Z-axis rotation angle (degrees). Defaults to .0.\n + `roll (float, optional)`: X-axis rotation angle (degrees). Defaults to .0.\n + """ + ... + # endregion + + # region Getters + def get_forward_vector(self) -> Vector3D: + """Computes the vector pointing forward according to the rotation of the object.""" + ... + + def get_right_vector(self) -> Vector3D: + """Computes the vector pointing to the right according to the rotation of the object.""" + ... + + def get_up_vector(self) -> Vector3D: + """Computes the vector pointing upwards according to the rotation of the object.""" + ... + # endregion + + # region Dunder Methods + def __eq__(self, __value: Rotation) -> bool: + """Returns `True` if both rotations represent the same orientation for every axis.""" + ... + + def __ne__(self, __value: Rotation) -> bool: + ... + + def __str__(self) -> str: ... + # endregion + + +class SemanticLidarDetection(): + """Data contained inside a `carla.SemanticLidarMeasurement`. Each of these represents one of the points in the cloud with its location, the cosine of the incident angle, index of the object hit, and its semantic tag.""" + + # region Instance Variables + @property + def point() -> Location: + """[x,y,z] coordinates of the point (meters).""" + @property + def cos_inc_angle() -> float: + """Cosine of the incident angle between the ray, and the normal of the hit object.""" + @property + def object_idx() -> int: + """ID of the actor hit by the ray.""" + @property + def object_tag() -> int: + """`Semantic tag` of the component hit by the ray.""" + # endregion + + # region Dunder Methods + def __str__(self) -> str: ... + # endregion + + +class SemanticLidarMeasurement(SensorData): + """Class that defines the semantic LIDAR data retrieved by a `sensor.lidar.ray_cast_semantic`. This essentially simulates a rotating LIDAR using ray-casting. Learn more about this here. + + https://carla.readthedocs.io/en/latest/ref_sensors/#semanticlidar-raycast-sensor + """ + + # region Instance Variables + @property + def channels() -> int: + """Number of lasers shot.""" + @property + def horizontal_angle() -> float: + """Horizontal angle the LIDAR is rotated at the time of the measurement (radians).""" + @property + def raw_data() -> bytes: + """Received list of raw detection points. Each point consists of [x,y,z] coordinates plus the cosine of the incident angle, the index of the hit actor, and its semantic tag.""" + # endregion + + # region Methods + def save_to_disk(self, path: str): + """Saves the point cloud to disk as a `.ply` file describing data from 3D scanners. The files generated are ready to be used within `MeshLab`, an open-source system for processing said files. Just take into account that axis may differ from Unreal Engine and so, need to be reallocated. + + Args: + `path (str)`\n + """ + # endregion + + # region Getters + def get_point_count(self, channel: int): + """Retrieves the number of points sorted by channel that are generated by this measure. Sorting by channel allows to identify the original channel for every point. + + Args: + `channel (int)`\n + """ + # endregion + + # region Dunder Methods + def __getitem__(self, pos: int) -> SemanticLidarDetection: ... + + def __iter__(self) -> Iterator[SemanticLidarDetection]: + """Iterate over the `carla.SemanticLidarDetection` retrieved as data.""" + ... + + def __len__(self): ... + def __setitem__(self, pos: int, detection: SemanticLidarDetection): ... + def __str__(self) -> str: ... + # endregion + + +class Sensor(Actor): + """Sensors compound a specific family of actors quite diverse and unique. They are normally spawned as attachment/sons of a vehicle (take a look at `carla.World` to learn about actor spawning). Sensors are thoroughly designed to retrieve different types of data that they are listening to. The data they receive is shaped as different subclasses inherited from `carla.SensorData` (depending on the sensor). + + Most sensors can be divided in two groups: those receiving data on every tick (cameras, point clouds and some specific sensors) and those who only receive under certain circumstances (trigger detectors). CARLA provides a specific set of sensors and their blueprint can be found in `carla.BlueprintLibrary`. All the information on their preferences and settlement can be found here, but the list of those available in CARLA so far goes as follow. + + https://carla.readthedocs.io/en/latest/ref_sensors/ + + Receive data on every tick. + - Depth camera. + - Gnss sensor. + - IMU sensor. + - Lidar raycast. + - SemanticLidar raycast. + - Radar. + - RGB camera. + - RSS sensor. + - Semantic Segmentation camera. + + Only receive data when triggered. + - Collision detector. + - Lane invasion detector. + - Obstacle detector. + """ + + # region Instance Variables + @property + def is_listening() -> bool: + """When `True` the sensor will be waiting for data.""" + # endregion + + # region Methods + def is_listening_gbuffer(self, gbuffer_id: GBufferTextureID) -> bool: + """Returns whether the sensor is in a listening state for a specific GBuffer texture. + + Args: + `gbuffer_id (GBufferTextureID)`: The ID of the target Unreal Engine GBuffer texture.\n + """ + + def listen(self, callback: Callable): + """The function the sensor will be calling to every time a new measurement is received. This function needs for an argument containing an object type `carla.SensorData` to work with. + + Args: + `callback (Callable)`: The called function with one argument containing the sensor data.\n + """ + + def listen_to_gbuffer(self, gbuffer_id: GBufferTextureID, callback: Callable): + """The function the sensor will be calling to every time the desired GBuffer texture is received. + + This function needs for an argument containing an object type `carla.SensorData` to work with. + + Args: + `gbuffer_id (GBufferTextureID)`: The ID of the target Unreal Engine GBuffer texture.\n + `callback (Callable)`: The called function with one argument containing the received GBuffer texture.\n + """ + + def stop(self): + """Commands the sensor to stop listening for data.""" + + def stop_gbuffer(self, gbuffer_id: GBufferTextureID): + """Commands the sensor to stop listening for the specified GBuffer texture. + + Args: + `gbuffer_id (GBufferTextureID)`: The ID of the Unreal Engine GBuffer texture.\n + """ + # endregion + + # region Dunder Methods + def __str__(self) -> str: ... + # endregion + + +class SensorData(): + """Base class for all the objects containing data generated by a `carla.Sensor`. This objects should be the argument of the function said sensor is listening to, in order to work with them. Each of these sensors needs for a specific type of sensor data. Hereunder is a list of the sensors and their corresponding data. + - Cameras (RGB, depth and semantic segmentation): `carla.Image`. + - Collision detector: `carla.CollisionEvent`. + - GNSS sensor: `carla.GnssMeasurement`. + - IMU sensor: `carla.IMUMeasurement`. + - Lane invasion detector: `carla.LaneInvasionEvent`. + - LIDAR sensor: `carla.LidarMeasurement`. + - Obstacle detector: `carla.ObstacleDetectionEvent`. + - Radar sensor: `carla.RadarMeasurement`. + - RSS sensor: `carla.RssResponse`. + - Semantic LIDAR sensor: `carla.SemanticLidarMeasurement`. + """ + # region Instance Variables + @property + def frame() -> int: + """Frame count when the data was generated.""" + ... + + @property + def timestamp() -> float: + """Simulation-time(seconds) when the data was generated.""" + ... + + @property + def transform() -> Transform: + """Sensor's transform when the data was generated.""" + # endregion + + +class TextureColor(): + """Class representing a texture object to be uploaded to the server. Pixel format is RGBA, uint8 per channel. + """ + # region Instance Variables + @property + def width() -> int: + """X-coordinate size of the texture.""" + @property + def height() -> int: + """Y-coordinate size of the texture.""" + # endregion + + # region Methods + def __init__(self, width: int, height: int) -> TextureColor: + """Initializes a the texture with a `(width, height)` size. + + Args: + `width (int)`: X-coordinate size of the texture.\n + `height (int)`: Y-coordinate size of the texture.\n + """ + ... + # endregion + + # region Getters + def get(self, x: int, y: int) -> Color: + """Get the `(x,y)` pixel data.""" + + # endregion + + # region Setters + def set(self, x: int, y: int, value: Color): + """Sets the `(x,y)` pixel data with `value`.""" + + def set_dimensions(self, width: int, height: int): + """Resizes the texture to te specified dimensions.""" + # endregion + + +class TextureFloatColor(): + """Class representing a texture object to be uploaded to the server. Pixel format is RGBA, float per channel.""" + + # region Instance Variables + @property + def width() -> int: + """X-coordinate size of the texture.""" + @property + def height() -> int: + """Y-coordinate size of the texture.""" + # endregion + + # region Getters + def get(self, x: int, y: int) -> FloatColor: + """Get the `(x,y)` pixel data.""" + + # endregion + + # region Setters + def set(self, x: int, y: int, value: FloatColor): + """Sets the `(x,y)` pixel data with `value`.""" + + def set_dimensions(self, width: int, height: int): + """Resizes the texture to te specified dimensions.""" + # endregion + + +class Timestamp(): + """Class that contains time information for simulated data. This information is automatically retrieved as part of the `carla.WorldSnapshot` the client gets on every frame, but might also be used in many other situations such as a `carla.Sensor` retrieveing data.""" + + # region Instance Variables + @property + def frame() -> int: + """The number of frames elapsed since the simulator was launched.""" + @property + def elapsed_seconds() -> float: + """Simulated seconds elapsed since the beginning of the current episode (seconds).""" + @property + def delta_seconds() -> float: + """Simulated seconds elapsed since the previous frame (seconds).""" + def platform_timestamp() -> float: + """Time register of the frame at which this measurement was taken given by the OS in seconds (seconds).""" + # endregion + + # region Methods + def __init__(self, frame: int, elapsed_seconds: float, delta_seconds: float, platform_timestamp: float) -> Timestamp: ... + # endregion + + # region Dunder Methods + def __eq__(self, __value: Timestamp) -> bool: ... + def __ne__(self, __value: Timestamp) -> bool: ... + def __str__(self) -> str: ... + # endregion + + +class TrafficLight(TrafficSign): + """ traffic light actor, considered a specific type of traffic sign. As traffic lights will mostly appear at junctions, they belong to a group which contains the different traffic lights in it. Inside the group, traffic lights are differenciated by their pole index. + + Within a group the state of traffic lights is changed in a cyclic pattern: one index is chosen and it spends a few seconds in green, yellow and eventually red. The rest of the traffic lights remain frozen in red this whole time, meaning that there is a gap in the last seconds of the cycle where all the traffic lights are red. However, the state of a traffic light can be changed manually.""" + + # region Instance Variables + @property + def state() -> TrafficLightState: + """Current state of the traffic light.""" + # endregion + + # region Methods + def freeze(self, freeze: bool): + """Stops all the traffic lights in the scene at their current state.""" + + def is_frozen(self) -> bool: + """The client returns `True` if a traffic light is frozen according to last tick. The method does not call the simulator.""" + + def reset_group(self): + """Resets the state of the traffic lights of the group to the initial state at the start of the simulation. + + + Note: This method calls the simulator. + """ + # endregion + + # region Getters + def get_affected_lane_waypoints(self) -> list[Waypoint]: + """Returns a list of waypoints indicating the positions and lanes where the traffic light is having an effect.""" + + def get_elapsed_time(self) -> float: + """The client returns the time in seconds since current light state started according to last tick. The method does not call the simulator (seconds).""" + + def get_green_time(self) -> float: + """The client returns the time set for the traffic light to be green, according to last tick. The method does not call the simulator (seconds). + + Setter: `carla.TrafficLight.set_green_time` + """ + + def get_group_traffic_lights(self) -> list[TrafficLight]: + """Returns all traffic lights in the group this one belongs to. + + + Note: This method calls the simulator. + """ + + def get_light_boxes(self) -> list[BoundingBox]: + """Returns a list of the bounding boxes encapsulating each light box of the traffic light.""" + + def get_opendrive_id(self) -> str: + """Returns the OpenDRIVE id of this traffic light.""" + + def get_pole_index(self) -> int: + """Returns the index of the pole that identifies it as part of the traffic light group of a junction.""" + + def get_red_time(self) -> float: + """The client returns the time set for the traffic light to be red, according to last tick. The method does not call the simulator (seconds). + + Setter: `carla.TrafficLight.set_red_time` + """ + + def get_state(self) -> TrafficLightState: + """The client returns the state of the traffic light according to last tick. The method does not call the simulator. + + Setter: `carla.TrafficLight.set_state` + """ + + def get_stop_waypoints(self) -> list[Waypoint]: + """Returns a list of waypoints indicating the stop position for the traffic light. These waypoints are computed from the trigger boxes of the traffic light that indicate where a vehicle should stop.""" + + def get_yellow_time(self) -> float: + """The client returns the time set for the traffic light to be yellow, according to last tick. The method does not call the simulator (seconds). + + Setter: `carla.TrafficLight.set_yellow_time` + """ + # endregion + + # region Setters + def set_green_time(self, green_time: float): + """Sets a given time for the green light to be active. + + Getter: `carla.TrafficLight.get_green_time` + + Args: + green_time (float): (seconds) + """ + + def set_red_time(self, red_time: float): + """Sets a given time for the red state to be active. + + Getter: carla.TrafficLight.get_red_time + + Args: + red_time (float): (seconds) + """ + + def set_state(self, state: TrafficLightState): + """Sets a given state to a traffic light actor. + + Getter: `carla.TrafficLight.get_state` + + Args: + state (TrafficLightState) + """ + + def set_yellow_time(self, yellow_time: float): + """Sets a given time for the yellow light to be active. + + Getter: `carla.TrafficLight.get_yellow_time` + + Args: + yellow_time (float): (seconds) + """ + # endregion + + # region Dunder Methods + def __str__(self) -> str: ... + # endregion + + +class TrafficLightState(Enum): + """All possible states for traffic lights. These can either change at a specific time step or be changed manually. The snipet in `carla.TrafficLight.set_state` changes the state of a traffic light on the fly.""" + Red = 0, + Yellow = 1, + Green = 2, + Off = 3, + Unknown = 4, + + +class TrafficManager(): + """The traffic manager is a module built on top of the CARLA API in C++. It handles any group of vehicles set to autopilot mode to populate the simulation with realistic urban traffic conditions and give the chance to user to customize some behaviours. The architecture of the traffic manager is divided in five different goal-oriented stages and a PID controller where the information flows until eventually, a `carla.VehicleControl` is applied to every vehicle registered in a traffic manager. In order to learn more, visit the documentation regarding this module. + + https://carla.readthedocs.io/en/latest/adv_traffic_manager/ + """ + + # region Methods + def auto_lane_change(self, actor: Actor, enable: bool): + """Turns on or off lane changing behaviour for a vehicle. + + Args: + actor (Actor): The vehicle whose settings are changed. + enable (bool): `True` is default and enables lane changes. `False` will disable them. + """ + + def collision_detection(self, reference_actor: Actor, other_actor: Actor, detect_collision: bool): + """Turns on/off collisions between a vehicle and another specific actor. In order to ignore all other vehicles, traffic lights or walkers, use the specific `ignore` methods described in this same section. + + Args: + reference_actor (Actor): Vehicle that is going to ignore collisions. + other_actor (Actor): The actor that `reference_actor` is going to ignore collisions with. + detect_collision (bool): `True` is default and enables collisions. `False` will disable them. + """ + + def distance_to_leading_vehicle(self, actor: Actor, distance: float): + """Sets the minimum distance in meters that a vehicle has to keep with the others. The distance is in meters and will affect the minimum moving distance. It is computed from front to back of the vehicle objects. + + Args: + actor (Actor): Vehicle whose minimum distance is being changed. + distance (float): Meters between both vehicles (meters). + """ + + def force_lane_change(self, actor: Actor, direction: bool): + """Forces a vehicle to change either to the lane on its left or right, if existing, as indicated in `direction`. This method applies the lane change no matter what, disregarding possible collisions. + + Args: + actor (Actor): Vehicle being forced to change lanes. + direction (bool): Destination lane. `True` is the one on the right and `False` is the left one. + """ + + def global_lane_offset(self, offset: float): + """Sets a global lane offset displacement from the center line. Positive values imply a right offset while negative ones mean a left one. Default is 0. Numbers high enough to cause the vehicle to drive through other lanes might break the controller. + + Args: + offset (float): Lane offset displacement from the center line. + """ + + def global_percentage_speed_difference(self, percentage: float): + """Sets the difference the vehicle's intended speed and its current speed limit. Speed limits can be exceeded by setting the `perc` to a negative value. Default is 30. Exceeding a speed limit can be done using negative percentages. + + Args: + percentage (float): Percentage difference between intended speed and the current limit. + """ + + def ignore_lights_percentage(self, actor: Actor, perc: float): + """During the traffic light stage, which runs every frame, this method sets the percent chance that traffic lights will be ignored for a vehicle. + + Args: + actor (Actor): The actor that is going to ignore traffic lights. + perc (float): Between 0 and 100. Amount of times traffic lights will be ignored. + """ + + def ignore_signs_percentage(self, actor: Actor, perc: float): + """During the traffic light stage, which runs every frame, this method sets the percent chance that stop signs will be ignored for a vehicle. + + Args: + actor (Actor): The actor that is going to ignore stop signs. + perc (float): Between 0 and 100. Amount of times stop signs will be ignored. + """ + + def ignore_vehicles_percentage(self, actor: Actor, perc: float): + """During the collision detection stage, which runs every frame, this method sets a percent chance that collisions with another vehicle will be ignored for a vehicle. + + Args: + actor (Actor): The vehicle that is going to ignore other vehicles. + perc (float): Between 0 and 100. Amount of times collisions will be ignored. + """ + + def ignore_walkers_percentage(self, actor: Actor, perc: float): + """During the collision detection stage, which runs every frame, this method sets a percent chance that collisions with walkers will be ignored for a vehicle. + + Args: + actor (Actor): The vehicle that is going to ignore walkers on scene. + perc (float): Between 0 and 100. Amount of times collisions will be ignored. + """ + + def keep_right_rule_percentage(self, actor: Actor, perc: float): + """During the localization stage, this method sets a percent chance that vehicle will follow the keep right rule, and stay in the right lane. + + Args: + actor (Actor): Vehicle whose behaviour is being changed. + perc (float): Between 0 and 100. Amount of times the vehicle will follow the keep right rule. + """ + + def random_left_lanechange_percentage(self, actor: Actor, percentage: float): + """Adjust probability that in each timestep the actor will perform a left lane change, dependent on lane change availability. + + Args: + actor (Actor): The actor that you wish to query. + percentage (float): The probability of lane change in percentage units (between 0 and 100). + """ + + def random_right_lanechange_percentage(self, actor: Actor, percentage: float): + """Adjust probability that in each timestep the actor will perform a right lane change, dependent on lane change availability. + + Args: + actor (Actor): The actor that you wish to query. + percentage (float): The probability of lane change in percentage units (between 0 and 100). + """ + + def shut_down(self): + """Shuts down the traffic manager.""" + + def update_vehicle_lights(self, actor: Actor, do_update: bool): + """Sets if the Traffic Manager is responsible of updating the vehicle lights, or not. Default is False. The traffic manager will not change the vehicle light status of a vehicle, unless its auto_update_status is st to True. + + Args: + actor (Actor): Vehicle whose lights status is being changed. + do_update (bool): If `True` the traffic manager will manage the vehicle lights for the specified vehicle. + """ + + def vehicle_lane_offset(self, actor: Actor, offset: float): + """Sets a lane offset displacement from the center line. Positive values imply a right offset while negative ones mean a left one. Default is 0. Numbers high enough to cause the vehicle to drive through other lanes might break the controller. + + + Args: + actor (Actor): Vehicle whose lane offset behaviour is being changed. + offset (float): Lane offset displacement from the center line. + """ + + def vehicle_percentage_speed_difference(self, actor: Actor, percentage: float): + """Sets the difference the vehicle's intended speed and its current speed limit. Speed limits can be exceeded by setting the `perc` to a negative value. Default is 30. Exceeding a speed limit can be done using negative percentages. + + + Args: + actor (Actor): Vehicle whose speed behaviour is being changed. + percentage (float): Percentage difference between intended speed and the current limit. + """ + # endregion + + # region Getters + def get_all_actions(self, actor: Actor) -> list[Waypoint]: + """Returns all known actions (i.e. road options and waypoints) that an actor controlled by the Traffic Manager will perform in its next steps. + + Args: + actor (Actor): The actor that you wish to query. + + Returns: + list[Waypoint]: list of lists with each element as follows - [Road option (string e.g. 'Left', 'Right', 'Straight'), Next waypoint (carla.Waypoint)] + """ + + def get_next_action(self, actor: Actor) -> list[Waypoint]: + """Returns the next known road option and waypoint that an actor controlled by the Traffic Manager will follow. + + Args: + actor (Actor): The actor that you wish to query. + + Returns: + list[Waypoint]: list of two elements - [Road option (string e.g. 'Left', 'Right', 'Straight'), Next waypoint (carla.Waypoint)] + """ + + def get_port(self) -> int: + """Returns the port where the Traffic Manager is connected. If the object is a TM-Client, it will return the port of its TM-Server. Read the documentation to learn the difference. + + https://carla.readthedocs.io/en/latest/python_api/#adv_traffic_manager.md#multiclient-and-multitm-management + """ + # endregion + + # region Setters + def set_boundaries_respawn_dormant_vehicles(self, lower_bound=25.0, upper_bound: float = WorldSettings.actor_active_distance): + """Sets the upper and lower boundaries for dormant actors to be respawned near the hero vehicle. + + + Warning: The `upper_bound` cannot be higher than the `actor_active_distance`. The `lower_bound` cannot be less than `25`. + + Args: + lower_bound (float, optional): The minimum distance in meters from the hero vehicle that a dormant actor will be respawned. Defaults to 25.0. + upper_bound (float, optional): The maximum distance in meters from the hero vehicle that a dormant actor will be respawned. Defaults to WorldSettings.actor_active_distance. + """ + + def set_desired_speed(self, actor: Actor, speed: float): + """Sets the speed of a vehicle to the specified value. + + Args: + actor (Actor): Vehicle whose speed is being changed. + speed (float): Desired speed at which the vehicle will move. + """ + + def set_global_distance_to_leading_vehicle(self, distance: float): + """Sets the minimum distance in meters that vehicles have to keep with the rest. The distance is in meters and will affect the minimum moving distance. It is computed from center to center of the vehicle objects. + + Args: + distance (float): Meters between vehicles (meters). + """ + + def set_hybrid_physics_mode(self, enabled=False): + """Enables or disables the hybrid physics mode. In this mode, vehicle's farther than a certain radius from the ego vehicle will have their physics disabled. Computation cost will be reduced by not calculating vehicle dynamics. Vehicles will be teleported. + + Args: + enabled (bool, optional): If `True`, enables the hybrid physics. Defaults to False. + """ + + def set_hybrid_physics_radius(self, r=50.0): + """With hybrid physics on, changes the radius of the area of influence where physics are enabled. + + Args: + r (float, optional): New radius where physics are enabled (meters). Defaults to 50.0. + """ + + def set_osm_mode(self, mode_switch=True): + """Enables or disables the OSM mode. This mode allows the user to run TM in a map created with the OSM feature. These maps allow having dead-end streets. Normally, if vehicles cannot find the next waypoint, TM crashes. If OSM mode is enabled, it will show a warning, and destroy vehicles when necessary. + + Args: + mode_switch (bool, optional): If True, the OSM mode is enabled. Defaults to True. + """ + + def set_path(self, actor: Actor, path: list[Location]): + """Sets a list of locations for a vehicle to follow while controlled by the Traffic Manager. + + Args: + actor (Actor): The actor that must follow the given path. + path (list[Location]): The list of carla.Locations for the actor to follow. + """ + + def set_random_device_seed(self, value: int): + """Sets a specific random seed for the Traffic Manager, thereby setting it to be deterministic. + + Args: + value (int): Seed value for the random number generation of the Traffic Manager. + """ + + def set_respawn_dormant_vehicles(self, mode_switch=False): + """If `True`, vehicles in large maps will respawn near the hero vehicle when they become dormant. Otherwise, they will stay dormant until they are within `actor_active_distance` of the hero vehicle again. + + + Args: + mode_switch (bool, optional) Defaults to False. + """ + + def set_route(self, actor: Actor, path: list[str]): + """Sets a list of route instructions for a vehicle to follow while controlled by the Traffic Manager. The possible route instructions are 'Left', 'Right', 'Straight'. + + + Warning: Ensure that the lane topology doesn't impede the given route. + + + Args: + actor (Actor): The actor that must follow the given route instructions. + path (list[str]): The list of route instructions (string) for the vehicle to follow. + """ + + def set_synchronous_mode(self, mode_switch=True): + """Sets the Traffic Manager to synchronous mode. In a multiclient situation, only the TM-Server can tick. Similarly, in a multiTM situation, only one TM-Server must tick. Use this method in the client that does the world tick, and right after setting the world to synchronous mode, to set which TM will be the master while in sync. + + + Warning: If the server is set to synchronous mode, the TM must be set to synchronous mode too in the same client that does the tick. + + Args: + mode_switch (bool, optional): If True, the TM synchronous mode is enabled.. Defaults to True. + """ + # endregion + + +class TrafficSign(Actor): + """Traffic signs appearing in the simulation except for traffic lights. These have their own class inherited from this in `carla.TrafficLight`. Right now, speed signs, stops and yields are mainly the ones implemented, but many others are borne in mind. + """ + + # region Instance Variables + @property + def trigger_volume() -> BoundingBox: + """A carla.BoundingBox situated near a traffic sign where the carla.Actor who is inside can know about it.""" + # endregion + + +class Transform(): + """Class that defines a transformation, a combination of location and rotation, without scaling. + """ + + # region Instance Variables + @property + def location() -> Location: + """Describes a point in the coordinate system.""" + @property + def rotation() -> Rotation: + """Describes a rotation for an object according to Unreal Engine's axis system (degrees (pitch, yaw, roll)).""" + # endregion + + # region Methods + def __init__(self, location: Location, rotation: Rotation) -> Transform: ... + + def transform(self, in_point: Location): + """Translates a 3D point from local to global coordinates using the current transformation as frame of reference. + + Args: + in_point (Location): Translates a 3D point from local to global coordinates using the current transformation as frame of reference. + """ + + def transform_vector(self, in_vector: Vector3D): + """Rotates a vector using the current transformation as frame of reference, without applying translation. Use this to transform, for example, a velocity. + + Args: + in_vector (Vector3D): Vector to which the transformation will be applied. + """ + # endregion + + # region Getters + def get_forward_vector(self) -> Vector3D: + """Computes a forward vector using the rotation of the object.""" + + def get_inverse_matrix(self) -> list[list[float]]: + """Computes the 4-matrix representation of the inverse transformation.""" + + def get_matrix(self) -> list[list[float]]: + """Computes the 4-matrix representation of the transformation.""" + + def get_right_vector(self) -> Vector3D: + """Computes a right vector using the rotation of the object.""" + + def get_up_vector(self) -> Vector3D: + """Computes an up vector using the rotation of the object.""" + # endregion + + # region Dunder Methods + def __eq__(self, __value: Transform) -> bool: + """Returns `True` if both `location` and `rotation` are equal for this and `other`.""" + + def __ne__(self, __value: Transform) -> bool: + """Returns `True` if any `location` and `rotation` are not equal for this and `other`.""" + + def __str__(self) -> str: + """Parses both `location` and `rotation` to string.""" + # endregion + + +class Vector2D(): + """Helper class to perform 2D operations.""" + + # region Instance Variables + @property + def x() -> float: + """X-axis value.""" + @property + def y() -> float: + """Y-axis value.""" + # endregion + + # region Methods + def __init__(self, x=0.0, y=0.0) -> Vector2D: ... + + def length(self) -> float: + """Computes the length of the vector.""" + + def make_unit_vector(self) -> Vector3D: + """Returns a vector with the same direction and unitary length.""" + + def squared_length(self) -> float: + """Computes the squared length of the vector.""" + # endregion + + # region Dunder Methods + # TODO 返回值 + def __add__(self, other=Vector2D) -> Vector2D: ... + + def __eq__(self, other=Vector2D) -> bool: + """Returns `True` if values for every axis are equal.""" + + def __mul__(self, other=Vector2D) -> float: ... + + def __ne__(self, bool=Vector2D) -> bool: + """Returns `True` if the value for any axis is different.""" + + def __str__(self) -> str: + """Returns the axis values for the vector parsed as string.""" + ... + + def __sub__(self, other=Vector2D) -> Vector2D: ... + def __truediv__(self, other=Vector2D): ... + + # endregion + + +class Vector3D(): + """Helper class to perform 3D operations.""" + + # region Instance Variables + @property + def x() -> float: + """X-axis value.""" + @property + def y() -> float: + """Y-axis value.""" + @property + def z() -> float: + """Z-axis value.""" + # endregion + + # region Methods + def __init__(self, x=0.0, y=0.0, z=0.0) -> Vector3D: ... + + def cross(self, vector: Vector3D) -> Vector3D: + """Computes the cross product between two vectors. +""" + + def distance(self, vector: Vector3D) -> float: + """Computes the distance between two vectors.""" + + def distance_2d(self, vector: Vector3D) -> Vector3D: + """Computes the 2-dimensional distance between two vectors.""" + + def distance_squared(self, vector: Vector3D) -> float: + """Computes the squared distance between two vectors.""" + + def distance_squared_2d(self, vector: Vector3D) -> float: + """Computes the 2-dimensional squared distance between two vectors.""" + + def dot(self, vector: Vector3D) -> float: + """Computes the dot product between two vectors.""" + + def dot_2d(self, vector: Vector3D) -> float: + """Computes the 2-dimensional dot product between two vectors.""" + + def length(self) -> float: + """Computes the length of the vector.""" + + def make_unit_vector(self) -> Vector3D: + """Returns a vector with the same direction and unitary length.""" + + def squared_length(self) -> float: + """Computes the squared length of the vector.""" + # endregion + + # region Getters + def get_vector_angle(self, vector: Vector3D) -> float: + """Computes the angle between a pair of 3D vectors in radians.""" + # endregion + + # region Dunder Methods + def __abs__(self) -> Vector3D: + """Returns a Vector3D with the absolute value of the components x, y and z.""" + + def __add__(self, other=Vector3D) -> Vector3D: ... + def __eq__(self, other=Vector3D) -> bool: ... + def __mul__(self, other=Vector3D): ... + def __ne__(self, other=Vector3D) -> bool: ... + def __str__(self) -> str: ... + def __sub__(self, other=Vector3D): ... + def __truediv__(self, other=Vector3D): ... + # endregion + + +class Vehicle(Actor): + """One of the most important groups of actors in CARLA. These include any type of vehicle from cars to trucks, motorbikes, vans, bycicles and also official vehicles such as police cars. A wide set of these actors is provided in `carla.BlueprintLibrary` to facilitate differente requirements. Vehicles can be either manually controlled or set to an autopilot mode that will be conducted client-side by the `traffic manager`.""" + + # region Instance Variables + def bounding_box() -> BoundingBox: + """Bounding box containing the geometry of the vehicle. Its location and rotation are relative to the vehicle it is attached to.""" + # endregion + + # region Methods + def apply_ackermann_control(self, control: VehicleAckermannControl): + """Applies an Ackermann control object on the next tick. + + Args: + `control (VehicleAckermannControl)`\n + """ + + def apply_ackermann_controller_settings(self, settings: VehicleAckermannControl): + """Applies a new Ackermann control settings to this vehicle in the next tick. + + + Warning: This method does call the simulator.""" + + def apply_control(self, control: VehicleControl): + """Applies a control object on the next tick, containing driving parameters such as throttle, steering or gear shifting.""" + + def apply_physics_control(self, physics_control: VehiclePhysicsControl): + """Applies a physics control object in the next tick containing the parameters that define the vehicle as a corporeal body. E.g.: moment of inertia, mass, drag coefficient and many more.""" + + def close_door(self, door_idx: VehicleDoor): + """Close the door `door_idx` if the vehicle has it. Use `carla.VehicleDoor.All` to close all available doors.""" + + def enable_carsim(self, simfile_path: str): + """Enables the CarSim physics solver for this particular vehicle. In order for this function to work, there needs to be a valid license manager running on the server side. The control inputs are redirected to CarSim which will provide the position and orientation of the vehicle for every frame. + + Args: + `simfile_path (str)`: Path to the `.simfile` file with the parameters of the simulation.\n + """ + + def enable_chrono_physics(self, max_substeps: int, max_substep_delta_time: int, vehicle_json: str, powertrain_json: str, tire_json: str, base_json_path: str): + """Enables Chrono physics on a spawned vehicle. + + + Note: Ensure that you have started the CARLA server with the ARGS="--chrono" flag. You will not be able to use Chrono physics without this flag set. + + Warning: Collisions are not supported. When a collision is detected, physics will revert to the default CARLA physics. + + Args: + `max_substeps (int)`: Max number of Chrono substeps.\n + `max_substep_delta_time (int)`: Max size of substep.\n + `vehicle_json (str)`: Path to vehicle json file relative to `base_json_path`.\n + `powertrain_json (str)`: Path to powertrain json file relative to `base_json_path`.\n + `tire_json (str)`: Path to tire json file relative to `base_json_path`.\n + `base_json_path (str)`: Path to `chrono/data/vehicle` folder. E.g., `/home/user/carla/Build/chrono-install/share/chrono/data/vehicle/` (the final / character is required).\n + """ + + def is_at_traffic_light(self) -> bool: + """Vehicles will be affected by a traffic light when the light is red and the vehicle is inside its bounding box. The client returns whether a traffic light is affecting this vehicle according to last tick (it does not call the simulator).""" + + def open_door(self, door_idx: VehicleDoor): + """Open the door `door_idx` if the vehicle has it. Use carla.VehicleDoor.All to open all available doors. + + Args: + `door_idx (VehicleDoor)`: door index.\n + """ + + def show_debug_telemetry(self, enabled=True): + """Enables or disables the telemetry on this vehicle. This shows information about the vehicles current state and forces applied to it in the spectator window. Only information for one vehicle can be shown so that, if you enable a second one, the previous will be automatically disabled. + """ + + def use_carsim_road(self, enabled: bool): + """Enables or disables the usage of CarSim vs terrain file specified in the `.simfile`. By default this option is disabled and CarSim uses unreal engine methods to process the geometry of the scene.""" + # endregion + + # region Getters + def get_ackermann_controller_settings(self) -> AckermannControllerSettings: + """Returns the last Ackermann control settings applied to this vehicle. + + + Warning: This method does call the simulator to retrieve the value. + """ + + def get_control(self) -> VehicleControl: + """The client returns the control applied in the last tick. The method does not call the simulator. + """ + + def get_failure_state(self) -> VehicleFailureState: + """Vehicle have failure states, to indicate that it is incapable of continuing its route. This function returns the vehicle's specific failure state, or in other words, the cause that resulted in it.""" + + def get_light_state(self) -> VehicleLightState: + """Returns a flag representing the vehicle light state, this represents which lights are active or not. + + + Setter: `carla.Vehicle.set_light_state` + """ + + def get_physics_control(self) -> VehiclePhysicsControl: + """The simulator returns the last physics control applied to this vehicle. + + + Warning: This method does call the simulator to retrieve the value. + """ + + def get_speed_limit(self) -> float: + """The client returns the speed limit affecting this vehicle according to last tick (it does not call the simulator). The speed limit is updated when passing by a speed limit signal, so a vehicle might have none right after spawning. + + Returns: + `float`: (km/h)\n + """ + + def get_traffic_light(self) -> TrafficLight: + """Retrieves the traffic light actor affecting this vehicle (if any) according to last tick. The method does not call the simulator. + """ + + def get_traffic_light_state(self) -> TrafficLightState: + """The client returns the state of the traffic light affecting this vehicle according to last tick. The method does not call the simulator. If no traffic light is currently affecting the vehicle, returns `green`. + """ + + def get_wheel_steer_angle(self, wheel_location: VehicleWheelLocation) -> float: + """ + Returns the physics angle in degrees of a vehicle's wheel. + + + Note: Returns the angle based on the physics of the wheel, not the visual angle. + """ + # endregion + + # region Setters + def set_autopilot(self, enabled=True, port=8000): + """Registers or deletes the vehicle from a Traffic Manager's list. When `True`, the Traffic Manager passed as parameter will move the vehicle around. The autopilot takes place client-side. + + Args: + `enabled (bool, optional)`: Defaults to True.\n + `port (int, optional)`: The port of the TM-Server where the vehicle is to be registered or unlisted. Defaults to 8000.\n + """ + + def set_light_state(self, light_state: VehicleLightState): + """Sets the light state of a vehicle using a flag that represents the lights that are on and off. + + + Getter: `carla.Vehicle.get_light_state` + """ + + def set_wheel_steer_direction(self, wheel_location: VehicleWheelLocation, angle_in_deg: float): + """Sets the angle of a vehicle's wheel visually. + + + Warning: Does not affect the physics of the vehicle. + """ + # endregion + + # region Dunder Methods + def __str__(self) -> str: ... + # endregion + + +class VehicleAckermannControl(): + """Manages the basic movement of a vehicle using Ackermann driving controls.""" + + # region Instance Variables + @property + def steer() -> float: + """Desired steer (rad). Positive value is to the right. Default is 0.0.""" + @property + def steer_speed() -> float: + """Steering velocity (rad/s). Zero steering angle velocity means change the steering angle as quickly as possible. Default is 0.0.""" + + @property + def speed() -> float: + """Desired speed (m/s). Default is 0.0.""" + + @property + def acceleration() -> float: + """Desired acceleration (m/s2) Default is 0.0.""" + + @property + def jerk() -> float: + """Desired jerk (m/s3). Default is 0.0.""" + # endregion + + # region Methods + def __init__(self, steer=0.0, steer_speed=0.0, speed=0.0, acceleration=0.0, jerk=0.0) -> VehicleAckermannControl: ... + # endregion + + # region Dunder Methods + def __eq__(self, other=VehicleAckermannControl): ... + def __ne__(self, __value: VehicleAckermannControl) -> bool: ... + def __str__(self) -> str: ... + # endregion + + +class VehicleControl(): + """Manages the basic movement of a vehicle using typical driving controls.""" + # region Instance Variables + @property + def throttle() -> float: + """A scalar value to control the vehicle throttle [0.0, 1.0]. Default is 0.0.""" + @property + def steer() -> float: + """A scalar value to control the vehicle steering [-1.0, 1.0]. Default is 0.0.""" + @property + def brake() -> float: + """A scalar value to control the vehicle brake [0.0, 1.0]. Default is 0.0.""" + @property + def hand_brake() -> bool: + """Determines whether hand brake will be used. Default is `False`.""" + @property + def reverse() -> bool: + """Determines whether the vehicle will move backwards. Default is `False`.""" + @property + def manual_gear_shift() -> bool: + """Determines whether the vehicle will be controlled by changing gears manually. Default is `False`. + """ + @property + def gear() -> int: + """States which gear is the vehicle running on.""" + # endregion + + # region Methods + def __init__(self, throttle=0.0, steer=0.0, brake=0.0, hand_brake=False, reverse=False, manual_gear_shift=False, gear=0): + """ + Args: + `throttle (float, optional)`: Scalar value between [0.0,1.0]. Defaults to 0.0.\n + `steer (float, optional)`: Scalar value between [0.0,1.0]. Defaults to 0.0.\n + `brake (float, optional)`: Scalar value between [0.0,1.0]. Defaults to 0.0.\n + `hand_brake (bool, optional)` Defaults to False.\n + `reverse (bool, optional)` Defaults to False.\n + `manual_gear_shift (bool, optional)` Defaults to False.\n + `gear (int, optional)` Defaults to 0.\n + """ + # endregion + + # region Dunder Methods + def __eq__(self, __value: VehicleControl) -> bool: ... + def __ne__(self, __value: VehicleControl) -> bool: ... + def __str__(self) -> str: ... + # endregion + + +class VehicleDoor(Enum): + """Possible index representing the possible doors that can be open. Notice that not all possible doors are able to open in some vehicles.""" + FL = 0, + """Front left door.""" + FR = 1, + """Front right door.""" + RL = 2, + """Back left door.""" + RR = 3, + """Back right door.""" + All = 6, + """Represents all doors.""" + + +class VehicleFailureState(Enum): + """Enum containing the different failure states of a vehicle, from which the it cannot recover. These are returned by get_failure_state() and only Rollover is currently implemented.""" + + NONE = 0, + Rollover = 1, + Engine = 2, + TirePuncture = 3, + + +class VehicleLightState(Enum): + """Class that recaps the state of the lights of a vehicle, these can be used as a flags. + + E.g: `VehicleLightState.HighBeam & VehicleLightState.Brake` will return `True` when both are active. + + Lights are off by default in any situation and should be managed by the user via script. The blinkers blink automatically. + + + Warning: Right now, not all vehicles have been prepared to work with this functionality, this will be added to all of them in later updates.""" + NONE = 0, + """All lights off.""" + Position = 1, + LowBeam = 2, + HighBeam = 4, + Brake = 8, + RightBlinker = 16, + LeftBlinker = 32, + Reverse = 64, + Fog = 128, + Interior = 256, + Special1 = 512, + """This is reserved for certain vehicles that can have special lights, like a siren.""" + Special2 = 1024, + """This is reserved for certain vehicles that can have special lights, like a siren.""" + All = -1, + """All lights on.""" + + +class VehiclePhysicsControl(): + """Summarizes the parameters that will be used to simulate a carla.Vehicle as a physical object. The specific settings for the wheels though are stipulated using `carla.WheelPhysicsControl`.""" + + # region Instance Variables + @property + def torque_curve() -> list[Vector2D]: + """Curve that indicates the torque measured in Nm for a specific RPM of the vehicle's engine.""" + @property + def max_rpm() -> float: + """The maximum RPM of the vehicle's engine.""" + + @property + def moi() -> float: + """The moment of inertia of the vehicle's engine. (kg*m^2)""" + + @property + def damping_rate_full_throttle() -> float: + """Damping ratio when the throttle is maximum.""" + + @property + def damping_rate_zero_throttle_clutch_engaged() -> float: + """Damping ratio when the throttle is zero with clutch engaged.""" + + @property + def damping_rate_zero_throttle_clutch_disengaged() -> float: + """Damping ratio when the throttle is zero with clutch disengaged.""" + + @property + def use_gear_autobox() -> bool: + """If `True`, the vehicle will have an automatic transmission.""" + + @property + def gear_switch_time() -> float: + """Switching time between gears. (seconds)""" + + @property + def clutch_strength() -> float: + """Clutch strength of the vehicle (kg*m^2/s).""" + + @property + def final_ratio() -> float: + """Fixed ratio from transmission to wheels.""" + + @property + def forward_gears() -> list[GearPhysicsControl]: + """List of objects defining the vehicle's gears.""" + + @property + def mass() -> float: + """Mass of the vehicle (kilograms).""" + + @property + def drag_coefficient() -> float: + """Drag coefficient of the vehicle's chassis.""" + + @property + def center_of_mass() -> Vector3D: + """Center of mass of the vehicle (meters).""" + + @property + def steering_curve() -> list[Vector2D]: + """Curve that indicates the maximum steering for a specific forward speed.""" + + @property + def use_sweep_wheel_collision() -> bool: + """Enable the use of sweep for wheel collision. By default, it is disabled and it uses a simple raycast from the axis to the floor for each wheel. This option provides a better collision model in which the full volume of the wheel is checked against collisions.""" + + @property + def wheels() -> list[WheelPhysicsControl]: + """List of wheel physics objects. This list should have 4 elements, where index 0 corresponds to the front left wheel, index 1 corresponds to the front right wheel, index 2 corresponds to the back left wheel and index 3 corresponds to the back right wheel. For 2 wheeled vehicles, set the same values for both front and back wheels.""" + # endregion + + # region Methods + def __init__(self, + torque_curve=[[0.0, 500.0], [5000.0, 500.0]], + max_rpm=5000.0, + moi=1.0, + damping_rate_full_throttle=0.15, damping_rate_zero_throttle_clutch_engaged=2.0, damping_rate_zero_throttle_clutch_disengaged=0.35, use_gear_autobox=True, + gear_switch_time=0.5, + clutch_strength=10.0, + final_ratio=4.0, + forward_gears=list(), + drag_coefficient=0.3, + center_of_mass=[0.0, 0.0, 0.0], + steering_curve=[[0.0, 1.0], [10.0, 0.5]], + wheels=list(), + use_sweep_wheel_collision=False, + mass=1000.0) -> VehiclePhysicsControl: + """VehiclePhysicsControl constructor. + + Args: + `torque_curve (list, optional)`. Defaults to [[0.0, 500.0], [5000.0, 500.0]].\n + `max_rpm (float, optional)`. Defaults to 5000.0.\n + `moi (float, optional)`: (kg*m^2). Defaults to 1.0.\n + `damping_rate_full_throttle (float, optional)`. Defaults to 0.15.\n + `damping_rate_zero_throttle_clutch_engaged (float, optional)`: Defaults to 2.0.\n + `damping_rate_zero_throttle_clutch_disengaged (float, optional)`: Defaults to 0.35.\n + `use_gear_autobox (bool, optional)`: Defaults to True.\n + `gear_switch_time (float, optional)`: (seconds). Defaults to 0.5.\n + `clutch_strength (float, optional)`: (kg*m^2/s). Defaults to 10.0.\n + `final_ratio (float, optional)`: Defaults to 4.0.\n + `forward_gears (list[GearPhysicsControl] optional)`: Defaults to list().\n + `drag_coefficient (float, optional)`: Defaults to 0.3.\n + `center_of_mass (list, optional)`: Defaults to [0.0, 0.0, 0.0].\n + `steering_curve (list, optional)`: Defaults to [[0.0, 1.0], [10.0, 0.5]].\n + `wheels (_type_, optional)`: Defaults to list().\n + `use_sweep_wheel_collision (bool, optional)`: Defaults to False.\n + `mass (float, optional)`: (kilograms). Defaults to 1000.0.\n + """ + # endregion + + # region Dunder Methods + def __eq__(self, other=VehiclePhysicsControl) -> bool: ... + def __ne__(self, other=VehiclePhysicsControl) -> bool: ... + def __str__(self) -> str: ... + # endregion + + +class VehicleWheelLocation(Enum): + """enum representing the position of each wheel on a vehicle. Used to identify the target wheel when setting an angle in `carla.Vehicle.set_wheel_steer_direction` or `carla.Vehicle.get_wheel_steer_angle`.""" + FL_Wheel = 0, + """Front left wheel of a 4 wheeled vehicle.""" + FR_Wheel = 1, + """Front right wheel of a 4 wheeled vehicle.""" + BL_Wheel = 2, + """Back left wheel of a 4 wheeled vehicle.""" + BR_Wheel = 3, + """Back right wheel of a 4 wheeled vehicle.""" + Front_Wheel = 0, + """Front wheel of a 2 wheeled vehicle.""" + Back_Wheel = 1, + """Back wheel of a 2 wheeled vehicle.""" + + +class Walker(Actor): + """This class inherits from the `carla.Actor` and defines pedestrians in the simulation. Walkers are a special type of actor that can be controlled either by an AI (`carla.WalkerAIController`) or manually via script, using a series of `carla.WalkerControl` to move these and their skeletons. + """ + + # region Methods + def apply_control(self, control: WalkerControl): + """On the next tick, the control will move the walker in a certain direction with a certain speed. Jumps can be commanded too.""" + + def blend_pose(self, blend_value: float): + """Set the blending value of the custom pose with the animation. The values can be: + + + 0: will show only the animation + + 1: will show only the custom pose (set by the user with set_bones()) + + any other: will interpolate all the bone positions between animation and the custom pose. + + Args: + `blend_value (float)`: value from 0 to 1 with the blend percentage\n + """ + + def hide_pose(self): + """Hide the custom pose and show the animation (same as calling `blend_pose(0)`). + """ + + def show_pose(self): + """Show the custom pose and hide the animation (same as calling `blend_pose(1)`). + """ + # endregion + + # region Getters + def get_bones(self) -> WalkerBoneControlOut: + """Return the structure with all the bone transformations from the actor. For each bone, we get the name and its transform in three different spaces: + + + name: bone name + + world: transform in world coordinates + + component: transform based on the pivot of the actor + + relative: transform based on the bone parent. + + + + Setter: `carla.Walker.set_bones` + + Returns: + `WalkerBoneControlOut`: _description_\n + """ + + def get_control(self) -> WalkerControl: + """The client returns the control applied to this walker during last tick. The method does not call the simulator. + """ + + def get_pose_from_animation(self): + """Make a copy of the current animation frame as the custom pose. Initially the custom pose is the neutral pedestrian pose.""" + + # endregion + + # region Setters + def set_bones(self, bones: list[WalkerBoneControlIn]): + """Set the bones of the actor. For each bone we want to set we use a relative transform. Only the bones in this list will be set. For each bone you need to setup this info: + + + name: bone name + + relative: transform based on the bone parent. + + + Getter: `carla.Walker.get_bones` + + Args: + `bones (WalkerBoneControlIn)`: list of pairs (bone_name, transform) for the bones that we want to set)\n + """ + # endregion + + # region Dunder Methods + def __str__(self) -> str: ... + # endregion + + +class WalkerAIController(Actor): + """Class that conducts AI control for a walker. The controllers are defined as actors, but they are quite different from the rest. They need to be attached to a parent actor during their creation, which is the walker they will be controlling (take a look at `carla.World` if you are yet to learn on how to spawn actors). They also need for a special blueprint (already defined in `carla.BlueprintLibrary` as "controller.ai.walker"). This is an empty blueprint, as the AI controller will be invisible in the simulation but will follow its parent around to dictate every step of the way. + """ + + # region Methods + def go_to_location(self, destination: Location): + """Sets the destination that the pedestrian will reach. + + Args: + `destination (Location)`: (meters)\n + """ + + def start(self): + """Enables AI control for its parent walker.""" + + def stop(self): + """Disables AI control for its parent walker.""" + # endregion + + # region Setters + def set_max_speed(self, speed=1.4): + """Sets a speed for the walker in meters per second. + + Args: + `speed (float, optional)`: An easy walking speed is set by default (m/s). Defaults to 1.4.\n + """ + # endregion + + # region Dunder Methods + def __str__(self) -> str: ... + # endregion + + +class WalkerBoneControlIn(): + """This class grants bone specific manipulation for walker. The skeletons of walkers have been unified for clarity and the transform applied to each bone are always relative to its parent. Take a look here to learn more on how to create a walker and define its movement. + + https://carla.readthedocs.io/en/latest/tuto_G_control_walker_skeletons/ + """ + + # region Instance Variables + @property + def bone_transforms() -> list[tuple[str, Transform]]: + """ + List with the data for each bone we want to set: + + name: bone name + + relative: transform based on the bone parent. + """ + # endregion + + # region Methods + def __init__(self, bone_transforms: list[tuple[str, Transform]]) -> WalkerBoneControlIn: + """Initializes an object containing moves to be applied on tick. These are listed with the name of the bone and the transform that will be applied to it. + + Args: + `bone_transforms (list[tuple[str,Transform]])`\n + """ + ... + # endregion + + # region Dunder Methods + def __str__(self) -> str: ... + # endregion + + +class WalkerBoneControlOut(): + """This class is used to return all bone positions of a pedestrian. For each bone we get its name and its transform in three different spaces (world, actor and relative).""" + + # region Instance Variables + def bone_transforms() -> list[tuple[str, Transform, Transform, Transform]]: + """ + List of one entry per bone with this information: + + + name: bone name + + world: transform in world coordinates + + component: transform based on the pivot of the actor + + relative: transform based on the bone parent. + """ + # endregion + + # region Dunder Methods + def __str__(self) -> str: ... + # endregion + + +class WalkerControl(): + """This class defines specific directions that can be commanded to a `carla.Walker` to control it via script. + + AI control can be settled for walkers, but the control used to do so is `carla.WalkerAIController`. + """ + + # region Instance Variables + @property + def direction() -> Vector3D: + """Vector using global coordinates that will correspond to the direction of the walker.""" + @property + def speed() -> float: + """A scalar value to control the walker's speed (m/s).""" + @property + def jump() -> bool: + """If `True`, the walker will perform a jump.""" + # endregion + + # region Methods + def __init__(self, direction=[1.0, 0.0, 0.0], speed=0.0, jump=False) -> WalkerControl: + """This class defines specific directions that can be commanded to a `carla.Walker` to control it via script. + + Args: + `direction (list, optional)`: Vector using global coordinates that will correspond to the direction of the walker.. Defaults to [1.0, 0.0, 0.0].\n + `speed (float, optional)`: A scalar value to control the walker's speed (m/s). Defaults to 0.0.\n + `jump (bool, optional)`: If `True`, the walker will perform a jump. Defaults to False.\n + """ + # endregion + + # region Dunder Methods + def __eq__(self, __value: WalkerControl) -> bool: ... + def __ne__(self, __value: WalkerControl) -> bool: ... + def __str__(self) -> str: ... + # endregion + + +class Waypoint(): + """Waypoints in CARLA are described as 3D directed points. They have a `carla.Transform` which locates the waypoint in a road and orientates it according to the lane. They also store the road information belonging to said point regarding its lane and lane markings. + + All the information regarding waypoints and the waypoint API is retrieved as provided by the OpenDRIVE file. Once the client asks for the map object to the server, no longer communication will be needed. + """ + # region Instance Variables + @property + def id() -> int: + """The identifier is generated using a hash combination of the road, section, lane and s values that correspond to said point in the OpenDRIVE geometry. The s precision is set to 2 centimeters, so 2 waypoints closer than 2 centimeters in the same road, section and lane, will have the same identificator.""" + + @property + def transform() -> Transform: + """Position and orientation of the waypoint according to the current lane information. This data is computed the first time it is accessed. It is not created right away in order to ease computing costs when lots of waypoints are created but their specific transform is not needed.""" + + @property + def road_id() -> int: + """OpenDRIVE road's id.""" + + @property + def section_id() -> int: + """OpenDRIVE section's id, based on the order that they are originally defined.""" + + @property + def is_junction() -> bool: + """True if the current Waypoint is on a junction as defined by OpenDRIVE.""" + + @property + def junction_id() -> int: + """OpenDRIVE junction's id. For more information refer to OpenDRIVE documentation. + + http://www.opendrive.org/docs/OpenDRIVEFormatSpecRev1.4H.pdf#page=20 + """ + + @property + def lane_id() -> int: + """OpenDRIVE lane's id, this value can be positive or negative which represents the direction of the current lane with respect to the road. For more information refer to OpenDRIVE documentation.""" + + @property + def s() -> float: + """OpenDRIVE s value of the current position.""" + + @property + def lane_width() -> float: + """Horizontal size of the road at current `s`.""" + + @property + def lane_change() -> LaneChange: + """Lane change definition of the current Waypoint's location, based on the traffic rules defined in the OpenDRIVE file. It states if a lane change can be done and in which direction.""" + + @property + def lane_type() -> LaneType: + """The lane type of the current Waypoint, based on OpenDRIVE 1.4 standard.""" + + @property + def right_lane_marking() -> LaneMarking: + """The right lane marking information based on the direction of the Waypoint.""" + + @property + def left_lane_marking() -> LaneMarking: + """The left lane marking information based on the direction of the Waypoint.""" + # endregion + + # region Methods + def next(self, distance: float) -> list[Waypoint]: + """Returns a list of waypoints at a certain approximate `distance` from the current one. It takes into account the road and its possible deviations without performing any lane change and returns one waypoint per option. The list may be empty if the lane is not connected to any other at the specified distance. + + Args: + `distance (float)`: The approximate distance where to get the next waypoints (meters).\n + + Returns: + `list[Waypoint]`\n + """ + + def next_until_lane_end(self, distance: float) -> list[Waypoint]: + """This method does not return the waypoint previously visited by an actor, but a list of waypoints at an approximate `distance` but in the opposite direction of the lane. Similarly to `next()`, it takes into account the road and its possible deviations without performing any lane change and returns one waypoint per option. The list may be empty if the lane is not connected to any other at the specified distance. + + + Args: + `distance (float)`: The approximate distance where to get the previous waypoints (meters).\n + + Returns: + `list[Waypoint]`\n + """ + + def previous(self, distance: float) -> list[Waypoint]: + """This method does not return the waypoint previously visited by an actor, but a list of waypoints at an approximate `distance` but in the opposite direction of the lane. Similarly to `next()`, it takes into account the road and its possible deviations without performing any lane change and returns one waypoint per option. The list may be empty if the lane is not connected to any other at the specified distance. + + Args: + `distance (float)`: The approximate distance where to get the previous waypoints (meters).\n + + Returns: + `list[Waypoint]`\n + """ + + def previous_until_lane_start(self, distance: float) -> list[Waypoint]: + """Returns a list of waypoints from this to the start of the lane separated by a certain distance. + + Args: + `distance (float)`: The approximate distance between waypoints (meters).\n + + Returns: + `list[Waypoint]`\n + """ + # endregion + # region Getters + + def get_junction(self) -> Junction: + """If the waypoint belongs to a junction this method returns the associated junction object. Otherwise returns `null`.""" + + def get_landmarks(self, distance: float, stop_at_junction=False) -> list[Landmark]: + """Returns a list of landmarks in the road from the current waypoint until the specified distance. + + Args: + `distance (float)`: The maximum distance to search for landmarks from the current waypoint (meters).\n + `stop_at_junction (bool, optional)`: Enables or disables the landmark search through junctions. Defaults to False.\n + """ + + def get_landmarks_of_type(self, distance: float, type: str, stop_at_junction=False) -> list[Landmark]: + """Returns a list of landmarks in the road of a specified type from the current waypoint until the specified distance. + + Args: + `distance (float)`: The maximum distance to search for landmarks from the current waypoint (meters).\n + `type (str)`: The type of landmarks to search.\n + `stop_at_junction (bool, optional)`: Enables or disables the landmark search through junctions. Defaults to False.\n + """ + + def get_left_lane(self) -> Waypoint: + """Generates a Waypoint at the center of the left lane based on the direction of the current Waypoint, taking into account if the lane change is allowed in this location. Will return `None` if the lane does not exist. + """ + + def get_right_lane(self) -> Waypoint: + """Generates a waypoint at the center of the right lane based on the direction of the current waypoint, taking into account if the lane change is allowed in this location. Will return None if the lane does not exist.""" + # endregion + + # region Dunder Methods + def __str__(self) -> str: ... + # endregion + + +class WeatherParameters(): + """This class defines objects containing lighting and weather specifications that can later be applied in `carla.World`. So far, these conditions only intervene with `sensor.camera.rgb`. They neither affect the actor's physics nor other sensors. + + Each of these parameters acts indepently from the rest. Increasing the rainfall will not automatically create puddles nor change the road's humidity. That makes for a better customization but means that realistic conditions need to be scripted. However an example of dynamic weather conditions working realistically can be found here. + + https://github.com/carla-simulator/carla/blob/master/PythonAPI/examples/dynamic_weather.py + """ + # region Instance Variables + @property + def cloudiness() -> float: + """Values range from 0 to 100, being 0 a clear sky and 100 one completely covered with clouds.""" + @property + def precipitation() -> float: + """Rain intensity values range from 0 to 100, being 0 none at all and 100 a heavy rain.""" + @property + def precipitation_deposits() -> float: + """Determines the creation of puddles. Values range from 0 to 100, being 0 none at all and 100 a road completely capped with water. Puddles are created with static noise, meaning that they will always appear at the same locations.""" + @property + def wind_intensity() -> float: + """Controls the strenght of the wind with values from 0, no wind at all, to 100, a strong wind. The wind does affect rain direction and leaves from trees, so this value is restricted to avoid animation issues.""" + @property + def sun_azimuth_angle() -> float: + """The azimuth angle of the sun. Values range from 0 to 360. Zero is an origin point in a sphere determined by Unreal Engine (degrees).""" + @property + def sun_altitude_angle() -> float: + """Altitude angle of the sun. Values range from -90 to 90 corresponding to midnight and midday each (degrees).""" + @property + def fog_density() -> float: + """Fog concentration or thickness. It only affects the RGB camera sensor. Values range from 0 to 100.""" + @property + def fog_distance() -> float: + """Fog start distance. Values range from 0 to infinite (meters).""" + @property + def wetness() -> float: + """Wetness intensity. It only affects the RGB camera sensor. Values range from 0 to 100.""" + @property + def fog_falloff() -> float: + """Density of the fog (as in specific mass) from 0 to infinity. The bigger the value, the more dense and heavy it will be, and the fog will reach smaller heights. Corresponds to `Fog Height Falloff` in the UE docs. + + If the value is 0, the fog will be lighter than air, and will cover the whole scene. + A value of 1 is approximately as dense as the air, and reaches normal-sized buildings. + + For values greater than 5, the air will be so dense that it will be compressed on ground level. + """ + @property + def scattering_intensity() -> float: + """Controls how much the light will contribute to volumetric fog. When set to 0, there is no contribution.""" + @property + def mie_scattering_scale() -> float: + """Controls interaction of light with large particles like pollen or air pollution resulting in a hazy sky with halos around the light sources. When set to 0, there is no contribution.""" + @property + def rayleigh_scattering_scale() -> float: + """Controls interaction of light with small particles like air molecules. Dependent on light wavelength, resulting in a blue sky in the day or red sky in the evening.""" + @property + def dust_storm() -> float: + """Determines the strength of the dust storm weather. Values range from 0 to 100.""" + # endregion + + # region Methods + def __init__(self, + cloudiness=0.0, + precipitation=0.0, + precipitation_deposits=0.0, + wind_intensity=0.0, + sun_azimuth_angle=0.0, + sun_altitude_angle=0.0, + fog_density=0.0, + fog_distance=0.0, + wetness=0.0, + fog_falloff=0.0, + scattering_intensity=0.0, + mie_scattering_scale=0.0, + rayleigh_scattering_scale=0.0331) -> WeatherParameters: + """Method to initialize an object defining weather conditions. This class has some presets for different noon and sunset conditions listed in a note below. + + + Note: ClearNoon, CloudyNoon, WetNoon, WetCloudyNoon, SoftRainNoon, MidRainyNoon, HardRainNoon, ClearSunset, CloudySunset, WetSunset, WetCloudySunset, SoftRainSunset, MidRainSunset, HardRainSunset. + + Args: + `cloudiness (float, optional)`: 0 is a clear sky, 100 complete overcast. Defaults to 0.0.\n + `precipitation (float, optional)`: 0 is no rain at all, 100 a heavy rain. Defaults to 0.0.\n + `precipitation_deposits (float, optional)`: 0 means no puddles on the road, 100 means roads completely capped by rain. Defaults to 0.0.\n + `wind_intensity (float, optional)`: 0 is calm, 100 a strong wind. Defaults to 0.0.\n + `sun_azimuth_angle (float, optional)`: 0 is an arbitrary North, 180 its corresponding South. Defaults to 0.0.\n + `sun_altitude_angle (float, optional)`: 90 is midday, -90 is midnight. Defaults to 0.0.\n + `fog_density (float, optional)`: Concentration or thickness of the fog, from 0 to 100. Defaults to 0.0.\n + `fog_distance (float, optional)`: Distance where the fog starts in meters. Defaults to 0.0.\n + `wetness (float, optional)`: Humidity percentages of the road, from 0 to 100. Defaults to 0.0.\n + `fog_falloff (float, optional)`: Density (specific mass) of the fog, from 0 to infinity. Defaults to 0.0.\n + `scattering_intensity (float, optional)`: Controls how much the light will contribute to volumetric fog. When set to 0, there is no contribution. Defaults to 0.0.\n + `mie_scattering_scale (float, optional)`: Controls interaction of light with large particles like pollen or air pollution resulting in a hazy sky with halos around the light sources. When set to 0, there is no contribution. Defaults to 0.0.\n + `rayleigh_scattering_scale (float, optional)`: Controls interaction of light with small particles like air molecules. Dependent on light wavelength, resulting in a blue sky in the day or red sky in the evening. Defaults to 0.0331.\n + """ + # endregion + + # region Dunder Methods + def __eq__(self, __value: WeatherParameters) -> bool: ... + def __ne__(self, __value: WeatherParameters) -> bool: ... + def __str__(self) -> str: ... + # endregion + + +class WheelPhysicsControl(): + """Class that defines specific physical parameters for wheel objects that will be part of a `carla.VehiclePhysicsControl` to simulate vehicle it as a material object.""" + + # region Instance Variables + @property + def tire_friction() -> float: + """A scalar value that indicates the friction of the wheel.""" + @property + def damping_rate() -> float: + """Damping rate of the wheel.""" + @property + def max_steer_angle() -> float: + """Maximum angle that the wheel can steer (degrees).""" + @property + def radius() -> float: + """Radius of the wheel (centimeters).""" + @property + def max_brake_torque() -> float: + """Maximum brake torque (N*m).""" + @property + def max_handbrake_torque() -> float: + """Maximum handbrake torque.""" + @property + def position() -> Vector3D: + """World position of the wheel. This is a read-only parameter.""" + @property + def long_stiff_value() -> float: + """Tire longitudinal stiffness per unit gravitational acceleration. Each vehicle has a custom value (kg/rad).""" + @property + def lat_stiff_max_load() -> float: + """Maximum normalized tire load at which the tire can deliver no more lateral stiffness no matter how much extra load is applied to the tire. Each vehicle has a custom value.""" + @property + def lat_stiff_value() -> float: + """Maximum stiffness per unit of lateral slip. Each vehicle has a custom value.""" + # endregion + + # region Methods + def __init__(self, + tire_friction=2.0, + damping_rate=0.25, + max_steer_angle=70.0, + radius=30.0, + max_brake_torque=1500.0, + max_handbrake_torque=3000.0, + position: Vector3D = (0.0, 0.0, 0.0)) -> WheelPhysicsControl: ... + # endregion + + # region Dunder Methods + def __eq__(self, __value: WheelPhysicsControl) -> bool: ... + def __ne__(self, __value: WheelPhysicsControl) -> bool: ... + def __str__(self) -> str: ... + # endregion + + +class World(): + """World objects are created by the client to have a place for the simulation to happen. The world contains the map we can see, meaning the asset, not the navigation map. Navigation maps are part of the `carla.Map` class. It also manages the weather and actors present in it. There can only be one world per simulation, but it can be changed anytime.""" + + # region Instance Variables + @property + def id() -> int: + """The ID of the episode associated with this world. Episodes are different sessions of a simulation. These change everytime a world is disabled or reloaded. Keeping track is useful to avoid possible issues.""" + @property + def debug() -> DebugHelper: + """Responsible for creating different shapes for debugging. Take a look at its class to learn more about it.""" + # endregion + + # region Methods + def apply_color_texture_to_object(self, object_name: str, material_parameter: MaterialParameter, texture: TextureColor): + """Applies a `texture` object in the field corresponfing to `material_parameter` (normal, diffuse, etc) to the object in the scene corresponding to `object_name`.""" + + def apply_color_texture_to_objects(self, objects_name_list: list[str], material_parameter: MaterialParameter, texture: TextureColor): + """Applies a `texture` object in the field corresponfing to `material_parameter` (normal, diffuse, etc) to the object in the scene corresponding to all objects in `objects_name_list`.""" + + def apply_float_color_texture_to_object(self, object_name: str, material_parameter: MaterialParameter, texture: TextureFloatColor): + """Applies a `texture` object in the field corresponfing to `material_parameter` (normal, diffuse, etc) to the object in the scene corresponding to all objects in `objects_name_list`.""" + + def apply_float_color_texture_to_objects(self, objects_name_list: list[str], material_parameter: MaterialParameter, texture: TextureFloatColor): + """Applies a `texture` object in the field corresponfing to `material_parameter` (normal, diffuse, etc) to the object in the scene corresponding to all objects in `objects_name_list`.""" + + def apply_settings(self, world_settings: WorldSettings) -> int: + """This method applies settings contained in an object to the simulation running and returns the ID of the frame they were implemented. + + + Warning: If synchronous mode is enabled, and there is a Traffic Manager running, this must be set to sync mode too. Read this to learn how to do it. + https://carla.readthedocs.io/en/latest/adv_traffic_manager/#synchronous-mode + """ + + def apply_textures_to_object(self, object_name: str, diffuse_texture: TextureColor, emissive_texture: TextureFloatColor, normal_texture: TextureFloatColor, ao_roughness_metallic_emissive_texture: TextureFloatColor): + """Applies all texture fields in `carla.MaterialParameter` to the object `object_name`. Empty textures here will not be applied. + """ + + def apply_textures_to_objects(self, objects_name_list: list[str], diffuse_texture: TextureColor, emissive_texture: TextureFloatColor, normal_texture: TextureFloatColor, ao_roughness_metallic_emissive_texture: TextureFloatColor): + """Applies all texture fields in `carla.MaterialParameter` to all objects in `objects_name_list`. Empty textures here will not be applied.""" + + def cast_ray(self, initial_location: Location, final_location: Location) -> list[LabelledPoint]: + """Casts a ray from the specified initial_location to final_location. The function then detects all geometries intersecting the ray and returns a list of `carla.LabelledPoint` in order. + + Args: + initial_location (Location): The initial position of the ray. + final_location (Location): The final position of the ray. + """ + + def enable_environment_objects(self, env_objects_ids: set[int], enable: bool): + """Enable or disable a set of EnvironmentObject identified by their id. These objects will appear or disappear from the level. + + Args: + env_objects_ids (set[int]): Set of EnvironmentObject ids to change. + enable (bool): State to be applied to all the EnvironmentObject of the set. + """ + + def freeze_all_traffic_lights(self, frozen: bool): + """Freezes or unfreezes all traffic lights in the scene. Frozen traffic lights can be modified by the user but the time will not update them until unfrozen.""" + + def ground_projection(self, location: Location, search_distance: float) -> LabelledPoint: + """Projects the specified point downwards in the scene. The functions casts a ray from location in the direction (0,0,-1) (downwards) and returns a `carla.LabelledPoint` object with the first geometry this ray intersects (usually the ground). If no geometry is found in the search_distance range the function returns `None`. + + Args: + location (Location): The point to be projected. + search_distance (float): The maximum distance to perform the projection. + """ + + def load_map_layer(self, map_layers: MapLayer): + """Loads the selected layers to the level. If the layer is already loaded the call has no effect. + + + Warning: This only affects "Opt" maps. The minimum layout includes roads, sidewalks, traffic lights and traffic signs. + + Args: + map_layers (MapLayer): Mask of level layers to be loaded. + """ + + def on_tick(self, callback: Callable) -> int: + """This method is used in `asynchronous mode`. It starts callbacks from the client for the function defined as `callback`, and returns the ID of the callback. The function will be called everytime the server ticks. It requires a `carla.WorldSnapshot` as argument, which can be retrieved from `wait_for_tick()`. Use `remove_on_tick()` to stop the callbacks. + + Args: + callback (Callable): Function with a `snapshot` as compulsory parameter that will be called when the client receives a tick. + """ + + def project_point(self, location: Location, direction: Vector3D, search_distance: float) -> LabelledPoint: + """Projects the specified point to the desired direction in the scene. The functions casts a ray from location in a direction and returns a carla.Labelled object with the first geometry this ray intersects. If no geometry is found in the search_distance range the function returns `None`. + + Args: + `location (Location)`: The point to be projected.\n + `direction (Vector3D)`: The direction of projection.\n + `search_distance (float)`: The maximum distance to perform the projection.\n + + Returns: + `LabelledPoint`\n + """ + + def remove_on_tick(self, callback_id: int): + """Stops the callback for callback_id started with `on_tick()`. + + Args: + `callback_id (int)`: The callback to be removed. The ID is returned when creating the callback.\n + """ + + def reset_all_traffic_lights(self): + """Resets the cycle of all traffic lights in the map to the initial state. + """ + + def spawn_actor(self, blueprint: ActorBlueprint, transform: Transform, attach_to: Actor = None, attachment=AttachmentType.Rigid) -> Actor: + """The method will create, return and spawn an actor into the world. The actor will need an available blueprint to be created and a transform (location and rotation). It can also be attached to a parent with a certain attachment type. + + Args: + `blueprint (ActorBlueprint)`: The reference from which the actor will be created.\n + `transform (Transform)`: Contains the location and orientation the actor will be spawned with.\n + `attach_to (Actor, optional)`: The parent object that the spawned actor will follow around. Defaults to None.\n + `attachment (AttachmentType, optional)`: Determines how fixed and rigorous should be the changes in position according to its parent object. Defaults to AttachmentType.Rigid.\n + + Returns: + `Actor`\n + """ + + def tick(self, seconds=10.0) -> int: + """This method is used in synchronous mode, when the server waits for a client tick before computing the next frame. This method will send the tick, and give way to the server. It returns the ID of the new frame computed by the server. + + + Note: If no tick is received in synchronous mode, the simulation will freeze. Also, if many ticks are received from different clients, there may be synchronization issues. Please read the docs about synchronous mode to learn more. + + Args: + `seconds (float, optional)`: Maximum time the server should wait for a tick (meters). Defaults to 10.0.\n + + Returns: + `int`\n + """ + + def try_spawn_actor(self, blueprint: ActorBlueprint, transform: Transform, attach_to: Actor = None, attachment=AttachmentType.Rigid) -> Actor: + """Same as `spawn_actor()` but returns `None` on failure instead of throwing an exception. + + Args: + `blueprint (ActorBlueprint)`: The reference from which the actor will be created.\n + `transform (Transform)`: Contains the location and orientation the actor will be spawned with.\n + `attach_to (Actor, optional)`: The parent object that the spawned actor will follow around. Defaults to None.\n + `attachment (AttachmentType, optional)`: Determines how fixed and rigorous should be the changes in position according to its parent object. Defaults to AttachmentType.Rigid.\n + + Returns: + `Actor`\n + """ + + def unload_map_layer(self, map_layers: MapLayer): + """Unloads the selected layers to the level. If the layer is already unloaded the call has no effect. + + + Warning: This only affects "Opt" maps. The minimum layout includes roads, sidewalks, traffic lights and traffic signs. + + Args: + `map_layers (MapLayer)`: Mask of level layers to be unloaded.\n + """ + + def wait_for_tick(self, seconds=10.0) -> WorldSnapshot: + """This method is used in asynchronous mode. It makes the client wait for a server tick. When the next frame is computed, the server will tick and return a snapshot describing the new state of the world. + + Args: + `seconds (float, optional)`: Maximum time the server should wait for a tick (meters). Defaults to 10.0.\n + + Returns: + `WorldSnapshot`\n + """ + # endregion + + # region Getters + def get_actor(self, actor_id: int) -> Actor: + """Looks up for an actor by ID and returns `None` if not found.""" + + def get_actors(self, actor_ids: list = None) -> ActorList: + """Retrieves a list of `carla.Actor` elements, either using a list of IDs provided or just listing everyone on stage. If an ID does not correspond with any actor, it will be excluded from the list returned, meaning that both the list of IDs and the list of actors may have different lengths.""" + + def get_blueprint_library(self) -> list[BlueprintLibrary]: + """Returns a list of actor blueprints available to ease the spawn of these into the world.""" + + def get_environment_objects(self, object_type: CityObjectLabel = CityObjectLabel.Any) -> list[EnvironmentObject]: + """Returns a list of EnvironmentObject with the requested semantic tag. The method returns all the EnvironmentObjects in the level by default, but the query can be filtered by semantic tags with the argument `object_type`. + + Args: + `object_type (CityObjectLabel, optional)`: Semantic tag of the EnvironmentObjects that are returned. Defaults to CityObjectLabel.Any.\n + """ + + def get_level_bbs(self, actor_type: CityObjectLabel = CityObjectLabel.Any) -> list[BoundingBox]: + """Returns an array of bounding boxes with location and rotation in world space. The method returns all the bounding boxes in the level by default, but the query can be filtered by semantic tags with the argument `actor_type`. + + Args: + `actor_type (CityObjectLabel, optional)`: Semantic tag of the elements contained in the bounding boxes that are returned. Defaults to CityObjectLabel.Any.\n + + Returns: + `list[BoundingBox]`\n + """ + + def get_lightmanager(self) -> LightManager: + """Returns an instance of carla.LightManager that can be used to handle the lights in the scene.""" + + def get_map(self) -> Map: + """Asks the server for the XODR containing the map file, and returns this parsed as a `carla.Map`. + + + Warning: This method does call the simulation. It is expensive, and should only be called once. + + """ + + def get_names_of_all_objects(self) -> list[str]: + """Returns a list of the names of all objects in the scene that can be painted with the apply texture functions.""" + + def get_random_location_from_navigation(self) -> Location: + """This can only be used with walkers. It retrieves a random location to be used as a destination using the `go_to_location()` method in `carla.WalkerAIController`. This location will be part of a sidewalk. Roads, crosswalks and grass zones are excluded. The method does not take into consideration locations of existing actors so if a collision happens when trying to spawn an actor, it will return an error. Take a look at `generate_traffic.py` for an example.""" + + def get_settings() -> WorldSettings: + """Returns an object containing some data about the simulation such as synchrony between client and server or rendering mode.""" + + def get_snapshot(self) -> WorldSnapshot: + """Returns a snapshot of the world at a certain moment comprising all the information about the actors.""" + + def get_spectator(self) -> Actor: + """Returns the spectator actor. The spectator is a special type of actor created by Unreal Engine, usually with ID=0, that acts as a camera and controls the view in the simulator window.""" + + def get_traffic_light(self, landmark: Landmark) -> TrafficLight: + """Provided a landmark, returns the traffic light object it describes. + + Args: + `landmark (Landmark)`: The landmark object describing a traffic light.\n + """ + + def get_traffic_light_from_opendrive_id(self, traffic_light_id: str) -> TrafficLight: + """Returns the traffic light actor corresponding to the indicated OpenDRIVE id. + + Args: + `traffic_light_id (str)`: The OpenDRIVE id.\n + """ + + def get_traffic_lights_from_waypoint(self, waypoint: Waypoint, distance: float) -> list[TrafficLight]: + """This function performs a search along the road in front of the specified waypoint and returns a list of traffic light actors found in the specified search distance. + + Args: + `waypoint (Waypoint)`: The input waypoint.\n + `distance (float)`: Search distance.\n + """ + + def get_traffic_lights_in_junction(self, junction_id: int) -> list[TrafficLight]: + """Returns the list of traffic light actors affecting the junction indicated in `junction_id`. + + Args: + `junction_id (int)`: The id of the junction.\n + """ + + def get_traffic_sign(self, landmark: Landmark) -> TrafficSign: + """Provided a landmark, returns the traffic sign object it describes. + + Args: + `landmark (Landmark)`: The landmark object describing a traffic sign.\n + """ + + def get_vehicles_light_states(self) -> dict[int, VehicleLightState]: + """Returns a dict where the keys are `carla.Actor` IDs and the values are `carla.VehicleLightState` of that vehicle. + """ + + def get_weather(self) -> WeatherParameters: + """Retrieves an object containing weather parameters currently active in the simulation, mainly cloudiness, precipitation, wind and sun position. + + + Setter: `carla.World.set_weather` + """ + # endregion + + # region Setters + def set_pedestrians_cross_factor(self, percentage: float): + """Sets the percentage of pedestrians that can walk on the road or cross at any point on the road. + + + Note: Should be set before pedestrians are spawned. + + Args: + `percentage (float)`: Value should be between 0.0 and 1.0. For example, a value of 0.1 would allow 10% of pedestrians to walk on the road.\n + """ + + def set_pedestrians_seed(self, seed: int): + """ Sets the seed to use for any random number generated in relation to pedestrians. + + + Note: Should be set before pedestrians are spawned. If you want to repeat the same exact bodies (blueprint) for each pedestrian, then use the same seed in the Python code (where the blueprint is choosen randomly) and here, otherwise the pedestrians will repeat the same paths but the bodies will be different. + """ + + def set_weather(self, weather: WeatherParameters): + """Changes the weather parameteres ruling the simulation to another ones defined in an object. + + + Getter: `carla.World.get_weather` + Args: + `weather (WeatherParameters)`: New conditions to be applied.\n + """ + # endregion + + # region Dunder Methods + def __str__(self) -> str: + """The content of the world is parsed and printed as a brief report of its current state.""" + # endregion + + +class WorldSettings(): + """The simulation has some advanced configuration options that are contained in this class and can be managed using carla.World and its methods. These allow the user to choose between client-server synchrony/asynchrony, activation of "no rendering mode" and either if the simulation should run with a fixed or variable time-step. Check this out if you want to learn about it. + + https://carla.readthedocs.io/en/latest/adv_synchrony_timestep/ + """ + + # region description + @property + def synchronous_mode() -> bool: + """States the synchrony between client and server. When set to true, the server will wait for a client tick in order to move forward. It is `False` by default.""" + @property + def no_rendering_mode() -> bool: + """When enabled, the simulation will run no rendering at all. This is mainly used to avoid overhead during heavy traffic simulations. It is `False` by default.""" + @property + def fixed_delta_seconds() -> float: + """Ensures that the time elapsed between two steps of the simulation is fixed. Set this to `0.0` to work with a variable time-step, as happens by default.""" + @property + def substepping() -> bool: + """Enable the physics substepping. This option allows computing some physics substeps between two render frames. If synchronous mode is set, the number of substeps and its time interval are fixed and computed are so they fulfilled the requirements of `carla.WorldSettings.max_substep` and `carla.WorldSettings.max_substep_delta_time`. These last two parameters need to be compatible with c`arla.WorldSettings.fixed_delta_seconds`. Enabled by default.""" + @property + def max_substep_delta_time() -> float: + """Maximum delta time of the substeps. If the carla.`WorldSettingsmax_substep` is high enough, the substep delta time would be always below or equal to this value. By default, the value is set to 0.01.""" + @property + def max_substeps() -> int: + """The maximum number of physics substepping that are allowed. By default, the value is set to 10. + """ + @property + def max_culling_distance() -> float: + """Configure the max draw distance for each mesh of the level.""" + @property + def deterministic_ragdolls() -> bool: + """Defines wether to use deterministic physics for pedestrian death animations or physical ragdoll simulation. When enabled, pedestrians have less realistic death animation but ensures determinism. When disabled, pedestrians are simulated as ragdolls with more realistic simulation and collision but no determinsm can be ensured.""" + @property + def tile_stream_distance() -> bool: + """Used for large maps only. Configures the maximum distance from the hero vehicle to stream tiled maps. Regions of the map within this range will be visible (and capable of simulating physics). Regions outside this region will not be loaded.""" + @property + def actor_active_distance() -> float: + """Used for large maps only. Configures the distance from the hero vehicle to convert actors to dormant. Actors within this range will be active, and actors outside will become dormant.""" + ... + + @property + def spectator_as_ego() -> float: + """Used for large maps only. Defines the influence of the spectator on tile loading in Large Maps. By default, the spectator will provoke loading of neighboring tiles in the absence of an ego actor. This might be inconvenient for applications that immediately spawn an ego actor.""" + # endregion + + # region Methods + def __init__(self, + synchronous_mode=False, + no_rendering_mode=False, + fixed_delta_seconds=0.0, + max_culling_distance=0.0, + deterministic_ragdolls=False, + tile_stream_distance=3000, + actor_active_distance=2000, + spectator_as_ego=True) -> WorldSettings: + """Creates an object containing desired settings that could later be applied through `carla.World` and its method `apply_settings()`. + + Args: + `synchronous_mode (bool, optional)`: Set this to true to enable client-server synchrony. Defaults to False.\n + `no_rendering_mode (bool, optional)`: Set this to true to completely disable rendering in the simulation. Defaults to False.\n + `fixed_delta_seconds (float, optional)`: Set a fixed time-step in between frames. 0.0 means variable time-step (seconds). Defaults to 0.0.\n + `max_culling_distance (float, optional)`: Configure the max draw distance for each mesh of the level (meters). Defaults to 0.0.\n + `deterministic_ragdolls (bool, optional)`: Defines wether to use deterministic physics or ragdoll simulation for pedestrian deaths. Defaults to False.\n + `tile_stream_distance (int, optional)`: Used for large maps only. Configures the maximum distance from the hero vehicle to stream tiled maps (meters). Defaults to 3000.\n + `actor_active_distance (int, optional)`: Used for large maps only. Configures the distance from the hero vehicle to convert actors to dormant (meters). Defaults to 2000.\n + `spectator_as_ego (bool, optional)`: Used for large maps only. Defines the influence of the spectator on tile loading in Large Maps. Defaults to True.\n + + Returns: + `WorldSettings`: _description_\n + """ + # endregion + + # region Dunder Methods + def __eq__(self, __value: WorldSettings) -> bool: ... + def __ne__(self, __value: WorldSettings) -> bool: ... + def __str__(self) -> str: ... + # endregion + + +class WorldSnapshot(): + """This snapshot comprises all the information for every actor on scene at a certain moment of time. It creates and gives acces to a data structure containing a series of `carla.ActorSnapshot`. The client recieves a new snapshot on every tick that cannot be stored.""" + pass + + # region Instance Variables + @property + def id() -> int: + """A value unique for every snapshot to differentiate them.""" + @property + def frame() -> int: + """Simulation frame in which the snapshot was taken.""" + @property + def timestamp() -> Timestamp: + """Precise moment in time when snapshot was taken. This class works in seconds as given by the operative system (seconds).""" + # endregion + + # region Methods + def find(self, actor_id: int) -> ActorSnapshot: + """Given a certain actor ID, returns its corresponding snapshot or `None` if it is not found. + """ + + def has_actor(self, actor_id: int) -> bool: + """Given a certain actor ID, checks if there is a snapshot corresponding it and so, if the actor was present at that moment.""" + # endregion + + # region Dunder Methods + def __eq__(self, __value: WorldSnapshot) -> bool: + """Returns True if both `timestamp` are the same.""" + + def __iter__(self) -> Iterator[ActorSnapshot]: + """Iterate over the `carla.ActorSnapshot` stored in the snapshot.""" + + def __len__(self) -> int: + """Returns the amount of `carla.ActorSnapshot` present in this snapshot.""" + + def __ne__(self, __value: WorldSnapshot) -> bool: + """Returns True if both `timestamp` are different.""" + # endregion + + +class command(): + + class ApplyAngularImpulse(): + """Command adaptation of `add_angular_impulse()` in `carla.Actor`. Applies an angular impulse to an actor. + """ + # region Instance Variables + @property + def actor_id() -> int: + """Actor affected by the command.""" + @property + def impulse() -> Vector3D: + """Angular impulse applied to the actor (degrees*s).""" + # endregion + + # region Methods + def __init__(self, actor: Union[Actor, int], impulse: Vector3D) -> command.ApplyAngularImpulse: + """Applies an angular impulse to an actor. + + Args: + `actor (Union[Actor,int])`: Actor or its ID to whom the command will be applied to.\n + `impulse (Vector3D)`: (degrees*s)\n + """ + # endregion + + class ApplyForce(): + """Command adaptation of `add_force()` in `carla.Actor`. Applies a force to an actor.""" + # region Instance Variables + @property + def actor_id() -> int: + """Actor affected by the command.""" + @property + def force() -> Vector3D: + """Force applied to the actor over time (N).""" + # endregion + + # region Methods + def __init__(self, actor: Union[Actor, int], force: Vector3D): + """Applies a force to an actor. + + Args: + `actor (Union[Actor, int])`: Actor or its ID to whom the command will be applied to.\n + `force (Vector3D)`: (N)\n + """ + # endregion + + class ApplyImpulse(): + """Command adaptation of `add_impulse()` in `carla.Actor`. Applies an impulse to an actor.""" + # region Instance Variables + @property + def actor_id() -> int: + """Actor affected by the command.""" + @property + def impulse() -> Vector3D: + """Impulse applied to the actor (N*s).""" + # endregion + + # region Methods + def __init__(self, actor: Union[Actor, int], impulse: Vector3D): + """Applies an impulse to an actor. + + Args: + `actor (Union[Actor, int])`: Actor or its ID to whom the command will be applied to.\n + `impulse (Vector3D)`: (N*s)\n + """ + # endregion + + class ApplyTargetAngularVelocity(): + """Command adaptation of `set_target_angular_velocity()` in `carla.Actor`. Sets the actor's angular velocity vector. + """ + + # region Instance Variables + @property + def actor_id() -> int: + """Actor affected by the command.""" + @property + def angular_velocity() -> Vector3D: + """The 3D angular velocity that will be applied to the actor (deg/s).""" + # endregion + + # region Methods + def __init__(self, actor: Union[Actor, int], angular_velocity: Vector3D): + """Sets the actor's angular velocity vector. + + Args: + `actor (Union[Actor, int])`: Actor or its ID to whom the command will be applied to.\n + `angular_velocity (Vector3D)`: Angular velocity vector applied to the actor.\n + """ + # endregion + + class ApplyTargetVelocity(): + """Command adaptation of `set_target_velocity()` in `carla.Actor`. Sets the actor's target velocity vector. + """ + # region Instance Variables + @property + def actor_id() -> int: + """Actor affected by the command.""" + @property + def velocity() -> Vector3D: + """The 3D velocity applied to the actor (m/s).""" + # endregion + + # region Methods + def __init__(self, actor: Union[Actor, int], velocity: Vector3D): + """Sets the actor's target velocity vector. + + Args: + `actor (Union[Actor, int])`: Actor or its ID to whom the command will be applied to.\n + `velocity (Vector3D)`: Velocity vector applied to the actor.\n + """ + # endregion + + class ApplyTorque(): + """Command adaptation of `set_transform()` in `carla.Actor`. Sets a new transform to an actor. + """ + + # region Instance Variables + @property + def actor_id() -> int: + """Actor affected by the command.""" + @property + def transform() -> Transform: + """Transformation to be applied.""" + # endregion + + # region Methods + def __init__(self, actor: Union[Actor, int], transform: Transform): + """Sets a new transform to an actor. + + Args: + `actor (Union[Actor, int])`: Actor or its ID to whom the command will be applied to.\n + `transform (Transform)`\n + """ + # endregion + + class ApplyVehicleAckermannControl(): + """Command adaptation of `apply_ackermann_control()` in `carla.Vehicle`. Applies a certain akermann control to a vehicle. + """ + # region Instance Variables + @property + def actor_id() -> int: + """Actor affected by the command.""" + @property + def control() -> AckermannControllerSettings: + """Vehicle ackermann control to be applied.""" + # endregion + + # region Methods + def __init__(self, actor: Union[Actor, int], control: AckermannControllerSettings): + """Applies a certain akermann control to a vehicle. + + Args: + `actor (Union[Actor, int])`: Actor or its ID to whom the command will be applied to.\n + `control (AckermannControllerSettings)`: Vehicle ackermann control to be applied.\n + """ + # endregion + + class ApplyVehicleControl(): + """Command adaptation of `apply_control()` in `carla.Vehicle`. Applies a certain control to a vehicle.""" + + # region Instance Variables + @property + def actor_id() -> int: + """Actor affected by the command.""" + @property + def control() -> VehicleControl: + """Vehicle control to be applied.""" + # endregion + + # region Methods + def __init__(self, actor: Union[Actor, int], control: VehicleControl): + """Applies a certain control to a vehicle. + + Args: + `actor (Union[Actor, int])`: Actor or its ID to whom the command will be applied to.\n + `control (VehicleControl)`: Vehicle control to be applied.\n + """ + # endregion + + class ApplyVehiclePhysicsControl(): + """Command adaptation of `apply_physics_control()` in `carla.Vehicle`. Applies a new physics control to a vehicle, modifying its physical parameters.""" + + # region Instance Variables + @property + def actor_id() -> int: + """Actor affected by the command.""" + @property + def control() -> VehiclePhysicsControl: + """Physics control to be applied.""" + # endregion + + # region Methods + def __init__(self, actor: Union[Actor, int], control: VehicleControl): + """Applies a new physics control to a vehicle, modifying its physical parameters. + + Args: + `actor (Union[Actor, int])`: Actor or its ID to whom the command will be applied to.\n + `control (VehicleControl)`: Physics control to be applied.\n + """ + # endregion + + class ApplyWalkerControl(): + """Command adaptation of `apply_control()` in `carla.Walker`. Applies a control to a walker.""" + + # region Instance Variables + @property + def actor_id() -> int: + """Walker actor affected by the command.""" + @property + def control() -> VehiclePhysicsControl: + """Walker control to be applied.""" + # endregion + + # region Methods + def __init__(self, actor: Union[Actor, int], control: VehicleControl): + """Applies a control to a walker. + + Args: + `actor (Union[Actor, int])`: Actor or its ID to whom the command will be applied to.\n + `control (VehicleControl)`: Walker control to be applied.\n + """ + # endregion + + class ApplyWalkerControl(): + """Apply a state to the walker actor. Specially useful to initialize an actor them with a specific location, orientation and speed.""" + + # region Instance Variables + @property + def actor_id() -> int: + """Walker actor affected by the command.""" + @property + def transform() -> Transform: + """Transform to be applied.""" + @property + def speed() -> float: + """Speed to be applied (m/s).""" + # endregion + + # region Methods + def __init__(self, actor: Union[Actor, int], transform: Transform, speed: float): + """Apply a state to the walker actor. + + Args: + `actor (Union[Actor, int])`: Actor or its ID to whom the command will be applied to.\n + `transform (Transform)`: Transform to be applied.\n + `speed (float)`: Speed to be applied (m/s).\n + """ + # endregion + + class DestroyActor(): + """Command adaptation of `destroy()` in `carla.Actor` that tells the simulator to destroy this actor. It has no effect if the actor was already destroyed. When executed with `apply_batch_sync()` in c`arla.Client` there will be a `command.Response` that will return a boolean stating whether the actor was successfully destroyed.""" + + # region Instance Variables + @property + def actor_id() -> int: + """Actor affected by the command.""" + # endregion + + # region Methods + def __init__(self, actor: Union[Actor, int]): + """Command adaptation of `destroy()` in `carla.Actor` that tells the simulator to destroy this actor. + + Args: + `actor (Union[Actor, int])`: Actor or its ID to whom the command will be applied to.\n + """ + # endregion + + class Response(): + """States the result of executing a command as either the ID of the actor to whom the command was applied to (when succeeded) or an error string (when failed). actor ID, depending on whether or not the command succeeded. The method `apply_batch_sync()` in c`arla.Client` returns a list of these to summarize the execution of a batch. + """ + + # region Instance Variables + @property + def actor_id() -> int: + """Actor to whom the command was applied to. States that the command was successful.""" + @property + def error() -> str: + """A string stating the command has failed.""" + # endregion + + # region Methods + def has_error(self) -> bool: + """Returns `True` if the command execution fails, and `False` if it was successful.""" + # endregion + + class SetAutopilot(): + """Command adaptation of `set_autopilot()` in `carla.Vehicle`. Turns on/off the vehicle's autopilot mode.""" + + # region Instance Methods + @property + def actor_id() -> int: + """Actor that is affected by the command.""" + @property + def enabled() -> bool: + """If autopilot should be activated or not.""" + @property + def port() -> int: + """Port of the Traffic Manager where the vehicle is to be registered or unlisted.""" + # endregion + + # region Methods + def __init__(self, actor: Union[Actor, int], enabled: bool, port=8000): + """Turns on/off the vehicle's autopilot mode. + + Args: + `actor (Union[Actor, int])`: Actor or its ID to whom the command will be applied to.\n + `enabled (bool)`: _description_\n + `port (int, optional)`: The Traffic Manager port where the vehicle is to be registered or unlisted. If None is passed, it will consider a TM at default port 8000. Defaults to 8000.\n + """ + # endregion + + class SetEnableGravity(): + """Command adaptation of `set_enable_gravity()` in `carla.Actor`. Enables or disables gravity on an actor.""" + # region Instance Variables + @property + def actor_id() -> int: + """Actor that is affected by the command.""" + @property + def enabled() -> bool: + """If gravity should be activated or not.""" + # endregion + + # region Methods + def __init__(self, actor: Union[Actor, int], enabled: bool): + """Enables or disables gravity on an actor. + + Args: + `actor (Union[Actor, int])`: Actor or Actor ID to which the command will be applied to.\n + `enabled (bool)`: If gravity should be activated or not.\n + """ + # endregion + + class SetSimulatePhysics(): + """Command adaptation of `set_simulate_physics()` in `carla.Actor`. Determines whether an actor will be affected by physics or not.""" + # region Instance Variables + @property + def actor_id() -> int: + """Actor that is affected by the command.""" + @property + def enabled() -> bool: + """If physics should be activated or not.""" + # endregion + + # region Methods + def __init__(self, actor: Union[Actor, int], enabled: bool): + """Determines whether an actor will be affected by physics or not. + + Args: + `actor (Union[Actor, int])`: Actor or Actor ID to which the command will be applied to.\n + `enabled (bool)`: If physics should be activated or not.\n + """ + # endregion + + class SetVehicleLightState(): + """Command adaptation of `set_light_state()` in `carla.Vehicle`. Sets the light state of a vehicle.""" + # region Instance Variables + @property + def actor_id() -> int: + """Actor that is affected by the command.""" + @property + def light_state() -> VehicleLightState: + """Recaps the state of the lights of a vehicle, these can be used as a flags.""" + # endregion + + # region Methods + def __init__(self, actor: Union[Actor, int], light_state: VehicleLightState): + """Sets the light state of a vehicle. + + Args: + `actor (Union[Actor, int])`: Actor or its ID to whom the command will be applied to.\n + `light_state (VehicleLightState)`: Recaps the state of the lights of a vehicle, these can be used as a flags.\n + """ + # endregion + + class ShowDebugTelemetry(): + """Command adaptation of `show_debug_telemetry()` in `carla.Actor`. Displays vehicle control telemetry data. + """ + # region Instance Variables + @property + def actor_id() -> int: + """Actor that is affected by the command.""" + @property + def enabled() -> bool: + """If debug should be activated or not.""" + # endregion + + # region Methods + def __init__(self, actor: Union[Actor, int], enabled: bool): + """Displays vehicle control telemetry data. + + Args: + `actor (Union[Actor, int])`: Actor or Actor ID to which the command will be applied to.\n + `enabled (bool)`: If debug should be activated or not.\n + """ + # endregion + + class SpawnActor(): + """Command adaptation of `spawn_actor()` in `carla.World`. Spawns an actor into the world based on the blueprint provided and the transform. If a parent is provided, the actor is attached to it.""" + + # region Instance Variables + @property + def transform() -> Transform: + """Transform to be applied.""" + @property + def parent_id() -> int: + """Identificator of the parent actor.""" + # endregion + + # region Methods + @overload + def __init__(self): ... + @overload + def __init__(self, blueprint: ActorBlueprint, transform: Transform): ... + @overload + def __init__(self, blueprint: ActorBlueprint, transform: Transform, parent: Union[Actor, int]): ... + + def then(self, command: command): + """Links another command to be executed right after. It allows to ease very common flows such as spawning a set of vehicles by command and then using this method to set them to autopilot automatically. + + Args: + `command (command)`: a Carla command.\n + """ + # endregion From 951fcc4cc9015e7db769fbf6711577ebe1f8b566 Mon Sep 17 00:00:00 2001 From: Daniel Date: Thu, 15 Feb 2024 16:51:08 +0100 Subject: [PATCH 60/99] Fixes and missing Iterators --- PythonAPI/carla/source/carla/libcarla.pyi | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/PythonAPI/carla/source/carla/libcarla.pyi b/PythonAPI/carla/source/carla/libcarla.pyi index c332a0dc9..b5f78c45a 100644 --- a/PythonAPI/carla/source/carla/libcarla.pyi +++ b/PythonAPI/carla/source/carla/libcarla.pyi @@ -467,7 +467,7 @@ class ActorBlueprint(): # endregion # region Dunder Methods - def __iter__(self): + def __iter__(self) -> Iterator[ActorAttribute]: """Iterate over the `carla.ActorAttribute` that this blueprint has. """ ... @@ -515,7 +515,7 @@ class ActorList(): """Returns the actor corresponding to pos position in the list.""" ... - def __iter__(self): + def __iter__(self) -> Iterator[Actor]: """Iterate over the `carla.Actor` contained in the list.""" ... @@ -656,7 +656,7 @@ class BlueprintLibrary(): """Returns the blueprint stored in `pos` position inside the data structure containing them. """ - def __iter__(self): + def __iter__(self) -> Iterator[ActorBlueprint]: """Iterate over the `carla.ActorBlueprint` stored in the library.""" def __len__(self): @@ -3672,6 +3672,7 @@ class Vehicle(Actor): """One of the most important groups of actors in CARLA. These include any type of vehicle from cars to trucks, motorbikes, vans, bycicles and also official vehicles such as police cars. A wide set of these actors is provided in `carla.BlueprintLibrary` to facilitate differente requirements. Vehicles can be either manually controlled or set to an autopilot mode that will be conducted client-side by the `traffic manager`.""" # region Instance Variables + @property def bounding_box() -> BoundingBox: """Bounding box containing the geometry of the vehicle. Its location and rotation are relative to the vehicle it is attached to.""" # endregion @@ -4737,7 +4738,7 @@ class World(): def get_actors(self, actor_ids: list = None) -> ActorList: """Retrieves a list of `carla.Actor` elements, either using a list of IDs provided or just listing everyone on stage. If an ID does not correspond with any actor, it will be excluded from the list returned, meaning that both the list of IDs and the list of actors may have different lengths.""" - def get_blueprint_library(self) -> list[BlueprintLibrary]: + def get_blueprint_library(self) -> BlueprintLibrary: """Returns a list of actor blueprints available to ease the spawn of these into the world.""" def get_environment_objects(self, object_type: CityObjectLabel = CityObjectLabel.Any) -> list[EnvironmentObject]: From be8735fc286ee8fea3fc189b29842385adf2c896 Mon Sep 17 00:00:00 2001 From: Daraan Date: Mon, 19 Feb 2024 15:51:36 +0100 Subject: [PATCH 61/99] Fixed Actor.parent Can be None or an Actor --- PythonAPI/carla/source/carla/libcarla.pyi | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/PythonAPI/carla/source/carla/libcarla.pyi b/PythonAPI/carla/source/carla/libcarla.pyi index b5f78c45a..6f2368d9a 100644 --- a/PythonAPI/carla/source/carla/libcarla.pyi +++ b/PythonAPI/carla/source/carla/libcarla.pyi @@ -101,7 +101,7 @@ class Actor(): ... @property - def parent() -> ["Actor"]: + def parent() -> Union["Actor", None]: """Actors may be attached to a parent actor that they will follow around. This is said actor.""" ... From bc6e7cd5ea5c05ba3b9b47b491f2db7c9258963e Mon Sep 17 00:00:00 2001 From: Daniel Date: Thu, 29 Feb 2024 10:15:31 +0100 Subject: [PATCH 62/99] Fixed missing return types --- PythonAPI/carla/source/carla/libcarla.pyi | 33 +++++++++++------------ 1 file changed, 16 insertions(+), 17 deletions(-) diff --git a/PythonAPI/carla/source/carla/libcarla.pyi b/PythonAPI/carla/source/carla/libcarla.pyi index 6f2368d9a..5d432abc7 100644 --- a/PythonAPI/carla/source/carla/libcarla.pyi +++ b/PythonAPI/carla/source/carla/libcarla.pyi @@ -3578,23 +3578,22 @@ class Vector2D(): # endregion # region Dunder Methods - # TODO 返回值 - def __add__(self, other=Vector2D) -> Vector2D: ... + def __add__(self, other: Vector2D) -> Vector2D: ... - def __eq__(self, other=Vector2D) -> bool: + def __eq__(self, other: Vector2D) -> bool: """Returns `True` if values for every axis are equal.""" - def __mul__(self, other=Vector2D) -> float: ... + def __mul__(self, other: Vector2D) -> float: ... - def __ne__(self, bool=Vector2D) -> bool: + def __ne__(self, bool: Vector2D) -> bool: """Returns `True` if the value for any axis is different.""" def __str__(self) -> str: """Returns the axis values for the vector parsed as string.""" ... - def __sub__(self, other=Vector2D) -> Vector2D: ... - def __truediv__(self, other=Vector2D): ... + def __sub__(self, other: Vector2D) -> Vector2D: ... + def __truediv__(self, other: Vector2D): ... # endregion @@ -3658,13 +3657,13 @@ class Vector3D(): def __abs__(self) -> Vector3D: """Returns a Vector3D with the absolute value of the components x, y and z.""" - def __add__(self, other=Vector3D) -> Vector3D: ... - def __eq__(self, other=Vector3D) -> bool: ... - def __mul__(self, other=Vector3D): ... - def __ne__(self, other=Vector3D) -> bool: ... + def __add__(self, other: Vector3D) -> Vector3D: ... + def __eq__(self, other: Vector3D) -> bool: ... + def __mul__(self, other: Vector3D): ... + def __ne__(self, other: Vector3D) -> bool: ... def __str__(self) -> str: ... - def __sub__(self, other=Vector3D): ... - def __truediv__(self, other=Vector3D): ... + def __sub__(self, other: Vector3D): ... + def __truediv__(self, other: Vector3D): ... # endregion @@ -3844,8 +3843,8 @@ class VehicleAckermannControl(): # endregion # region Dunder Methods - def __eq__(self, other=VehicleAckermannControl): ... - def __ne__(self, __value: VehicleAckermannControl) -> bool: ... + def __eq__(self, other: VehicleAckermannControl) -> bool: ... + def __ne__(self, other: VehicleAckermannControl) -> bool: ... def __str__(self) -> str: ... # endregion @@ -4060,8 +4059,8 @@ class VehiclePhysicsControl(): # endregion # region Dunder Methods - def __eq__(self, other=VehiclePhysicsControl) -> bool: ... - def __ne__(self, other=VehiclePhysicsControl) -> bool: ... + def __eq__(self, other: VehiclePhysicsControl) -> bool: ... + def __ne__(self, other: VehiclePhysicsControl) -> bool: ... def __str__(self) -> str: ... # endregion From 251b293d6107de4ef4c59a3d1cce2363e25c7ea4 Mon Sep 17 00:00:00 2001 From: Daniel Date: Thu, 29 Feb 2024 10:18:56 +0100 Subject: [PATCH 63/99] Updated changelog needs merge with dev version --- CHANGELOG.md | 1 + 1 file changed, 1 insertion(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index d743c9c7e..dd6a7be18 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -18,6 +18,7 @@ * PythonAPI `Sensor.is_listening` was defined twice (property and method), cleaned and clarified it as a method. * Added V2X sensors for cooperative awareness message and custom user-defined messages to support vehicle-to-vehicle communication * Added named tuples for BasicAgent.py's detection result to allow for type-hints and better semantics. + * Added type-hint support for the PythonAPI ## CARLA 0.9.15 From 7b2c1db39b2824cc6b81c562b17295fb5f837242 Mon Sep 17 00:00:00 2001 From: Daniel Date: Thu, 29 Feb 2024 10:22:27 +0100 Subject: [PATCH 64/99] Added DSVEventArray iterator --- PythonAPI/carla/source/carla/libcarla.pyi | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/PythonAPI/carla/source/carla/libcarla.pyi b/PythonAPI/carla/source/carla/libcarla.pyi index 5d432abc7..33ceabd61 100644 --- a/PythonAPI/carla/source/carla/libcarla.pyi +++ b/PythonAPI/carla/source/carla/libcarla.pyi @@ -1136,7 +1136,7 @@ class DVSEventArray(): # region Dunder Methods def __getitem__(self, pos: int): ... - def __iter__(self): + def __iter__(self) -> Iterator[DVSEvent]: """Iterate over the `carla.DVSEvent` retrieved as data.""" def __len__(self): ... From f275e47f4e30531c90a37eaee5ee409bd292c963 Mon Sep 17 00:00:00 2001 From: Daniel Date: Thu, 29 Feb 2024 10:40:17 +0100 Subject: [PATCH 65/99] Added missing type for Labelled Point --- PythonAPI/carla/source/carla/libcarla.pyi | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/PythonAPI/carla/source/carla/libcarla.pyi b/PythonAPI/carla/source/carla/libcarla.pyi index 33ceabd61..2b464f9d5 100644 --- a/PythonAPI/carla/source/carla/libcarla.pyi +++ b/PythonAPI/carla/source/carla/libcarla.pyi @@ -1563,14 +1563,13 @@ class LabelledPoint(): """Class that represent a position in space with a semantic label.""" # region Instance Variables - # TODO 类型未定义 @property def location() -> Location: """Position in 3D space.""" ... @property - def label(): + def label() -> CityObjectLabel: """Semantic tag of the point.""" ... # endregion From 4c1104dc470acb6a374463499f46a48da8673ca4 Mon Sep 17 00:00:00 2001 From: Daniel Date: Thu, 29 Feb 2024 10:58:29 +0100 Subject: [PATCH 66/99] Fixed spelling misstakes --- PythonAPI/carla/source/carla/libcarla.pyi | 46 +++++++++++------------ 1 file changed, 23 insertions(+), 23 deletions(-) diff --git a/PythonAPI/carla/source/carla/libcarla.pyi b/PythonAPI/carla/source/carla/libcarla.pyi index 2b464f9d5..0f10b019c 100644 --- a/PythonAPI/carla/source/carla/libcarla.pyi +++ b/PythonAPI/carla/source/carla/libcarla.pyi @@ -65,7 +65,7 @@ class Actor(): https://carla.readthedocs.io/en/latest/bp_library/ """ - # region Instnce Variables + # region Instance Variables @property def attributes() -> dict: """A dictionary containing the attributes of the blueprint this actor was based on. @@ -195,7 +195,7 @@ class Actor(): # region Getters def get_acceleration(self) -> Vector3D: - """Returns the actor's 3D acceleration vector the client recieved during last tick. + """Returns the actor's 3D acceleration vector the client received during last tick. The method does not call the simulator. @@ -205,7 +205,7 @@ class Actor(): ... def get_angular_velocity(self) -> Vector3D: - """Returns the actor's angular velocity vector the client recieved during last tick. + """Returns the actor's angular velocity vector the client received during last tick. The method does not call the simulator. @@ -215,7 +215,7 @@ class Actor(): ... def get_location(self) -> Location: - """Returns the actor's location the client recieved during last tick. + """Returns the actor's location the client received during last tick. The method does not call the simulator. @@ -227,7 +227,7 @@ class Actor(): ... def get_transform(self) -> Transform: - """Returns the actor's transform (location and rotation) the client recieved during last tick. + """Returns the actor's transform (location and rotation) the client received during last tick. The method does not call the simulator. @@ -238,7 +238,7 @@ class Actor(): """ def get_velocity(self) -> Vector3D: - """Returns the actor's velocity vector the client recieved during last tick. + """Returns the actor's velocity vector the client received during last tick. The method does not call the simulator. @@ -588,7 +588,7 @@ class ActorState(Enum): class AttachmentType(Enum): - """Class that defines attachment options between an actor and its parent. When spawning actors, these can be attached to another actor so their position changes accordingly. This is specially useful for sensors. The snipet in `carla.World.spawn_actor` shows some sensors being attached to a car when spawned. + """Class that defines attachment options between an actor and its parent. When spawning actors, these can be attached to another actor so their position changes accordingly. This is specially useful for sensors. The snippet in `carla.World.spawn_actor` shows some sensors being attached to a car when spawned. + Note that the attachment type is declared as an enum within the class.""" @@ -669,7 +669,7 @@ class BlueprintLibrary(): class BoundingBox(): - """Bounding boxes contain the geometry of an actor or an element in the scene. They can be used by `carla.DebugHelper` or a `carla.Client` to draw their shapes for debugging. Check out the snipet in `carla.DebugHelper.draw_box` where a snapshot of the world is used to draw bounding boxes for traffic lights. + """Bounding boxes contain the geometry of an actor or an element in the scene. They can be used by `carla.DebugHelper` or a `carla.Client` to draw their shapes for debugging. Check out the snippet in `carla.DebugHelper.draw_box` where a snapshot of the world is used to draw bounding boxes for traffic lights. """ # region Instance Variables @@ -695,7 +695,7 @@ class BoundingBox(): # region Methods def __init__(self, location: Location, extent: Vector3D) -> BoundingBox: - """Bounding boxes contain the geometry of an actor or an element in the scene. They can be used by `carla.DebugHelper` or a `carla.Client` to draw their shapes for debugging. Check out the snipet in `carla.DebugHelper.draw_box` where a snapshot of the world is used to draw bounding boxes for traffic lights. + """Bounding boxes contain the geometry of an actor or an element in the scene. They can be used by `carla.DebugHelper` or a `carla.Client` to draw their shapes for debugging. Check out the snippet in `carla.DebugHelper.draw_box` where a snapshot of the world is used to draw bounding boxes for traffic lights. Args: `location (Location)`: Center of the box, relative to its parent.\n @@ -1052,7 +1052,7 @@ class Color(): class ColorConverter(Enum): - """Class that defines conversion patterns that can be applied to a `carla.Image` in order to show information provided by `carla.Sensor`. Depth conversions cause a loss of accuracy, as sensors detect depth as float that is then converted to a grayscale value between 0 and 255. Take a look at the snipet in `carla.Sensor.listen` to see an example of how to create and save image data for `sensor.camera.semantic_segmentation`. + """Class that defines conversion patterns that can be applied to a `carla.Image` in order to show information provided by `carla.Sensor`. Depth conversions cause a loss of accuracy, as sensors detect depth as float that is then converted to a grayscale value between 0 and 255. Take a look at the snippet in `carla.Sensor.listen` to see an example of how to create and save image data for `sensor.camera.semantic_segmentation`. """ # region Instance Variables @@ -1146,7 +1146,7 @@ class DVSEventArray(): class DebugHelper(): - """Helper class part of `carla.World` that defines methods for creating debug shapes. By default, shapes last one second. They can be permanent, but take into account the resources needed to do so. Take a look at the snipets available for this class to learn how to debug easily in CARLA.""" + """Helper class part of `carla.World` that defines methods for creating debug shapes. By default, shapes last one second. They can be permanent, but take into account the resources needed to do so. Take a look at the snippets available for this class to learn how to debug easily in CARLA.""" # region Methods def draw_arrow(self, begin: Location, end: Location, thickness=0.1, arrow_size=0.1, color: Color = (255, 0, 0), life_time=-1.0): @@ -1163,7 +1163,7 @@ class DebugHelper(): ... def draw_box(self, box: BoundingBox, rotation: Rotation, thickness=0.1, color: Color = (255, 0, 0), life_time=-1.0): - """Draws a box, ussually to act for object colliders. + """Draws a box, usually to act for object colliders. Args: box (BoundingBox): Object containing a location and the length of a box for every axis. @@ -1524,7 +1524,7 @@ class Image(SensorData): def __getitem__(self, pos=int) -> Color: ... def __iter__(self) -> Iterator[Color]: - """terate over the `carla.Color` that form the image.""" + """Iterate over the `carla.Color` that form the image.""" ... def __len__(self) -> int: ... @@ -1740,13 +1740,13 @@ class LandmarkType(Enum): CityEnd = "311", Highway = "330", DeadEnd = "357", - RecomendedSpeed = "380", - RecomendedSpeedEnd = "381", + RecomendedSpeed = "380", # NOTE: Wrong Spelling, but is named like this internally! + RecomendedSpeedEnd = "381", # NOTE: Wrong Spelling, but is named like this internally! # endregion class LaneChange(Enum): - """Class that defines the permission to turn either left, right, both or none (meaning only going straight is allowed). This information is stored for every `carla.Waypoint` according to the OpenDRIVE file. The snipet in `carla.Map.get_waypoint` shows how a waypoint can be used to learn which turns are permitted.""" + """Class that defines the permission to turn either left, right, both or none (meaning only going straight is allowed). This information is stored for every `carla.Waypoint` according to the OpenDRIVE file. The snippet in `carla.Map.get_waypoint` shows how a waypoint can be used to learn which turns are permitted.""" # region Instance Variables NONE = 0, @@ -1817,7 +1817,7 @@ class LaneMarkingColor(Enum): class LaneMarkingType(Enum): - """Class that defines the lane marking types accepted by OpenDRIVE 1.4. The snipet in `carla.Map.get_waypoint` shows how a waypoint can be used to retrieve the information about adjacent lane markings. + """Class that defines the lane marking types accepted by OpenDRIVE 1.4. The snippet in `carla.Map.get_waypoint` shows how a waypoint can be used to retrieve the information about adjacent lane markings. + Note on double types: Lane markings are defined under the OpenDRIVE standard that determines whereas a line will be considered "BrokenSolid" or "SolidBroken". For each road there is a center lane marking, defined from left to right regarding the lane's directions. The rest of the lane markings are defined in order from the center lane to the closest outside of the road. """ @@ -1838,7 +1838,7 @@ class LaneMarkingType(Enum): class LaneType(Enum): - """Class that defines the possible lane types accepted by OpenDRIVE 1.4. This standards define the road information. The snipet in `carla.Map.get_waypoint` makes use of a waypoint to get the current and adjacent lane types.""" + """Class that defines the possible lane types accepted by OpenDRIVE 1.4. This standards define the road information. The snippet in `carla.Map.get_waypoint` makes use of a waypoint to get the current and adjacent lane types.""" # region Instance Variables Any = -2, @@ -2464,7 +2464,7 @@ class MaterialParameter(Enum): Normal = 0, """The Normal map of the object. Present in all objects.""" AO_Roughness_Metallic_Emissive = 1, - """A texture where each color channel represent a property of the material (R: Ambien oclusion, G: Roughness, B: Metallic, A: Emissive/Height map in some objects).""" + """A texture where each color channel represent a property of the material (R: Ambient occlusion, G: Roughness, B: Metallic, A: Emissive/Height map in some objects).""" Diffuse = 2, """The Diffuse texture of the object. Present in all objects.""" Emissive = 3, @@ -2534,7 +2534,7 @@ class OpendriveGenerationParameters(): @property def enable_pedestrian_navigation() -> bool: - """If `True`, Pedestrian navigation will be enabled using Recast tool. For very large maps it is recomended to disable this option. Default is `True`.""" + """If `True`, Pedestrian navigation will be enabled using Recast tool. For very large maps it is recommended to disable this option. Default is `True`.""" ... # endregion @@ -3066,7 +3066,7 @@ class TextureFloatColor(): class Timestamp(): - """Class that contains time information for simulated data. This information is automatically retrieved as part of the `carla.WorldSnapshot` the client gets on every frame, but might also be used in many other situations such as a `carla.Sensor` retrieveing data.""" + """Class that contains time information for simulated data. This information is automatically retrieved as part of the `carla.WorldSnapshot` the client gets on every frame, but might also be used in many other situations such as a `carla.Sensor` retrieving data.""" # region Instance Variables @property @@ -3212,7 +3212,7 @@ class TrafficLight(TrafficSign): class TrafficLightState(Enum): - """All possible states for traffic lights. These can either change at a specific time step or be changed manually. The snipet in `carla.TrafficLight.set_state` changes the state of a traffic light on the fly.""" + """All possible states for traffic lights. These can either change at a specific time step or be changed manually. The snippet in `carla.TrafficLight.set_state` changes the state of a traffic light on the fly.""" Red = 0, Yellow = 1, Green = 2, @@ -3667,7 +3667,7 @@ class Vector3D(): class Vehicle(Actor): - """One of the most important groups of actors in CARLA. These include any type of vehicle from cars to trucks, motorbikes, vans, bycicles and also official vehicles such as police cars. A wide set of these actors is provided in `carla.BlueprintLibrary` to facilitate differente requirements. Vehicles can be either manually controlled or set to an autopilot mode that will be conducted client-side by the `traffic manager`.""" + """One of the most important groups of actors in CARLA. These include any type of vehicle from cars to trucks, motorbikes, vans, bycicles and also official vehicles such as police cars. A wide set of these actors is provided in `carla.BlueprintLibrary` to facilitate different requirements. Vehicles can be either manually controlled or set to an autopilot mode that will be conducted client-side by the `traffic manager`.""" # region Instance Variables @property From 755c0d827de0fa1408344d9f7b3bb57043626398 Mon Sep 17 00:00:00 2001 From: Daniel Date: Thu, 14 Mar 2024 10:34:59 +0100 Subject: [PATCH 67/99] Removed wrong unit indication --- PythonAPI/carla/source/carla/libcarla.pyi | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/PythonAPI/carla/source/carla/libcarla.pyi b/PythonAPI/carla/source/carla/libcarla.pyi index 0f10b019c..07a0e54c9 100644 --- a/PythonAPI/carla/source/carla/libcarla.pyi +++ b/PythonAPI/carla/source/carla/libcarla.pyi @@ -4690,7 +4690,7 @@ class World(): + Note: If no tick is received in synchronous mode, the simulation will freeze. Also, if many ticks are received from different clients, there may be synchronization issues. Please read the docs about synchronous mode to learn more. Args: - `seconds (float, optional)`: Maximum time the server should wait for a tick (meters). Defaults to 10.0.\n + `seconds (float, optional)`: Maximum time the server should wait for a tick. Defaults to 10.0.\n Returns: `int`\n @@ -4722,7 +4722,7 @@ class World(): """This method is used in asynchronous mode. It makes the client wait for a server tick. When the next frame is computed, the server will tick and return a snapshot describing the new state of the world. Args: - `seconds (float, optional)`: Maximum time the server should wait for a tick (meters). Defaults to 10.0.\n + `seconds (float, optional)`: Maximum time the server should wait for a tick. Defaults to 10.0.\n Returns: `WorldSnapshot`\n From 232cb8c2501a4b1a53fd9cd8cbeb7b1368758b23 Mon Sep 17 00:00:00 2001 From: Daniel Date: Thu, 14 Mar 2024 10:40:23 +0100 Subject: [PATCH 68/99] Added missing -> World to load_world --- PythonAPI/carla/source/carla/libcarla.pyi | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/PythonAPI/carla/source/carla/libcarla.pyi b/PythonAPI/carla/source/carla/libcarla.pyi index 07a0e54c9..948be2f2e 100644 --- a/PythonAPI/carla/source/carla/libcarla.pyi +++ b/PythonAPI/carla/source/carla/libcarla.pyi @@ -827,7 +827,7 @@ class Client(): `reset_settings (bool, optional)`: Option to reset the episode setting to default values, set to false to keep the current settings. This is useful to keep sync mode when changing map and to keep deterministic scenarios. Defaults to True.\n """ - def load_world(self, map_name: str, reset_settings=True, map_layers=MapLayer.All): + def load_world(self, map_name: str, reset_settings=True, map_layers=MapLayer.All) -> World: """Creates a new world with default settings using `map_name` map. All actors in the current world will be destroyed. + Warning: `map_layers` are only available for "Opt" maps @@ -836,6 +836,9 @@ class Client(): `map_name (str)`: Name of the map to be used in this world. Accepts both full paths and map names,e.g. `'/Game/Carla/Maps/Town01'` or `'Town01'`. Remember that these paths are dynamic.\n `reset_settings (bool, optional)`: Option to reset the episode setting to default values, set to false to keep the current settings. This is useful to keep sync mode when changing map and to keep deterministic scenarios. Defaults to True.\n `map_layers (MapLayer, optional)`: Layers of the map that will be loaded. This parameter works like a flag mask. Defaults to MapLayer.All.\n + + Returns: + `World`\n """ def reload_world(self, reset_settings=True): From a0cff7143488c3316b3371eabcac4c254efb3844 Mon Sep 17 00:00:00 2001 From: Daniel Date: Thu, 14 Mar 2024 11:05:33 +0100 Subject: [PATCH 69/99] Added missing return value to reload_world --- PythonAPI/carla/source/carla/libcarla.pyi | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/PythonAPI/carla/source/carla/libcarla.pyi b/PythonAPI/carla/source/carla/libcarla.pyi index 948be2f2e..59a5dbf4e 100644 --- a/PythonAPI/carla/source/carla/libcarla.pyi +++ b/PythonAPI/carla/source/carla/libcarla.pyi @@ -841,7 +841,7 @@ class Client(): `World`\n """ - def reload_world(self, reset_settings=True): + def reload_world(self, reset_settings=True) -> World: """Reload the current world, note that a new world is created with default settings using the same map. All actors present in the world will be destroyed, but traffic manager instances will stay alive. Args: @@ -849,6 +849,9 @@ class Client(): Raises: `RuntimeError` when corresponding. + + Returns: + `World`\n """ def replay_file(self, name: str, start: float, duration: float, follow_id: int, replay_sensors: bool): From de33210abd7b67d7a14cd98d6d8c8f3d93b253a3 Mon Sep 17 00:00:00 2001 From: Daniel Date: Thu, 14 Mar 2024 16:49:51 +0100 Subject: [PATCH 70/99] FIX: __init__ methods do not return --- PythonAPI/carla/source/carla/libcarla.pyi | 55 +++++++++-------------- 1 file changed, 20 insertions(+), 35 deletions(-) diff --git a/PythonAPI/carla/source/carla/libcarla.pyi b/PythonAPI/carla/source/carla/libcarla.pyi index 59a5dbf4e..e84adec22 100644 --- a/PythonAPI/carla/source/carla/libcarla.pyi +++ b/PythonAPI/carla/source/carla/libcarla.pyi @@ -694,15 +694,12 @@ class BoundingBox(): # endregion # region Methods - def __init__(self, location: Location, extent: Vector3D) -> BoundingBox: + def __init__(self, location: Location, extent: Vector3D): """Bounding boxes contain the geometry of an actor or an element in the scene. They can be used by `carla.DebugHelper` or a `carla.Client` to draw their shapes for debugging. Check out the snippet in `carla.DebugHelper.draw_box` where a snapshot of the world is used to draw bounding boxes for traffic lights. Args: `location (Location)`: Center of the box, relative to its parent.\n `extent (Vector3D)`: Vector containing half the size of the box for every axis.\n - - Returns: - `BoundingBox`\n """ ... @@ -782,16 +779,13 @@ class Client(): """ # region Methods - def __init__(self, host="127.0.0.1", port=2000, worker_threads=0) -> Client: + def __init__(self, host="127.0.0.1", port=2000, worker_threads=0): """Client constructor. Args: `host (str, optional)`: IP address where a CARLA Simulator instance is running. Defaults to "127.0.0.1".\n `port (int, optional)`: TCP port where the CARLA Simulator instance is running. Defaults to 2000 and the subsequent 2001.\n `worker_threads (int, optional)`: Number of working threads used for background updates. If 0, use all available concurrency. Defaults to 0.\n - - Returns: - `Client`: _description_\n """ def apply_batch(self, commands: list[command]): @@ -1039,7 +1033,7 @@ class Color(): # endregion # region Methods - def __init__(self, r=0, g=0, b=0, a=255) -> Color: + def __init__(self, r=0, g=0, b=0, a=255): """Initializes a color, black by default. Args: @@ -1280,7 +1274,7 @@ class FloatColor(): # endregion # region Methods - def __init__(self, r=.0, g=.0, b=.0, a=1.0) -> FloatColor: + def __init__(self, r=.0, g=.0, b=.0, a=1.0): """Initializes a color, black by default. Args: @@ -1288,9 +1282,6 @@ class FloatColor(): g (float, optional): Green color. Defaults to .0. b (float, optional): Blue color. Defaults to .0. a (float, optional): Alpha channel. Defaults to 1.0. - - Returns: - FloatColor """ ... # endregion @@ -1372,16 +1363,13 @@ class GearPhysicsControl(): # endregion # region Methods - def __init__(self, ratio=1.0, down_ratio=0.5, up_ratio=0.65) -> GearPhysicsControl: + def __init__(self, ratio=1.0, down_ratio=0.5, up_ratio=0.65): """Class that provides access to vehicle transmission details by defining a gear and when to run on it. This will be later used by `carla.VehiclePhysicsControl` to help simulate physics. Args: `ratio (float, optional)`: The transmission ratio of the gear. Defaults to 1.0.\n `down_ratio (float, optional)`: Quotient between current RPM and MaxRPM where the autonomous gear box should shift down. Defaults to 0.5.\n `up_ratio (float, optional)`: Quotient between current RPM and MaxRPM where the autonomous gear box should shift up. Defaults to 0.65.\n - - Returns: - `GearPhysicsControl`\n """ ... # endregion @@ -1414,7 +1402,7 @@ class GeoLocation(): # endregion # region Methods - def __init__(self, latitude=0.0, longitude=0.0, altitude=0.0) -> GeoLocation: + def __init__(self, latitude=0.0, longitude=0.0, altitude=0.0): """Class that contains geographical coordinates simulated data. The `carla.Map` can convert simulation locations by using the tag in the OpenDRIVE file. Args: @@ -2241,7 +2229,7 @@ class LightState(): # endregion # region Methods - def __init__(self, intensity=0.0, color=Color, group=LightGroup.NONE, active=False) -> LightState: + def __init__(self, intensity=0.0, color=Color, group=LightGroup.NONE, active=False): """This class represents all the light variables except the identifier and the location, which are should to be static. Using this class allows to manage all the parametrization of the light in one call. Args: @@ -2268,16 +2256,13 @@ class Location(Vector3D): # endregion # region Methods - def __init__(self, x=0.0, y=0.0, z=0.0) -> Location: + def __init__(self, x=0.0, y=0.0, z=0.0): """Represents a spot in the world. Args: `x (float, optional)`: Distance from origin to spot on X axis (meter). Defaults to 0.0.\n `y (float, optional)`: Distance from origin to spot on Y axis (meter). Defaults to 0.0.\n `z (float, optional)`: Distance from origin to spot on Z axis (meter). Defaults to 0.0.\n - - Returns: - `Location`\n """ ... @@ -2321,7 +2306,7 @@ class Map(): # endregion # region Methods - def __init__(self, name: str, xodr_content: str) -> list[Transform]: + def __init__(self, name: str, xodr_content: str): """Constructor for this class. Though a map is automatically generated when initializing the world, using this method in no-rendering mode facilitates working with an .xodr without any CARLA server running. Args: @@ -2601,7 +2586,7 @@ class OpticalFlowPixel(): # endregion # region Methods - def __init__(self, x=.0, y=.0) -> OpticalFlowPixel: + def __init__(self, x=.0, y=.0): """Initializes the Optical Flow Pixel. Zero by default. Args: @@ -2796,7 +2781,7 @@ class Rotation(): # endregion # region Methods - def __init__(self, pitch=.0, yaw=.0, roll=.0) -> Rotation: + def __init__(self, pitch=.0, yaw=.0, roll=.0): """+ Warning: The declaration order is different in CARLA (pitch,yaw,roll), and in the Unreal Engine Editor (roll,pitch,yaw). When working in a build from source, don't mix up the axes' rotations. Args: @@ -3019,7 +3004,7 @@ class TextureColor(): # endregion # region Methods - def __init__(self, width: int, height: int) -> TextureColor: + def __init__(self, width: int, height: int): """Initializes a the texture with a `(width, height)` size. Args: @@ -3089,7 +3074,7 @@ class Timestamp(): # endregion # region Methods - def __init__(self, frame: int, elapsed_seconds: float, delta_seconds: float, platform_timestamp: float) -> Timestamp: ... + def __init__(self, frame: int, elapsed_seconds: float, delta_seconds: float, platform_timestamp: float): ... # endregion # region Dunder Methods @@ -3511,7 +3496,7 @@ class Transform(): # endregion # region Methods - def __init__(self, location: Location, rotation: Rotation) -> Transform: ... + def __init__(self, location: Location, rotation: Rotation): ... def transform(self, in_point: Location): """Translates a 3D point from local to global coordinates using the current transformation as frame of reference. @@ -3570,7 +3555,7 @@ class Vector2D(): # endregion # region Methods - def __init__(self, x=0.0, y=0.0) -> Vector2D: ... + def __init__(self, x=0.0, y=0.0): ... def length(self) -> float: """Computes the length of the vector.""" @@ -3619,7 +3604,7 @@ class Vector3D(): # endregion # region Methods - def __init__(self, x=0.0, y=0.0, z=0.0) -> Vector3D: ... + def __init__(self, x=0.0, y=0.0, z=0.0): ... def cross(self, vector: Vector3D) -> Vector3D: """Computes the cross product between two vectors. @@ -3844,7 +3829,7 @@ class VehicleAckermannControl(): # endregion # region Methods - def __init__(self, steer=0.0, steer_speed=0.0, speed=0.0, acceleration=0.0, jerk=0.0) -> VehicleAckermannControl: ... + def __init__(self, steer=0.0, steer_speed=0.0, speed=0.0, acceleration=0.0, jerk=0.0): ... # endregion # region Dunder Methods @@ -4208,7 +4193,7 @@ class WalkerBoneControlIn(): # endregion # region Methods - def __init__(self, bone_transforms: list[tuple[str, Transform]]) -> WalkerBoneControlIn: + def __init__(self, bone_transforms: list[tuple[str, Transform]]): """Initializes an object containing moves to be applied on tick. These are listed with the name of the bone and the transform that will be applied to it. Args: @@ -4261,7 +4246,7 @@ class WalkerControl(): # endregion # region Methods - def __init__(self, direction=[1.0, 0.0, 0.0], speed=0.0, jump=False) -> WalkerControl: + def __init__(self, direction=[1.0, 0.0, 0.0], speed=0.0, jump=False): """This class defines specific directions that can be commanded to a `carla.Walker` to control it via script. Args: @@ -4999,7 +4984,7 @@ class command(): # endregion # region Methods - def __init__(self, actor: Union[Actor, int], impulse: Vector3D) -> command.ApplyAngularImpulse: + def __init__(self, actor: Union[Actor, int], impulse: Vector3D): """Applies an angular impulse to an actor. Args: From 0197e0ae5bdd9f09513af1b00acd11d1c618ded1 Mon Sep 17 00:00:00 2001 From: Daniel Date: Tue, 2 Apr 2024 17:48:34 +0200 Subject: [PATCH 71/99] FIX: added ApplyTransform, fixed ApplyTorque --- PythonAPI/carla/source/carla/libcarla.pyi | 29 ++++++++++++++++++++++- 1 file changed, 28 insertions(+), 1 deletion(-) diff --git a/PythonAPI/carla/source/carla/libcarla.pyi b/PythonAPI/carla/source/carla/libcarla.pyi index e84adec22..7b5d33216 100644 --- a/PythonAPI/carla/source/carla/libcarla.pyi +++ b/PythonAPI/carla/source/carla/libcarla.pyi @@ -5081,7 +5081,34 @@ class command(): # endregion class ApplyTorque(): - """Command adaptation of `set_transform()` in `carla.Actor`. Sets a new transform to an actor. + """ + Command adaptation of `add_torque()` in carla.Actor. Applies a torque to an actor. + """ + + # region Instance Variables + @property + def actor_id() -> int: + """Actor affected by the command.""" + + @property + def transform() -> Vector3D: + """Torque applied to the actor over time (degrees).""" + + # endregion + + # region Methods + def __init__(self, actor: Union[Actor, int], torque: Vector3D): + """Sets a new transform to an actor. + + Args: + `actor (Union[Actor, int])`: Actor or its ID to whom the command will be applied to.\n + `torque (Vector3D)`: Torque vector in global coordinates (degrees). + """ + # endregion + + class ApplyTransform(): + """ + Command adaptation of `set_transform()` in `carla.Actor`. Sets a new transform to an actor. """ # region Instance Variables From 1d4450b026094a731f6e294be056b6d0c5c796af Mon Sep 17 00:00:00 2001 From: Daniel Date: Wed, 3 Apr 2024 11:59:26 +0200 Subject: [PATCH 72/99] Filled in missing information and types. --- PythonAPI/carla/source/carla/libcarla.pyi | 17 ++++++++++++++--- 1 file changed, 14 insertions(+), 3 deletions(-) diff --git a/PythonAPI/carla/source/carla/libcarla.pyi b/PythonAPI/carla/source/carla/libcarla.pyi index 7b5d33216..34bc16d90 100644 --- a/PythonAPI/carla/source/carla/libcarla.pyi +++ b/PythonAPI/carla/source/carla/libcarla.pyi @@ -1,5 +1,5 @@ from enum import Enum -from typing import Callable, Iterable, Iterator, Union, overload +from typing import Callable, Iterable, Iterator, Union, Optional, overload class AckermannControllerSettings(): @@ -4724,8 +4724,19 @@ class World(): def get_actor(self, actor_id: int) -> Actor: """Looks up for an actor by ID and returns `None` if not found.""" - def get_actors(self, actor_ids: list = None) -> ActorList: - """Retrieves a list of `carla.Actor` elements, either using a list of IDs provided or just listing everyone on stage. If an ID does not correspond with any actor, it will be excluded from the list returned, meaning that both the list of IDs and the list of actors may have different lengths.""" + def get_actors(self, actor_ids: Optional["list[int]"] = None) -> ActorList: + """ + Retrieves a list of `carla.Actor` elements, either using a list of IDs provided or just + listing everyone on stage. If an ID does not correspond with any actor, it will be excluded + from the list returned, meaning that both the list of IDs and the list of actors may have + different lengths. + + Args: + `actor_ids (list[int], optional)`: The IDs of the actors being searched. By default it is set to None and returns every actor on scene. + + Returns: + `ActorList` + """ def get_blueprint_library(self) -> BlueprintLibrary: """Returns a list of actor blueprints available to ease the spawn of these into the world.""" From 4c086ad7d96fdc0b1df23cd5970f4d40f903b246 Mon Sep 17 00:00:00 2001 From: Daniel Date: Wed, 3 Apr 2024 19:00:32 +0200 Subject: [PATCH 73/99] ActorList.filter actually returns ActorList --- PythonAPI/carla/source/carla/libcarla.pyi | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/PythonAPI/carla/source/carla/libcarla.pyi b/PythonAPI/carla/source/carla/libcarla.pyi index 34bc16d90..5db389340 100644 --- a/PythonAPI/carla/source/carla/libcarla.pyi +++ b/PythonAPI/carla/source/carla/libcarla.pyi @@ -487,14 +487,14 @@ class ActorList(): """ # region Methods - def filter(self, wildcard_pattern: str) -> list: + def filter(self, wildcard_pattern: str) -> ActorList: """Filters a list of Actors matching wildcard_pattern against their variable `type_id` (which identifies the blueprint used to spawn them). Matching follows fnmatch standard. Args: `wildcard_pattern (str)`\n Returns: - `list`\n + `ActorList`\n """ ... From caac503fdbbb3ac66aea64c36f7a13a34b85f95e Mon Sep 17 00:00:00 2001 From: Daniel Date: Fri, 12 Apr 2024 15:49:53 +0200 Subject: [PATCH 74/99] Fixed CityObjectLabels --- PythonAPI/carla/source/carla/libcarla.pyi | 54 +++++++++++++---------- 1 file changed, 30 insertions(+), 24 deletions(-) diff --git a/PythonAPI/carla/source/carla/libcarla.pyi b/PythonAPI/carla/source/carla/libcarla.pyi index 5db389340..590d8df08 100644 --- a/PythonAPI/carla/source/carla/libcarla.pyi +++ b/PythonAPI/carla/source/carla/libcarla.pyi @@ -744,30 +744,36 @@ class BoundingBox(): class CityObjectLabel(Enum): """Enum declaration that contains the different tags available to filter the bounding boxes returned by carla.World.get_level_bbs(). These values correspond to the semantic tag that the elements in the scene have.""" - None, - Buildings = 1, - Fences = 2, - Other = 3, - Pedestrians = 4, - Poles = 5, - RoadLines = 6, - Roads = 7, - Sidewalks = 8, - TrafficSigns = 9, - Vegetation = 10, - Vehicles = 11, - Walls = 12, - Sky = 13, - Ground = 14, - Bridge = 15, - RailTrack = 16, - GuardRail = 17, - TrafficLight = 18, - Static = 19, - Dynamic = 20, - Water = 21, - Terrain = 22, - Any = 23 + NONE = 0, + Buildings = 3, + Fences = 5, + Other = 22, + Pedestrians = 12, + Poles = 6, + RoadLines = 24, + Roads = 1, + Sidewalks = 2, + TrafficSigns = 8, + Vegetation = 9, + Car = 14, + Walls = 4, + Sky = 11, + Ground = 25, + Bridge = 26, + RailTrack = 27, + GuardRail = 28, + TrafficLight = 7, + Static = 20, + Dynamic = 21, + Water = 23, + Terrain = 10, + Truck = 15, + Motorcycle = 18, + Bicycle = 19, + Bus = 16, + Rider = 13, + Train = 17, + Any = 255 class Client(): From df1eb257217f37cd78ac500b1b560520aa7dc1e4 Mon Sep 17 00:00:00 2001 From: Daniel Date: Fri, 12 Apr 2024 16:32:37 +0200 Subject: [PATCH 75/99] Disambiguated get_waypoint signature Syntax fix (squased) --- PythonAPI/carla/source/carla/libcarla.pyi | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/PythonAPI/carla/source/carla/libcarla.pyi b/PythonAPI/carla/source/carla/libcarla.pyi index 590d8df08..0b5b5074c 100644 --- a/PythonAPI/carla/source/carla/libcarla.pyi +++ b/PythonAPI/carla/source/carla/libcarla.pyi @@ -2412,6 +2412,11 @@ class Map(): """ ... + @overload + def get_waypoint(self, location: Location, project_to_road=False, lane_type=LaneType.Driving) -> Waypoint | None: + ... + + @overload def get_waypoint(self, location: Location, project_to_road=True, lane_type=LaneType.Driving) -> Waypoint: """Returns a waypoint that can be located in an exact location or translated to the center of the nearest lane. Said lane type can be defined using flags such as `LaneType.Driving & LaneType.Shoulder`. @@ -2424,7 +2429,7 @@ class Map(): """ ... - def get_waypoint_xodr(self, road_id: int, lane_id: int, s: float) -> Waypoint: + def get_waypoint_xodr(self, road_id: int, lane_id: int, s: float) -> Waypoint | None: """Returns a waypoint if all the parameters passed are correct. Otherwise, returns `None`. Args: From e7655593849d5e346dd3e7c9f56e8bca38f6e746 Mon Sep 17 00:00:00 2001 From: Daniel Date: Fri, 12 Apr 2024 16:32:06 +0200 Subject: [PATCH 76/99] Added undocumented variables FutureActor laod_world_if_different --- PythonAPI/carla/source/carla/libcarla.pyi | 22 ++++++++++++++++++++++ 1 file changed, 22 insertions(+) diff --git a/PythonAPI/carla/source/carla/libcarla.pyi b/PythonAPI/carla/source/carla/libcarla.pyi index 0b5b5074c..83eecf148 100644 --- a/PythonAPI/carla/source/carla/libcarla.pyi +++ b/PythonAPI/carla/source/carla/libcarla.pyi @@ -853,6 +853,25 @@ class Client(): Returns: `World`\n """ + + def load_world_if_different(self, map_name: str, reset_settings=True, map_layers=MapLayer.All): + """" + Creates a new world with default settings using `map_name` map only if it is a different map + from the currently loaded map. + Otherwise this function returns `None`. All actors in the current world will be destroyed. + + Args: + `map_name (str)`: Name of the map to be used in this world. Accepts both full paths and map names, + e.g.'/Game/Carla/Maps/Town01' or 'Town01'. Remember that these paths are dynamic.\n + `reset_settings (bool, optional)`: Option to reset the episode setting to default values, set to false to keep the current settings. + This is useful to keep sync mode when changing map and to keep deterministic scenarios. + Defaults to True.\n + `map_layers (MapLayer, optional)`: Layers of the map that will be loaded. This parameter works like a flag mask. + Defaults to MapLayer.All.\n + + Returns: + None + """ def replay_file(self, name: str, start: float, duration: float, follow_id: int, replay_sensors: bool): """Load a new world with default settings using `map_name` map. All actors present in the current world will be destroyed, but traffic manager instances will stay alive. @@ -5283,6 +5302,9 @@ class command(): `actor (Union[Actor, int])`: Actor or its ID to whom the command will be applied to.\n """ # endregion + + class FutureActor(): + """A utility object used to reference an actor that will be created in the command in the previous step, it has no parameters or methods.""" class Response(): """States the result of executing a command as either the ID of the actor to whom the command was applied to (when succeeded) or an error string (when failed). actor ID, depending on whether or not the command succeeded. The method `apply_batch_sync()` in c`arla.Client` returns a list of these to summarize the execution of a batch. From ddb5834e3855aa8b24e7e12094075670d7efbf9e Mon Sep 17 00:00:00 2001 From: Daniel Date: Fri, 14 Jun 2024 18:56:03 +0200 Subject: [PATCH 77/99] Corrected Sensor.is_listening Was changed to a function in 0.9.15. More info see: https://github.com/carla-simulator/carla/pull/7439 --- PythonAPI/carla/source/carla/libcarla.pyi | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/PythonAPI/carla/source/carla/libcarla.pyi b/PythonAPI/carla/source/carla/libcarla.pyi index 83eecf148..3a8767f2f 100644 --- a/PythonAPI/carla/source/carla/libcarla.pyi +++ b/PythonAPI/carla/source/carla/libcarla.pyi @@ -2945,12 +2945,16 @@ class Sensor(Actor): """ # region Instance Variables - @property - def is_listening() -> bool: - """When `True` the sensor will be waiting for data.""" + #@property + #def is_listening() -> bool: + # """When `True` the sensor will be waiting for data.""" # endregion # region Methods + + def is_listening(self) -> bool: + """Returns whether the sensor is in a listening state.""" + def is_listening_gbuffer(self, gbuffer_id: GBufferTextureID) -> bool: """Returns whether the sensor is in a listening state for a specific GBuffer texture. From 2935897950f47fd2477c59548192f70435baecde Mon Sep 17 00:00:00 2001 From: Daniel Date: Tue, 23 Jul 2024 12:20:40 +0200 Subject: [PATCH 78/99] Added type hints for `values` attribute on enums --- PythonAPI/carla/source/carla/libcarla.pyi | 57 +++++++++++++++-------- 1 file changed, 37 insertions(+), 20 deletions(-) diff --git a/PythonAPI/carla/source/carla/libcarla.pyi b/PythonAPI/carla/source/carla/libcarla.pyi index 3a8767f2f..52b2a853d 100644 --- a/PythonAPI/carla/source/carla/libcarla.pyi +++ b/PythonAPI/carla/source/carla/libcarla.pyi @@ -1,5 +1,19 @@ from enum import Enum -from typing import Callable, Iterable, Iterator, Union, Optional, overload +from typing import Callable, Iterable, Iterator, Union, Optional, overload, ClassVar + +class __CarlaEnum(Enum): + """ + CARLA's Enums have a `values` entry that is not part of the python enum.Enum class. + This abstract class adds this method. + """ + + values : ClassVar[dict[int, "__CarlaEnum"]] + names : ClassVar[dict[str, "__CarlaEnum"]] + + def __init_subclass__(cls): + cls.values : dict[int, cls] + cls.names : dict[str, cls] + class AckermannControllerSettings(): @@ -373,7 +387,7 @@ class ActorAttribute(): # endregion -class ActorAttributeType(Enum): +class ActorAttributeType(__CarlaEnum): """CARLA provides a library of blueprints for actors in `carla.BlueprintLibrary` with different attributes each. This class defines the types those at `carla.ActorAttribute` can be as a series of enum. All this information is managed internally and listed here for a better comprehension of how CARLA works. """ # region Instance Variables @@ -575,7 +589,7 @@ class ActorSnapshot(): # endregion -class ActorState(Enum): +class ActorState(__CarlaEnum): """Class that defines the state of an actor.""" # region Instance Variables Invalid = 0, @@ -587,7 +601,7 @@ class ActorState(Enum): # endregion -class AttachmentType(Enum): +class AttachmentType(__CarlaEnum): """Class that defines attachment options between an actor and its parent. When spawning actors, these can be attached to another actor so their position changes accordingly. This is specially useful for sensors. The snippet in `carla.World.spawn_actor` shows some sensors being attached to a car when spawned. + Note that the attachment type is declared as an enum within the class.""" @@ -742,7 +756,7 @@ class BoundingBox(): # endregion -class CityObjectLabel(Enum): +class CityObjectLabel(__CarlaEnum): """Enum declaration that contains the different tags available to filter the bounding boxes returned by carla.World.get_level_bbs(). These values correspond to the semantic tag that the elements in the scene have.""" NONE = 0, Buildings = 3, @@ -1076,7 +1090,7 @@ class Color(): # endregion -class ColorConverter(Enum): +class ColorConverter(__CarlaEnum): """Class that defines conversion patterns that can be applied to a `carla.Image` in order to show information provided by `carla.Sensor`. Depth conversions cause a loss of accuracy, as sensors detect depth as float that is then converted to a grayscale value between 0 and 255. Take a look at the snippet in `carla.Sensor.listen` to see an example of how to create and save image data for `sensor.camera.semantic_segmentation`. """ @@ -1317,7 +1331,7 @@ class FloatColor(): # endregion -class GBufferTextureID(Enum): +class GBufferTextureID(__CarlaEnum): """Defines the identifiers of each GBuffer texture (See the method `carla.Sensor.listen_to_gbuffer`).""" # region Instance Variables @@ -1710,7 +1724,7 @@ class Landmark(): # endregion -class LandmarkOrientation(Enum): +class LandmarkOrientation(__CarlaEnum): """Helper class to define the orientation of a landmark in the road. The definition is not directly translated from OpenDRIVE but converted for the sake of understanding.""" # region Instance Variables @@ -1725,6 +1739,9 @@ class LandmarkOrientation(Enum): class LandmarkType(Enum): """Helper class containing a set of commonly used landmark types as defined by the default country code in the OpenDRIVE standard (Germany 2017). `carla.Landmark` does not reference this class. The landmark type is a string that varies greatly depending on the country code being used. This class only makes it easier to manage some of the most commonly used in the default set by describing them as an enum.""" + + # NOTE: Has no attributes for `values` and `names` + # region Instance Variables Danger = "101", LanesMerging = "121", @@ -1764,7 +1781,7 @@ class LandmarkType(Enum): # endregion -class LaneChange(Enum): +class LaneChange(__CarlaEnum): """Class that defines the permission to turn either left, right, both or none (meaning only going straight is allowed). This information is stored for every `carla.Waypoint` according to the OpenDRIVE file. The snippet in `carla.Map.get_waypoint` shows how a waypoint can be used to learn which turns are permitted.""" # region Instance Variables @@ -1820,7 +1837,7 @@ class LaneMarking(): # endregion -class LaneMarkingColor(Enum): +class LaneMarkingColor(__CarlaEnum): """Class that defines the lane marking colors according to OpenDRIVE 1.4.""" # region Instance Variables @@ -1835,7 +1852,7 @@ class LaneMarkingColor(Enum): # endregion -class LaneMarkingType(Enum): +class LaneMarkingType(__CarlaEnum): """Class that defines the lane marking types accepted by OpenDRIVE 1.4. The snippet in `carla.Map.get_waypoint` shows how a waypoint can be used to retrieve the information about adjacent lane markings. + Note on double types: Lane markings are defined under the OpenDRIVE standard that determines whereas a line will be considered "BrokenSolid" or "SolidBroken". For each road there is a center lane marking, defined from left to right regarding the lane's directions. The rest of the lane markings are defined in order from the center lane to the closest outside of the road. @@ -1856,7 +1873,7 @@ class LaneMarkingType(Enum): # endregion -class LaneType(Enum): +class LaneType(__CarlaEnum): """Class that defines the possible lane types accepted by OpenDRIVE 1.4. This standards define the road information. The snippet in `carla.Map.get_waypoint` makes use of a waypoint to get the current and adjacent lane types.""" # region Instance Variables @@ -2032,7 +2049,7 @@ class Light(): # endregion -class LightGroup(Enum): +class LightGroup(__CarlaEnum): """This class categorizes the lights on scene into different groups. These groups available are provided as a enum values that can be used as flags. + Note. So far, though there is a `vehicle` group, vehicle lights are not available as `carla.Light` objects. These have to be managed using `carla.Vehicle` and `carla.VehicleLightState`.""" @@ -2460,7 +2477,7 @@ class Map(): # endregion -class MapLayer(Enum): +class MapLayer(__CarlaEnum): """Class that represents each manageable layer of the map. Can be used as flags. + WARNING: Only "Opt" maps are able to work with map layers.""" @@ -2478,7 +2495,7 @@ class MapLayer(Enum): """All layers selected.""" -class MaterialParameter(Enum): +class MaterialParameter(__CarlaEnum): """Class that represents material parameters. Not all objects in the scene contain all parameters.""" # region Instance Variables @@ -3236,7 +3253,7 @@ class TrafficLight(TrafficSign): # endregion -class TrafficLightState(Enum): +class TrafficLightState(__CarlaEnum): """All possible states for traffic lights. These can either change at a specific time step or be changed manually. The snippet in `carla.TrafficLight.set_state` changes the state of a traffic light on the fly.""" Red = 0, Yellow = 1, @@ -3921,7 +3938,7 @@ class VehicleControl(): # endregion -class VehicleDoor(Enum): +class VehicleDoor(__CarlaEnum): """Possible index representing the possible doors that can be open. Notice that not all possible doors are able to open in some vehicles.""" FL = 0, """Front left door.""" @@ -3935,7 +3952,7 @@ class VehicleDoor(Enum): """Represents all doors.""" -class VehicleFailureState(Enum): +class VehicleFailureState(__CarlaEnum): """Enum containing the different failure states of a vehicle, from which the it cannot recover. These are returned by get_failure_state() and only Rollover is currently implemented.""" NONE = 0, @@ -3944,7 +3961,7 @@ class VehicleFailureState(Enum): TirePuncture = 3, -class VehicleLightState(Enum): +class VehicleLightState(__CarlaEnum): """Class that recaps the state of the lights of a vehicle, these can be used as a flags. E.g: `VehicleLightState.HighBeam & VehicleLightState.Brake` will return `True` when both are active. @@ -4089,7 +4106,7 @@ class VehiclePhysicsControl(): # endregion -class VehicleWheelLocation(Enum): +class VehicleWheelLocation(__CarlaEnum): """enum representing the position of each wheel on a vehicle. Used to identify the target wheel when setting an angle in `carla.Vehicle.set_wheel_steer_direction` or `carla.Vehicle.get_wheel_steer_angle`.""" FL_Wheel = 0, """Front left wheel of a 4 wheeled vehicle.""" From 8df99c0414ea5a285a473520fc80c07483130240 Mon Sep 17 00:00:00 2001 From: Daniel Date: Wed, 24 Jul 2024 11:36:29 +0200 Subject: [PATCH 79/99] Fix intendation shadowing methods --- PythonAPI/carla/source/carla/libcarla.pyi | 96 ++++++++++++----------- 1 file changed, 51 insertions(+), 45 deletions(-) diff --git a/PythonAPI/carla/source/carla/libcarla.pyi b/PythonAPI/carla/source/carla/libcarla.pyi index 52b2a853d..0b3a7a163 100644 --- a/PythonAPI/carla/source/carla/libcarla.pyi +++ b/PythonAPI/carla/source/carla/libcarla.pyi @@ -898,67 +898,67 @@ class Client(): `replay_sensors (bool)`: Flag to enable or disable the spawn of sensors during playback.\n """ - def request_file(self, name: str): - """Requests one of the required files returned by `carla.Client.get_required_files`. + def request_file(self, name: str): + """Requests one of the required files returned by `carla.Client.get_required_files`. - Args: - `name (str)`: Name of the file you are requesting.\n - """ + Args: + `name (str)`: Name of the file you are requesting.\n + """ - def show_recorder_actors_blocked(self, filename: str, min_time: float, min_distance: float) -> str: - """The terminal will show the information registered for actors considered blocked. An actor is considered blocked when it does not move a minimum distance in a period of time, being these `min_distance` and `min_time`. + def show_recorder_actors_blocked(self, filename: str, min_time: float, min_distance: float) -> str: + """The terminal will show the information registered for actors considered blocked. An actor is considered blocked when it does not move a minimum distance in a period of time, being these `min_distance` and `min_time`. - Args: - `filename (str)`: Name of the recorded file to load.\n - `min_time (float - seconds)`: Minimum time the actor has to move a minimum distance before being considered blocked. Default is 60 seconds.\n - `min_distance (float - centimeters)`: Minimum distance the actor has to move to not be considered blocked. Default is 100 centimeters.\n + Args: + `filename (str)`: Name of the recorded file to load.\n + `min_time (float - seconds)`: Minimum time the actor has to move a minimum distance before being considered blocked. Default is 60 seconds.\n + `min_distance (float - centimeters)`: Minimum distance the actor has to move to not be considered blocked. Default is 100 centimeters.\n - Returns: - `str`\n - """ + Returns: + `str`\n + """ - def show_recorder_collisions(self, filename: str, category1: str, category2: str) -> str: - """The terminal will show the collisions registered by the recorder. These can be filtered by specifying the type of actor involved. The categories will be specified in `category1` and `category2` as follows: 'h' = Hero, the one vehicle that can be controlled manually or managed by the user. 'v' = Vehicle 'w' = Walker 't' = Traffic light 'o' = Other 'a' = Any If you want to see only collisions between a vehicles and a walkers, use for `category1` as 'v' and `category2` as 'w' or vice versa. If you want to see all the collisions (filter off) you can use 'a' for both parameters. + def show_recorder_collisions(self, filename: str, category1: str, category2: str) -> str: + """The terminal will show the collisions registered by the recorder. These can be filtered by specifying the type of actor involved. The categories will be specified in `category1` and `category2` as follows: 'h' = Hero, the one vehicle that can be controlled manually or managed by the user. 'v' = Vehicle 'w' = Walker 't' = Traffic light 'o' = Other 'a' = Any If you want to see only collisions between a vehicles and a walkers, use for `category1` as 'v' and `category2` as 'w' or vice versa. If you want to see all the collisions (filter off) you can use 'a' for both parameters. - Args: - `filename (str)`: Name or absolute path of the file recorded, depending on your previous choice.\n - `category1 (str)`: Character variable specifying a first type of actor involved in the collision.\n - `category2 (str)`: Character variable specifying the second type of actor involved in the collision.\n + Args: + `filename (str)`: Name or absolute path of the file recorded, depending on your previous choice.\n + `category1 (str)`: Character variable specifying a first type of actor involved in the collision.\n + `category2 (str)`: Character variable specifying the second type of actor involved in the collision.\n - Returns: - `str`\n - """ + Returns: + `str`\n + """ - def show_recorder_file_info(self, filename: str, show_all: bool) -> str: - """The information saved by the recorder will be parsed and shown in your terminal as text (frames, times, events, state, positions...). The information shown can be specified by using the `show_all` parameter. Here is some more information about how to read the recorder file. + def show_recorder_file_info(self, filename: str, show_all: bool) -> str: + """The information saved by the recorder will be parsed and shown in your terminal as text (frames, times, events, state, positions...). The information shown can be specified by using the `show_all` parameter. Here is some more information about how to read the recorder file. - https://carla.readthedocs.io/en/latest/ref_recorder_binary_file_format/ + https://carla.readthedocs.io/en/latest/ref_recorder_binary_file_format/ - Args: - `filename (str)`: Name or absolute path of the file recorded, depending on your previous choice.\n - `show_all (bool)`: If `True`, returns all the information stored for every frame (traffic light states, positions of all actors, orientation and animation data...). If `False`, returns a summary of key events and frames.\n + Args: + `filename (str)`: Name or absolute path of the file recorded, depending on your previous choice.\n + `show_all (bool)`: If `True`, returns all the information stored for every frame (traffic light states, positions of all actors, orientation and animation data...). If `False`, returns a summary of key events and frames.\n - Returns: - `str`\n - """ + Returns: + `str`\n + """ - def start_recorder(self, filename: str, additional_data=False): - """Enables the recording feature, which will start saving every information possible needed by the server to replay the simulation. + def start_recorder(self, filename: str, additional_data=False): + """Enables the recording feature, which will start saving every information possible needed by the server to replay the simulation. - Args: - `filename (str)`: Name of the file to write the recorded data. A simple name will save the recording in 'CarlaUE4/Saved/recording.log'. Otherwise, if some folder appears in the name, it will be considered an absolute path.\n - `additional_data (bool, optional)`: Enables or disable recording non-essential data for reproducing the simulation (bounding box location, physics control parameters, etc). Defaults to False.\n - """ + Args: + `filename (str)`: Name of the file to write the recorded data. A simple name will save the recording in 'CarlaUE4/Saved/recording.log'. Otherwise, if some folder appears in the name, it will be considered an absolute path.\n + `additional_data (bool, optional)`: Enables or disable recording non-essential data for reproducing the simulation (bounding box location, physics control parameters, etc). Defaults to False.\n + """ - def stop_recorder(self): - """Stops the recording in progress. If you specified a path in `filename`, the recording will be there. If not, look inside `CarlaUE4/Saved/`.""" + def stop_recorder(self): + """Stops the recording in progress. If you specified a path in `filename`, the recording will be there. If not, look inside `CarlaUE4/Saved/`.""" - def stop_replayer(self, keep_actors: bool): - """Stop current replayer. + def stop_replayer(self, keep_actors: bool): + """Stop current replayer. - Args: - `keep_actors (bool)`: `True` if you want autoremove all actors from the replayer, or `False` to keep them.\n - """ + Args: + `keep_actors (bool)`: `True` if you want autoremove all actors from the replayer, or `False` to keep them.\n + """ # endregion # region Getters @@ -5031,7 +5031,13 @@ class WorldSnapshot(): # endregion + + class command(): + """ + Submodule with commands that can be used with `carla.Client.apply_batch` + and `carla.Client.apply_batch_sync`. + """ class ApplyAngularImpulse(): """Command adaptation of `add_angular_impulse()` in `carla.Actor`. Applies an angular impulse to an actor. From 19b892f76b32f8cdd8f55cb35dc74ed611b0d095 Mon Sep 17 00:00:00 2001 From: Daniel Date: Wed, 24 Jul 2024 14:19:42 +0200 Subject: [PATCH 80/99] Fix missing @property --- PythonAPI/carla/source/carla/libcarla.pyi | 1 + 1 file changed, 1 insertion(+) diff --git a/PythonAPI/carla/source/carla/libcarla.pyi b/PythonAPI/carla/source/carla/libcarla.pyi index 0b3a7a163..076663929 100644 --- a/PythonAPI/carla/source/carla/libcarla.pyi +++ b/PythonAPI/carla/source/carla/libcarla.pyi @@ -1806,6 +1806,7 @@ class LaneInvasionEvent(SensorData): def actor() -> Actor: """Gets the actor the sensor is attached to, the one that invaded another lane.""" + @property def crossed_lane_markings() -> list[LaneMarking]: """List of lane markings that have been crossed and detected by the sensor.""" # endregion From a089c3b800b175116e038d20e23ce7e57ce83c29 Mon Sep 17 00:00:00 2001 From: Daniel Date: Wed, 24 Jul 2024 14:19:55 +0200 Subject: [PATCH 81/99] Formatted some docstring to be shorter --- PythonAPI/carla/source/carla/libcarla.pyi | 69 ++++++++++++++++++----- 1 file changed, 56 insertions(+), 13 deletions(-) diff --git a/PythonAPI/carla/source/carla/libcarla.pyi b/PythonAPI/carla/source/carla/libcarla.pyi index 076663929..2fd00a398 100644 --- a/PythonAPI/carla/source/carla/libcarla.pyi +++ b/PythonAPI/carla/source/carla/libcarla.pyi @@ -602,27 +602,48 @@ class ActorState(__CarlaEnum): class AttachmentType(__CarlaEnum): - """Class that defines attachment options between an actor and its parent. When spawning actors, these can be attached to another actor so their position changes accordingly. This is specially useful for sensors. The snippet in `carla.World.spawn_actor` shows some sensors being attached to a car when spawned. + """ + Class that defines attachment options between an actor and its parent. + When spawning actors, these can be attached to another actor so their + position changes accordingly. This is specially useful for sensors. + The snippet in `carla.World.spawn_actor` shows some sensors being + attached to a car when spawned. + Note that the attachment type is declared as an enum within the class.""" # region Instance Variables Rigid = 0, - """With this fixed attachment the object follow its parent position strictly. This is the recommended attachment to retrieve precise data from the simulation.""" + """With this fixed attachment the object follow its parent position strictly. + This is the recommended attachment to retrieve precise data from the simulation.""" + SpringArm = 1, - """An attachment that expands or retracts the position of the actor, depending on its parent. This attachment is only recommended to record videos from the simulation where a smooth movement is needed. SpringArms are an Unreal Engine component so check the UE docs to learn more about them. + """ + An attachment that expands or retracts the position of the actor, + depending on its parent. This attachment is only recommended to record + videos from the simulation where a smooth movement is needed. SpringArms + are an Unreal Engine component so check the UE docs to learn more about + them. https://docs.unrealengine.com/5.3/en-US/using-spring-arm-components-in-unreal-engine/ - + Warning: The `SpringArm` attachment presents weird behaviors when an actor is spawned with a relative translation in the Z-axis (e.g. `child_location = Location(0,0,2)`). - """ + + Warning: The `SpringArm` attachment presents weird behaviors when an + actor is spawned with a relative translation in the Z-axis (e.g. `child_location = Location(0,0,2)`). + """ SpringArmGhost = 2, - """An attachment like the previous one but that does not make the collision test, and that means that it does not expands or retracts the position of the actor. The term ghost is because then the camera can cross walls and other geometries. This attachment is only recommended to record videos from the simulation where a smooth movement is needed. SpringArms are an Unreal Engine component so check the UE docs to learn more about them. + """ + An attachment like the previous one but that does not make the collision test, + and that means that it does not expands or retracts the position of the actor. + The term ghost is because then the camera can cross walls and other geometries. + This attachment is only recommended to record videos from the simulation where + a smooth movement is needed. SpringArms are an Unreal Engine component so + check the UE docs to learn more about them. https://docs.unrealengine.com/5.3/en-US/using-spring-arm-components-in-unreal-engine/ - + Warning: The `SpringArm` attachment presents weird behaviors when an actor is spawned with a relative translation in the Z-axis (e.g. `child_location = Location(0,0,2)`).""" + + Warning: The `SpringArm` attachment presents weird behaviors when an actor is + spawned with a relative translation in the Z-axis (e.g. `child_location = Location(0,0,2)`). + """ # endregion @@ -1091,7 +1112,12 @@ class Color(): class ColorConverter(__CarlaEnum): - """Class that defines conversion patterns that can be applied to a `carla.Image` in order to show information provided by `carla.Sensor`. Depth conversions cause a loss of accuracy, as sensors detect depth as float that is then converted to a grayscale value between 0 and 255. Take a look at the snippet in `carla.Sensor.listen` to see an example of how to create and save image data for `sensor.camera.semantic_segmentation`. + """ + Class that defines conversion patterns that can be applied to a `carla.Image` in order to show + information provided by `carla.Sensor`. Depth conversions cause a loss of accuracy, as sensors + detect depth as float that is then converted to a grayscale value between 0 and 255. Take a look + at the snippet in `carla.Sensor.listen` to see an example of how to create and save image data + for `sensor.camera.semantic_segmentation`. """ # region Instance Variables @@ -3014,7 +3040,12 @@ class Sensor(Actor): class SensorData(): - """Base class for all the objects containing data generated by a `carla.Sensor`. This objects should be the argument of the function said sensor is listening to, in order to work with them. Each of these sensors needs for a specific type of sensor data. Hereunder is a list of the sensors and their corresponding data. + """ + Base class for all the objects containing data generated by a `carla.Sensor`. + This objects should be the argument of the function said sensor is listening to, + in order to work with them. Each of these sensors needs for a specific type of + sensor data. Hereunder is a list of the sensors and their corresponding data. + - Cameras (RGB, depth and semantic segmentation): `carla.Image`. - Collision detector: `carla.CollisionEvent`. - GNSS sensor: `carla.GnssMeasurement`. @@ -3044,7 +3075,9 @@ class SensorData(): class TextureColor(): - """Class representing a texture object to be uploaded to the server. Pixel format is RGBA, uint8 per channel. + """ + Class representing a texture object to be uploaded to the server. + Pixel format is RGBA, uint8 per channel. """ # region Instance Variables @property @@ -3082,7 +3115,10 @@ class TextureColor(): class TextureFloatColor(): - """Class representing a texture object to be uploaded to the server. Pixel format is RGBA, float per channel.""" + """ + Class representing a texture object to be uploaded to the server. + Pixel format is RGBA, float per channel. + """ # region Instance Variables @property @@ -3109,7 +3145,11 @@ class TextureFloatColor(): class Timestamp(): - """Class that contains time information for simulated data. This information is automatically retrieved as part of the `carla.WorldSnapshot` the client gets on every frame, but might also be used in many other situations such as a `carla.Sensor` retrieving data.""" + """ + Class that contains time information for simulated data. This information is automatically + retrieved as part of the `carla.WorldSnapshot` the client gets on every frame, but might also + be used in many other situations such as a `carla.Sensor` retrieving data. + """ # region Instance Variables @property @@ -4993,7 +5033,10 @@ class WorldSettings(): class WorldSnapshot(): - """This snapshot comprises all the information for every actor on scene at a certain moment of time. It creates and gives acces to a data structure containing a series of `carla.ActorSnapshot`. The client recieves a new snapshot on every tick that cannot be stored.""" + """ + This snapshot comprises all the information for every actor on scene at a certain moment of time. + It creates and gives acces to a data structure containing a series of `carla.ActorSnapshot`. + The client recieves a new snapshot on every tick that cannot be stored.""" pass # region Instance Variables From d9c217ee3cfc607e10d0eadc8895e87bdfe9e742 Mon Sep 17 00:00:00 2001 From: Daniel Date: Wed, 24 Jul 2024 14:48:37 +0200 Subject: [PATCH 82/99] Added stubs for HUD drawing Functions from #7168 --- PythonAPI/carla/source/carla/libcarla.pyi | 77 ++++++++++++++++++++--- 1 file changed, 68 insertions(+), 9 deletions(-) diff --git a/PythonAPI/carla/source/carla/libcarla.pyi b/PythonAPI/carla/source/carla/libcarla.pyi index 2fd00a398..957e75701 100644 --- a/PythonAPI/carla/source/carla/libcarla.pyi +++ b/PythonAPI/carla/source/carla/libcarla.pyi @@ -1211,11 +1211,16 @@ class DVSEventArray(): class DebugHelper(): - """Helper class part of `carla.World` that defines methods for creating debug shapes. By default, shapes last one second. They can be permanent, but take into account the resources needed to do so. Take a look at the snippets available for this class to learn how to debug easily in CARLA.""" + """ + Helper class part of `carla.World` that defines methods for creating debug shapes. By default, + shapes last one second. They can be permanent, but take into account the resources needed to do + so. Take a look at the snippets available for this class to learn how to debug easily in CARLA. + """ # region Methods - def draw_arrow(self, begin: Location, end: Location, thickness=0.1, arrow_size=0.1, color: Color = (255, 0, 0), life_time=-1.0): - """Draws an arrow from `begin` to `end` pointing in that direction. + def draw_arrow(self, begin: Location, end: Location, thickness=0.1, arrow_size=0.1, color: Color = (255, 0, 0), life_time=-1.0, persistent_lines=True): + """ + Draws an arrow from `begin` to `end` pointing in that direction. Args: begin (Location): Point in the coordinate system where the arrow starts (meters). @@ -1226,8 +1231,21 @@ class DebugHelper(): life_time (float, optional): Shape's lifespan. By default it only lasts one frame. Set this to `0` for permanent shapes (seconds). Defaults to -1.0. """ ... + + def draw_hud_arrow(self, begin: Location, end: Location, thickness=0.1, arrow_size=0.1, color: Color = (255, 0, 0), life_time=-1.0, persistent_lines=True): + """ + Draws an arrow on the HUD from `begin` to `end` which can only be seen server-side. + + Args: + begin (Location): Point in the coordinate system where the arrow starts (meters). + end (Location): Point in the coordinate system where the arrow ends and points towards to (meters). + thickness (float, optional): Density of the line (meters). Defaults to 0.1. + arrow_size (float, optional): Size of the tip of the arrow (meters). Defaults to 0.1. + color (Color, optional): RGB code to color the object. Defaults to (255,0,0). + life_time (float, optional): Shape's lifespan. By default it only lasts one frame. Set this to `0` for permanent shapes (seconds). Defaults to -1.0. + """ - def draw_box(self, box: BoundingBox, rotation: Rotation, thickness=0.1, color: Color = (255, 0, 0), life_time=-1.0): + def draw_box(self, box: BoundingBox, rotation: Rotation, thickness=0.1, color: Color = (255, 0, 0), life_time=-1.0, persistent_lines=True): """Draws a box, usually to act for object colliders. Args: @@ -1238,9 +1256,37 @@ class DebugHelper(): life_time (float, optional): Shape's lifespan. By default it only lasts one frame. Set this to `0` for permanent shapes. Defaults to -1.0. """ ... + + def draw_hud_box(self, box: BoundingBox, rotation: Rotation, thickness=0.1, color: Color = (255, 0, 0), life_time=-1.0, persistent_lines=True): + """ + Draws a box on the HUD, usually to act for object colliders. The box can only be seen server-side. - def draw_line(self, begin: Location, end: Location, thickness=0.1, color: Color = (255, 0, 0), life_time=-1.0): - """Draws a line in between `begin` and `end`. + Args: + box (BoundingBox): Object containing a location and the length of a box for every axis. + rotation (Rotation): Orientation of the box according to Unreal Engine's axis system (degrees (pitch,yaw,roll)). + thickness (float, optional): Density of the lines that define the box (meters). Defaults to 0.1. + color (Color, optional): RGB code to color the object. Defaults to (255,0,0). + life_time (float, optional): Shape's lifespan. By default it only lasts one frame. Set this to `0` for permanent shapes. Defaults to -1.0. + """ + ... + + + def draw_line(self, begin: Location, end: Location, thickness=0.1, color: Color = (255, 0, 0), life_time=-1.0, persistent_lines=True): + """ + Draws a line in between `begin` and `end`. + + Args: + begin (Location): Point in the coordinate system where the line starts (meters). + end (Location): Spot in the coordinate system where the line ends (meters). + thickness (float, optional): Density of the line. Defaults to 0.1. + color (Color, optional): RGB code to color the object. Defaults to (255,0,0). + life_time (float, optional): Shape's lifespan. By default it only lasts one frame. Set this to `0` for permanent shapes. Defaults to -1.0. + """ + ... + + def draw_hud_line(self, begin: Location, end: Location, thickness=0.1, color: Color = (255, 0, 0), life_time=-1.0, persistent_lines=True): + """ + Draws a line on the HUD in between `begin` and `end`. The line can only be seen server-side. Args: begin (Location): Point in the coordinate system where the line starts (meters). @@ -1251,8 +1297,21 @@ class DebugHelper(): """ ... - def draw_point(self, location: Location, size=0.1, color=(255, 0, 0), life_time=-1.0): - """Draws a point location. + def draw_point(self, location: Location, size=0.1, color=(255, 0, 0), life_time=-1.0, persistent_lines=True): + """ + Draws a point location. + + Args: + location (Location): Spot in the coordinate system to center the object (meters). + size (float, optional): Density of the point (meters). Defaults to 0.1. + color (tuple, optional): RGB code to color the object. Defaults to (255,0,0). + life_time (float, optional): Shape's lifespan. By default it only lasts one frame. Set this to 0 for permanent shapes (seconds). Defaults to -1.0. + """ + ... + + def draw_hud_point(self, location: Location, size=0.1, color=(255, 0, 0), life_time=-1.0, persistent_lines=True): + """ + Draws a point on the HUD at `location`. The point can only be seen server-side. Args: location (Location): Spot in the coordinate system to center the object (meters). @@ -1262,7 +1321,7 @@ class DebugHelper(): """ ... - def draw_string(self, location: Location, text: str, draw_shadow=False, color: Color = (255, 0, 0), life_time=-1.0): + def draw_string(self, location: Location, text: str, draw_shadow=False, color: Color = (255, 0, 0), life_time=-1.0, persistent_lines=True): """Draws a string in a given location of the simulation which can only be seen server-side. Args: From 41e595c056a5e8c215977baee21491008f17cb26 Mon Sep 17 00:00:00 2001 From: Daniel Date: Wed, 24 Jul 2024 15:53:47 +0200 Subject: [PATCH 83/99] Corrected and more precise type-hints - fixed carla.Waypoint.next_until_lane_end --- PythonAPI/carla/source/carla/libcarla.pyi | 68 ++++++++++++----------- 1 file changed, 36 insertions(+), 32 deletions(-) diff --git a/PythonAPI/carla/source/carla/libcarla.pyi b/PythonAPI/carla/source/carla/libcarla.pyi index 957e75701..ef75fc8b5 100644 --- a/PythonAPI/carla/source/carla/libcarla.pyi +++ b/PythonAPI/carla/source/carla/libcarla.pyi @@ -1,5 +1,5 @@ from enum import Enum -from typing import Callable, Iterable, Iterator, Union, Optional, overload, ClassVar +from typing import Callable, Iterable, Iterator, Union, Optional, overload, ClassVar, Any class __CarlaEnum(Enum): """ @@ -471,7 +471,7 @@ class ActorBlueprint(): # endregion # region Setters - def set_attribute(self, id: str, value: str): + def set_attribute(self, id: str, value: str) -> None: """If the `id` attribute is modifiable, changes its value to `value`. Args: @@ -495,8 +495,8 @@ class ActorBlueprint(): class ActorList(): - """A class that contains every actor present on the scene and provides access to them. - + """ + A class that contains every actor present on the scene and provides access to them. The list is automatically created and updated by the server and it can be returned using `carla.World`. """ @@ -1159,7 +1159,10 @@ class DVSEvent(): class DVSEventArray(): - """Class that defines a stream of events in `carla.DVSEvent`. Such stream is an array of arbitrary size depending on the number of events. This class also stores the field of view, the height and width of the image and the timestamp from convenience. Learn more about them here. + """ + Class that defines a stream of events in `carla.DVSEvent`. Such stream is an array of arbitrary + size depending on the number of events. This class also stores the field of view, the height and + width of the image and the timestamp from convenience. Learn more about them here. https://carla.readthedocs.io/en/latest/ref_sensors/ """ @@ -1218,7 +1221,7 @@ class DebugHelper(): """ # region Methods - def draw_arrow(self, begin: Location, end: Location, thickness=0.1, arrow_size=0.1, color: Color = (255, 0, 0), life_time=-1.0, persistent_lines=True): + def draw_arrow(self, begin: Location, end: Location, thickness=0.1, arrow_size=0.1, color: Color =Color(255, 0, 0), life_time=-1.0, persistent_lines=True) -> None: """ Draws an arrow from `begin` to `end` pointing in that direction. @@ -1232,7 +1235,7 @@ class DebugHelper(): """ ... - def draw_hud_arrow(self, begin: Location, end: Location, thickness=0.1, arrow_size=0.1, color: Color = (255, 0, 0), life_time=-1.0, persistent_lines=True): + def draw_hud_arrow(self, begin: Location, end: Location, thickness=0.1, arrow_size=0.1, color: Color =Color(255, 0, 0), life_time=-1.0, persistent_lines=True) -> None: """ Draws an arrow on the HUD from `begin` to `end` which can only be seen server-side. @@ -1245,7 +1248,7 @@ class DebugHelper(): life_time (float, optional): Shape's lifespan. By default it only lasts one frame. Set this to `0` for permanent shapes (seconds). Defaults to -1.0. """ - def draw_box(self, box: BoundingBox, rotation: Rotation, thickness=0.1, color: Color = (255, 0, 0), life_time=-1.0, persistent_lines=True): + def draw_box(self, box: BoundingBox, rotation: Rotation, thickness=0.1, color: Color =Color(255, 0, 0), life_time=-1.0, persistent_lines=True) -> None: """Draws a box, usually to act for object colliders. Args: @@ -1257,7 +1260,7 @@ class DebugHelper(): """ ... - def draw_hud_box(self, box: BoundingBox, rotation: Rotation, thickness=0.1, color: Color = (255, 0, 0), life_time=-1.0, persistent_lines=True): + def draw_hud_box(self, box: BoundingBox, rotation: Rotation, thickness=0.1, color: Color =Color(255, 0, 0), life_time=-1.0, persistent_lines=True) -> None: """ Draws a box on the HUD, usually to act for object colliders. The box can only be seen server-side. @@ -1271,7 +1274,7 @@ class DebugHelper(): ... - def draw_line(self, begin: Location, end: Location, thickness=0.1, color: Color = (255, 0, 0), life_time=-1.0, persistent_lines=True): + def draw_line(self, begin: Location, end: Location, thickness=0.1, color: Color =Color(255, 0, 0), life_time=-1.0, persistent_lines=True) -> None: """ Draws a line in between `begin` and `end`. @@ -1284,7 +1287,7 @@ class DebugHelper(): """ ... - def draw_hud_line(self, begin: Location, end: Location, thickness=0.1, color: Color = (255, 0, 0), life_time=-1.0, persistent_lines=True): + def draw_hud_line(self, begin: Location, end: Location, thickness=0.1, color: Color =Color(255, 0, 0), life_time=-1.0, persistent_lines=True) -> None: """ Draws a line on the HUD in between `begin` and `end`. The line can only be seen server-side. @@ -1297,7 +1300,7 @@ class DebugHelper(): """ ... - def draw_point(self, location: Location, size=0.1, color=(255, 0, 0), life_time=-1.0, persistent_lines=True): + def draw_point(self, location: Location, size=0.1, color=Color(255, 0, 0), life_time=-1.0, persistent_lines=True) -> None: """ Draws a point location. @@ -1309,7 +1312,7 @@ class DebugHelper(): """ ... - def draw_hud_point(self, location: Location, size=0.1, color=(255, 0, 0), life_time=-1.0, persistent_lines=True): + def draw_hud_point(self, location: Location, size=0.1, color=(255, 0, 0), life_time=-1.0, persistent_lines=True) -> None: """ Draws a point on the HUD at `location`. The point can only be seen server-side. @@ -1321,7 +1324,7 @@ class DebugHelper(): """ ... - def draw_string(self, location: Location, text: str, draw_shadow=False, color: Color = (255, 0, 0), life_time=-1.0, persistent_lines=True): + def draw_string(self, location: Location, text: str, draw_shadow=False, color: Color = (255, 0, 0), life_time=-1.0, persistent_lines=True) -> None: """Draws a string in a given location of the simulation which can only be seen server-side. Args: @@ -1861,7 +1864,7 @@ class LandmarkType(Enum): CityEnd = "311", Highway = "330", DeadEnd = "357", - RecomendedSpeed = "380", # NOTE: Wrong Spelling, but is named like this internally! + RecomendedSpeed = "380", # NOTE: Wrong Spelling, but is named like this internally! RecomendedSpeedEnd = "381", # NOTE: Wrong Spelling, but is named like this internally! # endregion @@ -3065,16 +3068,18 @@ class Sensor(Actor): `gbuffer_id (GBufferTextureID)`: The ID of the target Unreal Engine GBuffer texture.\n """ - def listen(self, callback: Callable): - """The function the sensor will be calling to every time a new measurement is received. This function needs for an argument containing an object type `carla.SensorData` to work with. + def listen(self, callback: Callable[[SensorData], Any]) -> None: + """ + The function the sensor will be calling to every time a new measurement is received. + This function needs for an argument containing an object type `carla.SensorData` to work with. Args: - `callback (Callable)`: The called function with one argument containing the sensor data.\n + `callback (Callable[[SensorData], Any])`: The called function with one argument containing the sensor data.\n """ - def listen_to_gbuffer(self, gbuffer_id: GBufferTextureID, callback: Callable): - """The function the sensor will be calling to every time the desired GBuffer texture is received. - + def listen_to_gbuffer(self, gbuffer_id: GBufferTextureID, callback: Callable[[SensorData], Any]) -> None: + """ + The function the sensor will be calling to every time the desired GBuffer texture is received. This function needs for an argument containing an object type `carla.SensorData` to work with. Args: @@ -3646,17 +3651,17 @@ class Transform(): """Describes a rotation for an object according to Unreal Engine's axis system (degrees (pitch, yaw, roll)).""" # endregion - # region Methods - def __init__(self, location: Location, rotation: Rotation): ... + # region Methods + def __init__(self, location: Location = Location(0,0,0), rotation: Rotation = Rotation(0,0,0)): ... - def transform(self, in_point: Location): + def transform(self, in_point: Vector3D) -> Vector3D: """Translates a 3D point from local to global coordinates using the current transformation as frame of reference. Args: in_point (Location): Translates a 3D point from local to global coordinates using the current transformation as frame of reference. """ - def transform_vector(self, in_vector: Vector3D): + def transform_vector(self, in_vector: Vector3D) -> Vector3D: """Rotates a vector using the current transformation as frame of reference, without applying translation. Use this to transform, for example, a velocity. Args: @@ -4488,11 +4493,10 @@ class Waypoint(): """ def next_until_lane_end(self, distance: float) -> list[Waypoint]: - """This method does not return the waypoint previously visited by an actor, but a list of waypoints at an approximate `distance` but in the opposite direction of the lane. Similarly to `next()`, it takes into account the road and its possible deviations without performing any lane change and returns one waypoint per option. The list may be empty if the lane is not connected to any other at the specified distance. - + """Returns a list of waypoints from this to the end of the lane separated by a certain `distance`."" Args: - `distance (float)`: The approximate distance where to get the previous waypoints (meters).\n + `distance (float)`: The approximate distance between waypoints.(meters). Returns: `list[Waypoint]`\n @@ -4877,11 +4881,11 @@ class World(): def get_actors(self, actor_ids: Optional["list[int]"] = None) -> ActorList: """ - Retrieves a list of `carla.Actor` elements, either using a list of IDs provided or just - listing everyone on stage. If an ID does not correspond with any actor, it will be excluded - from the list returned, meaning that both the list of IDs and the list of actors may have + Retrieves a list of `carla.Actor` elements, either using a list of IDs provided or just + listing everyone on stage. If an ID does not correspond with any actor, it will be excluded + from the list returned, meaning that both the list of IDs and the list of actors may have different lengths. - + Args: `actor_ids (list[int], optional)`: The IDs of the actors being searched. By default it is set to None and returns every actor on scene. From f797e1593a9ddebbc99c4e5407c6358ca45e04b9 Mon Sep 17 00:00:00 2001 From: Daniel Date: Wed, 24 Jul 2024 17:13:39 +0200 Subject: [PATCH 84/99] Improved get_waypoint disambiguation correctly added two overload function --- PythonAPI/carla/source/carla/libcarla.pyi | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/PythonAPI/carla/source/carla/libcarla.pyi b/PythonAPI/carla/source/carla/libcarla.pyi index ef75fc8b5..eef5c8c4c 100644 --- a/PythonAPI/carla/source/carla/libcarla.pyi +++ b/PythonAPI/carla/source/carla/libcarla.pyi @@ -1,5 +1,5 @@ from enum import Enum -from typing import Callable, Iterable, Iterator, Union, Optional, overload, ClassVar, Any +from typing import Callable, Iterable, Iterator, Union, Optional, overload, ClassVar, Any, Literal class __CarlaEnum(Enum): """ @@ -2538,11 +2538,14 @@ class Map(): ... @overload - def get_waypoint(self, location: Location, project_to_road=False, lane_type=LaneType.Driving) -> Waypoint | None: + def get_waypoint(self, location: Location, project_to_road: Literal[True]=True, lane_type=LaneType.Driving) -> Waypoint: ... @overload - def get_waypoint(self, location: Location, project_to_road=True, lane_type=LaneType.Driving) -> Waypoint: + def get_waypoint(self, location: Location, project_to_road: Literal[False], lane_type=LaneType.Driving) -> Waypoint | None: + ... + + def get_waypoint(self, location: Location, project_to_road=True, lane_type=LaneType.Driving): """Returns a waypoint that can be located in an exact location or translated to the center of the nearest lane. Said lane type can be defined using flags such as `LaneType.Driving & LaneType.Shoulder`. The method will return `None` if the waypoint is not found, which may happen only when trying to retrieve a waypoint for an exact location. That eases checking if a point is inside a certain road, as otherwise, it will return the corresponding waypoint. @@ -2565,7 +2568,6 @@ class Map(): ... # endregion - class MapLayer(__CarlaEnum): """Class that represents each manageable layer of the map. Can be used as flags. From b061f9e9512e2cb85d3f9f8d0ad5493a96cf0ed9 Mon Sep 17 00:00:00 2001 From: Daniel Date: Wed, 24 Jul 2024 18:05:14 +0200 Subject: [PATCH 85/99] Fix spelling mistakes --- PythonAPI/carla/source/carla/libcarla.pyi | 15 ++++++++------- 1 file changed, 8 insertions(+), 7 deletions(-) diff --git a/PythonAPI/carla/source/carla/libcarla.pyi b/PythonAPI/carla/source/carla/libcarla.pyi index eef5c8c4c..edb594432 100644 --- a/PythonAPI/carla/source/carla/libcarla.pyi +++ b/PythonAPI/carla/source/carla/libcarla.pyi @@ -4562,7 +4562,7 @@ class Waypoint(): class WeatherParameters(): """This class defines objects containing lighting and weather specifications that can later be applied in `carla.World`. So far, these conditions only intervene with `sensor.camera.rgb`. They neither affect the actor's physics nor other sensors. - Each of these parameters acts indepently from the rest. Increasing the rainfall will not automatically create puddles nor change the road's humidity. That makes for a better customization but means that realistic conditions need to be scripted. However an example of dynamic weather conditions working realistically can be found here. + Each of these parameters acts independently from the rest. Increasing the rainfall will not automatically create puddles nor change the road's humidity. That makes for a better customization but means that realistic conditions need to be scripted. However an example of dynamic weather conditions working realistically can be found here. https://github.com/carla-simulator/carla/blob/master/PythonAPI/examples/dynamic_weather.py """ @@ -4728,16 +4728,16 @@ class World(): # region Methods def apply_color_texture_to_object(self, object_name: str, material_parameter: MaterialParameter, texture: TextureColor): - """Applies a `texture` object in the field corresponfing to `material_parameter` (normal, diffuse, etc) to the object in the scene corresponding to `object_name`.""" + """Applies a `texture` object in the field corresponding to `material_parameter` (normal, diffuse, etc) to the object in the scene corresponding to `object_name`.""" def apply_color_texture_to_objects(self, objects_name_list: list[str], material_parameter: MaterialParameter, texture: TextureColor): - """Applies a `texture` object in the field corresponfing to `material_parameter` (normal, diffuse, etc) to the object in the scene corresponding to all objects in `objects_name_list`.""" + """Applies a `texture` object in the field corresponding to `material_parameter` (normal, diffuse, etc) to the object in the scene corresponding to all objects in `objects_name_list`.""" def apply_float_color_texture_to_object(self, object_name: str, material_parameter: MaterialParameter, texture: TextureFloatColor): - """Applies a `texture` object in the field corresponfing to `material_parameter` (normal, diffuse, etc) to the object in the scene corresponding to all objects in `objects_name_list`.""" + """Applies a `texture` object in the field corresponding to `material_parameter` (normal, diffuse, etc) to the object in the scene corresponding to all objects in `objects_name_list`.""" def apply_float_color_texture_to_objects(self, objects_name_list: list[str], material_parameter: MaterialParameter, texture: TextureFloatColor): - """Applies a `texture` object in the field corresponfing to `material_parameter` (normal, diffuse, etc) to the object in the scene corresponding to all objects in `objects_name_list`.""" + """Applies a `texture` object in the field corresponding to `material_parameter` (normal, diffuse, etc) to the object in the scene corresponding to all objects in `objects_name_list`.""" def apply_settings(self, world_settings: WorldSettings) -> int: """This method applies settings contained in an object to the simulation running and returns the ID of the frame they were implemented. @@ -5000,13 +5000,14 @@ class World(): def set_pedestrians_seed(self, seed: int): """ Sets the seed to use for any random number generated in relation to pedestrians. - + Note: Should be set before pedestrians are spawned. If you want to repeat the same exact bodies (blueprint) for each pedestrian, then use the same seed in the Python code (where the blueprint is choosen randomly) and here, otherwise the pedestrians will repeat the same paths but the bodies will be different. + + Note: Should be set before pedestrians are spawned. If you want to repeat the same exact bodies (blueprint) for each pedestrian, then use the same seed in the Python code (where the blueprint is chosen randomly) and here, otherwise the pedestrians will repeat the same paths but the bodies will be different. """ def set_weather(self, weather: WeatherParameters): - """Changes the weather parameteres ruling the simulation to another ones defined in an object. + """Changes the weather parameters ruling the simulation to another ones defined in an object. + Getter: `carla.World.get_weather` + Args: `weather (WeatherParameters)`: New conditions to be applied.\n """ From a959577ccf6ba7496f342b8cedf22d2c0bf414f0 Mon Sep 17 00:00:00 2001 From: Daniel Date: Mon, 29 Jul 2024 15:19:38 +0200 Subject: [PATCH 86/99] Better usage of Enum if typing.Self is availiable Using Self will not report an override / incompatible error. --- PythonAPI/carla/source/carla/libcarla.pyi | 15 ++++++++++----- 1 file changed, 10 insertions(+), 5 deletions(-) diff --git a/PythonAPI/carla/source/carla/libcarla.pyi b/PythonAPI/carla/source/carla/libcarla.pyi index edb594432..b5a74c368 100644 --- a/PythonAPI/carla/source/carla/libcarla.pyi +++ b/PythonAPI/carla/source/carla/libcarla.pyi @@ -1,14 +1,19 @@ from enum import Enum +import sys from typing import Callable, Iterable, Iterator, Union, Optional, overload, ClassVar, Any, Literal - +if sys.version_info < (3, 11): + from typing_extensions import Self +else: + from typing import Self + class __CarlaEnum(Enum): """ - CARLA's Enums have a `values` entry that is not part of the python enum.Enum class. - This abstract class adds this method. + CARLA's Enums have a `values` and `names` attribute that are not part of the python `enum.Enum` + class. This abstract stub class adds these attributes. """ - values : ClassVar[dict[int, "__CarlaEnum"]] - names : ClassVar[dict[str, "__CarlaEnum"]] + values : ClassVar[dict[int, Self]] + names : ClassVar[dict[str, Self]] def __init_subclass__(cls): cls.values : dict[int, cls] From 453ceca112cfe866f95f39921fdd79d004fc7cd1 Mon Sep 17 00:00:00 2001 From: Daniel Date: Mon, 29 Jul 2024 16:30:49 +0200 Subject: [PATCH 87/99] Fix: Enum values were tuples. Added Flag or Int to Enums --- PythonAPI/carla/source/carla/libcarla.pyi | 355 +++++++++++----------- 1 file changed, 178 insertions(+), 177 deletions(-) diff --git a/PythonAPI/carla/source/carla/libcarla.pyi b/PythonAPI/carla/source/carla/libcarla.pyi index b5a74c368..958e78197 100644 --- a/PythonAPI/carla/source/carla/libcarla.pyi +++ b/PythonAPI/carla/source/carla/libcarla.pyi @@ -1,4 +1,4 @@ -from enum import Enum +from enum import Enum, Flag, IntFlag import sys from typing import Callable, Iterable, Iterator, Union, Optional, overload, ClassVar, Any, Literal if sys.version_info < (3, 11): @@ -392,15 +392,15 @@ class ActorAttribute(): # endregion -class ActorAttributeType(__CarlaEnum): +class ActorAttributeType(int, __CarlaEnum): """CARLA provides a library of blueprints for actors in `carla.BlueprintLibrary` with different attributes each. This class defines the types those at `carla.ActorAttribute` can be as a series of enum. All this information is managed internally and listed here for a better comprehension of how CARLA works. """ # region Instance Variables - Bool = 0, - Int = 1, - Float = 2, - String = 3, - RGBColor = 4, + Bool = 0 + Int = 1 + Float = 2 + String = 3 + RGBColor = 4 # endregion @@ -594,19 +594,19 @@ class ActorSnapshot(): # endregion -class ActorState(__CarlaEnum): +class ActorState(int, __CarlaEnum): """Class that defines the state of an actor.""" # region Instance Variables - Invalid = 0, + Invalid = 0 """An actor is Invalid if a problem has occurred.""" - Active = 1, + Active = 1 """An actor is Active when it visualized and can affect other actors.""" - Dormant = 2, + Dormant = 2 """An actor is Dormant when it is not visualized and will not affect other actors through physics. For example, actors are dormant if they are on an unloaded tile in a large map.""" # endregion -class AttachmentType(__CarlaEnum): +class AttachmentType(int, __CarlaEnum): """ Class that defines attachment options between an actor and its parent. When spawning actors, these can be attached to another actor so their @@ -617,11 +617,11 @@ class AttachmentType(__CarlaEnum): + Note that the attachment type is declared as an enum within the class.""" # region Instance Variables - Rigid = 0, + Rigid = 0 """With this fixed attachment the object follow its parent position strictly. This is the recommended attachment to retrieve precise data from the simulation.""" - SpringArm = 1, + SpringArm = 1 """ An attachment that expands or retracts the position of the actor, depending on its parent. This attachment is only recommended to record @@ -635,7 +635,7 @@ class AttachmentType(__CarlaEnum): actor is spawned with a relative translation in the Z-axis (e.g. `child_location = Location(0,0,2)`). """ - SpringArmGhost = 2, + SpringArmGhost = 2 """ An attachment like the previous one but that does not make the collision test, and that means that it does not expands or retracts the position of the actor. @@ -782,37 +782,37 @@ class BoundingBox(): # endregion -class CityObjectLabel(__CarlaEnum): +class CityObjectLabel(int, __CarlaEnum): """Enum declaration that contains the different tags available to filter the bounding boxes returned by carla.World.get_level_bbs(). These values correspond to the semantic tag that the elements in the scene have.""" - NONE = 0, - Buildings = 3, - Fences = 5, - Other = 22, - Pedestrians = 12, - Poles = 6, - RoadLines = 24, - Roads = 1, - Sidewalks = 2, - TrafficSigns = 8, - Vegetation = 9, - Car = 14, - Walls = 4, - Sky = 11, - Ground = 25, - Bridge = 26, - RailTrack = 27, - GuardRail = 28, - TrafficLight = 7, - Static = 20, - Dynamic = 21, - Water = 23, - Terrain = 10, - Truck = 15, - Motorcycle = 18, - Bicycle = 19, - Bus = 16, - Rider = 13, - Train = 17, + NONE = 0 + Buildings = 3 + Fences = 5 + Other = 22 + Pedestrians = 12 + Poles = 6 + RoadLines = 24 + Roads = 1 + Sidewalks = 2 + TrafficSigns = 8 + Vegetation = 9 + Car = 14 + Walls = 4 + Sky = 11 + Ground = 25 + Bridge = 26 + RailTrack = 27 + GuardRail = 28 + TrafficLight = 7 + Static = 20 + Dynamic = 21 + Water = 23 + Terrain = 10 + Truck = 15 + Motorcycle = 18 + Bicycle = 19 + Bus = 16 + Rider = 13 + Train = 17 Any = 255 @@ -1116,7 +1116,7 @@ class Color(): # endregion -class ColorConverter(__CarlaEnum): +class ColorConverter(int, __CarlaEnum): """ Class that defines conversion patterns that can be applied to a `carla.Image` in order to show information provided by `carla.Sensor`. Depth conversions cause a loss of accuracy, as sensors @@ -1126,13 +1126,13 @@ class ColorConverter(__CarlaEnum): """ # region Instance Variables - Raw = 0, + Raw = 0 """No changes applied to the image. Used by the `RGB camera`.""" - Depth = 1, + Depth = 1 """Converts the image to a linear depth map. Used by the `depth camera`.""" - LogarithmicDepth = 2, + LogarithmicDepth = 2 """Converts the image to a depth map using a logarithmic scale, leading to better precision for small distances at the expense of losing it when further away.""" - CityScapesPalette = 3, + CityScapesPalette = 3 """Converts the image to a segmented map using tags provided by the blueprint library. Used by the `semantic segmentation camera`.""" # endregion @@ -1424,25 +1424,25 @@ class FloatColor(): # endregion -class GBufferTextureID(__CarlaEnum): +class GBufferTextureID(int, __CarlaEnum): """Defines the identifiers of each GBuffer texture (See the method `carla.Sensor.listen_to_gbuffer`).""" # region Instance Variables - SceneColor = 0, + SceneColor = 0 """The texture "SceneColor" contains the final color of the image.""" - SceneDepth = 1, + SceneDepth = 1 """The texture "SceneDepth" contains the depth buffer - linear in world units.""" - SceneStencil = 2, + SceneStencil = 2 """The texture "SceneStencil" contains the stencil buffer.""" - GBufferA = 3, + GBufferA = 3 """The texture "GBufferA" contains the world-space normal vectors in the RGB channels. The alpha channel contains "per-object data".""" - GBufferB = 4, + GBufferB = 4 """The texture "GBufferB" contains the metallic, specular and roughness in the RGB channels, respectively. The alpha channel contains a mask where the lower 4 bits indicate the shading model and the upper 4 bits contain the selective output mask.""" - GBufferC = 5, + GBufferC = 5 """The texture "GBufferC" contains the diffuse color in the RGB channels, with the indirect irradiance in the alpha channel. If static lightning is not allowed, the alpha channel will contain the ambient occlusion instead.""" - GBufferD = 6, + GBufferD = 6 """ The contents of the "GBufferD" varies depending on the rendered object's material shading model (GBufferB): MSM_Subsurface (2), MSM_PreintegratedSkin (3), MSM_TwoSidedFoliage (6): @@ -1464,17 +1464,17 @@ class GBufferTextureID(__CarlaEnum): B: Iris mask. A: Iris distance. """ - GBufferE = 7, + GBufferE = 7 """The texture "GBufferE" contains the precomputed shadow factors in the RGBA channels. This texture is unavailable if the selective output mask (GBufferB) does not have its 4th bit set.""" - GBufferF = 8, + GBufferF = 8 """The texture "GBufferF" contains the world-space tangent in the RGB channels and the anisotropy in the alpha channel. This texture is unavailable if the selective output mask (GBufferB) does not have its 5th bit set.""" - Velocity = 9, + Velocity = 9 """The texture "Velocity" contains the screen-space velocity of the scene objects.""" - SSAO = 10, + SSAO = 10 """The texture "SSAO" contains the screen-space ambient occlusion texture.""" - CustomDepth = 11, + CustomDepth = 11 """The texture "CustomDepth" contains the Unreal Engine custom depth data.""" - CustomStencil = 12, + CustomStencil = 12 """The texture "CustomStencil" contains the Unreal Engine custom stencil data.""" # endregion @@ -1817,15 +1817,15 @@ class Landmark(): # endregion -class LandmarkOrientation(__CarlaEnum): +class LandmarkOrientation(int, __CarlaEnum): """Helper class to define the orientation of a landmark in the road. The definition is not directly translated from OpenDRIVE but converted for the sake of understanding.""" # region Instance Variables - Positive = 0, + Positive = 0 """The landmark faces towards vehicles going on the same direction as the road's geometry definition (lanes 0 and negative in OpenDRIVE).""" - Negative = 1, + Negative = 1 """The landmark faces towards vehicles going on the opposite direction to the road's geometry definition (positive lanes in OpenDRIVE).""" - Both = 2, + Both = 2 """Affects vehicles going in both directions of the road.""" # endregion @@ -1874,17 +1874,17 @@ class LandmarkType(Enum): # endregion -class LaneChange(__CarlaEnum): +class LaneChange(int, __CarlaEnum): """Class that defines the permission to turn either left, right, both or none (meaning only going straight is allowed). This information is stored for every `carla.Waypoint` according to the OpenDRIVE file. The snippet in `carla.Map.get_waypoint` shows how a waypoint can be used to learn which turns are permitted.""" # region Instance Variables - NONE = 0, + NONE = 0 """Traffic rules do not allow turning right or left, only going straight.""" - Right = 1, + Right = 1 """Traffic rules allow turning right.""" - Left = 2, + Left = 2 """Traffic rules allow turning left.""" - Both = 3, + Both = 3 """Traffic rules allow turning either right or left.""" # endregion @@ -1931,72 +1931,73 @@ class LaneMarking(): # endregion -class LaneMarkingColor(__CarlaEnum): +class LaneMarkingColor(int, __CarlaEnum): """Class that defines the lane marking colors according to OpenDRIVE 1.4.""" # region Instance Variables - White = 0, - Standard = 0, + White = 0 + Standard = 0 """White by default.""" - Blue = 1, - Green = 2, - Red = 3, - Yellow = 4, - Other = 5, + Blue = 1 + Green = 2 + Red = 3 + Yellow = 4 + Other = 5 # endregion -class LaneMarkingType(__CarlaEnum): +class LaneMarkingType(int, __CarlaEnum): """Class that defines the lane marking types accepted by OpenDRIVE 1.4. The snippet in `carla.Map.get_waypoint` shows how a waypoint can be used to retrieve the information about adjacent lane markings. + Note on double types: Lane markings are defined under the OpenDRIVE standard that determines whereas a line will be considered "BrokenSolid" or "SolidBroken". For each road there is a center lane marking, defined from left to right regarding the lane's directions. The rest of the lane markings are defined in order from the center lane to the closest outside of the road. """ # region Instance Variables - Other = 0, - Broken = 1, - Solid = 2, - SolidSolid = 3, - SolidBroken = 4, - BrokenSolid = 5, - BrokenBroken = 6, - BottsDots = 7, - Grass = 8, - Curb = 9, - NONE = 0, + Other = 0 + Broken = 1 + Solid = 2 + SolidSolid = 3 + SolidBroken = 4 + BrokenSolid = 5 + BrokenBroken = 6 + BottsDots = 7 + Grass = 8 + Curb = 9 + NONE = 0 # endregion -class LaneType(__CarlaEnum): +class LaneType(IntFlag, __CarlaEnum): """Class that defines the possible lane types accepted by OpenDRIVE 1.4. This standards define the road information. The snippet in `carla.Map.get_waypoint` makes use of a waypoint to get the current and adjacent lane types.""" # region Instance Variables - Any = -2, - NONE = 1, + Any = -2 + NONE = 1 """Every type except for `NONE`.""" - Driving = 2, - Stop = 4, - Shoulder = 8, - Biking = 16, - Sidewalk = 32, - Border = 64, - Restricted = 128, - Parking = 256, - Bidirectional = 512, - Median = 1024, - Special1 = 2048, - Special2 = 4096, - Special3 = 8192, - RoadWorks = 16384, - Tram = 32768, - Rail = 65536, - Entry = 131072, - Exit = 262144, - OffRamp = 524288, - OnRamp = 1048576, + Driving = 2 + Stop = 4 + Shoulder = 8 + Biking = 16 + Sidewalk = 32 + Border = 64 + Restricted = 128 + Parking = 256 + Bidirectional = 512 + Median = 1024 + Special1 = 2048 + Special2 = 4096 + Special3 = 8192 + RoadWorks = 16384 + Tram = 32768 + Rail = 65536 + Entry = 131072 + Exit = 262144 + OffRamp = 524288 + OnRamp = 1048576 # endregion + class LidarDetection(): """Data contained inside a `carla.LidarMeasurement`. Each of these represents one of the points in the cloud with its location and its associated intensity.""" # region Instance Variables @@ -2143,17 +2144,17 @@ class Light(): # endregion -class LightGroup(__CarlaEnum): +class LightGroup(int, __CarlaEnum): """This class categorizes the lights on scene into different groups. These groups available are provided as a enum values that can be used as flags. + Note. So far, though there is a `vehicle` group, vehicle lights are not available as `carla.Light` objects. These have to be managed using `carla.Vehicle` and `carla.VehicleLightState`.""" - NONE = 0, + NONE = 0 """All lights.""" - Vehicle = 1, - Street = 2, - Building = 3, - Other = 4, + Vehicle = 1 + Street = 2 + Building = 3 + Other = 4 class LightManager(): @@ -2573,35 +2574,35 @@ class Map(): ... # endregion -class MapLayer(__CarlaEnum): +class MapLayer(Flag, __CarlaEnum): """Class that represents each manageable layer of the map. Can be used as flags. + WARNING: Only "Opt" maps are able to work with map layers.""" - NONE = 0, - Buildings = 1, - Decals = 2, - Foliage = 4, - Ground = 8, - ParkedVehicles = 16, - Particles = 32, - Props = 64, - StreetLights = 128, - Walls = 256, - All = 65535, + NONE = 0 + Buildings = 1 + Decals = 2 + Foliage = 4 + Ground = 8 + ParkedVehicles = 16 + Particles = 32 + Props = 64 + StreetLights = 128 + Walls = 256 + All = 65535 """All layers selected.""" -class MaterialParameter(__CarlaEnum): +class MaterialParameter(int, __CarlaEnum): """Class that represents material parameters. Not all objects in the scene contain all parameters.""" # region Instance Variables - Normal = 0, + Normal = 0 """The Normal map of the object. Present in all objects.""" - AO_Roughness_Metallic_Emissive = 1, + AO_Roughness_Metallic_Emissive = 1 """A texture where each color channel represent a property of the material (R: Ambient occlusion, G: Roughness, B: Metallic, A: Emissive/Height map in some objects).""" - Diffuse = 2, + Diffuse = 2 """The Diffuse texture of the object. Present in all objects.""" - Emissive = 3, + Emissive = 3 """Emissive texture. Present in a few objects.""" # endregion @@ -3365,13 +3366,13 @@ class TrafficLight(TrafficSign): # endregion -class TrafficLightState(__CarlaEnum): +class TrafficLightState(int, __CarlaEnum): """All possible states for traffic lights. These can either change at a specific time step or be changed manually. The snippet in `carla.TrafficLight.set_state` changes the state of a traffic light on the fly.""" - Red = 0, - Yellow = 1, - Green = 2, - Off = 3, - Unknown = 4, + Red = 0 + Yellow = 1 + Green = 2 + Off = 3 + Unknown = 4 class TrafficManager(): @@ -4050,30 +4051,30 @@ class VehicleControl(): # endregion -class VehicleDoor(__CarlaEnum): +class VehicleDoor(int, __CarlaEnum): """Possible index representing the possible doors that can be open. Notice that not all possible doors are able to open in some vehicles.""" - FL = 0, + FL = 0 """Front left door.""" - FR = 1, + FR = 1 """Front right door.""" - RL = 2, + RL = 2 """Back left door.""" - RR = 3, + RR = 3 """Back right door.""" - All = 6, + All = 6 """Represents all doors.""" -class VehicleFailureState(__CarlaEnum): +class VehicleFailureState(int, __CarlaEnum): """Enum containing the different failure states of a vehicle, from which the it cannot recover. These are returned by get_failure_state() and only Rollover is currently implemented.""" - NONE = 0, - Rollover = 1, - Engine = 2, - TirePuncture = 3, + NONE = 0 + Rollover = 1 + Engine = 2 + TirePuncture = 3 -class VehicleLightState(__CarlaEnum): +class VehicleLightState(Flag, __CarlaEnum): """Class that recaps the state of the lights of a vehicle, these can be used as a flags. E.g: `VehicleLightState.HighBeam & VehicleLightState.Brake` will return `True` when both are active. @@ -4081,22 +4082,22 @@ class VehicleLightState(__CarlaEnum): Lights are off by default in any situation and should be managed by the user via script. The blinkers blink automatically. + Warning: Right now, not all vehicles have been prepared to work with this functionality, this will be added to all of them in later updates.""" - NONE = 0, + NONE = 0 """All lights off.""" - Position = 1, - LowBeam = 2, - HighBeam = 4, - Brake = 8, - RightBlinker = 16, - LeftBlinker = 32, - Reverse = 64, - Fog = 128, - Interior = 256, - Special1 = 512, + Position = 1 + LowBeam = 2 + HighBeam = 4 + Brake = 8 + RightBlinker = 16 + LeftBlinker = 32 + Reverse = 64 + Fog = 128 + Interior = 256 + Special1 = 512 """This is reserved for certain vehicles that can have special lights, like a siren.""" - Special2 = 1024, + Special2 = 1024 """This is reserved for certain vehicles that can have special lights, like a siren.""" - All = -1, + All = -1 """All lights on.""" @@ -4218,19 +4219,19 @@ class VehiclePhysicsControl(): # endregion -class VehicleWheelLocation(__CarlaEnum): +class VehicleWheelLocation(int, __CarlaEnum): """enum representing the position of each wheel on a vehicle. Used to identify the target wheel when setting an angle in `carla.Vehicle.set_wheel_steer_direction` or `carla.Vehicle.get_wheel_steer_angle`.""" - FL_Wheel = 0, + FL_Wheel = 0 """Front left wheel of a 4 wheeled vehicle.""" - FR_Wheel = 1, + FR_Wheel = 1 """Front right wheel of a 4 wheeled vehicle.""" - BL_Wheel = 2, + BL_Wheel = 2 """Back left wheel of a 4 wheeled vehicle.""" - BR_Wheel = 3, + BR_Wheel = 3 """Back right wheel of a 4 wheeled vehicle.""" - Front_Wheel = 0, + Front_Wheel = 0 """Front wheel of a 2 wheeled vehicle.""" - Back_Wheel = 1, + Back_Wheel = 1 """Back wheel of a 2 wheeled vehicle.""" From da80757e27a5176d274a514b24ae40c39b5ead8f Mon Sep 17 00:00:00 2001 From: Daniel Date: Mon, 29 Jul 2024 16:32:39 +0200 Subject: [PATCH 88/99] Fixes for wrong stubs - OpendriveGenerationParameter had no init - missing @property - wrong signatures --- PythonAPI/carla/source/carla/libcarla.pyi | 19 +++++++++++++++++-- 1 file changed, 17 insertions(+), 2 deletions(-) diff --git a/PythonAPI/carla/source/carla/libcarla.pyi b/PythonAPI/carla/source/carla/libcarla.pyi index 958e78197..a24ab7792 100644 --- a/PythonAPI/carla/source/carla/libcarla.pyi +++ b/PythonAPI/carla/source/carla/libcarla.pyi @@ -858,7 +858,7 @@ class Client(): `list[command.Response]`\n """ - def generate_opendrive_world(self, opendrive: str, parameters: OpendriveGenerationParameters = (2.0, 50.0, 1.0, 0.6, True, True), reset_settings=True): + def generate_opendrive_world(self, opendrive: str, parameters: OpendriveGenerationParameters = OpendriveGenerationParameters(2.0, 50.0, 1.0, 0.6, True, True), reset_settings=True): """Loads a new world with a basic 3D topology generated from the content of an OpenDRIVE file. This content is passed as a `string` parameter. It is similar to `client.load_world(map_name)` but allows for custom OpenDRIVE maps in server side. Cars can drive around the map, but there are no graphics besides the road and sidewalks. Args: @@ -1663,10 +1663,12 @@ class Junction(): """Class that embodies the intersections on the road described in the OpenDRIVE file according to OpenDRIVE 1.4 standards.""" # region Instance Variables + @property def id() -> int: """Identifier found in the OpenDRIVE file.""" ... + @property def bounding_box() -> BoundingBox: """Bounding box encapsulating the junction lanes.""" ... @@ -2672,6 +2674,19 @@ class OpendriveGenerationParameters(): """If `True`, Pedestrian navigation will be enabled using Recast tool. For very large maps it is recommended to disable this option. Default is `True`.""" ... # endregion + + # region Methods + + # region Methods + def __init__(self, vertex_distance: float =2.0, + max_road_length:float = 50.0, + wall_height:float = 1.0, + additional_width: float=0.6, + smooth_junctions: bool =True, + enable_mesh_visibility: bool=True, + enable_pedestrian_navigation: bool=True): + """Constructor method""" + ... class OpticalFlowImage(SensorData): @@ -4637,7 +4652,7 @@ class WeatherParameters(): fog_falloff=0.0, scattering_intensity=0.0, mie_scattering_scale=0.0, - rayleigh_scattering_scale=0.0331) -> WeatherParameters: + rayleigh_scattering_scale=0.0331): """Method to initialize an object defining weather conditions. This class has some presets for different noon and sunset conditions listed in a note below. + Note: ClearNoon, CloudyNoon, WetNoon, WetCloudyNoon, SoftRainNoon, MidRainyNoon, HardRainNoon, ClearSunset, CloudySunset, WetSunset, WetCloudySunset, SoftRainSunset, MidRainSunset, HardRainSunset. From ca81e35d59218e3932ea95a6494abc04568346f1 Mon Sep 17 00:00:00 2001 From: Daniel Date: Mon, 29 Jul 2024 16:34:01 +0200 Subject: [PATCH 89/99] Added self parameter to property signatures --- PythonAPI/carla/source/carla/libcarla.pyi | 600 +++++++++++----------- 1 file changed, 300 insertions(+), 300 deletions(-) diff --git a/PythonAPI/carla/source/carla/libcarla.pyi b/PythonAPI/carla/source/carla/libcarla.pyi index a24ab7792..f9e916567 100644 --- a/PythonAPI/carla/source/carla/libcarla.pyi +++ b/PythonAPI/carla/source/carla/libcarla.pyi @@ -26,32 +26,32 @@ class AckermannControllerSettings(): # region Instance Variables @property - def speed_kp() -> float: + def speed_kp(self) -> float: """Proportional term of the speed PID controller.""" ... @property - def speed_ki() -> float: + def speed_ki(self) -> float: """Integral term of the speed PID controller.""" ... @property - def speed_kd() -> float: + def speed_kd(self) -> float: """Derivative term of the speed PID controller.""" ... @property - def accel_kp() -> float: + def accel_kp(self) -> float: """Proportional term of the acceleration PID controller.""" ... @property - def accel_ki() -> float: + def accel_ki(self) -> float: """Integral term of the acceleration PID controller.""" ... @property - def accel_kd() -> float: + def accel_kd(self) -> float: """Derivative term of the acceleration PID controller.""" ... # endregion @@ -86,46 +86,46 @@ class Actor(): # region Instance Variables @property - def attributes() -> dict: + def attributes(self) -> dict: """A dictionary containing the attributes of the blueprint this actor was based on. """ ... @property - def id() -> int: + def id(self) -> int: """Identifier for this actor. Unique during a given episode. """ ... @property - def type_id() -> str: + def type_id(self) -> str: """The identifier of the blueprint this actor was based on, e.g., `vehicle.ford.mustang.`""" ... @property - def is_alive() -> bool: + def is_alive(self) -> bool: """Returns whether this object was destroyed using this actor handle.""" ... @property - def is_active() -> bool: + def is_active(self) -> bool: """Returns whether this actor is active (`True`) or not (`False`).""" ... @property - def is_dormant() -> bool: + def is_dormant(self) -> bool: """Returns whether this actor is dormant (`True`) or not (`False`) - the opposite of `is_active`.""" ... @property - def parent() -> Union["Actor", None]: + def parent(self) -> Union["Actor", None]: """Actors may be attached to a parent actor that they will follow around. This is said actor.""" ... @property - def semantic_tags() -> list[int]: + def semantic_tags(self) -> list[int]: """A list of semantic tags provided by the blueprint listing components for this actor. E.g. a traffic light could be tagged with `Pole` and `TrafficLight`. These tags are used by the semantic segmentation sensor. Find more about this and other sensors here @@ -133,12 +133,12 @@ class Actor(): """ @property - def actor_state() -> ActorState: + def actor_state(self) -> ActorState: """Returns the carla.ActorState, which can identify if the actor is Active, Dormant or Invalid.""" ... @property - def bounding_box() -> BoundingBox: + def bounding_box(self) -> BoundingBox: """Bounding box containing the geometry of the actor. Its location and rotation are relative to the actor it is attached to.""" # endregion @@ -345,17 +345,17 @@ class ActorAttribute(): # region Instance Variables @property - def id() -> str: + def id(self) -> str: """The attribute's name and identifier in the library. """ @property - def is_modifiable() -> bool: + def is_modifiable(self) -> bool: """It is True if the attribute's value can be modified.""" @property - def recommended_values() -> list[str]: + def recommended_values(self) -> list[str]: """A list of values suggested by those who designed the blueprint.""" @property - def type() -> ActorAttributeType: + def type(self) -> ActorAttributeType: """The attribute's parameter type.""" # endregion @@ -410,13 +410,13 @@ class ActorBlueprint(): # region Instance Variables @property - def id() -> str: + def id(self) -> str: """The identifier of said blueprint inside the library. E.g. `walker.pedestrian.0001`.""" @property - def tags() -> list[str]: + def tags(self) -> list[str]: """A list of tags each blueprint has that helps describing them. E.g. `['0001', 'pedestrian', 'walker']`. @@ -554,7 +554,7 @@ class ActorSnapshot(): # region Instance Variables @property - def id() -> int: + def id(self) -> int: """An identifier for the snapshot itself.""" ... # endregion @@ -714,14 +714,14 @@ class BoundingBox(): # region Instance Variables @property - def extent() -> Vector3D: + def extent(self) -> Vector3D: """Vector from the center of the box to one vertex. The value in each axis equals half the size of the box for that axis. `extent.x * 2` would return the size of the box in the X-axis. Returns: `Vector3D`: meters\n """ @property - def location() -> Location: + def location(self) -> Location: """The center of the bounding box. Returns: @@ -729,7 +729,7 @@ class BoundingBox(): """ @property - def rotation() -> Rotation: + def rotation(self) -> Rotation: """The orientation of the bounding box.""" # endregion @@ -1068,13 +1068,13 @@ class CollisionEvent(SensorData): """ # region Instance Variables @property - def actor() -> Actor: + def actor(self) -> Actor: """The actor the sensor is attached to, the one that measured the collision.""" @property - def other_actor() -> Actor: + def other_actor(self) -> Actor: """The second actor involved in the collision.""" @property - def normal_impulse() -> Vector3D: + def normal_impulse(self) -> Vector3D: """Normal impulse resulting of the collision.(N*s)""" # endregion @@ -1084,16 +1084,16 @@ class Color(): # region Instance Variables @property - def r() -> int: + def r(self) -> int: """Red color (0-255).""" @property - def g() -> int: + def g(self) -> int: """Green color (0-255).""" @property - def b() -> int: + def b(self) -> int: """Blue color (0-255).""" @property - def a() -> int: + def a(self) -> int: """Alpha channel (0-255).""" # endregion @@ -1145,16 +1145,16 @@ class DVSEvent(): # region Instance Variables @property - def x() -> int: + def x(self) -> int: """X pixel coordinate.""" @property - def x() -> int: + def x(self) -> int: """Y pixel coordinate.""" @property - def t() -> int: + def t(self) -> int: """Timestamp of the moment the event happened.""" @property - def pol() -> bool: + def pol(self) -> bool: """Polarity of the event. True for positive and False for negative.""" # endregion @@ -1174,16 +1174,16 @@ class DVSEventArray(): # region Instance Variables @property - def fov() -> float: + def fov(self) -> float: """Horizontal field of view of the image.""" @property - def height() -> int: + def height(self) -> int: """Image height in pixels.""" @property - def width() -> int: + def width(self) -> int: """Image width in pixels.""" @property - def raw_data() -> bytes: ... + def raw_data(self) -> bytes: ... # endregion # region Methods @@ -1348,27 +1348,27 @@ class EnvironmentObject(): # region Instance Variables @property - def transform() -> Transform: + def transform(self) -> Transform: """Contains the location and orientation of the EnvironmentObject in world space.""" ... @property - def bounding_box() -> BoundingBox: + def bounding_box(self) -> BoundingBox: """Object containing a location, rotation and the length of a box for every axis in world space.""" ... @property - def id() -> int: + def id(self) -> int: """Unique ID to identify the object in the level.""" ... @property - def name() -> str: + def name(self) -> str: """Name of the EnvironmentObject.""" ... @property - def type() -> CityObjectLabel: + def type(self) -> CityObjectLabel: """Semantic tag.""" ... # endregion @@ -1385,22 +1385,22 @@ class FloatColor(): # region Instance Variables @property - def r() -> float: + def r(self) -> float: """Red color.""" ... @property - def g() -> float: + def g(self) -> float: """Green color.""" ... @property - def b() -> float: + def b(self) -> float: """Blue color.""" ... @property - def a() -> float: + def a(self) -> float: """Alpha channel.""" ... # endregion @@ -1518,17 +1518,17 @@ class GeoLocation(): # region Instance Variables @property - def latitude() -> float: + def latitude(self) -> float: """North/South value of a point on the map (degrees).""" ... @property - def longitude() -> float: + def longitude(self) -> float: """West/East value of a point on the map (degrees).""" ... @property - def altitude() -> float: + def altitude(self) -> float: """Height regarding ground level (meters).""" ... # endregion @@ -1557,17 +1557,17 @@ class GnssMeasurement(SensorData): # region Instance Variables @property - def altitude() -> float: + def altitude(self) -> float: """Height regarding ground level (meters).""" ... @property - def latitude() -> float: + def latitude(self) -> float: """North/South value of a point on the map (degrees).""" ... @property - def longitude() -> float: + def longitude(self) -> float: """West/East value of a point on the map (degrees).""" ... # endregion @@ -1582,17 +1582,17 @@ class IMUMeasurement(SensorData): # region Instance Variables @property - def accelerometer() -> Vector3D: + def accelerometer(self) -> Vector3D: """Linear acceleration (m/s2).""" ... @property - def compass() -> float: + def compass(self) -> float: """Orientation with regard to the North ([0.0, -1.0, 0.0] in Unreal Engine) (radians).""" ... @property - def gyroscope() -> Vector3D: + def gyroscope(self) -> Vector3D: """Angular velocity. (rad/s)""" ... # endregion @@ -1609,22 +1609,22 @@ class Image(SensorData): # region Instance Variables @property - def fov() -> float: + def fov(self) -> float: """Horizontal field of view of the image (degrees).""" ... @property - def height() -> int: + def height(self) -> int: """Image height in pixels.""" ... @property - def width() -> int: + def width(self) -> int: """Image width in pixels.""" ... @property - def raw_data() -> bytes: + def raw_data(self) -> bytes: """Flattened array of pixel data, use reshape to create an image array.""" ... # endregion @@ -1664,12 +1664,12 @@ class Junction(): # region Instance Variables @property - def id() -> int: + def id(self) -> int: """Identifier found in the OpenDRIVE file.""" ... @property - def bounding_box() -> BoundingBox: + def bounding_box(self) -> BoundingBox: """Bounding box encapsulating the junction lanes.""" ... # endregion @@ -1692,12 +1692,12 @@ class LabelledPoint(): # region Instance Variables @property - def location() -> Location: + def location(self) -> Location: """Position in 3D space.""" ... @property - def label() -> CityObjectLabel: + def label(self) -> CityObjectLabel: """Semantic tag of the point.""" ... # endregion @@ -1708,106 +1708,106 @@ class Landmark(): # region Instance Variables @property - def road_id() -> int: + def road_id(self) -> int: """The OpenDRIVE ID of the road where this landmark is defined. Due to OpenDRIVE road definitions, this road may be different from the road the landmark is currently affecting. It is mostly the case in junctions where the road diverges in different routes. Example: a traffic light is defined in one of the divergent roads in a junction, but it affects all the possible routes.""" ... @property - def distance() -> float: + def distance(self) -> float: """Distance between the landmark and the waypoint creating the object (querying `get_landmarks` or `get_landmarks_of_type`) (meters).""" ... @property - def s() -> float: + def s(self) -> float: """Distance where the landmark is positioned along the geometry of the road `road_id` (meters).""" ... @property - def t() -> float: + def t(self) -> float: """Lateral distance where the landmark is positioned from the edge of the road `road_id` (meters).""" ... @property - def id() -> str: + def id(self) -> str: """Unique ID of the landmark in the OpenDRIVE file.""" ... @property - def name() -> str: + def name(self) -> str: """Name of the landmark in the in the OpenDRIVE file.""" ... @property - def is_dynamic() -> bool: + def is_dynamic(self) -> bool: """Indicates if the landmark has state changes over time such as traffic lights.""" ... @property - def orientation() -> LandmarkOrientation: + def orientation(self) -> LandmarkOrientation: """Indicates which lanes the landmark is facing towards to (degrees).""" ... @property - def z_offset() -> float: + def z_offset(self) -> float: """Height where the landmark is placed (meters).""" ... @property - def country() -> str: + def country(self) -> str: """Country code where the landmark is defined (default to OpenDRIVE is Germany 2017).""" ... @property - def type() -> str: + def type(self) -> str: """Type identifier of the landmark according to the country code.""" ... @property - def sub_type() -> str: + def sub_type(self) -> str: """Subtype identifier of the landmark according to the country code.""" @property - def value() -> float: + def value(self) -> float: """Value printed in the signal (e.g. speed limit, maximum weight, etc).""" @property - def unit() -> str: + def unit(self) -> str: """Units of measurement for the attribute `value`.""" ... @property - def height() -> float: + def height(self) -> float: """Total height of the signal (meters).""" @property - def width() -> float: + def width(self) -> float: """Total width of the signal (meters).""" @property - def text() -> str: + def text(self) -> str: """Additional text in the signal.""" @property - def h_offset() -> float: + def h_offset(self) -> float: """Orientation offset of the signal relative to the the definition of `road_id` at `s` in OpenDRIVE (meters).""" ... @property - def pitch() -> float: + def pitch(self) -> float: """Pitch rotation of the signal (Y-axis in UE coordinates system) (meters).""" @property - def roll() -> float: + def roll(self) -> float: """Roll rotation of the signal (X-axis in UE coordinates system) (meters).""" @property - def waypoint() -> Waypoint: + def waypoint(self) -> Waypoint: """A waypoint placed in the lane of the one that made the query and at the `s` of the landmark. It is the first waypoint for which the landmark will be effective.""" @property - def transform() -> Transform: + def transform(self) -> Transform: """The location and orientation of the landmark in the simulation.""" # endregion @@ -1902,7 +1902,7 @@ class LaneInvasionEvent(SensorData): """Gets the actor the sensor is attached to, the one that invaded another lane.""" @property - def crossed_lane_markings() -> list[LaneMarking]: + def crossed_lane_markings(self) -> list[LaneMarking]: """List of lane markings that have been crossed and detected by the sensor.""" # endregion @@ -1916,19 +1916,19 @@ class LaneMarking(): # region Instance Variables @property - def color() -> LaneMarkingColor: + def color(self) -> LaneMarkingColor: """Actual color of the marking.""" @property - def lane_change() -> LaneChange: + def lane_change(self) -> LaneChange: """Permissions for said lane marking to be crossed.""" @property - def type() -> LaneMarkingType: + def type(self) -> LaneMarkingType: """Lane marking type.""" @property - def width() -> float: + def width(self) -> float: """Horizontal lane marking thickness.""" # endregion @@ -2004,10 +2004,10 @@ class LidarDetection(): """Data contained inside a `carla.LidarMeasurement`. Each of these represents one of the points in the cloud with its location and its associated intensity.""" # region Instance Variables @property - def point() -> Location: + def point(self) -> Location: """Point in xyz coordinates (meters).""" @property - def intensity() -> float: + def intensity(self) -> float: """Computed intensity for this point as a scalar value between [0.0 , 1.0].""" # endregion @@ -2023,15 +2023,15 @@ class LidarMeasurement(SensorData): """ # region Instance Variables @property - def channels() -> int: + def channels(self) -> int: """Number of lasers shot.""" @property - def horizontal_angle() -> float: + def horizontal_angle(self) -> float: """Horizontal angle the LIDAR is rotated at the time of the measurement (radians).""" @property - def raw_data() -> bytes: + def raw_data(self) -> bytes: """Received list of 4D points. Each point consists of [x,y,z] coordinates plus the intensity computed for that point.""" # endregion @@ -2071,35 +2071,35 @@ class Light(): # region Instance Variables @property - def color() -> Color: + def color(self) -> Color: """Color of the light.""" ... @property - def id() -> int: + def id(self) -> int: """Identifier of the light.""" ... @property - def intensity() -> float: + def intensity(self) -> float: """Intensity of the light. (lumens)""" @property - def is_on() -> bool: + def is_on(self) -> bool: """Switch of the light. It is `True` when the light is on. When the night mode starts, this is set to `True`.""" ... @property - def location() -> Location: + def location(self) -> Location: """Position of the light (meters).""" ... @property - def light_group() -> LightGroup: + def light_group(self) -> LightGroup: """Group the light belongs to.""" @property - def light_state() -> LightState: + def light_state(self) -> LightState: """State of the light. Summarizes its attributes, group, and if it is on/off.""" # endregion @@ -2351,19 +2351,19 @@ class LightState(): # region Instance Variables @property - def intensity() -> float: + def intensity(self) -> float: """Intensity of a light.""" @property - def color() -> Color: + def color(self) -> Color: """Color of a light.""" @property - def group() -> LightGroup: + def group(self) -> LightGroup: """Group a light belongs to.""" @property - def active() -> bool: + def active(self) -> bool: """Switch of a light. It is `True` when the light is on.""" # endregion @@ -2384,13 +2384,13 @@ class Location(Vector3D): """Represents a spot in the world.""" # region Instance Variables @property - def x() -> float: + def x(self) -> float: """Distance from origin to spot on X axis (meter).""" @property - def y() -> float: + def y(self) -> float: """Distance from origin to spot on Y axis (meter).""" @property - def z() -> float: + def z(self) -> float: """Distance from origin to spot on Z axis. (meter)""" # endregion @@ -2440,7 +2440,7 @@ class Map(): # region Instance Variables @property - def name() -> str: + def name(self) -> str: """The name of the map. It corresponds to the .umap from Unreal Engine that is loaded from a CARLA server, which then references to the .xodr road description.""" # endregion @@ -2616,17 +2616,17 @@ class ObstacleDetectionEvent(SensorData): """ # region Instance Variables @property - def actor() -> Actor: + def actor(self) -> Actor: """The actor the sensor is attached to.""" ... @property - def other_actor() -> Actor: + def other_actor(self) -> Actor: """The actor or object considered to be an obstacle.""" ... @property - def distance() -> float: + def distance(self) -> float: """Distance between actor and other (meters).""" ... # endregion @@ -2640,37 +2640,37 @@ class OpendriveGenerationParameters(): """This class defines the parameters used when generating a world using an OpenDRIVE file.""" # region Instance Variables @property - def vertex_distance() -> float: + def vertex_distance(self) -> float: """Distance between vertices of the mesh generated. Default is 2.0.""" ... @property - def max_road_length() -> float: + def max_road_length(self) -> float: """Max road length for a single mesh portion. The mesh of the map is divided into portions, in order to avoid propagating issues. Default is 50.0.""" ... @property - def wall_height() -> float: + def wall_height(self) -> float: """Height of walls created on the boundaries of the road. These prevent vehicles from falling off the road. Default is 1.0.""" ... @property - def additional_width() -> float: + def additional_width(self) -> float: """Additional with applied junction lanes. Complex situations tend to occur at junctions, and a little increase can prevent vehicles from falling off the road. Default is 0.6.""" ... @property - def smooth_junctions() -> bool: + def smooth_junctions(self) -> bool: """If `True`, the mesh at junctions will be smoothed to prevent issues where roads blocked other roads. Default is `True`.""" ... @property - def enable_mesh_visibility() -> bool: + def enable_mesh_visibility(self) -> bool: """If `True`, the road mesh will be rendered. Setting this to False should reduce the rendering overhead. Default is True.""" ... @property - def enable_pedestrian_navigation() -> bool: + def enable_pedestrian_navigation(self) -> bool: """If `True`, Pedestrian navigation will be enabled using Recast tool. For very large maps it is recommended to disable this option. Default is `True`.""" ... # endregion @@ -2693,22 +2693,22 @@ class OpticalFlowImage(SensorData): """Class that defines an optical flow image of 2-Dimension float (32-bit) vectors representing the optical flow detected in the field of view. The components of the vector represents the displacement of an object in the image plane. Each component outputs values in the normalized range [-2,2] which scales to [-2 size, 2 size] with size being the total resolution in the corresponding component.""" # region Instance Variables @property - def fov() -> float: + def fov(self) -> float: """Horizontal field of view of the image. (degrees)""" ... @property - def height() -> int: + def height(self) -> int: """Image height in pixels.""" ... @property - def width() -> int: + def width(self) -> int: """Image width in pixels.""" ... @property - def raw_data() -> bytes: + def raw_data(self) -> bytes: """Flattened array of pixel data, use reshape to create an image array.""" # endregion @@ -2735,12 +2735,12 @@ class OpticalFlowPixel(): # region Instance Variables @property - def x() -> float: + def x(self) -> float: """Optical flow in the x component.""" ... @property - def y() -> float: + def y(self) -> float: """Optical flow in the y component.""" # endregion @@ -2790,48 +2790,48 @@ class Osm2OdrSettings(): # region Instance Variables @property - def use_offsets() -> bool: + def use_offsets(self) -> bool: """Enables the use of offset for the conversion. The offset will move the origin position of the map. Default value is False. """ ... @property - def offset_x() -> float: + def offset_x(self) -> float: """Offset in the X axis. Default value is 0.0 (meters).""" ... @property - def offset_y() -> float: + def offset_y(self) -> float: """Offset in the Y axis. Default value is 0.0 (meters).""" ... @property - def default_lane_width() -> float: + def default_lane_width(self) -> float: """Width of the lanes described in the resulting XODR map. Default value is 4.0 (meter).""" ... @property - def elevation_layer_height() -> float: + def elevation_layer_height(self) -> float: """Defines the height separating two different OpenStreetMap layers. Default value is 0.0.""" ... @property - def center_map() -> bool: + def center_map(self) -> bool: """When this option is enabled, the geometry of the map will be displaced so that the origin of coordinates matches the center of the bounding box of the entire road map.""" ... @property - def proj_string() -> str: + def proj_string(self) -> str: """Defines the `proj4` string that will be used to compute the projection from geocoordinates to cartesian coordinates. This string will be written in the resulting OpenDRIVE unless the options `use_offsets` or `center_map` are enabled as these options override some of the definitions in the string.""" ... @property - def generate_traffic_lights() -> bool: + def generate_traffic_lights(self) -> bool: """Indicates wether to generate traffic light data in the OpenDRIVE. Road types defined by `set_traffic_light_excluded_way_types(way_types)` will not generate traffic lights.""" ... @property - def all_junctions_with_traffic_lights() -> bool: + def all_junctions_with_traffic_lights(self) -> bool: """When disabled, the converter will generate traffic light data from the OpenStreetMaps data only. When enabled, all junctions will generate traffic lights.""" # endregion @@ -2862,22 +2862,22 @@ class RadarDetection(): # region Instance Variables @property - def altitude() -> float: + def altitude(self) -> float: """Altitude angle of the detection (radians).""" ... @property - def azimuth() -> float: + def azimuth(self) -> float: """Azimuth angle of the detection (radians).""" ... @property - def depth() -> float: + def depth(self) -> float: """Distance from the sensor to the detection position (meters).""" ... @property - def velocity() -> float: + def velocity(self) -> float: """The velocity of the detected object towards the sensor (m/s).""" ... # endregion @@ -2924,17 +2924,17 @@ class Rotation(): # region Instance Variables @property - def pitch() -> float: + def pitch(self) -> float: """Y-axis rotation angle (degrees).""" ... @property - def yaw() -> float: + def yaw(self) -> float: """Z-axis rotation angle (degrees).""" ... @property - def roll() -> float: + def roll(self) -> float: """X-axis rotation angle (degrees).""" ... # endregion @@ -2982,16 +2982,16 @@ class SemanticLidarDetection(): # region Instance Variables @property - def point() -> Location: + def point(self) -> Location: """[x,y,z] coordinates of the point (meters).""" @property - def cos_inc_angle() -> float: + def cos_inc_angle(self) -> float: """Cosine of the incident angle between the ray, and the normal of the hit object.""" @property - def object_idx() -> int: + def object_idx(self) -> int: """ID of the actor hit by the ray.""" @property - def object_tag() -> int: + def object_tag(self) -> int: """`Semantic tag` of the component hit by the ray.""" # endregion @@ -3008,13 +3008,13 @@ class SemanticLidarMeasurement(SensorData): # region Instance Variables @property - def channels() -> int: + def channels(self) -> int: """Number of lasers shot.""" @property - def horizontal_angle() -> float: + def horizontal_angle(self) -> float: """Horizontal angle the LIDAR is rotated at the time of the measurement (radians).""" @property - def raw_data() -> bytes: + def raw_data(self) -> bytes: """Received list of raw detection points. Each point consists of [x,y,z] coordinates plus the cosine of the incident angle, the index of the hit actor, and its semantic tag.""" # endregion @@ -3146,17 +3146,17 @@ class SensorData(): """ # region Instance Variables @property - def frame() -> int: + def frame(self) -> int: """Frame count when the data was generated.""" ... @property - def timestamp() -> float: + def timestamp(self) -> float: """Simulation-time(seconds) when the data was generated.""" ... @property - def transform() -> Transform: + def transform(self) -> Transform: """Sensor's transform when the data was generated.""" # endregion @@ -3168,10 +3168,10 @@ class TextureColor(): """ # region Instance Variables @property - def width() -> int: + def width(self) -> int: """X-coordinate size of the texture.""" @property - def height() -> int: + def height(self) -> int: """Y-coordinate size of the texture.""" # endregion @@ -3209,10 +3209,10 @@ class TextureFloatColor(): # region Instance Variables @property - def width() -> int: + def width(self) -> int: """X-coordinate size of the texture.""" @property - def height() -> int: + def height(self) -> int: """Y-coordinate size of the texture.""" # endregion @@ -3240,13 +3240,13 @@ class Timestamp(): # region Instance Variables @property - def frame() -> int: + def frame(self) -> int: """The number of frames elapsed since the simulator was launched.""" @property - def elapsed_seconds() -> float: + def elapsed_seconds(self) -> float: """Simulated seconds elapsed since the beginning of the current episode (seconds).""" @property - def delta_seconds() -> float: + def delta_seconds(self) -> float: """Simulated seconds elapsed since the previous frame (seconds).""" def platform_timestamp() -> float: """Time register of the frame at which this measurement was taken given by the OS in seconds (seconds).""" @@ -3270,7 +3270,7 @@ class TrafficLight(TrafficSign): # region Instance Variables @property - def state() -> TrafficLightState: + def state(self) -> TrafficLightState: """Current state of the traffic light.""" # endregion @@ -3656,7 +3656,7 @@ class TrafficSign(Actor): # region Instance Variables @property - def trigger_volume() -> BoundingBox: + def trigger_volume(self) -> BoundingBox: """A carla.BoundingBox situated near a traffic sign where the carla.Actor who is inside can know about it.""" # endregion @@ -3667,10 +3667,10 @@ class Transform(): # region Instance Variables @property - def location() -> Location: + def location(self) -> Location: """Describes a point in the coordinate system.""" @property - def rotation() -> Rotation: + def rotation(self) -> Rotation: """Describes a rotation for an object according to Unreal Engine's axis system (degrees (pitch, yaw, roll)).""" # endregion @@ -3726,10 +3726,10 @@ class Vector2D(): # region Instance Variables @property - def x() -> float: + def x(self) -> float: """X-axis value.""" @property - def y() -> float: + def y(self) -> float: """Y-axis value.""" # endregion @@ -3772,13 +3772,13 @@ class Vector3D(): # region Instance Variables @property - def x() -> float: + def x(self) -> float: """X-axis value.""" @property - def y() -> float: + def y(self) -> float: """Y-axis value.""" @property - def z() -> float: + def z(self) -> float: """Z-axis value.""" # endregion @@ -3841,7 +3841,7 @@ class Vehicle(Actor): # region Instance Variables @property - def bounding_box() -> BoundingBox: + def bounding_box(self) -> BoundingBox: """Bounding box containing the geometry of the vehicle. Its location and rotation are relative to the vehicle it is attached to.""" # endregion @@ -3988,22 +3988,22 @@ class VehicleAckermannControl(): # region Instance Variables @property - def steer() -> float: + def steer(self) -> float: """Desired steer (rad). Positive value is to the right. Default is 0.0.""" @property - def steer_speed() -> float: + def steer_speed(self) -> float: """Steering velocity (rad/s). Zero steering angle velocity means change the steering angle as quickly as possible. Default is 0.0.""" @property - def speed() -> float: + def speed(self) -> float: """Desired speed (m/s). Default is 0.0.""" @property - def acceleration() -> float: + def acceleration(self) -> float: """Desired acceleration (m/s2) Default is 0.0.""" @property - def jerk() -> float: + def jerk(self) -> float: """Desired jerk (m/s3). Default is 0.0.""" # endregion @@ -4022,26 +4022,26 @@ class VehicleControl(): """Manages the basic movement of a vehicle using typical driving controls.""" # region Instance Variables @property - def throttle() -> float: + def throttle(self) -> float: """A scalar value to control the vehicle throttle [0.0, 1.0]. Default is 0.0.""" @property - def steer() -> float: + def steer(self) -> float: """A scalar value to control the vehicle steering [-1.0, 1.0]. Default is 0.0.""" @property - def brake() -> float: + def brake(self) -> float: """A scalar value to control the vehicle brake [0.0, 1.0]. Default is 0.0.""" @property - def hand_brake() -> bool: + def hand_brake(self) -> bool: """Determines whether hand brake will be used. Default is `False`.""" @property - def reverse() -> bool: + def reverse(self) -> bool: """Determines whether the vehicle will move backwards. Default is `False`.""" @property - def manual_gear_shift() -> bool: + def manual_gear_shift(self) -> bool: """Determines whether the vehicle will be controlled by changing gears manually. Default is `False`. """ @property - def gear() -> int: + def gear(self) -> int: """States which gear is the vehicle running on.""" # endregion @@ -4121,70 +4121,70 @@ class VehiclePhysicsControl(): # region Instance Variables @property - def torque_curve() -> list[Vector2D]: + def torque_curve(self) -> list[Vector2D]: """Curve that indicates the torque measured in Nm for a specific RPM of the vehicle's engine.""" @property - def max_rpm() -> float: + def max_rpm(self) -> float: """The maximum RPM of the vehicle's engine.""" @property - def moi() -> float: + def moi(self) -> float: """The moment of inertia of the vehicle's engine. (kg*m^2)""" @property - def damping_rate_full_throttle() -> float: + def damping_rate_full_throttle(self) -> float: """Damping ratio when the throttle is maximum.""" @property - def damping_rate_zero_throttle_clutch_engaged() -> float: + def damping_rate_zero_throttle_clutch_engaged(self) -> float: """Damping ratio when the throttle is zero with clutch engaged.""" @property - def damping_rate_zero_throttle_clutch_disengaged() -> float: + def damping_rate_zero_throttle_clutch_disengaged(self) -> float: """Damping ratio when the throttle is zero with clutch disengaged.""" @property - def use_gear_autobox() -> bool: + def use_gear_autobox(self) -> bool: """If `True`, the vehicle will have an automatic transmission.""" @property - def gear_switch_time() -> float: + def gear_switch_time(self) -> float: """Switching time between gears. (seconds)""" @property - def clutch_strength() -> float: + def clutch_strength(self) -> float: """Clutch strength of the vehicle (kg*m^2/s).""" @property - def final_ratio() -> float: + def final_ratio(self) -> float: """Fixed ratio from transmission to wheels.""" @property - def forward_gears() -> list[GearPhysicsControl]: + def forward_gears(self) -> list[GearPhysicsControl]: """List of objects defining the vehicle's gears.""" @property - def mass() -> float: + def mass(self) -> float: """Mass of the vehicle (kilograms).""" @property - def drag_coefficient() -> float: + def drag_coefficient(self) -> float: """Drag coefficient of the vehicle's chassis.""" @property - def center_of_mass() -> Vector3D: + def center_of_mass(self) -> Vector3D: """Center of mass of the vehicle (meters).""" @property - def steering_curve() -> list[Vector2D]: + def steering_curve(self) -> list[Vector2D]: """Curve that indicates the maximum steering for a specific forward speed.""" @property - def use_sweep_wheel_collision() -> bool: + def use_sweep_wheel_collision(self) -> bool: """Enable the use of sweep for wheel collision. By default, it is disabled and it uses a simple raycast from the axis to the floor for each wheel. This option provides a better collision model in which the full volume of the wheel is checked against collisions.""" @property - def wheels() -> list[WheelPhysicsControl]: + def wheels(self) -> list[WheelPhysicsControl]: """List of wheel physics objects. This list should have 4 elements, where index 0 corresponds to the front left wheel, index 1 corresponds to the front right wheel, index 2 corresponds to the back left wheel and index 3 corresponds to the back right wheel. For 2 wheeled vehicles, set the same values for both front and back wheels.""" # endregion @@ -4363,7 +4363,7 @@ class WalkerBoneControlIn(): # region Instance Variables @property - def bone_transforms() -> list[tuple[str, Transform]]: + def bone_transforms(self) -> list[tuple[str, Transform]]: """ List with the data for each bone we want to set: + name: bone name @@ -4414,13 +4414,13 @@ class WalkerControl(): # region Instance Variables @property - def direction() -> Vector3D: + def direction(self) -> Vector3D: """Vector using global coordinates that will correspond to the direction of the walker.""" @property - def speed() -> float: + def speed(self) -> float: """A scalar value to control the walker's speed (m/s).""" @property - def jump() -> bool: + def jump(self) -> bool: """If `True`, the walker will perform a jump.""" # endregion @@ -4449,58 +4449,58 @@ class Waypoint(): """ # region Instance Variables @property - def id() -> int: + def id(self) -> int: """The identifier is generated using a hash combination of the road, section, lane and s values that correspond to said point in the OpenDRIVE geometry. The s precision is set to 2 centimeters, so 2 waypoints closer than 2 centimeters in the same road, section and lane, will have the same identificator.""" @property - def transform() -> Transform: + def transform(self) -> Transform: """Position and orientation of the waypoint according to the current lane information. This data is computed the first time it is accessed. It is not created right away in order to ease computing costs when lots of waypoints are created but their specific transform is not needed.""" @property - def road_id() -> int: + def road_id(self) -> int: """OpenDRIVE road's id.""" @property - def section_id() -> int: + def section_id(self) -> int: """OpenDRIVE section's id, based on the order that they are originally defined.""" @property - def is_junction() -> bool: + def is_junction(self) -> bool: """True if the current Waypoint is on a junction as defined by OpenDRIVE.""" @property - def junction_id() -> int: + def junction_id(self) -> int: """OpenDRIVE junction's id. For more information refer to OpenDRIVE documentation. http://www.opendrive.org/docs/OpenDRIVEFormatSpecRev1.4H.pdf#page=20 """ @property - def lane_id() -> int: + def lane_id(self) -> int: """OpenDRIVE lane's id, this value can be positive or negative which represents the direction of the current lane with respect to the road. For more information refer to OpenDRIVE documentation.""" @property - def s() -> float: + def s(self) -> float: """OpenDRIVE s value of the current position.""" @property - def lane_width() -> float: + def lane_width(self) -> float: """Horizontal size of the road at current `s`.""" @property - def lane_change() -> LaneChange: + def lane_change(self) -> LaneChange: """Lane change definition of the current Waypoint's location, based on the traffic rules defined in the OpenDRIVE file. It states if a lane change can be done and in which direction.""" @property - def lane_type() -> LaneType: + def lane_type(self) -> LaneType: """The lane type of the current Waypoint, based on OpenDRIVE 1.4 standard.""" @property - def right_lane_marking() -> LaneMarking: + def right_lane_marking(self) -> LaneMarking: """The right lane marking information based on the direction of the Waypoint.""" @property - def left_lane_marking() -> LaneMarking: + def left_lane_marking(self) -> LaneMarking: """The left lane marking information based on the direction of the Waypoint.""" # endregion @@ -4589,34 +4589,34 @@ class WeatherParameters(): """ # region Instance Variables @property - def cloudiness() -> float: + def cloudiness(self) -> float: """Values range from 0 to 100, being 0 a clear sky and 100 one completely covered with clouds.""" @property - def precipitation() -> float: + def precipitation(self) -> float: """Rain intensity values range from 0 to 100, being 0 none at all and 100 a heavy rain.""" @property - def precipitation_deposits() -> float: + def precipitation_deposits(self) -> float: """Determines the creation of puddles. Values range from 0 to 100, being 0 none at all and 100 a road completely capped with water. Puddles are created with static noise, meaning that they will always appear at the same locations.""" @property - def wind_intensity() -> float: + def wind_intensity(self) -> float: """Controls the strenght of the wind with values from 0, no wind at all, to 100, a strong wind. The wind does affect rain direction and leaves from trees, so this value is restricted to avoid animation issues.""" @property - def sun_azimuth_angle() -> float: + def sun_azimuth_angle(self) -> float: """The azimuth angle of the sun. Values range from 0 to 360. Zero is an origin point in a sphere determined by Unreal Engine (degrees).""" @property - def sun_altitude_angle() -> float: + def sun_altitude_angle(self) -> float: """Altitude angle of the sun. Values range from -90 to 90 corresponding to midnight and midday each (degrees).""" @property - def fog_density() -> float: + def fog_density(self) -> float: """Fog concentration or thickness. It only affects the RGB camera sensor. Values range from 0 to 100.""" @property - def fog_distance() -> float: + def fog_distance(self) -> float: """Fog start distance. Values range from 0 to infinite (meters).""" @property - def wetness() -> float: + def wetness(self) -> float: """Wetness intensity. It only affects the RGB camera sensor. Values range from 0 to 100.""" @property - def fog_falloff() -> float: + def fog_falloff(self) -> float: """Density of the fog (as in specific mass) from 0 to infinity. The bigger the value, the more dense and heavy it will be, and the fog will reach smaller heights. Corresponds to `Fog Height Falloff` in the UE docs. If the value is 0, the fog will be lighter than air, and will cover the whole scene. @@ -4625,16 +4625,16 @@ class WeatherParameters(): For values greater than 5, the air will be so dense that it will be compressed on ground level. """ @property - def scattering_intensity() -> float: + def scattering_intensity(self) -> float: """Controls how much the light will contribute to volumetric fog. When set to 0, there is no contribution.""" @property - def mie_scattering_scale() -> float: + def mie_scattering_scale(self) -> float: """Controls interaction of light with large particles like pollen or air pollution resulting in a hazy sky with halos around the light sources. When set to 0, there is no contribution.""" @property - def rayleigh_scattering_scale() -> float: + def rayleigh_scattering_scale(self) -> float: """Controls interaction of light with small particles like air molecules. Dependent on light wavelength, resulting in a blue sky in the day or red sky in the evening.""" @property - def dust_storm() -> float: + def dust_storm(self) -> float: """Determines the strength of the dust storm weather. Values range from 0 to 100.""" # endregion @@ -4686,34 +4686,34 @@ class WheelPhysicsControl(): # region Instance Variables @property - def tire_friction() -> float: + def tire_friction(self) -> float: """A scalar value that indicates the friction of the wheel.""" @property - def damping_rate() -> float: + def damping_rate(self) -> float: """Damping rate of the wheel.""" @property - def max_steer_angle() -> float: + def max_steer_angle(self) -> float: """Maximum angle that the wheel can steer (degrees).""" @property - def radius() -> float: + def radius(self) -> float: """Radius of the wheel (centimeters).""" @property - def max_brake_torque() -> float: + def max_brake_torque(self) -> float: """Maximum brake torque (N*m).""" @property - def max_handbrake_torque() -> float: + def max_handbrake_torque(self) -> float: """Maximum handbrake torque.""" @property - def position() -> Vector3D: + def position(self) -> Vector3D: """World position of the wheel. This is a read-only parameter.""" @property - def long_stiff_value() -> float: + def long_stiff_value(self) -> float: """Tire longitudinal stiffness per unit gravitational acceleration. Each vehicle has a custom value (kg/rad).""" @property - def lat_stiff_max_load() -> float: + def lat_stiff_max_load(self) -> float: """Maximum normalized tire load at which the tire can deliver no more lateral stiffness no matter how much extra load is applied to the tire. Each vehicle has a custom value.""" @property - def lat_stiff_value() -> float: + def lat_stiff_value(self) -> float: """Maximum stiffness per unit of lateral slip. Each vehicle has a custom value.""" # endregion @@ -4740,10 +4740,10 @@ class World(): # region Instance Variables @property - def id() -> int: + def id(self) -> int: """The ID of the episode associated with this world. Episodes are different sessions of a simulation. These change everytime a world is disabled or reloaded. Keeping track is useful to avoid possible issues.""" @property - def debug() -> DebugHelper: + def debug(self) -> DebugHelper: """Responsible for creating different shapes for debugging. Take a look at its class to learn more about it.""" # endregion @@ -5048,40 +5048,40 @@ class WorldSettings(): # region description @property - def synchronous_mode() -> bool: + def synchronous_mode(self) -> bool: """States the synchrony between client and server. When set to true, the server will wait for a client tick in order to move forward. It is `False` by default.""" @property - def no_rendering_mode() -> bool: + def no_rendering_mode(self) -> bool: """When enabled, the simulation will run no rendering at all. This is mainly used to avoid overhead during heavy traffic simulations. It is `False` by default.""" @property - def fixed_delta_seconds() -> float: + def fixed_delta_seconds(self) -> float: """Ensures that the time elapsed between two steps of the simulation is fixed. Set this to `0.0` to work with a variable time-step, as happens by default.""" @property - def substepping() -> bool: + def substepping(self) -> bool: """Enable the physics substepping. This option allows computing some physics substeps between two render frames. If synchronous mode is set, the number of substeps and its time interval are fixed and computed are so they fulfilled the requirements of `carla.WorldSettings.max_substep` and `carla.WorldSettings.max_substep_delta_time`. These last two parameters need to be compatible with c`arla.WorldSettings.fixed_delta_seconds`. Enabled by default.""" @property - def max_substep_delta_time() -> float: + def max_substep_delta_time(self) -> float: """Maximum delta time of the substeps. If the carla.`WorldSettingsmax_substep` is high enough, the substep delta time would be always below or equal to this value. By default, the value is set to 0.01.""" @property - def max_substeps() -> int: + def max_substeps(self) -> int: """The maximum number of physics substepping that are allowed. By default, the value is set to 10. """ @property - def max_culling_distance() -> float: + def max_culling_distance(self) -> float: """Configure the max draw distance for each mesh of the level.""" @property - def deterministic_ragdolls() -> bool: + def deterministic_ragdolls(self) -> bool: """Defines wether to use deterministic physics for pedestrian death animations or physical ragdoll simulation. When enabled, pedestrians have less realistic death animation but ensures determinism. When disabled, pedestrians are simulated as ragdolls with more realistic simulation and collision but no determinsm can be ensured.""" @property - def tile_stream_distance() -> bool: + def tile_stream_distance(self) -> bool: """Used for large maps only. Configures the maximum distance from the hero vehicle to stream tiled maps. Regions of the map within this range will be visible (and capable of simulating physics). Regions outside this region will not be loaded.""" @property - def actor_active_distance() -> float: + def actor_active_distance(self) -> float: """Used for large maps only. Configures the distance from the hero vehicle to convert actors to dormant. Actors within this range will be active, and actors outside will become dormant.""" ... @property - def spectator_as_ego() -> float: + def spectator_as_ego(self) -> float: """Used for large maps only. Defines the influence of the spectator on tile loading in Large Maps. By default, the spectator will provoke loading of neighboring tiles in the absence of an ego actor. This might be inconvenient for applications that immediately spawn an ego actor.""" # endregion @@ -5128,13 +5128,13 @@ class WorldSnapshot(): # region Instance Variables @property - def id() -> int: + def id(self) -> int: """A value unique for every snapshot to differentiate them.""" @property - def frame() -> int: + def frame(self) -> int: """Simulation frame in which the snapshot was taken.""" @property - def timestamp() -> Timestamp: + def timestamp(self) -> Timestamp: """Precise moment in time when snapshot was taken. This class works in seconds as given by the operative system (seconds).""" # endregion @@ -5175,10 +5175,10 @@ class command(): """ # region Instance Variables @property - def actor_id() -> int: + def actor_id(self) -> int: """Actor affected by the command.""" @property - def impulse() -> Vector3D: + def impulse(self) -> Vector3D: """Angular impulse applied to the actor (degrees*s).""" # endregion @@ -5196,10 +5196,10 @@ class command(): """Command adaptation of `add_force()` in `carla.Actor`. Applies a force to an actor.""" # region Instance Variables @property - def actor_id() -> int: + def actor_id(self) -> int: """Actor affected by the command.""" @property - def force() -> Vector3D: + def force(self) -> Vector3D: """Force applied to the actor over time (N).""" # endregion @@ -5217,10 +5217,10 @@ class command(): """Command adaptation of `add_impulse()` in `carla.Actor`. Applies an impulse to an actor.""" # region Instance Variables @property - def actor_id() -> int: + def actor_id(self) -> int: """Actor affected by the command.""" @property - def impulse() -> Vector3D: + def impulse(self) -> Vector3D: """Impulse applied to the actor (N*s).""" # endregion @@ -5240,10 +5240,10 @@ class command(): # region Instance Variables @property - def actor_id() -> int: + def actor_id(self) -> int: """Actor affected by the command.""" @property - def angular_velocity() -> Vector3D: + def angular_velocity(self) -> Vector3D: """The 3D angular velocity that will be applied to the actor (deg/s).""" # endregion @@ -5262,10 +5262,10 @@ class command(): """ # region Instance Variables @property - def actor_id() -> int: + def actor_id(self) -> int: """Actor affected by the command.""" @property - def velocity() -> Vector3D: + def velocity(self) -> Vector3D: """The 3D velocity applied to the actor (m/s).""" # endregion @@ -5286,11 +5286,11 @@ class command(): # region Instance Variables @property - def actor_id() -> int: + def actor_id(self) -> int: """Actor affected by the command.""" @property - def transform() -> Vector3D: + def transform(self) -> Vector3D: """Torque applied to the actor over time (degrees).""" # endregion @@ -5312,10 +5312,10 @@ class command(): # region Instance Variables @property - def actor_id() -> int: + def actor_id(self) -> int: """Actor affected by the command.""" @property - def transform() -> Transform: + def transform(self) -> Transform: """Transformation to be applied.""" # endregion @@ -5334,10 +5334,10 @@ class command(): """ # region Instance Variables @property - def actor_id() -> int: + def actor_id(self) -> int: """Actor affected by the command.""" @property - def control() -> AckermannControllerSettings: + def control(self) -> AckermannControllerSettings: """Vehicle ackermann control to be applied.""" # endregion @@ -5356,10 +5356,10 @@ class command(): # region Instance Variables @property - def actor_id() -> int: + def actor_id(self) -> int: """Actor affected by the command.""" @property - def control() -> VehicleControl: + def control(self) -> VehicleControl: """Vehicle control to be applied.""" # endregion @@ -5378,10 +5378,10 @@ class command(): # region Instance Variables @property - def actor_id() -> int: + def actor_id(self) -> int: """Actor affected by the command.""" @property - def control() -> VehiclePhysicsControl: + def control(self) -> VehiclePhysicsControl: """Physics control to be applied.""" # endregion @@ -5400,10 +5400,10 @@ class command(): # region Instance Variables @property - def actor_id() -> int: + def actor_id(self) -> int: """Walker actor affected by the command.""" @property - def control() -> VehiclePhysicsControl: + def control(self) -> VehiclePhysicsControl: """Walker control to be applied.""" # endregion @@ -5422,13 +5422,13 @@ class command(): # region Instance Variables @property - def actor_id() -> int: + def actor_id(self) -> int: """Walker actor affected by the command.""" @property - def transform() -> Transform: + def transform(self) -> Transform: """Transform to be applied.""" @property - def speed() -> float: + def speed(self) -> float: """Speed to be applied (m/s).""" # endregion @@ -5448,7 +5448,7 @@ class command(): # region Instance Variables @property - def actor_id() -> int: + def actor_id(self) -> int: """Actor affected by the command.""" # endregion @@ -5470,10 +5470,10 @@ class command(): # region Instance Variables @property - def actor_id() -> int: + def actor_id(self) -> int: """Actor to whom the command was applied to. States that the command was successful.""" @property - def error() -> str: + def error(self) -> str: """A string stating the command has failed.""" # endregion @@ -5487,13 +5487,13 @@ class command(): # region Instance Methods @property - def actor_id() -> int: + def actor_id(self) -> int: """Actor that is affected by the command.""" @property - def enabled() -> bool: + def enabled(self) -> bool: """If autopilot should be activated or not.""" @property - def port() -> int: + def port(self) -> int: """Port of the Traffic Manager where the vehicle is to be registered or unlisted.""" # endregion @@ -5512,10 +5512,10 @@ class command(): """Command adaptation of `set_enable_gravity()` in `carla.Actor`. Enables or disables gravity on an actor.""" # region Instance Variables @property - def actor_id() -> int: + def actor_id(self) -> int: """Actor that is affected by the command.""" @property - def enabled() -> bool: + def enabled(self) -> bool: """If gravity should be activated or not.""" # endregion @@ -5533,10 +5533,10 @@ class command(): """Command adaptation of `set_simulate_physics()` in `carla.Actor`. Determines whether an actor will be affected by physics or not.""" # region Instance Variables @property - def actor_id() -> int: + def actor_id(self) -> int: """Actor that is affected by the command.""" @property - def enabled() -> bool: + def enabled(self) -> bool: """If physics should be activated or not.""" # endregion @@ -5554,10 +5554,10 @@ class command(): """Command adaptation of `set_light_state()` in `carla.Vehicle`. Sets the light state of a vehicle.""" # region Instance Variables @property - def actor_id() -> int: + def actor_id(self) -> int: """Actor that is affected by the command.""" @property - def light_state() -> VehicleLightState: + def light_state(self) -> VehicleLightState: """Recaps the state of the lights of a vehicle, these can be used as a flags.""" # endregion @@ -5576,10 +5576,10 @@ class command(): """ # region Instance Variables @property - def actor_id() -> int: + def actor_id(self) -> int: """Actor that is affected by the command.""" @property - def enabled() -> bool: + def enabled(self) -> bool: """If debug should be activated or not.""" # endregion @@ -5598,10 +5598,10 @@ class command(): # region Instance Variables @property - def transform() -> Transform: + def transform(self) -> Transform: """Transform to be applied.""" @property - def parent_id() -> int: + def parent_id(self) -> int: """Identificator of the parent actor.""" # endregion From 77856f467c1f6f741423d698081e25d09b92a3f0 Mon Sep 17 00:00:00 2001 From: Daniel Date: Mon, 29 Jul 2024 17:01:20 +0200 Subject: [PATCH 90/99] Various fixes - wrong signatures - wrong names --- PythonAPI/carla/source/carla/libcarla.pyi | 68 ++++++++++++++--------- 1 file changed, 41 insertions(+), 27 deletions(-) diff --git a/PythonAPI/carla/source/carla/libcarla.pyi b/PythonAPI/carla/source/carla/libcarla.pyi index f9e916567..ae3d14385 100644 --- a/PythonAPI/carla/source/carla/libcarla.pyi +++ b/PythonAPI/carla/source/carla/libcarla.pyi @@ -1,10 +1,15 @@ from enum import Enum, Flag, IntFlag import sys from typing import Callable, Iterable, Iterator, Union, Optional, overload, ClassVar, Any, Literal -if sys.version_info < (3, 11): - from typing_extensions import Self -else: +if sys.version_info >= (3, 11): from typing import Self +else: + from typing_extensions import Self + +if sys.version_info >= (3, 9): + from typing import Annotated +else: + from typing_extensions import Annotated class __CarlaEnum(Enum): """ @@ -63,7 +68,7 @@ class AckermannControllerSettings(): speed_kd: float = 0.25, accel_kp: float = 0.01, accel_ki: float = 0.0, - accel_kd: float = 0.01) -> AckermannControllerSettings: + accel_kd: float = 0.01): """Manages the settings of the Ackermann PID controller. """ # endregion @@ -1148,7 +1153,7 @@ class DVSEvent(): def x(self) -> int: """X pixel coordinate.""" @property - def x(self) -> int: + def y(self) -> int: """Y pixel coordinate.""" @property def t(self) -> int: @@ -1305,7 +1310,7 @@ class DebugHelper(): """ ... - def draw_point(self, location: Location, size=0.1, color=Color(255, 0, 0), life_time=-1.0, persistent_lines=True) -> None: + def draw_point(self, location: Location, size=0.1, color: Color=Color(255, 0, 0), life_time=-1.0, persistent_lines=True) -> None: """ Draws a point location. @@ -1317,7 +1322,7 @@ class DebugHelper(): """ ... - def draw_hud_point(self, location: Location, size=0.1, color=(255, 0, 0), life_time=-1.0, persistent_lines=True) -> None: + def draw_hud_point(self, location: Location, size=0.1, color: Color=Color(255, 0, 0), life_time=-1.0, persistent_lines=True) -> None: """ Draws a point on the HUD at `location`. The point can only be seen server-side. @@ -1329,7 +1334,7 @@ class DebugHelper(): """ ... - def draw_string(self, location: Location, text: str, draw_shadow=False, color: Color = (255, 0, 0), life_time=-1.0, persistent_lines=True) -> None: + def draw_string(self, location: Location, text: str, draw_shadow=False, color: Color = Color(255, 0, 0), life_time=-1.0, persistent_lines=True) -> None: """Draws a string in a given location of the simulation which can only be seen server-side. Args: @@ -1484,13 +1489,17 @@ class GearPhysicsControl(): """ # region Instance Variables - def ratio() -> float: + @property + def ratio(self) -> float: """The transmission ratio of the gear.""" ... - def down_ratio() -> float: + @property + def down_ratio(self) -> float: """Quotient between current RPM and MaxRPM where the autonomous gear box should shift down.""" - def up_ratio() -> float: + + @property + def up_ratio(self) -> float: """Quotient between current RPM and MaxRPM where the autonomous gear box should shift up.""" # endregion @@ -1898,7 +1907,8 @@ class LaneInvasionEvent(SensorData): """ # region Instance Variables - def actor() -> Actor: + @property + def actor(self) -> Actor: """Gets the actor the sensor is attached to, the one that invaded another lane.""" @property @@ -2894,7 +2904,8 @@ class RadarMeasurement(SensorData): """ # region Instance Variables - def raw_data() -> bytes: + @property + def raw_data(self) -> bytes: """The complete information of the `carla.RadarDetection` the radar has registered. """ # endregion @@ -3248,7 +3259,9 @@ class Timestamp(): @property def delta_seconds(self) -> float: """Simulated seconds elapsed since the previous frame (seconds).""" - def platform_timestamp() -> float: + + @property + def platform_timestamp(self) -> float: """Time register of the frame at which this measurement was taken given by the OS in seconds (seconds).""" # endregion @@ -3559,17 +3572,17 @@ class TrafficManager(): # endregion # region Setters - def set_boundaries_respawn_dormant_vehicles(self, lower_bound=25.0, upper_bound: float = WorldSettings.actor_active_distance): + def set_boundaries_respawn_dormant_vehicles(self, lower_bound:Annotated[float, ">=25.0"], upper_bound: Annotated[float, "<= WorldSettings.actor_active_distance"]) -> None: """Sets the upper and lower boundaries for dormant actors to be respawned near the hero vehicle. + Warning: The `upper_bound` cannot be higher than the `actor_active_distance`. The `lower_bound` cannot be less than `25`. Args: - lower_bound (float, optional): The minimum distance in meters from the hero vehicle that a dormant actor will be respawned. Defaults to 25.0. - upper_bound (float, optional): The maximum distance in meters from the hero vehicle that a dormant actor will be respawned. Defaults to WorldSettings.actor_active_distance. + lower_bound (float, optional): The minimum distance in meters from the hero vehicle that a dormant actor will be respawned. + upper_bound (float, optional): The maximum distance in meters from the hero vehicle that a dormant actor will be respawned. """ - def set_desired_speed(self, actor: Actor, speed: float): + def set_desired_speed(self, actor: Actor, speed: float) -> None: """Sets the speed of a vehicle to the specified value. Args: @@ -3577,7 +3590,7 @@ class TrafficManager(): speed (float): Desired speed at which the vehicle will move. """ - def set_global_distance_to_leading_vehicle(self, distance: float): + def set_global_distance_to_leading_vehicle(self, distance: float) -> None: """Sets the minimum distance in meters that vehicles have to keep with the rest. The distance is in meters and will affect the minimum moving distance. It is computed from center to center of the vehicle objects. Args: @@ -4203,7 +4216,7 @@ class VehiclePhysicsControl(): steering_curve=[[0.0, 1.0], [10.0, 0.5]], wheels=list(), use_sweep_wheel_collision=False, - mass=1000.0) -> VehiclePhysicsControl: + mass=1000.0): """VehiclePhysicsControl constructor. Args: @@ -4390,7 +4403,8 @@ class WalkerBoneControlOut(): """This class is used to return all bone positions of a pedestrian. For each bone we get its name and its transform in three different spaces (world, actor and relative).""" # region Instance Variables - def bone_transforms() -> list[tuple[str, Transform, Transform, Transform]]: + @property + def bone_transforms(self) -> list[tuple[str, Transform, Transform, Transform]]: """ List of one entry per bone with this information: @@ -4725,7 +4739,7 @@ class WheelPhysicsControl(): radius=30.0, max_brake_torque=1500.0, max_handbrake_torque=3000.0, - position: Vector3D = (0.0, 0.0, 0.0)) -> WheelPhysicsControl: ... + position: Vector3D = Vector3D(0.0, 0.0, 0.0)): ... # endregion # region Dunder Methods @@ -4840,7 +4854,7 @@ class World(): """Resets the cycle of all traffic lights in the map to the initial state. """ - def spawn_actor(self, blueprint: ActorBlueprint, transform: Transform, attach_to: Actor = None, attachment=AttachmentType.Rigid) -> Actor: + def spawn_actor(self, blueprint: ActorBlueprint, transform: Transform, attach_to: Optional[Actor] = None, attachment=AttachmentType.Rigid) -> Actor: """The method will create, return and spawn an actor into the world. The actor will need an available blueprint to be created and a transform (location and rotation). It can also be attached to a parent with a certain attachment type. Args: @@ -4865,7 +4879,7 @@ class World(): `int`\n """ - def try_spawn_actor(self, blueprint: ActorBlueprint, transform: Transform, attach_to: Actor = None, attachment=AttachmentType.Rigid) -> Actor: + def try_spawn_actor(self, blueprint: ActorBlueprint, transform: Transform, attach_to: Optional[Actor] = None, attachment=AttachmentType.Rigid) -> Actor: """Same as `spawn_actor()` but returns `None` on failure instead of throwing an exception. Args: @@ -4952,7 +4966,7 @@ class World(): def get_random_location_from_navigation(self) -> Location: """This can only be used with walkers. It retrieves a random location to be used as a destination using the `go_to_location()` method in `carla.WalkerAIController`. This location will be part of a sidewalk. Roads, crosswalks and grass zones are excluded. The method does not take into consideration locations of existing actors so if a collision happens when trying to spawn an actor, it will return an error. Take a look at `generate_traffic.py` for an example.""" - def get_settings() -> WorldSettings: + def get_settings(self) -> WorldSettings: """Returns an object containing some data about the simulation such as synchrony between client and server or rendering mode.""" def get_snapshot(self) -> WorldSnapshot: @@ -5094,7 +5108,7 @@ class WorldSettings(): deterministic_ragdolls=False, tile_stream_distance=3000, actor_active_distance=2000, - spectator_as_ego=True) -> WorldSettings: + spectator_as_ego=True): """Creates an object containing desired settings that could later be applied through `carla.World` and its method `apply_settings()`. Args: @@ -5417,7 +5431,7 @@ class command(): """ # endregion - class ApplyWalkerControl(): + class ApplyWalkerState(): """Apply a state to the walker actor. Specially useful to initialize an actor them with a specific location, orientation and speed.""" # region Instance Variables From 798c9e144c7030777498b253a2db75b39fff96de Mon Sep 17 00:00:00 2001 From: Daniel Date: Mon, 29 Jul 2024 17:48:08 +0200 Subject: [PATCH 91/99] Added setters for VehicleControl --- PythonAPI/carla/source/carla/libcarla.pyi | 24 +++++++++++++++++++++-- 1 file changed, 22 insertions(+), 2 deletions(-) diff --git a/PythonAPI/carla/source/carla/libcarla.pyi b/PythonAPI/carla/source/carla/libcarla.pyi index ae3d14385..30e9fc5ef 100644 --- a/PythonAPI/carla/source/carla/libcarla.pyi +++ b/PythonAPI/carla/source/carla/libcarla.pyi @@ -4034,28 +4034,48 @@ class VehicleAckermannControl(): class VehicleControl(): """Manages the basic movement of a vehicle using typical driving controls.""" # region Instance Variables + @property def throttle(self) -> float: """A scalar value to control the vehicle throttle [0.0, 1.0]. Default is 0.0.""" + @throttle.setter + def throttle(self, value: float):... + @property def steer(self) -> float: """A scalar value to control the vehicle steering [-1.0, 1.0]. Default is 0.0.""" + @steer.setter + def steer(self, value: float): ... + @property def brake(self) -> float: """A scalar value to control the vehicle brake [0.0, 1.0]. Default is 0.0.""" + @brake.setter + def brake(self, value: float): ... + @property def hand_brake(self) -> bool: """Determines whether hand brake will be used. Default is `False`.""" + @hand_brake.setter + def hand_brake(self, value: bool): ... + @property def reverse(self) -> bool: """Determines whether the vehicle will move backwards. Default is `False`.""" + @reverse.setter + def reverse(self, value: bool): ... + @property def manual_gear_shift(self) -> bool: - """Determines whether the vehicle will be controlled by changing gears manually. Default is `False`. - """ + """Determines whether the vehicle will be controlled by changing gears manually. Default is `False`.""" + @manual_gear_shift.setter + def manual_gear_shift(self, value: bool): ... + @property def gear(self) -> int: """States which gear is the vehicle running on.""" + @gear.setter + def gear(self, value: int): ... # endregion # region Methods From 26dc3867243ecbec3c6d2415d2b86628bc93ae5e Mon Sep 17 00:00:00 2001 From: Daniel Date: Mon, 29 Jul 2024 18:01:28 +0200 Subject: [PATCH 92/99] Improved get_waypoints and Literal type hints --- PythonAPI/carla/source/carla/libcarla.pyi | 16 +++++++++++----- 1 file changed, 11 insertions(+), 5 deletions(-) diff --git a/PythonAPI/carla/source/carla/libcarla.pyi b/PythonAPI/carla/source/carla/libcarla.pyi index 30e9fc5ef..67baa8050 100644 --- a/PythonAPI/carla/source/carla/libcarla.pyi +++ b/PythonAPI/carla/source/carla/libcarla.pyi @@ -1,6 +1,7 @@ from enum import Enum, Flag, IntFlag import sys -from typing import Callable, Iterable, Iterator, Union, Optional, overload, ClassVar, Any, Literal +from typing import Callable, Iterable, Iterator, Union, Optional, overload, ClassVar, Any + if sys.version_info >= (3, 11): from typing import Self else: @@ -10,6 +11,11 @@ if sys.version_info >= (3, 9): from typing import Annotated else: from typing_extensions import Annotated + +if sys.version_info >= (3, 8): + from typing import Literal +else: + from typing_extensions import Literal class __CarlaEnum(Enum): """ @@ -2556,14 +2562,14 @@ class Map(): ... @overload - def get_waypoint(self, location: Location, project_to_road: Literal[True]=True, lane_type=LaneType.Driving) -> Waypoint: + def get_waypoint(self, location: Location, project_to_road: Literal[False], lane_type:LaneType=LaneType.Driving) -> Waypoint | None: ... @overload - def get_waypoint(self, location: Location, project_to_road: Literal[False], lane_type=LaneType.Driving) -> Waypoint | None: + def get_waypoint(self, location: Location, project_to_road: Literal[True]=True, lane_type: Literal[LaneType.Driving]=LaneType.Driving) -> Waypoint: ... - - def get_waypoint(self, location: Location, project_to_road=True, lane_type=LaneType.Driving): + + def get_waypoint(self, location: Location, project_to_road:bool=True, lane_type: LaneType=LaneType.Driving) -> Waypoint | None: """Returns a waypoint that can be located in an exact location or translated to the center of the nearest lane. Said lane type can be defined using flags such as `LaneType.Driving & LaneType.Shoulder`. The method will return `None` if the waypoint is not found, which may happen only when trying to retrieve a waypoint for an exact location. That eases checking if a point is inside a certain road, as otherwise, it will return the corresponding waypoint. From 58e0374f4ff3e5dc5e02fa1a73060601ce8c8249 Mon Sep 17 00:00:00 2001 From: Daniel Date: Thu, 1 Aug 2024 16:21:29 +0200 Subject: [PATCH 93/99] Corrected [try_]spawn_actor keyword name --- PythonAPI/carla/source/carla/libcarla.pyi | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/PythonAPI/carla/source/carla/libcarla.pyi b/PythonAPI/carla/source/carla/libcarla.pyi index 67baa8050..27fdcdbe1 100644 --- a/PythonAPI/carla/source/carla/libcarla.pyi +++ b/PythonAPI/carla/source/carla/libcarla.pyi @@ -4880,7 +4880,7 @@ class World(): """Resets the cycle of all traffic lights in the map to the initial state. """ - def spawn_actor(self, blueprint: ActorBlueprint, transform: Transform, attach_to: Optional[Actor] = None, attachment=AttachmentType.Rigid) -> Actor: + def spawn_actor(self, blueprint: ActorBlueprint, transform: Transform, attach_to: Optional[Actor] = None, attachment_type=AttachmentType.Rigid) -> Actor: """The method will create, return and spawn an actor into the world. The actor will need an available blueprint to be created and a transform (location and rotation). It can also be attached to a parent with a certain attachment type. Args: @@ -4905,7 +4905,7 @@ class World(): `int`\n """ - def try_spawn_actor(self, blueprint: ActorBlueprint, transform: Transform, attach_to: Optional[Actor] = None, attachment=AttachmentType.Rigid) -> Actor: + def try_spawn_actor(self, blueprint: ActorBlueprint, transform: Transform, attach_to: Optional[Actor] = None, attachment_type=AttachmentType.Rigid) -> Actor: """Same as `spawn_actor()` but returns `None` on failure instead of throwing an exception. Args: From aec0b261af06104894c10a119909be0d2ee39c1a Mon Sep 17 00:00:00 2001 From: Daniel Date: Thu, 1 Aug 2024 16:57:18 +0200 Subject: [PATCH 94/99] Added Transform.inverse_transform and corrected signature parameter is called in_point not in_vector --- PythonAPI/carla/source/carla/libcarla.pyi | 32 +++++++++++++++++++---- 1 file changed, 27 insertions(+), 5 deletions(-) diff --git a/PythonAPI/carla/source/carla/libcarla.pyi b/PythonAPI/carla/source/carla/libcarla.pyi index 27fdcdbe1..33ef254f1 100644 --- a/PythonAPI/carla/source/carla/libcarla.pyi +++ b/PythonAPI/carla/source/carla/libcarla.pyi @@ -3697,17 +3697,39 @@ class Transform(): def __init__(self, location: Location = Location(0,0,0), rotation: Rotation = Rotation(0,0,0)): ... def transform(self, in_point: Vector3D) -> Vector3D: - """Translates a 3D point from local to global coordinates using the current transformation as frame of reference. + """ + Translates a 3D point from local to global coordinates using the current + transformation as frame of reference. Args: - in_point (Location): Translates a 3D point from local to global coordinates using the current transformation as frame of reference. + in_point (Location): Location in the space to which the transformation will be applied. + + Note: + This operation transforms `in_point` in place. + """ + + def inverse_transform(self, in_point: Vector3D) -> Vector3D: + """ + Applies the inverse of `transform` by translating a 3D point from global to local + coordinates using the current transformation as frame of reference. + + Args: + in_point (Vector3D): Vector to which the transformation will be applied. + + Note: + This operation transforms `in_point` in place. """ - def transform_vector(self, in_vector: Vector3D) -> Vector3D: - """Rotates a vector using the current transformation as frame of reference, without applying translation. Use this to transform, for example, a velocity. + def transform_vector(self, in_point: Vector3D) -> Vector3D: + """ + Rotates a vector using the current transformation as frame of reference, + without applying translation. Use this to transform, for example, a velocity. Args: - in_vector (Vector3D): Vector to which the transformation will be applied. + in_point (Vector3D): Vector to which the transformation will be applied. + + Note: + This operation transforms `in_point` in place. """ # endregion From 2b465bcd66c4e4cfda0b99923505777bd1dae917 Mon Sep 17 00:00:00 2001 From: Daniel Date: Thu, 8 Aug 2024 14:57:30 +0200 Subject: [PATCH 95/99] Improved Callable and callbacks signature --- PythonAPI/carla/source/carla/libcarla.pyi | 18 ++++++++++++------ 1 file changed, 12 insertions(+), 6 deletions(-) diff --git a/PythonAPI/carla/source/carla/libcarla.pyi b/PythonAPI/carla/source/carla/libcarla.pyi index 33ef254f1..a3006e8e7 100644 --- a/PythonAPI/carla/source/carla/libcarla.pyi +++ b/PythonAPI/carla/source/carla/libcarla.pyi @@ -1,6 +1,6 @@ from enum import Enum, Flag, IntFlag import sys -from typing import Callable, Iterable, Iterator, Union, Optional, overload, ClassVar, Any +from typing import Callable, Iterable, Iterator, Union, Optional, overload, ClassVar, Any, TypeVar if sys.version_info >= (3, 11): from typing import Self @@ -17,6 +17,12 @@ if sys.version_info >= (3, 8): else: from typing_extensions import Literal + +# Note: __protected_variables are not part of the carla module, they are helpers to complete the stubs. + +__SensorData = TypeVar("__SensorData", bound=SensorData) # type: ignore +"""Generic that allows subclassing.""" + class __CarlaEnum(Enum): """ CARLA's Enums have a `values` and `names` attribute that are not part of the python `enum.Enum` @@ -3108,7 +3114,7 @@ class Sensor(Actor): `gbuffer_id (GBufferTextureID)`: The ID of the target Unreal Engine GBuffer texture.\n """ - def listen(self, callback: Callable[[SensorData], Any]) -> None: + def listen(self, callback: Callable[[__SensorData], Any]) -> None: """ The function the sensor will be calling to every time a new measurement is received. This function needs for an argument containing an object type `carla.SensorData` to work with. @@ -3117,14 +3123,14 @@ class Sensor(Actor): `callback (Callable[[SensorData], Any])`: The called function with one argument containing the sensor data.\n """ - def listen_to_gbuffer(self, gbuffer_id: GBufferTextureID, callback: Callable[[SensorData], Any]) -> None: + def listen_to_gbuffer(self, gbuffer_id: GBufferTextureID, callback: Callable[[__SensorData], Any]) -> None: """ The function the sensor will be calling to every time the desired GBuffer texture is received. This function needs for an argument containing an object type `carla.SensorData` to work with. Args: `gbuffer_id (GBufferTextureID)`: The ID of the target Unreal Engine GBuffer texture.\n - `callback (Callable)`: The called function with one argument containing the received GBuffer texture.\n + `callback (Callable[[__SensorData], Any])`: The called function with one argument containing the received GBuffer texture.\n """ def stop(self): @@ -4872,11 +4878,11 @@ class World(): map_layers (MapLayer): Mask of level layers to be loaded. """ - def on_tick(self, callback: Callable) -> int: + def on_tick(self, callback: Callable[[WorldSnapshot], Any]) -> int: """This method is used in `asynchronous mode`. It starts callbacks from the client for the function defined as `callback`, and returns the ID of the callback. The function will be called everytime the server ticks. It requires a `carla.WorldSnapshot` as argument, which can be retrieved from `wait_for_tick()`. Use `remove_on_tick()` to stop the callbacks. Args: - callback (Callable): Function with a `snapshot` as compulsory parameter that will be called when the client receives a tick. + callback (Callable[[WorldSnapshot], Any]): Function with a `snapshot` as compulsory parameter that will be called when the client receives a tick. """ def project_point(self, location: Location, direction: Vector3D, search_distance: float) -> LabelledPoint: From 7633334063cc7390cd152313d8746d7d31479dc7 Mon Sep 17 00:00:00 2001 From: Daniel Date: Thu, 15 Aug 2024 22:14:15 +0200 Subject: [PATCH 96/99] Corrections and additions more setters missing, wrong types corrected spelling --- PythonAPI/carla/source/carla/libcarla.pyi | 132 ++++++++++++++++------ 1 file changed, 96 insertions(+), 36 deletions(-) diff --git a/PythonAPI/carla/source/carla/libcarla.pyi b/PythonAPI/carla/source/carla/libcarla.pyi index a3006e8e7..5e864d2ac 100644 --- a/PythonAPI/carla/source/carla/libcarla.pyi +++ b/PythonAPI/carla/source/carla/libcarla.pyi @@ -1,6 +1,7 @@ from enum import Enum, Flag, IntFlag import sys -from typing import Callable, Iterable, Iterator, Union, Optional, overload, ClassVar, Any, TypeVar +from typing import (Callable, Iterable, Iterator, Union, Optional, overload, ClassVar, Any, TypeVar, + type_check_only) if sys.version_info >= (3, 11): from typing import Self @@ -20,9 +21,10 @@ else: # Note: __protected_variables are not part of the carla module, they are helpers to complete the stubs. -__SensorData = TypeVar("__SensorData", bound=SensorData) # type: ignore +__SensorData = TypeVar("__SensorData", bound=SensorData) """Generic that allows subclassing.""" +@type_check_only class __CarlaEnum(Enum): """ CARLA's Enums have a `values` and `names` attribute that are not part of the python `enum.Enum` @@ -37,7 +39,6 @@ class __CarlaEnum(Enum): cls.names : dict[str, cls] - class AckermannControllerSettings(): """Manages the settings of the Ackermann PID controller.""" @@ -137,7 +138,7 @@ class Actor(): ... @property - def parent(self) -> Union["Actor", None]: + def parent(self) -> Actor | None: """Actors may be attached to a parent actor that they will follow around. This is said actor.""" ... @@ -1897,7 +1898,7 @@ class LandmarkType(Enum): # endregion -class LaneChange(int, __CarlaEnum): +class LaneChange(IntFlag, __CarlaEnum): """Class that defines the permission to turn either left, right, both or none (meaning only going straight is allowed). This information is stored for every `carla.Waypoint` according to the OpenDRIVE file. The snippet in `carla.Map.get_waypoint` shows how a waypoint can be used to learn which turns are permitted.""" # region Instance Variables @@ -1992,7 +1993,11 @@ class LaneMarkingType(int, __CarlaEnum): class LaneType(IntFlag, __CarlaEnum): - """Class that defines the possible lane types accepted by OpenDRIVE 1.4. This standards define the road information. The snippet in `carla.Map.get_waypoint` makes use of a waypoint to get the current and adjacent lane types.""" + """ + Class that defines the possible lane types accepted by OpenDRIVE 1.4. + This standards define the road information. The snippet in `carla.Map.get_waypoint` + makes use of a waypoint to get the current and adjacent lane types. + """ # region Instance Variables Any = -2 @@ -2021,7 +2026,6 @@ class LaneType(IntFlag, __CarlaEnum): # endregion - class LidarDetection(): """Data contained inside a `carla.LidarMeasurement`. Each of these represents one of the points in the cloud with its location and its associated intensity.""" # region Instance Variables @@ -2417,7 +2421,13 @@ class Location(Vector3D): # endregion # region Methods - def __init__(self, x=0.0, y=0.0, z=0.0): + @overload + def __init__(self, rhs: Vector3D): ... + + @overload + def __init__(self, x: float=0.0, y: float=0.0, z: float=0.0): ... + + def __init__(self, x: float=0.0, y: float=0.0, z: float=0.0): """Represents a spot in the world. Args: @@ -2568,14 +2578,14 @@ class Map(): ... @overload - def get_waypoint(self, location: Location, project_to_road: Literal[False], lane_type:LaneType=LaneType.Driving) -> Waypoint | None: + def get_waypoint(self, location: Location, project_to_road: Literal[True]=True, lane_type: Literal[LaneType.Driving, LaneType.Any]=LaneType.Driving) -> Waypoint: ... @overload - def get_waypoint(self, location: Location, project_to_road: Literal[True]=True, lane_type: Literal[LaneType.Driving]=LaneType.Driving) -> Waypoint: + def get_waypoint(self, location: Location, project_to_road :bool | None=True, lane_type: LaneType=LaneType.Driving) -> Waypoint | None: ... - def get_waypoint(self, location: Location, project_to_road:bool=True, lane_type: LaneType=LaneType.Driving) -> Waypoint | None: + def get_waypoint(self, location: Location, project_to_road: bool | None=True, lane_type: LaneType=LaneType.Driving) -> Waypoint | None: """Returns a waypoint that can be located in an exact location or translated to the center of the nearest lane. Said lane type can be defined using flags such as `LaneType.Driving & LaneType.Shoulder`. The method will return `None` if the waypoint is not found, which may happen only when trying to retrieve a waypoint for an exact location. That eases checking if a point is inside a certain road, as otherwise, it will return the corresponding waypoint. @@ -2598,6 +2608,7 @@ class Map(): ... # endregion + class MapLayer(Flag, __CarlaEnum): """Class that represents each manageable layer of the map. Can be used as flags. @@ -2697,8 +2708,6 @@ class OpendriveGenerationParameters(): ... # endregion - # region Methods - # region Methods def __init__(self, vertex_distance: float =2.0, max_road_length:float = 50.0, @@ -3130,7 +3139,7 @@ class Sensor(Actor): Args: `gbuffer_id (GBufferTextureID)`: The ID of the target Unreal Engine GBuffer texture.\n - `callback (Callable[[__SensorData], Any])`: The called function with one argument containing the received GBuffer texture.\n + `callback (Callable[[SensorData], Any])`: The called function with one argument containing the received GBuffer texture.\n """ def stop(self): @@ -3584,7 +3593,7 @@ class TrafficManager(): # endregion # region Setters - def set_boundaries_respawn_dormant_vehicles(self, lower_bound:Annotated[float, ">=25.0"], upper_bound: Annotated[float, "<= WorldSettings.actor_active_distance"]) -> None: + def set_boundaries_respawn_dormant_vehicles(self, lower_bound: Annotated[float, ">=25.0"], upper_bound: Annotated[float, "<= WorldSettings.actor_active_distance"]) -> None: """Sets the upper and lower boundaries for dormant actors to be respawned near the hero vehicle. + Warning: The `upper_bound` cannot be higher than the `actor_active_distance`. The `lower_bound` cannot be less than `25`. @@ -3694,9 +3703,16 @@ class Transform(): @property def location(self) -> Location: """Describes a point in the coordinate system.""" + @location.setter + def location(self, value: Location | Vector3D): + ... + @property def rotation(self) -> Rotation: """Describes a rotation for an object according to Unreal Engine's axis system (degrees (pitch, yaw, roll)).""" + @rotation.setter + def rotation(self, value: Rotation | Vector3D): + ... # endregion # region Methods @@ -3875,7 +3891,7 @@ class Vector3D(): def __add__(self, other: Vector3D) -> Vector3D: ... def __eq__(self, other: Vector3D) -> bool: ... - def __mul__(self, other: Vector3D): ... + def __mul__(self, other: Vector3D | float) -> Vector3D: ... def __ne__(self, other: Vector3D) -> bool: ... def __str__(self) -> str: ... def __sub__(self, other: Vector3D): ... @@ -3905,13 +3921,13 @@ class Vehicle(Actor): + Warning: This method does call the simulator.""" - def apply_control(self, control: VehicleControl): + def apply_control(self, control: VehicleControl) -> None: """Applies a control object on the next tick, containing driving parameters such as throttle, steering or gear shifting.""" def apply_physics_control(self, physics_control: VehiclePhysicsControl): """Applies a physics control object in the next tick containing the parameters that define the vehicle as a corporeal body. E.g.: moment of inertia, mass, drag coefficient and many more.""" - def close_door(self, door_idx: VehicleDoor): + def close_door(self, door_idx: VehicleDoor) -> None: """Close the door `door_idx` if the vehicle has it. Use `carla.VehicleDoor.All` to close all available doors.""" def enable_carsim(self, simfile_path: str): @@ -4004,7 +4020,7 @@ class Vehicle(Actor): # endregion # region Setters - def set_autopilot(self, enabled=True, port=8000): + def set_autopilot(self, enabled=True, port=8000) -> None: """Registers or deletes the vehicle from a Traffic Manager's list. When `True`, the Traffic Manager passed as parameter will move the vehicle around. The autopilot takes place client-side. Args: @@ -4012,7 +4028,7 @@ class Vehicle(Actor): `port (int, optional)`: The port of the TM-Server where the vehicle is to be registered or unlisted. Defaults to 8000.\n """ - def set_light_state(self, light_state: VehicleLightState): + def set_light_state(self, light_state: VehicleLightState) -> None: """Sets the light state of a vehicle using a flag that represents the lights that are on and off. + Getter: `carla.Vehicle.get_light_state` @@ -4156,7 +4172,7 @@ class VehicleFailureState(int, __CarlaEnum): TirePuncture = 3 -class VehicleLightState(Flag, __CarlaEnum): +class VehicleLightState(IntFlag, __CarlaEnum): """Class that recaps the state of the lights of a vehicle, these can be used as a flags. E.g: `VehicleLightState.HighBeam & VehicleLightState.Brake` will return `True` when both are active. @@ -4635,12 +4651,19 @@ class Waypoint(): `stop_at_junction (bool, optional)`: Enables or disables the landmark search through junctions. Defaults to False.\n """ - def get_left_lane(self) -> Waypoint: - """Generates a Waypoint at the center of the left lane based on the direction of the current Waypoint, taking into account if the lane change is allowed in this location. Will return `None` if the lane does not exist. + def get_left_lane(self) -> Waypoint | None: + """ + Generates a Waypoint at the center of the left lane based on the direction of the current + Waypoint, taking into account if the lane change is allowed in this location. + Will return `None` if the lane does not exist. """ - def get_right_lane(self) -> Waypoint: - """Generates a waypoint at the center of the right lane based on the direction of the current waypoint, taking into account if the lane change is allowed in this location. Will return None if the lane does not exist.""" + def get_right_lane(self) -> Waypoint | None: + """ + Generates a waypoint at the center of the right lane based on the direction of the current + waypoint, taking into account if the lane change is allowed in this location. + Will return `None` if the lane does not exist. + """ # endregion # region Dunder Methods @@ -4667,7 +4690,7 @@ class WeatherParameters(): """Determines the creation of puddles. Values range from 0 to 100, being 0 none at all and 100 a road completely capped with water. Puddles are created with static noise, meaning that they will always appear at the same locations.""" @property def wind_intensity(self) -> float: - """Controls the strenght of the wind with values from 0, no wind at all, to 100, a strong wind. The wind does affect rain direction and leaves from trees, so this value is restricted to avoid animation issues.""" + """Controls the strength of the wind with values from 0, no wind at all, to 100, a strong wind. The wind does affect rain direction and leaves from trees, so this value is restricted to avoid animation issues.""" @property def sun_azimuth_angle(self) -> float: """The azimuth angle of the sun. Values range from 0 to 360. Zero is an origin point in a sphere determined by Unreal Engine (degrees).""" @@ -4970,7 +4993,7 @@ class World(): def get_actor(self, actor_id: int) -> Actor: """Looks up for an actor by ID and returns `None` if not found.""" - def get_actors(self, actor_ids: Optional["list[int]"] = None) -> ActorList: + def get_actors(self, actor_ids: Optional[list[int]] = None) -> ActorList: """ Retrieves a list of `carla.Actor` elements, either using a list of IDs provided or just listing everyone on stage. If an ID does not correspond with any actor, it will be excluded @@ -5118,40 +5141,79 @@ class WorldSettings(): @property def synchronous_mode(self) -> bool: """States the synchrony between client and server. When set to true, the server will wait for a client tick in order to move forward. It is `False` by default.""" + @synchronous_mode.setter + def synchronous_mode(self, value: bool): + ... + @property def no_rendering_mode(self) -> bool: """When enabled, the simulation will run no rendering at all. This is mainly used to avoid overhead during heavy traffic simulations. It is `False` by default.""" + @no_rendering_mode.setter + def no_rendering_mode(self, value: bool): + ... + @property - def fixed_delta_seconds(self) -> float: + def fixed_delta_seconds(self) -> float | None: """Ensures that the time elapsed between two steps of the simulation is fixed. Set this to `0.0` to work with a variable time-step, as happens by default.""" + @fixed_delta_seconds.setter + def fixed_delta_seconds(self, value: float | None): + ... + @property def substepping(self) -> bool: """Enable the physics substepping. This option allows computing some physics substeps between two render frames. If synchronous mode is set, the number of substeps and its time interval are fixed and computed are so they fulfilled the requirements of `carla.WorldSettings.max_substep` and `carla.WorldSettings.max_substep_delta_time`. These last two parameters need to be compatible with c`arla.WorldSettings.fixed_delta_seconds`. Enabled by default.""" + @substepping.setter + def substepping(self, value: bool): + ... + @property def max_substep_delta_time(self) -> float: """Maximum delta time of the substeps. If the carla.`WorldSettingsmax_substep` is high enough, the substep delta time would be always below or equal to this value. By default, the value is set to 0.01.""" + @max_substep_delta_time.setter + def max_substep_delta_time(self, value: float): + ... + @property def max_substeps(self) -> int: - """The maximum number of physics substepping that are allowed. By default, the value is set to 10. - """ + """The maximum number of physics substepping that are allowed. By default, the value is set to 10.""" + @max_substeps.setter + def max_substeps(self, value: int): + ... + @property def max_culling_distance(self) -> float: """Configure the max draw distance for each mesh of the level.""" + @max_culling_distance.setter + def max_culling_distance(self, value: float): + ... + @property def deterministic_ragdolls(self) -> bool: """Defines wether to use deterministic physics for pedestrian death animations or physical ragdoll simulation. When enabled, pedestrians have less realistic death animation but ensures determinism. When disabled, pedestrians are simulated as ragdolls with more realistic simulation and collision but no determinsm can be ensured.""" + @deterministic_ragdolls.setter + def deterministic_ragdolls(self, value: bool): + ... + @property def tile_stream_distance(self) -> bool: """Used for large maps only. Configures the maximum distance from the hero vehicle to stream tiled maps. Regions of the map within this range will be visible (and capable of simulating physics). Regions outside this region will not be loaded.""" + @tile_stream_distance.setter + def tile_stream_distance(self, value: bool): + ... + @property def actor_active_distance(self) -> float: """Used for large maps only. Configures the distance from the hero vehicle to convert actors to dormant. Actors within this range will be active, and actors outside will become dormant.""" + @actor_active_distance.setter + def actor_active_distance(self, value: float): ... @property def spectator_as_ego(self) -> float: """Used for large maps only. Defines the influence of the spectator on tile loading in Large Maps. By default, the spectator will provoke loading of neighboring tiles in the absence of an ego actor. This might be inconvenient for applications that immediately spawn an ego actor.""" - # endregion + @spectator_as_ego.setter + def spectator_as_ego(self, value: float): + ... # region Methods def __init__(self, @@ -5190,9 +5252,9 @@ class WorldSettings(): class WorldSnapshot(): """ This snapshot comprises all the information for every actor on scene at a certain moment of time. - It creates and gives acces to a data structure containing a series of `carla.ActorSnapshot`. - The client recieves a new snapshot on every tick that cannot be stored.""" - pass + It creates and gives access to a data structure containing a series of `carla.ActorSnapshot`. + The client receives a new snapshot on every tick that cannot be stored. + """ # region Instance Variables @property @@ -5230,8 +5292,6 @@ class WorldSnapshot(): # endregion - - class command(): """ Submodule with commands that can be used with `carla.Client.apply_batch` From 334740ae535f25f6f4eb6468956914c33b45668f Mon Sep 17 00:00:00 2001 From: Daniel Date: Fri, 23 Aug 2024 15:02:35 +0200 Subject: [PATCH 97/99] Fixed Vector arithmetic --- PythonAPI/carla/source/carla/libcarla.pyi | 13 ++++++------- 1 file changed, 6 insertions(+), 7 deletions(-) diff --git a/PythonAPI/carla/source/carla/libcarla.pyi b/PythonAPI/carla/source/carla/libcarla.pyi index 5e864d2ac..b8691681f 100644 --- a/PythonAPI/carla/source/carla/libcarla.pyi +++ b/PythonAPI/carla/source/carla/libcarla.pyi @@ -3815,7 +3815,7 @@ class Vector2D(): def __eq__(self, other: Vector2D) -> bool: """Returns `True` if values for every axis are equal.""" - def __mul__(self, other: Vector2D) -> float: ... + def __mul__(self, other: float) -> Vector2D: ... def __ne__(self, bool: Vector2D) -> bool: """Returns `True` if the value for any axis is different.""" @@ -3825,7 +3825,7 @@ class Vector2D(): ... def __sub__(self, other: Vector2D) -> Vector2D: ... - def __truediv__(self, other: Vector2D): ... + def __truediv__(self, other: float) -> Vector2D: ... # endregion @@ -3849,8 +3849,7 @@ class Vector3D(): def __init__(self, x=0.0, y=0.0, z=0.0): ... def cross(self, vector: Vector3D) -> Vector3D: - """Computes the cross product between two vectors. -""" + """Computes the cross product between two vectors.""" def distance(self, vector: Vector3D) -> float: """Computes the distance between two vectors.""" @@ -3891,11 +3890,11 @@ class Vector3D(): def __add__(self, other: Vector3D) -> Vector3D: ... def __eq__(self, other: Vector3D) -> bool: ... - def __mul__(self, other: Vector3D | float) -> Vector3D: ... + def __mul__(self, other: float) -> Vector3D: ... def __ne__(self, other: Vector3D) -> bool: ... def __str__(self) -> str: ... - def __sub__(self, other: Vector3D): ... - def __truediv__(self, other: Vector3D): ... + def __sub__(self, other: Vector3D) -> Vector3D: ... + def __truediv__(self, other: float) -> Vector3D: ... # endregion From c097d7acf123824e7f032f20fe6d3fd9e7bfa4cc Mon Sep 17 00:00:00 2001 From: MattRoweEAIF <125647690+MattRoweEAIF@users.noreply.github.com> Date: Thu, 29 Aug 2024 14:58:48 +0200 Subject: [PATCH 98/99] added digital twins video (#8090) --- Docs/adv_digital_twin.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Docs/adv_digital_twin.md b/Docs/adv_digital_twin.md index 8c06a4013..8cc07d220 100644 --- a/Docs/adv_digital_twin.md +++ b/Docs/adv_digital_twin.md @@ -15,6 +15,8 @@ The __Digital Twin Tool__ enables procedural generation of unique 3D environments based on road networks derived from the [OpenStreetMap](https://www.openstreetmap.org) (OSM) service. Through the Digital Twin Tool interface in CARLA's Unreal Engine editor a user can select a region of map from OSM and download the road network as the basis for a new CARLA map. The tool then fills the spaces between the roads with procedurally generated 3D buildings that adjust to the layout of the road, creating a realistic 3D road environment with high variability. + + ## Building the OSM renderer If you are using Linux, you have the option of using the OSM renderer in the CARLA interface to navigate a large OSM map region that you have downloaded. You first need to build the OSM renderer before proceeding to build CARLA. Run `make osmrenderer` inside the CARLA root directory. You may need to upgrade your version of CMake to v3.2 or above in order for this to work. This will create two folders in your build directory called `libosmcout-source` and `libosmcout-build`. Before proceeding to build CARLA, you need to then edit the `Build.sh` file in the directory `$CARLA_ROOT/Build/libosmcout-source/maps` like so, to ensure the executable is found: From 9e94feb3a52e6f5ba01d8a0e579e5cd3c008a507 Mon Sep 17 00:00:00 2001 From: AreopagX <49414432+AreopagX@users.noreply.github.com> Date: Thu, 29 Feb 2024 19:15:58 +0100 Subject: [PATCH 99/99] navigation information is now loaded when changing maps --- CHANGELOG.md | 1 + LibCarla/source/carla/client/detail/Simulator.cpp | 6 ++++++ 2 files changed, 7 insertions(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index dd6a7be18..138f015a1 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,4 +1,5 @@ ## Latest Changes + * Fixed a bug that caused navigation information not to be loaded when switching maps * Prevent from segfault on failing SignalReference identification when loading OpenDrive files * Added vehicle doors to the recorder * Added functions to get actor' components transform diff --git a/LibCarla/source/carla/client/detail/Simulator.cpp b/LibCarla/source/carla/client/detail/Simulator.cpp index 8b4089a88..5083dd378 100644 --- a/LibCarla/source/carla/client/detail/Simulator.cpp +++ b/LibCarla/source/carla/client/detail/Simulator.cpp @@ -88,6 +88,12 @@ namespace detail { const auto id = GetCurrentEpisode().GetId(); _client.LoadEpisode(std::move(map_name), reset_settings, map_layers); + // delete the pointer to _episode so that the Navigation information + // will be loaded for the correct map + assert(_episode.use_count() == 1); + _episode.reset(); + GetReadyCurrentEpisode(); + // We are waiting 50ms for the server to reload the episode. // If in this time we have not detected a change of episode, we try again // 'number_of_attempts' times.