From 4c2772c7c9d5c6954b046e7970c81615266398e1 Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Wed, 13 Sep 2023 10:51:17 +0900 Subject: [PATCH 1/3] fix(tensorrt_yolox): update yolox-s model (#4949) * fix(tensorrt_yolox): update yolox-s model Signed-off-by: badai-nguyen * fix: cspell check Signed-off-by: badai-nguyen * fix: typo Signed-off-by: badai-nguyen * fix: lint_cmake check Signed-off-by: badai-nguyen --------- Signed-off-by: badai-nguyen --- perception/tensorrt_yolox/CMakeLists.txt | 17 ++++++++++------- .../launch/yolox_s_plus_opt.launch.xml | 3 ++- 2 files changed, 12 insertions(+), 8 deletions(-) diff --git a/perception/tensorrt_yolox/CMakeLists.txt b/perception/tensorrt_yolox/CMakeLists.txt index 01ade9bac43d6..80a7f0964b4bc 100644 --- a/perception/tensorrt_yolox/CMakeLists.txt +++ b/perception/tensorrt_yolox/CMakeLists.txt @@ -30,7 +30,7 @@ set(DATA_PATH "${CMAKE_CURRENT_SOURCE_DIR}/data") if(NOT EXISTS "${DATA_PATH}") execute_process(COMMAND mkdir -p ${DATA_PATH}) endif() -function(download FILE_NAME FILE_HASH) +function(download SUB_DIR FILE_NAME FILE_HASH) message(STATUS "Checking and downloading ${FILE_NAME}") set(FILE_PATH ${DATA_PATH}/${FILE_NAME}) set(STATUS_CODE 0) @@ -44,14 +44,14 @@ function(download FILE_NAME FILE_HASH) else() message(STATUS "diff ${FILE_NAME}") message(STATUS "File hash changes. Downloading now ...") - file(DOWNLOAD https://awf.ml.dev.web.auto/perception/models/${FILE_NAME} ${FILE_PATH} STATUS DOWNLOAD_STATUS TIMEOUT 3600) + file(DOWNLOAD https://awf.ml.dev.web.auto/perception/${SUB_DIR}/${FILE_NAME} ${FILE_PATH} STATUS DOWNLOAD_STATUS TIMEOUT 3600) list(GET DOWNLOAD_STATUS 0 STATUS_CODE) list(GET DOWNLOAD_STATUS 1 ERROR_MESSAGE) endif() else() message(STATUS "not found ${FILE_NAME}") message(STATUS "File doesn't exists. Downloading now ...") - file(DOWNLOAD https://awf.ml.dev.web.auto/perception/models/${FILE_NAME} ${FILE_PATH} STATUS DOWNLOAD_STATUS TIMEOUT 3600) + file(DOWNLOAD https://awf.ml.dev.web.auto/perception/${SUB_DIR}/${FILE_NAME} ${FILE_PATH} STATUS DOWNLOAD_STATUS TIMEOUT 3600) list(GET DOWNLOAD_STATUS 0 STATUS_CODE) list(GET DOWNLOAD_STATUS 1 ERROR_MESSAGE) endif() @@ -62,10 +62,13 @@ function(download FILE_NAME FILE_HASH) endif() endfunction() -download(yolox-tiny.onnx 97028baf73ce55e115599c9c60651b08) -download(yolox-sPlus-opt.onnx bf3b0155351f90fcdca2626acbfd3bcf) -download(yolox-sPlus-opt.EntropyV2-calibration.table c6e6f1999d5724a017516a956096701f) -download(label.txt 9ceadca8b72b6169ee6aabb861fe3e1e) +set(V1_PATH models/object_detection_yolox_s/v1) +download(models yolox-tiny.onnx 97028baf73ce55e115599c9c60651b08) +download(models yolox-sPlus-opt.onnx bf3b0155351f90fcdca2626acbfd3bcf) +download(models yolox-sPlus-opt.EntropyV2-calibration.table c6e6f1999d5724a017516a956096701f) +download(${V1_PATH} yolox-sPlus-T4-960x960-pseudo-finetune.onnx 37165a7e67bdaf6acff93925c628f2b2) +download(${V1_PATH} yolox-sPlus-T4-960x960-pseudo-finetune.EntropyV2-calibration.table d266ea9846b10e4dab53572152c6fd8f) +download(models label.txt 9ceadca8b72b6169ee6aabb861fe3e1e) ########## # tensorrt_yolox diff --git a/perception/tensorrt_yolox/launch/yolox_s_plus_opt.launch.xml b/perception/tensorrt_yolox/launch/yolox_s_plus_opt.launch.xml index 43f59e944f889..cb89f5829c65d 100644 --- a/perception/tensorrt_yolox/launch/yolox_s_plus_opt.launch.xml +++ b/perception/tensorrt_yolox/launch/yolox_s_plus_opt.launch.xml @@ -1,8 +1,9 @@ + - + From 7c15e169a321e7556efe71f9f0a2b0c8fd741242 Mon Sep 17 00:00:00 2001 From: Satoshi Tanaka <16330533+scepter914@users.noreply.github.com> Date: Tue, 29 Aug 2023 21:09:17 +0900 Subject: [PATCH 2/3] fix(tier4_percetion_launch): fix order of Camera-Lidar-Radar fusion pipeline (#4779) * fix(tier4_percetion_launch): fix order of Camera-Lidar-Radar fusion pipeline Signed-off-by: scepter914 * fix clustering update Signed-off-by: scepter914 * fix from Camera-LidAR fusion Signed-off-by: scepter914 * refactor Signed-off-by: scepter914 * refactor Signed-off-by: scepter914 * fix merge Signed-off-by: scepter914 * Update launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml Co-authored-by: Shunsuke Miura <37187849+miursh@users.noreply.github.com> * style(pre-commit): autofix --------- Signed-off-by: scepter914 Co-authored-by: Shunsuke Miura <37187849+miursh@users.noreply.github.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Signed-off-by: tomoya.kimura --- ...ra_lidar_fusion_based_detection.launch.xml | 28 +- ...ar_radar_fusion_based_detection.launch.xml | 354 +++++++++++++++--- 2 files changed, 329 insertions(+), 53 deletions(-) diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml index aef7220680d67..941de9c7df11e 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml @@ -1,8 +1,25 @@ + + + + - + + + + + + + + + + + + + + @@ -28,15 +45,6 @@ - - - - - - - - - + + + + - + + + + + + - - + + + - + + + + + + + + + - + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + - + @@ -78,10 +77,279 @@ - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + From d0af89b4bfed0185e71d50bb979dc8c7fb87e8e1 Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Tue, 12 Sep 2023 21:14:24 +0900 Subject: [PATCH 3/3] feat(image_projection_based_fusion): add roi based clustering for small unknown object detection (#4681) * feat: add roi_pointcloud_fusion node Signed-off-by: badai-nguyen fix: postprocess Signed-off-by: badai-nguyen fix: launch file Signed-off-by: badai-nguyen chores: refactor Signed-off-by: badai-nguyen fix: closest cluster Signed-off-by: badai-nguyen * chores: refactor Signed-off-by: badai-nguyen * docs: add readme Signed-off-by: badai-nguyen * fix: add missed parameter declare Signed-off-by: badai-nguyen * fix: add center transform Signed-off-by: badai-nguyen * fix: typos in launch Signed-off-by: badai-nguyen * docs: update docs Signed-off-by: badai-nguyen * fix: change roi pointcloud fusion output to clusters Signed-off-by: badai-nguyen * fix: add cluster debug roi pointcloud fusion Signed-off-by: badai-nguyen * fix: use IoU_x in roi cluster fusion Signed-off-by: badai-nguyen * feat: add cluster merger package Signed-off-by: badai-nguyen * fix: camera lidar launch Signed-off-by: badai-nguyen * style(pre-commit): autofix * fix: cluster merger Signed-off-by: badai-nguyen * fix: roi cluster fusion unknown object fix Signed-off-by: badai-nguyen * chore: typo Signed-off-by: badai-nguyen * docs: add readme cluster_merger Signed-off-by: badai-nguyen * docs: update roi pointcloud fusion readme Signed-off-by: badai-nguyen * chore: typo Signed-off-by: badai-nguyen * fix: multiple definition bug Signed-off-by: badai-nguyen * chore: refactor Signed-off-by: badai-nguyen * docs: update docs Signed-off-by: badai-nguyen * chore: refactor Signed-off-by: badai-nguyen * chore: pre-commit Signed-off-by: badai-nguyen * fix: update camera_lidar_radar mode launch Signed-off-by: badai-nguyen --------- Signed-off-by: badai-nguyen Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../object_recognition_utils/transform.hpp | 64 ++++++ common/object_recognition_utils/package.xml | 6 + ...ra_lidar_fusion_based_detection.launch.xml | 59 +++++- ...ar_radar_fusion_based_detection.launch.xml | 44 +++- launch/tier4_perception_launch/package.xml | 1 + perception/cluster_merger/CMakeLists.txt | 27 +++ perception/cluster_merger/README.md | 72 +++++++ .../include/cluster_merger/node.hpp | 73 +++++++ .../launch/cluster_merger.launch.xml | 14 ++ perception/cluster_merger/package.xml | 28 +++ .../src/cluster_merger/node.cpp | 73 +++++++ .../CMakeLists.txt | 6 + .../image_projection_based_fusion/README.md | 1 + .../docs/images/roi_pointcloud_fusion.png | Bin 0 -> 118768 bytes .../docs/roi-pointcloud-fusion.md | 93 +++++++++ .../fusion_node.hpp | 5 + .../roi_pointcloud_fusion/node.hpp | 53 +++++ .../utils/utils.hpp | 36 ++++ .../launch/roi_pointcloud_fusion.launch.xml | 77 +++++++ .../image_projection_based_fusion/package.xml | 1 + .../src/fusion_node.cpp | 1 + .../src/roi_cluster_fusion/node.cpp | 8 +- .../src/roi_pointcloud_fusion/node.cpp | 165 +++++++++++++++ .../src/utils/utils.cpp | 194 +++++++++++++++++- 24 files changed, 1094 insertions(+), 7 deletions(-) create mode 100644 perception/cluster_merger/CMakeLists.txt create mode 100644 perception/cluster_merger/README.md create mode 100644 perception/cluster_merger/include/cluster_merger/node.hpp create mode 100644 perception/cluster_merger/launch/cluster_merger.launch.xml create mode 100644 perception/cluster_merger/package.xml create mode 100644 perception/cluster_merger/src/cluster_merger/node.cpp create mode 100644 perception/image_projection_based_fusion/docs/images/roi_pointcloud_fusion.png create mode 100644 perception/image_projection_based_fusion/docs/roi-pointcloud-fusion.md create mode 100644 perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_pointcloud_fusion/node.hpp create mode 100644 perception/image_projection_based_fusion/launch/roi_pointcloud_fusion.launch.xml create mode 100644 perception/image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp diff --git a/common/object_recognition_utils/include/object_recognition_utils/transform.hpp b/common/object_recognition_utils/include/object_recognition_utils/transform.hpp index 4446c87427e88..31892853a855f 100644 --- a/common/object_recognition_utils/include/object_recognition_utils/transform.hpp +++ b/common/object_recognition_utils/include/object_recognition_utils/transform.hpp @@ -15,15 +15,22 @@ #ifndef OBJECT_RECOGNITION_UTILS__TRANSFORM_HPP_ #define OBJECT_RECOGNITION_UTILS__TRANSFORM_HPP_ +#include + #include +#include +#include #include #include #include #ifdef ROS_DISTRO_GALACTIC +#include #include #else +#include + #include #endif @@ -45,6 +52,23 @@ namespace detail return boost::none; } } + +[[maybe_unused]] inline boost::optional getTransformMatrix( + const std::string & in_target_frame, const std_msgs::msg::Header & in_cloud_header, + const tf2_ros::Buffer & tf_buffer) +{ + try { + geometry_msgs::msg::TransformStamped transform_stamped; + transform_stamped = tf_buffer.lookupTransform( + in_target_frame, in_cloud_header.frame_id, in_cloud_header.stamp, + rclcpp::Duration::from_seconds(1.0)); + Eigen::Matrix4f mat = tf2::transformToEigen(transform_stamped.transform).matrix().cast(); + return mat; + } catch (tf2::TransformException & e) { + RCLCPP_WARN_STREAM(rclcpp::get_logger("detail::getTransformMatrix"), e.what()); + return boost::none; + } +} } // namespace detail namespace object_recognition_utils @@ -79,6 +103,46 @@ bool transformObjects( } return true; } +template +bool transformObjectsWithFeature( + const T & input_msg, const std::string & target_frame_id, const tf2_ros::Buffer & tf_buffer, + T & output_msg) +{ + output_msg = input_msg; + if (input_msg.header.frame_id != target_frame_id) { + output_msg.header.frame_id = target_frame_id; + tf2::Transform tf_target2objects_world; + tf2::Transform tf_target2objects; + tf2::Transform tf_objects_world2objects; + const auto ros_target2objects_world = detail::getTransform( + tf_buffer, input_msg.header.frame_id, target_frame_id, input_msg.header.stamp); + if (!ros_target2objects_world) { + return false; + } + const auto tf_matrix = detail::getTransformMatrix(target_frame_id, input_msg.header, tf_buffer); + if (!tf_matrix) { + RCLCPP_WARN( + rclcpp::get_logger("object_recognition_utils:"), "failed to get transformed matrix"); + return false; + } + for (auto & feature_object : output_msg.feature_objects) { + // transform object + tf2::fromMsg( + feature_object.object.kinematics.pose_with_covariance.pose, tf_objects_world2objects); + tf_target2objects = tf_target2objects_world * tf_objects_world2objects; + tf2::toMsg(tf_target2objects, feature_object.object.kinematics.pose_with_covariance.pose); + + // transform cluster + sensor_msgs::msg::PointCloud2 transformed_cluster; + pcl_ros::transformPointCloud(*tf_matrix, feature_object.feature.cluster, transformed_cluster); + transformed_cluster.header.frame_id = target_frame_id; + feature_object.feature.cluster = transformed_cluster; + } + output_msg.header.frame_id = target_frame_id; + return true; + } + return true; +} } // namespace object_recognition_utils #endif // OBJECT_RECOGNITION_UTILS__TRANSFORM_HPP_ diff --git a/common/object_recognition_utils/package.xml b/common/object_recognition_utils/package.xml index 95925e846a55c..2f2472515ebad 100644 --- a/common/object_recognition_utils/package.xml +++ b/common/object_recognition_utils/package.xml @@ -17,7 +17,13 @@ geometry_msgs interpolation libboost-dev + pcl_conversions + pcl_ros rclcpp + sensor_msgs + std_msgs + tf2 + tf2_eigen tier4_autoware_utils ament_cmake_ros diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml index 941de9c7df11e..34c2fd4cdc27c 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml @@ -79,11 +79,53 @@ - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + @@ -95,6 +137,8 @@ + + @@ -287,11 +331,22 @@ + + + + + + + + + + + - + diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml index 8d4a285094651..7d1353433da85 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml @@ -142,12 +142,54 @@ - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/launch/tier4_perception_launch/package.xml b/launch/tier4_perception_launch/package.xml index c1723c1fa07e8..336588891d9b2 100644 --- a/launch/tier4_perception_launch/package.xml +++ b/launch/tier4_perception_launch/package.xml @@ -12,6 +12,7 @@ ament_cmake_auto autoware_cmake + cluster_merger compare_map_segmentation crosswalk_traffic_light_estimator detected_object_feature_remover diff --git a/perception/cluster_merger/CMakeLists.txt b/perception/cluster_merger/CMakeLists.txt new file mode 100644 index 0000000000000..49506f4b439fb --- /dev/null +++ b/perception/cluster_merger/CMakeLists.txt @@ -0,0 +1,27 @@ +cmake_minimum_required(VERSION 3.8) +project(cluster_merger) + +# find dependencies +find_package(autoware_cmake REQUIRED) +autoware_package() + +# Targets +ament_auto_add_library(cluster_merger_node_component SHARED + src/cluster_merger/node.cpp +) + +rclcpp_components_register_node(cluster_merger_node_component + PLUGIN "cluster_merger::ClusterMergerNode" + EXECUTABLE cluster_merger_node) + + +if(BUILD_TESTING) + list(APPEND AMENT_LINT_AUTO_EXCLUDE ament_cmake_uncrustify) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + +ament_auto_package( + INSTALL_TO_SHARE + launch +) diff --git a/perception/cluster_merger/README.md b/perception/cluster_merger/README.md new file mode 100644 index 0000000000000..b46f7401b70ec --- /dev/null +++ b/perception/cluster_merger/README.md @@ -0,0 +1,72 @@ +# cluster merger + +## Purpose + +cluster_merger is a package for merging pointcloud clusters as detected objects with feature type. + +## Inner-working / Algorithms + +The clusters of merged topics are simply concatenated from clusters of input topics. + +## Input / Output + +### Input + +| Name | Type | Description | +| ---------------- | -------------------------------------------------------- | ------------------- | +| `input/cluster0` | `tier4_perception_msgs::msg::DetectedObjectsWithFeature` | pointcloud clusters | +| `input/cluster1` | `tier4_perception_msgs::msg::DetectedObjectsWithFeature` | pointcloud clusters | + +### Output + +| Name | Type | Description | +| ----------------- | ----------------------------------------------------- | --------------- | +| `output/clusters` | `autoware_auto_perception_msgs::msg::DetectedObjects` | merged clusters | + +## Parameters + +| Name | Type | Description | Default value | +| :---------------- | :----- | :----------------------------------- | :------------ | +| `output_frame_id` | string | The header frame_id of output topic. | base_link | + +## Assumptions / Known limits + + + +## (Optional) Error detection and handling + + + +## (Optional) Performance characterization + + + +## (Optional) References/External links + + + +## (Optional) Future extensions / Unimplemented parts diff --git a/perception/cluster_merger/include/cluster_merger/node.hpp b/perception/cluster_merger/include/cluster_merger/node.hpp new file mode 100644 index 0000000000000..8da5999f00384 --- /dev/null +++ b/perception/cluster_merger/include/cluster_merger/node.hpp @@ -0,0 +1,73 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef CLUSTER_MERGER__NODE_HPP_ +#define CLUSTER_MERGER__NODE_HPP_ + +#include "message_filters/subscriber.h" +#include "message_filters/sync_policies/approximate_time.h" +#include "message_filters/synchronizer.h" +#include "rclcpp/rclcpp.hpp" +#include "tier4_autoware_utils/tier4_autoware_utils.hpp" + +#include "tier4_perception_msgs/msg/detected_objects_with_feature.hpp" + +#include +#include + +#include +#include +#include +#include + +namespace cluster_merger +{ +using tier4_perception_msgs::msg::DetectedObjectsWithFeature; +using tier4_perception_msgs::msg::DetectedObjectWithFeature; + +class ClusterMergerNode : public rclcpp::Node +{ +public: + explicit ClusterMergerNode(const rclcpp::NodeOptions & node_options); + +private: + // Subscriber + + tf2_ros::Buffer tf_buffer_; + tf2_ros::TransformListener tf_listener_; + + rclcpp::Subscription::SharedPtr sub_objects_{}; + message_filters::Subscriber objects0_sub_; + message_filters::Subscriber objects1_sub_; + typedef message_filters::sync_policies::ApproximateTime< + DetectedObjectsWithFeature, DetectedObjectsWithFeature> + SyncPolicy; + typedef message_filters::Synchronizer Sync; + Sync sync_; + + std::string output_frame_id_; + + std::vector::SharedPtr> sub_objects_array{}; + std::shared_ptr transform_listener_; + + void objectsCallback( + const DetectedObjectsWithFeature::ConstSharedPtr & input_objects0_msg, + const DetectedObjectsWithFeature::ConstSharedPtr & input_objects1_msg); + // Publisher + rclcpp::Publisher::SharedPtr pub_objects_; +}; + +} // namespace cluster_merger + +#endif // CLUSTER_MERGER__NODE_HPP_ diff --git a/perception/cluster_merger/launch/cluster_merger.launch.xml b/perception/cluster_merger/launch/cluster_merger.launch.xml new file mode 100644 index 0000000000000..1bbd0ebd91e12 --- /dev/null +++ b/perception/cluster_merger/launch/cluster_merger.launch.xml @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + diff --git a/perception/cluster_merger/package.xml b/perception/cluster_merger/package.xml new file mode 100644 index 0000000000000..14826ad07e098 --- /dev/null +++ b/perception/cluster_merger/package.xml @@ -0,0 +1,28 @@ + + + + cluster_merger + 0.1.0 + The ROS 2 cluster merger package + Yukihiro Saito + Shunsuke Miura + autoware + Apache License 2.0 + + ament_cmake_auto + + geometry_msgs + message_filters + object_recognition_utils + rclcpp + rclcpp_components + tier4_autoware_utils + tier4_perception_msgs + autoware_cmake + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/perception/cluster_merger/src/cluster_merger/node.cpp b/perception/cluster_merger/src/cluster_merger/node.cpp new file mode 100644 index 0000000000000..48bf953027510 --- /dev/null +++ b/perception/cluster_merger/src/cluster_merger/node.cpp @@ -0,0 +1,73 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "cluster_merger/node.hpp" + +#include "object_recognition_utils/object_recognition_utils.hpp" + +#include +#include +#include +namespace cluster_merger +{ + +ClusterMergerNode::ClusterMergerNode(const rclcpp::NodeOptions & node_options) +: rclcpp::Node("cluster_merger_node", node_options), + tf_buffer_(get_clock()), + tf_listener_(tf_buffer_), + objects0_sub_(this, "input/cluster0", rclcpp::QoS{1}.get_rmw_qos_profile()), + objects1_sub_(this, "input/cluster1", rclcpp::QoS{1}.get_rmw_qos_profile()), + sync_(SyncPolicy(10), objects0_sub_, objects1_sub_) +{ + output_frame_id_ = declare_parameter("output_frame_id"); + using std::placeholders::_1; + using std::placeholders::_2; + sync_.registerCallback(std::bind(&ClusterMergerNode::objectsCallback, this, _1, _2)); + + // Publisher + pub_objects_ = create_publisher("~/output/clusters", rclcpp::QoS{1}); +} + +void ClusterMergerNode::objectsCallback( + const DetectedObjectsWithFeature::ConstSharedPtr & input_objects0_msg, + const DetectedObjectsWithFeature::ConstSharedPtr & input_objects1_msg) +{ + if (pub_objects_->get_subscription_count() < 1) { + return; + } + // TODO(badai-nguyen): transform input topics to desired frame before concatenating + /* transform to the same with cluster0 frame id*/ + DetectedObjectsWithFeature transformed_objects0; + DetectedObjectsWithFeature transformed_objects1; + if ( + !object_recognition_utils::transformObjectsWithFeature( + *input_objects0_msg, output_frame_id_, tf_buffer_, transformed_objects0) || + !object_recognition_utils::transformObjectsWithFeature( + *input_objects1_msg, output_frame_id_, tf_buffer_, transformed_objects1)) { + return; + } + + DetectedObjectsWithFeature output_objects; + output_objects.header = input_objects0_msg->header; + // add check frame id and transform if they are different + output_objects.feature_objects = transformed_objects0.feature_objects; + output_objects.feature_objects.insert( + output_objects.feature_objects.end(), transformed_objects1.feature_objects.begin(), + transformed_objects1.feature_objects.end()); + pub_objects_->publish(output_objects); +} +} // namespace cluster_merger + +#include "rclcpp_components/register_node_macro.hpp" +RCLCPP_COMPONENTS_REGISTER_NODE(cluster_merger::ClusterMergerNode) diff --git a/perception/image_projection_based_fusion/CMakeLists.txt b/perception/image_projection_based_fusion/CMakeLists.txt index 906ad71d21732..ce7c3b5ea12a9 100644 --- a/perception/image_projection_based_fusion/CMakeLists.txt +++ b/perception/image_projection_based_fusion/CMakeLists.txt @@ -22,6 +22,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/utils/utils.cpp src/roi_cluster_fusion/node.cpp src/roi_detected_object_fusion/node.cpp + src/roi_pointcloud_fusion/node.cpp ) target_link_libraries(${PROJECT_NAME} @@ -39,6 +40,11 @@ rclcpp_components_register_node(${PROJECT_NAME} EXECUTABLE roi_cluster_fusion_node ) +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "image_projection_based_fusion::RoiPointCloudFusionNode" + EXECUTABLE roi_pointcloud_fusion_node +) + set(CUDA_VERBOSE OFF) # set flags for CUDA availability diff --git a/perception/image_projection_based_fusion/README.md b/perception/image_projection_based_fusion/README.md index 1bbee35ab44f8..207989d8a6f25 100644 --- a/perception/image_projection_based_fusion/README.md +++ b/perception/image_projection_based_fusion/README.md @@ -58,3 +58,4 @@ The rclcpp::TimerBase timer could not break a for loop, therefore even if time i | roi_cluster_fusion | Overwrite a classification label of clusters by that of ROIs from a 2D object detector. | [link](./docs/roi-cluster-fusion.md) | | roi_detected_object_fusion | Overwrite a classification label of detected objects by that of ROIs from a 2D object detector. | [link](./docs/roi-detected-object-fusion.md) | | pointpainting_fusion | Paint the point cloud with the ROIs from a 2D object detector and feed to a 3D object detector. | [link](./docs/pointpainting-fusion.md) | +| roi_pointcloud_fusion | Matching pointcloud with ROIs from a 2D object detector to detect unknown-labeled objects | [link](./docs/roi-pointcloud-fusion.md) | diff --git a/perception/image_projection_based_fusion/docs/images/roi_pointcloud_fusion.png b/perception/image_projection_based_fusion/docs/images/roi_pointcloud_fusion.png new file mode 100644 index 0000000000000000000000000000000000000000..c529de7c728fba996a08f3718aef2a7a6d705ccc GIT binary patch literal 118768 zcmY&cHYQ9p*|u$KvTfVed-{C!d;6oV^IW^+WMP`U472(Z|&ARr(J65_)0ARyp9ARwP6pdo=z(%c)Efj{8(f)a|*z>f#CK?v}S z0>Vho$h6y3OV6>F8bZ&qmyq|3o^db9kC9dC6BrsD2f=jAwk4tyAcJ}pzw-^M<<_z5I5X%uPuA<0q6DtS4o1l9!kOYPA->bg-2 z1*=u?(Lb$w@X|nB3gl#a!?o-ww8>&weaF&FATUt;EXG(+KZzBXE})iQB>D=aLm=qwH_ zVnifX4w2xwH3`0wam zLoT-)6WdP~_h+kx#bMtIdNyr9{zwEk9!>?;TP`cB6aq8Tj3eopS)rCkGRkJpj34@Y zy7p9TrVhNX(Sp*+LW0!}C-ah7|CYrz%XpH_uH(*G8TOeG738S?qM#@%8SIN7wCyUF z{T{q^+b#M)BrX-xrxOdp(%NRnV@8vS%o5yeWI@!DY6I1-`p^J}cccLvWOl~L(`&)v zVpG6kY?;~96dteZ?A3q0#US}}=JiXBHzPZB&x-wo6*muO!w;E5(7b)`)0kA#*rQu$ zC*alwUzgVIpC_#Lc=^XGMVxqHVksyABht!_CbM9%T3}8W$kH)=DkYTVd##m@LKRdj zp_B?TtrZQwl{NwKU&|>@Mg!*TPg!lPyOuaUig)j(M3c=4F86U63OyD8nB3v1|X9ZpEWfKby+p!u-~}2U|(E0;3?am?(9&K zbMo}Njp1{88xvO_^RucefLNB1z{M3dsS%Ts#QI}(yw^-!aPzq+_C;D+!@kZh;`R!BoJ`Nj`E>1^Fe;;gzU2>_(TV}K`tjoj4v!nE zv$OM9Du;s6-<^#ve?zxi*TV>E+nQy%lPhuZ+%nIBZi~Gwm0&bA3B ztI3%uJyGcnJG0Vw2vaZ_%hUiNQwW%>6MW}S)@j=b52xkfdJPB8Kv~hCsS%64$eLI6 z0TAljh!rkf+LZ698s231d?*1;?MYmIsrSqIdC~pvY=1;TA9uHSD=mlxMl~I|IQ6|A zX6pF|bc zl)V#Y6&dqq7>WrH9D3`!+*-yZ4^ zqebm>aMp2y`1<%-VCd087I;A6ImAX>eFK3H0{gBydcd2bw)M2CSmBCnd49EF(#?$b z)iAHJ(^XUB=-y|$0fHNgF&r%^^SXMCy#bnL!#BK|mq8 zo99sQoz8OpblreKy&>3v=_GGrd_TARmoMVaJie}U0l)1G5QdF|Hyo4ZM;BO93V7E; z%VlH*aVUr_>atSnt1PDYvFpSQtoZiPzL#Qm3CX?%Geb49!DrtKfgT`M81>zozM%5N z6kLUSba;Ru*qm84SqRIfKU!mBr}=WV1Wk<%3?7!I^;Sq3T*oj7g^YcSiBe#5aADs)>v}r#n+sV6F>2>WN5jL-4_@>%bhVB#awjp z->vg=>B9mm^UCmk<5>5+$MyB~4G0e2-rYUHc)mI8nb+}-m^AsbN)(7ZkAC~f>-AQ} zvC{_>qgbBW`xUt^3lU8YOspRbf1UNx2`zPi=P0PyzJaQ^c&~_0x>aMgB{FBa1efsV ztUg4s`tK@n&)ll(#_#4z1r|>A+k;y9yxQxot@Z5%%?E|oE&~0}X7`+9+iT8aa?WV% zQRnV0_O{P7T%$kkcbk@m)bkOoBy6R9d(x`Vix!U(WLe}ul}hRg>B=fG)_X3kg9>>$ z6%imE53*yn1)+an8S_bbzuwLtA?_y2|GsQrTI_jL(_DA|^Q15E$VpcJU4g5G_u0Jh zv83YM0guk%rT9CHoeJozjJZ6N_n&M^<7F9*TwW{NG=-X-RKFFGBOooO?g zBYUZ8O%m6m`uSzFdj=X#&&>RyV)b03;&X=*HJs^Tsy{KRU};ruGtf#Hc((OhA1gfz z+b{R6>boo{EEBtlG6@~j)+j6wqY&5U(Me>YoTcNJymB2qG!&ZSxpR>WZIW&1qdVxFmc_-h`UUpCvcjK%0Lt+_U9)$i z6Xes2)SH?Hw&{u&<5yXb0~j|e#PLV2V+>M}8iU~L>4h0HaypR*^oq~<=Ggtio6cZz zHl)#x!?Cnn?fsxau9ufVV`t{K}`41{cDRxNH%)DdyTjoe>8b*pneXRxeWe1j_7 z+><@nK9xGVuNQ!awypQJF{EC`l~Zg?dU)snF~)!Hg(JB=cElU7Ct#s_=J{BX{jXoY z^tXCLQ+Yj;2M5K0z^tX$c5z{|RB!1Xm-Dd$Enz5cH_S+t@h_%~`c7J}=;t8nDN;vC zU)esT!sVs@ko^AR78dKPO3l`@uzWS+57d2HeTu_!ScpszvrU5PskG~Fjx02_CQ44x zqU)?)E{FAK?*|~{l2QaT^N&waD~8<5mkILIW~hjUEq~>ms>dgTTMUYG0f&pFRAo<2 zQPs^TbS($T!{AH677|cMZ-R;i}btm+}O)76|P=&IU-n_4LH5vpCYzJAq1H19q_v!m1!Ta)t zO2RwTyH^J8Rf-@RI=DAqfq>xbH=sLAITn7aF2kZBI;K*tDQCXa}q+r zEx%t|Y!(X_t%kr2*D5!YEcjkjr_J0PGtaUTVd(T)Y(f&7-EF|@S&Bi|pPvPCaDyph z1n>4xvqCrs8%7nn7lh|LUY&>Ch8JZoYfDaEj!!NEq(IiA#TR(6)u;Q^@zepxTXs$B zUxeQ=1Wk{go^L9KAIVwKASzdw!T=i<2oya@S`A6woTUfZafvn0U-DP@<3OSA?L~vl zw1q#IVUHiO)VjgDIe*I_99ZNP+ZwQ6tS!L=^W7;CC1u#njRPbSo^*rNYB3ivLBNAp`4RKb@Z~dx zzDr*mwE1Hvj#Jv;_V|qujPhBa^1RlKynAQt&!eN0kP3bsHb5H-GGoAF7e7%11KBix3PJel}tDo51dZG{A zR*?1J*uJW5_2lN|gvU`n{)i2^ZAh2tP0Ceq;wuQ@UVdF{#mS@XM!vunby>lIq8CJ} z=TXI%!pFqK;jn>>&!?NrwQ$?$e9{5B$Ov^wS5dM6LQx~wsAoLNZ!>wFDs@awSs zgl_MKTjjPkQ^?~p)mhFM>e-HncW2E`mTZ^KF8;lPW(ttu%?|jmjKL)W-BlAhK zB`QpgM~V)dxYPMEvBHVSTg^_Z#62<2FIz|Sx8S!?8?^K1nc1aj#Bq4NyC7`IdX|Tp zNO_s$fw?pTl1g$5)wEff`z4om0}bidx9h+h7Wxa;+aFA0q z*&eplS98wJUD@!Ky_^};57k)k90QB&4G>nT7L%<3F>i|2PdF0(`RQ5eRm)&qLO%Jr zPOQv`xt?Ep%4mKpVq=;kT!2Qag#zP@*mPWH-FUr`8mqqY6YTHhQ0T#B6wq4 zGURm0N+`!NX!gkCr-Gcx_Qu-_+})34H)Rj4SA#Q#{h6T}MGNAS!IypOAfRrBMEjb7 zXg%KMo1>bcwK^H{cW`ucx9xt7h?6rJs6QF?`{9$>thHD5UVb#x{;^*H=RPouMgX!{qw z!ND1{zBt*wP}FukL@NVX(L>GSPW|D_Gu*zLYTa?b)q{TfJGGBrOoEtG$M{#cX^{P& zcVCUXM@G00X=C_+zEQXReB%&D!SJPEXy_oM|zA>&v!O#U~LVf3&qpyxmX_0HQeQb<@s&Te+N^5e`!;eluFu{w8Me4C_(D##_SOZiO5>1`67XrJa94Jr z#PjkKw;vvHZ=IayQl!L+{%z0rPXcDf2q?1f9ji1Z4)j+^Swhl^yl=U5rxBDQfod*Fj%@fC2+BfhBnTGdGxtyI7x%je(H=rAHZ}v$`qe(d2m3r{+#t4~G4Z3Ho*FSh` zC{TB>TsNBN)elp-DDGWcnVnmVjNfi-Ws@7=zYTU^z4_PwJXEdDia7cW6Dt@(m182t zTrnQHmk>LP8~Q*NPp30hs#XIa3ZMXNlc`YfeHIsRl!{5mq*!~4p0w|2b71(gAb}%_ zU(Kf5TVJ)9r%AtWE%F<09S_#CSjg6F=OgHz%$vJ93q!ZBLEfZ8s;^Ba!2GzRMzmJn zWT{1X{*2oZRuom2m8DHUL=pM$fEuZv`AQV4TFa2^wO=j^6ysZAlPvgsE!)dkP&k1U zFU}6cT$)_(M`xIQ#WE#{oRvHXJZN6BGP=j(tacOI%LIPT%B09>o7YhlX%#zYQLNYQ zHndcH2m{Xsgc3z#f#e7>Lav6k)F^(bQQ{5=JudGZbkj{$_R=a=>ab#PrLCxSL9#l( zc6JLqCc*C3w;pVNMffdgB{o=bC_vR0_^yq0mD!d)8X=f(qj30!W|HOCIJ|y(YI4$W znpVfe{W|VFaNpU0_YxN`zS0aXFMD)p%J#cqzV}+RB4&2-XobnYLbC6Api9_mlo^?U zFWwo?T(wm#B3m55k8BU$#w7LjWo>&0$SSEuwadBB4bWjySYs6mFYZJ24bo~87KgM- z(zO=lHV@Xox90k)Sca7I$C|>vFNIY!(dBH7)3VG*zUJD~NGJ{c1ir|EPnDO~*30|l z63V*$k#snLuE64Ak_V#LyCen&4Rf}^a zM)d3U4=l?S3wNa(lId7yW@Tl+l1shR{RD}4rY3-b#?2TEQnRFNj7+Pol|~ItZ{|hE zc8j+bgC?NdJ~1{mFd+8w@|wjRLns&>pzh1l}pg96@q6@u7V{!Y=A3r(u*w!z zg#Uf}hxw54hBMLE33p$%Y1R?aR*;gJf_7`HYG)}Snsc9MPW{PvRmJTc3U^xiOMw; z?!$xXT=qtly^lfb1dQJt+ZCVu;SLc z7BpGoMb%OGY*h?;-YF;el4hBj79(#%3ZWJ3@>83y1+OA*c|B!p&KhqgWfbN_zWcB^ zn6Eu~?3izFf_BS1zD@fmd7QR)z&4~sjBe{ywtvDg#=HhK4NpuDmJdJN;4$75T-&8P z1cZ^1F(fREkcB1g?e!VJJv08bq{d^T(MqX2bIkq%owhzAWoO0UG)t*HWDbUyh6K{+ z?TKyYcTDs*Sx)f}%o@Pcz7y!J8rjvM3*y01u*s~fwBQTi*|5__dSa;FAD3dYl-ulhwbaQ!{Z!5O#LX7W0vv{QmZ;?{ag9(@X)TofYMeP)kLpqQM_*GcpkuL!{R zdhnHqCA|a?b4I;xaESmI0xN8`vqAby?cl23GrYf9Wf}{~TbdeuJ-VA??{N8LO8NW% zc=3_{Vu|1o_BjP5TcIbjQR$Qy8Fv-nS-g(+e}-CdjMl+o`86`bXS|DofOl|PUZsyH zH`HrnZ)I4$TT>OTrCi@$Toqm9pDILgV$bg{KW{O$#aREPT|!tyq{{2n&Cky-BqStL zxlH|^7^2C-=D-NgpTjiqvX;)=(a=l;)Ple)wm6jvGk5m3^N(yRbbI5Nq9H`E179S= z;lXH|vx3zVBVycxy1S+CEYyYEL~c{mFUytg2pS-H++@{YcRdjCxW$1|$JEpm9-BEN zoyT3-S$sZl-TOTa*r(}YrII5=5$GQfRuBInEVdX;Z!x)7Z5s{kB`I`DV}f}wRvg?~ zi%s0JMa_lJ)lh&sUs}7yci*6L-thUX<^190dfap>7e*mpI=Xkvl^qB1?tFdR7Yr)w z{q}f1%4)S)$=L+R?+O3Ikn}<{O~OkJC!<<4*wS<0QyYqD7hzH4E_Q7ki^Wnt1!i@H zSIqu;p&3HcR#4Q|*2V)MR*SXPq~E`hyL);j&FW@x=UBF*_}(@Es1=9Z#%E?m5fPUY z+($G=KuL+y`HVW0p1_L!zhsVPK>F{swnCJefQLkuotqvlbT10f;~J(AkHP&6?VX?o=X34s>}+=1 zE%2To1R`SM+-9L-C)Sh*FepTuiwyyJ1qBY*D`F7!viR=q?kzVfD=TKRnUE}@;D1;S zs-0wsprVB;lEpz=pZ@9a*?C2)fkeCg9iwPBdXzrUI%#FA`*<3CVAn+*nLPH^;qS=< z8ogGRj2RV#=C7_2hz{mAWc!04rURtC)cB&3nCdrY&B*n2OcXTN4a@>^=mS}<_otr{ zL*3eW4o%u>&F9WO56z^PxY9a-duEInShzsTM8IN6lqB-mBVKkuT|6n;qpcrC==X)8 zQEN5-0S@Ek)-SrLT#48t#G<9V++2FgC1wzywm}pdB6Q9}(KCL>TN{XDUzXaIuE$<46i8{+cz* zQ>oDAf83dG3PQw{yxtqF5LFcnDLF~T!pawjYEOqzuq;$i(J^wy8aN-udY6aiXh1SN ztHm=6GJpeapo;nrJw`ZDX``MZ#PHWG!%r1*=S7p)40B9bpzv-{RQ3R<&RPKq5OsG&jSIfD^k!Rf3OzICr&W1I;fuwE^`ZYg|MgOQc$>In(LIXdT zJ9zzkHB9%o{{AL*JXaP9I4uExNDRJ1(%BYgYu?wJ=`E2fP(>w?g6YXdTYcb?mT(9H zXG4)hXCJKvw; zwj}U+K23CZzaJqUCf@;@g@S@26oJh`4*c+Xu`=9^FpVqfI{*hV3w91(LG@7(Wdz`e zX#7>vHRP}68;CAhQUD?c@FTwpZ(^$bv??YSmF{i^OxeHF8H+RRuYa&H4PbYz(@7dK zUD6UZkx)`niNarN02al#@;Q~I&w+Drfjx9W*+?DSiGZ2eXODN(<>#C-t*7IskK^qh zmWB&QXtKUAXj$feI8_FhCE(?f@^XOR6yJlP#wXu5HWdPyIBJy448NPkV>s;Gx`vli zQi0XbYG7eId5Fr3g(b-ZyzP_L{3)hSUVF4V)QI6UjB%S^hIaqD#op%q9jMJxRZs!7 zQ8LSsSZx_`kjy!J@47|qxb+Ltf3yHi9W`a&-i;m}9P~V-)ssGtHkG9JoP-%4bSt*I z=ka&}Q@iaXk2mg4!WV6Pk|EO4iJ;>+UyivBqLC)j_uPGId6go(um)JAOrUUu+%~Sd zxLBw=(Vl^__cV4N7n7o+2tb~%$?$p#1xjeUn}Z+y08JcP2`4TqYdlw~=5e=ZTx-3a z-mvBdM^{n(>jEC1H#J`-MOh&L*qS`p7(F*XPA7h()UoBEwKNiv(95svdrt&8s3*i( zGucUMTwfOVLDJ>~pXD;bG+3E?8UjOWkV;p%Wtgw)rV2x=Mq<5vI-4-|e)M2?d%U#l z3JROjDL&$0i0OKpqZG5T#$1OmNaRA;+8g`e#6p`fC`4?(dL7h-xqGTxp4(0`he`LY zZYnzt#yRa8uiZP3X;oW&q&(KmgA?9hq>+JpvWnpEx$TH2cz)S)|WCIqdV-0?f-8p&H{Z%e$M9--_7$1nV{!*@Kc?7bs* zQBYSmP|tFjw`ST*aHJn8s^SOvbG<*lU*2-|6L8Dm;NXA?VZJnuO6BS=RfP?(1==o~ z5FbbeHnT}*tSqmZ=Dsf!-alnEW*+jESy9X?u?%jDO#>7vy3y5fBy(reg3U{QkBI}M zpWut_z*u=>S~=McEEkGXHi)P_24`(~kx)wRnneoOke?l~LCWxdZS9{Y)NI5;P-{2E;;)}Y<^`hpYcO(I z$mM7eAK%k%laySqa4yk$#3YWKwM_=F1o?SdU!LDPXMv1zj&8I>OpbWjvrb;xN*}7m zb_;&h`JSj{#9Xr$C%k+;Yd6!5kKD13+;OJe>5rifULZQ;%Jqg4VQcV7j0wq>nJFpi zi4{Ecb=6J9yWr>kaTA=l63C4MF3Na%z-({%;?S9O_YdznG`6zIAsh){H`a3V@)%sN z4BDU1xFF#%JAcu&57IQO$gk>Y#eQULe<&1Gs|{dQn;o~y8rHJ4TAccJySlm@4kmo# zX*8~Gre#(1bAg*sBpIW(gx&@I2tt0coFvXG_viCKf18{X#)!|ww^oOX=P26~dv+8< z4QCvvP8=M`Wl9%HODm2rirA&?Jo__trk@Uc9-60nxr_fW3Yz+eo^7dR-W)pXlisMW z*jzd-O;Gf9dlvZ}tZDPcVm86wIlPJ9eU9Y93TW{jU9ohms~vX$Y3;lqg{r7koivltgx&yjO9d~XvNc{2e|JFnHf zteeP;@zk^RhH5;d35Yt=$nW4nMBTL}^_r#tF*_D?b(4PHiZ;CEjM{GcogCK!sCh!n z$DVGFlh|zu!?KaFuq4jc+Df=`&F6qzBZ<)v*45Ru6*$%Kc-)D}EW`Ie{)=evaIray zoQ0g-tT?m-&1MOb#x=K}_6G%LxhilqlJ~)4sdJ8-{?Ykct+~P$_g>B2ASCN@{-*OV zdOaTaguRLh{aL3-d|*={q;J=X_K_8HM9O3(WG+W$;S3T!;JD|5{_ya%nWV8x^u52KxuXVO;ef@l6ydkO8ruO8NwPq0OC*fq?;s!!95g-z#wd z-}}YyHbRt0H0P31ge;&DU2#&9z|BvHbK`ah_Iuu`fpdQMe*8Xo06=5 zXjX=YROCLiQ9p6?wofT@^OHGH#ZDt>!0uC#0Ojq+N}ta=m<$Gy zo1IS8R|&LYVPRoIA|v;JPYaYvl%YpQaeu&84z%)KglR@3A zSS(7xHp0%;u;mbSH}|dIJAH70gQB-@Ao}<3!T11n);9|wTZ7A0E-+Uj^0=ngR!Z*o z6CM{=Y+n?g^sEfSOVb6{BbAxuxxx)qrAua;yGJL1`nDB$(4-`%k7Br-{zC~9NdZZ1 zNv(M>jmrO#1Jzw76a=eT%XfWNpo;J2x~cCGamr|0F|f1;ME z=fpU>J;VH~l@JqYFZYtG0Zq_*JG%7ruGs=X^-|B&G~#fFGAufkrH^rTzWB@A)Agj) z(qtlMzQo5KC1L$8A=fhuHg+-D=HUf&hZ1$B#?JdaS~|VOrw%4~;r$jFpi2}J`^r!2 zVP%Ku;%sVa+jAc95J{F(B`U(+v<#Eo&^@Hb=I^#s9t~wB)P8J!XSHhXddrB>;@*QLCD1*!BOdmBp>u={ zqk6Z1-Rog3sQxlgH2m<=bP~sgH~jIeZPDT{_-u6F)4b^AX8P4Moop#~XvZR0Syy++ z_%P`byl76z_@qLCuepJrG7_h;b)1S#$g8{Ll+&nN!b;B=NsZds-wZUgrH2PSI_@LP z%O;-i-NS^dF-_jGda$S)o4X+hkFHn@)_`uz(HvyeZA;G3jfL$84v&t zP>Ula744GS{ShTx)C9ebnSW#SK)MJ7#>S+6$W2TWGS|Aap*1YwLc^58kdwn6n1dtF z9Byf)<)=erxQ)$w=h9_X%tqbahwH!YmN(M%%1C>{%*e@QfZPrrMT)MJI>-bw9@mYz z9DZYSN67J~S^13054Zm8YAnW^N%pXaL;C**00H4~_fbenB#0z%U=PBIG`MEdGtmx%;|jjdP3 zjzLaKE@@zgMCJVCyqN|*&l7GPjG@c-Wpw*(^kAY44%Y+B#c7w~k7gj(Q`BBp$y=MI zY{F%<0~^SLlj%aHJ#=ExqU5qS6IQqMP%k z^~cOo%Tlyw>1DJ-ut+l4eMSh09Jy@$H!+ho-XqbgZp9P zTuCx(7jQ>{!m%&yuW+^MOs8D&9*c9jgyg;WugR9=on_8Wo7&fX%QI#z7gHmk79Lg% zMNPj`qPstfB~YzNz}gZ~By#3G)Gd?gHR96Lsjeq%B;JD^yKto)<(jc zT2EV=6zNz@K6`?%_Xg3eEO0)Mqe8AHk66;)?XMzY&@+uhF?75`J3|TC3-NhALRre! z>C#WcL0OCbuFFcYKTtd201k9SqXFmo;c!H!Db8PGo4w_%Eu{e98bldx>lhpyZ+~FJ z-=wj}Ryc?22g+p85A?siLZSjW?+l`oD+{e*;FceC$wer?^F&3UpABQHKo z>rJCnb-iDOKunyTMNc0!Qc4Z~R6VbV##Ik^;9bA|>44dJzj>vF{oUSBlnfWaAg}p!cc@IxChw0)f z%);ot_$&m-XMT0-e@$fYK((LGjZrYm7tLvbV!Z5m42QSl?Ix#O8LI7cciEq(H+o-4 zzwIGZt1d9m8bI&TPwLpAX>JxBKf`0ND{VIw&PD}A$_F~oh|FRc{Ncw?1 z84-F5y^j{d)Eq~ivfvfoPoVxUtBZVe0WD(I)HR{vC01~YZ(8gP?9~rO>g*M*4e^TZ z5=~>ne~EJTF1l{;Fcu9TGM1YisQ`G=q)r{kd|=?=TLo2`y>NLwfE~cRJ6Y`Uyk8Yl zRmDtCPoKq&|A2B4hM(S;uw_xubrc+ffomu=eaKsDd!N?O+RtR2jIBAD}1mJP=&ITMBsw zM;6@R-{13$&?>dM$-aP1Zpy_dguF#OE(G;Wx;&z+8s-nWiR z_;|2RFjICOjPd(z5jj1*DLOuCOs{Vcua>cE9V@id%lk{kICe%jJFxhWus3I_dSS3u1}22c13g1VeGkSL9-3a3PxAq;7f=tJh?8y$4b(1d>6NYo zefkr)j}$9*Iyej!8D-Xe030#W>z-I+3#xOD)%B~4s(lS#M`r&P-`)h{l4V$%&aurH zV{4necQps&@{LUYfD`bP-DxA`P9(ZUH9TIO2 zh_xHqV9X6qpRvCjnW^XvHzVwrb6%Z{B)C4DBXX!U=K=J6P`Ez`S6m4r(!tIO3)j@|9^;}1Z2khGqK-LIFY~fb&3vS)yo1W z?2lSZ!44*GonXV{#aGgW`cSv#%L!HLE;^@oE9OhRG1GWZ<=dmS+2sR12_3h`%U-@acM9}*uR*H5I^`}CpcC+-GvMNwXvfW}ahejjYO)aN#)FO9e}HXD3- zktqT-@a)EH9e_!tpQ_ifm(_Z>(U7Y57B9lCZ+RA=vHLPb6Oyk~%N$o+Os(1YyRng- z)8U}=H-S(gP~yxod-*TanPUK_!oa}bVvs26VnILZpD^_GH_#)~n6v_#JepY!!U`(m zGnR=3eU$JAI1dJXOQ6i&V0m+Y`RpF(BVgeu+K@ZYFQ&{m>~_SPhKpkjPCa5Up3jo2a#NC5gm$hzHY)k&g>MMTEWM^_Ja1x^AxtUszVf2Y zl{!+ZN9B6!;U}JnxyAv51*E+;K7WanOJt@Oj0ZyMr!(L6blyRL%I5HRpqJ&jMO|%i zejlh>3%RFH|8yaMn&zm5>4fS!&RfJ|dc;o`R!gBU;=^A3BWHPNPd zb+UYe zX{a!1ol!o*8L+P}mjn3Rm%S+5Hxoi1+~gJ{nK{r4l}h^?e)~8k0Vs9|w-*?&5C4+& zSWTM^vAg{NgfMY9nvO6GCrts(|M1ghD<(mChBC0QmN?R5bO4Z+``ZXgh>9=ykK0Om z#gaImYI_@X3IfE%U6D(aHiD5ynKp18Rb1NaF6(Z3=E1(_<=Q-?R(JD#33(+9I(IVA zs!f|RV?o%OG%lzi=S}X4*xa~Mt>>ck!aFX!5Xhu!U{bhmChnH3T0Zr7*bHvHUvp=+ zT1jME_fYtv2jEtM9}QatYZ&BTm97|xh`^MT7+T`qA53x`g_M*423r!5ROtu&$J`4= z-2~n4vm;4=0fgahJig4E*=LRGOr`PkT1v;2ABo-0!wvCjzuW(bs9fP<5xSrJ#v3An z(1G)8|)6gLRG;knx;3ki8~|^q!EXa6jMj(S5#C1jqNV zcE+11I`9=Fsc=Ec=uSnDc41FE%bAOBVT&mE>`xY#u8{NQCMnO@MmHxx537KxK(HJXfOH1)M9|2rOs9XL=c>+IWoM?H)us;|ND>FaK7**Zec}AydZU>vIefgI{^XWO-;i?OHPcWBr z?92?4{!G_d*<|Zmps!QiDEMs~SjijP+6#Fq@1s7}n<{<7*V`9Q!oX3fwXGU3x20BO z(dFUSHySRJ*tj?mX=!-A_ZKFBPlLy#_i?*D`q2IW{c#8h-xr^~@RvqcpboI=2gk_t zl zmoDM>J;!iCQ`@-nwr!zKNMjpqO(=)z9WyY9^ea=oL%%p{tQN%Gr1^sUuDh&)2lzJp zqn;HjqYMs@)jp_Eb(8^mCNp?X^fa2u?dfuSd-O451KlC#*QZrJ-CY&P^o$44nsl`u zYLGO%jxqg*@s~sHgD@HQjiJAhwnP^%INeR$4sk+kog7s#L)3a6=8y_F)m)^XFj-6h^-=4ziGw)o|diK<^ zAN86T9o?)^&zyQ{jj2KV`<${HG6+fJ&u& z2atY{a&zP8d(zF&`OJ3ebb@6bep0N>xksR7WsNr+j@M&M!elanzhAMJbqpp3(xn7= z1vD-WCkO~0JV-D=sa?Ii&`cDF6V7~(ls(I#&^4>c#nA*C_C2a9-8UJLi-PZbC!huY z^i{?%qmvyKF^@DRJ}EdqGTNvetpZAU#i)pV>~_CP_%6>l$0hNyWm^4ALRk$~?4C3x z`C}Yb2dgr6yqQAP^5gcsNU7@n3Xkm2C@Ix&WN-m!h5gd&f6DrQcNxCO_5!j&@g;qt zfgWl8uT%{OX*B@>jnrava`o?91^57%{o?m&(&`Yz)MDNZC3zwz#O(n7KkdDZh!h6K2G#o|EV+9EaIuem z3S<>5Nl8f`S=P>u!PDL8a86XbbkqztjOLEOb_6vENgz;3dOe@Ax!s)%0Vu$P+3>k2 zZ27iImVV6556J<(V8Su z1R+;zb3$w0jUHS9EzBE5)Mw3Q^pZ&Gc5nS}mLqt~*0|CMR$9;qu$}VjgFJ0Sk9+)! zO632Ly^G-wS4drS)eC=Pu7Af+ zGljly+~z@`E-g+;(z3E0GY0{MI7vzXH^LU){W2Ty%(C4MbNQk*oZ%%TM8!gKseUmn z%g125B^-&*H}-J3JxttfdyVb$0F8#K1wf-=uPmV&ii#7FejIgs z2=rFcJJ2oCtWmZyKPRZS_r0Ffu*!ZG9`aOL@2!6~psv-%GoQFPq#cEHZS!)WI{nzgeVT$%5F#}5^yrG=K6CN*H;VyX+BC{ zwe#bSJ9^WdAunb|B6c=3!fW6$u}KfY)6j-K-BDnJZSahOr@@U*!M z3|=?&jUuF_ECjAsbcR@qwHH!?9HR_VX-S_>4y{KAmRP3f#QPiuR|lI`jFd8e>^P zLPC?7!sw-Fvw(#K)$E)c4%@9>7N%VQeJ4esJP;t%F6nANtSiTR^JYZxY7AMga|=k};=G<(@~XP@N897- zc>JUbFs+&3nXP%1U{aavApc=aVGUMO!MT9-M~0tdt%n4kFET54r+FVj zSrMKKy1vC%wi076{*!%|@|ywE52QE^99+o1_IFyOmhHMN2o`Bwdx-Ubl-Py05{Vrg z2UJ6)vJOlGb0L}CsSy>R??_Nz4sG9|MY)*+%16z;6n^KnNq8_^O5OFJ7`{AQ0(4s5 zmf*tYZ|LkgS}?PEb?Twv;RbInj~|(Rll{IVfi(1w93?G=lWMOenr7LpzDci0F}G&E z=TG;Xyb|LJ?SM2~MaP2VA>H-Gcu&{L5=A-~@vSkY=jb3V7h}=c1MB6l#S>?}kn%@7F%g=|+kk{kRHzKUrtt}?E?tzHR6vV6RhDs+TPLP3w{>ss+ zld5TKo$a}_{q>~rm4>~mvzJhZDWz7Ms@x6d_|h?u%+PVUAf&b#(5#`2%N6rV zx`CB;10D!|iT}seTSry7y-}keA|-;-Eh^p8tr!SMN~d%;(jig;0@Bh-OLsRC(kaqi z(hXAIvpx5B$2ab{|DEF)ynFBUuJy#6^Oc;wB%fZx!4=%5? z3mHBceeIKAav_e2`%YLE%Kys9&EoclzIRx>EjlYH=-OJ8x?dkUP_oYj8O2pBI3JT2siZp;G&}t9G-Q%) zFmNelpM9Ct1r@ni!wNk?sqtg^|0uLPHa0v$=h2^U3-^%@2N1*9Qps+ zubWPDF9o@AZ}7&cT^5|PAbtIj_@2N2>gao2o6xY+iDBVjm#sMRj-nW|7d|!}-yWZl zcpt6hGxVCx+0aZ~Co#dQ681MSl0l4iK4fR<>FGAd7cMu13TBHKp5z*8Xj3vUFqD}L zE_Bg#t7p0l#*lSC`qS{(_~RDKwfp1^IoHeTVhb#9j%Xp5TkL=PLmomraAaU+Ht1fQ zTq|7+WlG_@Q8D>++;$YTIuz$k0S`qL%4uX{mRUR$#|Rv)#1QM-w{HkG2EfR2eHhZo z;L9Lh`LpG@jGRx&R!=5}^x`dxzL=7JAycJ)S$No}{HvkyI#c)2JX2JsI?{3SRdt3= zHc{E9R~g8`%orBsQ64jAdE|Mj#VcB7bvv1jf$I}5l=Fx-bz+v(KF%s1HxZTC^Z9tV z?!928{F@seP_syrkM0{35gBPaYG#^OedRm!q+_#qX=%wkSl7}!rK`GVvDXm)=*I+R za;+=jSV(rZoLl))0x@vc&+~y?em`ik)VB70txH|86whLo&oR`YD4+G(llS18v~&q5 zm|xT4f%FyBRF7@uo|Hd?@h)szNsc`B^PDcl;%IVlZ;7k9x+kvD}KhPeh*}Kr2Hx&z7QIXct(t)^vukAYYTRl zc*s=Z&CJ}~M-y~RW+OU*v{zy_qBciayF^EIf#+5Y-uAV#Klq^AH}fN4QpTmAkOpNV zMw8rCU_hZOxk|IN`5E(RSs53+%8wx-889RAiAt2x+In2=CA$2%qAAK{@Z%GU`UNL3 z31w!t-s8e)Ep^+Y=i!fiOa<>vv}w=R$VD`5Q>?29=|q(KS&DDz@LCP|$PjGOuFp{W z9*2H-Q^D`;KyiFyWb~TP*P*&sp1IVHnJ4)}_jYvksmtF(icYO({`-Ghm^ihhO(`V< zjE)QYsbnAVH!j#7HRqeSaIAW(UeVWV9wkq-&OD2yyPN7tqg3K@_2No^;^)sXnG|_S z6#r=3X7&zyG0i?q@*gujGfx?eC4}DZuSkD-*Ks7vz`aD<4jOa$wB?nReSm!MC@6Y` zPo`QYtsAikj<&b#M;H4D5-0O9Z{!#(cSS>ugk3t`bI>o^zw|RQ0~f|1%M%rDOU+!f z%>;9y9N*g8n7RHG66$~GjS?_aslbGDblX$!LmHof;n8{N+4!JCZ8~2#4X3C*II2C}_~Cu?F>7erzLEJX{}h2DFHihWz&y&)1>b11BN^lLKj``bt)>O>YA{}aSPT1enXO7ie2x;lpXR8->OfR4f?U2eW6Cj6cl9aQ$ClCDczzsF;HplnC!21 zym_g-@Q8xF_QNzQBFdV9ArIo{U!I>FOxgGE{niha{d1+%hbr>*uwnnRg1qcc9;NUS zR|+6#A&uQ5Ab4?ob$K@DgR?fg`UmqXJc3n*!JkCTXPlkicja6C`V7w(H_?e;0vl7@ zu2U89IhSd{-!4(@u>9;SsHo8D-y>^Is@xGelr_>Lx| zLh#LOiX<8iJ)_LrC7Q-i_0E&O0p&}5V-@=4>ZZTU?%fTYrhNA_^7LHea(CpZ_A#UO z8pZ3Z-R-h<8zQP5W~9SI&lOH>hl_<_G_=@0A;Bu44+EdK58Z^~IoGN;j&MjQZof4g zt-C72py+&$OtJp>^x?63K7OtLy*&rEDWv?#C))87II>^Uf46wi`3_V3_wqK@kOeqhFwolD4~{^R2800SNU z?M$7^lx;@_Lu;4GrXaaa0Tw;k`}VOJsbbqL<^}arT}i-$N{#zz>F5GL(ZK?YBqOOmow7>G)5*oC}8e{vlsP+$naGX;MsjQZ4Yz|y`wk5MVIeqW4 z#j7@K@=rwf?GD+W2j`9-_9|{~Ed-h;`<+_4u^W3^Zy>+ETD=wHHPLvuL!(vMxc^JX zx^0*vcx&mKumQhOzUk%5d*$=uSI4{gr|bFY+gknp*cb+LFAC9&_qN*UUusualx;1U zGO>j_28{Qa(I&}W;mw23uNOd} zgg*HJGx=PU?#>iO6qnrb2RrhpNQFECv5z&ZoScz>v4&+x#qNVK6}$b)>)Zb3ZoUlG zK6a#0NnZ`TOHwdJKguf$h*XVloIc4QBxqS!T#Vy3Cj@EOZ3=-X9Ff!a+tV4knYgLj zHj*fpdWXKk`y`X??yutc!#SPtrrNLL$2BVZ1$`~G+khQ>U@>HzmwZTa7W2GEO&K2t zrJ1FkF%eriX5}(d_rj7i#gIm?LRJ27rp#hJtf6P;Lo%zrh{4ep9I1|XCyxh8&dQ^C zQN8>d*K>icDudsQ$`Zz)$PBNjG?lX zZ+VR0%;|o8Ce`u9gKgJl1iQh6I_C+Pbb0eumF6_2*~COdv{+V37`xm0II8SU^==ZY zk!+9rNoIxg!e|Y71;z^({`~10`TnNxI=L-@Y;rg2Lqj{ayo3Y>ZDb&nR)aO~%n|C0 zj?j|nN>~lZqMJk0N5m7pie)EV*tRD)v_BeCIrF}}k&O|laSiAiI_JWoO;=M2)u=va zbY=S>sHjIu_SN|mZ>sv952ie}LPR77J`qavr1ZTfS@c|k>#rmvY_-|tosN)>V-BWt zayUN%s9W;~LcQT=j?&@Upbw<+g=MAcll6C_+taliajy}2QQ&4?hUUHIl!o(^l&En# z_a%{MN;iuA>mODng|ZHVz5{jBA$=5hVo@~w9N|S|uyy3$r$$Xa*ZCMk&*sfil1PW9 zXpV0&i?oAc+hicuWuA&qHYvZ7k!d&KvOC??rSv@2rF7qYTK@3+A2_UEUeo?6)R6^> z;fs*VW6+->s!sH*9L_d&jbBfBEM7IuNJ{l@$@Wk`P+XQ18$kvewZxvz`%P){*g9li z2XT#yKPMzeEw&pv#1fO@KO1w> zMHPaVGiu2s?bLBwFGlFO%-x$6>(Ye-=5A3iUzRw|QQEz8D}Gf6KYLir`;rpmwD}7L zseKzbk|H*@O^_5%0!GZMOK=@YCQ-gJ=l8zMYB+~RkUH;fFh159zq`x~d6 zmH*uzeAp=Y8kIw7;yAzosH|inL*iC}&Zmbh@veSr?jJ|q*TY;<)UAe$UvQOJxVZ_a zcq>KAk2c$GsGFJP;J4;Hm65p<+;HtjmqME17?qQj)sj?`_)}Rv?P__H@EPFH(gMJ6 zy-W)SAd1p$lViJjl@jq%U~G<7K!7ylWh)4@B_K_Wh60#3TF}QFi7&<{ZfCcjGIKM{ zJ9Xey)Aq5s z?&zO$Kc;kIWz;BK`bzHKD5G)D;roZc=odMBe^@3&JqnGz9R7&W z!p5tvB&V70j!_d^j&FI`PjVJ-$r)vTMpVfeo3o8nX@jpE9eIEhcBsGda0XF3?3{o* z6blH|`&5|)QcqvM8kCR3yjF=5 z;fi=fL;*hyS}b_%uP;wH9XD0~`_MPJk`g@k&iaSzo!@y-Z?mGD9{v`1pq`y1`LTux z&`hM>lyUL>d$KQ@rPHWsXflEn0=qh2W9rYh7*2s$=BP$I2oad9SNoD6YAPrww16&s zZM-xKK2ly&^EJ#en*YlCCY``jclCF}VaCdK})a64CdwNmJn=K!;Eo@#TE zZtF-Wbb4ZZFB}}Wn3VJ8erZ^PJ{XU<=hH=-u>tI?^Bue)qo~>lVZC?M&#TN z&t@k2AR+3A#=+4|%w_VKs~a5UwHm;lp8V0eP_{JO5F^#EFO==<>`r^}TfaRpc_lJVh(#FIy<-}i68);>+jG19@9eR-@1*VQ z99oF9{SNH7ir{m|3)3B<}z#IzfqW`^zM5JzQ1XG3xPT8yjG1{8*!@BX( zf6ye|cCr0kE{8iUE}8?#-BF z6W6({?M(hY+(TEdGa!KPf;*% z%wG%}j$*TS;tu zp1Dmtkf7m%edzk5Q#beW0xKcwo*DaY6P*{5O@RqP*e${BxV5U)Vq$Gl(hto8L6jb7 zF)L;(v*7_og|y$Za~kZ$MqW!uNK~1Za}|8>eB&89ZYc3sFi(9Q{n1vKH)7&4F_FA{ z5i#e>yVZDo$p%w>G@vk8MMNANh*CF`t{irWrdZ@((9)Wf{n1VOcS2D^92<(Q_c><+W#$$S68uq2RmuVBU;+Wo)^wA#F^um&ZwV&d9j$|BiM9I zPM@OV;tb{}ux&K8v|Rpt&srNR)Zxy+hftEyW#o^%Mv+l|D9nHR%8ae{S9_7`8zJ-A ztw2h8hKi!&Ncv6tXL%P_eFqtSMUzw-EzQp~RIA-7YH`~3XTG*0k)Iz~u3V*5FL=L; ziaC<8y80xIOcnk)=B1uG>E!HISeAZW6{!7)yrufbFYZ--i51%%;~KiNH0!o7PDRvq zN+?%yq>&nikL23!Sry$Ym8!bCLmy)ivg{S+_*H2YH>gMB^qEmWpa655MSEjgF;-+o`%#eaor z({g2KX2$4seLj2kC$|v7CLN4l#fri7%9L*olfM>^clwJHi8{WC{=HYSC&oH++Scc3 zpSCu}qp{mi8}aHp8(t4i8zRXza**qYKb2Y}Y_Ts4$;!CX)Rjz=o4vWf=wyi0@3l+5 zCA6u3;yiygRE)qRs_&sPCyW*+-(x~ke!ge^!NVo|0};+Oo3}oio?4?bqgKXzLv|~~ za`XW+hO+TjOsur$viR*Xf(0yPuXqx2MY5|{C%x|?0lX!){0O4M^JM};!u>WP zo!wCtoxwsKQOI`U;6^nXs&rJsH|1ppfsbHVU!L z3GT~J#0v99NMa+7K;#*$t|+9B9fXy-B-)cVzQ{FHXuTC()6sHpM$TNKk|O*b3JZf2 z{%1x;v?3xReHg4=>EEasig8MksSsJfLJy?$sqMjGVRVll-wSSQ0TnO_pUu~a@WdHh^6(`uFPs^-7#F4e1_bFK-$ znwZg`+|KA`4YofhG_BL2B;wsM-+AXlBbvV|cU68UDl|M67M$O;uYh;zvS(a(d?+VS zx!xB%n_#_}DK_%JsFWl>b+`5GfSk`Wkwv4zX7e{k=<4c$?e_SF_Ot?>l1d6wENbP^I?x{16=0hP*~W1dT*zD?cc^i?URQvB2c z2}#KoY5C619s}4&k7#Hhs@(CME(;uPy24s6wp3-ZgfO~XoAwm? z?LwbjJe@*A`@-u*2`aHS+$sO#nts&>s(K$g$rxFfL_^>E z4jRz(6oD5wL_{*@e-UgYGa(jCjhMlcbOgg)b63Q47ul9la%{(G(o8PR(qdhqgxO1V>0 znm~Y_9gXR%Pn0vUHG*Tb9hAePKN#AI2!&U7e@0Qc%yU1Se6z)wTle7>`&r~GZLG$T z8STj;-cl87n$sjTcLUAdnUR|n0?Kk{6;w?Ry^=aM`j6}+8`)9WUiP>LWC&&*JWGvU z;0z=e+4NIFqZBqeSTtiZs=K0=@{}?-@t5LMBR%tbY|!E`e1E zOZMT5<_tqA^>Q=RC!8;I-)qa7cWf4xR54&ilDX{qy!09G$3d#^ZGYnAX&~v3Zb0HQ)Ytc89tv|*b0JR^fkf+nFT+MZZo|9H_ytmp`O6R=7c$(tFi5U zbQ4m4cHNnKv^}K}mNGvg(6)O&n64K#u4wwb)mBq!Vp3`R=)b5IFWAt-Ols*gGi|*% z{W$qxjVF#KfU4P!D}+LjH3|Iec{J9EkLrmD zsi^uRXrvPDtSOKQM0VoGQ|c0xp1)v;(L;>2nw`M=E;Z^UwW{6Xfu?zPe;;TFcB=kjwU zY6jQ@sIp0+QTXFQM-S`|r#P<9{^tuou8Hw|$W3`=R{59p!`| zCni1p5m=Rjh*7ua3&(9Tp4VHiWb|wCPPa->$eMYGGDQU_z??hTWrgHwKeq9A3b59F zu}KL??zbvle!cy@q7xoc*eNDT{evJPj4I2XfUUb$6X|nA)Kb}baF?wxk<9jY#A-z# zRtr4~W(p_(FY@y8`VTKk8VOwz`iJDi5k1ZvxH_)@qlWCmFI(U3wmI=TQAm|-MPQfp zjY}(_%L_tH6A>Td-&k;w{FayLNiNOu4-7ycl6d^H6Nk;k0lI2~W0(3bB)?O%wdJ_J zI%x#Xdnr_Kdk)bPO!~1mIexuZbxmCNd;xVI3&GUp+vw*A`}=6d1d`0Hi$^J59z@Db zY0{&tXMn5Yl#ag+>^;tkeWC21qWnzaDTYyLoa5F6za_b?M}cpI<$5QKh;?W=O#@Do zpscF;u}$x3?&!kC2Ds2lWfb=I^gLo?!_m>vA?1k*n}c4PksRh*P_YOTfR{5bV2oRy|!(7%0v*HfpZW$U!?Si(#E8w&%2M363bQyg~M zF6B8P%&irU)@#Tl@-@T!D10*V{rmUd$7;I+dm zHV#`A3dwn>BOC6#l zWn^dv0!v$v>bOX!%GH4rO%e#rCRY*o9DT0~#NE|^WZS-brzALp4aJx7_Ea?xi4k#e zf!fyB#FsGDxm-S`om+ID$Lq=+a1egiLwd-sH_^~a4SwEJFEe@CpDdiaK?7xLlI`{s zKWs?YC(D2U!GRLndNpb^+u#A?Tu{|Z&iVANA3p0~l4XCte^@@oF#Exh$>t)5ZUsp? z311liFMb5zB}qde_);pNcYX0DJ?77$=Z)=rm1orPA=3zN8xrA~Zh-0=W; z4VlkzllWxXiAwbH@J+SXM;aQMyJTeD^Q{5n^=?k<#h^3XhiXQO18#7z8ffr1hi(dp z;9Z#Nw})Oc2Lc{GAtCTkZT+Ixuc10}*~qUn8P3GsM45D)!ymX8Rq%v=YbZ+ptp@s! z@&2~^f)e16#VG;LlV?0yl5iC$2I}!vi2pPLgAA3pVkj2NPp%Wa@e;$^B#)OS+8ekv z6%_8ll4ba@zXzfvB0RkLXCz&By%hjGNYHl$-y!FFUszaZ--1c~oT407m5@#Q^{ZFt zV6&J#^7yFcEzBFk3fjWG7VV!%>>U^ivc~1`%k0M}W@rDgk7cRw^hc0{$Akl9w z2P<{gSLfw5Cz+5Scpr1VhHqg!=3G@ZP(>P~3q8LvKmb#A-7GRxvYIJ(M41E5i(|@x z0l|lS4S81`)?2OA2pjYQi30C}00JCcW%?X6t7yS#W4w(9G z{(y?b=kb>d2@DKBk#PE3O*3kz>_d(`0Mr5}sqboIV01KkU_cIfv4z7ah^Yy2uW3Cm z_Qb`WJwrGKnGV;?u21U~BQRc=9+{t?|3o1e12ObFg%p6dDF`(7CeqKqKw?SB9LqYS z{22UoGUYUry``n*W(y;37~Wz^(o!Oua^1*xKO7VX5Dq9hYZIeM{V?Hnm`&mHx)K68 zx6Es>c`2U-Hsd3N&4F*vK9O<<-F^5Hk<;_E>*KSt=}CF5dZ1loqFMo%l!fl!2ZI{K zA;rXjmxLrR zHkJs~WQ+jEC<#Uk)6ml111*83COJ^Q#(@5ES^SpU0#`|Ds|fs7Ut9wtqX@Tc@+->G zla)T%T*LG6QurrH>eO5EHZ(NHPv_7Ono`*6|3LQCTX0M-zGj_LZ>p7f34LO5004Y;@9&2F zfAHoDxFDs~ge&69mrfXPA{KHkf(Db7ni@Is=MU(Kh+(<_+MgF1(jH2PkdA{0NbKN1 zX88Pt z2jczsW*b8x2G~Aa_b}Y(K=te(Tq_I)0}b3GAJlIIvzD!rC7G8I{^XXg_kAn|;vW?4)O9Auf>sSCp@gkFrYC z^P%uV7;lM*i8-&t8JkSklq2v~F}^r>Z1yS?)<1jt+ADQ^%%~=1({%g4zgb#Y8LF~f zG^5f{?4jAR!t7&Pg#8hTC>cgjy1~(HzQwQ1ax$jz>ZtH0D(ZKNpWhKx=TCzLz}7)o zk_--UITYZK`J6i({^%%i+~QV~j^8qlXDs(%Agxo_I3rMaRVzHKy$r($w?>Aw7bL7T6xC$x@P%4+f?wl2R4V ze_w@W#6ehsE#e)-_mjoaOCQQ7GjRZB=O4jiTTHkVR8>1c=&?RsTM664?DFpsEDKyt z^aU(XppR5U1Qc|FR~)ZDy7pP{EUIYUW*xm={Q50*E`K<>PX>=W*llOW#@4jyAFK}E z3N082C$kd6?ltHx?%ur%bz~03Pt&2HA@;b}n=|zZGxctqfbZ4SLvsclrWnnC-&({o zv4F7$vz8voG*t&rYmONCX|3~8INeAnJTx^ZBP*-)ZSxIqI_%t?Z*^Jw762ugB1qJK z7(AX|UTy=yifoFA#|VP95;H_Rl9Gv;dFi>UfDdU^ZcMXm+Wg$lNJxLc(dMY%vCU|| zY;0{!V{n@FsQd?9D1JluC3becLbwz`ySO$}UkfX;0{UTC5#Y2**xw={#&M>#>Q96a z?dBcW+45mpn#pUcYttG2-3e=z=3_GDmEcW~#tK6g;MX>ZYseH8dpN8>H3kdFj? zz2xWEF7H2qKsUv6oBzTkBy0!pXX8+&57=@rp?%9v{KtJz7Qu5Nw$+g;VQfWB zS{D~Q4+j6y+tS--cc@YbOFlhEkN%xUSaCtzn!|#TzN%__vY&O7k3uY>hxC*(wvUNF zwrQwvOrN3V&n*FA?7G`!e+H7Yzg<-+ng8tyJRh@hZ8$*tx_Y)_ck19E{aVclyuT17 zb{M50?2&ghL($uqJukFB z=F)R&4mDq2w?`|f%lytx*atx?-lXoX%&>>2t1-83r}9cDmSVS^$33Eg$dk zQsd!beev>#{4f4*LViQwQXL}Nl+eF-Ng?d;F|S1|6p2nY`FYmxJe0>7>AtpO>klh- z-9^xXgF1!n{b8J6z0#_8r9~{0cmM0)J50SvOiVQ;n{}M}TR~zaT!V#o-EXlzqR$qF zRFC*^GYle?e*F4u1T7ae*xzKug|nRU4Hm<1$k634cA7Rv`Jw~DMrg&NLuX?3{`_!qVctsZWT=2WZfRlg$^4KiAn@S2dlnNED` ziM;$>;FK>QRUd9m#(w;WJ~j1c<#rvA4Em4bUP(#m1IzS@oL^z<6=LV|{rj~^WvcYI z5M1E*H(5v~lNBsej$|A8sLOr0;G#DFR{n0S)6NPUHYDfOSu2!Q7(}< zZh9$^Tc+Q1TL*^CpHoTYHqR%jJ4}T~dnwOfFEp-gI2)@(L^pNqtZ=SczdSZfTOmj`wMe5DrBdKvb-73-q@|akz{)O7_?9T>6bh;6|3|$bk7Y7) z=f1BTaOIENc*vmQWn%F~Mwla|ViCP!V_-O$h%j^2j8;3mO3ia#YHi>f8HIp@oL~^{Q3S2Qjg-stH!F>z zv6V(4be;0|hj_?eH5R=@iux=)KQ1|ytA>6e8)`5d#<_0P7=^-7%D$aNbr z_nxkU)`rmpsa4PzLW**ai*f~aheN+eOXH^HsZ-a*Q z#w*6eHp32_AMtqi^R}}$Shl%L9~}=$MUgvRJ3ZL(DvlSsek&Awk6+&}@zYU{*OFlk z#YIfB^dV@21|D-D+lOBMrDb`xJG^1~N51*~J21?pL`XerOAMSp~z<}DZVbA;U|t~BIHSc z=9q8rGlykUl_T0}8%g>2rDuCs-0?w)r*j|)ts6CSQ8(8wI+%aRiO!piY?9@4`-WyG z%Q|1rKbTmpt={pwtu2r_==IWfLnE0ia=MK*JxVA1A-l)=sujn#)wkrX?vnM#hW$nQ zI{5dXCwA`#-H-ikly{}P$}Z4Cb@aq>j@LS|^^2TaAhsJ+-H7exaej?O^64JkR>}p9oC0XH_i^$ z$heT^LN~Zpu}94Khx14PMf;&wJdpYV3xEUf+*F%m3z}b79~o7qtT+m+s)a6!xX1}p zGwFW@)BM>Q&$HdcCmFCL=e$1R?>{-Jn|E{JIcR@__Ul2_=g3}?Dw$dKTK~VuLPwHb ztf9a2W(|_jucL^@h$3RI1vT__e+cvEg=$N<-lYeRqv&w}95Utp8+F)Ck!SAlU5e(o zh!BnmpNa0Ce%B*pgk9|AoQg&MQ!31HF_-@w=@oAlGVfJ=b}-nMe+&%#27N)@-#@uv z

Q`R}!D?4d@xbR=R32R1lOQ$>E#1vd%sNh zk`pxv*rcbB$oy{3)I=bo+#2~Q`qei(A3uq=IZ15&bEN;c#r%>8-kV$2hQsExSJujf zWQ-^Tst3h{kcK;-dwh0%6X!@*= zTy_}*8KYCPOy4hke{i-(&X4J663)juBAu{3# zqI<(oEaU!Bzq0Gv|710Hr^>!0{U+OsZ{Ddzxw|*c`%~yRIq|5dQZ{CuDTcFxmp&FC zVZIX*zPPc2uAxf@Nyp>yZFIjl+%{j$Oh$F4^7`WqoZ(Ul%bnS&>S>Ct@BhebZjNS6 zUl*>Eie=GW+O{>VoV#Hz!n0qzGETK&F~ikhh9>@R*g#NvqDbMh&iZez{i=NYHy%SKdmL z+pLrX%1$(S_aq7s%WewNT4@t#te+DQS_GOsG z)CTZk&S+}pD=Q{STg@mHX7QyYZi*ps@vsSzDY-h!heEF}a<+swQEuJ=!BB$^OBd8r zD*$(|ZjP5CPB&CT|0NLxKy5y{c3SZ0XMcU#Km8qlTPq?NIIzB3sddO!JgGGa}35ijQ)iOfi|DF~Y z14Ju|4YYh|gPqVIIzwwiEaF}@5uT$72m@^-2FURN)$50B_8(pliU6sPKA)Z1UIYby z`#^g(+Dm|LV@nOF>lXcy*j+*^)5cJQBcneySq_Cbx_9#KmB;RdE4Fc`?tBmW1aEwI zQNhd-g?dk2qjl3CzQW5bio$Av>nYn`Eb3yJcj!y(7`bDVf(dt9WzKI%Bx#_BUF-9B zSiiNC_PlbvI$tr{K5uM3{WJGt0q4vvtNzjIGUw-+%E<#51h~P{cuj5}9zD9#zp_ew zJ#U2)g-=&vuo3_fE@a5`g70d<7H>AyZk*SKfuV2yRU*l@>H4Rqisb-h!AS$f*D@#p zGR(&c%*1mP+S=Nn_fjs@hJUyG!fAYmnwt8bR8&4-G_ldw4|lXZ@k?hCBU?CgFx#=1 zmPe{7p6uN{C0E($!Hpfvb;1h#{9hs9+Sn-B;aGv_@3tl@)95i-)XUzEWXng_Sb?`8 zKr?nAFMxy4ZCN?}vLkei5Wh=7PVR|1O!kvL5(3AN-G{(@&5Y@t5VL^Yav?=Yrg~%>y#d@5#JNj z2qV9@aF2iSH+RW(S#0&Byy`)fIpwvx6;_()c=z{KEaE9gis_nD`@Goj8-hdI_Vuxr@#XZ4*U-&!qCzR(WJ9OZ%kvrN2 z2D2?dJwbm@pj`1ZKOonQ{-U+KJuiE3JWayx zd=oDv;nkP<_Jh-^*^Vsv#nZ#_arep&j@BMdUk*-@#o<`NsN}5wN3pMEwD(t>_Sd6F z_i9=0zJKZYZAw^IV5fm2#!)7Y;8s3e&tiGTLuV%sfnTZQ_ZIK1&nJG%8HEZGAw{C0 z;Q)OSI2Y!D6e&737Q~Qxpg(cgo{D35lZlIupYF&EYkTDTZ*8F?CVkOdc#H7qg@ZbM zk#U~6)RTgh?d?7YM7f8_upU1;bi88X+)gn`xponXg8ZSqBnDR2P{0vO;ku_#%5vWO z0(ML22wz#)ngo5g=gYA=fXZ0_I(4WG?Z`5Cur7gGu61;@yk`S(r6xjU3wYv(HofNV z?qK`XzC8%M`|xKmZb`Vj&xYB3F}!rzd|i}>dN5S&p6u;DsFG$+R;f21MwKyYJ^Lxs zJDlBNkg892;9_R#OPM*N-GvcldBXh zJcaum$fRM~l2>cyVdlba2Y&^y*uLNusUC5eQhrK_#IznY1iJ`#xI+_=u)WI0%ltlq zIbO>N-=78#*x16vsXWS*FGUb}llNcVq-9_TM5=Fid6hCdTkOEe!0^3~sC7i)6*)3X zCBQ|IX5!V50X@apuKou8ml&IY+}=*cst7 z+_zFY`@|hRYGw$CxW#yh9~2|Fckg;<-m2g}EiEZ2fs0V|0MGaJ^W(6Z;=8yg&^l&9 zK!+OA7jCNP^Uqg)Ja;!&J-7%aWyI{&)PxskCjPxt=x;%)MC6mdCp(3XQDk=WEvODP zCD#f0Cf|WOz-Z$3dQC_$Ub$#*&(!EM2*k-xL^GqRu0BC<4Nq61fsF$A6nwn%{!cpd z>3*;TsdZ!lt!h-J<8sgZomD5L+44AV?Esrapy*Y+!}Pcp~7_{5~ax3UGGtezG~}+ET2?m7FRlqYd7PacAo&cqsvtWn;p#J~xPxG-*z!Qd`@CDK%E-DHiS`t{QG~gZp z0&VC!K}Bd_4}etq=$c+sge#>?c*R`=yix-xHrntoOkXMrN+vCipU~YvnZTu_EP$mV zBqV$Z+#B-RPzDy{1Tf+QV_w(k<)D7y6LN%4EASPG!fr7yLr9U?T^&ez16YT_rx?cn zW#G@G-2AmP6&Tvs*J2Sc|rVg4Iz@6m?PiG7~S}1rWSwM6K zPrU=g4GjmAo3L&iJ(>d zg#1+*L%H-;*Otvy z&POttspAKZJ8z^)Y~&@WCA&xat%nqQiPoU#fC$g3S=EHaRwu_KnoZvi@d@_e0-!U9 z8(*M8`+2SwN?wVeTWBVmb3-Tn!a; zYF;_>m)Y`Z0IK7IucWi9>%#i_Synrd*vD>AYC9qHcW}GkJ=pxf+d)mz16&D+y+|O1 z&PA(ee}iuGU-?U2Kn)Q7pSz{wpHg}=9Y0~Zm~(Lrt;5cr`tJBeAa%eP1zAMg<#b*R zPC|Ltq^$z5CC?$n0^aX~hLeImHT*vID680)tBa~Smy|J&TS z%m3=1k7sN0>fb3+?_IoqG%jD##kExod{xWZ$oEJ@370xEQRl)5O|rAIGrPxM2Oy|G z3q%8p_#V*ntQ1d#_j%pfNx*hj~#cYIVFA{@9O`9@hToe9a9YU(O~IucD*_6 z@+4|`=6dg>=lz{3Y>BP~u)4gzLV0IfV>=@*?rpqJjA=!-rBV0KWs6aJnZ}Y;e*QN} zdPO}Mb{I6=(odx2AN`0%e$<4m_(3;mmI^&k@Z%Ko?3j)X+t}q(S@Kh7t+8HcPyX~w z;=@*!GBKey?oVEZX-{LAua`u$C)C>?qjbea@EBZN@Ck?(3kK;amMheAM&W-VH|L%t zw1{Oaj_AE8TPu!hYPy0e613OZ;XWVb!;Y7Px4(4#?H=gzA|cZ!+fe5=Ld|9p<`h!!gR?BSpL6-Xj+m8 zhv|8~!ZS|;u(UFls1S8Um5aK`-y#(GfVYL?aYFfU*9z;K`It=>uvg>L2>A_~qX(m2hz}v^L9IhaYJ& zY8F93(HxWOkf{Fsi^Wv!btljjCZjpgL$-*m0(W#YS@0YHhrkIlB~XWkhK5RZ)R+SS z+^knz1lIxGxN+mlV?)U#S1h1^KmL8u1$#a4Q9?)>51IA2g`{}3{?9w**Rg0BzXkml zf3rtI`K`JR*uP}W+mLw^Jz5@dxc>cg=$Del-cz_RS@L6Zd`xgoAl8<-1cIS7=g09MxDx1d*nO{SjcAP}#G*J>rT+S%;<7*oq+Rj2U;P3qOFCWFVIG6;gm z1%0Wcc+NfOLII3TOiV;jS;TyDGbf0-C&$Rg5M>v_sdyPFzO`)kpQF?qD+s*IUmD*M zhkG%Cb8~Zt;H(fhSarDdBs4}TaS(NfekXUhDRNBfb@^80a@tzdzn(oQf2Vgf`lOZ5 zVY`2k5shM6yl*)Phmf=2nMAH3U9h#7I=hD@a_FD!y7LWW?b<&t0?w}{Rx{7ND6Sn@ zWkni42%FNRn3JxP987iinlQ>wjoOj%STq4V(%|6+mo0|I#>NhXZ>s~@0hHs9_IAW% z59}h7q4dC^V#uo>YiSLk<$2#;7Sy-b$Uu>%z!gcUA|RH(I7j5;qb~v_*&Em0)=wPU`8#v)-b}wiu$n?E9^0=|Ac^ zM5U?S4?c`ZckowU(P$S(;p--A5#Bo<7G3x9`gyxZ%lebvk9`x?%Z8Z7dXo0vN^eZm z1M?h9R8QuwnV4Gq8*7rNu6_mhH;q$Z5sUowk-Q`s;Q`JG&J;rLinyHvQI?us3j4kq2@*6pe&NZX*#0 z`1g9HoM__c4VzWZj(HAqY#J2vTRbH3qd5t2eaCURlVy?EP{_O#E=#qzQTn;g7W;18 z8|RUX1-0N{$5M}TL!?A<6qg0RhzGZu-VJmM37$SQvhFH8Z7N5om%5?DUkAt%&UYGA`9M)4EU{nWpA^9`dzJjbH5U*qC>r<2rU{e|CH(m+- zYKaJYM^Q6;oMRtfp|85T@?|nqmo12H#YRG6dEklcDrIk1k_z`h+gL7jV(&vb-sDBP z_mX*@rCD@(y^Lp7wo;-3Q(mK-Hfe6W!WIJRd*0^WVA2JQd|*h(@_Yc*3eW^{0z+DY z&b#+vD}x~gJ5ZgJUYZs32pLj@IcgAmJG);9fS2ip{)|FbXnrQ|DlF z>vkE|ip_{HicMCodZP_i0-3e=--Vjy57{b9bS0lpe?5%r`MSEomIh`Vj7cypG$`%+%UO({{;qs>=vTiJJ zXUzC@I#@3y(W)fp?tAIR*_Fg5LL_k*7!j5*GZxuL@x+fXzrp}Ug5^o+!Y=t;ZRLdq zZhmqO&AM>ulX)P2KD2#-RX7jYL}$=L{Vp@b16N=p$V%lk=paLT zfEWgY4fSJqIMVB4kxJno_285aq6_%0*~nbewENFvBdXt$?0w5aFTe4Y?X~fi=#23w zo4mzjO-QixRG~)9DIH6ik&sJs*p za`TOvKVP%y!><$8gPl&ExH{|_?t9%sGO>1!*i2(G*x6T&EguBX3vn*tyq@U&8t(z8wJd9ug7bnkS!B!9PNxR8Wo9Cc;(as#<8Rb zMRNu?%&vrLw5wNRugRp(?+CLySc{*0A6z>>k6C7@&*Fie*9goeE>=aasX+_4+#S2P z1JNf>64BTB;E2qLUZ3GyU0oskJ>iBX&3}8>SMPssf_j^(?9<1OvT>K6iF%7{_ut~9 z<*RX-ZFl<;sgyVlKXB!3I3i|r_;h~a=;$dB5Z)jVboFZKi32{yI!}DrW?vc>%f;#N zy}uh*bsfbAdJPx-gY#*HV~hVb9*~UGEF~Y% z>7BAji+2W(h(a?{&6{ONAaDE+V#u}isaKT*&Q+Ao)1ET@35}bPZwy` zhH9QmZ+JjY@54lxmMvNsr>0y8G#9#GoU?8f$#M?>(&8w(Pt=}vDd6z zuUPeCaIpTs*QcO(90tu?20~PV%l!eWDd;Ss7EWS6pIqI`&{zDDbApud@T0)X4Etw= z_O%G!WEg`9n|9Y{7#^Lh=(tS|Gy7R%Fc3SDL7K zx1n0^$_*C`_N0iWXxF>)fJ_>r97FlJYJt3=~fxNCx0gwL^Ug zO>?s6U(;LIr0EXnl28iW2NevQ;>Ttq^iVPkm~crVX343|$QeK!BsM~PCz2L9GAa}v zPA6$BcXoPO1TqpJ@blr%OI4X+3>&##yB}PA&5r!9;SYb*BWex!58rGRM7J<*vC`y? zf>6WF&5`ZYE0ZB)8pW!wq@@j8d@)|fKf3-3<2+(hq5qcY|FHGm@mThM_%M}*l1fs9 zq#`?ttdv5LP*#ZSRrVgKJ1T_AN>pVZ7_c-3ialDCY@)HJ3px+J*=n!ul+l8a?Q9vnr0`Yx4i2WPauBRd1XzH6?$WVW|GYYuzu}e1B$-%13*&Uqnuzuo8%^;ocjfn7K`%yR zM0A^wC=d%e{#+~D7yr&nd#=sc9!P(Q_zfopSaQYL#E^FtyNRKKSRn@DVW*#h>G=1_ z(ENKcS%jSl{y&h!MjFFqz&%b{Ie^s>6Sg28eNSgQAk4zD1+N2ZnWyLGbisE1I{%C9 z0G9B$@5=sN1rTTa6wvhsT*t4dtbnfPiKv*!IIqx~t(0m36G%}>Gt6ccAa$WBw`Fgi(V&=^(& z+UV=Ual1}kH8L{Fea0>z5R5)4Ll>r2|NXZCy!^Tz74^PN?C`$$_h?VGBcawHQjWDH z(V*T8zhd7M8S*T^T{D@>zW!SBvGo7+RiVM$=S>)Q!q5{ub&ISa8u3eb&H78T!wGFB z-|d9$@>knHgAJSRCzI%YW0*fxKFPN<5a1lQs{(iSR-8*I%S(oPtt~khhI;-NeThrn@T-I5AlEDfElnXWH_Bg zuEHP?f^@3v{8TaTQc=|@;uFNcD25Bn7m6uP*H-ZOSb&1@f|*pDt?iL;4-V^Kgy1kd zi;Q&ZarBYApOnN-l(M$t?c_&bANcRhQ&^xg0mP19OicB__GNv>46}iej=kEkFHBFO z*w(NY;o{oqUGX1~ThMaRybNnr?TxAwglB}<+D~S}uoq#8>HLE<+i_(mYim;!lG@&y zw0R*-w}6gK)=JLwP5AF8x<~Qf{#>r2<|>29Dg3j3 zBn^Ihy6PvOO~CUC=G)bO{`{$^qR3?84!AxYCVLpFlT6Rdlr%I@n46n}EnQ{R@e6M9 zEi&9h)ViR^+caD^hlfWPyqFNWFaE>lzz#0VLGh{t*1`?tqzh&xCAMObAx z=ICPO7#`L%)T= z$tyRwON*cY829a*SQtN3?Br-P<|rj4Md%dFHBV8bFGdN+AARO;LNho zCrXm<*fF#;8p*9<*JGx2GE1!i;m~ww@f_2)?SGGGxu`yl9?WeZJ;k*nxUDuZ=Nq1h+zn0%DjxIRyOzbt!{g+;3O5zDv782|Y)h)QE; zRIRV0lT(IHg_o7HyXSarULIljw2OvD%F?pt>Niuv2Z2|U+H&x(u?)NwsPMPP$K7)t z{LNzn5h#f&;1n`cy_;~BVQ~GS5X;=72vA3&qQb%C!IOO?G?M=!wU-&Oi^}Yvn)j;-$^p3cce}7#G`N^#2b8Zk@ev8YG;n z)v2+L(S>akY{24mMZ-O%ka>*7%qgz1Y(KJh1u|)%DZav$3s#rWYpc zR(@I*t^G1ZMPO-TGlWT|9uD@f7mwvA&`5Dn8jsjTxXXS71^PV7uI zZ&^AKM`7%!(!|kJS>*Sh!^*s^YGz59{fSWB;4kTh$Ni6S>Po$!V5wqqvH8JrY(ne8 zml&lTPRmA9)?9iJ8c&`yghZq|mDI-H6X-G&&bledB z6Fy#^m4;3IzgqNlITAc3x&-|f8U#r{1{BO)UOqlV6$`o7i$ulx+cwLt@4J=Qo+Y>E zJDDknvzphhKYm;)oL{u4QOw3!=C$^zdU+~^Ir-CjnYfC_;|cLT=Y_PmwMrZL7Edf> zQ9kD@-!5iv@r@@Sm)miG`s-EwCYrWU9CD20TR?@#&@FUcjDss9dED!8FK=%E3CDPO zpJ6yk@&SS;sC3RlG4>Npvb4rySI57aq&o|8_G#Rt*4Ikx zy?2&x!@(ZigE|`r#}RZ7)6*8%d~&vIGsRb{hl@@oC%=oizQ76ms1hWr9H84be1YEa zK$nufYKgDFRtG!!U!KR>IZkQVX6-XnS(FwXHTaIEEc4av^^gLCgR)L)Lq3a3bmwT6AN;7i5E`e4Hv1JtHD8wC^M$Ly~ncLJXEiLsk0YKBC8fS)n z0)&1IjWrHWTOoS9MpQ8`_;1%1IL=MaJnak+|9Igl6ct3#C0$onht!@4i5N!IkDHAy zL<80z4?>mpcLbn6J5(bw{eEM?OeLMeX~CZ6RR&s$;-QgeAW~|krYdd@Y^Ny9R?pR4 zVxeobn9vdG@Op{zuZqJI5wu2sJNHfASl4P@rg56xJ~jt8Wnm9^2{8Eor*rTCrw>s z<4QU9P%@Of2$3077XA7yi9J|Cv6$F#K0n?u2cAZB$2gdvT!`{YLdwbh&z_0v=^ep< z6G`q1yww2O^X%UtusT(QYLqb00;P}7yjKKWwPr)2$1Z#6e=*^B@#+E{t{?ov|CWFO zzBV$!+*-%*!ZCq^zK&)ehw53B=EM|%Wb%b@=&+L04JaRC>(Xj-3M@BI`mI*~^ox3) zX1}3z-843&L;TL^H905YvkR{R>z(aRBt`M2eD=O9vs}cqGM?$Tzl-#{-i++U?QyA` ztb&F5*yxs<&?9PjQRXP)U3ms`dZ)Gs?WTb{JrUacJKc)zUiVf`W0`1rob2>qxUB~(STP)=rze=RsC-c3^(?I6kYExFQp}Z8 zG1TJS6#vR34_8<hS`bX(W3=)<5dO2+l@O~g5T|w|4}7ZAY!~vYjv`Yk5T>k(vyfd zy_xZB^XYG)jC|%9TW&9K4Ulf3*Il3GQ$OZXF~_I;q}Be!`trifFe~dcVfCeA)|1@6FV3pvb+ZF=DI96ZY5=~7zp-rn6ssttNdi~d7YXn$xc5$ zM-rA>goI>yIhef=-TmInO2UC$_f|meA|>P{&=^*ts{Tq5idqC{or282@HP1f+ni8a z6DALTs)LhAMlDbQY@?vi2T=yxMs#xJg!#kdi&jiN6)lY8A4-;u<-0`dc^HQoKl0hw zf4zWlm8wZI>siK^3p);Q=JVP7;O&j%i@B8;wRVaxB>yw-RF!$Box^TQn}^FQ6g#ZC zW%;D!Pt7q~Oz(Q3fJ$aj?F0Xhmvdj3b`;HqmJXZh?4_Z5dpk~q9 zvCjtUlJDzGf0h}gSqe7nl*dgjc*1(@VLsq{X10Z??Lh)xF`Gf zv)0i;X#KBevDbrZ8{que*;$i{GZ!!rLQOsJ{X6!~i zX9|8IHR@q`?%8qc_{b+)CR2OPg2{cLYnMJpmjN#%hd44GdrWqSrn%g(o z-&*!NY<|g{>J?!wce(tKe7IlJ43e0Ah{>9u-X_zXYy``b4f-(sDm8w7lmOj@-dM&rrQ^Zsp zZZ<@fP%u0X<<m3Xo( z7aMxzZc(RveLH;P5T%jD{ew{^P^?igFf`%;;1P2PpFy4`yVk~qVwwr<0cu5(4+vv~ zLjC5=Llkti+Zo&wrv5!%fwzEu&@KV!=g`PWlWdAQ4LvhDR%n>`2%O<^h?NwbR=h^% zVqHTC>GuWUI}xGx&v&l6{`!%q@s&-NS!YROP2iYcv-z#6jJI;R2h{tyUFrm!lT0-C z8`0%{*oA&7v$k^YQ6k-3xUdOX?4)V?W1v5EvxVf)GO(&|4hawcP2GdbBQ!YsIL%H* zLLjg84>d`d!@~l{;|eY$;F*)Ab`$^QyqK#LT=>TY(1mZM3j!J;t0S~-SWoxGcS`os zrT#lvdEyfLN$i9dliKw4Up(^?l(110@;Ufm&&h0;-3BaA??aU4sbXxCIZd_Ha8PoyyAh}q395X zg0V47OfFS=l5yyjvi0!=G-!eEjAz5K}kzFo%Mz=Aa>CKC@{}zvl)>gpTz?_1`ZOLnW z$%4{Ht!Zd1-u3mjx}19kpu8 zs`X3R`7XVy%wi+UZ9)-RKTg0Og34`+#fJd_BhtuZ)!I+XQ@>vjcddT2(aqOai&CGxV=Cx3BMuCe1$io9& zYhT;*Sn~*t?zh`0*eu=7r2S~oC;WZ@$XTgee=R+kd*My|?bEqqGghsdww03Yf^=6> zgkI;}sSydk=oCa@C?I?c@|^w}jfxvevHAotmNiP+#cyFD%iCW>UdPBQ4ybWESbU3_&V=Ia6&-?L$EyGm2J*~CIUlB zLUIlYQ<7eHYrI_R<>*Ak-J3s<7{xVPApEk`T%!)tnE#pA`}Og@9#OW}8fs&f#@oNsUL(F)j*_TRY(fnh(+1xiVblL$vK zltd3e3Is|>ln5|lC2-xOaf;9g=}SVkO5y(Le*gYP zaNgL2Q(DIWT9Y43>Rg!WlY@~Ys79YA>|9)2z#E0`hW3<6jEx9f4vzjoJT8b@ef_|M zs~605LkIO8vL#>vfw%CWCG39a1aP1Qe~fpeN>?@2)G(bArH{}LAQIS@3f;Pr`O{QO@4=`z@8TSa+#^+B5@85tQN z+Z`HGwEO;4ia{GKO-_D3`|~#=wRLsup`>>37bYPP1^)$4Yy&EE0QXT~7O@dB05I?3f#U=i z{Ft59`C|m2QfKX-tlT}7v6X!|Fq`}9g= zTu#o{cr_H6lz`wB^05-=UloSn%Hlk+5(xw;B3riw{qN{k_{vVu9Ez@x~=+qSO8gI&PB^8#U|~ zIPEV7uySy4u)miM)&WfE4FnP5YT$1+S8w&nL|nk{qyv?Hlq%~pnOhjgrXbn^$K zWRuk`ai9N|29Jc`oC`~bdnGpy9XYbe(9kfJIgko75AjV-F{6OUS#Fq< z3H0?32somz%1Nm55o?!#S%6tWctH$n{&z@1)e-(}aLgs#C+^%i1H74-I3svfM+WX% zd?Fn?fWCI+=b+y(IZuAiot`YLj6H7~~ z+qWCPZvHa(0#ee&B z-%C;-J*ri;^U2B}9od0OT#I{b(tTAYR^PxN=(f8XLII&`MpeD}{<*a`?($EtBnA2# z9Q&&{Yi0(|IsD$7{+nA&m_i#KKo{_bL%ct_`B9t~zk4cq@%oxD$|{&gN1|6p_i9q# z#o_P&tUA5x(&ftl_-XGFHhfq{=Bq*1N-K~zRtQA6rmjYN!oH6*&AjgnfJ5}Ps#8%r z>Mn_uzG621bnu2zN3!s3y1t=Oak}^cowSGsiMDe3VzZ*RAA^d^&FThp_9cKcX#DCl z`_ua;JT=O<`Em7(4ZSX$`Skt|cq3!=(>{KJQ@MCJ>`bYG=|29q-J`=Y@yY^>D&U4X z5<>#a;{)kUp>Jb!TRDN(q{MT*f%x708^5EGB(a(54HvW?!F4eCxVVq$TPAWNfD4x% z%j*o+E&rV}UgTq3&Bh4PIxOqnFXE6!ygN{ChGsh*^hef6PsT)xw=~@8OqV~9t`!trWUxtOr4ffsFdSy{w27Ucbv2RU72zESIt#XJwuv3D8Er+j`qj#xdjK4ng2|eJrfpi0B{vgJ3}@}y@c%Ll2#}*tA|v4cJXuc(SPWhA2RIjK zy3AD2W|_l=Bpv}6RU#i;83=m%ApcCU(}FUP^Cc(~Yh5QT?o)WCj%+f@8a6z8;|8s2 za=S2Bnb+LTG@H`>K@3J!gKpQ$3Yv>f8!&1QiqT9jWJu*+*xScFA$k7LaMJO|p;-)4 z#khuit7E;OWrQZa;tLWW$vs1FZrM!)3eT49=B1 zF>~IHD!AAicG5d-`{t2Q4iScg_;cDqL`R@+o_urd0?X&hHL+iPw+y;O?VxQYgf6h< z!nx80=LsfoZ!~r*_r=Dh(Dn?_qTmERdJVAfUwaT$xWvQN zKr&gmZnj$bFFqW#532D}J>GOT#3nz61~3zFEF019slu-bmG9p{Girqg(tSq~H@djG zkYKj~W?uZ*PPi?*i(^Zxu#i=p#CA;oVHQx)*?EA5CfI6_&Wtbr&BvuSnV*pfBEJev zDhm=QkIp5!jI|dsc^2tjUyoe;wDehJhppGp{o(Q4q0{buMK?Ut%K}NeB{RPizlx!s ztXmHW&M+vs`Pk|GtC$ZmOKoIx=IkM=pBt7qMy6Q!cTLYSElf$@Jhc$v>k zWWGYEm(uLI&}q4%;(aZ`yJzQ}T{2p$v4Y^V_Qo!%e$qkSAUYYtBj0A`1U~dMgu8vW zD~;I3s`y|SbEC*et%dE;td>w8W#~Tvx2dY6`4NnJjM_9sNZyq7+hvyJJ@83vFNaEghwp&+yjYp!ax z#vEZ8j8o=oyj16QZ~4~(r+Q_lM(lugy!w>$sgg@|odY_wKPF{Se%AR?ntZtH9u-Ai zpwLpekSz8zxtY(%#(1}~c&pJ4_Jz0^F*W+UN_h(-x-P%_qjx8nb z(eGHtb~yW>J86&nsUpf`<|FGFLCMGOAL#wnG_LNWRsV2sYPv3U1CAeN76aC?A2&@e zE>=M(^Gp1rMJ(AT7`>361&&8Be(v47ce=YI^qR-6S~zl)>G5J8MH5Q*5LA%4a};#^ zXn-R}z;yK=ej0eBj}$yf@R-sFuNbINe9;x}+OvmPMH=9{>28l%71%vcO%l4-feP=L zxw&gX?YEDrC%cqmiDhac${NELt(em77C#L6jLv&o%5dZ&3Jf(akIrGs`(^I z`Tz-x)u6lN>1iKOc7@i{)A6MIxUuW~K;tWBW~T!+O;;&QnQVT{4okW%I~6i;9te9E zSE3|*ucza4xT*b=NrG(@lf1nAtfQr}$hLT-nbw z|CZFJtudr8gWqR2EjO6cZiZH;>ykBN3cFEc3>0ia$VTV^}d)vMX*-7qqnEMz;g$h z>8}UMqt>sNbgwm-@znOHg9%3`V0J`IERq;FV`TSW#{nz32&FF68$lBrfumNUBdEg4 z2BL^3q!|w4kA#1qI3)TINE5bh+xE&**P}hGW8=T{%Tv5EyB!X2C_3TCbP;78PEEk~ zDzs9+`&h`2AQdF4UkDv^Jyi^DXMIeVs`(i^hu`)0*YvQM|KmrI%J z41NoA(RnvL`^hHk&gxi`Ys2d&%1N=9!0}F zxRRW`N2E{I)x0*X#S*h5Gj+)Xi>mnZ8_5q-30iVc3TcS4)Kz*u%KBbs!)))9Qoc{hSw9ES)kqG^^i`jip^Nk?-X`Cp>gPvuOW4+ZFu4Doy1he(8@(ER_!hEe zNBLcY^R8ciSsm#Q<>e{*FuNeoN02xO+D%;Op>HFFX)yqxFs0*l`8{o=|gig`Bun zyReZx?W9g z;`Sy{`#G<~$xsG*?M<5ZO}TxhUv`aGkB{3`?4gw5N~5)(ef&(te*To7ELumt?a#Df z(xuz@^TcS+E@fHOl9o$UHE#AyWvezrVZD_qb-~jTUcR1g>b2$4c86U@xd#(%{bq*g zqPP9hJ)SAK-17MH9q*ryhU?lbn^y%ji)Py|a%%}RR)jiQmtJV0*~FLN9buqn#b(CL zSiHd4Y%%;N7gAf@aHo^M_^fw)l7*7iet4wZx%?vVUEqNLMXB#1Uu&J1Ncy@s{ z6g#+$X;K`PTnK4|kR1<&*pOfo4AAao(s`45>{oP9DpRtO7D%o1cV7%55gJh z%a@xrdCu!`@12ih3tAr^?^hSU;HSB!C(HHqp7{G)ckxOArR^2yQYhqoI2`10d8uH? z!9S>Ho1;0|6z5lEyNSQ(r>5h$Zf`_EkV@*ojx5H~m38Mx{mNSIq~^C_)wRiV7NNz@ z<<@8~f9g`1HSXEEKmRf1ditX^m9<}?n>cjK)ShQo*Na7H*5$|EKW#KKArS1hmLBk> zox17wNapc=!fKU$)%GKqprD{WU4PYYSR2vra)d|-+LPatB(gg{`?uhwPcJMOfOF?S zFohE}uXaw@EjL`L{J&w;F{H`i`6}^8yg+WuvnW)ACtAeyA+}2j?E24d7b)_b<%#<_*1w9{n59^pY9d5Vg53`wc z$a?+xSxZE?@4U@1n(bLR&SS=o-ZUY@5i;d3A|x1uy4CS7LRo=l5iLA=TR3hUsasCT zK&wX(GkkqFOV^(J4W+)X8LKqkO^pSCfD4Jz6#t2&@4*@{qM$NLt*QUb-+g5A4g~7IaO&ugyJJ2nWG>U|?!W z4ra5Q>dI@k^P|4~ofRukz*O)N7|FB4b+89|cxUz3ae7Z&P23t_MnGuxK<950<9w{s zq$2u7#IWVC;|3@!Dyp9{kM$M1`8+30+!WfN{EkvpL*pO`DJiMQ!YADylRfJFHsX(* zhw(Sj2cvOu9C|8+eP_<+v?*#4iF<*{^q9rx*o8Ulz!h{gtEHJxBP!dw(0G~KDjA>Te1NL+=j|q{L#%u zgp6*l)=t9q5*R6}L^R5CrQ5kbhIZrzPxcLK%3>={>gNl^DZ$!of#iYGN~zn^Aj%48 zAdx|j1_C4i>bBtn!Qzi*|1Z8R7><>7_4Px5jxot)ga$lEEt2yuVo$vcIvF7n!Vvg9 zeDpEoJ^o@8Uz!OV63i1KTxJQxIMyiQn?aUZ^Xs;gsd1%opi(F&SF$ZXXuA$Lg@|31 zl^Z@_Ab~3MEC$V`WANI)jm{Ji2-Z*~bmj%;km%5Hg3Nl<5^OUDeYm`h3ZY!3RevGL`5vbz`D!i{RL6t%!&{mhN8Vgs{S%zYXSv5{2 zwyQ%v&up(;zI?fpBP}ZGu#nyN>T7bM1O^8O00OF4%*4OOcm$J~c#O>;-FmB*+>&nM z4u|B7fuy%9@E9S%P+XCX8u;F|n5`TCUFULOKVXRwq(FENwqhJDF$b>-!XudQ(FF4I z+I8ui?6ZKd%h@Jshp*S3kM5VZvZD4eVCL-KdVrt)mzmQGrRIczM$qeD-(pOIFY=d> zkxCpwU?eZ0hakQmD*?XYc;fwqoN*OmmV7KP^ehU^=Czcc(nYiD_e`?#Zn<5;;ggPy zN=VqcWy==A3cg}i`j4{0k_HrPM4j7R@0zpCiCclGxYsZqCKCoxke|1}ZWdwRsQt}a zJBzWg@zCd6IVy9-AM=yiE_B|444`Me>%6!3z>=K2+?hv_7meDp9|vCAve=EuMIHHH z7#ove!dxO_<6{!Molwzk8_@$vX5uaU%U(u)%&uM&GHdSxOF zv(%>Yb|jg3JXFpY>KfS}eEDT^i}q^;blIJIs=-Dk{Q#e5l+!YBO08YpgQ_zUV`IEO zgwEsdI+SGhff9p$Q`*jMfism((CP>RN@|>_OFvH==*4cp@!U%||-66fz^8{jcXc?Z@AL_WNn0 z@AjZj^xnJqFWDaWdVzsAksOJ*e*5#u9h=V=Mkvk7NbLK^1vu``%FWNe&%fpZ7VCie zWAOeiDYCRB;q(lPZcG_mtjgwg?%auBJsAKm2-bk6Do8pIQwueoB{Sba7IYlemxT!I3b_YGht+DmULSaAe zJdJg+H66yi)b<}VEXY*44OwNYk6PCB>_2Jy;hJ&Mi@?ujc8$h@qxQ8$;r??q^#|$; zHLh9-T)%KmqJm7@Vk0%#UTxLU#VtZ6p6ooV9dnU$MnTJW&eQ90O)cj=>al*l!LQNA zy#J0|pI?RnZ^#?6G(fB0+LEMDghNMwAzc?i8~E>fmI*cTe_2;oDBgoo2FEG+O(P}%XpeS)abyQ7gl_ewBvayE>}j!_;weHIfBG$O>4 zhZjJv!F9F_|C*Y&tfSYoI~+fC`C9~gKJysmpBwAb?9ZH+;-T3qHX`5Vt!-X!xb|>k zf=a3RIL)1%Q8n(jf2=!;B=wm&)maynj#^ylY%D@^O%ZnI6%nQNYx2#we3k6vGP ze|kp1OGn#0TW9(|mY;faG%-c{s*824XI!;K)5Uh?beL-;Vxda*0;w?Oc$j&$pSk&t z!2xsm=RjuMqgbH};~{kG_wV1PPZZBTQ&3e?Gsf+vV3e-8h$H6W0}O;m zIf|ziY=lLmFvyHcg;WV)m*1@WA|CkCbQz^F+zDhe6m7;ptJEmE>`HgzK(e`cQ$$@b zVCHy`e%u_3SOp&BmTl%0h&vE1rdE=4@62iaipAuy0J*9YQ35U5aa zMkyyHBK0jj*exz%g$j(=8-S@g#wOoBChCq~q;790b2j6mT^R51Bc`~hUr{NlCAU{z zGXM9G_Q3rMR%g)2^M^M&4A)X)nnciIz^%p5Q1%yX&;21&mA!TOj%&6Zi?S${P)E2q zwb!@z3HT3xk(fGrN+9xvb%M|nbNl#d?m*#5GkL}8^XX;O_5wK$I((+g1|MFH`ovB9 zCf^TPZtGFz$(+y5(z{;pRje19&P-E&w&%Tk*}ECvdCX-NCK|d*dQ3g~V#V%`y|FD$ z6th?Z{4wQ5C>T9a%|Ta?)jN&}Vmwc1@6bQOb|?bF)UG2{(bamq z3LPb+Ds&X5EwVDBQ=*yUx=uD{KLO*Ct8qc|CT=lKI>#!kYE`sx2Yp@gFAOv$>U)+r(Q14y;9YeACDT5X8#a0?H=IQ z(l}mQU;lRBd(?8i{{B=5s-TC}@@!)&ckP5Ltyh$Mv?RrWi`F!R)j#IT_Vm4kI(8GW#b3o84M%GFr#{yoy1muNQNf^Wpe)ek7*UzY^X43j& zdxY)*-pLH5kVW57ThG2*YYCP>u=P!jfl@bpsg%k z=Zsu$Smb6YS_{icamZ4>SAj8d$?t3Pdsaq&7?evv{f?K59YDUkt(=WZ{%faINv% zlhsZU{4F>N$y(j&&e@HbDMVk~g+KP-$7fvfmAZ~DagvrF9s@R}$vadAn6nnE0ZU2s_c?^^W~!P>o>wz z9L!e@G`YIUG>>8^nU+PVia(1W$!>xRR#^xm}IVwnE!3E|c#Bau!gJ2hf z$Kls7&G0uDk|2s5L6wP(Qy@VkfcBMZc-nFH2>LQ4No-CA<0MViN@Qn>mh59L)XA%#kQ@bMEKUBP83 z*P37I9`YC7JnPc;&BpDU)-Cm1kM1uoyRM|XEu%7zq#b&|c&y)o%OSAOrV*SBb-8=7 zn13fJb3%Fu+1yF<-hytctxODrP8Af>C+LMl_f>>v%;xNzBK8~Lg|lUW&bwElA5#v9 z$_aCw(4n8Oru&HkHc=&&!MtE*Ga`5PCEu!w`H`h6xyX?VR=n`M1iw)z`*xk0l$2(| zRV%5KLWp^|*$zX>g}Z+>R+<`6!7Eqi&qBgI=}hZQor2}VLl$cT5}?FSn|$25g@y*y z77LjZI~0FX?7xsDA@k|Yo1vBWhfD{TO6wb3er4ZOHYA(7rbFUmmMP~WbSklbtKr~a zO+}YeMf&tNgFCA47;~Dl&bUp{Ja#O*xO%C0#%<7CbT!t>{451awPit8ovVUxNOx$) z<{b=|Z%8c3DBt}rx{qhAVXKSguK>aGFM@s+=BlWqXrv`_&K&V0bz%U`AmCWO#eUa;l?~2+?56Q_Nea;-Mtas9}Xot0&l0Gsl zFffv>RE8E`(f(PUS-_h|WfqeDW_iK-&SfjZFWm=ruxY=Dam_aTdSh;j@(OQg@Vc>f zSR{*w@rgGpCTCc>$i6TzUTMyn(_Y|oNpR!Zw>rL&Co-hO$cKiZ?TZeUKo&*RMTl@~ zwr>8iVXt7$phA_$kMb;+MLFhR*KXr}#*6u+)<0P-=($tFN~bN4*MC@Qjfo3sU2dP9 zDB$jNisOrP9de9Z4>F?$xdv2ZjCeN_iEd@W+^wvsiPF$;^r0Gr&o6)GWof3eoH`YV z#&`FwT{n?juIlgaWiB=*>ei^1n!3943VR{9C~1`wlf8KHku14<2a7Vlaf`csuOrA? zLIKVXs@iHySs-q*X*)?!734 zpvmbMdD`+n$ZuDM=NER~cCZ~&{%&wZJHm4Fx$WMJsmjGvOj<5=G_5j|*GE-_pEs@3 z+#ee@U+SOOy+U$YabA2m;^~wVM^wja&Y{u0#qF;u&z{lB+~4*#cV+q<&-U$RZ>|;F z9-89#^=vUBNg>RW-zc6e(;}+WtFz>dZTs}1=sg>wsfwXk^+aA%p}Byu9qKNwWYn_G zkH5&QW?!DLTkl};J1D608>f)~d`3)WaawtKK(TsFfItL!6J;r8xD1%MrQ61kk0N~o znUFqFP}KUUl2d)SFimu`YD5Tfa=O*3;TXhNYc>*+TeY{t`x03KO$11j0Py0w z`Ti_buf`ylQ1sy=FXtLMgy99Az?$)cocm_IynZ^4T^+Z^H*pX!F3oR~nXGu%7$&2r z$p8vTdlj$=q?`izEOJh1)~Jbwx>1_U5KykUGz*MeUCJNrJ}oGy&9gs^yWcCeBJ5sG zfH>DFJNaA(rk1RVmh$w9JNf5-+M3! zj$$PT9x1Z?J+olCbo)DBMW)-xav1gmvMB+N#ZrUFceXLSM_CAqimeL9fJq(zF@cP! z5mOByqVwG6O5%fY=?E zTtm#mfE+);fD;6brYB72YemoNTNXOrkuqfYEG(QZD*W*C?ayDvhAz-cRpnoCzco6v zHRqYC{9UO`gO3^6@gdR@_M=@5Y6Y)S3Pq`sa%QhBFLc{bJ!QCZ<-+i&KM-()!|5MC z-n{ksGBGg`0v;o+&t{d5XAk$o>7z_7&*nIIr*Q}sL~Y%X>b5AL#2e`7KzQZi&CIBJ z`}jztcKC;fHvrWjOulMu*AYU2Ac0Me*;8pnBnCjUtV_)u$W_1O4qqtC( zzq?UB)9&_&>%svuv!mT&P~FeSL$Ko!#Y(VhAb|!s^A>`o?~bYC$Nqk*9l>4FOeM68 z{KoQ;SbB$Y8^<1(0cE-^2s<4+0y}H2#eY>4kN!2={;}lVmBuS!9IQtcY6GiY?+OYH zl>uN*Fk43&rdeKpTPgFc(u zF$jed0!m$>;NqV}^Vsm&aIAxuJs;Mi^^T4X36oP!gJrCnc8&~Fg+w;Vt5DCIvz3bu zU+sP)mRgOiXyDV6$u(^;7S*!+-jh%4PWj^=0cHA!Bo%Iqrj?R<*8`!_ci0aM16+2@ zE^&*AolLmeuV7RGnZCY5Q{>b=+RQ(~CUMLgCMPL*!ly{FDGkR4Y_=G{v_@H< ztG@015IykgNX;+bqjIhsoGOrNhX>2q+&R;^Z+qMK?>X?y%HP+}G57p(oK(hsLWhhd zkx-_?VjiPC9*~`&hi0frmD)Pv@CihHP&6nhDItqxj=#D-G}146m9-%7@8hZ#w*9u( zsW1ZF@(CO$%nsF3mQyuypTT?STJarM6!4PZsnprJS%M*5TGF`FkGJTUV}(xt+?ynl zx7Ic>{+U#q^fGI0pUZj~wg?L&c+mR9UCs;)LV>F)cNco{!I6;%YRQ#IxENTf6S%St z+E2uNfSZKVGeILpy!$1G%A6<9dJ*W$I^gXS$) z#Wih%LqY<6t4m8O$tKic=4>umxn-Bqx@OX{M~!rJ67|_-!QXAab`wv9fE-~r`?A>x zEy0UqOm{btfc-W3L!GXOJ*^?@;%9#l8ykC_u0QnhF-**n za(^x@T^clIy5R8^tUbg^+zG<|1he5zp{pKGp`$Ii`J`Wz^55|~qEYCC*n z=0ELgl(;%Y3 zb&wjS;PQLPgoTBB9R?}#?57CuM-o}ZwEYdCq8L7NZrRdWu7W37S-oBGH=Io5I% zPY{hE9DxG6rog2?4j>hpL~qGxCWz@VsST{_9Vh|S#NTdg5BA+m{>;1Kxb(fLDL%=c zN)&p4T!!lmBHt%G^KCpa)_bj(c$LjmGtZ{RX#>ZJ6T4|>XpjSd;NWQm*D~OHG5|`0 zdLCP-fO=mRd*yIc!5s9oytMf4*r$p;@$b!7WKnP6qDD2wO`}VcSLI} z+$g>yia9727GvW~Ek+mDxt6^i+OK}=j|?3(ROe949s8_jPGh(^VN!#KU8Z9$=6ccr=R=tmxtWjfUP{ zk5E^iy>n(FENs8awV83vU!H+S{Y)iZ!((I%+XI+!U-!O=1?K;N%Vwin{I6i`%utD^ z)jU4`@y&IAtk_ez@>Y|%%(*s**wafKe8N>6xB!|4aKZkAmk$n62a6K?M|fR-+2A@| z#Up9a=M4c&HyHo@U?W^wbPOM+Ml;hIvZzbtOV|nvcTZ({uE7K++4Vh~UgThPNm#t& zMIqz_UB?<>R#UI2G~?D|czrmjxPHB>vVOUt4;Nv`ef_~=!0tb1ymSN&-@PbS#Z=93 zbSPMgtUlrl{)jHm{)-^$L%R&t%=cR^CKp9cU(-2kclK#T>7hV!Ekl;tRL-^4M03N3 z$4|`oreaQh2=){xApW9$=v)ZzE{sTnu3g2~p~FxQB?~sP5leJ7Zr+iGTc?fdi37{A z&l|Os?w`QmF1v~e0O9?GVhS`M$TjuzA}e%Cj80~NCIM!0C0eVP_&(;ZsJ;NigyF|s z19YOOtUl}(I7r9I>Io*@d0`=TsYsqC4`kf7Dm9$0n>f3LFmG-JdD=uWKitGVqE;O z$B%a)*up4}qjmMd7_qAoYU6m+7N}+)nzX&{6l&R+Yc=dOzv&a!@mK;R-1i;{L61nn z3cnYZ-dS5RM0E4G5+4l%_;eFaO1;}8|_Gl0$R+O*X-^CuzcMDPj^qk2N{B7rx`-9J^G;i%W=5iMNq zE0U6%Q5(UX1&^*8v-#WfH6sWiupl{d;>1(;l0i z37O2s%|t0=K~O79p9||H+XIZJsik8{i6JT+m(P2yj<9eK+heA zf(bK$qRWfI)+0NBC17$lP1Ja8CW$zXI3o;=@M&4X8V#h$XuJzTR*Kf^%(L}g=vhn) zH#;JHq4iJhID}5+cU`2w6~uL;7Bf_Wiv&ig7u0kt&F9i75%b<@j_2;F#LG0pu61{2t^+eMGK* zj7d~;$_-&$ER=)#?>aEaKv9kn4M1T=poBzWoVi+lzpKz$00#{PV|lv*gBmok@a{mN zxZwl-Z&OB|KxwZX@2m_$BibxS_C(s-&c(d4XZhGukf1VLgPHyj|)OdM(fM-stP+@CQ2R})lPGn8Qd2{p88-;^MjAL>Zl9@XRV_f8mPo15_DnR1G{++;4-iG{=FdHKFU_gL@7g?(p3BnYrK*D7R z+p0$qx=|qKUtZWl*#z@w0P`(ie4&!m89%+q!NO9dMj~wUbr){t3lP$pp_`$Lr&^S( zc#^xU$~)gKuF_ngS`-;K>>~m0LtMs;%*GnsxS7$VcR_Cy2PhdvG@+V3|ezEkO&Q-AB^6&2BjupXMaW}Aebw^Z~6lT)n9 z3sYKi=QS*u>PH1di#a=*%XgEfni)uDpIH%R;5wF~>smi*GnYSKXe)Xw{qUHnlV+WA zz`mxuqgvCwQsm36U%oDM7W|B&q`SlLpkB$<2JU>@BovH3yd))7N5R7t7mN>+%?hKF zYB+scwhaD1T)lTZ*ZuxKURS#`NkvGaAz2}_Wfb9RkSKd)W$)1-Ar#3XRAD=@~SI(>0M31z{JywAI=Uxt(CN zpIWdlu{?G{ZeiAz>EW>(^?g^n^Fq`5_VE3txVjXfqp;KUk3?Ro{obt>!pds5=c&A8 z8YZT~9O}aq!@neq4NoNO`(dGRXUo3%@zJB%v$v1T)ffqlv~%1oU#gvSOYLV{m;CPh zmH;86^-}8G9t_6Usx3OADroISbEt+LN;sFCWS<5-J?q)d`8vca=eQTB5<~0%*shR@x?H(yk>q!S z`@4gZa!o#J_d7=)3U9`qco&rqF9ndk7}5Qd;?lzS4)~8&#YMRq#S6zid3H`RuFg(k zrWBO0%Jin_jTYBduRo#PqAYxME=prh%6(P#f9r00rA_l+*>$D-_$om^L1k&-=-#1= z7u$S>jKv~M*H4svxuDrUq-L)pB(ZQ&FUK4R>><)1p+>{5wvYL09CvS-zV zl$@GM1>5XL9agKEq2oGxnF_>}$`zb70f$M&E7xgEi}$^pc=UG?IwGZ}#)z7UP!K`F z!x4Pqgcdi`vZE6aa6i9dX!Ie4J`*^^H1Zv6T+A54Fdar{v(MeTcO`li%TVCH^BnW_ z^@Sbp`S5C#KtGy?HR8)&6n*mUqqK>uw#$iH_-Q;$SsnOFd$Q?ySIsqt$fc5?yjYXf zndP;WV{LqKa$U%t9}EjGw&%8c@6)Xxyz1B@h2Up9p0Iw#!uUoUr_APx%Be$qq&$pv160d=Of;gP`q&WKDhi6Kf?PmjekpKv5HM816TV+97w^!Efw*TK!J0cZagA`S#+`wG))LAed2!#}x0s}t`?i){q9C6UD zcj%PuTgMktdxXPm${ZDj`%-nB@`0M(^_L%X#XcHrFkqoHP8=1@-g!4K*-wRE+`<$}aJa&JEXRz_r zn$WP%W1Y#FsR=pfX_LbjW{mrIPwc-{I-4%5`~B#HvbZb`6{WoIKcbT}r+Nfy847|k z>5tp+4ZM_fy>Y@yQCl8rn!N36+)U{ao z%KCB9eV@3BDeZzwhvn$aop_yZO!jijC|2E(>QwXEU$r4LU&L*lz-h;vXs_o+rmH5( zGpz%bO@iC8?(Kj}q3KI)fs=8@2ms(KFxp~sz<+dcVcW&2PWUO`GsB%S^ zTIM}%*dY3T@)pxlNL;U@qMKjljWkx)9V8DZF+8_)8X7KC4 zg8^l;3T&?ce+MnAV9MCLln9F`&kU-_8T_ctXS2Gmj!dBt5Y%d}_N zDgfs&3vfV;m^%h+M=R3|hjEDTj(6m)6m;j-uR+GOgN`_dlAS&=Iodwew&-;iSj@ z#?*XWqLFRUrT9N3{P7-}K8PM_b;PyvPpnuxrScUqRj+;UI8U*NT z(;eFqJGm=@c<(N?WH?uRytb&ou%@c5rN8ZCtFfa(Cc}~3lBTAm>U8y6O<<8@%MlSO z3Tc)jN6N5%x-g_cr_c@QhyVYcPFE_-Z_6P^!PHz0;~XthIK7N_10@1=LlPcjU-eS_ zY(=x!FhvO*sJl~<7ps_Z3}zdlxLve(_r6a4(bosx5ybZ$0*z!%C{P8 b(9@yOF1 zpRjMg+3dF6s`u&sasH&-{a+^1JQ4(&_)iv=mTu~rC}+R4%pgi$a9UCxZV6MT)vh>1 zFY`~SPZWDI|4G;nZVH<`dPK78>%B|5PT|(n4D@#1Q6DRg)2VoKdc>=`3bM0vaynIb zT9|Tim*p&OpH{e;MD-@oNO9x$-D!j2%AYSj-lsb^nvgDsuZNziqa#1~PVPnc4;#>x zvk))e54*znH+6CAvzOI&ecwLaw!PrEd^ zt{PWju%IU0?8EJjr))Jk1*tz=)180yrX*~urcXgtl6i7GuRkN5o{xnl|Eoof!4whg zV~SQwgVCQ~#JU+Mr}}L1I&&}3BT7Rd&tP?IxQCR9*9nnJGY$J~V-_dm)y{)ch6=A5 zu7*Ha-rh)xjAQc40<{}33+$=P2kW=S$+H&P(fFOo|1DfJ+|%2e2+MTGr3EWk+O2}fJ?ib-vXb(V6R^p~ya?b-1_E>d z*ATrT@Ck@s4e4Zs4#xbp_IA3YT#&THFZrd1ZGO`8j*WIVRnV#w35Q~d(_&*Kvu69h z3x&jsc=Xp_DQ;@q==J7axRms4-u|0LE*z^$S$t6+}gg)2l6_; za5K|-&G}fJFSI#4#I=X=`owI$U-n{D!^we@4;t<-DIO`4RH>3^{+)KKA=>hA`-~;C z6T=a)LH90zk*K8s!tE2bJqejY3L0mOmi+#b1XkY#TML_*SV4ryNZ@}-SuFfbV1hF@ z5R@NCvE96_(^IFud$relwuqS zaTghN`sB>RbR%GGX=;Ubs>qXKM(Gb$V_kKAO3}X;&3ljLnG{idroK9E7c{l^%P$+1 zamh0_drYpG2PfV8F09Qx$snG}d}!yQ-L6$5(*NugoV?mAb6F{hOQ6>JVbyg9Z<{U( zYH=OY-|9kH3AP+#VoZ}Ibn5Q}?wg&-ZMt;g*{RCv_SakQ#65mfP}-2Y=QiI)Fh=CM&cy!u^(*hD1yH;A zuMVnk>_-Kxp{{f~@WZQe72_-ly8v>veq#yI$E-cZr~4b$l5js3*EE zbAdJ{9?taSR-tSOBpi>uloVgS*hQIBHA=SuQH3oC5LNgux?Z`pgrWe4GhrNq%>Zfu zQeIie%dYz!IYE^D7*2woOoPFeQfX!^XrCyGV7m^!j}hBlxsrAs?=YB(Vcwuy`*tT1 zK$9)@GZq>b)Lcu_{C7dG-8O**eqEZ&&lgj!h^_lXaBb;m$_5mz%(`tpwAwf54T zF#~%yr$saRkrAuhPluh4*a6nW&IN9>apOifaQ%3Cit{F%y$Lg!D_cTg1>kuriVsvs zH)aH|0}pvW+ck3}l;$K2T+skb5M#P4w^XR4q@|hp_@Xpj<~4&W9r%_R*;ZkL7>mb2srtu^+Me5jP+*~N$?N9S>#sA&5VSxA9jS$ zxKSDQM;?OiO7$d7-17XD2tVR9+%~UFu0@%l>Ap{N8&?<0T z?_%VQ`AjtaD>{zdeTyV02IQTf$oQ6`f4$v)QW}dc9Ou>z*?Vw!>FDXf@gjd&Hr~yS z*sO(#ttSkF{)VHcRO(tM?CDKTZk>G$GdfPtZn&zkZ)H9Mk{4dn zkA?aamrE=L1QhEZP>k+OV>Ua3UHz!E68tz|$qrsd)(qe%)e8WXD5dLTrCA4>7 z-abtp>8qdM_t250P+YtYKW_cD{knq+X%@4;ZVw(M3V1;8#jr1apcog41|-$%uw()D z(I;e$ANi#JxqmmeaY;9Of=Q&X&Nd45-LYd66Jdm$@e-y#e`yBd;U8)n_H8U z>Q2+KJo@A~J(Pg|Pc8?fUrMEakU)O^M9-INRt&E^Bz( zpooPX4q;mmxa#MTJjG`&xGYKiLP9SvgTR7G^)mOspg~FYE?^Q0=n#Q9kzpTd+C&tl zk|=mVlpqlY$ zz%ESeGIB~gAT)t-S&P7xjAjT4@W+5VLkG%UXea9SBj^obt?m6(R(1x{{h_A9yQ|mW z<8MaC=V_MjB2-TN&c_&xl=MX)`RlyUco8K=0EM%SpaHS|NU1^A6q&O?iXMs;1F#x| z_s7vr6-C9xA9SnLq0VsWZ@9i>%9f}}EmV3bGW^b#cALJCE9JYWsUKGFl~h(fu?o_> z_^(&5x*TC|STY!a5h8}Kc=OHp%0!<-$eW$QXukah2KP+ME+4B!8ruJz;ea8EPRFmg z8MPb0X&5@)erY$tkDQIGdivM3A*v-(-TA4OJD7nISp^}YV2Q_pmpI5%hVA+--9!V= z9Y^6rK{sa#CZ>3I&*$Y|C@${uO3R?OIczf&e*5cbhFKkP*yv$vF)5`QFrKdReEclc z+-BgI(^BcX4a$>eZ%IC4=3g_kzinKvPt0?(;}Kp#o|oZKm8)v?s@+(2YnDa1Q20zS zKfSTa(&*)kwcP=&UvvIGKKH|pV5a#9GbAEnQIa@z9S1IO2f|z-<2i{|-_45}%Rx-j z%h|Zl6l2$H!@-RK()DA5y~~ucOXej*2IeH{ieZYqzci&Y`Ng0>x4V*a*3i2xV){B_U4Cfy?|yNkpn}g+GxcTB^;Z<3C2ijiuKoWiJdVjR z{+xYNfwxdTMn8UL1y2#`B5X?KgeXbBVtc`2R*)QIJ~8)VNr}3ca&^@cB}skvQYB1#fLg+*6T@oOA@j~eTLh0C0@kkC=XOsQrV6oz>5RH5?}k)Q#{=kXZE- zm^9=xyfPNCSa^yFXO%NdT|ikQ#6&D=disc~8+Yzj!JHniAH#efTg?Mv9||I7)e5%h z$RxbD8$P**P^RG!>Oa$rDGpIa`}p{zKWPn_ALC0G@%WaZv9_*N4?e)7dD&Gy%cGH` z@XgpA*Sww>x-)Z$xZLzR9KsXw*2y&}o|)BehUwy)$i9CgBKL?4L*EtL5WGAm)@#8r#b}w4@%6QY6OoaTWL$?atR6CERzbr+Hh`%hCr{ZW=#_RJ-6C!utH{}Y=z0%yjKihh; zVRy2^>+WH(xw7L&9NQyu9|nFpCbI3F)91O(?BX0wy(fG3G4box0b7iOlyhD`+@tMS+}coE9~kwgS(`9QZT$ zwWVY_scD~58MyyPHNtK1d;5C26#EI4CA$kpLes6HP;DTX6;&C^pf{3c2lY^9V^=`_ z!;GssI(q-oDB)w#GyNUF2n&OIv<(2(Q9lblM7;rLt*rFK%@Byu*Yi)AesY+);z-+q z;whd(y4TFq6uNEP8mmL)WB2jsQDF#{WFnx(O4L}&1_#)qWTKVv$_m~3PFRTjy(!wTN z*8YbJFxIqX@kOQEnN7ECOD*C>DDumnO7%*iDgO?o~6 z28DgaK2CM#-ye?2#gNQ4+Q>{bls(RH#zLqevi-1^R>qWXuSB?m6HE(9FzN<4!Cd-O zt@FOf`B{tWgZpg)@h64gC+AoWXc<!*$BWk+vO>~D-J zdgX9z@Mr{u*Q;OMc{>L;8rj5IpS)QpmG_c~)j`-#%DTPEaEd(I?{jDFCcq#Ds$KUS<&V{PYP!uZZ2-`=t9 zlndrX#$B}Q^_8^>U9QzT&M*r;$cxn3v@SdBW1;=;-kV|H3fc=E?CHJJleNb~)_3L``{+PoY~kWu;VHjIpSTKFy{xk6$*icD zY@OamsnuJNQDvjoeAS?g!+6X|rH6s>uuXX2@R3+qhk~fn%pY&weAO{(61;I7MkiOt zW1scL&4tc@H3z#7Vpz8Q^!)oux+K0mxF;*5eF%d@RPf1iU3e48nJ{^Kj=dhF*#>Ng zSU3{%^3Uvf$Lr2Y!&Dck0f!DAypIq-NLFsK@6$#zdAnq-f{6(y@ghZtsGp=uaBy%$ zAtg1jR7Oh(){V9>wGE&ADbw4ZYhIYoQUdP7{BdBwpiJo3Ny|MteD+nLx!UlYx)ls1)z~$h)}lu5X*UVA6z-5; z5^-MgnBTA`W^2)%_KUrD5852w4S}lqtIljQR4C1dMWw&aK2pj(#1`_rgSEzmf^9h)1|oHv79ZP)!_5J z>yUkY-1MiDms~Rvk=%RP4Xg*L%ot0BmbVuPWZ2K%UG*s|mg84O2#<88qOORQ43AAYdZ}7Z8y(B5q zsxS~?Q|5;L18hcw$(Z$4oQ;#$&|r#tOv{SUkA&P=AWoZMvilKERxL%rux_#M<}3ql z@**Sz-5#unxHZe3%&{M!--st}Kk4a3+YpjI6Zgkktlg9DeENH*bt<(E_g>p`*tFC& zj$e4tP=7@{fl*>3#S1vi3e$YZWXkOx^ylK=y6@u-!LrzgiSH;TVha}3g~r$My|OZ4 zsC@rwfzy(Pi-tik{ok!(<>Q)ig@v9oYkR&qoz%F)+VR2k*T>lH|E^7`dzjU3C1qH7 zQN(WK{I+LxPSU=P5o5te%Zpyc{gdBryYYMu-M}qw%N~Zkc1t^siUb>6I`^A~CrH9^ zD)ZsY*4M02M^>9wy^Og3v~qSV;OSGfp+H_^g$0cTdB^a5e`-b(X1vi~fr<&%FmbN{ z!gWL7jXWa`M13DkBKEBohcp0{3jBF1U})pVdL1hq@-+gB;qJ46kugk4xyv)R@8aX* zBUK}gFE+|(PgVIn+PHs0z34j;ej|l0o-bOtSr@ik# zhg_`xaK+$TuZESkv)hru?? z2AQYY_uWhK9sj8%-M>|mCPlE3-#pJOj%8lE;c`)vaBvfXCBwZ=ZCD7&Jj%y0U(4}5 z^UEez?Zw@iu$)c5IDQ4tiVXTO?cYF65l)ivTB z$m0O4acRfxQrLZpL&Hj9c&ye=An~B{sRT{D>TNbmgG!FQ4+^3|&ql%`;WS1q`_(O# zXfd(Qfyg2_qQLm{ya>>Gcu}ZVWy-VG3DoaePdTTe8OqP*V?o_khn%!v&cDE|GQfT>Y z9jc*B56od@<;yo@t@GQnZ`%6ntqjw3s7KY+yVmeeQR?Z+0xB_RPIki`*f}`( znG7TlX{?m|66X0}_rfr)qr1Bh)R+eCNZM4n%a<>Uii$o74BV8j;VrD)`N#;tOnmb9 zkRRLy|ET-xwgB_XZ)6)d|DH?sxVJs%J;d z{k&|opZR38UOJCLbu-J|G$xq|%QgOWouA(_S{kRi4}7Bda_D*fd!>Igd=za&l(^th>icR)@QGtg7uOi|dLX zWbW7OQNL7Fr|fko=AQP9@`D`XLzHXQf1~t`4xM&d4Bqd-k{eTK_&R@pT~6 zX3q}9BCWjS8)M)t_#_F0$lwWk{C&dW@Q8$M0sIe%r!}B~H0w&t=z(X0Un&+S&y83H zO3~&IIS4v^fwB`!-c&a?54bXcBfEo^Rtm&l^brWqczq=rGJ>3?f4c6;DJgl#L=mwS zYhZV@yJPgN+&@Cxeo{X(O@+uw)Lnmre~IBKZ&Lv9b{`01tM4=$tJU-o^Hbtrk2+ba8O_s=Gs-FaE1 z9cNo!GYZZ9oXe)VanZ44kNteZj$aAhMXQlee%C5DgI^)k%)kG*lI`Sld$aZ`5#^~T zm&-k4be~zJ?U-pgID5;ZGa+_K(qN4nTf*&oLh7`|(RvqVN7f{>zf};fcpBuRD>8dw zy2iyZ8PY#QdBxNO)IZ_CNaX$k#f16}1R0GOY#>L2Fi znJ9XcCl>gudk{kY%kj}zI^tX zZ}7#<9QpC=$h`4SoOyGCdEZa_TW#|*Hobbp(PXLky`$F;mSVHl^Sz2OeolQMT9Ky@ z-LCuWv6yq$AU$Ydoh$|a$FHuv<7Zn{0!+MR^@RQH%d(WzXX?`Sl!?r)u33NQV-~|r zNdc*ss|^gY6=qc!I40@ccv!Qo7o8SA#q;Yo`rWGN<-104Q*iV4zRxeD%R=AK80^QN z{Qipe@EOI~mG?%xOiB@V02s@-XaI&uasiVCbjkT zrd>swpo{}k&NAmt1Y6UV<7lQ~z!Mf89vvUA4MC{T!mk?0tTQbQWAkDr+y$+Ld` zZXn<8@vijp<`NH;pG+pSQ^!W_>196lBo(QwH=wi8?4q3S8kV)OkRP3U_fP71l@8bQ z%Jwt88|EF9j`JVo{9$ZH_sWe?Xlcqddo0OfHg47@fxC9Tw`Soc$Ev!o>>WHJx0W^x zonAc5VCJGoac#afw9;L~d0u~u|E8Ys%A?Posj&R9=5*v%))+n=`N43uQd7aN^R#fA zKqh?TU`7-lAHTigKyZue^nB-bCsiQO&$nF^>UcLWFmOq+e>q6Lgp85h!%!`M#C@oc ztb5s`9#VLSu+8xBVL%9U12pPF(P~SIo}M1i%M-0em0`L-c-fG36tuLosB>y*YLe6H z(j^KUT||6==>kR(V`I8`7b(>CeYc<7ihx8aWtw}P`Ge25MTs4|80s{3cz)n|URSjQ zgJG?(#8OA0v$x~g{WgvcoUho-LgVMT_MD(r>lqSTa`c+MQE;Z(h2n(&gRAW9v(p*h ze@BkL+S_J4Xw|1#YL~S;iAi`iy*lgqqRQesno_ zEGuLDLS6~oaMtA~1umc03;Z7cm=tJ|s*{qE0=yL52w2P@&=pfJ&Hncl$B_6GB6Aq! zRxp#_GADfzvATOH*^wWV(Zv* zXAW9eSP%nUbfq42E=adI2{SVw@?P-T6j9xN&gCu#1A9VnUsHS!MPv?xh-r}V+UwW7 z#SecRDfyJKU0KAFj;7tj9i^;H z(O*|vCh!mw9H3DUY^-QwrfkeJJ^+bdQH~%_xe!1^6$DIdbkBE)`z$NN6ffVpMF-Uu zM3s17K=9f0zPx<;^d9aP%qBrZhiHkdc_@eNC>t9N%;K3*jKi{Lx;&uP?)cd_yL%H4 z4-b9}YNb^quncZ<^k|n-QY>Oi4+*?P)%x_g< z0V+nt* zeysjxCwPKm#8jT7^_+ialCdOh_;}&xdAKWhpjA}FHwzk`{XK|<0Xz>u0ua+E3LHwB z{WJEGuid&ZtWeiEeb2>Z(MFsqblk+*(Aw5^0vZ-B>#+{)1i$5E*~4I%WtjDWvU?xJ z`lfJ0Ck(;(?Poafbv1Q#y8HXff&N+leC>LCm#nsSwEl>OZ^JaGVOg9g^nE z5djDplz_KyAE_)(_=7@Mi~^+&PZ=^H-Rp1e2{<^V<<0Gm(9%bQ9&aW zCRp0)HR}O&0WIe-DH^_t+QwOjHyIZ8p`mv%SBH4Bc_>BZr4X~StQVnbj zPWgM7g{)y`X9s_X%-{hH$5FfPn5NvH9l&rkFHydiHgZ?0|haTULSK&m7KRu+%^J-9q<#gPL3Hk^Au*43rRsqgssg8GF0<2N;X z-rCRWPvkkpO8?#-J7jZL=0xD7z{HAguQ!^gfKb2;fk(mj?+oAoB_$VUjT8J)Q zg+Kajqk_3LCZq3cOqhZ6GX~nw8-_V4M6_L=&5VTnmPX3;V9~8%s5fAP{tZVQhW2#y zHa~XasG}wVhJ=QzH*Z$J6}lKm7b@f(+KkIphA1WIH|Q8a%aT}b59hVxCflsOe?V>} z1d!krX`>or@k$=%cbGki3oxbeSsZpK0zA$WH*`p#Q4Yf}jv@Wfn;qCP_JD!#)dCjY zEd~q&}!91>O zWaJA(cg3&^3d$D8fD#iAd`k}Wu6WG*4jKx=LhT%e$M9PDfq^>c8j}bGO=(`lq(A(_ zc7+=^_Cd)AG7FWTq!{XbCAMvh%|SSp5IFXa+YK)keo2Pt4mf zO`_T5V|&2LCE@C*M3ivO+s5ygaeSKs3oecO@eZa&WwtWBK=1u6_a=0)w8(Lss9aqWS zzhQ%`d>dfm?!R~is!1590ye|kEk*D6x#Yu8J^(BO0qa7wmddB8gpbcf;%FY!U0BDk z1j)lV>H2Z5i@s1*s6941|&*ea$l<3&j123u?I9S4^8M-knpPoF?{ z0;dm_yu}~_24|OmzOWJ84cuhAS>-u&zU;5rpr?j|M+-nE;jBO!jF6gId46$I;P(KO zeSCIdGu_Cx=ES{$n2v^_xh>W0cr{7juE1vL%$I%}1!kAzS=ak|C%QW+#Z)`~x#;Z1 ztA-IQm?7)HcYw!%!)&sVX*y3U(1x_U1vW6G6U{H2Q+Rx6d1j&VSs z4L^nDm|}i`#cJ8FVqpz;w#1{7C(8ifxUbUp0Ng!PxOIL!?ZN?148_1sHmedY1q-*5 z@~z8nsN*58B$9nsSJ$Q~a9fH>N^sm1VoR@yXE>LFKowU6d&vm$pnfB z>(QjfnpwYRDbKDJY6-bYa2hs;3;p_fK92sujc-QUnKM37V6`w$RLrkG@R7`g2vm8tloxLiFp~bd7V#Tg_-0u7 zz2!D|{0yXHkbr-~%E8f$xsLv?93&Em!z&N5YQQGNVOX(`i6;T;iMXraTEIZ_foVB)c3vawHU{ZY7&J%w%3ub)8K? zJBBzf$tJ&Xsu71>g0po}wiW{p_hj0V`fHiLTYEov!0j-b&TSkjh(e^~7(24Ox8&|( zyrcoL+&iT-FZ9Jppf|6l*sI$AN+Fu8K{T7L%qJyyS!6w8E7hmu%TFm$%q7hf%CwqV)+eKFl+Vxe|*4AGUhO$M1$+^d%Jv)#DIN~~mX4lxtDh&r) z%~P_QHgWZ#v=wzV!}JrgRTQg4_~2>85{!OML18ausVkzT%JbWWHQQCCiMK@I8Ep+xi6clpTg)zQD80O@d5nBfQ~S2#2Jn{9;K^q zhJ$q#reyd@84>4qg`I!0+}_cB!Ufd`J|qM_OfIFb2*}sA`6WhdmwgiGh2f1F4K7(f`9hV--#d zSbt`_FmZVf4Cwu`b#R6KuBg(XWt4#K98eGUFk}2WD10R@T(}TEf`jQCPL+UwGE~%f zB_%-pDyma2nV5{zmF__8O!A}20bWiIc(X)&1}00ZRB>Vg1x!u7auZ469}{tfoSq+B zgOZ5EbVGlQVs2O3_R$-u2K!)Nn2b8f{M7QvRy{(9+Zaz88nU5)uDH| z+H`yJJ4+Opbvt(!KoMj!H=IT*Oc8n%?8Cd?W?^R%$1K>pAHqcj)>zy0OB^@&-Z+n8&hc74_Cr#V zzKd>fJW3jzIv7Kgm6e4;B!Pd*X)~eeEB)jXAQJg|K*fo|9Q%YQn*o>{vLln{NaJO% zx!2Hf=$;JPW_EL_e(WV22Pt7`fzx4m4fv8W?2+YBI8);Z0LAp!!>$cSLeI=QpmCBI zFjV9LBzkTut#)fQYl>{_{wInIp0(shg)((%nV-=d0y-NYZTJ$Ah$Xm!wNAf;)fr@yH5;+C`|EKFvwX?oC!QD$E4+M6DP-jZ^-Du z{R*+gy}#u+dHKUI2--0mvV2G-v!X^L9R!5X_WHc3dLxX_>=eh4Np~nU^qbRun(K^m~ zV76Vu!-n|n#{~sp2PL7devm|BA-t%P9Pr^!FaHawP_qk8KO9PcYVoA853Ii10mK9d zdJ{BRe1Rm@g8TB1lE+c_lmfSeQNTYi3i3w(8gOXmb3hjc&adFD3PEK6m)2%<6wrRY zEgsy0MbN8>40|dUXwZn}0X+jR9^1CqVv;?HcS@p#BK(#0CUIB(e0zw5CxunEByu@z(_+AW@4U&!x~-@AHp0|={J=`(%zKodf1lW8 zw3!$OqK&n#8l0S%zzZRPwJ;ahfi0AvoTGTOIg2<-q0dKh>8`)-kG}8b5X(&yn~wqu zLT(P0d=!O-KEmWstS9kp;4HzxeHj!j-Yn%>t3IrTrMdmsa;c(gM(8uR35ewmj;=hX zB|GIj+(tMV5UGM7Yi^r~AN8Al(PIYL1mZZvN$?NlMDIjh>K7cWKePrb;sMIV4?7(t zbdMYd&Az}KMFFt*u&{q1)I=m%#Cg4^Qykcb8~*Nxeb~l8&#;+FQ1=jZHul3ZnZOHv z{=mK672|S8&CBbFO8{nXki6+t({|uAp=Hen%W?JN-KwM_l}pEZb{1rIs4OcA;#fjDOiQ7eT9it1KI1!rc*cv-VGKEzUyCJ&2hRb9`p934m9$`%G$wK zzHG)tod)(Df&a0ek#$rjY^RJkaU!~tlG1>D2K|PDX00uLIo|1h6b5(U!I64uAEDjh zdAoUf;*YNdtDHy%0n`8;j@(Fe9q-ej;)Ca$iK%JV|9WvYRMkWTfD;^3mDE5q0gtkL zm+xI_UqqgU9l?Z%H|B!@-Z$n0L}~>8Kj0jSN59Rs+l>mNs5dq>RVQJ57~{e4l1D!- zJ6i}9C|Tl=Gr{Hsrw>*hr3CK1a|-o1ohzY#BN8MGx6{+p6$IXBXQ3iSvK;V8i$vzaJAEd4EN5ZwrF77Rx*>DwFJndVorL>5={ za7!A%1r$QCMClkD)bD>1G(6QQj96KwQ>PRhA8x7Mc5xX=k7L0Df&fukS_>NmffZx% z4JAcIc-tAazmLJ03HL;r;tMP*9bkfZ6GT1-gWJZTL#_Bno|{N^9varq*vPz(RJWjciq7I>$fh42$}1=;fxpQ&k4bn5ai<670n&@cl*$AyS^LyWC; zA2jUVvj^UEWDrM6lsNe`#cxM2Q36~Nu)+haM2h67U|k|3=GmxmpqV2cpe38%Pt6;q z6Y`w`d{5CmV+Lh2)ucmohS+DRn6%?x+>oMZ2nhe&#+nrxP*MzfJm|yF=L4faZ45ah zueBkz7B0NzW<|_7Q040O=&C`?jIba;^i?cv*KgdojngC`U}HYeK1_!sBCZ57!4`W* zm^6{10hJ>YI{YLKRdS@HreaF9QB86At*h~(j=?5JuWQpAs6!5nu}nx{$<)Ac{uF{6 zQxv5Ek5y7%#~1^r7b6N?7>A~b>0=q9%{UK`3WFH{;Q&sWC!LRz&yB{JIs+$5Y(#K& z1Bv1O^KH>h&CO^)oNuqZcI^*leKNoaT;XH_{}K@t>)C@Au*!z7D|AJFwCSV_h+6=O zqw?C%|4%+*wvVv0-!biO0bHZO@SX_DVCIF3*cERb_uT&1%Wqu~sYJ-Kk(Vz4{yJzW zc7Y3v#$7#E7SZ!C61)~GEqsGSTQ+0%0xN{JGMG&%egQG~|Az;&iEqt*XrwT!=u-KsO%g~N9K?9_* zTLC-;GQwiX2aihon>G2^Da;4A#mRf5r10PbLxRc|4DCOoLB?F3n)GtI4&S(u110K# zXmbF|pziA+-SlnUfM9%dZ0va)Dq#*DkN%d0-^~dw-RpLUPNV3?1H*5X&X-NWa*V7^*BBY zW1o8%oC5%~ElrCiuys_;&XxHu&Nl4K0L@X1qX?a3ej4lr14BdFy6@qssr4Y=q99m> zHEyBcm)Hv|EYh3gvCECH!^N3~@(O^?pl}|h*}x?0>+5l!qbP3g5*{2FP(Z312%E%C2x{){Y3{NA zXM!B}VS6KBC#C(q&E7A@5J?eu7&f_~th!=pPBCm)R3W=Gh<^0rUD zS}MabmcX6|vPFRFO*@kwJw{(S$^crbvb&2f6_k{MHD6)N<2b?*B=o!XD)wbs`y_&< zp?=@Vz#xl70FqVZ%VTm^uABoHHYg0rO6}XHE z3F88nv^1-nJ}aPx@ZtpCglC4ibx;ZjDJ)3cIE0p^LD|j|5_O(|Tr6i&{&;!y0;>Sy zg@#f!KE5~BXJr|oO2O~Mor&Iy%VOY~@921O-lCY1j7(0cxHrQcpT)4={n*Ms6_%Tw zVNv-hvBjzFY;)V`Kem4vdAV?+b@rF|pVIF?>+2$J*ugIat;*jaCH_i$vWC5gurM7c zgn#F@(Ar5zl(Gz8zIv5hS>V;c_XmKvIF6O8k(bb{bjD9ZhQHVQY;SKbapOcWh1mk{ z;BV5EY|s23n*&`*F|L~*c3|dAA|sLecdGkvSEhhzmPL2o(o`CCoS_#fA-$w%er|!n z%*cv~xr{g9+=BW2zc+5U!GI9Ho6onUNiP>I$tHY8dllv?ZKp)( zJ{GjcU!DdZGjTC%^fLRc$NC8`J=^smX?v%V_Y$hmNpScuE5B_|+-V>|fa*Trw37%5 z-s(ZDWg;mj9su_5u)6GFFqxj-nq$ib4HSk42tRIY&c_?URg_<}<~WeL+DKsHUwY z0E=Ihio*r^J5$ELs)s9z7^M?VQaEg5Y_uz46=HkW;?|?KR5d@GP zsKTcq95kwh&pxAbdK%=U@8RbIe9lWeyz{jyJ=fezz~;aH+;GX7lQrCnI*p(!;q?S2 zgb^7yN0qqqMD6fcFQQJ%z>!Iy+0wXo@6wf~V^Q&f{SNA2IPJI}fGdEF8;P11!}H|eUO1WU5R3ceEct35PrhD*{niEk>0zt(gO*{>R{`~NbOSQ6;r=~wW z_tj{Pc}fa1D{Jg!{dxGRqwKQ%_0yzuj+#**^XSz`0N)CuAF`M~IxY;VEVt7eV{fe- zrI#Zjw2DgT`q0X-DfT%njc!@|HNrq+Khkn1uZPGe5zvkESfi&7Gb2J%`<};uVJw`+ zANc!U51-CGB;jnFVo#(W97lfC%cOS!S z7FZux6l88%?!#QthY74GRvQXGgjf)^R;wBDGeVya#y^h;uldh^+a0Fc)+d~HoKOF- znSvxj0yRVbi@HFsTxvIdNzpBP_*sKy#^E?`4a|2`G0yM=ikh{d3Bw^O*fWjqN4vx% zrKD&LUaQ976ie2@=V@wb?S!E?+Wk@M_L7qIXhoGBe%INKeikcSKA;W%t*EB_(Wi3T zFoY{L1QX_=x@Zacy*~*4eYGF|ft-p93*sC{-Y%xos?r=q<2OP|X}* zX2zsomgK9nS}Xx!MbUZj;wB=jyOFpSEaAYJLj<nGsuOzn52c-1f!C-BmOdsYPziqF1Uy4)gYI#JohkHQfZOD${a!b3Vks z_<+Xd=80CbD#9Abicf(@5t%Ll`@;7IY8F%AxE8AfeId5+DM3NX9Xm*04hWyc&X6oC z-A01GQmwPHnr7LW&*=(S_gmo?FTty7U#FuiH)DQ)79v#_$1$B4x*B3d$i}wyF3uK$ z>qFgIjy~~`o7?Ni$o0VR;PqUnpOC{+7#Vbi0Jqf-f808%T9Zo0BJJFk*jv}o-)|sm zY|P;;Jhj(&(lZ*7d*I2V#z98mCBTv+8D0+_5HSAWkt097-aIc*<)FWJ2{0zvBM>+S zfQJ%1&qE^lx@2&8qQC=RgW&%wjG7xKBi~hAnr)A$wmQtpD$vwuj0hKaSD;?dpFkrb z5QNSRZt%p^2fWo7KJwh6$=13{rufKZ=d~_UXbq8TYZKp29*m{sE0i%BIGzIM;d<=qI)rQWpVvU|bD}76u|Wa%_2$_U{k)@pWvE*o|XVPw>_m>+J_2ok9>6Nn3@7KdKLFX+$#+Gz-o_F)_!$LatWjI*y=j z+!k-&Zp2KU-f7+hdl^eh+ivU1>VcpYNnbjUOA<2@Lzcj23pH;pOs@~>Tk|63UDp-q zt$xhRZ_l4QUf*!(Q9b6poET4BfN>S>;hyVxvwq_lb6cNprl3HH{k4_RQeou=>=^Qn z9(vUHAY~t=+N%G@*IPzq*=AwGAQpn4f{28uNJw{wB8W%{(%qfXZP6v&pdj7dUD5*5 z-QCjl?#r2Z*LuGn-&)REub_YlFmov3u=UOVu<%yYQ>G_d zXSgS3DdNxIJt-*>Y1#YdCMIPH@)RyY&1iu3x@y1-*y6nocO?@*jmCWh#JqRq74C`KRWM+2@TEuf<%P z>1PoRcK{R*x5D75rpo^Vm>@GVRapD_4$|h$ZUQ9|fOz<+k)p%S@u#H^O74o5vG1Je z7H@#8++9ru4Q<`#xqtx7g5sIl_S_)IpaW=v20#1GVg%R)!+z@;`S*XTV)`(?PutL@n_N7ic8UztNTMt&lB z@JAtxV*qo2QQG(YJ#voFYW~wxcEXH%e7@y2rN=J=hk!7%Vb|E$n?c4Rry}}pNy$}C z&e^kmr^m|1#@hFz?hwC(C?Rm_(1Uvg;^qiQfR4Oc4i8#b3?L%xoMS z#Di^%n)8kj>?#J+ivN8hw}Io6`15DzdaS5(Ew6>lr|kc60b;XfDp&f-aZb$H``q@<0* zH!op#ionnS0VaXw4cOHK_<#)D?9BsY4jLIGLJS1>Kt3DqdomFQYDI2pU+=*|qKq^h zNug`1*;xv!^IsEG&jXV-OG@CyCl+}7_7<`ghb$lz(5A!yprXWaNqsIJo|A+vzvupzc1N>z5ABGD|DJn^^QKsiLBmsGZu3V+kmH4A*c|==v zZ0i__^Jk+oh0hT*iLeSvI^>FR3<&*GBq#ZGVt0P`4#4FAcV@sg0DRy;`0*cxA>254 z-Uyrg&TS;dQ3@B(0fbDB&uyEP{Hh`qC|^{W8E;DRpVXFw@7UVHH`w=kox8MxE0~#C znfLV*vE-_%SSWcBzywxNQ9-(G0H%x!Wn)ZLp`ru?u=A@=a9uyP0*bXhtZ2mJ)1D)* zBnoh#D4)}k(O=$DF4@#L&EfU0$j!+K=+_VCjIe!#ZO2ZYPX0SRq~B$$?N{e)she{k zoEe&sTVE~@XDFITd|3}r2?4A^DDI$#&9>D+Uc@{8P-VCPrEiO5)P|Y?qOJ+}a)zK0 z&MPQL#Iw%`!I>A6!Q3$7l;3Q07et-lIL=Bap@$qIv!?Fqr zZ=mP>tTd73g0v&{-v2tX$tQZvL_pHdJCx4P94?r=gB{dLbJJT^L580 z%p@g-cIQZII4&Ca;G5QA9gnen;{CHX_LUhaO+gS3#JeB}J}olrM_7wik6c1? zN-ePMjE$i*7||x(DWwMDJ|c0M2b=&F`pCTpnP@rIS(OsdSPyupl97=?YUZW~wJhw2 zAX@Grd=H4~pvY)oHNXn-1nSk8hZxk5kPh=Py8@#w$G$#hBWFx*|J&3KQs3E?rYkxD2#R@|@Ffn_Iv@8h|tx3d#5;4Td`;Bt0--0ZHL! zUr-J;KYs$u)==$V!Z?QHGysj~8C2l2&sUVj1@88IXEOP<~jN8N7*(kOwAwWW!P+Koej3g3;(Wh!=wt&p+i1w3S8w}Duk!hpQXqQxTJS& z?WOqr5_qeD4#!OeI#{ z3>CxP01QbXxlJB-69}fL7V^sDf6sYjsIX%BCE@mjzP>azmB$dHL$1Z5u#29+Cc2@s zo>g&}A>YmNPQRL>kP4suQB}8x*Wq$#dBE}9=i}B3q8E)xQ+j*(U71Ic=K(Lxg$idj zuvjBsjsqDD6AZH60LazDcWN?V2{01%$ro>9Ai!j-q9OhWS=rf{Cm(G#9I5w&sCj`X z#2Ss*=Xp8F0d0m81WQ||A+p9pR;ywvaeh!+8*`OQET4Vgny9p{NPNs@baY1|K43x2 z`Lh3!16^C+{OXp{1X#?OFjgg6T#pXpje~| zf^-nl$81M9ANXpD)0oxZFPf!$%(h28E0x9cMV~8v5FV^#YqfOfTA=NZ*Vv9RxU*B4 z`6lQ0p7ZjW-`?PiA$n_gP0NE*t7Wze?McThZnZemJYN2<6ba@M#+N6x)CRBa0JR2& zeol*NlseP#8#5^+Ne&gHH+SgO9@;_pT+9kKvGUKxAbJ9;~11)(MLltIs>#gcYtB9DQ zeHZG7LsFm1uHoNf>1m_AA*!oE*mP?SN()|ueYrg#vpc; zyI(IxjsquB)tErpU21-NkKh7+cqV?f}mA99l*8b=|5zhyid>R5mW82Nij!Ay( z#I1?FjKapmz=U}jlb6*|#3g5~vRB0u#QMqi_ehXc+N@fUbs8--@2PUwGw4lp zheQ4xo)-=|wDU+xYV5F9JBi7S`;nAlB2UJo(IS5_roa2~qlzOe6qnGXSc!y6*$(mH*y+9CaZ^{VIdCI5u%=01uFY`AbXPAM+MhbB&!uHIdDN0E0Ox1Yw~tm zV91@>9C;OK0SO5@MhXe!Vm#R7|8D&ZW!;3;`C?({Xn)mGh%rm}FvogrJgCS|42DVE zxAw`G1T~8TwFB#p&PerBS%IY%*fSxsDfAgPv2v!WK~8(Dk4QTa0WR+$5x@`So5!&G zjO}UH`nWhq*y!|5@l7VRu82BQ{zU)JKxJ>sVYi1DN3RQL|2jL`V+WqTaOi%-=Q=Bb z=js+2YsB15;N-vPPIg_5aMLHsq$Xj)&r>d3j<0-0#ClUQ(Xb!8^y@@Z7^>i&oA&ro zZAQFi;GAn%yynAGyuH73xqA~oVl%V@y7qYv>`1q+6}P0A)zBUy7~D4OOAsXuOw}0y zm6erqn`(uHSGR+U0e5{2bnsZwg!JKHNk7!mE~7Go2numzn)Q0$p82%e{%Rhy z;q40d%LEH!ErSEC_K+Nbn`Pv0Pde5=^z?kMRZ1SXqO}$*_up|;x4*G5d7^#su++UK z*F?AfL`ERqI@wa6_e+-ToX$0>)PSQKn2TB?R0Cbt?-PukV3B{fTgay#x*n-;*d}bk zmpeC-OzmLY>CUMU=d!%`A)xV`Uw47uZT5KP2}|Xyk|iyOt;u1AN(8fN*hqf?;ly*| zl^h^b$jV-YXpx`bn+|GEaAR28pHgNQMe1GUYX=8TsCPeqrsO+zIS!hQXIcLwEGQ{> zN_E0P=sMOCIrA!KotRCF((~!lw(hoU_QFP6&?WHg(8SZOnfKg7ExafcaP71dkU{Ju({;OOg4D$=!;NZC9^L1&|4d6rB6eT6lq69=g5sP&` z?hZDJc~VtwcGFyKfl5`GWcubxTU%Y+)*D4B*KZp!bB2E?BZFSisbh|$Z3#4Js|ybN zxgGVu)|5O1y;#X*#00d&k70PXv<+9~Hh=c~d3pv)IQ(D$NIYaQxC1l=SidCC4NyJ@ zBzLvi=N2<(IVZrRg>YxNDivbw(XwgF24_RD`=QQkWKeg%u(4{)vA0wnyN`*ft-W22 za%KS#O#W=O4h%{D9BW+U(c`xPx<>Xu0KwU>BuA{8n#X|z37Q=s6f{84uid1BCm5Da z3|4oOlh3M2St<{WrpvGt6g~Tab?Sl2vCK8=GJvN~E@7(PmLcxMK@=foTZ1k}eycx; z0X1~6^XUGFR8#D=$`US>T>I3Vmtz8>3MvSn6f)frb$Vwk=UxG^V)FBgeOS87vo-|6 z(3veax3q*n{eUvda;aq_wLMV{7_?**>=6k=raA-B`?yhJP?&WG<-(hqTMADi{KYEV z{>s{h6SZG_@#IVhQ>EAQ1YvtnkVAY!;?s2#)35-9g*iR|lV1y{^q0p<>ERf()X(^s zqOG|Dp&g>zAp~#f(~U>d5Vu;p;e_M_#|8`7#f+KnZ`LO#hubtOCDkv|Z+)X~*FI*` zVF+{~_LQ|!zdkwih0U~hSV6$yjI)G9BE1}i9EZGawC|umm8y9ls!I>43jk%k1zrt! zb!wg+?et-HgjEF9xj#EZ&`kKJ>@_M4!UKBD1p~&`cc5CeKKsgEk-Oldr zEW|}1nsJ5k*MSutu)y(vCxs|xQQ+f2#HH3~ks(;7K~vwjDoDYvCg9~rM$Zr2Sryl@ z8t7aHL&D>KSpOu@)J+F!K-dC*4!Qm4&&*CNLV=?i{Nss4b{=O(>5;k!n`4Ei)$MW)Tf`eG^MIAhAoAST0QMe_p zg<)0XHCO!(48OTFUQ|@3L1Tzug%j%>jt>CZ%~?eY2Y-N&5FDV&0`Fw%fN9z36D~kE z`vR^nQQ^i~A1CgHTV6zrD-|A7Uq5rEkiPb*Mf+E3Jx_%m@Gffww+hgT z1LWk!+syBoJl#Gu!`E*}FPr;n8gRvnG%KZh__xB3l9cs)oNM0Q0 z(q=KVFdmN#%JwX5opMXMJHKt7e&$uK}ZcJ5PlP!ciVKCBY)npwSkqB ztV zkOdw~lL3ns*f%*M@t*ZmCh&DZ?YS-;5U`ja#0Kf+#} zc+OGnPUdzQ+mBaMb)v;^Ta!^4Y#5O}ETCJ@$jEwA#0eictuunFdX{yOBQn+_9`o?l zqku#1FVGKthEyV3Tf2kQJvCA!So5imkJ$YDqQ&&PtJFhTq*RMv`+`=##$|i-ysFib z+b*K^(G-ti(R)+p0_^7`fvGgu#*|ysw#V!uVN_k2bNn7^E8>TLKeudZ#Pj(hKFie?vu*W+05+e1x4Dy82(fl(g7=q-hTz+ss18$mZTqHZVR|+O%>wUnub*#O{MZj9Ii!%b3B2LMya5s6Xij8gL!*^20yt3&sDrcf9 z$A<%6F0j`DYKC*=4gv~j0uV$S^fMrvSMMz?A~&75$xp-Gn4ff7 zmK$_SKl2{TAejM;=x>EE4ShvFe_8aB@aC{f#V`$R#m~vj1NgCw%yO#e}>mMxf}q9KBw7(bJ%w19dbHQc4DMR7Js@5;4#Q_GmGe zn$#1q0?)*;ii#_gEuVuiF7IoLpi{m5C4IlIz4m^Wjd<_ymuxiq60|t>zu0LbLyuQm zV84pE#&THBUIpY1NqU5|9BgG}<>aIRQCL=M01p}Z%^OhifO7-J}`a7>A zZPNCRj{JgxhW7U0f`ShwtZcXup&G`#Ooq-14bii&n*DC)qW z`da3KM4CW!A^-vWt~?OzD-ZV#5KqK_DF6{{NX|X%F$UYpJP#W8Y&bY|+Xd`b!zu_R z|HMMa1L0kKhzt=%pn1DLnH)gH8lcGoZ72^94;&37*{;gLDtT@K2XO*Qlv`MOu)S1I zYLK-yRWkclI$b8L>u>E@G`qUvh0lm4Y&?p39j^Q?G7K@EY#psA5Y7Bj&5Ke}65SD? zthPMxq*e!M4D85xc!<8#e}p-fzH0kQwd1}tSD!AdT@gNN>69yyiGt)4*^FAB+0Q4p z>Pb83%-`C5Yx10O@ZCET(NAsRS3*1*1eC?Dl|+6pdH(v<^ODe{dOuo=y@@4BqMYNQ z$3|*UY=I>RAa2U)Fs$eBSq#2?__3M}u|*kI6hLqX1V1Q|z-kW-uV=dW?~*JFc6ues!r0_S6?kmGxbe&I7^Jlht$>i(tvc_8Sq{3J9#KzTbkP0*4bs z(l8D&nT?lm^;l#mF?P0bKB`_~l%}T2yB=%)LHC77IoUO`lAm~E-}DNa3pxXMuZ2IG zX=)O|4vIiCp8Cl2Sko@M3R4OV?DqqhV-Csh41Hi?B*mAr7oDw>AH&>6x18pRa{9uJCXIlc37UqdF?(jpg^Z12GbJE z^#Cw1KsNw}uDRAfJ7B=Q0|GaoHA8Q|02Ur{Cg`&3L85^hN-YJH6cLFSwPW^*N=$0n zUkTBZFNs+CrYD7J`+KSyx?uiOi2m&}WLs*_QM% zuCo3=SUA}=M&xpgAFi;WhKB%0hn-R5+}`x}6v?EjdQfWtvxj-{<(oG*k-vgPayMKw z&?-*y&I3YGSn5HS|LI`kI6d$42-d++)rGa0|HLm)oa&e@nUhUH)(L?PAl?ev7uwW@dDmg;Dr9pB?(H_wJxbRQT|=!)9x~1 zdv?JM#~%f$^H4nDiUGwAvbh{2o|$$xPJH?kKP43SS4h4L>~O!Nrs@yuzzuX7Kqa7B67ubY^f3?Gfj2|RNCXcos! zMJxJ$o1s3goD0|Jg?ksdIB{nugU|0y~e#wP_*f617tIJd(*;#(|!a}_2ie(}E zH3;U690=fNz_6$$hl%q}NlA$nZT(kJ`+g%_9$ElTKn*|Mu8jYNjHYtKqa#`=1>Q9$ z~tyaT-A&;S`SSdajqib$&v;Ta}o z)8xgdDAwAjw|2xM`8xn!5_|bo$vm;Lv%B#iht)_&`W0;9dpy(7OSw#Vc@M4}*RWM4zBk`U+f@T`;}| zLytgM3ia(YssAgr+?{&kDk^#31ct@)0Ym}LWZ73irPAPdRCt{PRi8sA4{}Vne>|{= zVLj*77erSG6bsk09bvF?KsI&2j*)?SAVE_7x2)XmiV-z6?CwFBh*$(3)O=o#EL za=-)a!5A-ZrVpyP3>Epvh?Y&h@|k1ZxGJ)_Y8OvKVrB1t+d1^2fg8|LVSyZDm?h;XwhrS>O*)-)h9>+5RZty&3^r4A^Wy+tbq0l9GX~0MJNS z0EJobzvGc2e`ppO8cIn#mt)C71tFwQJM{|x-b40^MkAm_Kw1Z&44@&#j*vkw&vg$) zuP_Rh2YcWp55g_PLUv_1-}MleS3O%_;YNg@l99>pF@+FaHf;=!DV@8yg<)iI*+jpX zW1h3bSXNu8ekw00cZE9ubgap;OYK_tb@`;f&EMUwiM&n)b^{=c&I7h7s89?cr2>ln z{^F8=ArLubujPHYL0xKrT<+c!@u1{Ns_DL`A;pg@=%kF{DeWC53#)b}Z@d*Qr!K2t zSr{+ZakLIG4MNVzDBO*0;LXYjo@zi0e!>CVVGVxx4P;v(DPo{)CYOvy5I&!PuLVZx zrPgn6)X60`9I)|^8~>E(1CkJ@LmG5gP+;jnMU$hi7-?9iNhA=8}_NP?R z$72m~ooY2wj}>rI*sX-@S8gOpF@k zMkPHZ4R2)3pAQ|K?d^^@pv|d%WjHfp5YVctE%0h?kZ*{$lpL`iwU`k=0Znr!3>s?- zA5_SYEzLeEbCek9Fz*r(`9WX%Z-0Yh_n(XVzJ>bv@WQg$x7ctALRI4^gjOW*Cm1x- zXwa;Tm@EQuI2q8;x58Jx10xIY8n}-j8H`ktXXh$xex$et#k~W{{tkaGQzC3_G$Chv zg8H#!z&4b}b$N9uBGpW@J~maMi0^v8yHVVzT5Ho1-&|p-aBtRXT%PxNNBsPXyx+Pg zqpWIf$q=LCX6xDM7jJttj#8R^jLpdS;SqqAFdNr1rR~#`EFgaoMDK92GjvSH6DBIcvV3xVZ*wVu zv2kcIyhfkB15icqlwpEAENJg>c`GDic7-+q;mmL8!g>WGz@8xzKPU1qk4co5NS0?v?;(q5a2y3V)T#jyFzHs z3knJl=M=cJ0Wc(^$fOOjHhrjWJZGOaV8ZPb4shpaQSs~Bp=kL|xjdzbM~}B8i5gFD zj4^D)CD=O_Vapx&W}R9*GN+9cq?^fdsO4sRF=2JO_?lCvGbMHkFAb11?vQExhT)0-7t!y)`}tf^TOUNhxAvv z0lSoZ(JayOcEe03=C9Qfh+j~P;|aSRdp%G;_A1vdupB+)_b7kiu=8j#@`SRZXU*Zs zpIB3^7#cPr9lk zAt3=p7p$zb3=Lt6&JT3RL?{OEAs7GWZCsivW%nl{`qj}R&-J!C8A6ul=ll!hN>q_G zjS&ct?m;62ZXrkr0+2vM1FqHq6G{<`Fo3a@0tFSJww6^^QWLL*H_MHQ6j=Fwh1XKn z^revHHR#tsu$N?t5tTZ9wnN?1bvDDxcbh)tQuI1z?uis^+QN>fIC)KV!-ZlK^J3OfLGzypoh zdil37|@2%C>{Gm0&oeN$h@}U9J=24&c zsvR{9pS#f_qCr+&&;!936&o9i0Pm2Q1>+f=qWA1t<&~d>>IoDfVfG>v{%ZYAEhgZOmZ@P!KJHU0_zeeF^=Fbw6#$f*7W0@qO zHI!uGl7fwAEVbrL+GDDG@uMvX-bp;itrSi-r$SzNZT8&=_n&BGuxwf&(a0D*`8|3| zLPs~`HixFxn1}i=_BH&ScPMVE)5Cg33}4j7CH|&l|EwPT)Pm*TtMIZRC(J|wQ$wLc zbg3kAo9i;#!fC41mrw}AH-nYL@54akEIV)`3&b8^aiF2`*s;21vJ?M)vE-x;tS|&& zlV!NM`C9sePoLCk+^)|p@&H2dI+t@D@1IcGq+S670o;!WkMJ z09hcSL`Yv;U(d468VirWaNvxnG3zfo@X=Jlz%Uswx<~i-w(-PWI*GTwK4mhP%pqbX zCX9o4TuQ4sRe{+tWA4YQ8Ufs|RUX=x9{d=QZTYieZSZEnM1{#B{b=Bqs^^;el!!6a zmXefSVwn=wN8XM_=F8R&N%l-Fk&>^m%)LbPUoO-Fw^x%i#V&`mUfZ4p#eZpGpweLY z;_0ua5n;@}c$o=`Yy!|u?AySLv+^e$XL53q-6haT3J#MjDh-%A0>7OZXr<61ZAD)= zC+htxlN7+YHLpDYM~MB;@X3V1aDQ^JTAx&?r=e|{ZA}Dk&uoqzn5F@n9?`o(9wHE- zlvduLfWDX>lBEEHL<}5}8K^I4Q$eP9@mQ}fzm!e&be>>ZQ&UP7)3|@8Z)drY;h>=< zW^tEB?3hd;l681|dLpMyMzO5GHm`bhkB#8AM&h$W`rM9SYCXsEfo7tGg*Kvd7hZ4q zj@gx07?te;5w~a$FPUS{Q4{j#W6VeLo`>4Gp)aV`CF$SEb*=bHaYLm#?lmw{5Dh>3gTT~Fj(2Hx_Oq{V$L+q!7}%$0gui?Q$`25P0<#z%1{mm6#FCU^$RXnDFW0`| zJX%V6awL+R^an$nfE$Oy=H6UuK+}&$&PudUFvmAQk=_K-2?I#!G_T&r1C#+;Ai&|C z0Oc7jETCZv00*7Gf3fAk$k?1{o19QYNw|0LJ#3u>GqMVUb-sT-8hO)?Y6HD zk>VqQ8>&4OBsKF^UxI4=#p@4xXd_OdQ2}v9lKJ3gLYrP)^$85@88Dytxc>iH{eVB7 z58TOYY{iA7sb&9xy;9YpE{T{)T%=d!v@Q-;Cu#?~$W5cm9O*emRgI90_s@ z*v}#6pRn`=u6VNc4j|zL(3C@_a5vBrR(g|Qk!>0lbLx?V1&_z`zJ>4 zFZlSA!nY4*j3Dn41y>vR2!x!Aqcn+CjB4q#GIe!7F$35Ef8We3wzt!F6o&h%CS%F< zZhsUAT+WG=F{woeaTEryvv~9|Fcz;Ca`8u+cVnjLjYM}WBMR*0@re#p>Rl=hhguFAnguh3qFU*nSOijnt z6WY6W;fOgN5lM>gH9uLpvlj0BOFmzzrHVfx9}9)pVRmA~ncWh7OEONZt#a?-pp@v$ zNVaq3HgC<_KTOA84x^l7XiL|HtGl_AhIWqHDI))BFzvm%vTe;~d9Y1Sqj|Vt)^WY>?`~^7cE-^w8AU-Tk*GkJazM!+gl`k(S%FcBjpbk&uwE!e;ZA-;I>t zm8mQ%h}6pHEod>IwE-Om64D9+iFE5{;M@8F@Jz5$K%AX{cuGZ_E*IzT8H^Fwh1=Kg zJV~O()J#`s*1blPi=^xw25AKVZ~_xSskKuctIZS&2C1DyJP8(c66I2|7DdQxs*Wc0%7 zF%drqp50%h08yBj=GLHozB81>6w{@b{0gXj@$;cFhX?UePdO6Y#9 zP5AFIY6nyZa)}{D4!ZK?q1=Q-2bib=Z1w5Zp+BF|ae*QWCcj>OF0A<=!;f z`-iMrl;Qgthg8T9sum0m;-KaPbpT>V1;Fz2XbNx|guxyMJ_hg^Ld-KPm}Mp8s6CF$ z23?V>{SO`rEVO$wBQOFszr|s$+*qUeoTf=0lAdwb73c>jKy=V;4}A`po$`$JtQr}z ziPVZ_GZfn{YWwPP8PX?Z7Guo(;B%_v%moDg=9kCCdBFX8(~=ju{1y!cSP^vmx2hyM zxSnpXLpuhen-17l0A%^5m**{Kird6KWvrN}0 z*~P%(TBhp?b4(XlxPWI8vKj@uRXDbX9LTZ7WhJ#(RaL~aG93MC7}CnDxlT#6zVY8H zE~Mt-#2Den!pR4CufDBKB%cNjeKYXIjA0OJDkG0%i~XeY2oLFD$hBVtnBW0xMavc_4|eT)p})#45r`5ug*OMX}&{ z4#x$Wyi|jD#7Y#V(P$RK1|-NlLA`PEF$Gm(f#ida*U*O*?+>jUZR#=W)2~yGR7@n# z^$KeY4|Dl{=m5+F3^L`oUdMq(GSlcQSo#El>Ry)A8U9=HocHy&&?nt&7LVbnnS9U~ zTP)#6%o&>=(lXOm^vRY5*@Lduf$0e%A%~48;?V|(BUShUxac4-7cBZZ$(1i z3-E1&d{0NXNTvoFKEGO7fxTGbo^2MFtH6oJ03ndfVS(}VDb-~i0{H?hiv38dAdLj6 zOz&c=hdb<*C03Y$RdE9GMkNafS>;T4r%o`K8uxn`Th!e zk8;)Fa&BlE0MP3zqKM^2DUS*}@07{l3jFgONHzf54Z}bTH_{yNhahvIKT!xHc@EuD z_8%^ZK|n|d9UYA?-$`mBVv4xDHRM@m7-BfpE!s;1Ka$|9Jn+y$`~^Y6yH$PoNKLK% z>{MA!&I3r-zyd2W9Sbj=bo2#$o;obA6=KOH=BZyp?K&}f7AXQW_#pct09~~jcXsQldIuP8@hAjnzv=dx*IxT4L zmnZs5yIYWVoS*<~wty7_ZZeviP zq#LZosX|M`5gsZCy5H>T?96~xqAPk-cxx5yRtMY1m+t)+I}VtYz7-ZkpmWH$DW|0L z7K$L^eGW4zbZE$ztNgDolfSaLCQmU381~HEL^xEOhtu@jqsZ#fW&yleXW>5$t*xFB zYL4I;h%NL1Y@{Lb`wghw5D#KlvHQ%IjR}&J{~hkn+&pzxm8tfwi6~{Ks>6&u*{g_n zo}uN2@5_g^w35DGiw|Zo@&h+OllBGHQb zz4rT!8SK5_4n=t5#;*>~P}PV8`N(@+LCZQ~a@|EMo4%=y{+lLGxk(9WiVce0RM{Oi zmO4{RwBW_-x)Jt;kdN4!LzX+4lGOdYc8ff<>TAPa8EGaHh&?o*$($l}U;d>az3Y=_ zxANw&+w9DSU$*dhOsvT}!(t9YvDgbMZ13gYhkdG+o7rIRltJ||j?V>75h1)CU~@yK zS}{H|;hv`c?;Ef?J3VNrpNv2I{F$IK^=)#ZkQMeLXN_A)uQ8i<8|dG`I|AwzaJg>O zVE8VbZogT+1R2MHPdQ}h@ELIYTmof+>TEKk=x|JIU{}}et-OK>Q-ve((2(d({Y77i_ z;DYArv83l9kv*=}6N|O+O5)%rLE+}+zSrI!sip5Uu_lj;XPK4d*B5+m7vq+Nt*xHC z2)di`{EH+)+@=G(h`gGzvQ=Yl42*kpEWPG4XsM+#kN7Jtak(c6|9?SScKM3Rn!=7p zi$C1Q4A~d7<@h;onX^;!IC~boyeD5@dq0<)Sq@AB2@h zt#2^woEnoptlj3=Ag9sTH~#e36jlH7%sWusInItepkcPuLha$ZWA3b$f)5pnvjK

|;`@Ys-r08%|wBmshjt^#p10M-Qf(WSi!06KXTc$xkNbyU2| zfg*T>Wxfe;dU^JcvUa=7uh3-T00Z{8D8Nd%esYj(toU#;T;44vN=d3dzkmq|r-0=w zB{-2okdXcK3)lRjXWLxvMe5?s>vYd&z-S+8A)>q*Ej9Lh&W87Ka6_}z-RjU~k2}HR zLH{Kgnuq*39SzCfACmg9Wa_RP&-wRuFTmyz$)FZ zm!CpilK0c$)PFBvTy=K6zdrj4MqxN!^$i>g&8d`vBYKCmDPfBpmpJo?+P6a(qSO;D z-AilXOWuR@S|c|!J0INW{c!FGG-&$nrN8gV^3g%lzSsQ1xVvU$hAk?GeA-R z4{S4Mv?rTS{@sb9RAD~HJ$&`TmnseM{1;Wpy8ZwpG4EXTiq*K$C}sEi(<6Y2pg-bX z2OlvwC+xLT=Ti2WF9UTA$!dqKFzlS6-)?BnAYZ(~sxn{~OjE+6C<|IhF#4=^+J9Q{ zceFXrN;fRI2%L!8+o|*~LGT>ndcl)lQc_o(`My<*JUBQ6Q9Gc(3LSV!5EeuaY)Zq4 z9IJuy+N~mT^=y!+)^?m2q;It5%?Il64H)!ty%6HG6H5Z?w!6)XVV>ymL)At+7%`7{ z&P4(V)e@>4h@JLWFk>F6$llCsA2Ypb_^UVHm3a9M%XFnE}qW>+ix?^9ByRc6t@V3yq8oZ^4N#uop%p^!t2BVMqZn*3*LWJMDN{xzg6*FP zG%WNerwyoV&57R6EUvh!dK0pT0 zOu=5M9y?mf!_$+cublNS78MuxAbsRmjX-8as3;E=cmpepYMr1ldgA|Wy9_N z#rq(Hjd1AolA%e0r(B3w-$8-97%zNI|p%Z)E~59~}X`d$ycw$c@$hh$vnr}K~u zMTojuu?BJx&;ukx$i>Yrg>G45|EEbbPTFfKl*KqX*sKROSz@9#1KP^U!@pZgo`H7U z(JZ!dTq$srdNt0$rV25BDKZ-H0frT!x%n0saV;1c!4?xf9Au<<_UhHNeVF$lo`SaL zgXwD{7CeLj>ib5_M%~&XdO zX|015us6kF)`DH=%hdiE9nJb&YNe1ES%-KtgS*5&>^rZdB|q#LZ#S!Zj>`7LUUOWe z`AD9#HTpj;K*N#6pt(Y;ivuHV03PHIEO7)>!jR>>-8HbQ#K5-W8CO{u>xcjq6HRV!AkuBzu}K1(J7C@y zfJradmO%o@OBW0mKI4WOms3Eaf2OAH)uCZqKQC$}|bR(Yiix}P1zm=ElBu1G3NpB1tuJ85y+B;t?C(lbPH?2o-Y&@Z3iH)5d8 zEl`uzRkWdMc5~>CwfFcVombPHS+w_uSvM!%`;#M!YD>XpYS`IMAj)->xgoi@Kx~2l zD=sR6vhzo3;6aB;!Wa99*K9l${14$cHK{IY1)@LyiZH<1ef<1DEBq}!z8moEw=Z72 zhzkHaYF`*-X=UDb2kFhk-mB8iAt4HR{a^azB^2gVes0CDnQR zIa4rM#r z7u=Y$MzuV5XL)JtEl|^|7YnzWQF2OYWi&LVZQ}0>oP|}z{4;cd@i+Lt)f(ZbL6D6w zFp*cS&tN-{ZXg$^9Bj)Y0`V%*nbv z<9Lm}#wB~BXnHJ8PleL?S2aEZOpE8oe$_2z!A2Br*H^NS9r{bFPKvN|uOH7U;B{=8 z^Use}UHmOpZF9dLrNCj+AZ!&~>vp%HY4*4?YEjZj|F-)|@A}2&tMIr#zt2ZBPE_oN zHWn9ODmt*NMbP{Z%^(!#_FLpjcv!VJ8-eMj%NXeQRbCAv(VY6WyZ+(!M(Wm1LR_=h z!?a4XCm<(WLwX^k41X%j-2MPQ^{)dTbs?r-)@NYR1guBMe@O*O1hCd-W@n{S z9}*NmFyi=@hHXupEMxpA3s14(5HEdgQ+Ux8{l49}H$6kaQCosW0XWA|N*@Y~ac2at zDW#RzC6^fABi%H|`siLkD(O~xd%#yR?>9$6oo?6?%ZGj417Xo4gUR9u(v07Xr|Joo z92R^XHO|4k>Yv-CMK4!K3fJ8v&Qwc-voJ&{Wy=`nY6%$)m-2tXA3#q(ks7piS!kDv zDm7s^x=nu|Bq;Mu{Bzmkr&MV#?i;<6vh*d7ZnB`t?|QQGvp+71JxWY6ev|!N!cLNZ zuajG{hkK&Ge~el787vGV%U%oB-IvLD_wvPytGG7{&~M@Xs;MIB-iB=!d9&M(i%_)a!se_V=^CqBu4h!4i*CqqDv^71lZ>gewFP|AL7 zXU7gu$qyMSS|xr~*8AWN4Y(P?9t*utPr677ol7O5~sPoo`k26zm z)Y#e%&+TqEDOk1QvJ^Q@`$}k7W>Etn{EKim{;~;px6@WI5L+#t);ZuSs`bYarWs#X zart~_`8d?Dcv9kzTxe3xZHt|4q2EM-FC!MQ|FR`rNKmLaJ2Pwqk#hH1rxMxtf6Pv$ z$LoI7PRI6?0A0cZj27?S?Zt5cYB|S;`I}(b^BEK&AYNTt!H#+ZR$0$P8ekQY54s6Z z#ApEAhnFcim6n?;EUZsa73b;bZaKfXe@I%GNjT)__#30HryC37x&z}E&ki*EGM>7` z0125;?3%#NmJzgUN_FmPnMC8WdUTk+w{3K<*NYL8 z6xer96JLUD3j~XP2lrfrhWyX7X^w;^I(6AVkD%*3R1t#X}RUAOr;-)Pa$7_4nbQ&Vqb5)toYg(RJgSbS!fj%mv?cOnwi zRB&_S=i=h}JvkYWlS7B{5omp&goFdGwXo?$&i>y=y9)n20famPhzMWYboo+zp~41` zP2U861s#sU!dr4)MIi^y#e>7ZlUQXJmtU)^EnSmpWy8ad+k5Zc#Y#HWUcn_KwCCb# zm*>o;1)CKRRl+YcG&E#Y7W$S9egV5hYvaJ{CT8Qm_y1-c_)PrhHJDz428ZwDCSt(* zW&(alfPa7lO8~!b=y5$@?o8mHdRlB~5FHcKJKo2%x^V1*hQ{%G^3zI5iGBUZLs24P zjSSIAxtR{BD7#&(S&~a9aR`Cu?m&c1z9-$`^+H<=H`&d z#R^oro%O;V0bC&tE-t?FmpIURe|v@w?QG%EGlJU_r8x3@jVkf#zx#djYNJmI3iIo^ z&E7NEL=HXn)C$k0y|uRbdt$;g|MHxTh2=3bGY+`5f;( z?gk35u(fs3$m+cy!~ecz(O&~d__0KS8O$en&SoFfz5s|?Xf>YO4h!y{^YimN zLU%z!n)gPPpd1Ji_MDu&miaDgbtn=xwogh^Zv?QhDHxe!Cud?*dEEIP)u2w_%Px!$ zt8!KcYz1|75=htb0yyYpx(pICNuDb#xY+#Pr@v=tZ2SeTJUKZ$0EfQ9Kc)E746GEv z-UjS};0k?|jl$~UGCVu~^}a+vUZ+rVZKRnohTV-DA#}a9 zHfwl5Wnp4w?)~%UDuDJ#{OH@{dw_nkDH1;|;Q8NIEeMM(_^OqZm3O+iw=}>T2`@b+ zHWpJPcp3uMdMj8Q*j>ILM1vt?oa&)|hUVhnbu;P9LXY#m@# zdp^Di5g@Eis!Va_6xnbONsW*Bu5UgXU*B*~^1ppCX?iQRvk1-PnX`$>caoR*gJWaV z^bI{-UDr^+D)I_w2|VGw>cT%E_Ws3!|DQWqT;ulb+u*_UtD~b4+8@uaU$6T9;RPxW zGMTBXt5;oKoGO%mNETWRHgw@OwE3BYvw?;dsipmegMuQ<+8Y1;OMDdjvC+ibO2U68 zEnqp8>dH?~FFA=e*x&!<8U`MslX*vp3*6eg7p;OiwEsQD6K_VNA zQx`}F;dy5PPDe=oS6_b2b`MVrSpjF?x~_Uu=F`)=8_Qlo2ex^H+E0c{o!2)|oN=ak z=`gA3=_7Jq0wq}scJ0W&8v1tO+ZC3l(fI#+&KK~8A_fM)N_^t;6edK?K}Wb`;08t< za)D924F=?q+~F-h!0E->&aT7!7`8lLr|MAD;+PI{OC85X8%DaZ;N3#1>)9UkJRQE< z(DmG=pr8Qw=f#hA8sN_cZ~T?)60Z@;g% z7gZ$K0vJlr#65+$df@&r8;dh#BUXtpECZ^CB$Fb^u|O4TPk3<(&vpJdS7-O#-~AcZy4St#wN@;s$5b|SZpJE*&fVyW ze4*Y6?H9?IWrT91+zWlupiqj)5efulK7r^a2!$2+p#}w!hb%8%yfc9^quVIJRpux` zFn#zd%(7$63m&!^+DwPUJvDUh6KO}3#*`eEAr(C#qr{M5`ZX3yK)?7Qdj|y_wK7$ z;Js?|Yp;yar?LWScoQ?TO#^fR{{9*E&T3MggNLQ5_hoGZj4|#DD$g#o(S zk+Gqm?1D7yoSPe%M{mTnwgav5j}sC)P<>}^ZS8mXiJFm7bWRg@D2fK4we7&{DvAeA zMn^&0?AFt#PrvS8xAnUDh0ZgyYq{1Q!`0Ejb##23A1VM=pVA9CpjR+*5M>6QC|Dv5 zq|;Uhp1>6)Ws+zC&j7bpf}Al%X|Y-6NsFRua7encg5w|sO?P12z?gZ$w¥#Igh} z-2Sy=@SvS3=|!aor#IY)ZB+4^nho(SNIW1l|dAjJl7 zr)P5wq;><>%D@IZH7X7=g0IfN7;gLhW#jFy=yy>H0430|txMjx^HQcFrxsiD!Ws3& z94NP*V2l3j@&T{axI3s?jjUhF8;9Mp4i*e_VkJ}UIffoEFsBv!p z_3I`;d>jglPWYIh6{zyLb3#yhQz+ zg1mt}MGY1mv=Kt-syYs+p2nJNfRU1ym&f5mliYPkoTs&X4MDH^cSnqA;5u|S!w!rv zA*NR9%)*z6{=y*#97uZl6q|we+1|(dFh+|_Hj)Fp64Z%+rBeHOxFZy2zAXh(tbk4- z12eg@`>#pHBL=w2n)>1e7nWg|R~+bp`fUEc&;EhzJ}ezM`kQZ@yXtL~{==UoxPa4E z8%uE`BCwepK1-^sD=kkH zyYb+tW@RmhAiV_bd`=H@k2<0}n2f-yZf<5n&t9AW4j`LriHV6hhR(5Q!U>TB3{`A# zF(2j|-kR_T^s{`ZrY7);1_s~UEQ+i%z`SYr2)_IsW~?t?zQn>o_(nQ+!qNgLo7ZrU z+Rk^n&n%^o!a#^78JL)uL>xvP(UbK~V#)8e;-$c~yC@IjopWKA_$A~P*6JK_4iNUD zX*fxFqoLgPtHi6R!dn*=@sftSn7nf}yy1}srk!)aCN7=Du3kM*96ti@I?O){pw0k*FIjheiKs&wPA^vY<7p~j=PiE1s zzAymfBe9z!Tnsh~2+(6A;^OFu%_zK@t@$z0k1KEwY5ERolb%B64^gkeqD86Ajh$%Y zg4Pv8u?ByIdB(8k+7EVo_}b6Oc|7uE&N?cNieSbpTrw7P?ofVZjeB0SrQD*Iu`Qv)a9^ zk_JBxp*m?jkQxdQH{9Tda_azE2N`g~G@+(&v9i*I3#s@e*3E@iNrfScn1h>fS~Jg7E~nnNbAO#h3~@J7-2WSxHBO>sH{Ko{$%#3E;X{$2mc4>& zXVXbz+&zj%+uV4bsXdn)0x~3>5hY!|e3?RlgC&$)z0o;-Ybk!ILI%s4_X zKsapxyjN#>YK_QHEX3zKp=NWF8YD`g@XQLF7(w=lum|YPi!% z$mJp;Cj4o&9X*-GJ`RCqvO6=lqcMEzU`CBs;FQ15E>Iz%rxzM@Zdo=g}_rN z2h@;x_J-b5_MCH{Q}pR5=sFv&Dz44Aob&$b1yr0!Ok2^+@P4#{R9dNy zoL`e*&-myl;wOGIZ-re^L$NpV+FF;#&rI~YOCs}`da__OYG%BGgM)LLoc5ZS#1t~6 z;>IW|D`QnikTyE{43JE1#ouqKcqw}j*# zcmT6C7dR}<%*=%K&a#)wLi=)9Ip|$6&DjJM1h5;ZGcX{_qxpAvHatD?Vi8Oc4k~hV z5x=Z3?gEZ~Bd#)jF#r<&5wC0vKZLmfSRGD)Yozxq^CUONRc{`k6WOxG6Q|LIL4u#Z zl$;nXS(gWbR4C~lSKDiYPUjd&$_BZ=P(jw6s3)@+R)FthBVS=%S=z6ae4=&OOpOR46oMO}nnukM9CM0^cde9K^8!6bYO{Kk|LB z(QtjHP~0wC{7SG#do_Fx_$)Ar<(OZ89g<1QywMOCb5J#i?+ALNT)f1(n$WhUp zc}+eL6ISFR;$pa5VCnl^%?q&u-ft%f2*52xbTwB#0#HEbMHyH>q!5sEH^JvmfizC5H|M zL9efG9flrbd>JC263hbyWyApp?4x25)_%+1Kh=+BCA7HF#TH`~F`^8>$Uh)p-PnE9 zTf<0WnE0zD+X_9PQL9`WseJ;#jf^=(WChSPG~G7u_Ws1S3kZRzk(CCjdMMx_5Wo#5 zi-3M8r5z$6AB@#PEN+5E=*!eE)h%f($j{%Pxg1JEGOLW)t7IpWg0hAN6W9lDoD7I9 z=#c0JzL6$CAf@=&201yys7346u2n)yzLl&Dh^erY7N1-F{ojl(oU3c~uw6K*Cx971 zc)SKw&~QxvWucv@YHBKgw#lT0#r;RM*TqCcmK0BZuwKT=>4}j(h>efgZFf6={t1i` z&^OTIWy*KVip(j(<7fUp{&sjcM)P?G1#!Ss@Cyl@JK7`tAMz6;696sHgJtKTycPQ~ zb{o+y?^L6)T&ZX;M*Lo;jH5kP*@q8Wr>^lWUw)eU9tAhkfvLox$W>3D?nr8z zB17D9A&QC=;LOqI<6ctj^*9^_GWQLOKQ%o)ls-R|UVoA0{|Or3aQ}%iBlJbY!M>kA z2{y&Fp#{9f_4z8!1q63*kjFXvF6k(%sEUeYk&YXNmO=ZNg2!KKcIz>?_cvum=)U}_lqK+RSI)W-; z5DRFPuT|IkFY*M@nBuen{ufcLW0%w8_~s&4>~8@~JsQw=%NrL~?Nd{0JH3`lT&yUC zQt}4IRM4PSkZ=h4W_y6a!f^uyz=XocJl476U?xF>h&zv8m^8zfcs*x^6~R?&o3O$ z=O|1hJ`(M#EjaZP3Rv81f%G+&kO(CoNu=Tee*9 z3=~=3eu-R;D_lBU865@rtgS}gUAJ}l`6X7-q713;@*qcW8WFbPlp$OaP!PfS1VaB0 zBPjF>oqgc?V6dSZy#{^}K$;P@gDBtCrx9M>o$#=8a4^MuLK^lY+?d$cC2;f{j4n22F415 zk}Wd7;s{=*)FUF&(b2ikTF8Z113jiQkMV)A+jU8TntOSjx^NIlN=og}HS|08uiAx? zYdA&}93T_Wg9#U|yvL*uRZt#isc4zQi>woF5-J&NY;6(YiJi=^vv9@H>{YxK@Z=( zVT&Pq25}1V`d-$D?P7SD~PSJ&73qUjf|*KymaWc(q5Wo#l34-Z(Mur=R4KHOD% z+7-5&-FM*{bA<_hLuil9AluBUjnZodoO{gU#Y2>rEyi5qdofL!DcE>0@FZGAtRs3j zJ2`n@E4`kPQ7}lyHvxkHl9r*oc#5wV?ZL-S!lnRw5?|L5u;Wk?#-0*7 zlate=L%ZS*P#rk57(fcNb$(d>b6wz`N$xX4EXPRvBDRf2%rf=mH2%h9FIJaY4?qALKs37V-1RmW-lhDy~vs9Xj0fc6->Q+t4kKr@jdZ_IvLi@8a-9@}-Y z^^RgVI^-Y3df-AmJJv$5;i6Ow9Ym~tnUV|XVZfL&j^Wn7S5?Rlh6DjAVfS$8Nzo&n zp<$Crf46YEkmal#UX<2VUO+eaXnWq`Rp%A{WE^Tb4 zOmT*u1o?=d!9pRJx|h=min@DC2HpqrO~J8ak`8U53>FsZIGHJn3{V9!1qj-)JAPv` zBq{yb0>fgLDlf|b^Db#;;R;|kI5hMMxA?sthPke$-6g;aPxSO&@4-ItRv0G1@n0HH zdmoDfjMv6I#&V=72GQM${pTcr7Pv%|{hUVj5dj4@?_6K~<*!XmWZiH&J3s3i<-BRy zhMnqG|AVijP^c)=6W2JqVH14G{^ycZLv~;*auoOipcbHEH;;Sw?wQEDBTPaQBt*v@ zEe>rtUs^@4yamYIvxgCmk3wdvo@*<&1FW6o7Nj7jf_yhjMhWq2SD9)|o2^z5aGl zEYF`0y*ntfk`)Q~`|(0#c@}W&fmqN}K;sw~>iErP&0x*`ZCD=gRm=UB^1X(m2bqBh z&>!laOoI0T#h^HvO^oYMM>%Y;)YX@$mU~P01t}+XkaAa--g|L(kht-k3vRp)UT87c zD^S#cn5QR)yH(wCVE~aigqQdN8S<&C-K!++Elxq|Nu(AC=7~GMZ^!9oW|oMng%4BE z8=E2i@O8wB*`NQx+7B%F@g$e2-b8erR7S-g;q~tOJ3VY|J%w`*Xa%VP9{|F;EeY^~ z*ir$=c`%8Y(0ypm2!h8L@z1am2p}9_Fx|)os-jGC0g6MdFzf`|vx1$*4RD7d`;Pvn zG0&c@OfMW}B_qGO%+e8SgDru*y=&ygg(#+wOHMi+Ea1%W-QsI1F{C05^Zm?+xnWnr zkWH1Ae$~*RU&Po8NdfKo3w%0vE-GY@%EG{hH3&+jq-^(o#M>%|2|iSG=iPrt6kN$U zmf-jCAn>trz}3z_dc?%U?(MLO(6p4^v4bB-09OIYR2W89{0fq;op;4%RL3nWSIF4t z=mwZj(q9cTEjHZf2x%L?7aEErCL}2w2ri*9lXS3@#TQ_fnJ*$BC{)}g3ff+wT~n7` zenEkW_*#sQ550Sri9%A?yBP?ajWe_EXM~gSH+RA4YD|xKg}`hO!dO#ST~(*2hOlK8?227L$euke4wage@J z_zFxy71UHg;Vh{@0JZ*o(?g_jt6N%TKXGIuZ3FfoBK0*mI#>)4#=gi7xiAbD4{Ri= zs1aitMD#|FJ|en67E2YG&2nk5U72QBaOdU6?!)QAAQ8rs zkX2AUfIw8r69~U^#}{BaE;Ex8#Vn*P3s?g!dnAO4T-dV~=)=U416NzZ2#Q#Ut}78! z#ptEr82BN;Xuqw0imT=dvEBG3oXeJB#HSBZg%S7})0m026fI52JRk(2Lc6lFvJP{U z{BC`@1a02&_Aq<9ZD+~D|Ay{#6a*vy65uWZ@P9XIX`*8~{I3gkfi!~#H(~0j?UzX7 zI*t|CryXxS-PqhL3i3)s#5*ny0n!d$6=g(4l?!l68TtnlIN(c4;2?+UEM1VrL9B>5 zQL5;e0Y=!yCc`J6Cjv1L$n$mx8YmvHX*|dvij?XjzG1peU7%pZL{e4$!+9pWJbzT(K4 zx}Y7J&dVAzDejG$%YnTzE;LHG48CFlzn5_^PqpX!cSaaE5NPX2o&-ttq^gwUWEdf^ zX{H!L1yV%yzyUVMG!E2}T=8*MTKZ7vKEwxvjSf8j8Qp4@(t!vZ=v33Eo8xdU*&YeQfXS^xuIui2*P|hMpvnW4;B^{ zCT`dSbfnJA9K;#~3n6`slMgNwx8QhEQ$>MoFO^Kexy7H5t}1Z)Tw^b2-X4S&9YyqH z{z}pZ1%i$BJUkk%3gk!dE&Pb<@BqX+Ftf1%E9$hw+ztzasRqTus=RCv5;KFO+6oaw z$;Gox#WA2r2oNQiH%y~D6nXsUQRD(Ft*z0{=TRZk1<}RsSp72wH1r?QE-NR8^M9$g z<{!*o=8fH4T3hH>NlrN$R_!b{d^bn`fP zc<9uK8cD}x#1t$atQ+bvpao%5US@1Bpjy@jjQ!~4GpwtiEC+T?cKMp6fAot2Dg%SS$O-NX!jtf4_J}h#{q&v z%RHF4v#$7y}_ap*XQS000ngeszIi@3G5^$G_v0<4pTcH>yO zK)m3_{pjuW+u=c^rZxlmGv^e6&Fq$)O`7cgW(Fqf-;jwCA1Zn@Z6NFWs2 z^w2>(z&p-`&;)UMP0b>AcXu$g4Gj%!C&|OrXxQ2O;S^dyV`7^x^5-C6z{M&TFVJ{E zS%|gps8^}3cJ}sYr3`YGWB4Qa4wTxJ*4AD*X7;(E;hl2{0)h7L--QO~*7aT_Q&JcS^5?BQk?Q>+@z@(9Oth1-!uCa+YIaK*!sefCQ%u4J6!FT}Atu7-UHfB!B`?)7pK5FA z!68A~hNG*pvfS_KMmKcAS`RvgXbbDpy!XX>K~T^*)z{ZoN_YfFp9OHlQ}ok$^=uH7 ziXmT(d@0Ff!Qmq0BEnekt%hynvRh?`Y<+!PM%~xw34r26Mnp_lY~ZI* zkQh*FYZP7Se9ex)2;Aj5LZ;ydAdjXwy%~BWfDx!dhqlcRZ!3%X+V}hSoi*QjdV1*p ze3$LcJ7SDCR=e}}$re^tK6~Pn|65qfJ|&Ml5n3c~pt5$x2p@!g#t`;*>j@=18Kvyr z7z+cPf$Ec^98T(2#6i}>=i->5`5ELD!OqkF5MQ!uVNpy;@(j%Qv)o+VR&ZSBJ`Lc- z!S#@7D`beMR;vcM3b(nDXaQkiR%Aud9Fe!?3h0Q-6o>@LX1t?2rljOiISm4UpPPfm z0GPf(X|&CcPa8>O4#VEiFcI?+dP-u~X+l4hWs9NNbEvaJYMhT9wlqP<`Ew6Ajs3Xu6WGk56E}BEE$GhzS)1N-+}k1==4Gi747s45A2g_i!XC z*6|ypcJ35_@&wXSKD!nW4Mf@mElx&WUIpLWAk&w|M)uxDEDYFRm^^AQiK9cvyuiQ@ zNz(*uN=Vawj9x+mp~+#(gJD3xH4n#p9Ds-c1_JKR1ko5wF^*nbG92DDlrBF4)c~&B zA0sGG;=FA6^5HtOk&zJu?nJ2=t!Tti;wzy}F#j2?1q#Ak0vdpiArBwkM13x@Ux3-O zF&_bWmZa$|p%CfLi4zYs`#@kUqO`hATcL^3tH#F3>uu?&so?OWrKC#Uz1x2(fe&F) zSQO5uzo=(8RpYOB5K>RvFhGDpbbNEfyhXmLLS*3(Od#(KVI<7@BGT|O*1%z)RUN!X zhC=`n7=*M3PQaWg8nB5|4eP$8Cv$$T#NL2b3XP5q#xH9hnEO2tHFdz73ZnETzzilf2sTyD?9!eiID~MiIdFUkXtoIPJrT+kxlH<7qS*;ai$F!8s-#q6 zTCA_D`;U$%hzJuvM3TT3z739&`;se;Rcz)>DvPLPk@)ef(#R&3@_)`Ej#y0j()hKs zwUt-W?0w14^xv<>#U6m`lkDJzy5`Sltqvk!e^Q!)^D{@fB*H?%PU3)L&{S!NC5Q#s zUvB(1RgUzVdq{o*^gKZ1F3OUnOZln?kfKzRin8gY$49jG^=v!WQLGSp@UQ`+;ktD) zv%8q-i(XWHfs8cbtAR^wOYknwkH(c9>Sa%%i{$_rjB7E!7Morxl6w z4wUPa#;U8PkZX)S$eqY{LbL0eo<4A-EW>(J2}z|>pitOC4lexfuEoSuM6l67TKGPc za~#%=e5E+wyk068`6G-ldtY^P}Uoiqg#V9>DQy4V!ErRG58|BwliK z)b`AoGmpT1NuGO8M5uhzd)@%m!f7IGqoY7FG>D1wDo>7WD;B`-tX8X_Vy=im zBn@pQ`=n=#_}rvYUmAH=?v-a{V)FBIOP~oPpzu^(seYBO0n3Hh3~KTX%!_d6C%#+> z0Pmh1JJT;yDLw>mN(jmjEr1}^7%QMIFe7b&SqAD}u+6+H zo~=mo7N_jhmh+Bm+Cfht02A;41{|T3DJWS=QDaj)O~nWxMM5e#rlDq}rAaad{d0gZ z+<#<${b~R{AL#&;Df^NSqC^DQ?6|o|Vkw1IP|4dmZHtn{U7Mi?Xt?Pys7L5MlI8*QVe!T*s|U z##Am9hz&fc@}}41tIW-*fUx?S-NZ$Dx2a;c>nXdgX5>igu4LS-?;H19n;|wX4qwC! zh7oKL5IGrkQs&E!^fWQ>(OUpd@J(Bdif(Q>l0byz1gm%b!nkrIWg$nSry%pzefAFm zS)pkj>dzCQdPpe~9=ZFziph%VowL(Iiqiu{(f(`ZUBu8|wD{j|Wq#X{dPSB|=ejHD z_kq51iU>$D5Y!;P8;|*j5eU%xf_VLpIx~ENgeg+@FPRZtw3ZA#eaZci-aqd1vw1&y zfBUlN`N+q{r>y|p3i=@_HT7Q6&UGdmP5@g2jsRNCF3PX;VqyW+ z63S`k&nDT@V(4S>jP%p*U8S$rYkrBAm$c+oS06+#&!Gengl@aLub|?WL8NUYU)^TTIB4hn%k*3g1WE@-) zW#WfQX6M1`)gjZ7= z-Ap}$q2;3!6ZDj)U0tQ+ja&c{n2KF~vzHfyz-#lK=gF3RHd4FFPorpNl}lz6Km#$RsKyRd-sRT&e0#+WWnK8W*?1YANrd!Pi>m6MSlJ)$H#d z{`RcT-SK|-;q?Oci3~9X4(C%YbVUlSHujgf?b&C$Q~unYAK00cQY_bZ(CWF{pPkm< z&JD3cltxcM072?44sI50W+7iAPa}^d9#mCreYQ66&9=>@p{A8@Dhq-T1uNhEDkt;B zbSQS2sNr(Pp`692cw>8^Jzqj`n{W>sob(j<(cdrKoh~kT$XQ)W zMeDJLe)jjP?+@VAg?xTSSE8mWA$aQj?eEJO;+5d&i;owQbfQD9=H9R~# ztJ_xWxTiDsXWinD(U$!?$PfO(LNgNn$UnuDo2#9iJ-L2Tn5*Kj_WfVKqFNOWjNJ2m zRwfH{EI)izUw`M^DZGx=VG7rf!H8mY$8eeTb(>uVY6p+cF zrS*Zl7>AqPqJ+6=X(nem2<%iH+L@1T8$e-4YD&Qp=^VQZ9s!)OTen(D$70tVTb}>s zYZ~=en%YoP+P?AFht+YM8aj{3g8lgMOUf{;rvrK-2KpKJ2;A|?*LvX7e zx7N@gWVEs82Va*~sNqg4kB_3;vd6_w*o`?{8Z(H>X(9^S*ot;49*{p|X}He7;HHeL z0=-}HzSk|jdjjeQehz3@8!2v$-tYTzHf|lSf}+jhXg-;n`33Bz=VafPmvbcs^Ia25 zq-xJzuctYIM_-}jw9^s`iat;_%{RB${h+(W&;~XP54NhtDQTN)*yOF_SMDy!v*V7v zpPj93N0`F9uU6F6*+2tJOV0zm1XMG-*6XfUxN|eB2`V=hlsAei{3z+p-Xw09+$0dq zha>DhHM762?sM?{UUABEM~oO+SRE&WeOkoZBeC_{{9NOFY4KcNo+&@p z2kQ1OO^qE6eXkPB=H|zL@0NKxMd|!A@;mgU%JRJ`92@CWlsE+Z_*LF++$&_hY|+LO zxnG6lF=O0LHd4F)nW@>cwEj9-gP$K9gI6glhwNi`Qb!LNr0JoH%-fj@Si;U^PmeDR zKChLbyw`2|x0~Yp?=x+iCN~Z2o-Qm-OTCv+I#a047bn#l&z^n{dK-$zHe)VEiqZ|F z-*jb`SLgQ2jsCilk~5Z;r=`(%%c{v@_v-qTpL)sG7q$Hw^wW+fGVxtiVdCJ?PO|&* zI!B~y%t@;Pk10t!=1WHji8W~YS~qACcd9K*H?P&r?_yDR?lrMe!OARA270#^*ZHif z1{2AICqEvlfY{;M>tK;$bi!J85uPx&gj?B^GUpiN$t7XQ0@Jl znHi@HCT~qmh};_Uv9>&sH+QyW`jfy{hxUV|sb#|>(|y{iraJO*;bLM5rgi~jRR)}&*Gl~A zxU|On&kNOCysTV%$FG|^A7EgZjF1{S{i5Zf=`K8LuvkWtJnU0lbE=IDiWv$Iz0-fH zSLPR(AYdm~yiIG}4y$@g!#=4wukAb^IUa1+l51;Wcl+Imi)I#Tt2dOGnGZ;CX@b&8giY`j+#rR1*ZolBm1odTdP~PfHBjI=LyA+kxv7 zd|&TD`J99EYQwO9o;*7fvL{%$_SSHK?!l0@{ssmd$KDt$T8Sr;<*S0E&X*Er>4;9ie==f)@R3$6z_-$x4!f6X}_Gka7|rvx7`=B_&ZijS)%)go{Qam zcUYA7?z_vCmyh45=opTVe-fXg4h4d&)34{R19usn74S`Yd?w`eL&d|p8XvA;q)z49AqB+Ec{j`b-trK%gRuLoBM22 zu1fDlZ0@S>J?95Jy}5ThJKEIN@?>bu&ClzwhL>h!UgrIz4_v$BC?AhpLSfMhyxXZ@ z4KA*ib@i)t-A);)^K-6RGuCiDSjS@T`Rh(*XN6a?B{}Hbi78%;&B`y$3hzycr%?7@ z_Ty;yxzwRG?(Qi!bp<1X;Ao%QNu^pJrdq7sp4`8Cs>Xz8^>wK&&2^7Y4h+;kqEnZx z`IHpqSuShy{FFE2%3hmU&Q)DKy^b=mt;g@nUd>XcD>ll#@Iv%%O-{b!zg;SnT{6XFCPN~LQchhLqYQt$t9lAOS^)MfTKCi-+| zZrzsk*9T=3SDhM8){vHw3!F=)Ver5NF zDEDvbw0HBMy?w{rEJB6zvc6ZogzXdy)YuQZ^NEhwE{>3v#JsnA*uvkH7yo`Lb7}ao z{Xk>NG0}6fta!oYYz}pJ&3_x#e9p4%<4>=MlXsq|>>Rom1Uu@nn0lF1S9bNBuYb>4 zyM6t}udPq7RBd^@8^=M3iTcCeNS=9_7DEYU-j-fV`f=BV^O<( zc~sj#gGcOKf+@ar1KlB5_;zvqtq-kbRZ2y~xRR9V1E|JdX%R6|B_>%ClD7T2ySFxS zHRVd1w^Led%j{Sgyc0VA`>!jF^qexmU(d8Mw5m=@(2ht7qbtu6eP=6(&j@ayuKZ^C zl{HJ#4J~B%sBGbqQJQETa&{eg>vQ?V^Kz_^QjaKzpxTY(l3Sj)`ds&RSAyxOn-u20*xr)- zJ~AoQSIB8_R8GJ1bs?(NV zGn04`&6_;B38h{xJhJe*Z_i&UXc6W*mio^U3n|w=!Q*$%Vpisyna&>tpD}3sa2<=m>!y{5Zvslwk)^pzWLT-Pb^&f z1rq`bmcOg4s*j!g?DXr2SykWkl#4>3to1c~^0SYrM)cy>!{z((CH;t-k*0EAEmF{SB39WG4z4cx9;Y-C=qzaM`>q?3cgrQCL;NeMfD<0pguix=`r__&r9=RN| ziBmkuim?gb&oOw@eTX<7lf_vE0w}-t9zL&>_lTTkpB(kL8|X+^Va2e>jpH@$pi)g7 yvBKmdZ*A_A>rMU{T}cc9`R6g)|Cj%|IZw%IS{rnb$;O*JRa0GC?Wu~f*M9*ah~|U< literal 0 HcmV?d00001 diff --git a/perception/image_projection_based_fusion/docs/roi-pointcloud-fusion.md b/perception/image_projection_based_fusion/docs/roi-pointcloud-fusion.md new file mode 100644 index 0000000000000..5d0b241a578d6 --- /dev/null +++ b/perception/image_projection_based_fusion/docs/roi-pointcloud-fusion.md @@ -0,0 +1,93 @@ +# roi_pointcloud_fusion + +## Purpose + +The node `roi_pointcloud_fusion` is to cluster the pointcloud based on Region Of Interests (ROIs) detected by a 2D object detector, specific for unknown labeled ROI. + +## Inner-workings / Algorithms + +- The pointclouds are projected onto image planes and extracted as cluster if they are inside the unknown labeled ROIs. +- Since the cluster might contain unrelated points from background, then a refinement step is added to filter the background pointcloud by distance to camera. + +![roi_pointcloud_fusion_image](./images/roi_pointcloud_fusion.png) + +## Inputs / Outputs + +### Input + +| Name | Type | Description | +| ------------------------ | -------------------------------------------------------- | --------------------------------------------------------- | +| `input` | `sensor_msgs::msg::PointCloud2` | input pointcloud | +| `input/camera_info[0-7]` | `sensor_msgs::msg::CameraInfo` | camera information to project 3d points onto image planes | +| `input/rois[0-7]` | `tier4_perception_msgs::msg::DetectedObjectsWithFeature` | ROIs from each image | +| `input/image_raw[0-7]` | `sensor_msgs::msg::Image` | images for visualization | + +### Output + +| Name | Type | Description | +| ----------------- | -------------------------------------------------------- | -------------------------------------------- | +| `output` | `sensor_msgs::msg::PointCloud2` | output pointcloud as default of interface | +| `output_clusters` | `tier4_perception_msgs::msg::DetectedObjectsWithFeature` | output clusters | +| `debug/clusters` | `sensor_msgs/msg/PointCloud2` | colored cluster pointcloud for visualization | + +## Parameters + +### Core Parameters + +| Name | Type | Description | +| ---------------------- | ------ | -------------------------------------------------------------------------------------------- | +| `min_cluster_size` | int | the minimum number of points that a cluster needs to contain in order to be considered valid | +| `cluster_2d_tolerance` | double | cluster tolerance measured in radial direction | +| `rois_number` | int | the number of input rois | + +## Assumptions / Known limits + +- Currently, the refinement is only based on distance to camera, the roi based clustering is supposed to work well with small object ROIs. Others criteria for refinement might needed in the future. + + + +## (Optional) Error detection and handling + + + +## (Optional) Performance characterization + + + +## (Optional) References/External links + + + +## (Optional) Future extensions / Unimplemented parts + + diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/fusion_node.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/fusion_node.hpp index 016633fa4ef92..5174aebe069a8 100644 --- a/perception/image_projection_based_fusion/include/image_projection_based_fusion/fusion_node.hpp +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/fusion_node.hpp @@ -29,6 +29,9 @@ #include #include #include +#include +#include +#include #include #include @@ -49,6 +52,8 @@ using autoware_auto_perception_msgs::msg::DetectedObjects; using sensor_msgs::msg::PointCloud2; using tier4_perception_msgs::msg::DetectedObjectsWithFeature; using tier4_perception_msgs::msg::DetectedObjectWithFeature; +using PointCloud = pcl::PointCloud; +using autoware_auto_perception_msgs::msg::ObjectClassification; template class FusionNode : public rclcpp::Node diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_pointcloud_fusion/node.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_pointcloud_fusion/node.hpp new file mode 100644 index 0000000000000..2b4eb822a9edb --- /dev/null +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_pointcloud_fusion/node.hpp @@ -0,0 +1,53 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef IMAGE_PROJECTION_BASED_FUSION__ROI_POINTCLOUD_FUSION__NODE_HPP_ +#define IMAGE_PROJECTION_BASED_FUSION__ROI_POINTCLOUD_FUSION__NODE_HPP_ + +#include "image_projection_based_fusion/fusion_node.hpp" + +#include +#include +namespace image_projection_based_fusion +{ +class RoiPointCloudFusionNode +: public FusionNode +{ +private: + int min_cluster_size_{1}; + bool fuse_unknown_only_{true}; + double cluster_2d_tolerance_; + + rclcpp::Publisher::SharedPtr pub_objects_ptr_; + std::vector output_fused_objects_; + rclcpp::Publisher::SharedPtr cluster_debug_pub_; + + /* data */ +public: + explicit RoiPointCloudFusionNode(const rclcpp::NodeOptions & options); + +protected: + void preprocess(sensor_msgs::msg::PointCloud2 & pointcloud_msg) override; + + void postprocess(sensor_msgs::msg::PointCloud2 & pointcloud_msg) override; + + void fuseOnSingleImage( + const PointCloud2 & input_pointcloud_msg, const std::size_t image_id, + const DetectedObjectsWithFeature & input_roi_msg, + const sensor_msgs::msg::CameraInfo & camera_info, PointCloud2 & output_pointcloud_msg) override; + bool out_of_scope(const DetectedObjectWithFeature & obj); +}; + +} // namespace image_projection_based_fusion +#endif // IMAGE_PROJECTION_BASED_FUSION__ROI_POINTCLOUD_FUSION__NODE_HPP_ diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/utils/utils.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/utils/utils.hpp index 541cf997412c2..d7fd3c3882046 100644 --- a/perception/image_projection_based_fusion/include/image_projection_based_fusion/utils/utils.hpp +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/utils/utils.hpp @@ -32,18 +32,54 @@ #include #endif +#include "image_projection_based_fusion/fusion_node.hpp" + +#include +#include +#include +#include + +#include "autoware_auto_perception_msgs/msg/shape.hpp" +#include "tier4_perception_msgs/msg/detected_object_with_feature.hpp" + +#include +#include +#include + #include #include +#include namespace image_projection_based_fusion { +using PointCloud = pcl::PointCloud; std::optional getTransformStamped( const tf2_ros::Buffer & tf_buffer, const std::string & target_frame_id, const std::string & source_frame_id, const rclcpp::Time & time); Eigen::Affine3d transformToEigen(const geometry_msgs::msg::Transform & t); +void convertCluster2FeatureObject( + const std_msgs::msg::Header & header, const PointCloud & cluster, + DetectedObjectWithFeature & feature_obj); +PointCloud closest_cluster( + PointCloud & cluster, const double cluster_2d_tolerance, const int min_cluster_size, + const pcl::PointXYZ & center); + +void updateOutputFusedObjects( + std::vector & output_objs, const std::vector & clusters, + const std_msgs::msg::Header & in_cloud_header, const std_msgs::msg::Header & in_roi_header, + const tf2_ros::Buffer & tf_buffer, const int min_cluster_size, const float cluster_2d_tolerance, + std::vector & output_fused_objects); + +geometry_msgs::msg::Point getCentroid(const sensor_msgs::msg::PointCloud2 & pointcloud); + +pcl::PointXYZ getClosestPoint(const pcl::PointCloud & cluster); +void addShapeAndKinematic( + const pcl::PointCloud & cluster, + tier4_perception_msgs::msg::DetectedObjectWithFeature & feature_obj); + } // namespace image_projection_based_fusion #endif // IMAGE_PROJECTION_BASED_FUSION__UTILS__UTILS_HPP_ diff --git a/perception/image_projection_based_fusion/launch/roi_pointcloud_fusion.launch.xml b/perception/image_projection_based_fusion/launch/roi_pointcloud_fusion.launch.xml new file mode 100644 index 0000000000000..181f4ccb88320 --- /dev/null +++ b/perception/image_projection_based_fusion/launch/roi_pointcloud_fusion.launch.xml @@ -0,0 +1,77 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/perception/image_projection_based_fusion/package.xml b/perception/image_projection_based_fusion/package.xml index 32d7a5633b811..5ff99af2ebb21 100644 --- a/perception/image_projection_based_fusion/package.xml +++ b/perception/image_projection_based_fusion/package.xml @@ -14,6 +14,7 @@ autoware_auto_perception_msgs autoware_point_types cv_bridge + euclidean_cluster image_transport lidar_centerpoint message_filters diff --git a/perception/image_projection_based_fusion/src/fusion_node.cpp b/perception/image_projection_based_fusion/src/fusion_node.cpp index 9ce34d8482fbd..447e66f076c0b 100644 --- a/perception/image_projection_based_fusion/src/fusion_node.cpp +++ b/perception/image_projection_based_fusion/src/fusion_node.cpp @@ -420,4 +420,5 @@ void FusionNode::publish(const Msg & output_msg) template class FusionNode; template class FusionNode; template class FusionNode; +template class FusionNode; } // namespace image_projection_based_fusion diff --git a/perception/image_projection_based_fusion/src/roi_cluster_fusion/node.cpp b/perception/image_projection_based_fusion/src/roi_cluster_fusion/node.cpp index 77f6a5c506d92..e9cb76b050427 100644 --- a/perception/image_projection_based_fusion/src/roi_cluster_fusion/node.cpp +++ b/perception/image_projection_based_fusion/src/roi_cluster_fusion/node.cpp @@ -171,12 +171,16 @@ void RoiClusterFusionNode::fuseOnSingleImage( for (const auto & feature_obj : input_roi_msg.feature_objects) { int index = 0; double max_iou = 0.0; + bool is_roi_label_known = + feature_obj.object.classification.front().label != ObjectClassification::UNKNOWN; for (const auto & cluster_map : m_cluster_roi) { double iou(0.0), iou_x(0.0), iou_y(0.0); if (use_iou_) { iou = calcIoU(cluster_map.second, feature_obj.feature.roi); } - if (use_iou_x_) { + // use for unknown roi to improve small objects like traffic cone detect + // TODO(badai-nguyen): add option to disable roi_cluster mode + if (use_iou_x_ || !is_roi_label_known) { iou_x = calcIoUX(cluster_map.second, feature_obj.feature.roi); } if (use_iou_y_) { @@ -192,8 +196,6 @@ void RoiClusterFusionNode::fuseOnSingleImage( } } if (!output_cluster_msg.feature_objects.empty()) { - bool is_roi_label_known = feature_obj.object.classification.front().label != - autoware_auto_perception_msgs::msg::ObjectClassification::UNKNOWN; bool is_roi_existence_prob_higher = output_cluster_msg.feature_objects.at(index).object.existence_probability <= feature_obj.object.existence_probability; diff --git a/perception/image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp b/perception/image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp new file mode 100644 index 0000000000000..233e568ebee0b --- /dev/null +++ b/perception/image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp @@ -0,0 +1,165 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "image_projection_based_fusion/roi_pointcloud_fusion/node.hpp" + +#include "image_projection_based_fusion/utils/geometry.hpp" +#include "image_projection_based_fusion/utils/utils.hpp" + +#ifdef ROS_DISTRO_GALACTIC +#include +#include +#else +#include +#include +#endif + +#include "euclidean_cluster/utils.hpp" + +namespace image_projection_based_fusion +{ +RoiPointCloudFusionNode::RoiPointCloudFusionNode(const rclcpp::NodeOptions & options) +: FusionNode("roi_pointcloud_fusion", options) +{ + fuse_unknown_only_ = declare_parameter("fuse_unknown_only"); + min_cluster_size_ = declare_parameter("min_cluster_size"); + cluster_2d_tolerance_ = declare_parameter("cluster_2d_tolerance"); + pub_objects_ptr_ = + this->create_publisher("output_clusters", rclcpp::QoS{1}); + cluster_debug_pub_ = this->create_publisher("debug/clusters", 1); +} + +void RoiPointCloudFusionNode::preprocess(__attribute__((unused)) + sensor_msgs::msg::PointCloud2 & pointcloud_msg) +{ + return; +} + +void RoiPointCloudFusionNode::postprocess(__attribute__((unused)) + sensor_msgs::msg::PointCloud2 & pointcloud_msg) +{ + const auto objects_sub_count = pub_objects_ptr_->get_subscription_count() + + pub_objects_ptr_->get_intra_process_subscription_count(); + if (objects_sub_count < 1) { + return; + } + + DetectedObjectsWithFeature output_msg; + output_msg.header = pointcloud_msg.header; + output_msg.feature_objects = output_fused_objects_; + + if (objects_sub_count > 0) { + pub_objects_ptr_->publish(output_msg); + } + output_fused_objects_.clear(); + // publish debug cluster + if (cluster_debug_pub_->get_subscription_count() > 0) { + sensor_msgs::msg::PointCloud2 debug_cluster_msg; + euclidean_cluster::convertObjectMsg2SensorMsg(output_msg, debug_cluster_msg); + cluster_debug_pub_->publish(debug_cluster_msg); + } +} +void RoiPointCloudFusionNode::fuseOnSingleImage( + const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, + __attribute__((unused)) const std::size_t image_id, + const DetectedObjectsWithFeature & input_roi_msg, + const sensor_msgs::msg::CameraInfo & camera_info, + __attribute__((unused)) sensor_msgs::msg::PointCloud2 & output_pointcloud_msg) +{ + if (input_pointcloud_msg.data.empty()) { + return; + } + std::vector output_objs; + // select ROIs for fusion + for (const auto & feature_obj : input_roi_msg.feature_objects) { + if (fuse_unknown_only_) { + bool is_roi_label_unknown = feature_obj.object.classification.front().label == + autoware_auto_perception_msgs::msg::ObjectClassification::UNKNOWN; + if (is_roi_label_unknown) { + output_objs.push_back(feature_obj); + } + } else { + // TODO(badai-nguyen): selected class from a list + output_objs.push_back(feature_obj); + } + } + if (output_objs.empty()) { + return; + } + + // transform pointcloud to camera optical frame id + Eigen::Matrix4d projection; + projection << camera_info.p.at(0), camera_info.p.at(1), camera_info.p.at(2), camera_info.p.at(3), + camera_info.p.at(4), camera_info.p.at(5), camera_info.p.at(6), camera_info.p.at(7), + camera_info.p.at(8), camera_info.p.at(9), camera_info.p.at(10), camera_info.p.at(11); + geometry_msgs::msg::TransformStamped transform_stamped; + { + const auto transform_stamped_optional = getTransformStamped( + tf_buffer_, input_roi_msg.header.frame_id, input_pointcloud_msg.header.frame_id, + input_roi_msg.header.stamp); + if (!transform_stamped_optional) { + return; + } + transform_stamped = transform_stamped_optional.value(); + } + + sensor_msgs::msg::PointCloud2 transformed_cloud; + tf2::doTransform(input_pointcloud_msg, transformed_cloud, transform_stamped); + + std::vector clusters; + clusters.resize(output_objs.size()); + + for (sensor_msgs::PointCloud2ConstIterator iter_x(transformed_cloud, "x"), + iter_y(transformed_cloud, "y"), iter_z(transformed_cloud, "z"), + iter_orig_x(input_pointcloud_msg, "x"), iter_orig_y(input_pointcloud_msg, "y"), + iter_orig_z(input_pointcloud_msg, "z"); + iter_x != iter_x.end(); + ++iter_x, ++iter_y, ++iter_z, ++iter_orig_x, ++iter_orig_y, ++iter_orig_z) { + if (*iter_z <= 0.0) { + continue; + } + Eigen::Vector4d projected_point = projection * Eigen::Vector4d(*iter_x, *iter_y, *iter_z, 1.0); + Eigen::Vector2d normalized_projected_point = Eigen::Vector2d( + projected_point.x() / projected_point.z(), projected_point.y() / projected_point.z()); + + for (std::size_t i = 0; i < output_objs.size(); ++i) { + auto & feature_obj = output_objs.at(i); + const auto & check_roi = feature_obj.feature.roi; + auto & cluster = clusters.at(i); + + if ( + check_roi.x_offset <= normalized_projected_point.x() && + check_roi.y_offset <= normalized_projected_point.y() && + check_roi.x_offset + check_roi.width >= normalized_projected_point.x() && + check_roi.y_offset + check_roi.height >= normalized_projected_point.y()) { + cluster.push_back(pcl::PointXYZ(*iter_orig_x, *iter_orig_y, *iter_orig_z)); + } + } + } + + // refine and update output_fused_objects_ + updateOutputFusedObjects( + output_objs, clusters, input_pointcloud_msg.header, input_roi_msg.header, tf_buffer_, + min_cluster_size_, cluster_2d_tolerance_, output_fused_objects_); +} + +bool RoiPointCloudFusionNode::out_of_scope(__attribute__((unused)) + const DetectedObjectWithFeature & obj) +{ + return false; +} +} // namespace image_projection_based_fusion + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(image_projection_based_fusion::RoiPointCloudFusionNode) diff --git a/perception/image_projection_based_fusion/src/utils/utils.cpp b/perception/image_projection_based_fusion/src/utils/utils.cpp index 670c5596001fb..76cd1e3c61e82 100644 --- a/perception/image_projection_based_fusion/src/utils/utils.cpp +++ b/perception/image_projection_based_fusion/src/utils/utils.cpp @@ -13,7 +13,6 @@ // limitations under the License. #include "image_projection_based_fusion/utils/utils.hpp" - namespace image_projection_based_fusion { @@ -39,4 +38,197 @@ Eigen::Affine3d transformToEigen(const geometry_msgs::msg::Transform & t) return a; } +void convertCluster2FeatureObject( + const std_msgs::msg::Header & header, const PointCloud & cluster, + DetectedObjectWithFeature & feature_obj) +{ + PointCloud2 ros_cluster; + pcl::toROSMsg(cluster, ros_cluster); + ros_cluster.header = header; + feature_obj.feature.cluster = ros_cluster; + feature_obj.object.kinematics.pose_with_covariance.pose.position = getCentroid(ros_cluster); + feature_obj.object.existence_probability = 1.0f; +} + +PointCloud closest_cluster( + PointCloud & cluster, const double cluster_2d_tolerance, const int min_cluster_size, + const pcl::PointXYZ & center) +{ + // sort point by distance to camera origin + + auto func = [center](const pcl::PointXYZ & p1, const pcl::PointXYZ & p2) { + return tier4_autoware_utils::calcDistance2d(center, p1) < + tier4_autoware_utils::calcDistance2d(center, p2); + }; + std::sort(cluster.begin(), cluster.end(), func); + PointCloud out_cluster; + for (auto & point : cluster) { + if (out_cluster.empty()) { + out_cluster.push_back(point); + continue; + } + if (tier4_autoware_utils::calcDistance2d(out_cluster.back(), point) < cluster_2d_tolerance) { + out_cluster.push_back(point); + continue; + } + if (out_cluster.size() >= static_cast(min_cluster_size)) { + return out_cluster; + } + out_cluster.clear(); + out_cluster.push_back(point); + } + return out_cluster; +} + +void updateOutputFusedObjects( + std::vector & output_objs, const std::vector & clusters, + const std_msgs::msg::Header & in_cloud_header, const std_msgs::msg::Header & in_roi_header, + const tf2_ros::Buffer & tf_buffer, const int min_cluster_size, const float cluster_2d_tolerance, + std::vector & output_fused_objects) +{ + if (output_objs.size() != clusters.size()) { + return; + } + Eigen::Vector3d orig_camera_frame, orig_point_frame; + Eigen::Affine3d camera2lidar_affine; + orig_camera_frame << 0.0, 0.0, 0.0; + { + const auto transform_stamped_optional = getTransformStamped( + tf_buffer, in_cloud_header.frame_id, in_roi_header.frame_id, in_roi_header.stamp); + if (!transform_stamped_optional) { + return; + } + camera2lidar_affine = transformToEigen(transform_stamped_optional.value().transform); + } + orig_point_frame = camera2lidar_affine * orig_camera_frame; + pcl::PointXYZ camera_orig_point_frame = + pcl::PointXYZ(orig_point_frame.x(), orig_point_frame.y(), orig_point_frame.z()); + + for (std::size_t i = 0; i < output_objs.size(); ++i) { + PointCloud cluster = clusters.at(i); + auto & feature_obj = output_objs.at(i); + if (cluster.points.size() < std::size_t(min_cluster_size)) { + continue; + } + + // TODO(badai-nguyen): change to interface to select refine criteria like closest, largest + // to output refine cluster and centroid + auto refine_cluster = + closest_cluster(cluster, cluster_2d_tolerance, min_cluster_size, camera_orig_point_frame); + if (refine_cluster.points.size() < std::size_t(min_cluster_size)) { + continue; + } + + refine_cluster.width = refine_cluster.points.size(); + refine_cluster.height = 1; + refine_cluster.is_dense = false; + // convert cluster to object + convertCluster2FeatureObject(in_cloud_header, refine_cluster, feature_obj); + output_fused_objects.push_back(feature_obj); + } +} + +void addShapeAndKinematic( + const pcl::PointCloud & cluster, + tier4_perception_msgs::msg::DetectedObjectWithFeature & feature_obj) +{ + if (cluster.empty()) { + return; + } + pcl::PointXYZ centroid = pcl::PointXYZ(0.0, 0.0, 0.0); + float max_z = -1e6; + float min_z = 1e6; + for (const auto & point : cluster) { + centroid.x += point.x; + centroid.y += point.y; + centroid.z += point.z; + max_z = max_z < point.z ? point.z : max_z; + min_z = min_z > point.z ? point.z : min_z; + } + centroid.x = centroid.x / static_cast(cluster.size()); + centroid.y = centroid.y / static_cast(cluster.size()); + centroid.z = centroid.z / static_cast(cluster.size()); + + std::vector cluster2d; + std::vector cluster2d_convex; + + for (size_t i = 0; i < cluster.size(); ++i) { + cluster2d.push_back( + cv::Point((cluster.at(i).x - centroid.x) * 1000.0, (cluster.at(i).y - centroid.y) * 1000.)); + } + cv::convexHull(cluster2d, cluster2d_convex); + if (cluster2d_convex.empty()) { + return; + } + pcl::PointXYZ polygon_centroid = pcl::PointXYZ(0.0, 0.0, 0.0); + for (size_t i = 0; i < cluster2d_convex.size(); ++i) { + polygon_centroid.x += static_cast(cluster2d_convex.at(i).x) / 1000.0; + polygon_centroid.y += static_cast(cluster2d_convex.at(i).y) / 1000.0; + } + polygon_centroid.x = polygon_centroid.x / static_cast(cluster2d_convex.size()); + polygon_centroid.y = polygon_centroid.y / static_cast(cluster2d_convex.size()); + + autoware_auto_perception_msgs::msg::Shape shape; + for (size_t i = 0; i < cluster2d_convex.size(); ++i) { + geometry_msgs::msg::Point32 point; + point.x = cluster2d_convex.at(i).x / 1000.0; + point.y = cluster2d_convex.at(i).y / 1000.0; + point.z = 0.0; + shape.footprint.points.push_back(point); + } + shape.type = autoware_auto_perception_msgs::msg::Shape::POLYGON; + constexpr float eps = 0.01; + shape.dimensions.x = 0; + shape.dimensions.y = 0; + shape.dimensions.z = std::max((max_z - min_z), eps); + feature_obj.object.shape = shape; + feature_obj.object.kinematics.pose_with_covariance.pose.position.x = + centroid.x + polygon_centroid.x; + feature_obj.object.kinematics.pose_with_covariance.pose.position.y = + centroid.y + polygon_centroid.y; + feature_obj.object.kinematics.pose_with_covariance.pose.position.z = + min_z + shape.dimensions.z * 0.5; + feature_obj.object.existence_probability = 1.0; + feature_obj.object.kinematics.pose_with_covariance.pose.orientation.x = 0; + feature_obj.object.kinematics.pose_with_covariance.pose.orientation.y = 0; + feature_obj.object.kinematics.pose_with_covariance.pose.orientation.z = 0; + feature_obj.object.kinematics.pose_with_covariance.pose.orientation.w = 1; +} + +geometry_msgs::msg::Point getCentroid(const sensor_msgs::msg::PointCloud2 & pointcloud) +{ + geometry_msgs::msg::Point centroid; + centroid.x = 0.0f; + centroid.y = 0.0f; + centroid.z = 0.0f; + for (sensor_msgs::PointCloud2ConstIterator iter_x(pointcloud, "x"), + iter_y(pointcloud, "y"), iter_z(pointcloud, "z"); + iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) { + centroid.x += *iter_x; + centroid.y += *iter_y; + centroid.z += *iter_z; + } + const size_t size = pointcloud.width * pointcloud.height; + centroid.x = centroid.x / static_cast(size); + centroid.y = centroid.y / static_cast(size); + centroid.z = centroid.z / static_cast(size); + return centroid; +} + +pcl::PointXYZ getClosestPoint(const pcl::PointCloud & cluster) +{ + pcl::PointXYZ closest_point; + double min_dist = 1e6; + pcl::PointXYZ orig_point = pcl::PointXYZ(0.0, 0.0, 0.0); + for (std::size_t i = 0; i < cluster.points.size(); ++i) { + pcl::PointXYZ point = cluster.points.at(i); + double dist_closest_point = tier4_autoware_utils::calcDistance2d(point, orig_point); + if (min_dist > dist_closest_point) { + min_dist = dist_closest_point; + closest_point = pcl::PointXYZ(point.x, point.y, point.z); + } + } + return closest_point; +} + } // namespace image_projection_based_fusion