From 402ef62f6b810d5cf5ea557d93a54a2cd3e1757f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Bar=C4=B1=C5=9F=20Zeren?= Date: Tue, 1 Oct 2024 16:49:26 +0300 Subject: [PATCH 01/19] feat: mask cluster fusion MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Barış Zeren --- .../CMakeLists.txt | 6 + .../config/mask_cluster_fusion.param.yaml | 12 + .../mask_cluster_fusion/node.hpp | 46 ++++ .../launch/mask_cluster_fusion.launch.xml | 72 ++++++ .../src/fusion_node.cpp | 1 + .../src/mask_cluster_fusion/node.cpp | 233 ++++++++++++++++++ 6 files changed, 370 insertions(+) create mode 100644 perception/autoware_image_projection_based_fusion/config/mask_cluster_fusion.param.yaml create mode 100644 perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/mask_cluster_fusion/node.hpp create mode 100644 perception/autoware_image_projection_based_fusion/launch/mask_cluster_fusion.launch.xml create mode 100644 perception/autoware_image_projection_based_fusion/src/mask_cluster_fusion/node.cpp diff --git a/perception/autoware_image_projection_based_fusion/CMakeLists.txt b/perception/autoware_image_projection_based_fusion/CMakeLists.txt index 73d305d2ab2a8..423ed0222de5a 100644 --- a/perception/autoware_image_projection_based_fusion/CMakeLists.txt +++ b/perception/autoware_image_projection_based_fusion/CMakeLists.txt @@ -24,6 +24,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/roi_detected_object_fusion/node.cpp src/segmentation_pointcloud_fusion/node.cpp src/roi_pointcloud_fusion/node.cpp + src/mask_cluster_fusion/node.cpp ) target_link_libraries(${PROJECT_NAME} @@ -51,6 +52,11 @@ rclcpp_components_register_node(${PROJECT_NAME} EXECUTABLE roi_pointcloud_fusion_node ) +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "autoware::image_projection_based_fusion::MaskClusterFusionNode" + EXECUTABLE mask_cluster_fusion_node +) + set(CUDA_VERBOSE OFF) # set flags for CUDA availability diff --git a/perception/autoware_image_projection_based_fusion/config/mask_cluster_fusion.param.yaml b/perception/autoware_image_projection_based_fusion/config/mask_cluster_fusion.param.yaml new file mode 100644 index 0000000000000..90ba841d53b2d --- /dev/null +++ b/perception/autoware_image_projection_based_fusion/config/mask_cluster_fusion.param.yaml @@ -0,0 +1,12 @@ +/**: + ros__parameters: + fusion_distance: 100.0 + trust_object_distance: 100.0 + trust_object_iou_mode: "iou" + non_trust_object_iou_mode: "iou_x" + use_cluster_semantic_type: false + only_allow_inside_cluster: true + roi_scale_factor: 1.1 + iou_threshold: 0.65 + unknown_iou_threshold: 0.1 + remove_unknown: true diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/mask_cluster_fusion/node.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/mask_cluster_fusion/node.hpp new file mode 100644 index 0000000000000..6d68ed675f730 --- /dev/null +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/mask_cluster_fusion/node.hpp @@ -0,0 +1,46 @@ +#include "autoware/image_projection_based_fusion/fusion_node.hpp" + +#include + +#include + +#include +#include + +namespace autoware::image_projection_based_fusion { + const std::map IOU_MODE_MAP{{"iou", 0}, + {"iou_x", 1}, + {"iou_y", 2}}; + + class MaskClusterFusionNode + : public FusionNode { + public: + explicit MaskClusterFusionNode(const rclcpp::NodeOptions &options); + + protected: + void preprocess(DetectedObjectsWithFeature &output_msg) override; + + void postprocess(DetectedObjectsWithFeature &output_msg) override; + + void fuseOnSingleImage( + const DetectedObjectsWithFeature &input_cluster_msg, const std::size_t image_id, + const SegmentationMask &input_mask_msg, + const sensor_msgs::msg::CameraInfo &camera_info, + DetectedObjectsWithFeature &output_object_msg) override; + + bool out_of_scope(const DetectedObjectWithFeature & obj) override; + + std::string trust_object_iou_mode_{"iou"}; + bool use_cluster_semantic_type_{false}; + bool only_allow_inside_cluster_{false}; + double roi_scale_factor_{1.1}; + double iou_threshold_{0.0}; + double unknown_iou_threshold_{0.0}; + const float min_roi_existence_prob_ = + 0.1; // keep small value to lessen affect on merger object stage + bool remove_unknown_; + double fusion_distance_; + double trust_object_distance_; + std::string non_trust_object_iou_mode_{"iou_x"}; + }; +} // namespace autoware::image_projection_based_fusion \ No newline at end of file diff --git a/perception/autoware_image_projection_based_fusion/launch/mask_cluster_fusion.launch.xml b/perception/autoware_image_projection_based_fusion/launch/mask_cluster_fusion.launch.xml new file mode 100644 index 0000000000000..7a3fa3eee0565 --- /dev/null +++ b/perception/autoware_image_projection_based_fusion/launch/mask_cluster_fusion.launch.xml @@ -0,0 +1,72 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp b/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp index 16a089fcc6d09..c9a4fe9a33ebe 100644 --- a/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp @@ -439,4 +439,5 @@ template class FusionNode< template class FusionNode; template class FusionNode; template class FusionNode; +template class FusionNode; } // namespace autoware::image_projection_based_fusion diff --git a/perception/autoware_image_projection_based_fusion/src/mask_cluster_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/mask_cluster_fusion/node.cpp new file mode 100644 index 0000000000000..8aafc2cf11817 --- /dev/null +++ b/perception/autoware_image_projection_based_fusion/src/mask_cluster_fusion/node.cpp @@ -0,0 +1,233 @@ +#include "autoware/image_projection_based_fusion/mask_cluster_fusion/node.hpp" + +#include "autoware/image_projection_based_fusion/utils/geometry.hpp" +#include "autoware/image_projection_based_fusion/utils/utils.hpp" + +#include "autoware/euclidean_cluster/utils.hpp" + +namespace autoware::image_projection_based_fusion { + bool is_far_enough( + const DetectedObjectWithFeature &obj, const double distance_threshold) { + const auto &position = obj.object.kinematics.pose_with_covariance.pose.position; + return position.x * position.x + position.y * position.y > + distance_threshold * distance_threshold; + } + + MaskClusterFusionNode::MaskClusterFusionNode(const rclcpp::NodeOptions &options) + : FusionNode( + "mask_cluster_fusion", options) { + trust_object_iou_mode_ = declare_parameter("trust_object_iou_mode"); + non_trust_object_iou_mode_ = declare_parameter("non_trust_object_iou_mode"); + use_cluster_semantic_type_ = declare_parameter("use_cluster_semantic_type"); + only_allow_inside_cluster_ = declare_parameter("only_allow_inside_cluster"); + roi_scale_factor_ = declare_parameter("roi_scale_factor"); + iou_threshold_ = declare_parameter("iou_threshold"); + unknown_iou_threshold_ = declare_parameter("unknown_iou_threshold"); + remove_unknown_ = declare_parameter("remove_unknown"); + fusion_distance_ = declare_parameter("fusion_distance"); + trust_object_distance_ = declare_parameter("trust_object_distance"); + } + + void MaskClusterFusionNode::preprocess( + __attribute__((unused)) DetectedObjectsWithFeature &output_msg) { + return; + } + + void MaskClusterFusionNode::postprocess( + __attribute__((unused)) DetectedObjectsWithFeature &output_msg) { + return; + } + + void MaskClusterFusionNode::fuseOnSingleImage( + __attribute__((unused)) const DetectedObjectsWithFeature &input_cluster_msg, + __attribute__((unused)) const std::size_t image_id, + __attribute__((unused)) const SegmentationMask &input_mask_msg, + __attribute__((unused)) const sensor_msgs::msg::CameraInfo &camera_info, + __attribute__((unused)) DetectedObjectsWithFeature &output_object_msg) { + if (!checkCameraInfo(camera_info)) return; + + if (input_mask_msg.image.height == 0 || input_mask_msg.image.width == 0) { + return; + } + + // Convert mask to cv::Mat - Resize mask to the same size as the camera image + cv_bridge::CvImagePtr in_image_ptr; + try { + in_image_ptr = cv_bridge::toCvCopy( + std::make_shared(input_mask_msg.image), + input_mask_msg.image.encoding); + } catch (const std::exception &e) { + RCLCPP_ERROR(this->get_logger(), "cv_bridge exception:%s", e.what()); + return; + } + cv::Mat mask = in_image_ptr->image; + const int orig_width = camera_info.width; + const int orig_height = camera_info.height; + // resize mask to the same size as the camera image + cv::resize(mask, mask, cv::Size(orig_width, orig_height), 0, 0, cv::INTER_NEAREST); + + image_geometry::PinholeCameraModel pinhole_camera_model; + pinhole_camera_model.fromCameraInfo(camera_info); + + // get transform from cluster frame id to camera optical frame id + geometry_msgs::msg::TransformStamped transform_stamped; + { + const auto transform_stamped_optional = getTransformStamped( + tf_buffer_, /*target*/ camera_info.header.frame_id, + /*source*/ input_cluster_msg.header.frame_id, camera_info.header.stamp); + if (!transform_stamped_optional) { + RCLCPP_WARN_STREAM( + get_logger(), "Failed to get transform from " << input_cluster_msg.header.frame_id << " to " + << camera_info.header.frame_id); + return; + } + transform_stamped = transform_stamped_optional.value(); + } + + std::map m_cluster_roi; + std::map m_cluster_label; + for (std::size_t i = 0; i < input_cluster_msg.feature_objects.size(); ++i) { + if (input_cluster_msg.feature_objects.at(i).feature.cluster.data.empty()) { + continue; + } + + if (is_far_enough(input_cluster_msg.feature_objects.at(i), fusion_distance_)) { + continue; + } + + // filter point out of scope + if (debugger_ && out_of_scope(input_cluster_msg.feature_objects.at(i))) { + continue; + } + + sensor_msgs::msg::PointCloud2 transformed_cluster; + tf2::doTransform( + input_cluster_msg.feature_objects.at(i).feature.cluster, transformed_cluster, + transform_stamped); + + std::vector selected_projected_points; + auto min_x(static_cast(camera_info.width)); + auto min_y(static_cast(camera_info.height)); + int32_t max_x(0); + int32_t max_y(0); + selected_projected_points.reserve(transformed_cluster.data.size()); + std::vector point_counter_each_class = {0, 0, 0, 0, 0, 0, 0, 0}; + for (sensor_msgs::PointCloud2ConstIterator iter_x(transformed_cluster, "x"), + iter_y(transformed_cluster, "y"), iter_z(transformed_cluster, "z"); + iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) { + if (*iter_z <= 0.0) { + continue; + } + + Eigen::Vector2d projected_point = + calcRawImageProjectedPoint(pinhole_camera_model, cv::Point3d(*iter_x, *iter_y, *iter_z)); + + if (0 >= static_cast(projected_point.x()) || + static_cast(projected_point.x()) >= static_cast(camera_info.width) - 1 || + 0 >= static_cast(projected_point.y()) || + static_cast(projected_point.y()) >= static_cast(camera_info.height) - 1) { + continue; + } + + const uint8_t pixel_value = mask.at( + static_cast(projected_point.y()), static_cast(projected_point.x())); + const auto label_id = static_cast(static_cast(input_mask_msg.config.classification[ + pixel_value - 1].label)); + if (pixel_value != 0) { + min_x = std::min(static_cast(projected_point.x()), min_x); + min_y = std::min(static_cast(projected_point.y()), min_y); + max_x = std::max(static_cast(projected_point.x()), max_x); + max_y = std::max(static_cast(projected_point.y()), max_y); + + selected_projected_points.push_back(projected_point); + point_counter_each_class[label_id]++; + } + } + if (selected_projected_points.empty()) { + continue; + } + + sensor_msgs::msg::RegionOfInterest roi; + roi.x_offset = min_x; + roi.y_offset = min_y; + roi.width = max_x - min_x; + roi.height = max_y - min_y; + m_cluster_roi.insert(std::make_pair(i, roi)); + + auto max_it = std::max_element(point_counter_each_class.begin(), point_counter_each_class.end()); + int32_t max_index = std::distance(point_counter_each_class.begin(), max_it); + m_cluster_label.insert(std::make_pair(i, max_index)); + + std::cout << "max_index = " << max_index << std::endl; + + output_object_msg.feature_objects.at(i).feature.roi = roi; + + std::vector classification; + autoware_perception_msgs::msg::ObjectClassification object_classification; + object_classification.label = static_cast(max_index); + object_classification.probability = 1.0; + classification.push_back(object_classification); + output_object_msg.feature_objects.at(i).object.classification = classification; + } + std::cout << "m_cluster_roi.size() = " << m_cluster_roi.size() << std::endl; + + + + +// cv_bridge::CvImagePtr in_image_ptr; +// try { +// in_image_ptr = cv_bridge::toCvCopy( +// std::make_shared(input_mask_msg.image), +// input_mask_msg.image.encoding); +// } catch (const std::exception &e) { +// RCLCPP_ERROR(this->get_logger(), "cv_bridge exception:%s", e.what()); +// return; +// } +// +// cv::Mat mask = in_image_ptr->image; +// +// for (int row = 0; row < mask.rows; ++row) { +// for (int col = 0; col < mask.cols; ++col) { +// if (mask.at(row, col) != 0) { +// mask.at(row, col) = 255; +// } +// } +// } +// +// cv::imshow("result", mask); +// cv::waitKey(1); + } + + bool MaskClusterFusionNode::out_of_scope(const DetectedObjectWithFeature &obj) { + auto cluster = obj.feature.cluster; + bool is_out = false; + auto valid_point = [](float p, float min_num, float max_num) -> bool { + return (p > min_num) && (p < max_num); + }; + + for (sensor_msgs::PointCloud2ConstIterator iter_x(cluster, "x"), iter_y(cluster, "y"), + iter_z(cluster, "z"); + iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) { + if (!valid_point(*iter_x, filter_scope_min_x_, filter_scope_max_x_)) { + is_out = true; + break; + } + + if (!valid_point(*iter_y, filter_scope_min_y_, filter_scope_max_y_)) { + is_out = true; + break; + } + + if (!valid_point(*iter_z, filter_scope_min_z_, filter_scope_max_z_)) { + is_out = true; + break; + } + } + + return is_out; + } +} // namespace autoware::image_projection_based_fusion + +#include + +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::image_projection_based_fusion::MaskClusterFusionNode) \ No newline at end of file From 39f989e001d4fd50d655a9c7f9bc27369f707b97 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Bar=C4=B1=C5=9F=20Zeren?= Date: Thu, 10 Oct 2024 18:21:34 +0300 Subject: [PATCH 02/19] chore: update fusion node MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Barış Zeren --- .../config/mask_cluster_fusion.param.yaml | 13 +- .../mask_cluster_fusion/node.hpp | 62 ++- .../src/mask_cluster_fusion/node.cpp | 417 +++++++++--------- 3 files changed, 233 insertions(+), 259 deletions(-) diff --git a/perception/autoware_image_projection_based_fusion/config/mask_cluster_fusion.param.yaml b/perception/autoware_image_projection_based_fusion/config/mask_cluster_fusion.param.yaml index 90ba841d53b2d..ca97dc0286e5b 100644 --- a/perception/autoware_image_projection_based_fusion/config/mask_cluster_fusion.param.yaml +++ b/perception/autoware_image_projection_based_fusion/config/mask_cluster_fusion.param.yaml @@ -1,12 +1,5 @@ /**: ros__parameters: - fusion_distance: 100.0 - trust_object_distance: 100.0 - trust_object_iou_mode: "iou" - non_trust_object_iou_mode: "iou_x" - use_cluster_semantic_type: false - only_allow_inside_cluster: true - roi_scale_factor: 1.1 - iou_threshold: 0.65 - unknown_iou_threshold: 0.1 - remove_unknown: true + fusion_distance: 100.0 # the distance threshold for the fusion + fusion_ratio: 0.4 # the ratio between the selected cluster points and the total points in the cluster + remove_unknown: true # remove unknown clusters \ No newline at end of file diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/mask_cluster_fusion/node.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/mask_cluster_fusion/node.hpp index 6d68ed675f730..372ab8d861209 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/mask_cluster_fusion/node.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/mask_cluster_fusion/node.hpp @@ -7,40 +7,28 @@ #include #include -namespace autoware::image_projection_based_fusion { - const std::map IOU_MODE_MAP{{"iou", 0}, - {"iou_x", 1}, - {"iou_y", 2}}; - - class MaskClusterFusionNode - : public FusionNode { - public: - explicit MaskClusterFusionNode(const rclcpp::NodeOptions &options); - - protected: - void preprocess(DetectedObjectsWithFeature &output_msg) override; - - void postprocess(DetectedObjectsWithFeature &output_msg) override; - - void fuseOnSingleImage( - const DetectedObjectsWithFeature &input_cluster_msg, const std::size_t image_id, - const SegmentationMask &input_mask_msg, - const sensor_msgs::msg::CameraInfo &camera_info, - DetectedObjectsWithFeature &output_object_msg) override; - - bool out_of_scope(const DetectedObjectWithFeature & obj) override; - - std::string trust_object_iou_mode_{"iou"}; - bool use_cluster_semantic_type_{false}; - bool only_allow_inside_cluster_{false}; - double roi_scale_factor_{1.1}; - double iou_threshold_{0.0}; - double unknown_iou_threshold_{0.0}; - const float min_roi_existence_prob_ = - 0.1; // keep small value to lessen affect on merger object stage - bool remove_unknown_; - double fusion_distance_; - double trust_object_distance_; - std::string non_trust_object_iou_mode_{"iou_x"}; - }; -} // namespace autoware::image_projection_based_fusion \ No newline at end of file +namespace autoware::image_projection_based_fusion +{ +class MaskClusterFusionNode +: public FusionNode +{ +public: + explicit MaskClusterFusionNode(const rclcpp::NodeOptions & options); + +protected: + void preprocess(DetectedObjectsWithFeature & output_msg) override; + + void postprocess(DetectedObjectsWithFeature & output_msg) override; + + void fuseOnSingleImage( + const DetectedObjectsWithFeature & input_cluster_msg, const std::size_t image_id, + const SegmentationMask & input_mask_msg, const sensor_msgs::msg::CameraInfo & camera_info, + DetectedObjectsWithFeature & output_object_msg) override; + + bool out_of_scope(const DetectedObjectWithFeature & obj) override; + + double fusion_distance_; + double fusion_ratio_; + bool remove_unknown_; +}; +} // namespace autoware::image_projection_based_fusion \ No newline at end of file diff --git a/perception/autoware_image_projection_based_fusion/src/mask_cluster_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/mask_cluster_fusion/node.cpp index 8aafc2cf11817..c40dd279453e3 100644 --- a/perception/autoware_image_projection_based_fusion/src/mask_cluster_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/mask_cluster_fusion/node.cpp @@ -1,232 +1,225 @@ #include "autoware/image_projection_based_fusion/mask_cluster_fusion/node.hpp" +#include "autoware/euclidean_cluster/utils.hpp" #include "autoware/image_projection_based_fusion/utils/geometry.hpp" #include "autoware/image_projection_based_fusion/utils/utils.hpp" -#include "autoware/euclidean_cluster/utils.hpp" +namespace autoware::image_projection_based_fusion +{ +bool is_far_enough(const DetectedObjectWithFeature & obj, const double distance_threshold) +{ + const auto & position = obj.object.kinematics.pose_with_covariance.pose.position; + return position.x * position.x + position.y * position.y > + distance_threshold * distance_threshold; +} + +MaskClusterFusionNode::MaskClusterFusionNode(const rclcpp::NodeOptions & options) +: FusionNode( + "mask_cluster_fusion", options) +{ + fusion_distance_ = declare_parameter("fusion_distance"); + fusion_ratio_ = declare_parameter("fusion_ratio"); + remove_unknown_ = declare_parameter("remove_unknown"); +} + +void MaskClusterFusionNode::preprocess(__attribute__((unused)) + DetectedObjectsWithFeature & output_msg) +{ + return; +} + +void MaskClusterFusionNode::postprocess(__attribute__((unused)) + DetectedObjectsWithFeature & output_msg) +{ + if (!remove_unknown_) { + return; + } + DetectedObjectsWithFeature known_objects; + known_objects.feature_objects.reserve(output_msg.feature_objects.size()); + for (auto & feature_object : output_msg.feature_objects) { + bool is_roi_label_known = feature_object.object.classification.front().label != + autoware_perception_msgs::msg::ObjectClassification::UNKNOWN; + if (is_roi_label_known) { + known_objects.feature_objects.push_back(feature_object); + } + } + output_msg.feature_objects = known_objects.feature_objects; +} + +void MaskClusterFusionNode::fuseOnSingleImage( + __attribute__((unused)) const DetectedObjectsWithFeature & input_cluster_msg, + __attribute__((unused)) const std::size_t image_id, + __attribute__((unused)) const SegmentationMask & input_mask_msg, + __attribute__((unused)) const sensor_msgs::msg::CameraInfo & camera_info, + __attribute__((unused)) DetectedObjectsWithFeature & output_object_msg) +{ + if (!checkCameraInfo(camera_info)) return; + + if (input_mask_msg.image.height == 0 || input_mask_msg.image.width == 0) { + return; + } + + // Convert mask to cv::Mat - Resize mask to the same size as the camera image + cv_bridge::CvImagePtr in_image_ptr; + try { + in_image_ptr = cv_bridge::toCvCopy( + std::make_shared(input_mask_msg.image), + input_mask_msg.image.encoding); + } catch (const std::exception & e) { + RCLCPP_ERROR(this->get_logger(), "cv_bridge exception:%s", e.what()); + return; + } + cv::Mat mask = in_image_ptr->image; + const int orig_width = camera_info.width; + const int orig_height = camera_info.height; + // resize mask to the same size as the camera image + cv::resize(mask, mask, cv::Size(orig_width, orig_height), 0, 0, cv::INTER_NEAREST); + + image_geometry::PinholeCameraModel pinhole_camera_model; + pinhole_camera_model.fromCameraInfo(camera_info); + + // get transform from cluster frame id to camera optical frame id + geometry_msgs::msg::TransformStamped transform_stamped; + { + const auto transform_stamped_optional = getTransformStamped( + tf_buffer_, /*target*/ camera_info.header.frame_id, + /*source*/ input_cluster_msg.header.frame_id, camera_info.header.stamp); + if (!transform_stamped_optional) { + RCLCPP_WARN_STREAM( + get_logger(), "Failed to get transform from " << input_cluster_msg.header.frame_id << " to " + << camera_info.header.frame_id); + return; + } + transform_stamped = transform_stamped_optional.value(); + } -namespace autoware::image_projection_based_fusion { - bool is_far_enough( - const DetectedObjectWithFeature &obj, const double distance_threshold) { - const auto &position = obj.object.kinematics.pose_with_covariance.pose.position; - return position.x * position.x + position.y * position.y > - distance_threshold * distance_threshold; + for (std::size_t i = 0; i < input_cluster_msg.feature_objects.size(); ++i) { + if (input_cluster_msg.feature_objects.at(i).feature.cluster.data.empty()) { + continue; } - MaskClusterFusionNode::MaskClusterFusionNode(const rclcpp::NodeOptions &options) - : FusionNode( - "mask_cluster_fusion", options) { - trust_object_iou_mode_ = declare_parameter("trust_object_iou_mode"); - non_trust_object_iou_mode_ = declare_parameter("non_trust_object_iou_mode"); - use_cluster_semantic_type_ = declare_parameter("use_cluster_semantic_type"); - only_allow_inside_cluster_ = declare_parameter("only_allow_inside_cluster"); - roi_scale_factor_ = declare_parameter("roi_scale_factor"); - iou_threshold_ = declare_parameter("iou_threshold"); - unknown_iou_threshold_ = declare_parameter("unknown_iou_threshold"); - remove_unknown_ = declare_parameter("remove_unknown"); - fusion_distance_ = declare_parameter("fusion_distance"); - trust_object_distance_ = declare_parameter("trust_object_distance"); + if (is_far_enough(input_cluster_msg.feature_objects.at(i), fusion_distance_)) { + continue; } - void MaskClusterFusionNode::preprocess( - __attribute__((unused)) DetectedObjectsWithFeature &output_msg) { - return; + // filter point out of scope + if (debugger_ && out_of_scope(input_cluster_msg.feature_objects.at(i))) { + continue; } - void MaskClusterFusionNode::postprocess( - __attribute__((unused)) DetectedObjectsWithFeature &output_msg) { - return; + sensor_msgs::msg::PointCloud2 transformed_cluster; + tf2::doTransform( + input_cluster_msg.feature_objects.at(i).feature.cluster, transformed_cluster, + transform_stamped); + + auto min_x(static_cast(camera_info.width)); + auto min_y(static_cast(camera_info.height)); + int32_t max_x(0); + int32_t max_y(0); + + double total_projected_points = 0; + std::vector point_counter_each_class = {0, 0, 0, 0, 0, 0, 0, 0}; + + for (sensor_msgs::PointCloud2ConstIterator iter_x(transformed_cluster, "x"), + iter_y(transformed_cluster, "y"), iter_z(transformed_cluster, "z"); + iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) { + if (*iter_z <= 0.0) { + continue; + } + + Eigen::Vector2d projected_point = + calcRawImageProjectedPoint(pinhole_camera_model, cv::Point3d(*iter_x, *iter_y, *iter_z)); + + if ( + 0 >= static_cast(projected_point.x()) || + static_cast(projected_point.x()) >= static_cast(camera_info.width) - 1 || + 0 >= static_cast(projected_point.y()) || + static_cast(projected_point.y()) >= static_cast(camera_info.height) - 1) { + continue; + } + + const uint8_t pixel_value = mask.at( + static_cast(projected_point.y()), static_cast(projected_point.x())); + const auto label_id = static_cast( + static_cast(input_mask_msg.config.classification[pixel_value - 1].label)); + if (pixel_value != 0) { + min_x = std::min(static_cast(projected_point.x()), min_x); + min_y = std::min(static_cast(projected_point.y()), min_y); + max_x = std::max(static_cast(projected_point.x()), max_x); + max_y = std::max(static_cast(projected_point.y()), max_y); + + point_counter_each_class[label_id]++; + } + total_projected_points++; } - void MaskClusterFusionNode::fuseOnSingleImage( - __attribute__((unused)) const DetectedObjectsWithFeature &input_cluster_msg, - __attribute__((unused)) const std::size_t image_id, - __attribute__((unused)) const SegmentationMask &input_mask_msg, - __attribute__((unused)) const sensor_msgs::msg::CameraInfo &camera_info, - __attribute__((unused)) DetectedObjectsWithFeature &output_object_msg) { - if (!checkCameraInfo(camera_info)) return; - - if (input_mask_msg.image.height == 0 || input_mask_msg.image.width == 0) { - return; - } - - // Convert mask to cv::Mat - Resize mask to the same size as the camera image - cv_bridge::CvImagePtr in_image_ptr; - try { - in_image_ptr = cv_bridge::toCvCopy( - std::make_shared(input_mask_msg.image), - input_mask_msg.image.encoding); - } catch (const std::exception &e) { - RCLCPP_ERROR(this->get_logger(), "cv_bridge exception:%s", e.what()); - return; - } - cv::Mat mask = in_image_ptr->image; - const int orig_width = camera_info.width; - const int orig_height = camera_info.height; - // resize mask to the same size as the camera image - cv::resize(mask, mask, cv::Size(orig_width, orig_height), 0, 0, cv::INTER_NEAREST); - - image_geometry::PinholeCameraModel pinhole_camera_model; - pinhole_camera_model.fromCameraInfo(camera_info); - - // get transform from cluster frame id to camera optical frame id - geometry_msgs::msg::TransformStamped transform_stamped; - { - const auto transform_stamped_optional = getTransformStamped( - tf_buffer_, /*target*/ camera_info.header.frame_id, - /*source*/ input_cluster_msg.header.frame_id, camera_info.header.stamp); - if (!transform_stamped_optional) { - RCLCPP_WARN_STREAM( - get_logger(), "Failed to get transform from " << input_cluster_msg.header.frame_id << " to " - << camera_info.header.frame_id); - return; - } - transform_stamped = transform_stamped_optional.value(); - } - - std::map m_cluster_roi; - std::map m_cluster_label; - for (std::size_t i = 0; i < input_cluster_msg.feature_objects.size(); ++i) { - if (input_cluster_msg.feature_objects.at(i).feature.cluster.data.empty()) { - continue; - } - - if (is_far_enough(input_cluster_msg.feature_objects.at(i), fusion_distance_)) { - continue; - } - - // filter point out of scope - if (debugger_ && out_of_scope(input_cluster_msg.feature_objects.at(i))) { - continue; - } - - sensor_msgs::msg::PointCloud2 transformed_cluster; - tf2::doTransform( - input_cluster_msg.feature_objects.at(i).feature.cluster, transformed_cluster, - transform_stamped); - - std::vector selected_projected_points; - auto min_x(static_cast(camera_info.width)); - auto min_y(static_cast(camera_info.height)); - int32_t max_x(0); - int32_t max_y(0); - selected_projected_points.reserve(transformed_cluster.data.size()); - std::vector point_counter_each_class = {0, 0, 0, 0, 0, 0, 0, 0}; - for (sensor_msgs::PointCloud2ConstIterator iter_x(transformed_cluster, "x"), - iter_y(transformed_cluster, "y"), iter_z(transformed_cluster, "z"); - iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) { - if (*iter_z <= 0.0) { - continue; - } - - Eigen::Vector2d projected_point = - calcRawImageProjectedPoint(pinhole_camera_model, cv::Point3d(*iter_x, *iter_y, *iter_z)); - - if (0 >= static_cast(projected_point.x()) || - static_cast(projected_point.x()) >= static_cast(camera_info.width) - 1 || - 0 >= static_cast(projected_point.y()) || - static_cast(projected_point.y()) >= static_cast(camera_info.height) - 1) { - continue; - } - - const uint8_t pixel_value = mask.at( - static_cast(projected_point.y()), static_cast(projected_point.x())); - const auto label_id = static_cast(static_cast(input_mask_msg.config.classification[ - pixel_value - 1].label)); - if (pixel_value != 0) { - min_x = std::min(static_cast(projected_point.x()), min_x); - min_y = std::min(static_cast(projected_point.y()), min_y); - max_x = std::max(static_cast(projected_point.x()), max_x); - max_y = std::max(static_cast(projected_point.y()), max_y); - - selected_projected_points.push_back(projected_point); - point_counter_each_class[label_id]++; - } - } - if (selected_projected_points.empty()) { - continue; - } - - sensor_msgs::msg::RegionOfInterest roi; - roi.x_offset = min_x; - roi.y_offset = min_y; - roi.width = max_x - min_x; - roi.height = max_y - min_y; - m_cluster_roi.insert(std::make_pair(i, roi)); - - auto max_it = std::max_element(point_counter_each_class.begin(), point_counter_each_class.end()); - int32_t max_index = std::distance(point_counter_each_class.begin(), max_it); - m_cluster_label.insert(std::make_pair(i, max_index)); - - std::cout << "max_index = " << max_index << std::endl; - - output_object_msg.feature_objects.at(i).feature.roi = roi; - - std::vector classification; - autoware_perception_msgs::msg::ObjectClassification object_classification; - object_classification.label = static_cast(max_index); - object_classification.probability = 1.0; - classification.push_back(object_classification); - output_object_msg.feature_objects.at(i).object.classification = classification; - } - std::cout << "m_cluster_roi.size() = " << m_cluster_roi.size() << std::endl; - - - - -// cv_bridge::CvImagePtr in_image_ptr; -// try { -// in_image_ptr = cv_bridge::toCvCopy( -// std::make_shared(input_mask_msg.image), -// input_mask_msg.image.encoding); -// } catch (const std::exception &e) { -// RCLCPP_ERROR(this->get_logger(), "cv_bridge exception:%s", e.what()); -// return; -// } -// -// cv::Mat mask = in_image_ptr->image; -// -// for (int row = 0; row < mask.rows; ++row) { -// for (int col = 0; col < mask.cols; ++col) { -// if (mask.at(row, col) != 0) { -// mask.at(row, col) = 255; -// } -// } -// } -// -// cv::imshow("result", mask); -// cv::waitKey(1); + bool all_zero = std::all_of( + point_counter_each_class.begin(), point_counter_each_class.end(), + [](double value) { return value == 0; }); + if (all_zero) { + continue; } - bool MaskClusterFusionNode::out_of_scope(const DetectedObjectWithFeature &obj) { - auto cluster = obj.feature.cluster; - bool is_out = false; - auto valid_point = [](float p, float min_num, float max_num) -> bool { - return (p > min_num) && (p < max_num); - }; - - for (sensor_msgs::PointCloud2ConstIterator iter_x(cluster, "x"), iter_y(cluster, "y"), - iter_z(cluster, "z"); - iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) { - if (!valid_point(*iter_x, filter_scope_min_x_, filter_scope_max_x_)) { - is_out = true; - break; - } - - if (!valid_point(*iter_y, filter_scope_min_y_, filter_scope_max_y_)) { - is_out = true; - break; - } - - if (!valid_point(*iter_z, filter_scope_min_z_, filter_scope_max_z_)) { - is_out = true; - break; - } - } - - return is_out; + auto max_it = + std::max_element(point_counter_each_class.begin(), point_counter_each_class.end()); + auto max_index = std::distance(point_counter_each_class.begin(), max_it); + + RCLCPP_DEBUG(get_logger(), "Number of points in the cluster: %f", *max_it); + RCLCPP_DEBUG(get_logger(), "Total projected points: %f", total_projected_points); + RCLCPP_DEBUG(get_logger(), "Fusion ratio: %f", *max_it / total_projected_points); + + if (*max_it / total_projected_points < fusion_ratio_) { + continue; } -} // namespace autoware::image_projection_based_fusion + + // Set classification of the object + std::vector classification; + autoware_perception_msgs::msg::ObjectClassification object_classification; + object_classification.label = static_cast(max_index); + object_classification.probability = 1.0; + classification.push_back(object_classification); + output_object_msg.feature_objects.at(i).object.classification = classification; + + // Set roi of the object + sensor_msgs::msg::RegionOfInterest roi; + roi.x_offset = min_x; + roi.y_offset = min_y; + roi.width = max_x - min_x; + roi.height = max_y - min_y; + output_object_msg.feature_objects.at(i).feature.roi = roi; + } +} + +bool MaskClusterFusionNode::out_of_scope(const DetectedObjectWithFeature & obj) +{ + auto cluster = obj.feature.cluster; + bool is_out = false; + auto valid_point = [](float p, float min_num, float max_num) -> bool { + return (p > min_num) && (p < max_num); + }; + + for (sensor_msgs::PointCloud2ConstIterator iter_x(cluster, "x"), iter_y(cluster, "y"), + iter_z(cluster, "z"); + iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) { + if (!valid_point(*iter_x, filter_scope_min_x_, filter_scope_max_x_)) { + is_out = true; + break; + } + + if (!valid_point(*iter_y, filter_scope_min_y_, filter_scope_max_y_)) { + is_out = true; + break; + } + + if (!valid_point(*iter_z, filter_scope_min_z_, filter_scope_max_z_)) { + is_out = true; + break; + } + } + + return is_out; +} +} // namespace autoware::image_projection_based_fusion #include From 0c8bdcacd41e55e77ff017838618aaf09d936823 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Bar=C4=B1=C5=9F=20Zeren?= Date: Thu, 10 Oct 2024 18:25:06 +0300 Subject: [PATCH 03/19] chore: add license MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Barış Zeren --- .../mask_cluster_fusion/node.hpp | 14 ++++++++++++++ .../src/mask_cluster_fusion/node.cpp | 14 ++++++++++++++ 2 files changed, 28 insertions(+) diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/mask_cluster_fusion/node.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/mask_cluster_fusion/node.hpp index 372ab8d861209..b3be3cb7e1e8b 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/mask_cluster_fusion/node.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/mask_cluster_fusion/node.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 The Autoware Contributors +// +// 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 "autoware/image_projection_based_fusion/fusion_node.hpp" #include diff --git a/perception/autoware_image_projection_based_fusion/src/mask_cluster_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/mask_cluster_fusion/node.cpp index c40dd279453e3..b9a5d4a9f0808 100644 --- a/perception/autoware_image_projection_based_fusion/src/mask_cluster_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/mask_cluster_fusion/node.cpp @@ -1,3 +1,17 @@ +// Copyright 2024 The Autoware Contributors +// +// 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 "autoware/image_projection_based_fusion/mask_cluster_fusion/node.hpp" #include "autoware/euclidean_cluster/utils.hpp" From 80255566eed24434d379204c1963e570027adcc6 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Bar=C4=B1=C5=9F=20Zeren?= Date: Mon, 14 Oct 2024 11:43:47 +0300 Subject: [PATCH 04/19] chore: update mask fusion conditions MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Barış Zeren --- .../mask_cluster_fusion/node.hpp | 12 ++++ .../src/mask_cluster_fusion/node.cpp | 68 ++++++++++++++----- 2 files changed, 63 insertions(+), 17 deletions(-) diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/mask_cluster_fusion/node.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/mask_cluster_fusion/node.hpp index b3be3cb7e1e8b..379c8839ba9cd 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/mask_cluster_fusion/node.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/mask_cluster_fusion/node.hpp @@ -23,12 +23,24 @@ namespace autoware::image_projection_based_fusion { +struct MatchedCluster +{ + uint32_t mask_index{}; + uint32_t cluster_index{}; + uint32_t valid_point_number{}; + sensor_msgs::msg::RegionOfInterest roi; +}; +using MatchedClusters = std::vector; + class MaskClusterFusionNode : public FusionNode { public: explicit MaskClusterFusionNode(const rclcpp::NodeOptions & options); +private: + rclcpp::Publisher::SharedPtr detected_objects_pub_; + protected: void preprocess(DetectedObjectsWithFeature & output_msg) override; diff --git a/perception/autoware_image_projection_based_fusion/src/mask_cluster_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/mask_cluster_fusion/node.cpp index b9a5d4a9f0808..750ae037fd6a4 100644 --- a/perception/autoware_image_projection_based_fusion/src/mask_cluster_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/mask_cluster_fusion/node.cpp @@ -107,6 +107,7 @@ void MaskClusterFusionNode::fuseOnSingleImage( transform_stamped = transform_stamped_optional.value(); } + MatchedClusters matched_clusters; for (std::size_t i = 0; i < input_cluster_msg.feature_objects.size(); ++i) { if (input_cluster_msg.feature_objects.at(i).feature.cluster.data.empty()) { continue; @@ -132,7 +133,8 @@ void MaskClusterFusionNode::fuseOnSingleImage( int32_t max_y(0); double total_projected_points = 0; - std::vector point_counter_each_class = {0, 0, 0, 0, 0, 0, 0, 0}; + std::vector point_counter_each_class( + input_mask_msg.config.classification.size(), 0.0); for (sensor_msgs::PointCloud2ConstIterator iter_x(transformed_cluster, "x"), iter_y(transformed_cluster, "y"), iter_z(transformed_cluster, "z"); @@ -154,19 +156,18 @@ void MaskClusterFusionNode::fuseOnSingleImage( const uint8_t pixel_value = mask.at( static_cast(projected_point.y()), static_cast(projected_point.x())); - const auto label_id = static_cast( - static_cast(input_mask_msg.config.classification[pixel_value - 1].label)); if (pixel_value != 0) { min_x = std::min(static_cast(projected_point.x()), min_x); min_y = std::min(static_cast(projected_point.y()), min_y); max_x = std::max(static_cast(projected_point.x()), max_x); max_y = std::max(static_cast(projected_point.y()), max_y); - point_counter_each_class[label_id]++; + point_counter_each_class[static_cast(pixel_value - 1)]++; } total_projected_points++; } + // If there is no point projected on the mask, skip the cluster bool all_zero = std::all_of( point_counter_each_class.begin(), point_counter_each_class.end(), [](double value) { return value == 0; }); @@ -174,25 +175,44 @@ void MaskClusterFusionNode::fuseOnSingleImage( continue; } - auto max_it = + // Find the mask with the most projected points + auto max_object_it = std::max_element(point_counter_each_class.begin(), point_counter_each_class.end()); - auto max_index = std::distance(point_counter_each_class.begin(), max_it); + auto max_object_index = std::distance(point_counter_each_class.begin(), max_object_it); - RCLCPP_DEBUG(get_logger(), "Number of points in the cluster: %f", *max_it); + RCLCPP_DEBUG(get_logger(), "Number of points in the cluster: %u", *max_object_it); RCLCPP_DEBUG(get_logger(), "Total projected points: %f", total_projected_points); - RCLCPP_DEBUG(get_logger(), "Fusion ratio: %f", *max_it / total_projected_points); + RCLCPP_DEBUG(get_logger(), "Fusion ratio: %f", *max_object_it / total_projected_points); - if (*max_it / total_projected_points < fusion_ratio_) { + // check if the ratio of the cluster is smaller than the fusion ratio + if (*max_object_it / total_projected_points < fusion_ratio_) { continue; } - // Set classification of the object - std::vector classification; - autoware_perception_msgs::msg::ObjectClassification object_classification; - object_classification.label = static_cast(max_index); - object_classification.probability = 1.0; - classification.push_back(object_classification); - output_object_msg.feature_objects.at(i).object.classification = classification; + // check if there is a cluster that has the same mask with better iou + bool is_any_bigger_ratio_with_same_mask = std::any_of( + matched_clusters.begin(), matched_clusters.end(), + [max_object_it, max_object_index](const MatchedCluster & matched_cluster) { + return matched_cluster.mask_index == max_object_index && + matched_cluster.valid_point_number > *max_object_it; + }); + if (is_any_bigger_ratio_with_same_mask) { + continue; + } + + // remove the previous matched cluster with the same mask if it exists + matched_clusters.erase( + std::remove_if( + matched_clusters.begin(), matched_clusters.end(), + [max_object_index](const MatchedCluster & matched_cluster) { + return matched_cluster.mask_index == max_object_index; + }), + matched_clusters.end()); + + MatchedCluster matched_cluster; + matched_cluster.mask_index = max_object_index; + matched_cluster.cluster_index = i; + matched_cluster.valid_point_number = *max_object_it; // Set roi of the object sensor_msgs::msg::RegionOfInterest roi; @@ -200,7 +220,21 @@ void MaskClusterFusionNode::fuseOnSingleImage( roi.y_offset = min_y; roi.width = max_x - min_x; roi.height = max_y - min_y; - output_object_msg.feature_objects.at(i).feature.roi = roi; + matched_cluster.roi = roi; + + matched_clusters.push_back(matched_cluster); + } + + for (const auto & matched_cluster : matched_clusters) { + // Set classification of the object + std::vector classification; + autoware_perception_msgs::msg::ObjectClassification object_classification; + object_classification.label = + static_cast(input_mask_msg.config.classification[matched_cluster.mask_index].label); + object_classification.probability = 1.0; + classification.push_back(object_classification); + output_object_msg.feature_objects.at(matched_cluster.cluster_index).object.classification = + classification; } } From 308803e204041555dec282a3c205ae8fd6841309 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Bar=C4=B1=C5=9F=20Zeren?= Date: Wed, 27 Nov 2024 05:07:58 +0300 Subject: [PATCH 05/19] fix: missing header MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Barış Zeren --- .../autoware/image_projection_based_fusion/fusion_node.hpp | 2 ++ .../mask_cluster_fusion/node.hpp | 5 +---- .../autoware_image_projection_based_fusion/package.xml | 1 + .../src/mask_cluster_fusion/node.cpp | 4 ++-- 4 files changed, 6 insertions(+), 6 deletions(-) diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp index c9b4f1f7b903f..943e419620df8 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp @@ -21,6 +21,7 @@ #include #include +#include #include #include #include @@ -55,6 +56,7 @@ using tier4_perception_msgs::msg::DetectedObjectsWithFeature; using tier4_perception_msgs::msg::DetectedObjectWithFeature; using PointCloud = pcl::PointCloud; using autoware_perception_msgs::msg::ObjectClassification; +using autoware_internal_msgs::msg::SegmentationMask; template class FusionNode : public rclcpp::Node diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/mask_cluster_fusion/node.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/mask_cluster_fusion/node.hpp index 379c8839ba9cd..d8c2945e3b165 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/mask_cluster_fusion/node.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/mask_cluster_fusion/node.hpp @@ -37,10 +37,7 @@ class MaskClusterFusionNode { public: explicit MaskClusterFusionNode(const rclcpp::NodeOptions & options); - -private: - rclcpp::Publisher::SharedPtr detected_objects_pub_; - + protected: void preprocess(DetectedObjectsWithFeature & output_msg) override; diff --git a/perception/autoware_image_projection_based_fusion/package.xml b/perception/autoware_image_projection_based_fusion/package.xml index 335c4712071e0..2c97024e5b53c 100644 --- a/perception/autoware_image_projection_based_fusion/package.xml +++ b/perception/autoware_image_projection_based_fusion/package.xml @@ -20,6 +20,7 @@ autoware_lidar_centerpoint autoware_object_recognition_utils autoware_perception_msgs + autoware_internal_msgs autoware_point_types autoware_universe_utils cv_bridge diff --git a/perception/autoware_image_projection_based_fusion/src/mask_cluster_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/mask_cluster_fusion/node.cpp index 750ae037fd6a4..941336ceeb555 100644 --- a/perception/autoware_image_projection_based_fusion/src/mask_cluster_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/mask_cluster_fusion/node.cpp @@ -134,7 +134,7 @@ void MaskClusterFusionNode::fuseOnSingleImage( double total_projected_points = 0; std::vector point_counter_each_class( - input_mask_msg.config.classification.size(), 0.0); + input_mask_msg.classification.size(), 0.0); for (sensor_msgs::PointCloud2ConstIterator iter_x(transformed_cluster, "x"), iter_y(transformed_cluster, "y"), iter_z(transformed_cluster, "z"); @@ -230,7 +230,7 @@ void MaskClusterFusionNode::fuseOnSingleImage( std::vector classification; autoware_perception_msgs::msg::ObjectClassification object_classification; object_classification.label = - static_cast(input_mask_msg.config.classification[matched_cluster.mask_index].label); + static_cast(input_mask_msg.classification[matched_cluster.mask_index].label); object_classification.probability = 1.0; classification.push_back(object_classification); output_object_msg.feature_objects.at(matched_cluster.cluster_index).object.classification = From b268428efed4111926ed5ccf87d3f1769db99290 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Wed, 27 Nov 2024 02:34:29 +0000 Subject: [PATCH 06/19] style(pre-commit): autofix --- .../config/mask_cluster_fusion.param.yaml | 2 +- .../fusion_node.hpp | 4 +- .../mask_cluster_fusion/node.hpp | 4 +- .../launch/mask_cluster_fusion.launch.xml | 132 +++++++++--------- .../package.xml | 2 +- .../src/mask_cluster_fusion/node.cpp | 5 +- 6 files changed, 74 insertions(+), 75 deletions(-) diff --git a/perception/autoware_image_projection_based_fusion/config/mask_cluster_fusion.param.yaml b/perception/autoware_image_projection_based_fusion/config/mask_cluster_fusion.param.yaml index ca97dc0286e5b..dc39f9c713e8e 100644 --- a/perception/autoware_image_projection_based_fusion/config/mask_cluster_fusion.param.yaml +++ b/perception/autoware_image_projection_based_fusion/config/mask_cluster_fusion.param.yaml @@ -2,4 +2,4 @@ ros__parameters: fusion_distance: 100.0 # the distance threshold for the fusion fusion_ratio: 0.4 # the ratio between the selected cluster points and the total points in the cluster - remove_unknown: true # remove unknown clusters \ No newline at end of file + remove_unknown: true # remove unknown clusters diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp index 943e419620df8..7881b8cfce8b0 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp @@ -20,8 +20,8 @@ #include #include -#include #include +#include #include #include #include @@ -55,8 +55,8 @@ using sensor_msgs::msg::PointCloud2; using tier4_perception_msgs::msg::DetectedObjectsWithFeature; using tier4_perception_msgs::msg::DetectedObjectWithFeature; using PointCloud = pcl::PointCloud; -using autoware_perception_msgs::msg::ObjectClassification; using autoware_internal_msgs::msg::SegmentationMask; +using autoware_perception_msgs::msg::ObjectClassification; template class FusionNode : public rclcpp::Node diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/mask_cluster_fusion/node.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/mask_cluster_fusion/node.hpp index d8c2945e3b165..7aafb3f45925a 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/mask_cluster_fusion/node.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/mask_cluster_fusion/node.hpp @@ -37,7 +37,7 @@ class MaskClusterFusionNode { public: explicit MaskClusterFusionNode(const rclcpp::NodeOptions & options); - + protected: void preprocess(DetectedObjectsWithFeature & output_msg) override; @@ -54,4 +54,4 @@ class MaskClusterFusionNode double fusion_ratio_; bool remove_unknown_; }; -} // namespace autoware::image_projection_based_fusion \ No newline at end of file +} // namespace autoware::image_projection_based_fusion diff --git a/perception/autoware_image_projection_based_fusion/launch/mask_cluster_fusion.launch.xml b/perception/autoware_image_projection_based_fusion/launch/mask_cluster_fusion.launch.xml index 7a3fa3eee0565..3bbce2c5fd9c5 100644 --- a/perception/autoware_image_projection_based_fusion/launch/mask_cluster_fusion.launch.xml +++ b/perception/autoware_image_projection_based_fusion/launch/mask_cluster_fusion.launch.xml @@ -1,72 +1,72 @@ - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + - - + + - - - - - - - - - + + + + + + + + + - - - - - - - + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/perception/autoware_image_projection_based_fusion/package.xml b/perception/autoware_image_projection_based_fusion/package.xml index 2c97024e5b53c..bceb805b10977 100644 --- a/perception/autoware_image_projection_based_fusion/package.xml +++ b/perception/autoware_image_projection_based_fusion/package.xml @@ -17,10 +17,10 @@ autoware_cmake autoware_euclidean_cluster + autoware_internal_msgs autoware_lidar_centerpoint autoware_object_recognition_utils autoware_perception_msgs - autoware_internal_msgs autoware_point_types autoware_universe_utils cv_bridge diff --git a/perception/autoware_image_projection_based_fusion/src/mask_cluster_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/mask_cluster_fusion/node.cpp index 941336ceeb555..c711afaff0355 100644 --- a/perception/autoware_image_projection_based_fusion/src/mask_cluster_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/mask_cluster_fusion/node.cpp @@ -133,8 +133,7 @@ void MaskClusterFusionNode::fuseOnSingleImage( int32_t max_y(0); double total_projected_points = 0; - std::vector point_counter_each_class( - input_mask_msg.classification.size(), 0.0); + std::vector point_counter_each_class(input_mask_msg.classification.size(), 0.0); for (sensor_msgs::PointCloud2ConstIterator iter_x(transformed_cluster, "x"), iter_y(transformed_cluster, "y"), iter_z(transformed_cluster, "z"); @@ -271,4 +270,4 @@ bool MaskClusterFusionNode::out_of_scope(const DetectedObjectWithFeature & obj) #include -RCLCPP_COMPONENTS_REGISTER_NODE(autoware::image_projection_based_fusion::MaskClusterFusionNode) \ No newline at end of file +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::image_projection_based_fusion::MaskClusterFusionNode) From 315494ceb3f964e4de5c22ae2f5564ccaf4d9480 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Bar=C4=B1=C5=9F=20Zeren?= Date: Wed, 27 Nov 2024 05:41:14 +0300 Subject: [PATCH 07/19] fix: pre-commit.ci MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Barış Zeren --- .../mask_cluster_fusion/node.hpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/mask_cluster_fusion/node.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/mask_cluster_fusion/node.hpp index 7aafb3f45925a..fe4d45bb8a10a 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/mask_cluster_fusion/node.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/mask_cluster_fusion/node.hpp @@ -12,6 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. +#ifndef AUTOWARE__IMAGE_PROJECTION_BASED_FUSION__MASK_CLUSTER_FUSION__NODE_HPP_ +#define AUTOWARE__IMAGE_PROJECTION_BASED_FUSION__MASK_CLUSTER_FUSION__NODE_HPP_ + #include "autoware/image_projection_based_fusion/fusion_node.hpp" #include @@ -55,3 +58,5 @@ class MaskClusterFusionNode bool remove_unknown_; }; } // namespace autoware::image_projection_based_fusion + +#endif // AUTOWARE__IMAGE_PROJECTION_BASED_FUSION__MASK_CLUSTER_FUSION__NODE_HPP_ \ No newline at end of file From e7f14e8a01d206e10084082c3baafc623650d0ab Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Wed, 27 Nov 2024 02:43:35 +0000 Subject: [PATCH 08/19] style(pre-commit): autofix --- .../image_projection_based_fusion/mask_cluster_fusion/node.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/mask_cluster_fusion/node.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/mask_cluster_fusion/node.hpp index fe4d45bb8a10a..857e3a0257341 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/mask_cluster_fusion/node.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/mask_cluster_fusion/node.hpp @@ -59,4 +59,4 @@ class MaskClusterFusionNode }; } // namespace autoware::image_projection_based_fusion -#endif // AUTOWARE__IMAGE_PROJECTION_BASED_FUSION__MASK_CLUSTER_FUSION__NODE_HPP_ \ No newline at end of file +#endif // AUTOWARE__IMAGE_PROJECTION_BASED_FUSION__MASK_CLUSTER_FUSION__NODE_HPP_ From 7ef4ab54ed1439bde6ab45cb6ff50da1a181f100 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Bar=C4=B1=C5=9F=20Zeren?= Date: Thu, 5 Dec 2024 18:36:30 +0300 Subject: [PATCH 09/19] feat: add json schema MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Barış Zeren --- .../config/mask_cluster_fusion.param.yaml | 6 +-- .../schema/mask_cluster_fusion.schema.json | 46 +++++++++++++++++++ 2 files changed, 49 insertions(+), 3 deletions(-) create mode 100644 perception/autoware_image_projection_based_fusion/schema/mask_cluster_fusion.schema.json diff --git a/perception/autoware_image_projection_based_fusion/config/mask_cluster_fusion.param.yaml b/perception/autoware_image_projection_based_fusion/config/mask_cluster_fusion.param.yaml index dc39f9c713e8e..25af5703bb265 100644 --- a/perception/autoware_image_projection_based_fusion/config/mask_cluster_fusion.param.yaml +++ b/perception/autoware_image_projection_based_fusion/config/mask_cluster_fusion.param.yaml @@ -1,5 +1,5 @@ /**: ros__parameters: - fusion_distance: 100.0 # the distance threshold for the fusion - fusion_ratio: 0.4 # the ratio between the selected cluster points and the total points in the cluster - remove_unknown: true # remove unknown clusters + fusion_distance: 100.0 + fusion_ratio: 0.4 + remove_unknown: false diff --git a/perception/autoware_image_projection_based_fusion/schema/mask_cluster_fusion.schema.json b/perception/autoware_image_projection_based_fusion/schema/mask_cluster_fusion.schema.json new file mode 100644 index 0000000000000..cafec09cc29ab --- /dev/null +++ b/perception/autoware_image_projection_based_fusion/schema/mask_cluster_fusion.schema.json @@ -0,0 +1,46 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Mask Cluster Fusion Node", + "type": "object", + "definitions": { + "mask_cluster_fusion": { + "type": "object", + "properties": { + "fusion_distance": { + "type": "number", + "description": "If the detected object's distance is less than its value, the fusion will be processed.", + "default": 100.0, + "minimum": 0.0 + }, + "fusion_ratio": { + "type": "number", + "description": "The ratio between the selected cluster points and the total points in the cluster.", + "default": 0.4, + "minimum": 0.0 + }, + "remove_unknown": { + "type": "boolean", + "description": "If this parameter is true, all of objects labeled UNKNOWN will be removed in post-process.", + "default": false + } + }, + "required": [ + "fusion_distance", + "fusion_ratio", + "remove_unknown" + ] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/mask_cluster_fusion" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} From 4e5430ecb3453da63511d77413687bfec8813feb Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Thu, 5 Dec 2024 15:40:49 +0000 Subject: [PATCH 10/19] style(pre-commit): autofix --- .../schema/mask_cluster_fusion.schema.json | 6 +----- 1 file changed, 1 insertion(+), 5 deletions(-) diff --git a/perception/autoware_image_projection_based_fusion/schema/mask_cluster_fusion.schema.json b/perception/autoware_image_projection_based_fusion/schema/mask_cluster_fusion.schema.json index cafec09cc29ab..2435d00aeb7f7 100644 --- a/perception/autoware_image_projection_based_fusion/schema/mask_cluster_fusion.schema.json +++ b/perception/autoware_image_projection_based_fusion/schema/mask_cluster_fusion.schema.json @@ -24,11 +24,7 @@ "default": false } }, - "required": [ - "fusion_distance", - "fusion_ratio", - "remove_unknown" - ] + "required": ["fusion_distance", "fusion_ratio", "remove_unknown"] } }, "properties": { From 5b271430f922f7253dbcd4b349cf2338c3f7ea99 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Bar=C4=B1=C5=9F=20Zeren?= Date: Thu, 5 Dec 2024 18:46:17 +0300 Subject: [PATCH 11/19] fix: pre-commit.ci MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Barış Zeren --- .../src/mask_cluster_fusion/node.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/perception/autoware_image_projection_based_fusion/src/mask_cluster_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/mask_cluster_fusion/node.cpp index c711afaff0355..381f817ced238 100644 --- a/perception/autoware_image_projection_based_fusion/src/mask_cluster_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/mask_cluster_fusion/node.cpp @@ -18,6 +18,10 @@ #include "autoware/image_projection_based_fusion/utils/geometry.hpp" #include "autoware/image_projection_based_fusion/utils/utils.hpp" +#include +#include +#include + namespace autoware::image_projection_based_fusion { bool is_far_enough(const DetectedObjectWithFeature & obj, const double distance_threshold) From ffcfdde1b395ee8a7169af6dce56f652d077d652 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Thu, 5 Dec 2024 15:49:02 +0000 Subject: [PATCH 12/19] style(pre-commit): autofix --- .../src/mask_cluster_fusion/node.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception/autoware_image_projection_based_fusion/src/mask_cluster_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/mask_cluster_fusion/node.cpp index 381f817ced238..9af211c28faeb 100644 --- a/perception/autoware_image_projection_based_fusion/src/mask_cluster_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/mask_cluster_fusion/node.cpp @@ -18,8 +18,8 @@ #include "autoware/image_projection_based_fusion/utils/geometry.hpp" #include "autoware/image_projection_based_fusion/utils/utils.hpp" -#include #include +#include #include namespace autoware::image_projection_based_fusion From 9187a9e24866a577e5181bcbd08e7694b4fa6eb5 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Bar=C4=B1=C5=9F=20Zeren?= Date: Thu, 5 Dec 2024 19:55:11 +0300 Subject: [PATCH 13/19] feat: add readme MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Barış Zeren --- .../README.md | 13 +++--- .../docs/images/mask_cluster_fusion.png | Bin 0 -> 143889 bytes .../docs/mask-cluster-fusion.md | 38 ++++++++++++++++++ 3 files changed, 45 insertions(+), 6 deletions(-) create mode 100644 perception/autoware_image_projection_based_fusion/docs/images/mask_cluster_fusion.png create mode 100644 perception/autoware_image_projection_based_fusion/docs/mask-cluster-fusion.md diff --git a/perception/autoware_image_projection_based_fusion/README.md b/perception/autoware_image_projection_based_fusion/README.md index c976697b0396d..34db7f86f02cd 100644 --- a/perception/autoware_image_projection_based_fusion/README.md +++ b/perception/autoware_image_projection_based_fusion/README.md @@ -68,9 +68,10 @@ The rclcpp::TimerBase timer could not break a for loop, therefore even if time i ### Detail description of each fusion's algorithm is in the following links -| Fusion Name | Description | Detail | -| -------------------------- | ----------------------------------------------------------------------------------------------- | -------------------------------------------- | -| 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) | +| Fusion Name | Description | Detail | +| -------------------------- |---------------------------------------------------------------------------------------------------| -------------------------------------------- | +| 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) | +| mask_cluster_fusion | Overwrite a classification label of clusters by that of masks from a instance segmentation model. | [link](./docs/mask-cluster-fusion.md) | diff --git a/perception/autoware_image_projection_based_fusion/docs/images/mask_cluster_fusion.png b/perception/autoware_image_projection_based_fusion/docs/images/mask_cluster_fusion.png new file mode 100644 index 0000000000000000000000000000000000000000..7c9a06f82b89e812a94e04b9f14638adfe44e75d GIT binary patch literal 143889 zcmeEu1zeQb`oACwDAFNP0s_(u-AIe1f^-foF?5H7NFyR$qJ$_ZNVkMY2`C^PQqtY< ze+L*rckf+q?t1?}c0TURdCz<5`967`bNu9F#4laAa^cLGGnXW8irhJK<}B@*GjN+o z=Yf)2V5`+LXEXzCM3rsK91M(2_0LeS2p@f;U}iFcSldvrh)^&y>sVMY=o#x6TIrZs zGnnh!07bxa9YcNd;|kIcCu37n9SUYKHU=i((RF1Ih=N53_;wd;Yi?tE^j*r>+|~go zbKqpxVrM-nv$CUL5d^V-7?`MmC*u0LCJ>+%W+o65@BsluV#Zeb1`yyivBO$NUEAqf zSsO#lk4DD~^vM8Jg^tNuSI1QUsF;a?gYBpg46)MFw>mC`7O{v@FbM*+p&u6E2utoj+GU}{`+bM5Yyx79oMk{X8v94&;t3BWj$3*$ym?E z=%_9y+wt(AwQuSh8ydlS1_*gHN;4f;<>LZtBON`6{n7h}MW@Mfw2-jnw1Pl@_D)gl z^kY~hGY4UPQ|M~L*73L>06PEpyWgg1^$q0zN^?4b(vk`~AT22nizuhC6IepT#+n`= zCzPUgI;OVAOHRSeu485aaE3Y98v4JZ3f4A`Fi=}TY|Zubp%ep6#nS>{tj_?}|cHdYW5eHi1ge4~iI-fy_> zU#G{Z<%Y56>BWYXS?QbV*cjV=&-K4YfWN<>r&$uZxN;C{b{_$HsN9{l8k`0EtZ(YJL2b-OZj+LRl%|Fp6i|`@NzJdSmFU@i7L%97>&7VUh z$N!=7Na*~Y`aKPc)8Bs&l}tYhD`r>$3?u)3Typ$|75-;%$@#~)1k}C-RMwa|0QRJX z5reg{p}94Kjg^kMwFSh=1`tIMa|T@ryalTuXbKDocwhs8DpZ~0U%EiQ zP%HAkqC+`gDEy7+IwjOWFxZ@y>dZ{X8ViQsKVO9&o4nuIIX|e-A3>pOY^@7nu+WEC znCdfF+vu3<8Jinw*+a~90K)tcD)e-$jlS7Pr;VV$4H4jp!Qmg!`u92-5HR0>@vkBW zVrye+Y_2c-%`}G^amO6WsE&O&n40=mrO}@R zl>aH!209j*{|He2W4eu<9SWSksw{FcHgwW4q=zcN{}V~a@(7ShKP{42{#23lH?Z{| z6iNSmy!>xTrk`-dzK>1)HKU1~us9LSbp7U_pYnuQVD8ds(-j1Bv;R7#D{Mr6PhI@e zL;-A0AesRUX#969KF%M*Yv26QQ+_f05@Y!%9HifO#sB3XGe{8n-(SfQKlUB}qd{gim_mX< ziwzd3JtgE|5I=1Wa{cAZL6+mpp}%LR!?rARZNboh#vgc3;G@J1DKIQK1FWNKVt8ni z$R6zq9B*j>YS2U$Na--Pfi5Ex0}~t2_^Co*KLRNIoy{+*8N^3Ti2f=ObSX#PFI{GMormHl;?6*i*3Cz}5O z^Hbl!*hcwKq(bE^^q0!9AclSyfu^)U<0*$f4h1swhdGe%cIqYQPv~2R6`?;)UOW5+ zd+&$^|2WkPNG?0fg#wxcUisauG#EIKthGO^`1g~JPAt@K`Ap1Ar#KcSu}_O}SlNFk zd5nwmc%KEjl)#$Mv;1hb{s&BDCYB#M{l+vfZun(wW!9evcl{Gg1hqU_7>cZ_eivL@X0S3(fglzj! z@qc3)Sf{_P;y?D%|IOAjjBTJSbiz=7aVGlJdE>W=pAELZ48!Svf;nJ%9%hPvJ7odu z^w(vMpNRVXx{CjILNPEU{})&MKM|h$|3L8{gY%CS|6#>nUAX;5@w37VSD2XjPsq04 zD1I2zz&ibPW!rC)CXT{Ur!pk|2`2j06#xGOZ~RvAv;G+#|F`YEU!OUCn~(Av=J;h5 z|2M(;>v{Y?u>FBY@_D?bC3Uj zf;WCg@&6efKPxQxxLUF+~4O0E1G=g|Hl=dJ(y=K{X%hrm$w%`5u@b03CI zm<<05F#bOk=lgcq12hzI>bj8cMa1`aI{g21?-Dyq>cap6i{HZt|L-@af72x^Yz(kI zf7vh^+wZxg?54owbV3G@!|Se2;%V%bw$NMa4j<54A711Ky>t-7ZUJPK0a?1R=fF2Z zXgxt|=oJD$4O8d^HNY7dCSwEOAM5YWHd*Og+nNHmIso@Cn(G1o>YCbG1NYJ#R)=0t zV+~{+G5}2;jtRJ=>S$O;J^Uu9@ja9LL5SmYW~rXOfetW?!+8KU6w`m!y!mEu!Z7?R zp86+>QxX=Yw`fm!ilT<38*5MBo=sqm$$H_MAciD*FClsF$^m|bWz5eD1 zHb0ZM_=hoyBmVi-V-zef<@pVdKMJ^izfk=qL%;P28^kX!RM~&R3p*9(`-eCJdI{`5 z%oIw;_f-BL_CeBZ0TwPgMVH?{t@W2Xng`sX@P}7({VRm|7GOAiw(7s{*Z=myhQAWY4llI*8<%p! zuEssN|NOMMclZ=`?)EQwwlAvE2d*9@_}WYB?@xA}Mx$gEH7PB0Fzg_jKnN4* zOZmr!rszGrOODo)t$VFy8xzgD{!K-eWB!Pjt{~uGpu>Ilu|R-dnP~B9zs}H^Dosnw zW0yg`D&hJ=C3Lv5jX`JJbAC9|=f8U!9qu97)!b3Jw@IzO_mNJ2o?t#wZdd=I9gCar zn6#)|bYGu*SJ(G`t^dULulwE?1{$z@r*k_^#M8fl?}U$m282-qxGCVt zuActnKI8iCH$2(!BZO;;gjUKQsehPOwh?D&l;Sd$EqWqI>-_Quu{)d%sE*{kDF?dSu$TK9zgx z1h{m{_e06WpNR(GQps=3lxOqU%~mZ`9t10CI*NLx1W!q3e8f;@qdma_6#-lxQ-8iO zR!3(i$a+F5@Cw^4&lG>bC)(+KDh#=I3SB;xoM1AJ72#Iht(!NI?B;qYs=;ILByxI? zUS9chP4Ok1bmS@8vtV9lRBT=W9`nD)q$|jKot9eb&zG;DbOM98sH%3bsApY8b%b_q zNF@Cm3PsbTWbTvo_<)3@K&g05d6vKd8F$Cw?p-x-3XPDH#z_-bkUhryaDa!D_YneI z%VZRQ8tck0DNZ2FnT{NHGvj7X4@W*G-TD%@rkP)O@5l?q6Gj_^bmNT<&Q3$SRAo)Ah# z;wd*crA*s+poFdF?c4ar(q?=LU@#fGdB3l$z#jJA_S&mVgZKg>Kb$loRlcYbqVrZ#2^t>^_>n$)d8ImT@naflw1b=*SJBrg1Ozz^eL#zU>Wq& zfdL}JI7^?-<@8KMwH$3Y)qEq5#xSaG#W0z^;9CDq)J$Tjlcks?znTjs$^Ht=FgHG~ z)_*QTLH^`vT+IF2TYD(kKzSTMZo`zAQ_K7jkU(Dz9f0ylx?C_1?I-LL=1!x$ntMm! zEiF)P=!es%lAd}pKTbA)mA3IUfpRX%jGoq8Y^N6<5Go(r7HGB~d|tcjl>k}wERk+uHhtrDG7k;a{=I3YwlUG3Xxr`o=c^brf% zb+}W^J@z3n18w%_cSKJi#T-BiCT%eLTM9)&Gm(!ZCy$J-9zMFnx)$uL=7%FrfN{F( zD^T@bd+V$;AMogG_URscrqbxr{pDr@(JfF-F?$u$&lMIm3IHk zDGDINiR02@QA)k&V#3$ahC*t#!VRGOi+NXB8y0{$9}4|01C9dB$+~M3scgInl0!QY z%vGdFfaK2LtQDc_M*iE2S3WkV2(D`v6WPP~CN4bA1I8CwZpRIIS>RFCt5Z-IHadg? zp`}a=Kebo+^Ps?O@)L=$CIuKK;FN?k_3*+leC2Ro1;G=jTtPeppm^*wl-gupLr$$a z`XNBh$2c{VXV&^Z5Ar?T>LsYT15WWsO#mKwD7l}SWBbt@N8?ysAOAZ?BaTChCa}xo zgGQoBPoq{~nww?PnHn_E&8S|44$vs)r%8%KYhbB0a0e?FJkOGElcJY2fQ!4Y4-NFE9@ESuNhogI|A=_y>fz~qcUmmVwH@-} zSI75v9eJWX?)u%tIbn^bmgq;Li9Q)koDIVA1^*nEZoyR(9M_ID4I*5C=RKB>SbC1= zL@mT&BkZq@sPE=lqTP9I6&j|cz4rOR!ODuAxXpdWRCQ)_Lt9g)JG=qhhvq;E0-;Jq zK4hpu^(+nv2}GkiLxrU@TMH0*2@a#khx)D4JOG!T$#MD1%a`oi-4u#f_OQ{<0FvGr ziFbbwvy9*V((=Us3zda}sc!BondF`yD48$kbF=|1r;8wm!UF~Ts$}fHMqp=_MJk51aen4y34kLSA^q%ccFh$o zk5YlXvkQzpRajxlE{;uGRLLN-L2junOX}Cl7jxI!U!hOUeSSARy#!c6GUwrg=@coY zqU7kk#V$uNYge5q%}(UDrFrQ*gf$=qu3Jxf1XK8|V0bOM0nb>0O&ncBo2rkrGKJA1 z4TuMb9C%6@N!qs$#j7|KV24?H1G?0$9xApkzd!`kEESx`#6f~jt8~rc*ye4!wRP=# zxZC{uT<7!ss>L}_3ujdC9ujIBu;R#a?+jUIz1)$=P!PSD9RMtX6Fk?sbH3#}8qGzz z$rRkP^x1m_SF(3YV$x`JXUi4Vpw`?|O~8%=EV&u)yb%LTTJ{@v0EgY9UV4~lJF)+u z&V|rr#OIzzPiT~nJjoU|0WpD>?~S2*Z;}F_fO^V*g!%^Fyh&nA+Vu~2G=P`IB!)e* zafiq12y(~LXI`%D?#Q#WJ9da~t_=o!C^r^))B8abYC_179HCS<;j=ZGAC9w8IzYP{ z&#&d&vxh$~uy!dzs>D;r_w1a(;sl9_fEGlyXV4Xc?tcrM8``(oy;9e%S)JH2c%J!(J1QdbO_jY{lq@qjo(#7}_h9 zMFUmkSXf=`Vx#mV_ytk)G)Z(WLg&7E0K}ZYgV>T8&SVu!;*3aD^Kwv|sz+&+)$7Tu30ZN$p#y4)pWA2$H}S2bKJC}Nl4%Hc?Nw6II%L78Nr$hqt`hQY z@1JNpVXVuWLyWmPTFmE}y_a|n2>p@V6Lq(DwzOiGuFEQ*>Q91atAZU?YxYt1q`t;M zAr1|9KxK-(*Eh8|yofNkYketUTL&ND&30zqNBh^|e32IG9upzvP*I#c_dt|0Q-dyb z$gbk8Kmhl3sCphho(>OSLmcaR3kUeRSsfQm;;vblnuu}<<$}4Z>~j(#GjalPm;|1k zqn;QzUl1V>i1&jB)dK?qBZ(43haQD6R2$c|4E=b9ursNx%IcrF}9X_3CB z`BD&SWxn8o0~9@*J9EQ5L4cQ+PIy@eUSN0e?EYG|dplYRdR9WhqQ7qyTj78YZB_-~ zolY2XxR-5VsRYa3xr1q5GEGURo{wa%skvzO8FQXD$XK@BnpFC2z0CqcbqCU97_kZh zVLa4x3w-pQ=N1%L)f~-YxlrqOv#Cvd^QqusP=Ih}0HfIbL=s}iAR*kBk^02)T@a;q z3OL2L@_^f&KP#RoBF$X3pqOZ5*_ZM*61*K~2Z0gp& zcb{ynb3;Qzu$zY8xPJy44~JBDM)3;;)!1+xm#>UOHJ*GLJM%LqbzmhA#hL*5wG;Q! z3ybqnOwb#|J0Rx)^NilGszd7)bPgVHDQo1@}7doQyO^P?hFsZG?|+!6@*J#E*{sodkyFMk?}Y< zYDGjx!esdcW7*AuS>?68FPwYtj7|1%D(&?`q!xM`w@P0DX+RpNZbGkqmylthYz4KI zYclR-NmBQr03HNn=ts1BCr&m&R8__$XNzvUmE7nws;+0*J}G8;=m~@aB+pCgKjlzp z%m*R_Qg`Fn1fxxNqiv<9D>p4ZM&?y%9H=~aH^#p`^?Y+u;K1?AkmK%L0N_c|Ql1|~ zk%+F)Iorj*ijE5Ex2zud5IwFk;Ih&Z#cKSRWz^(J8>?xhH_m-_G!d?jy} z^NsB8Y)P*N95rX}?PcdHPSZ|Q8k}vobZ!@Pz-;|_ccO-NU^Dx%VvD2o=jgoRXOFUR zR5N2=*rn=o3^te|gyVMJX`D%o>bij1P|0H3>=R0GaBpAjwWGokvFNUvhi&;*%SVp6 zQkA*L{^!XH6nyON)XpX39G@6%WuO+XNOtcc_1hn!|I z!*D{kHG=Q^UEb(5$sQ?PsCea}4Z3Jc?szdYQpuNyXPp!TYQGSzF&ysix!y8dzve81 zv6pH`C}b|g-fv_u)f!edjE=_|MDK$}&iCO0#u6f5P9r_;gVk7?XOO#cVwf>LIaufEat_;alNus zhpWk~meq48`QQ=DYlh!%c=5<$d-1J&pd3bbDfb_)ubk^s3v{jb3#h}S!Z0n>MS(B7 zg&?g7X74CWd(O#2V(xOj(|ocu$v1G-CmVteU&H;hha5Wrn>8WEY)uSU|Mzdv1Oi9i zK2!>L8$qv@G4npryRY|ykogVjHvi20uYk*SYrx{}t2Z~aLDFRm4z84#ELLXbEe{Gb z6ZjLlWZlg9t(dJ|R;(|cH^`nCQMOr_dO7n-?D^Hj{SblCyk;qcc0v9eU2#3r!9X1Q zfd>lP2~QZ^+p{TrsHhG6wh&$A=AV;D_P^<_2}$yo#?GmAT*>iAu6s?bNQ2#amoba3 zFjpfyEVe3`h=&PWiv$F6yPO_c;Tk7N+PdxH($>brrLI4Q)4R$^sGs zIo4U`NbvRn?%3NxJQByf_q3%gVWf2Sh)T)U~gDJcMM^>G-?efiOmVHdnwcV7~b z?5QKduCSC;>T7V8%uu*5U+e~W`0A9(}Foa;-p=Ku`(ZOq43~WgZWe( z(2_2OePBRQo++8boYR48lL|5Rm3l~>*X;^Q=KLj<=3?;s*oUa3(Q2P2L?}X1bt$vo zCuCRFD~jQ;1aGBuJBo{`rUptg6rF(t;(N(pv(r##@*Ga;d=7KZ7*iDOU?PY7E1I!&`g(3@rqYw9On?DX{l4L0@0X?2$Tcw>DKj?wZB#nBH*k1r7k2%xF24&ODh za?;u?{gULcr0%l1o!FC~JIk{2Sdx2WBG$ROsVNAa{A`p80aYC(N0jO>cohk){KP&b<4qYy|;Ab0lZi zhOfil-mnskavbf%E)_vP&z}9`W+|@bRax%*WM5^yq{K01Y8B2I+H_tR- zIoW3-#Mm_1rx#~yXPoY!s+zmuAiR6k3 zpp>1E^dsWCl4dvO&!hULhURsQOlRcTGKNTGQnW?A`ndY!&fTktWc5!z?C*{A=51TN{_7FXvq~<^ zCneq7nx;ZnPzy;CRwJc-bw=Qz>>M@qL)nC&O@kf5{@H2Qg-aHG#{L=tEp_!F6@2wJ zmOVLLQypwqR`BMkwVKebI=n+iSe^AFYxDHF$bw5Wx0-BGELK_UU;H4H4=1bfI+yz*{@MVe|(q0 za&sM5^xnNdEE{@qdyV(r!NthP@ANgFfc*!TDLlE9WL($o7Hw@m zK0HOVfsQdYUA;h^_jLv>)jtw9E6cSh-J)Tb+#HOTzT5FIBcwbBU^J33GE@I)UHRUv!;yCnWii4 zvW0%l9dc8bq8A%Fe2o6O2d(kBGnEIT+x|E>UrVE$b6hzfkXIFWE%>fR>r>JVPZ0c9 z^;#!8z+YqdOJ8RZER6IOWZIeyPp7Fh%CO*bK^9^m5pUd;^`Z+jjOM4L!*1fOGwMyr z73EbpLS}c{+%wPz!}(b_&i0d&p}(t5C*B=+IO;}_$Q4ON*Am0_mXHGTUC5m6Arb~1we)7_<|hIiC>)U#7FffCAulP0C53kA&v zcJ3>e3ObAT)e~Ow3h4Wf)yTEYQfdci`=ued`B)p$%et^!zEb)qU>)p_V_h>+Usta3 zVW(a8E#EZ+!Lx{D57V3{)@=M^O%r->7W1>1;`b@BF~nF2Fvg^J^$@_+y+Y+hQKTuhW~1iDAbe*y>EO7 z(aV2hGO$#05ko33M$e7QFj}L`s&1DyLaV58$UVd{aLQ)&S!eh~8Ab?WZGkyz&BC{A^^RmlR9K|2z=1b!>)U+&rc8OH6-$HNEGbJ{{WFiB-tdld=P%>2 z@#M*FR4?zvq@b?ce}6-dcl=!|LcHc>ii~&5W|m3A$XqK@2rDABoHGQZ@^RrFUp`yQ zJ&JzdGWaUrb%uD}9EmptQAkXq>V+eUsnp2hHmvs_w^nZ7fD6Z~yf}M4vDkNm2`)@0 zeqTi0ks^DX#Ttvoy3Xp0>7aK;X0vQ9$&5mp`Zd1ncSs_dcGOO`v)+i?>#sWU+9w3% zMFRk@wa)KpSh$b7?oDXCiglY9UO?d&v@^Wn0n7e!4bHg1mgRZXdm#| zGLSDA-+5Fw(2#$txe`Ur`eg?Th*(SAo*Z+X;)%;=%iF_s17>LRnCvs{L`1T4o(7X~ zK{i7-YD=AT$A^}pR@ND>)9|XY;ppxOD?KxNVz+puNzc`fQd9mq4UG~l!{V^HJ(GQQ zDesau&Ju0-NTAY?bx62U%GCAFY;rRTwtFrLWW`f6HV1nalUeKLF}+1A-s62}0;Y6E z1fQ%G8I)TMpJXR4)nc_>4W~MndO2xyVL?;?#b=r?g@ak9^o%h9``A@1{|R{%0?mUiz&>Kt)xU8O1+Q#KqAlK{k^YdB0CK#SCBpC%|3O#OaT9dB3FB?ldx)8$`v7U7I zmE258OKjMqh=_-0%(+E_hywaE)gCPkbQ=**z$ZS7BX?zbmY#nZb*}X*@{kEcOy@nR zy7I7(H6rRgg_W0CB#O{2m8{9A@;M+jDk-&Q5`LrMz{RHpQL-W@guxv9vKROHvCnF~ zI$n}=>u*V7hxJqN^C+S$k?Ld?!YhZjmSn3qSesQbY=(ouOe~L`Klt!?@eFY7s8uY-sPd03kZ40(~-z1xv%sJ{bSTyj7`S59jysJb;l$fH;y!Nk2szR^&+;? z(F>b$E}Qjrq(K$8B_SoqDkwT?70Q$x^^EsxxSvdDrn*@(yf2&b8m`lrb6rL5X>z7d z;dDI5B+O@1dEsxRloh9_%{O#7q#`10Ju&&%=$ zx{D|B=N7H^68i?P=f!mk>{_r9O^4BirOU-oh!vRm!?mk$(vl%lBTskDT*Q6Cl}!-J z0v1t=10`Q#-z;c&=D=aPy8@X#m=|w?B)gEfxb!dWEbxGI>(A4ERXQ`7W%(@Rl3lev zeONnl1`@&hwIrJ_fl=EH0wq^xKN2f@87QyW!z;?}Tqq9oHe?UDwZr6KAxS)l4XRxc zYih4#qN`ulUqV?Gf4ECjlo83}QjUKqL!IQ-f)1y;<=zcKqt6$4?14QFe$i(9_KDL&}on>lj;w@f5|=biZtur&aGSUzh?$}eA*gmc-W&Y$LRbt(BRm;`))^%kX^P4t?*y{^Y z`Gf=3_=_VRh%$LX+cA$LA_BUlm51B9l=&GF;!O7Dbr*fib1%=nIY)2#0TVuicX=mt ze{~AOt8`&Lz%Kq-=v(Xnl3I>BPutHu94mOqS1M`Ob(X)dWb#M74kZoHaxq4Zpc}Jf zpETukJ&UO6#(loW*d=v6gd-m^L2&I}m&;$~78Lm9o=X-0ZKWi>RmYIyk$WT98_wX$8 zV)k@UU<@xlh;2L4{V*ixcicO=9@lB!^wKJ>~0a8GlG*nkl;2GLFH0AY#%WceZl z(S2Huk5kdMOO1lVk0lwZ&-c#7%7;;6Q)$NW2=d;}4ZK|>99Q$=R&oBPp(eS^dYv9` zDh53TCV8o3CfzHzbpz&F+@!IIWd69cc;~G1qe>d3o*7Ct1olurm0w<+?re|Ur=w|= ztU`()FeiD~CQyR3;x^P8R!VX6*82jPLHM`3mMcVO+h;O@-`TBILy(h{-*n?d4_5cs zEtE&JH3V_2e@Q<_H1GJnRDkp%#61VsdZJ!UX3Z@wmL9SFc7+;RzcTAZ>E#VIve8dU z2Q(m$ak5JJkkq2}ZGNPME;v61!6^4Cv_31Z+?_QJ3*UW34-d_vmDY;OPId%M>Lyz; z*UENAxJ_G@AM%J6fIi(D$YyE1AXz21D~*+lQnoe0+`Mc23P-Vr^HU;M2A^0k4^}8f z#pcD#r42VF)2#rVG3hhN6%cMalm`03Rk0BHD3Lckm#p{uy^OWY#hpmsQlee)zTef4 zGSz!w%+*aeN0MDJvloK=tg`!>>HRHbSqd& zK;fPYR00SCSyyf8F$KW(lDub0g(^bU&M?O=#Imk=03=x9>kdYV8Qc(i)t_N-C|(l}PueH!MRYP%d+XhmHjI`Q0| zP9fOzq-aE?GXK~^Y8(HA^6wGbcX&!XG$p(33lf_^|aH~(UEoy+;bp~T{c zyU%Jq*!1B0uD%x@tZ-G{=%bn48n>U>)2(seIq&e?x{VWsunPm(jTNge&LeJ}kDkg^ z_iIGC4xf;`o%T(}n1U^AmbUi{GheQ?g(W?njvcG^)zk6Xey&nPuq)*C=#43|;(k5~ zH9^5>bYmFk(e2JdGysZyBJYKr8jxhAk#Mg?3|_Oa@Kc^ z1nXDn(_TNVWgo0N1dAWlWmqd%>qcWc|#cYD{&6d{e4;|H1*zKu{g(-a}pTdJ;rxsEePHHFmH^(r-jrkf>5# zShfiNnp#=LX21-^&_%%d<_mzVh6#>@0(-1j)A(D9fhNInF^Vc&w=b_XiB!@Iw!V1i zOl_`|l_V<;dTt!-X#rn$txWpL!ti%%BvlY-F6p zmiSy;*2Wl!9uY+7kA`K?bIpvEpFWz4HQDSlst#*NzDwR^w&pK>jhdWj30%|fdS2tC z`=MkuyG4V)Mxi&3;AtQ+lE^v~7(ED-j{SVV_D<*KSO-ERgXja^@uV})9NsTo5*%J! z85XOI)2^VBzkG+c%^Q)5D$*7ERM1FRStydL4 z4<37~r0_Y5CN2)4t7AcLlWVdngs0fd{JDE|-KzYvsKLe6&YqpMZbkN;F`Te&vPW=) zfyy9$8p^Oe?u3|Y%yg#a;8DwL0*iY5O;1Nvg}BHngM=3Yj+61Mi8RO%Gj9=AFM2&D z$Sru+2&qAAEZj|py2w<`+`^$?!i3gny`W-B$b}h#&b0SdHyxP~ghj6Jxp?0r53Z3DvEyN_4y}HSi?S?X?Vk z0P3V_`YcxMl=A`~El7(=T8*1;72VU}{bT8&C*kU*F(_+Y@L8{GM4w1R;aTfNw3 zVLDwmVH4|0{S*mg=1kn$V)YE8(Qwb@e3-@aDA1ZlFebXVmfE|L3F1_T_KXg|19>77 zmV1}?oT>yyWHr-D61FX+qy81IGf%|C@?7*#XTq0-=HM#Y#8&cer5Hd1GRt9Yw^}CT z&D4RUUIOe-J{k!95Z64Ry$BnIf!%ikrsm`x{8S_z#@4+xK|L{#d|W8SX$?FIg z8x)U|FDlr?+rQz9UN#_b(>FgRpin@_dv%5O=oC=@Xwwo9}gl`=^ zf*~GJcP}O`?m=7`7=ihk1^NRsIP3Iew~b4l>Q=+^^Pb+`QYa++@Vbu69f3Np33UAo z5%M>N5`DDT&4s4k-HwozB$H)dv6~Z7j$+*1<-LqUkN6OETy?bV$;BxXcE4Bz0FlG* zz$qoN2F=dW$jKp5<@y}5phV|+E@#G9ulM24s~T4?1T?M|-r)iPsc|ijoG2`2s8*Kh z%U;VxPE71foyEK@$$u5`P96r1!p{CRIQ#MdQv+QFdRH|u?R`GHPqaJ(89GSKPmAAQ zpYIa0ne)FM|<(O zJJ451Hp!|e(IFPGH@g8}=dc|eYk6zorrvnz@J=yej;+#pmu)mpM&b1mXUCe!Fg(ll zMT0J~-G?NP@$ELbHrbc^Ngwcz6ibLWn_&HQ3u}Hex&LI?Av0&?@4q zZ@}Y=Di$qX?TX%CmRww;`;0D^PJEaL`Et6?(A$IhY!OHg(%$G_UVE>yqW0Dt%iRE~ zs~=|f(Q+9x=~ylA7gF6x4YqYK&`sU*myI;%>X0R|=SZ$(Y8~0hMC}T^kuC?y%uo6( zgDb5d<#&aj5N@uQG^VvKAu#`o@WFj}Zaf0GuqvjU`Y*Jhb_e)sg{mWd(wexsB~~Do zpvo$#4Vs{UD#*%Y6^9j3S#N=1Fcw;~jBnNUI8SJpny;xYagimPd1VHED?tZJ>1gNT z+l@h#C1K>LawA5k8S5pj90 zu`lkDu?C!_CXBhS;DAhQ|3x5sjw$-y^c}x&RrquRQ*v#osz8-I9Mr^0smr}YvcdC) zeRY?VO(uFZE^mF6)#uYbxTsl?3+J4y*3IUzER@0$AFH;apijMbSISS1A$+hi)q^zP zQ3K&+O5UaFAvfWdxp`?ffH6gkt=wkcGQ9o5h11PN!(L;K=dwp6-u{IRyNY)x#{L$` zo93wrxx5>I#8b%7;)%>FW$Rk9bK#9Nz56|s*y zo9+jB=57n+XDuhrrD?}I)7DNhCraL88a>#&crH*mqV>_JF5*U2PZPvADww-bg96Aa zCN!gwgr*#GTDoiQ+S1SO-*bCFwQII}J+6zgcO~=>XeSGc5RfZcd(ydv31|+~-!#C|vr&k7Xnoik_ z#)#RSdiAV>6A9Z=enM-eo0Q3fL&o0FJUs(tcYW;+ohEijT-@X2B4XmKsm?UyR)I>s z{gs{t<;6+x%mOAIg|!~(UWK{gHCA~kaHDm$0Kuyr^-JAnmwMLgHhQ@1{c!3(Z+cw9 z??;nQE$iW=R3hR_fhH&uNoU^Upv}EwW>fM(6CQ*ma6?E;MS{KNsWmNP-DHhx2Q>_u#{k!!vp5izi}CZu!JtBom0a|E72xHwxiVYE(|W zbH!$j|7E)}u!s!$o~C9p%eb}}zPvFZLIg9~dvd84Q@5WW9*e5gL-70Rw ze73l1BRW)}Vc98tP)`x3MCn~XjY&t@BFSDKMDS3$ADt;he_#utEu_0m=2=?|Qg%0#>=wYNlHFrR(pC1GF~hDmD&FTeH`%c64aQr<_Nj{Ar4 zo&&=*f{X@Qv}Aqq^?ghh@8xll^1flOT(6m2s*<}Jm@lMWL>bW^JV$=-%8QZfk9@8v z4jaQT{()Vy|S~w{`%7tBt_L1nDp>vqDIPE}Eoioj+-UpbpZ+z}tiubJ=#xocW zk=~(EFvh|Oyo44{7*McrnR06zt%>3x@2rEa%!B6XNADYDhaH6Kcs~bm3q z6=9#a-KtfDyO>OHwhNBS5~kXhXUnH)+ z83Lq*1MFt(&I@r4*gAI$JQ9o9{f4V|#|b>aW*Cnx>$26CxAe*1EPQ>fHLpbHD@8EL zwc+G512^J%L*+mkS6n)!7e^)h(em^juFWWo^0rkPGSNE1?J2Cgtl`|b+`$G$ z$;>JPp@Vwpny+b1KN`PujPe1yP7up<@&QJloTVFl-}-!=7q3~9E^Cpe_t|$E1qj7` z1!Ux0L?{I&Em%rERO{fLnWw{7%Pb}}jHK^QG*#~)Rfv@n-4-H08Udazud2)Vm4Rs|$As@sz_k^S6GqVh)b;0>_ z(@#0FZ@tKvBs03OlHveln&|0Og-6eA>}`@W8{1huQfah~qGJ|d!@2Fk$8;S@WmOzh zL7jwstwL(b(9W}EMzr~=`RmUFw^vq@B|hDfnRtryDRT^cGf*dEDEYI}eD9~Jeo|~< znShi7QT~e9Tx7%xyXZ_7=>7N(q)}UrWMhT8Ul&(Gj3qo%P#Wi0H+mCegBUas+u7*w zXb<}DYq={o-8e_VmD3-!$e1k4Xmh#u;$&^@Xk6=AHjY<95OI2=#XjKSO(yA@tvQz+eo;+bA|!kE)A@r^nF?A|fhcj? z9GWEX%gXohOQP6h(J10B_sJ;C_MB!!C?ZJ%T4c}2_$UtB5x7Nih`tTm)+w1(ukw(n-82P!t+JA z7?taWj7qe9LD(n%wUup3+T`fohSG=^nqs(bc+};%wS`yhS+YDfjlJFpNs%2rS#&P~ zR$2>sU74W=ZF=Kxvq7YRC;-Z*8f2uR6@|L@@Qy{bc1Hfz<^pZoN}vNbHZAU!Pq~#+ zsl*1YZ4YG72nwJ$2ZQb7!f2VHy>8^u+u?o~}1T$nn z_PQ%G5KTL-ozbng(Ki}3xK2k0<{S;$j7X!MFGsA-R^#ygVleWFHp>%D8bwy&N~tyo zesMfW99=K?3o&(hS0WQ{Sj`l$}r1~f+F5P~?+W4+s7>*yc zbmNU)gCL57lhXslkZJS)-y$T!{t}X%E%}N-l8#HVArUM2t}H2TCVk`zip(`1+#Sg< z`=3A5-+nVujTj1?PW7LDd#7S`t`ASkeUHtqU14_i_H*>soIH9+5u97#emEzDxQl<6 zsl#|)Ue#%1K4^MXU(Qk!9#XM_ItchOh`Pr zQNmcO_0R0pMzfydmSPBf1!lnUL8SWaOA#mUmN_kIpfzy8)-2^D!(R@AvP2<}F(nckHBo%C^VdO1IE0m^&)Avp;!xzq?5= zai?;Ow^}1)M}bmiQ)Cq`5K`Mck}unxSi&_Y)huSAGwWD@!6Y~jhDap zX|%S+7kLKE(r$97N$TR#4Rti`gD&7=&3|TMBdbf3CfJO*u5INl zG~34J*e`m-4-?!7n}Gbbz73{_CXgiRENU}OrCIumcnryHpAn9nt!+>YuVz^Eb>;C| zz@=psz88PrFM8ayFLpe$61t}wKwO02G2+21M_nNGV%hql+>;nT=d-*YS_JXTfQVh- z=9fULKy`F%9B&<6S@9cT78%i{sFD>b3LZ&}iEMMlVdS6nGtnx}au{XHfkK!=g>*~( zCc@(a`FOb+fsEIOQ(>c44oTR}4?^+cow5y;#|RjUs+_j_rsNX)QZC-PEW;L?s>)0wsp3Z_geA}=^eJTe2Z?FVeTNdpWd>!*3{Q$Z-dDxrJP zeCf!@xsNenWh4_-Uv+UXPI94alS~zqW^k7bmJ6We%a@XSA;RnndoYlzrdH^KSC=Tz zGPR7K(zYnApI^?q+>*p)07t&~;5I@<6IND_)yUI1oqpvR?w87-fSs=qF}^s~ZE(BI zS#xAS{_pLhkUz4*;W&X!^YOW&UGw?Jn1e3d+XfD2HFI;>2V9r*R93;>(ife7rzLJ zq>Ladh`)%^)T$Hx^0;|o1hdyCEN zD!QBm|6|3pf_i-2qUS{>RALU94c3*#BMWc(Rhr-Bs?Op}dWvE}a+21zGdoP)cPry3 zDvzYr7xSlTVDZ|RsAb%c#4d7r`e;k3!u2ab@~m{0Tz5Rr)PlM*W!AH;*jsNgUS!FE zbVz&U74!`B?;>I9BwTw;Ma_3zk5^bY^xcPiEe%y%WgWh}&uB#Ij+bX5y0t=N(D?Mu zMOti45R|FRm-vt;^K>(KfG>oLPrYS*%M5q%OR%ZM5I@rO<{LX_-9dgvxVZGaW)BAF z!6LOYTvYck@v}e|A~q`ANYr9|u97z4#18HuOk=yJ5FjTcm``<3z{m55>$D{(h=^}g z57-Z>l?u;($&>(&8lQn4)j2w9>{G)*^7Vn!F)!0`s znl%qD+qX(eV#=zVm(RFHsfb-N&uVLG*GMtdjQ);t{@w&4$?#i~taPobC2H|lH>IU( z5B4`mfQv1JW;7XA)$Z+tv`<;KrcYr+2bimvEb%?}aNS)Rx+&RIcagE|z6Wp8D+yy$ zPyO-tT-S}lJ@t#FbAW^78E#vyUjPC8B!TZa;H{M#DdN>2#GOOY%Ox1Am-fID_IuSM z23+F6F2j~d0kECmA=?>n!Ou~;i)jVhU@!N?$9je1jwLe3>G;zN;7p|6d|p2NV4n8F z|0C+3qATs9t!=ns+ZEebv6G5jv28mQt76+`#kOtRwr%|D+3()}ce2_#zT22{^nrfO z;!>nHzDv#Bbctu)3-4X_5QC0a!JpjxcNRfksrG|D@F85M#h9TnmthqJeW0lcNnFf1TkkU>yFy3l?&oJLct>ejm85LIj4)U)b73x|s;c^7&S)1X zp0RE>tkICr{TC%`EJfPg(6Pb0@zx3EVgrYMD5}0{@*mg@dKV)JDQOl0-yP0oS!^%M z#>)f&tFM)e$>kbh&2x_z?@dp&eNn1Q0i$TMba3uu5h?PnQs}ID;N-?i8m~KpcfT-` z%^E8>1jHh?f)OfRX=zB!x;G}K$DiId@18ly-y{)n?=r1-V+`n&d?<-QyW<~ z_uW6hJRi#d`$Kd8?1>c>Wb9xHxq6*BWGyGMIE?bQBv= z32ne>$a2(Mxj)0d1QyU2KTGY4>yz1qdEMFl6ATh@h_n$KrUU?!tcI4{KVR^J_Q+=F zE`?u^|2OO8d%azEam($}mpLj{IA4(e%U+CfU<+G+pru%xrHoVag9bT}NwDz$F$s8O zh+eKNMn?E70lISKtk+whos1U|xg+tLLPj|`GI@0gk~i9S_cIL|$Q|jdz00;{>Z2F| z`2o9!`@o%Z+f;9($3E1hrybxDl6Rr;A%VpbbP~%DVsLe{m1N6AfeMrrCNs%owwj)3 z--L$xwk?_C=I_j%NmhPWU{gCIb?wThz_yw_FdSqhf~WTV$zgpdkg|B@#?+V?>8%9& z*h4QkBa-VFukiC0ioc-XbM_F5dv)7wUe?}#4B*SKBFp|>%xiONf^EE?XeYFq{w%8X zR=F{*glR@=G#qVWdi(5f*|eK!av*wC|RucmFG2q&Iz={|1l#HP{?Z_CMj|f=n|ZG znPN2vRFY1dN?8CDH2?5FVaJ~~8#=0{uDq;bZ9z|)I)t91LJ?8~e|SDwYU7*)g!Ox{ za$4o^Yzg@oqkzLuL?z16{nD&a_!5HQgU*LM)e5rwl3X%$}8YR0ZXM^ z$2BC%`p5!zS|E-6nO@A~a6)afzVueY4%u7hFR2>!I}N}^M}M^;V?N%4)w*Fk5)mUl zw$Zx8=~g$j{s6F&y_ZcYgW)Vw#}V-1O;6VrU8E|yFKja{9jjMFIB9eX8<3*!vzC$7 zx!=Ucl}ey%{mdwDmf+2c_NZ3@{jL?*P4 zrbDe-r$xCA&qb+F{RBuOh z;yy8jOw^j{A67@fA@nqfS6kPZIS=73C(8q@eez4PCG`GsQuwn@J=i+Ovr|xLOzi5* zY069`!83?Z+V{E-I>?C))m351c80gePv(bC8YqsEQIty?*hbNHVbx( zrz^uId9%VuYt=)BP5ia~(19JNH}rOQWbu5u*l#k}-{;Y81cu$$=i%{6d`8H_A#DYC z(2+=ML(AOtWK<4rCiuj+LL`7SuKm8L4S{A4SegxD>GePnepFk3Ig$2ud%A)noJ?Qi zx{}G}L{DUqcZC$3=sh9#2bU|$=E_unJ541oFw!`d#-6lV>*CUO7@ptEECBw^T{UEK z24wISx3r*Zsd@~V&3E`X127khquuoqfq(Ix_=G#__kbn$`1Fwx%V@@vj&`cizm-GI zXR6>)Av>vVpJ58uiZUdzijVj0{Yw7K&;a-7zCNRzTeksn)w1k}A~xVv0c6Gu6W@@d z@oe3}xJK4X-4!p00W@~D+fA9oa^~{c)9YKKnvi_MFT*S_&ebCE^_{eeFivm%)Ps3_ zazHQO!|{{W$mQ3C1|MuWKNX)8A~WyStZqyj7)VvWy1so1EA?VPDMDC_AY?m^SnLOG zfvsrO=FGHf4!%#;Io0YWFJ&6qYo`7uE>;Yu;yLWWvFw2No4t4qiRkmdgT{=S_exj! zRMk5T!$2wHL;=kvXfc9kwx&Td{k=^jeX9G%1s4a?Ugi`@_Ura*A9P1xmWhzX^hEL% zX!ywyOp!Vn_x_op{ym9zfYRpP-SvLe4s8tWkc5Utg+Z&J00NCPZ6G2*#I*{CgL9Qk zL`83FJGgZ2;{yTTe>ugy1sqGQqSP9Si0SLIe|$Q{W}Npff6~$&P3~*KQ>#Q{fa*#^r~upxI}&EuLzY^kti=ry@-o?;W}0?*n5)wFp0s$)R9Z z>)>kJviGm`RknYnx>!QwDGHlw0GvW`Wpt93)QgXs{^aYiUvFs@M$w6MVy(tu1AIMtfU#YTs!DC}tu3KTA*Dh6sE)?-=lsR5~Bfe^TDv(*` z@FquX0ySOk=yy(cHC9JCwoH?l5rBLgTPpeofD>5w(xtcVEEwU2cYugqzkp zDrBnEkdfgH9DK_SoPD<59tXH8?56|$GfQ&5f7YNQ+p@}gx zf7B>G0Ay@oayzd?)YQlvb=>y6J<8U&+TEbAcXhc>ggC{{qAOJlekarKuC%iBp<)!b zv}2JnFo4*s;WhYl@BGDK1#8d9A9$C*1pq>3YWH4`;#u#(IEa1gun6_WYFa{ODzPmL2 zCDOEd$Ezq6tweJ=<dmfdCpRpGt{Z5)lp-1B)p34vzetNkaIpZ>n@2W2M z7$+Q@OYN=r*Fw`!PHjoPg$$oxw)9Md>}%&2@6h1MuQ!0TzI_<0uCGjPOr2y&tL-K?13b6EO3e`Ql9}~4fw!hL*~cVtJnZYOwMWYWaMGvs~ZZW6PP2S01{%N+<5)ewvef3S&8IH$b&Fh-#1W1!=o- zxIhWBFJa#vC81_ZNm4M<13xrj$JErI#rs_>JU}=!daA}FGyAGv)D7)oP34Kt>nQD= zN=)i5{P3vFaJ3FPTi1q%M0KrcGp0)Cw0#&2N~y^XsXt%T1caP~bUt;!>7R?E;n>%w zKW~~v(8L5Pz_99k+ZWEzP_fb%iI6|yHR7s-i2dzp(-ek4DH2<@hzvbiV z{!EwlS~hAh0_|nbyMYwdLU!|I*SYw5QX?zf(0aS+ zhK}v3l7dpll*hjfm8KYK8fZ`OnaZ;On-n9FsS`KK>8YIrx>uNkN#%Gly{0&yRFh^L zHin`&MU-kVfWxT`N1RLP`zmadgK20ZxYSAA!vk`C5`@c@SCYN-*Ezx>mHt z)HB=A|Id)@L1KS~rf0aAeIRvxB&(OaLZnCMsn7Z`x$4X&&GS|~aKAv=jatu08p+@3 z11o;PZW*Vz#=bGp6=po_DbwH~f)NmRv;tCp&ZP?+C zCfnmCv`Djhhr8NH8|wb=gX+h4zTw;3(L6Y9kg4vg*CbX3JH%X!-5@Y`4v1-MGjq6L zhf++Y7?S@L8aN+8Yj4LQAtBi;OUSvl1X>gev2zmQX~gibeUp>v(JJ^Oaqc0m+Rn3K zy_vdbDzympJMp@XK`ZAo?kLoYyn*DbF7m%?&4iY>~6KI7bm}6KDNbo5V{n^6rQ# zkH3I(js)%h8FmQaBext><^a485$_#TEY7belpMw-v=`gyt1dPnLAHkSE(Z?3P9tu& z`eY>zBu8)I=VjW*30ttU428-p<*GS;__txw9L4Dx9#na~Rf02>=0ITyZbfb#dT>@t zosxzyUp&ohb(WLa#}?~%&%#fn52E*$vWiL;a8efzTgJf{^zV&&>Y(FBBx_5Q0{8BU z0TYivJGrE|;qR-fpJw}YfptUhbdh@tv~=L2S{%7B#{=VxofhN+HYIy9e+L60yQBFP zt#E?M8eU%9l=0xu$Sbrsz#q;-P%1TdDbiib@Nxu81H8?t(AYgOH2-0W{Xj>@d-t~1 z<;W)$*v@j%jtPS_)xE!=%KhQ6@42rofVf|Hy&Gqj<&o-{=&H^5y22{=)L^VnNZ|WX zBvs&_wk-WFe|D|-bvj`+)Z5jvl0@>Po>Nrzc5_j$^AJ}WShv7!|TJaoaHMaLyDN( zQn_fXsM3ep|ML?Z|691UCYL7^8eHls$%am()Q?~M9F-pwmy)Dgi2vY)pF-~0P$Zrh zO%Tsx_B-->o}(yfe5XM@jI8Hy{QOHhO!wY+}lQt~+N;{AKgX(5FMe}j|UL?-dv%We4Q}*uZzEf}> zyz@~t=B?V?4x{({G9yI#(@tkH)>(#tqLQ;n)!#c;T~^_ zx{FChPVCCl-_dLti4`?iK2vxnab4%(ooG|@cl!{-{7mNb`r^{49R z0YnT-S*>2;-G##hp6J95v(T4w1g$c#$Bt)$=W#&qrkbEr--5tbZmS+QNx0MP0U9Go zvZ-&hV&<=!i`9ClWgS<1L=z@IX?x_pHWwlNe@|4fF@LSJtqK`+BSEJ|7u@gVB@|v) zz|a5(6?xIj;E2mHinXW&1Ow0ZU5A1>S(m1w>okn&kzvWzb|8}t;pTgTL}aU1FXz>D zg|TABZXQSd>+L+50ka%uAmB)IM`LPqY`bSbH(tw}s zeE}%IfdEH#CjY=bZMyZGQ0puCD`|&*JsvbBC)u#Hlu8q#1ZLfhPV!IfH4>6sR#i{Q zr;T_d!S(v-HILtm<@_KpNoVy|BeaCx4+=oRjl`KV%0?-hz7VTZdhaPPM5W|A@eTn- zp&Qe;WtPkNi2P?lBkpU~vi!II{I^6)Fa10~Vqx1b>E!$Q+HEoBK&eWf>pQuppQO;t| z#uX_0`g(%L&-w$yP^$L2NbnOTCwt)BE61~~n>p^vLO=r(Z4BoMZr*&|;V;?;d(Ctt zcH78Z-*Lx6>=2g($|CoB5ornQRn$>)Es&+_V(jLsni^KxY2eiJFy(hM-o-f23>5eQ z)6W(DV1cQ>qYia0R;;86Nv}1@PX@hzgF^5xLRL3JuyoyE34M9j&ibo#3?el#6)X9% z5hW#k;Li!HbQpnOUQ6nKKrI^6;HXaVHJlDCihr?#XE-49ZbVqrI2w*sC0{x9Gmwgb z>tv9^1ZGA~ia(cFcpbeoF~fyEb_p?mJj?rv%%_;peS33%>!<+g21SAx_nsnMPhXu> zuudN}DT(qF&n3<)dxzqC`2%=fhrlbmIrJVn?=A75&7+rAVqU6EcY?mBxcb_qQzR(9 z@J6!s&5x2=*4EIeA@P%u?4nbP(lQ=Pl`KgO*<~lLtX?M*Kuyi5_r9gR&ZcN5R7?gB z!f0}6$CADs1r)a@$G8o3t3L?DYP5Y0$yfSDT#CI$AkJHlBRPwaK8$%C$4R!jZ|n(W zeox@XTnUdlB_ro6OhL>}y23V%)IOm{PFo6R=$b#Cak_CPU!eIS_Hc$ zB>s;lwGnv{^OfC~t7u~hX-DGuE@=|Fot}2}LRcBh)+>xH*Inz>Qe&vn>Adup>(}+V z9H9D-XGa~sHBR<`lKRs{GCPUi8xj}-YPxBExtyfr_Tm%3Mu?jU{g8bn&Ax-cU;_OxjYvVKL$gL zYW`dk3{r`GT72z}pMT(FC&Ao3d61A3p^H9L-%O2)9Ose+LgKEwGx7WZxYqXK@6`Qn zZ^8WFwI&Fc`P~$k5YjgZ6<5=3Ju9aMe>6a4`aofXb^SL0DxwBJj?Kl|?_?lAQjeIc z;!IEepeqmtgTq;TOI6cKt|FxF4V$dhbSVdz z`>Rzs%FgyufAGXa75@s3wZ6ar7`q(z3diyXN-GYATKuR*UT=73e`8df~)>{F5XT98pje^GJx| zA(ImiWNYGQVN}UTP%%tUgA%W`Rg<9*@z37)!>9`VFaq-A7Av92Z+83hA|q2zq7K_e z6XvO9G>R-mF&Ve=)mvfV+Iz+Z!qOV@)K{sjjbLDW3gxd1Raw_>R?T3>f-MSBy5(_o z-3JTnN!XQD!l;aQp6l|SIn_yMy}zHddZf08#~hD*jltJm`(yf-$xS3k8;yAqjC3+H zZ_v)rz%!5C_w;yvF_C;p6T{MzOQ1}u`;+Xuk2q8C&`3Qk}>9&6#$ErwG6nnnj zmb`7Bwr6Eeo)-o>gEndp&Zs!$vZ9r3n3xNGliVIQ8&p)O7T7SIoL~?PL@5%br?1yo zNJBmlc6W|@qiJ+eBq^ACzG7UM;H6uG%B4Z|&^y`e4lrpmaW@`O&vA$o5=OhhTFn;Y_k z`D*ThQP8!W`$i97y;`~8TmpuA+~>$xky|XDyrK@(Ugk5dgr}XdP={qCcEl9ldfxB@ zn&FDKSh4=pAN3cv61ZP?M5InSL~;Td2Te^&4_@yEt9J%7tLHVx@<2`rZGi16f>eF+ ziQczRXmREbfYhq}nKFR?n-`_kU0DNbiILgo6{5{>;hXPAXE$MoQbFzg;iClSBKb%8 z)?i<+7uGK(O&$jq>>%m{tP+<3&&;##86-y=Uj` zBqk(BoW>G37Wq*$ck!7QQ`eWHay5G=D8_gtVPoSqiD3mf3PHRap2~8i!M(eK zr@^SGt)-=X?yUeK$3~^sj%$m99+PchFu;?BJ%iq@I z0pqg;;tG~an0a^H-AA<>hX_dr0=DJDaD#IZV;N2aoFf6Z(3uVqFaZPFQ)W#; zX&ZQLOnvjg7a!cL%{4t~)*7I}c*9Wv-V(^#px&eThhajX0UvhUimNa1w54^XIRPQB z{gdk$7}*BqGn_pJtb_D0E0!_%!nfjtz4JOq-#@StQOpky;)tX63wAlVL_|xwTBfsM zysg02QiWXKs;Bew!W|r1yS)_1h4xFtXJ!OX`k?YQN`n48fV1(d;zeATWh*pN{_178 zv2PX!`K95&1=r)QNB?dv{z-aTpKWx4yc03j2m~G3VdW+O;#)V^R-n4T*=z#DbEmez zt{5PBCtNxI=1$ECf(*E}?8@y9ZRHMN7L9b4Nx7ET(B7fKtE*Q$Ua%+_S)4tYf4i_dG=Cb&RD~o0xTwK!uoM1jU&_>z{5G zzVHF!T%;?4a9B@d0IIVFD7mvsrlRsimlbJ%ZL`g`-#0P7yj9jOR}SW?g5pDYt~~4i zFA8n`|4|s}C*#-s{dv78Vs6V08GtGam#gY87!FGlFz)QUzBjo2Dl%%g*=K}>q;Z0I zn>rz!Pm85Qu|44&P+r}oS%i_AL6?YF*be`;Se^U$6pW-YIKxhh1CwLfw zGyG+rGLBLKeZKro=;fE`h=~UULA{CCKao~Lv7ctWw|?qe`tqbT__Zj(z5j<>x6lHc zdg<-8lohN0;}zELr1WuiB60brnCXEpE+?VXm^x3yEn7!U@EazmT&ARVg@bdT!4ln| z@nT{|#M^)f>rCD}!*pS8$;NMIk%R0%ad9&a{q)N!02(?!!LR0`66nf}n+O&O_Vc>d zl>0;NcZGsna!w0F{-lSzOu528#XaE^k(rEwLPzF0`nhN2Kj`vIRBy3Q@1ya{re!bc zx%J*;>`7)br}(AIaEB{eYmghA9o-3eD9r=m@SmL)4(LJIGPq@nkW_oe47BGWUpUb}A>2amyL9`K26dxG)qQ*g6>G&a2?d!^7pW-WVK<&M^HF_CyN7 zQ$wwjJ+jTqmCgA@h2WFuf!2n^?bgNX5|`FwH>aBy*o}{#F9r<`^Yl*In_*}r|C|cb z{0f3(LXRZEU%5fpzGC=_1w#@1704~(O#-%K(=FS&(b1jjC3|A7JD>ZKGhFbG8|v)3 z{Nw&C;t5pcV>(u~E{SCm_w<|}W$a2Y2`+P6TKtZ9&~T<*IbN!NOxuwnIdsf^X!jQ^ z7VAM9zNqj%!aMt(5jHnj%WR!?`6riFmBRmQiHZ=h-1w2TUA#dg3BcHwvdvl8w>i#s?Mnf!)n&&(M8ryJoN8_{H9`9fwx)4*lgXo#_b(L`iO$( z8GUeVUxdhCapsSRg7_RXhu)a(KBweAyQKOcG+6wm$+Tadq(rA>jLbo0 zb#>?-99S!Qji7Ba_86xn#@yv@cSWbpKa+gOs8t^yDV|7IPuiJUMK8{lQn$Gdyd(POFM5Q8|IY0Rxpzx9;OAyx#z1 zr|tv$T2fRYy1d{>z!Y^DGe-A4yR!^Woh{p+wV8LD_GoO#m<-$CxIf2TwW|JfPRhsD z*Ft`2)0fTV(8{mD2>UkpOn4jwPF;!M&Y$q`|*-_KnI0uKoj`h$~E zDE!3|Fk49vbdrl_n+Hy#E4CKI%Xsq@9^$HnQ^JU^6-9?KBw(e|ah@aUM|?Z z4eEt|4od%JQz`^WX4ZPLtP`>Sj54dQjmnROTIi&dW3?c1u{*B+<*e!hTo$3lEzCLc zNQP_tPb>p9M0e}|-QIlS`kzY(Zg(lZifR$hjOOY;FzMk#-Z!|YmfMJXPXc~wVIA4? zlsteOi@NmGe-|g61*C}(45VP!4U7K5Jv1DBiFh4#4wM- zD)(cotD|d%R&!A9l~>2dDOoDFo@m0hywd5x29)!qBcS8#-&q20WJE%dH32;ZYCJ{1 z?~Cmm{~Wt-6wmkU>ho@oG@!s%3t7Lbfy49v2^zQFI!e#TIB<6;tZsi1q@$rpX8D(E zU%kL<9J6fBOmH0Gr9$IZDnDOp(CA^=Nqf^0IFqxC@143mL`T2|V5$qc?ZVi4BUYlR z`fN(J&JUcBP`o$?(Z919>dz8HUWr`5+5i~@GTGnV9sPBS{;y9(znot^J!ulK%W1kt z$OOSmDW(%m<04|=r8gVa0V~8r1_u&$6B$^+pwAL`rS@VFt1VL9Yv7~>SerIX*bggp zp%JiM{Xnm&PQ)|6OOe@W23gA@<+KgDu|uIC?? z*g?smvaYz`@ZPWF#~RTALp!i)#rk2n1yxjVaNgs)XV&ZekoPRcc*&Kaf5$i6C8(B( z$+=NP^?Vj#PA1qNe6ScQxDtJGyD+;}#hL8>W`GKt;!gO94iPgm|6uI;fQ6p|s}Ba2 zQ1N|l6g*Wn7*cvf`oF(LOPEzEpTNY}y@(^DY|^ptJ6USib>ICwBsnY*pC{i(2DgDvmiH z7K69;^+9O8b7JX%_n(mo*S%+?pv(rPdbcfDlZ~uGP>f;=*Tb9W4FMZ?;~!h&t+~7; zG$l_3f-%&2GHcAm7w|a{G-m!cWGyuSn3^Ov#GY^R{_E^hr%+KpGMfsoTjlzk&+9m)J35b0v$rDIv!Fm`8a%2ZjS3-|5Ub%Tyf%)-0D56=TSL0&@GO~> zqR*d*9;T{x0^c(OOJR| z3jbJsY2ankkyK3Nr@gB>ffZ7@L{I#*L-;SRj#3}_Or2&YJXHZE2!zPuYCG&`qc9cD zuRG5YBdL^z)p}v>?Vt)QtEBm6KIn$VhM4&HAmFf;;=IQb%hWZ`{EUXZ)W=U}+y_VE zL>I~dfJzt}d+Q3qrONX;4H%fxfkbMqvL4;F*@7Bt+0E;aIC%TW&(%HTJ~jNF?o&a^9WF6+O|lZp;@$?rkj^0gO{Q;7+iR z6Tw{|56F9kin}x!&XuW&cmbmkI$k4Ra5Z$8)ogO&tr#lKQI(ed!(TaO;H%qt|SbUjt8z&g>o_oVH00={|KX_Ge86N%xY&CMtKa%_(yBG(zd_EtS zUr2kUXh}i4U(Xd~(ourxtQZqnEoxboLEMYzX%H#`8@V{P(TjdW!I7fcICouageQ#U57^(rBK|t(DR>fbKV2=@T0#%kg zcQ$n;$!}$BFPhTSJKQ33F#J6UGb1U!dvmuq=Eh4URf>g=;26vMoE5yj&-IRt4$Q+8 zoc2@aL)or}NK0q&*`1lW;x+jloso}PF%2nDM?4k+UAOpt&H1C9Jxa}fhHDKaq`O6* zIpO`qDB*5mLu_U2EDV39l)D@L?aPe;^2-*M317CP5AK^mkerRXFjqHqMl2F;h*S>h z#K*FjqZ^g6!yfs);C@k??vXm?<4P(}4*Rb%E#U%yoU(QSGlcM~71Vjow#ywHWRjCJ z-n+6&C*%_V;dWatl{949{}X>&LD(UIACrYoqr49jOD$C3!-DY+uJpa{y**C%bxL6C zhj6Gsg;EB&3YeC_49KzMe1l#RdiTtUd;?a`=1~hF?tJ)^Bcy6<2BW|Lg&8{WUA! z{w{Cng~xmjQopnJl^IXG|Ds<{>Hoy8AIivtjQ+@rv>fa$5c?Mq5y#e{S`~=2m`&bu zp6CNVuPG;FX5CY3_gjDa3O*6T_4akVkIPDxX=s`-ETQ)vuxv)x8AM^?PMwVvg~8_^ zRQaZc_3sTLb>(v5kDTB?2j(x~16-lnVKWfT4R4HdIW7)5Mfmd>H5f^X<%H@n5=5#0?QQOKqfB`3R>Lev4SAriBp zHd`nm+mEZ@0>BtKYE%h4I2YrSY32*DuMtkc>l3FmG=@B;Bp+I^3f|oKwYZ2xpIVA! z^;JS=fFoT1HpeC#$|WQcUiF`$FQrFwc*3x@1WJtg6wgzOip<0C5h9+3g@rvE&@i1@ z(HYbU=!BHz6)JF9!T@1uk%OK*D%r0ttLXW5u(_Ag+6uX#teZtM;Iu8nAzg3zLU0llUen9QV)oKkK zj44JwPju26={I)TfN?>q6Q#CIy8R~aZy8+apBCYIRon3qmkxyvO-sGNC*D@x-AJis zVEl<~v9-NGBl_+3lEBLUh_VM;SWu%ITN{KYhw?Yk_KJa!3T;~1qBdglcch}kvWx2A z5nd0XpB2j0kd$f^h+`o`bCfKUw{Yqu6`R<~$;ozf1zH#;eWYtC{Tqzxizko@(@kH< zhsRMI8woF@ZrTl}?J_pLx+P!_3|7^jNEKR&Y@{I~_LG`xn3%Ng=hz-7YfB>*KGLZ{ zVC;N=S0YHE#s#m);y!%rv_9cO{7}0W*rl9k6b98V`Hpk; z9~+FDq(Qd!^JY5TG0W$y__e5s3qi#P=xo~_!%9p>F07eoh9Im()J8)npAbCJqfg$6;QC#i!Z*X~4phw0jm=7@%1g}?mCe|3UuN_x27`E)68l&xdZy~-8N(D^f6k6`1JDB ziol|>q&P!^fxFu}qsa)4&Tg>*0$L$Yc}}mZ7GaELEx_bhYFx128y#oE!p=ceg4BwF zq^&D!o($pFz4-1yg?QtV-(Q>dnbhoPNCL%F2HeLRCM?^Fj@S&XD74eZ8=XejrVhE^ z!L_h;KC5hMq=n?a7fbMX#D4CUF_?;lMZRpbpmwoP^aVRLNOWDW&hNyrmU&GEUY%|{w-jcZD1EuzX+}_ z{ojVulLPpdD4-Td2bRmCx2gms*0v_2Tzw3u-MKFyEDdTrxSv+|xZ*KqpuYT-wCe3p zPeB`{yJ9=?u{SEJ@S&x4pW0VI>-6;TH|EGDh%Dmqh}2yToG7iB$iO%%p?>cYiR`f~ z8}BP>b#(-_&BRvQI4;4-<6*o3wm(@$U+!THB3@1@a4(R*VJFCUugYXR&B{ldQ2gqS ze-hZ9x_(~obPd6dn$X{MrxJamP}uxXwCeV`lg!*RRkOSh2`ES|&6SGk685Wg^{r@` zeWWO=1%u(TOjA^OTU3J$bcSN(tBR8t*l4xaYl25G-lr+{kuDb@qU67Pv8Ag#=F3CFR`e>=LqWdvQNh2#oLUnu=fWRi_b=@isAcS=gyo@6~zO2t@ zHHFngu!tOIx8b(S(UAn-X>z9ixq2-0qyfnC7SADnl<5hX5yq;W&ObIZW#G~34w~qR z@lK|SE_>YlsC@H^Hl-EHm@|9Qc}zoJ?A)$r;`_Qw>F!wQ>ccXr4r*&TzR@U&U_3j2 z2++0$p%oZm(zG=s05OhR zS<0!ndtbWVUg(^ag{l1CYBhKtnrwZTNU@?vHgv%FBWpDx@;P}A^-AD$2-|Y zNWBkSViZq%aAeH&Nuwm6tC)MLpCp(1$3cg;>A-f}n?@aCl2c?LbgpL(IXBh)vS5C3 zvtLs7wlkdi>vpvsX3br{b>58X}eHxS-UzNvxn2byN|Eks=WrtyEI{ zEpSea&- zQp;K10g&EFpUd6;lFi1f(tr8&GsP!fJh=E+j#W{*aL?{e1{{{~mP&F3k>Sr$Otl3T ztg14kfJx2Cj*ct~c|>qdTQ%KM5=ip%rQWhR5#o&vncBgnXmlor$PpG!C~olAUZ=w- zsfOa&rEf(Yk-!l3FBt4u9?qB`yLQZC_>H5z8-)gfSiInNvA8P04*q})-Z$o>WQdS$;jD7Jg$=rx&aoiTe z>dShHu|ds04Aw>rPWL+KMxQvTjR}7g1g?t93;lh4q;vM8&XhR%BXhj5y#$r;K~iPz zu52O+uW&Qd=xhsP%oJX%#2anW3xnL)LNpq;HDV9)W_z^!{d-nzFB6tr>QQlF(Z>Ay z#FEew@o_OBL7AHi7-)Q)@M4q%1)IYk>o?HzpcCiDAW7P01Nb7jT_Eh_t(+KHfB$w^ zaw@Vq;`xtlm*xW1Bt!{(1BdO|brHO3w$?jum)wMb<-cZ{vnAjQ4wn0n@TJ_6lh8|+ zWSILeVW_MQqzw0oOnO{MQ6lz%9NMOn6l%Gcud~Ck_hVLkyboPIa@ah?p|9o9oC?PmQA zI4qbRIs5cBple3{JQW_Q(nn8ZCCVGZNkmf`Fh93BOQBb>+GeVM^JOC&7l7@ViGvfzE~@^k7O z`&Hy)uKdobddoG>+}0S^ME<=5;YP~X{d1Ns){deij{hW8)k+xl#m^*S=j?h^nI0A6 zspH_)f1?CmX$|oK_ zFiR<6pi2xUrO?v0AI>s`L)x5G!B5=W7Zs(8>E&0r91F*)Ve z-Gn%Q>6mM0C3v>A|6(f4TQ@gO{R1P+EZgU2mya%8^)i)9l2aol&4!lJa!-2Uz#c{| z34|kc@Qw>A@-cEn0~5WFGc50&97!gct@@?~*>Iu3`muOi){y2;$?=^D9Q1=ojpu5? zrA(gLLW6KkC$#jR=?WO$$dBMOz6nj@ZeQ{g_t9l|ZRKFTRWvU(qNy|5uHbow{t&vyRa-1yD=q@{L)1#GR zvNur5%*g^FrI^@J&hH8kL?iqkXL*phMrx#ku`B8*wUs zK%?6w`-`C~4*NBI;Ns3Mtc3Z=E@GbkwO2DJcE!(F-xE%LP3hhB2Pt#tu|glSrwyja zHW%vjN4XKJ24N3PoI3XFUrq{fhUB;yyP=EEk)lM8wPWelx1(>$cok26^ye=k^<%{q z$fRDH06+~!uPoO}9W@MLH&#SCq{q-JyqO;V{?%Y89$_@PH+GtgV=P`u)JJECLP}4Pl}k{?QTSxD_O$P6%*BUG#;y8(|SQ`91)1;U!l%3E&p&~!Qg&__+P0R?O)vtUx) z?)@*2`vCS@fAR#Hmb5ew3U($Cl7Diw!4Z4WN0=xI(FXk!*81$|D386t2-I2D`ij^B zw%Yu?dIhN7=vm2yWYbgUI@;+HEAlH*2oqUT(qFnIt0c05@$yJ;q^T=F1D2Sg-gjXN zLJ^rUl`&a`3XBv1-&wU_Olz9WN&~eVNWMY;e`k!b`-4M~hEaw6;E21_=Ls*QYxRE{ zJ_6ML+wkF?hBiJv*tr%@CGGf7W$s)t6!F9)aYWLee}At%rd6`7v;I1sLKx(Gjx5+I z2b}Z_zL)uxgf--Qc(FIA5Tu|(|9a6a1NGq*+1z3pMwH}&& zoo@&ZD*s_Tj$lfsUaZI(qr;(__T4@S@&Y9_nEU^c^^XCO#%=#NTy5r76Smqk)n?n9 zn{3;*ZQC|CYd72GW*eKW|6KQdU(fHw^LFOloX32>$N8ZHUo+fq@x@yWfZCoZIbSof zU6(`gt%l>qIt{GB5|G2N_7Y1uv|e1_hg}KdBc?y^ANxT=qn=aw`g*5cq4E2WS6Tcv zlP;Ez?qG=hHzYAQq5u4ou2QErhNZx=8Mah?Eg#-Oy$@)nS7rb(9}pn$ywAH-A53Et ze;f*7J@F`F>X~776Y^+K@jeoxHVq6~bn=b=(1QkFJ1vl``!02r+Yxm*$o+FB<@ z!vASKEq8E)8H$Jbl^mNq{R?QHtzW*{i@#W9h8{NJGwx%*!Afm5f3K)EFUS|g3C_WA zNZCCYWUUxM2-0Wq29#=+DT1@W zxNA?VNyhfL4Ec6imc(cgO!Hl^y4a1bY-p6^G#SvFQlYD8g~7J)UD&%yl4vV9yv^A9 z?Gd5M%O|d_yD6)j!|5n)s9@r2Am6?nEmirz>|P0lDeF=e^8Nhw^_mctRmQ}6eLW1w zu5@A*MzPB7D8GL@qljs#K3S+cIvt!u)o;c@m4kJ_X_(~3=iBqi z;F~?7Nnrns{NLa^Ak~x6g7P1yDmbB}7z0yNW*8xwk$n?V%J`9ydZW$gSZ9muiR=t; zq_5Isg{0Xard?;s27+o~VI&~_>w%la$qD^(myi6>*OzA%rDG=XfNvHsFtN}uBpc4E z(I7KXh_I$_ER^K()h5BkGzi+Pn&;=zk7?%OHq|z0E%b0<*yJD$ZR^vpC?pmd>Nbcp zc|s{;3I7CE17Olf#H{(MmV~ibZoQvCH>Ncf)(eZX>fw}(8eqEg%w~b}y8wN5NvUhi ze|Uo_67EX@TK$6#VPmd>TA+P6mCB{Koj($g#>CUk-9bx$#0sgUs|8_ptqpOZOa{r2 z(~W?SfC6niA=t9x`#6I6$;Av~j$owB2AX%kVw4V(W4MJOuSbJ=02X>$GKF)w7TC|4 zq?0DNxN-q-+4#a6yqUOTqB(eiKAkfr3>hVC0@<|k@XhwSa%4r2G^YNg+2~g3B=R5| z8eLy~ov1`1b7M_2`jCs=&axLi7Ec^^nOgUP&n92U6NTlMczpigg={~4rlW&Ru-M1Z zum9+B>x(qp`*Bg+ACJz66U^G|&p=;CG2LDVGIH5Gt`l*A16``z@cn*_!#i z`BEm%)Y_jzI9UpD0-t5|!Iwp$oD>hv2&Ca@)(=h3-~$KMmeFdG|7eb@bEOkPK)?{34`z(wxAj{`m97L#LhAC~}J6L#Y8RF}Q*K=N7{oQQo&a zdkDX`ce@iv_KGYwJ0$F27V<%SFDc{^7kJgdTSc%pa|*FE@?-0hFEEA1?$QY@*ya3T z&91C$b>H8CR2@uWeLW9?`Z|wYsk~vOUZf^9M9TuxuoCL?+HkzVW|1z@86F=bk(nwd zOjz0u08({9XtfmQ7(^8}PHBA&*!5SCsB#c-u`D(0u{_g9U|G`#E0H1PE(zeuA~1Ib zV%q#m(NQFEzX_Q<`DEmED+jf*NJe@Y@9TBCW*wQ$pt4V!99s{}K8S-u~`>$0oYiL@7(| zPv@BL4nx_nBi&;>`}j3G1!#>CC?5n7?+BTBH*UtLcWouYBjLk zdqB+%3{2c8B0aqA>mT2_(5V#!JpveSkKPwy|1)8=qyGo0PqRRE0~`O6c-DBU>cY_> z2~{H(FY|iCS9HIzX{s07+JdfT7YVya{vnzwzo3N7E+W|)Yb9hGj&{?Ni2Giw)%Fdq zDeukd1S|BvnNbZm8=&4@5_v%iTv5Bsf*dIWYODH*_taT%kN2ivluij_q z4zohfaQSn>C?K^inOI2jysGGZ%FGG<&$xazK4)lbL#iacgvpQ;kTEwQl&UBpMU4+g zVe7>e8#8?vz2%NYxV&YahrgpW?Ig&8Dc6p*bJ4%I_->_~OX0Mok;Q1r0R=~iN!U`Am$d`XUsa&e8>SS2zFYD_}wYk;PeO*s! z-ET0r8M&?`)d5gB0y^D<5ydjtc>7%s8W4L%=hKFBlxV?AdKFO&zw5zpSy#8h|2r9Y zd*Fpxa0JjLlC*6#wu?WClaW$1a@4WCt_u-LN(~;YVX)676ljHvZ!!Ruco`4GO&NoL zH0xhxxm1@x<($M&;=kOC+$87hyOPek*W&!s=d}q{N-SK31Iqhf4W+MjK&95)K;qiE z<%LN7NXZII1Hfeo?egO5L#C(119L%l6X~D$@NnLFK_)4yTss+tQhA1`E)bRIOmN|! zfRH@PS`r`3QxnCwwz>I=dvYYS&ID2nDttsqoc6TbQL3Yn>aOH&eK3JY)y)@mafq%i zb#+zwjd#RO^ElF2c835MHiH}0D1vx)pN(VOPh%L;;PAnZUd*kSgH-LoItYL8!Hl+Q z|1aS+3N>n`yetV)YGG$m##%97(t7t3v9q0#5>YF4BIZQkHDk`;#J8)E|IoXXwKkod z!c!4LCDjjSW|Zt!FYcD-g?2jrb&TL}0HAu(2){YDzV7lfEEoGoL}g&gskoJ?kV4wH z&@zu)P}bduC-XGOpW=k&$gm&?2LrNI6+#)W2-gzj#Mf6mujI1PY-&KSLhs&Z^(gwT zLnwyfWVrQ(_HrfFsq>U&xH54zeGML-yxM`76%2b`c9{I$J8xZxqD&vu(QIA4Ao zanfozF(HB!g%?xE))O9r)EQ^_vjie-Ut_$GR;Cc=e*Nli!i(Z^pQY%0aF1Xlzsa={ z6+9`bBpo0kG#!Tn)p1s9w9jQl6`nJpL6vHFeBU8DELjE-Cmk4Py2%kYSShyI zo~XNEN*~@(C*>Iw9<$OID+-ZJ(;GoMV+gitY3zq&Dk<_)XMl(eElB-KYk&}nSvd3) zyOIDlui4OqLNAT;v*Q%2ZFPxmRRC-x69p<9$qzpFSjwrvbMo_#e2f+7oiy}Gn(2W zY+gXiQAYLYXXQfz^in{kGu_F0vn{N7MNpxE$Vvjt9y1(*PXniWrc=YLW_;M8<5KHa ze0bcM_-bj^d@@G^x#4)MGlizjP0F&+$h(4E%Nx*Hq`z3vywK%Eg|pFJ(J)mVSy=OW zo>N=)mOC%1P4l8Tn_^kW!WeVh_>mA6EtSPo5=B9EL-v^Wx(0MOtfQINrw$Kj+O6Lk zk9))R*=_h3iFUwm(PEn{!)lw29Y)n@KVA=_SJQ()aHWUlwEsFjJgX=a#stmzTvUyp zZI2w-Q2@=nH^2HPV7h3i>@TYuNt-DgV`tFwWXc8s@~o}cGI@`(XQ^kRXM@h4jTXrd zEd`G}r?u?=W0sKluh8*3crVu9;~?@aXTORmrc6cYP{d2kC^2%qHt=nk=6j^H%ZI>) zq(HH-h&Df0>M4$Zigb+O6425aMxYMQ6@Mg`TA0^*_Mk($BEJU};z4Pz9=mvdWSBAL zvKGu4S0*V+Qk|t#*~}WE*Tgf@kMK}+s16k_yOw^TdTMffFf3-*uCD&w! zH;i&$BsC5ry!m8w!5W3LS2$1JV{So1Cc@cwk>h&Rfn5E-wN~M;s{M zO_A`vk*mrQiZzQ0kj-exO(K{b-g6MgBzK@XNz9JRbP?>b&i-cW%W>{vek{qI_~|0q zyc!O|{JO(t$L@_YrQ%aFwbMy+mW=3)e>6@3g{U<*i-xx^#%&6>kF`{=O!Ac;2`6K~ zk?T=%H8a*FQuhU0nY@hjS(!v*Q$|{bSq(|2?lb0Z@3yQe%O!+zHb_k6+<`ooCfcmQ z!DR-#^=uD0Yv3C%+CSui2EELd-qEv_XL|Q1T0i+RtQZOhhX_fm7V``i%oVn|04+v8 zsD{()QX_VK_PTQ5AC`Wu$wx#N3k{OFJZ?N9bJmfv(fs=t18SbRHrh!>MGg2A0WQHE=Y2TdL8xokAM zwyb&cHIxwt-xLKI9&3L!UKj+`xwN(}&WB=SFRvw1_IANho=*SoSPuNZv8;GD_(RDr| zq||AE23V!{v2C~9X24PLD#^5rB9f7Z#WsdUXV9-u|0KK281gGtw`&)TUy!Y{%m$ix zGuKljp|{GbdtXx$!Kp;Tg!m+Ru-_sJfYi>1Z_mvgppcC^HW>>Dw?BpOz8U?IHt04A z9@MD6<|iV*(U%*|P!f}jt`}pqmp5f!3`&0>?5Vl?;MsQCGJ1F3Nt9CV!x3c@J1Km7 z!7Mrbw9F61`rLnAbpYOw-io{qqSa7FIMlKu-T2d-S*t-zpAec)OxeE z_I2aHs6Z&8Ae%CSBDL+}0!?<7l-#?2o(U!Edi;i>DBQPIOOG9#=Sx-vSxM2b_Pt3Nw)x6~YTT_u(_ zQ}pgO9Asoe)gxco-j6RSmz)%&T0ARpJvu`BfFDoG0$g<4{i>EQaQ?rTc`W(8mw2oI+nrRSSM{4!2=Ido5~4J{D%pZL^EAgLe!OiqkY71 zakg=&m=QQOeQ=hpt4uB>6Vcf`8DYDm56 zR%C9A2rCYwV@mDgi;J9S-<43wa9=W$DVW64bn`YLh)DdIgmp!&-mWTY?`>^4y$Tkn zIM!aI8=`;gg%y0~!hTtTouGZjK4^d3$&xelJPChb&4}vB!y%yPdt(Py}mHAfT|FM1>z4d3SI$`!#U)M#|$ORoCU@Pzj}H zpNkO_u6lH?dyOR%P_JhdCUbGgF1K@}qZ42fW5Cv}G_nA)(wpWKBi5ns^xra>fKm$h zQdXovxii4wVYgY}nXuFUz3w7SUr+z>UWdxvdFQxe(PpL4DBohGZx>mB;)9>A@mFR*#t4JbTr z#?Gh(cV{*2z96~Tfi7gLZr))i<(C7i6E(5-6FI*=3NgW2GOtZL-`gx-lQp+*n3#>B zPSW(cek`chR4P{;51K0dj4Q3sX!3dksTHb&gU#xVhm>8<6e=Ztl6cF5En|li)@#=| z+FbKd&(ErWWEy4vW9Y^C$%G^?coEZeUby-;1M@07p;aCtgSGZ{ZX!B#gxT7gTPM>| zJsSQGRs_51=>WJ4_z;6xDki+gspg`Zkho0o?sxX@44r`fg=|KTSm<(7%n?wc?3bBoUMwP#Tv1zIY&SUk%9z4jjaen3EYcHM zWRw({9X>R+(_eLTZcfU{Wgx`gNSW?9$zUQDO4A!I56U`@a^VJo!$uFXFB0EcK z;ssQO$TuVRE=?;$i!BrZBX588)X?KBqJz^1$;t0&a!I4J9@utDy*~ZDH-&L~)+IGM z;_9(d?JCVqWW|(nx}>xfbJ<)#5Vl_S6a+xnB7cR94VM5)a|)A&UY+`@Y~MSD=zHsP z5@Qe2E@-;BRQtz-rSmUfSY3P5HvCg|UZz$L=H-m~D=`=5-tF#r9H#@9o4wuQ87RPe3O1!Pta(k7N zO?d^YOL;V+-0G{NElSY@S`ed5pP5Uf#mzvlv4dCz1sQ{b>*+|nVSi`jquT@S@ppvf zjn5($hVuk1cu$siGNYmh8xMmG&-e9>4;Kv9B$sq?y|)Ln3E`G@vG_jSg4xViCaIGZ zYE`{u>QcnYq_SeFNm1(1P(wdwAc7gXp<;4>majD+4D0#E9c9i97>l3o?D+qx`4+m} zyU7VUcnV^InUT#cFwYJtFMfG%c2#U+YH{g%bfiYD3 z_eXHk0NVAjuOHe9ZZ3b0P`rNGTwSp(8P8e>*d7b2*jzt9&%{z^!WALe{CSdpzU5bi zSp~lw4`7((N?>J@ysfOggvw-RuU-(ZIGfR^S0xq}OvvDrg@{~eL?+ZOZPI0CL6P2a zIyVSf=nxT0Wz765@=BnBmm#7)Q7y3cABWB-)qh^I{u8^vB}SY#cteAr8vHKR_sMdE zDzp%I&A58}b%P*!S9Qq&IZ}E3qpxZ{GwqAG3{s)y+*e(Ku;UAaWiMhhtOJx8CnI9# zG+mamKBEPBbuafKu@HVua~JgUje1+_uo9m?y$xS(OET-_0@T-0WQ3orue6L1r%Uf7s7 zEmdUVY6yzT<-hbmg0;m=VAXi(G+{7aCk^T#`oJG#@n2ExP&9K4R@HRYzd$=xzlH2a z5dgNU(O>XUivpvX0r{uuwY#U60U1%Idl6hmYOVk5^f-~^Pwec9KUbY90#nkKz}c-> zDs|V_O6S^&Q6x?Q#d)V%r~1RYm)y2@S**n%dJiGIIzMjKpM~u^uL@*c>d+b6dZ`9DsFk!6DZ)rY`|V zeg8M)ubsZ}L6|v_*yUhprlxwUN511HU?-1^Ber+1ni;MAr~Y9Mzgss1rzFUp&RC`802?4I`+z?Vh;RtZwmdg=EY26p{6NM zcB=R^FNvKl|LA`(Z;qu9*o`PRt?NhD?8~byvtlx4ol=iZFTehGlTG@sro#xDy{>dm zu24qMEu4}HpR|96*MPT*FT-|Qa49WROyy2jjy+Rz&X|4fi&;_{Dg#HTCq6!9?nsKq zo3qM1>D$BZ&!oxj!jEdhdr7eU?BQHk#WR-L(+&t@if=*JT)52Z2D^SZQTWz~R0Wle zG=8?;I`<}a2mLg`;reetP0tTf*ai|)6JN!_r%2o%q-9@%>JQI97AlBNag*6nj9ETT zCpbG)yVyrvWmGsw+VVt~j`AB_Sf9lfF`66BoR=3XE8U-QWr3B+q>AnudRh#qZk~(eS>?IH13p}J|8sS}e-LHrZPLkin zlyq}5ttMpH7YdQc7Y?CR50h>lAT616tgUu6V4+@DX3`m8s0JG zi(V$o?*BFFLgQN`O{6In{eY0nk+WBn6BGB){ZU3MFwX)4YARtUByj1dw*W$TE)w|F z9r!N*Df`|ws&zO$<`r*JVdmK#1A6LD(Z8rSp$!Gu9R!9K6LOaEH`z1^^0Y2ga08E&2+EKK| z6Gk;oEisyTavXRhe$x3^QP`Bb?+)z!P#}N)tlo#LzQY*Z ztyIri+Y!ZX@)svm5CnC&Ru9MSY)F~UHiGY7xlbYSZABQG+OBu(P2V#*%RuJ|HgJk8 z8x98Fz1Ok9@rn0WrWKmj)~?Sf9tLOkDbDWf+rV%TC?8Wn<{zWLpmhoXrZoDIC91$mPOU!UouyN8YWMts_u017LAO8eM4|F z^NX!9sCwCGZjq6%NCw(w+1M7vI8SuEGWZA|2}wCGX|>kHs*A^ZDjdVq63i(W@~A?8hWJOqufab#YzesvGGl= zF+vWAZ(i4Mk;_drg&>{EM7IPz_Mx-0FSuhPApStmKg<~y;M^afsW%Y~EJS^P`SOzP z?t%}CEwEH;)AtgkL#j?u?S}=G4$qI3p7!>&{scB;y8aOnEcRfbS`A#OvLU4nz-9O4 zS~*$gRU$dkBFkM+-z>LfBnAzw5nkm46LWXEjlF#xIZy*=1yO9CLB*O4M?P2N;uMlV zrQJrr9d3ySaH;!-9In$q0^rt&gy>7g$%Yd zG;o)GG*y_VOzeTSOkS}$QNO|;><=1*ORQ@6XbQ<&cI$GX8)vS_ZVEs8zUSuxl>up&Wv z*3!Dk1oAy$DiaIxn<5Kom2M)bs@|4TnW%qsvE9l_#$1m`)S&r!#vwT#gJDo{AshQ@ z_9E=F_Ai^WrUIVhlmA8X%%uNINDaeJn0flswj>g6_sq0TZ@B#;u)1D9=(-A=qlypj zYt1ZH;8INC+};UGanFDV@4(Shj=Ti5J`>3B2GeVAL*b^>mxd`R)(2BnDL@35lSk?A zYd{3k{>z2_%CAT}Iz5>5144+D%j^rm>2<@%9Q&n~ZNTeX3F5;3JWCn2p;*+^B3ZL^ zq?XTRXIg~=CZK%G>xBF*I_h(sh}dUe;JKs;BIR@cSa2A{>biACL&YU_?6>3E4W{+ zr4Yu|vA(}lnXe%muBf0=mCKGSX3SdHxR@tLxOKUXL=+NZMRII?-|xaPIJDIuRi>fR z;`wP$i8d0O;)fDuJd1}T1U79fF;hKX%L1C1MiARri;Wr^30@2qRX}Gl3KVCHtqe=d z7sx1oc#bJALIrf(Bkh21t{Qwc$L^v2@g-`ah8TI6^LT;jj$g)P>ql~@en?`mtks#% z65H~|KqE;S$5V?n*6UOZw@(>s)&^l=pCs*+*qk;LthKv;JeNt@@IDrbWov@XYL5)X zBh}z9T2(fbV*25UXxn1}4?$(y$`#laS&!S)TltVMsQ)uE7 z(~k=f?82xv| z#^C`@=sKjQH{V+k5(U0{zcc^YuxDA#)}948K~zlhmdzEnaiDuE_a)p74E{(iY)U~7 zHyPg^RAwBFqJINtm)X1%2!9y~o|n;Xc;$oMe~N<-`s8yfGJ)nxDE^%A*%3`nU~cyM za5!q@{->lZV;2t*zW7Te)-9=Au+|45DD#-j+U5k%aPF-tzV+7EF=FgQj(4ORq>2_P zrr1uLh0kQr%QT;M=Z=lD6ZnR=TqmzaD%*88Aqh_H*!-@pso+$$2`BBuqP2kQ$NO|;{1lB_)iYM=?MBAd zM)DZbOkv_~MhDK%_$Domq&6KM#V|}`6-!c)-qatRjIZ8}-f9ec=$U4OzAHaE5+zS$ zw;W$ZO0ip|`G*YS_qxEBseiJZ0mSE~0}W=fur#EYk#n2myI_KPj^>-xpKTImvPB;Rmm|Iri;7u=mC_VFBvsIVmMlR+LTF zP#p&cuHjL)BzvkjHgz+oQRPLf5pCI=J5gu?(wERQP|g&x6DoxXbGv(dqp>R~3fl)N zQV=>)_AQ zTkrq>ht~S-l;!Q2h~bwqY?u(24 zjD~IDQO!nD84QUu&NI;jwULKw9<@Vu#s=hma&Z_JXGN)$Xef`rU~N_+5K-5&4PeNbskwu4h>K4EqVpX^fCU zFT7Ergvlc3$&E8|)ZnZ<>8hWr>Oxo;ogXNbk@EuBX;AR0E@m>5B7$Fu6s0-;qrgxq zg(=$9j01)_))ldTML{K`mJ#khj=PaRBp437(@AG}t@nM-X@E%aeb%HEd&d#e-xoc_lVQTlfh$tc*Em%23Btv&G!j~EiT{)~)H}WRSt?|!*_4&0W z$=Q|n{Ul7?`<}Q-L`Kh0!lBa^KqZf3PLdQRCO2ON$3A$Dm^+Q{u4Q_UX}3AXiWe0dcG z@s|fq?`s(fYff2DF*k}y0_bj>PF)0zyf>J zg2TG?*3jSCOJj`afWw}C&iuJRed_8G%%}`V`k%hIZhO4AyxBV&x&dvw%p%=)2t&cr zeVvc;Kx+ur6c)ko3h*flRl*4~fDnc|VBSHc*kuE|~olLp^@m@Sx!!nC6^|CyXp#hH! zP#AF~N2KDWdw$l@H(6~WxF@LpIX5Emhnb|e@%G#M%Kzw#;{Jd7B4#K%8=Wv2u}U%) zPh!l@>R4%}7ENePhhA$t5&dgP0`*41c6I_KT_%fpHM*XOgFS_FKIjtdx=5|>l4zsb z!9&<6#(oxshR%XEu&Qx3g2w5X7Ex>xlC^!Sc2)`N+l7UsvO>R4%*#%V?^MOy=ZH>p z69R(m3hN(u)5skTHjP#l&B$*{*)Vta{|^ClS4y)8Ms!9hc^MjOx0 zE&qhLLup$lT9XnshpA7XlYsIkal$FriwSC6ko6VxI7Eo& z;h?a0Q7^%5(J^j`qFFYao5bmD^cx%;EmesMf)FlwUxQrCM-LeN*{cOCO2_#r*X z{#?#%CruCbPD0T3A%Nm9jO1mgXI*1LH9q-;sMyuGR&&^|ux$p3^l+K0pt;InVpE*apXw~6 zv4k0N!}M8!KmXDO&*o<04Wdw1Sqks`)dKi9eL1QP7v!7YDcrt13Rj8_x8sy}s53|c zl+QPQwmo1Y&!*~^|3EsKPr7<8`;qW9&FU1wt%Fcli1DW70G{wPOk0@DQkIhM|Jo8AJy%VitbKI2dM%{3tw_1$A12Dmz0iSK45(5 z`NU)aX8#iuqj9boAF*hX-P4DUcV-fE8#gk!A?|Wl*p~`-2dIjDWYCDBuJI*8xGb_c zRJXo`#2Y|zhQkw7T?@&QBUr8b7|?0bK_jj163|DAO>pc7nbcCsamGAuM)wBroy;`4 zZ)Dul{sb2rY7JjvumrJSx*7%9Z?bW-1^f#59g+R}(cDkmtyz0IcYoM*@e4 zSsibZ0rX(o#FT7!l|anTsTf?@*3rIVYwr$ryxDdotS{+jg`&8uei-W%G2%g+J-RD` zR@NdqGQhDSBk86hUa>Z|?SDLCJzG*}I7e^`#hZFym)cz#he7?G9~%^rcO9%<=RN9E zqv%Mj9|}rQWpnX5-H(#`yfReVh3t`O`l3YFY0b7*uyz<6(H2L)e7?8N`I#d=H54PL z!Q{=_JY!LvkfYLzqNX+(y}ld(^AG*g9eXL;Y259fP;W0M>s&psm?V-sVRC#tz=CHA zgx-}e8TNBppjI8#N+U^eRLIjui7xQ%Vs?FIB1VtAbEovII6_rw`O+6j+^%${n1cAI z5v82!7n=f+8(@3f1LG&Q!^oSrXM1gj!r~7^x_VCVHayeZiS4`jFcx}lExWprIWs7= zT0tnHD%XCV2BFps2875>@R{iA&Ac>a-g z^~oj!E?6NJB^)nzT*{~A5$;@e6)Q*f{|02%4M|A}7V-$24fYmDLLxxos;KA?_wmLm zq8Tx=I#9JJ=H+SVZ=vGg)bv72Z`la5*vwGjd;b2g{2x%@ukrtJHfG-f7B#+=PmCxI zUbz%gw%FASHBpLBWMh}lLAYK{DU(JY0KD&Xn-P6!S$~&?O_p|Hklbh3S2GCxJNzCV z0gi_5`Z6(gy6!0hP8$4%tDj!*NGj74Nc@0p)Qc-6&0;D2v0!D`k$K!KCNfCK6NpIN z`M3#N%G~*=``P@E;gtTZN7`|4cR_D`hR@XVoL z2Ti|oiR`fGcy!qO5y7f#e7FESg3XwSJs_ivb6vvE%{uyd)ik8}c8u~r2g18uO2Q}| z<+@4o9XKAZb9Ij!weq=owq(i8g0L^`8EvJqG2*RmWL=Tnp{8-YLw z6E{n^#AX5_zarR1ntS3qN3OC6U8L5yJq@^P+?!vmyYhPC~PqC?ph6L0fZG*rnR7Jz2Aqz4gjx`DL9v^XAe&3_GyKJ77lH4l7Ouuj6ECFno-n(t$}K>1OnraVT?_}jNzYy>^} zLnu<;2_NiP?UK5>*w&i2OKtd|+K#!W7>uRYzrz4&2zT{D*&%G@g9{K0E?!Zqcl=x8t z9=~Z>-g`HatsQMD)w;r%KTp;_*OyPXg>}hRJMt=yU&fDZebG$Tg%4zA!%+Q%LaGL# zVNl72rB;7OpXlEJpWC>hk&QFUzvL)p0#6waqC;#Fzg43uvNEX9>e(JP)wb(W*#(@k zyvh&qk4qh%tpc0-d&cQmYHnRv?W*>F&V8F?z9Vj-^4}JQZLNl;E}hmZdMbCgC*)g& zvgh2&;&-cH2t|(u7aRNhNq#?*qRRhVa#A*Yi_Fz*={stV|3T$|V+J)<8G|1a{eBYp zz3R>+*#Tr+V&|5Vr?%1y+S+Odf96wluJ(Wz;7yj)M zIbMa)m59XNFr=M)i{Myk@v^L`;j%i<#y1@C+)o-O_HoQFysbRt_%Sb+H7^^GHosWH z{>Ogy9@slQf`>_IF-!OKiex@EBI5Ns8P+PTYTBU$$$4ho1HNoFiyiua_niie%H@eD#@E z?ajmCt+B5#;^58O3VQ_dcwQ7$pV;Dgqw4q>k0nwf{M|j-sYvhhSrLjM(vP)SbFPea z8XX!}U-;%XClO|CJFGz0zGAS)6Rz6RW{9lPn;zT)0bi)V+r6FnK|y3sSZ>1Wvfj3$ zo~ZxPNOFd1lj79h^n-fTgky4Q3`TEw?=tC-FK9}#ZwE|BdjIyxOch6Xy?K$R1UVs2_#Ct~3J6zwSX2b4z3l*_(5k?!_0;-E#g z6p>}}vgR`+zOVHLU!JErAw|&hk&}hyXRZ8+259kA=dQIOLrd#B@})735^6QHm(JPw zy1~bt1`U@`XOugYXXs`wf7%x4u`tj7iTcJ_;rn-QJu}Oo)#WAEHg;c*HGMcR+p4k* z9?Ib{Uz1w&Wf87jj@IR+#O(}m9Ipe+yc%^Jnjg8^A@RR4gev56)~TxW29l8^;qp%S zM={U%_w4#G1^A>WVomM{8EeMPD7ndo@Mhp zewc)cO51EhWeW1*luPU9>hxK5})jizba$D!b=K+!(hcsATLysa& zywbuS<=Ea)Vw*QvV~#aCEryrQP4sU%*Yp;%I9P%JEjW=4s5v;h3h5it?(*XAhETX+{5d(yA>>ikyFqDo^#htnfMkb0ZjQhSSS83TTi~x2V*RxH@|EmSCvg&!G zfdzV)L${pM_l8cwqczVS&4=2g_8z2wjm_Sm~PJqrM)~i}gkDH*V1j%NE=4rcae7+Mg zc$LQ(Xs$Zkcyg+Kp^2FWxwZ&|;CHkl=R$vB4oZ##*E|9dp7?q5uZCM}ysY&_d6WM9 z0hRKq;X{4Q7Ln+b#-nD z%s~XK<;mXFo|O^LBrHjXCuvkf6)OU_*WqspvkedRE zg}V}OV4+@3V&Yv60KPfpqFiErf*Nfd(kAo?}Aqm{n6utmPA!oM z0MSHS9N0w^6#3z8!FdF(eJ$3JvG#hkhfy5N)T!ERT(bL1RB!jHh4q$D z*|yyV+P2jWuK_)h7Q|aS<}9kKNuoU>5Mf+w;hqc^I?zNq(~jOtg6e*`@x}dl5@>3R zV@BaEf{}P~eK5u!Cq@x#Bi9e-XCgwLl>w>k=WU+ru_gDza16_6IZT~^!4izu<_pA7 z5glgx@B?g+SyC{)7K;ct4~5`4c6&;}Cz4A!QF7=u(7XqV$R(fhW-AUm9O>cpC_1w^uaR zi2@V@D14+7sHTR(f^6+#m<|(`Zggyez$?l7Ut{ofKt%JJ(kZr0j>lh9X(0&X_>0L4+BlXRlJI-l+;+yKnO^Oh4%Zmz=)H3^ywHTw2Z`PdoD3+#v03vYpoi)R z3%L9BCK0h$5)*g8sv+FA2#ONRkPI8NOahAx2>vI?>eS$=X|eBO1hv?w73MjtQAUSa zmzB>cDpKe;n(8V#BGgI>Gq*Hx^|#Ks;K3T<^=)mJ6IPY=>MM6gYk=n4x~H|S6EpS8 zaZw|qlWE{{PWKu&Y&&H_W^)L&0du~|{y}8LPj!1IL@sCBLt2qOQZ&ASAarbp`(3+M z$Wcg{^c@!{-y9UmmAuH$mwr6Jz81R$2EgOIUV~K%S-eshfc;yJ2~q3YxGFwrr}6aX z+p+aTCc2fPf|XU)^~>4o^$`B+jw~aq{f-c{vayk-GcdFj2iVkzm&IYar-l|UJf|`g z6J?x50VHDwL=l)4bd{oucP)ov68T!X1NmjE-OuB2(%H+6&D6j(b1eq9soo;j+oCta z{lZ%IHqHqOdd}4}!#uSY>^60&S+;l}MkWlnFJgwk#BKHLFqJrZ_UvrasUjn>klg~f zAJ@ejTk8#WdgvclVJ_uSl47)z3|dNP2D;sz(%~1x3shx>8f>{fo=EIA4aGZ^$2w%w z1R-VFha?4TL?v2o29r_a(!n4&Jq}%#k*0!Ia7+R`0s&tt0AR1{I;pxFU#uM=0w7A+~W zi%ShO4LXIV0o{CQj-at|^Rq0-_UU+*m{vF2>sD+sDKj_JPIvfv1*%+uR zL-i@pAm41t0a*VZQQsIG=@zXWW1@*B=-9SBv2EM7ZQGjIwlPU2wrx#pe|^rq=YBuC zx~i+X`(1ml^~v4?MkOu#g28ER?3!9#j$t&KBVr-O{yWw6N42MFR-`$jAl`CFAY;gbZd|wENU;;wxk*4r< zHe+4LlihZ-40YVz?7PUf;al?9(CpGi0J^IUKn7)ox=75 z^)Q5zzvD-Z5gE}4@edcx8r<|W9Z?m=sR2p3>#{#12NbzSyx5<4n?iusP`qWSgK(~hAa*{z5D%J!1heD&0sxD zrIO}TYR^e{iU3C3zW*HrPq&HHXtlw}*;nqcWWsTeCN^v?7EOclF>*LFQoaa}QUth2 z9zfJ_L}>-^_Su9Xp}HBP_G+i3W-B-U%pMm+9blxth7c8NDhOB`Z((zOAY__@X5Z#P z6Cxws%@;#?JaXOH0p#Tyzv&iEEp{VJO~sOJ%IwFhEq(jKVwQI1?kR+U6Ky5Di^j(vY^+3F=Wr$=A@omOAL#N3LanA7Lj4Fsus=b3!|lEmlBVfBX} z1XYVDL?tJqltd`7gv||wA%^TVPAl5zia+&IwgOlBf2aC&V}vF>6eBq&HK8cS0!;oJ$z45loJ-uPb~ zoEQK9k=ABC@3$DfZU0*HYKt5h|2w#|t_$}Xj*fJPkg^GOtamdw_qMjdf_8E&gOMiC znrB2ZSwfSvR3A;%6`vP;MCmkHu%xH}`c;_4XvG04Xx_~DZG4(yppyP-cx{m!ws`&+ zLF}2{Hv;|&l#F$tydCd>nr~=#vYgDb5UuJoiTEZ6KU&n#Z(Ks!(-TrxTQz#F-EA<4 zJOubKTUY$H-sXY-b|GMF2KkLCvi|unN4=A5Je8>=W}qrhH;7fiNnz-Y0~7(Y_I|qj zW4cU{x|pFf7I6T#6=}rZ)`eEH2@p0&P83P?lPH5rEzO|G2{G{lkg$*tw%25Una%R9 z^GZ5MD6~C6{xYP%9XX93rPZHV=QRoIgfA>+1$3!fZ`EkwWQdE!eU^F z;8Vv4&DEJ7h{cJPD}ji}Fv0WBj=eD3=wqugPkKE4rDWRA=X*x2qR2sTVGSSMvLxbd zVY~Ol8pQgDNaq550R@lo?t;)oTWw9`qjIAC^aK-jFbClB!Z zeUH{Aogw0+M~+sr6%N3x=il~L6%_n4STNqzC+<)Wy}ekDNA|jr_Gxr@sQZ4$5u%Te zxzcwc4c=|J0Yl_{?R3jhm|`)jlAX=<;@!}J>47YMs#wzEQxhKH9}e>f##2iCa_*b( ztfiGBE47F5lb@9}saLLqCne$G!7x~OLZ zq8_7a7|RWZl1rmG>v8$Jc;JQ17s?z@^kJKBT9=B4%=WU8!`r`(#h-Ak2VRW6Eg7B{ z$kq7(p()CBi?cPqGWgmm3b93%Cv1&rvI_4PIzQajsq5jgfUSw&mmI}(i~Js*M0B60 zD$hJemW55Iv++@LB5?J0g$O@%d>2_MOT>B+8z$+yUC^+84kF*p2$kT=da>_o_8O(n z$#Je;taO?Yuv5%Wzq*YB&+OOl>(nP~U{5I7UqBmwUkqA;`)&xvR7Sl==m4%AgHBo4 zyDdiCRGDuAK9Q~_h=*lly108`y5kvcwDd}(s~S0@u=t!zad(r*Rf0VKgGOPT^AHJ*4y_jIbh zxdN$YutbD9vxz8Et=;Y3WYsBQ)JuGocp`T1E5~QJ-15?p;vz;pHPez_KyBaRvi4(p zPG9BQL-$)1i#9mf%5hg|E>ptI{Da269fWeaA~jtR;4NFsM1p$fZ0qXM$5lTssJ0DE zHwdfS^GQd!T6fbayyHQ`H2F(PaMU zW1S96Lhi=v!6vQty!M~g+2%hCr4^ZimbP!4{wq=;MLLVI;78ka{UF2jRF(q2V<@BC z{n|SgBL7z=VX|h_;lYi!xjtJzWI~>8-A)FjILg#+rUX*FvU^QU$7~XL09PK*0RBxw89o2C}RWV|y z7T3PmX+*AGp4!`$6DQcC(RG|uG`?;Ealb~cuE(%EQ-}i-hhUysW7|;rz0fOdO8TxF zs28f~j0IU@#;KS_w(7kQaeE;!!YK&+VfoaAJxN=4pqIVCkF7#m`ewm&Jq2K4#4)}= ze0PP0t&m(4nmDC+JO>)4AVIQYzelF&FXWW)E{rqkaQEvqEtk4S8yy|K*xNh_?~*jnN*u7!$kz^cL*|LPvGs}y~l?W z=JT05$fhbETXK$B!uYkqWL>SiPGOM+Gu$XZUq7Gtko1o9CyR=8R#%1ReTKh){!|1bX+?bJ(t05XMdBF%99z`OvX<~`dxDvT!?^HkGwcT7O){PaxX`xVmRI16_@&1?RnWPXv90cC+6B_VA( zVBWcfF|rH2B=b0TL0;t+l+={I2Low zz(s3bH{=YW@?Ue5`mIaYuWK%C;qi zyzJeQtgM!yxA+l}{#Tf)2~m;<fD8~_RNU7krsic0c{x}MJZX!xHf2j+WO|ADps`@OGxgb)U-PBzM34J*BXq0Ry?M8k{{s?| z_|x?4L}$trQ1x-ai)i@|O5kJr9}{IuT<5S4wc+$il1GSKHYXCYZAP1i8k)7P_6JshEfbk6!hIT{q`LK}454FZIbx0Xggc&bt z4syd?kYcW54zuac37RzNajhRK-N>dH5AqtW1sIux(e$rD>DM$_h7{TSSLfF>5!k~H z+#kn=mAi$PNvm0f6D#Rc`Ay(olwH#y$e3H}0(lwm6$j4KDQxBVwl&%Wg`8x$N689s zy+|0Ei=?oJ6$k+Py{BI0_iT+uQ>D$L*~Z&{Pdlcn$FNTze@H5&3rw-}2}kvC3HQEE zGv!NKwYeChkDr?!e-6UokC!U2uLs3h+B-XnCgkr##lv7&tgM2_xTmn7pb!<(%#6_G za1ct3|E{0h;=J8r<6$m?6$T^f2548PH9;GyF8Dt9VYPF38r{u(7mcl^m1Xj&1dEv( z{mFxKLpdsZu}dueWl3#mL01kFM#Q?dgM@`5IN*rMOJ7mX+zhG^_pyjMKSp0-`oSga z-eM@;#l3b0kOqv6VYh)c;ec550Io;2iR%1VHqNQ!pGQkYQQ8Q}r^)*1WXFSHXYZ#7 z?8utYUML%PefpJ^#D*~R@{<7Xp9g_O@bCh@y67gxcQO6N%@C6v-x;4iV0;%}?58+_ z_W?-x`qacq)ePMWf94@A=y_($Txyr>GfDJ& z4K>z-?T0~UvW2S^y4CCVzd))UG@@Xg#*~$58jVrJrHo0o;`xj4B%GXRI;v*A=s2=3 zTW|Z$nTZIHvoyu(Qay<7QnN2(e0^+x8A*Yo4&UEd6$P5-fO30y80WG5F&lb~ISno~ z%SvENEtN9(g@h!&DK`&A<@?HB*tD>DZP)>hVg=}V>fW9~yGJTPP^4>2ZQO(kND0I1 z_)2z=|9AS2ium8D#}yE8d=mN&D|b5ql?(6)K+GAVbtG88#* zv_GZoE)@-Xp&dJ=E(FfaLCN&SRUV6z??)rvGafb(G(lTA=G%{+sN$=<Q0Q?!nZZP(OM6`2{_Oi@x)%_3?NxlBeRn1M)owf2j3j`WN!C+M=Y3Er-hJO2 zToQ$eeJ=-N$zXjc>9o19EuiV#>rS=(Opn9Ylo5# z4Va=qu~{C@!ijcqY&5!E7*eT4notp)1D|)Mh6hjdgZ}c+(Usdl^l5mPvruw!7`NG> zE5o}{MzQJ|$N`q3*HNPZibWQe*}_@?&tAC6hf%nip?FwuhV=^$Z}Wkd;mS_gmVilM zZeP*av#KWpVoFE8@ga7jYa4gVlX=jC&P2Ayg$KIE=pT;IawV;2pN6sk*l-*^9K#9R zYLlJ5ZzZ0Zi+$M+I|3Xkm$B;$eMCf-jGn-NBJ(7|p7GMdDempM0CfIdQ=sa5K?Z>a z1{x_8d-?}@0Eq;W6tc9=k{RscoC++({Z+4;}~ zWhu}0u~plkzA-%@Ua2(v^Ix8Xp6VYBLVbhYstp95dLxtxlVx&0G5hmc9d*pFRKTrh zE*aZgwiLkAW`~ruN?a0Vw8fOU77d&(KQj5Ghs<`zghpf1+qQh`gfHOx2dusDmP;C; zYXzQ@URp)^pX#}#wCSk1f#~1l^KH&~j*UX6g7gHWb3M6*&Jc@~S7?h`l(j!vs$;Rok-M!%ouxXx7@Xp(8 z>-VU0sHNSK8wz2cYu2R)(H^EI39!VaW8#zPkrji@QtLax*uXsE( zp68h;3u#N1y3jdb}SqvC09~O3)$d#Fa4Db4MP=+U7pEkBm z1UJR5wauVq1v@aKq0;&(E(0x&v-b;hEs$s>%ChZ3C+_Q&_rug0kNomJE5k;4R+)*3 z`sRKOG21?pVfKZIs_o0c z*JN=>D*X15n3e3LY+lKyl1#^{)M}KP{HB(I;hUfJ!1e#AYZ|R6mi) zOL?~CqqZ3~6Y&=+ZkYQ(%S(ZypJ2Hiqf$gw0z6%{x92*a6YDQ8qOkFe6LMBGZK>mLp>pqO%!h6 z11EurBOT6*Tuveq0b01!(f|S}LC2EnVhHk@w+WU`g_PrQ=m*-d8kP~04OG?3BvYC+ zmXzXw$+p;hnFWcWDgcDwA=5PgL{w1lBRifcT=ur>W+#A1N{5EaAgXXQUDZDvrp>}zZJRS_cA-%Qk_3yxkid(#gjQ4PdRS02r*+7U1$HYPFcuM5rR%f6 z&fa?Z4BRqrBOwdF84nJy^%iY)*u|0SsCw4xB1fyAKXX7) zvQAfx+fZmwOGx)pJIM;jTrm;3hJV@HQ7wJlI%FN#_xgUeonO{RTM7$h=t!lR?c(Pd z7tkg;c0_M+xilGwUi{c_cfg!h!pSH|vGP`q=Bb}E^)P4p3ROt=I)_|2WJF7miT&g8 zDPry67j!{O$$Kuwj~$iXCcu&;cRQywa{W@F4WZ{%y}Q9ttrN=aepJXt(b4F9%GmX| z#;3f@BopQG91OYlnk7bPzNKxR{^-O7qvSGx@w-`D-OaD&V9JUu6h(`8OjM?dPW;5K!b z+;)E_eHH757<#eJrth1$wu1^2SB`eQhaJ|ImP%ykEJh~FT7gIugIOEgWlxqiQA__T zU5oWNJG5}*bzJ5GlF(%*u8gli`dkyhD)%ecm+^;%Df%7VC01DdzM=f`X(W23dFgabP#jU$Y7G19uI0jHsyYw%jm)hoMzM z<9j?I=`eV4{j4E&yYcAgA4z9t*3CmW%x-fg3th)ry}BJ4fO-Pf!JmW>vW5YALSnpt z;i%&BQ4|e@CSg9>AZR6q!1CnC^s?AnpYCA!|Fi&(nIdlJBCf;Hlq_>YtgJQ8ZE*$= zhsMT3YoVavpHmZXY#wAJNyBwcL3R{20JF<&;&LmHS1VZTJD zz2^->I61V^!HJPa$2|r+>?l}Ra6HlJ%^)g^8*CGhRJZIG9pQ~es~hcjB-+aGAt@SD zT1g%DawItv`Ef{(;5Xb}j)BAtN~FN6j3jpM|z z$^Er3BC3{yAx7FE{QmrRmxn|$c`D!gsBihCW7(6*Z;F5o)I;qNheqadZ*ZpNi(xY< zL?ZIEQb8SwHdAl)wBgd#QQYxJqU$fR?durtQ6P^9z!H5E>IpzDBSWf6xC?;x1NcVv z9M!-78PqxL`;WtWB!jdSS&pI-M2g^kIub zci#Z!J=A^rrS!SF_4~zYu*E#;A2{>DF&F9i>MMqZ5ziKZ3^i+(0zvKFz1>h$J3s$@ z>J!33VDEOw^x(0kV#H`K@ZHsIxG-F)g*im_-kZ`X;t!vtI|E%hN?hRxb-klati&$5 zyuxcO+H@d!jF7q+X*L{Z?AIOk7#tPtGzP`~oex+Sqs^x{2O@T$5oGlVCesfDqTz9; zqmL(tOH6E#l0EXGu}YqoADiHWA6O!FJkv`(182qV*rnBF4<2ydjV8&7 zAE|;sLo+cVOncx2WC0_;NiEcPDP*R5E8pJvJRf^~>(@<)T3Nw%)Z{sJ`r!_IDIhu> zFDB{9<>Qg5?a8yf*o*)UrJQ~e4Npo5iX!M2 zDwgFSv1rxN%cxPxaJ;7%zmn%b9FKpi%!jt${Dxg%dQhn_sFw7(a2!N!oepB^%p7d$ z$54+SP@x@?#CEqYXwo1)n=SSyWkd}ioBXLuNeT7cz0v1LK5TmNNGqF1r`EiI?Jt-> zZkOt5gJ;WSZOR$Oo4#>q=aa@KQ-`h(+4T%){O-5g)iblhwPsUz*<~}4;CGmVs)nK4 zWeiOAVkuhj8uG?_#W2ElgJM|3be<;ot~jP7 zL2y10gC_1EPj}&c8HBVe-lD&m-F18IaQ2^a-qZ^ zg>QP^D&PHMY(8eO=C{jU#8a%(y-v$rko9dgWgWY_Fx%=eU*^|$c`pQ&JD~_5+c6Vb zaPaxwLV#GcX4+bIGES&wBKINK<`O4rQc~E*`Zgi(!D$Vf^4-_K4scrR|HP6k@e_|H z_016eIT7K_POBm!&JrepBMew~tPq1;2zN3|V!Y%l>C$ujOUQmhAmq*d5-tuA{6!CI zWV7dmVaLZE3nCYYKMBDiDNw$u%T*WFZ8M)-;;uA%}9!+x}C0rfPn%qB0^Mfo5E9Y_S89K4(P)jqMLG5yV zvG!Ta$bYBc4g@z9uXG(@vRQK&Opv;Om7p+s&?uH5g*>(0lojt9H8;|CBVpnlQR?+q z))vI;!URaCrL)n-Mv~rGM=>winMewhL$4V@V?vwj-Ku0$XjHM#wk|5`*`IG-C97Sw47WH8yeMU>%`Y`$Wbsm zJJ^PEe!t*#0K?HpmlD6G%|ZW3&F0rLZJJpgBdcGBF|5aq3qFh}AZ!0EGW|G9Q9iVj z{2Jn6o5D5!)($@NBejw5U&i$`CGF;RAcT!``x2b=GZ60Mr?;7&@ahAoDXOjrq+kFV z`b(hrsFe5j%7Z#03g7vX4D;Y*5Ndv%vGem7v4}3ghun)07F zR<&4ms78wY1#IG;t=-*0em{KF+^BG%rnAfxCndK%QE^!pQ%_{sSB2f=ORx~XSz>I6O?v(1thv89(2Djk9Z+9(a<${DNYg(IrJ$24_A$C~DD#TT7)uS!~ z*!B=h{B!d7s6ElK3+FxZ)dO`95h1pC#FLSv?0|r?jB^Y_FCYJ+naI<5Ck;JD@wtZL zqwJ4OJ4TDely3IgCvu@Q5~@23k@zAv$uh;Hq?jkzsr*uqzvVf>$fQ%Ki* z!!HS6HL)FSNNPJ;58SJsS8U11b6_UbC?t^mpQG-F3%M5B%)e2-(a)stz>dT;zrqCo z2O$`}qXqW8m3qf4q^Kik5$yK@A!PYc565ZMB3vVu{F0#-i6zs~_4SzcmjL^xM*)R< zaTaLN^zdM|Wy#L7EvT0=V-poE5Li1PqIiUkzl;chzaCw&u?N%y1VS|P=lasy@XSym z;Ya^S%sq6kU1-3w$d8=63+;S6Lkv8(Ipjp)UXl94546 zP-;sg|5dPv-u#AyDQ_kXfK8PK?0v|r&(E2&jXDrW3K1arY*=WX_Pubi7;#e^Efyjy zU3FkVJDP%(%KTIjsLC*sN~LKo<84r1pV`-Ga_x(<=m(1#cC%Wy6y{uhG!L4zUwNe~ zK@7WdUz!z9si0TghYGCi^nD(@I+MEu*r>TpNy^J7G1^qsJPPRGE*k|VCgsHuph^7LA+uGekE~*pRf@!LQTaps*wO4 z*&Hh?)S!k-G;{v)@W4ZIu>}0_AfVXl5UStl+U2YI8=(p6TMYUG^>!!Ozl_%i8hV?v zFW6wJc%FAYN~43;{uR@&t^Kc$?{)9A}Bh&J>6kU>?X)x2`;FiyiPw<(%P~7NR ze1@Q)qc57oPv)~pJM!gt=4T4ckqh^X2}d-QK>&-qvTiFpo(of1wo$PZOWsbzLC1rs zft{L<;__Y|5v$_P92m)+IHwpjg5Z;6prXg-qI5(&O}&5QA>WbTT@y{mm%?!XUpO~dT!8m5M)ihB}YlSR9O2nAe0y0Hf zgaKtNHTz-5s)n)DzlLW~Nw(!|p;^=>`V_ZtrIw%fy07>C14s+|S+xDd@Ea$#uL(?% zbMx^p_^_fJaQICjqcPqF%h-09iVPEdJ-BK`|@-Y+H{gdLUQtCmY55pC}kzm8sA z!m{d@y~wF&~4$TkrQka!jO*hG2azeMuD3cz9~RbXAHnhskahh zXyi?N)5r4drj2jHMuNr=R zAiq8>EeCQSaVH}((St6nu_6NL_^M4vBAN=^b9&m=OBm<@lINWiw02DUP5S~N$dd6) zngU}4MGH8;yMV*1LcKLm4+s2!yjnMh-E3oRt~{R6_+KmQn2{T-S`0aJU2ZPr8ouNF zrFPw1Ht_TFaSA4I2NtPLSXV3%o(c1$2G+Dp(KtM9zd=GOsE{hGA@`%`W7qm5_4SE; z6eFLv0M9zEjChp%Z>vNA^;sWq=+xPw#xaoSg$07wR|xEe?#QzgYz;*e5j1TsiQ6Y) z7^JhsQ0)E1y^Bpl@pov%6ZSvdVrsy`d4Dcl>3Nd|7{go8{tLzVecpBdU)@-)|6koq z0 z&wM`^zIR6Jy^EEAHQ(bu$3y0jIaSTOO)b3Y-Hum^95JyVY=Pg_8|w4%hWN{m3_q7lVp z5=>SA)%#&F-0-t;Zu@sY!d^5HYlqy!?^_Ri#n|>*Afo)rrTBObw5H06RQy%!I;S{Z3c3p%(qfn@V~UO<8E!=|5ahNGyw&mc&|I1S?Ecuj99J6nwRW_ztg9blFIJiq%h_`ScgV<=eqpq=f8 zUc@9&06 z`(oE6m&C>KG;H1f3=B<-wiEG#FQdU*ZDy;{l2yUj!<#;)`guvvrN{WC-k9Wh1WAFYGesl z99t9~D*bTdt;#!vI<&*$>Nr_DZ4BQ0EC@=5G!{l#tp|Jcj>LhPNpP}ZmO4bYD`KX<8wYKVySONNJyXu>%1=A13tMczHPw(U&=|2qrVCB*$q9YkJ-*M7Q4xq34K_}56S9nz^N7fJrcIbOaU{wY z=%j>W$ZcVpm6<-!0$Tg!11EXsAu!1I z{OYw+18qj+@M^xm;b|m>AlELp@aw=lHDjM-$a`=R{JPttK7W=+>G#?7-nzv~;=c9k z&WKQ98HFA^Hd?g&v};k5ss841*!3$aHO)~w&8QKo{YM-<6IGm74h0}vD`-KIT^X0d z`XD0bw9{q!T|U;#FG;iYT%PoYUvfy5rW7@HvO`HoI%Oq`y21iczl zak`a1$YgZ8ki%@ChB<7kDC~*5?rF?@aiw%-x?<{E825fIcc_7|B*9vSY?C2#q4N3p z%->5h353VuV^wwT#66xekko*tLJ{}lD*%JRefC{sW8&!54r$r~bF%`|R}PuT`A$Cr zP({D)J9R6L#Zk9W^qtD*9JntLILn42R8de7)$LtO1__DE9?&`tB3!NYMZ%Mh#M0(J zsdsC>xZj7@0t#NEwC#bu9ziZ87`d_7r$v+k^pl4b#w(pEp&v0=} zZSugF*}Ewg{;RNv#HgkNzK4Cw)Hvq6_Z=Q&cM}ZD&9qOfu_=Y91zqqE6W;5fX5pVgK@Ly0Z%i-s9W>yR7GL=)A z+*CioZ@m>dGKn}5;PM6prZqX5T65RvAL3%dv6t{aj`V^fN;{~s+7FV32HFP19z4XA z_eJD=$L$sK)q~1l1pMHiUk_RkoNNURbzmd>dU26LBNH1`5^j2qkY*F%$4B%itE-FZ zEgc|RPaAga8ruCb=LwiIp`#xXxwSQ{Hsa)F!p1)6W=L-EpBF+fGN*QZVn9_*LOnY; zx)-9oZ8Odv2*{2*V{Zbb>cBcHIb>IN#IWP04AGW$)r}mg+#;_ugZps#1CwOT{n5EO zIuRxZ_)=NH_i4XK`$N27aperuUXpU=_aT zg)w8MlG85q(<6T!e8nSgc7~flsMSmpEBngWq7HIVzn;BbeccHt{3(aRTn$IQ-9kU% zu}-JuMP*e6UFa+@Z<^a&hnU|J^bv>2;|x9CG6l07>?f8d9O!i@dh*S8MP2#%^#ke7 zxw%+W68Cf#nj29^$9MCJ6O-(->Y>5HA%AqguOESG^!q^#9(TF`b>tQK$TS|&WHMlu zk{F)H5|nCo&iZMb;`U+Vp1DA%fI?bsFet@dBRr6y_ zY5|9#%Zz8MWJWkojeKZJXfDGWeb3Kty5Owbv0Th%x1}0B&7M+_--e6~_oFW^7hbUt zc5ExAvL2kTTBW4}&wWRZB{JK2m_F;Dk_iKr%p39bStVRX!_7CY?hj;PIf{&N)p>3a z1w(prQO!SxWtCRDrlr)h&6N@;YcP5I7(Ioe*mzR?iE?rYGcGPJ2e6HmtKo}Ft^HA{XHk)bgeZpsVEeYeWAS{A{> zqbrF$GJVZ|4kHZq=7eskzTb31(AaJV?xcpYxfaQ7wOPYtMC?AYbRQbZw-|>?w%rOX zsYvR=J$K>bvo*yzYqxmlx+W6Ru3hil{sT&Vw$P2B`u&#|y2-6kh1!g?=Oh|N{#hZC zypCXvAV%x-t2gKmy+8sIvlUi11^u+#5Ib|o~)Lzq0TcVRzj_Agrs$MKurn5%(g#-2(6|j zh35Q{R=E`2osH?>_S%_s8(H^a-+e}(EVqZ^6Fs8 zf;Yz40UH5d&-a7CRqc6zlx3l;9YRFug_;aB2Lf%ZI@aRP&!MC^!%cE8ntd^Q$K9bI z`*j=QS;68u$I#POc430jDRdiO<;g@Xril2kQNbiC$K$4cfiUFnAMAs@sXSnQ_;k3KS18?Cne6P&iHTM*_n9?B*7g zO{e~bLAu5MwC*J^<_z99XCzi&oh{oXxtuzQR9wc<(TQJ4kKpEQnVT)1RmA8vAd~Kb zRbxiKbOuftfBAXeV7$4BuTe;6A4&~X;^uIEp}JL~zGrCei9QSn1R{Z^S&F)yKV9+~ zX_jZy!XSc`2~*&OBJxyZ40x6_sR5~uFhupD36tb+l-$-bq`XR5MJQxW8?GJ$@+#6K zPqoyWZ`z}L>`Z4)n$;^cVQoPB5Uf&iXCzJ!l&IQNvSg)JvLN7@{$9gEC&0T0K>Uaz zov_dl)9c<5Yag5PJyOwoNUl78E@STcb&x;KLDh5n%cY0- z%TniS?18@&s1K0d{A`H=Zam4ta^O~fF&)0?@)&!(_=*YGH(J@2rJ?>d(lX)7@*6&s zS)xd@F8i!v_hLVCmd?XDrdHU?lPZ;`6Gw~fSe+!K{GRoGm{UBR2dB9Qxhv4XbCL6Jn?+%69+t#-swAN(eP3sv$gn%Jv|^nT4Rg_!|#K zklipIjgK8ti%-{3yd)%(s5Un$F&$P=)y}VBjh=!alrb4)Y%5z<2oG9+hY&A^J7CNu zf8XSHDx^}?y%-@~3iBJ5wJ%9rdxYyS_88Kv9Ny>*6EOom*PhP|3C5Z7yp4FVxQKz1 z&RTFm;sjYo3zabLOm3W6!BrFFQPup)> zl-tDI@|t%@3X2d#H>b0_ft1DJk$Tv7 zF8zeOr0oUDYh3<*>s$0mdC$~l^)4Lu>gq-l$lapyB^% z0c?hNBxe6wdehRloq2+i>0C{)lwNDuGCojZ6JKgS86pZ}BAg`4C8NP{B8AT43*RZd zG?;^<5Ut>o z#FCjse`tQ=$lw!aQujG>m!#|IuK6Ki*JTln>xChrvS5Z+&fFXY26-Tn$)_YBax`d) z)46Eyn(umpYks+m*)AHK^wlFS2iq8>Yl7KS6FvL)#mn$@snVRVPxqx8FPo78~P7x$EeBvB!uhJiO&dQ@AFF z0+h%2+Wtx#ApqUvLA#9T`&*@6zuAgBxaETAS18ItifV!W>NjPR$-Ow1mEW~|A&B>Nz5}x{s?X=@5_~EtN+V&{aqMq~ z!gcKdA4)`%hO4{cF40rN|3zn+_nAgDs6gV>An z^Nu3)pMZ1V@rT?LAISDCOxJDP5D(8YnCvL=&KMfQi|A?X-$5k!um16QELQ2+iW-x( zZ|tUAMaUG_#gS=h!W3PU1HWQy4{N$9JkM>Uii81HB?714$q8sca&mQ}|2~$IC&#Ux zNPX&L$Ipe(_iZOlJ39!YcWa(W49-ApN4SWOj*(J)?^h!0R|t(pl>KAuX(I($*ss&+ zN2}V) z?3Vu2-xm_)#TzAzzkkU(q6V4QSZ#?2aa#h)dPN0@RaiuFy0BCn3@j6XOUkHpeP^F_ zR{b*=NnAtedF|cOW+|ulHY?$Yo0}Lzd{3_lZv6{#|O~%Eh;mXqGm2Bs2QIsGg6$~UMY@{eV6-%{fT#yAHXO!<{fo{?VzGEgrO0&@ z{w)!FUNas#%;?@t;|)@h2~HtHE6{Zm)lGt4>l}r1i_(L`eo)6gB8nYEn&ee8w}J}t zcUqLaI}9m$JA+%T6aX3dq|oo(Na*^nIDg<{^|^cpKYB4Vh1>>dNR{iUzxaou4kF&c zk#q)hua(5g@pJb?Olt|2)^ZH5D*rr=?qur%e0Pf{43cl=s zBh3=zYHf>y1tA@5hl_V%_@cSRr63h`mpaI17M~~5m6`siEP#hi0v_gZV$fJNk#~(# za3q(QB;)lg73bC@C3h}oBH@NZ42CB@%WT~G&AcdjH~xY?8QWgM%4*)-eLvU_w&3$1 zSn5kXe5(%$V`_G(4vnMW6IYl1u4tPHhi`i?lFgr>8#!=DJ-Mqu%v%Bm({eP08=inc zvZvn8-1C~a&taXYaOxOWB4O_VYnbK8NSIJwZ{nfeaX^8HOCj9JOiaNu^u^H(W)Uq9*|94roq_~>(G*a^bFPG+n}q-AFJ~LP8hOO!a(nV&cB}~J?clVrQj>>BzaDDCsIT1{@4)p^DBTxQWFA}RJuC8 zseTk6qqmqEH{VN#%qGeL>DEgDJ581gPS<_wAh`7a z|Exr=%F?s5OU5LOoT>{I*4Nv1mPmK3Lh^uF-tJ0K25LXh7>@&*t7g0B25kKaM8w|o8{TkjYp>AFPgcG1fR3D-<~u%^ zU@NxB0b=m2nMw#%O{dvtw?RiSSv=zxI?_0R7KNs7m&B(GaPM*jtw%V{9IYNb=jLqt zSIvIW{`sJblS%rLz|x%0eKJSl{OuM9ervM?h3IJf+aQcPilXb1k1A77IBt z48LGR$_X{q7&bPIn=t7Kl`PNKZnemwcrTzM%=qcTw*&zKA$4Zol;;VbS^`r=)rWIr zNX)}X+XV#pBpO*QCsxB?EkHqF#Xc!AkHzB0RhK<3v~ZXqT4(`#=?{oy0``(rHXc_) z#ZC_VP9Cr^*=see267k$-a4>HAf@mE=1dVExX>cd{lHQ2!63mCOL%<`t0txWdi1U+ z8oP{eg!K6Jjk(zU)kn@JA}+D$izoq3FX8x~BAjrPY7g|ep0_`UuiGG|WZ~e$p+-Ws zxQ=`tOcHPZG?lvtURN}(Fl(Ia@xE9`{+Mh>9(irXj*xEXSqnapxBrL^1UnX)9aiM0 zaXwyBj$I>GR8-mx@Okg|_~D_4zu>~rC$~sM^5c+bS#_GNQWwO_&8n*L#kJMi_|5-&6Bc70E z;M-PC9MZO#mq3U;Jum207uVay3Vd8ab)f!M<=%$2ckQ=5jD90V7O{j7oD!;n-V;1~5q#NkBT{;UK?Mw=k%TkC|mv9t@y5m+{( zdDwdM!OranhvU5&)4=_`^Zx0%s%$21m`SYCOZ^{$IXC=)Edf4TrtHIjs3tgN7!*y9 z!xX-UdM+z(Rbl&fD940cRux$Z)qIj{sy;j0peBTYu&~{)cZ$r>39FG^PNlU_JcX{% zkLvem;M69#BnlmNr}FY*bKED~N)bqveBRSV=G7L+7Fg@R78RX1cFpq{&JFp5gyx};L&(u1Wqc5C&(k9-K84!5XGPgmaF1n2Tfz0HWfN2H3 z7=_0Q!=7oo(b_6lF$qt_*H=Oo%bmXMZnuM#rbvk$`=gXr}nEZS%3)# z7zm%c#;o$~sABN4T@wQSY6@L(N>VISG;Fn1Rr~22HIZ}u=hc zyk(`G^HQ_t4wjF&7 z2-^Ggl`eh&U{I5HlP}YgosNV6_*+!Gy%B(BhuD8R51V1=hgeU)s&C^?){Su8*RSCc z{#m1;%LF+P8p48Cf`8rRmX1R%gPqRfcZ}rBAl}m#?fH`2*TV`jAs}-I<%q8kNcSa6 ze^4HcgCR9Dz!m!um9jWHN=tNXvTZc*J6=%YnH`s3H!w~B(DI8GBaKNi+9#sr*9c-h z!&p~U+b)5l8YbZ3kD-?w4j2j%f0+|r&09Pr#~^$=H!W-0;)O#h*Xd{yYm4i$voB&+ z7tcsA`7|w&sKEF4QNFp4TOOMrMr5NE71ssJA7rE={`FNmsk?I1>Y1IDqhb|Q-2!9jP1v(pGT13Adp;E$JsbNF8%Y2`^py2 z1EtD%p@_HO4>TfmZy4s;0GvRk(|3$QTH3Lqcs$QX5YpF>UHjwszSD2>ubE*+zE93V zNBL;0WE5`~>|@X3z=(Szy1u?&fKlJ2xUN|dowz*cgV(Ts`Py>jv)E&h=cQ3-SoEoX z{i6Sv3T6s?aRYeUm`E!TaW%~420woaxs(E&w6gHh0#+t5`$1bS$Np(d33m2eRz-E3 zP*^H6JvvYl{f|wsdAE^7>_5h~0}rR)a{2ep^PzLf3jb~4@p~EY`M=yi>c70rS!d6k zowO%=!p`ZT1X#_EWW$TgoTQ927uYnfNkW@xMEHZ)-3e!sbo|vU0$gqY_zz04@swF; zDFx}Kp-V`p%DnE#f%Q4q7O@cy;v{HJNZR0N$Whn?TW zIqx9(DEnKR6Lz#=7Sl3_Q2q$ckJ1{uh?)3M9cCIdC`_U`R^;}aj_Qx$T zt@$1pZ3%BX^7FyPhR}`Mb895)xgH?l{ExfgD7U9TNSlAV5hU-SCL!9OVxEr}z#flU zf`nF_kQKfvevvpj9>lhC5mB^cX7N`T|Aarx>kSr+vK9jOhPM?La;3r>>VPGvMyuod zjpQ312_tH2imVM0$82R_M&J{y4h>b7&OZ3UWH|WOLY__P3th`xtdy*GZ)OR&#g=AQ zTg&t45ttF15*U5KwK%U53N!B4-ZKfv7; zB%iqyj&2B0LLftd9Vy(3ZVbg&&5w5Lm#!^3>t8f8sqIQ2R;X$DLnx3!dsk0;W8dEQ z?nI=GSXgLY z7f}sK=5GWpjI;vAQ0NCj%cDb`^Ly@y5V4S-*N`z;RN{x7LK+D)sPHA(&XWd6x|lA< z$8HGNqRC^r!#SQ0KE|P_nQmz-00-*#{z%X;d?Dz4Y-}(#jA+(`2tfa zeIO+GqFf13#0Fu^p|VM4#uY|UN}b$|2F11aG&KF z3XoN$mmCaOlQc^X@9)CIRgB87kR7av7)TWJN;nqGFau_bgF@L^t-;uMdk_w4$WjJr zU?2lxCj$Y?IysO%RR-BFl<8^zl&GGE$ZrTtA&{Ec5?1!990qd=a+hF=TI-ET#pdU@ zYkm1^24#bfu}7^#1G7mYAl$BjLo|7n*(OCK>g~Zl?o1q1+&DftTQWk8g9VCfM4J?I zbYGKjtnMsCH{C7%wUy$7shut`{(}9o@$&!^`^Bc5$S+H{wc0&RV58XPwc^&j%NbW60E#(i< z`X|8BCudo79romdwkpy`E^{C);&x+WHUH#>2xe_8E>`{zH)j_8MFBt4DY$HBx?|nH zej`Y*m!@M*Od+7?D!}cPAm{*8jGxBuOR367{mUEn5E{EGJDt<@wesQ+W8pjnEF9i) z(DIr0g)KFolM0VuayxpF27%*rCC=}}Gu^@<7W*whlBM3Y{b|RyNV%)zt{153oy|^` z@kkddMxT!_WjP#^3>HHn$tw=ZJ?8tF(oh)EtRax!87>gA@(RIGKE@UiZbb$&f-S-$Q94pDxS@*GXJ;H^SAYN5oiF0 zAy_KJcTMW#{WSl(O)BD0rAP<2;jH1IUl+;RS35Y3ZQP;g*e4V3c&_LK_~7*ze+k2>{Y6y* zWY;}BuIn{~l><>LAy7n3Pt;|Wa&l=za#jo;il?kWfx|t(lETgNZMq|@jTgLjb-^oYU2TBxXL z*^V0sFbqt=v2XNEAiwITts#YlZULdOPU!94%J`0oG{WpL?0G%PqW{*PL%DcE0x+*S z0H8B(Z%&4xm}CB2&#C`e3EPJaqvvdOL=L@&MLq}tqY+r1cD1dnxHZ(&{4hhECL7W2 ziHCcwysEJ{aSO%govIE=%W|T@nQ_`H*-Wwh(-ZVdTt!kTGf56#gov-b3|#%MO?$Nz zI8S`10EAzvgCk4D%W-j;5pU&Ra}qLJfbH-h`f-1HyoP#r1*&OdIFyA; z+>p_mi58=rOIEB+m(@w{72VVXKE(6$)X<)tnA;Pg$+rs#uq_b*?LlAFr_tt;3mixDCl&-&5Iupg$VhW$vu?6Iy^lT$l^- z!R0|!%4u}RWIgv#4kITp!-a4CSxN`e#hH7&rk!`p^(HL^@(YtI+D~N5THiAKZB#)s zfK7XMV%lgeIDD?O!w34_KbAEJ=F?dADR^9SdF46q0;X^S@}zjTW!g3^?I0&l3bs)H z_C*$k(TMXpkmza+o2|8goa?(26myBGGf=P-)gWM_`v07-Dz1p?;qjl-A3$rZQ+(o! zi@Kqq&yLWsZ*O4PesU#vPojO+Zo2TA%v@BEVj6K0`8gCx3XP^IGc4LjdQs8_dGl+~ zasvKf5KmRw=s`K40YMGqn=vhtK=R&4x1r2hv5% zFnBR2Il%NMMn<7(*E8M*)dVeTZC9s4?m^r|z`G+?I9p)~$1>gS_Be=Ei_bd<7zpc% z-R)W#cG&Vz*geksE*UmtYiVqL!VmIKfgtECRr^m+@>*C52ueg2yW+gl@yY7$j|YDH zA1eDw$YRD}@>7SI{PeDe+~qZVGkw`&)JRyMQLhoaoA_2k?jCOt#4~5}M(uBBCHkrU z7TkNi;hYj&V`^CcT3hw%0R?>GLHO64esv*@*EGEx5O<&oZAh`e;}uJu6-cW$Iu%Rb z64WrX$!o#6Ew+XupPEs;l|xdHJ!g#Us>Ki5$o_SFPh@(3fEC|4`CZ#{E&H^e|R)smft?JU(qEp=ns7C_gb{51buYw$&e9R(fBl$LxO$=gVK<1&vlgLJZj zWC^cMt`OThgfJ!EY~Xif4k!6_=jHuSLnb%f$?xOcDu@%6o=(VCP9}qVd!)fyiN~*> z60|sSJt(K*wV&N^eX^4D6(#X}Ft0F>b~oKJDF?B}tj1yCoHwjUsHut+gGiTM-HOrv zFryj%PwQr;aF@E5s!_~l+d{#agrzML#M-;a-rY%Uqw;O~m>4nUVn1swl8sJ4(<_S`2P9|q zy9CXvfs&P@aZVkgidZJ+d38(KmsvGLONPw&wiuUqCSa^-q}$%arc?rFs@`ODngPGG zJKx;zzrjkp)50$7EUF1-US(BP*w;Nh zFa+MMI=@IN%rNxWfQgoML#!Y;qHTEnvlq{?-U|z$oEWaUEoeQT9)!Jx(ZI#NziiYs zAZXcDM(?L+^53$XoC-QOat+BO%@}NK=Za9rqTZ(d#{!IdsMy9l7yOa;R`;$o6!JvT zL?UD{m4t5~ZaV9bFNy9FP=hzVycPH6!!%6<(OlnR91iq-EX37Q-4}^Gu&Jg z@);|`?XCHe^81bQONO2#WJV%?=rS7f44tDad+PY2%)!BBjhN%{^FIS}60$@ck2vxQ z`V#p;5>`rucyTn#@(09agMWXH#$25f(=QbH|j z=Itf}+Da=K4!p?=@1FDAC|s=8>uu`;agNq&_4*g**o~Tpj>G0J5vqU-|Dt5%&i60; zLA*ctijiI8$rAFIp<9LTzb83>=b3v(=9YT~?hYl`lV7Uf;BR}|(%^@}9r+x~dchjN z^j`rWo{1$DWSgse9ktM)^BHcj4M0z#UNvaz12Wq25u~wWLa&-JsZIHDD zrcushGnGV_DWXw3U7X4hYJFUC%j%7E&xgf~mq0X-Wi%;Lh~kJ5^zo=#oDgfJ-J755 z@e80{M$Shixb~aGBqoVsbfFZGfk#y&Oh*zVD>iO6#~Fwxs!^UiCT9buLThOHS8a~- zddmN+HlP2hjme^IoNVF2&5-j^e(F&SFtDh$<|Hg%sX`c^8DmJIzm>VZ&{IwF=mf36iMro zq^HsiME5lE{gHci%x)P57wfBaQj#5+WEMql#fGWG6N&Aq#0`lRF8XLA$A3iNn(60K zv#CTHsh&`g88yfYBG*vtC$@Rycvg%Twa&gM|9ogrpn6W^kJ2(H?;RD6SD{%&ihzot zxTIV?6>?^WFi#c@5${bK6lG>$W0nVI%rIetdKK3T zYh`a`4<3)ak!cKn8jiWICNQ;@!75CUn;;5cGHKINa$3Du^2iT6TsHX)j1UMEzFDrW zIm5CC`b=<+VzO%fe3wuN`bTlr@!KNoE?Q=5717`OSx$XsSIe?}_|9I7*A-PNc|it; zx`~N^Qb2M344sBwT^5^0?YmmkO*P66(fiXs2rV1bpnn%Em}#j0=;(wstu2#`$0XG6I7uxTo9m72k!d{lb^s)ENrgSiHkF{-j<#D!M4)CGGIkN z<|s{0l1Qco>>{h2DmG*2=fDAtP)zh`o!QD%NZie^H$uFx5gNyuR)ugG5$J3mGP|zv zsgI5g+*twHc>#YZl+5F&p%vQ2GoO&5@02{MU^2>B0g{oOV`xL@SKJPb=Jk}nla^EA zB7a1Vg#{!P07QQ=p-^0%1fC0&mVrU3NYaVHbG6XjC!1o&4a^OU#{=A=;zAmetB|;; z#><5*vNR?x>8yZCpSal?{>1g|U5Q06aNNI5W8?woKo}#B+S|Q7W=`$fa-P24S8%z2 z%z2sR8*GkQ4CH)K_093Mr}|pdX`6;7zNlz z(*V(%r4`2JtDK@ibX*s=aSJL$=fMByEe=dhGA{X*C3Z3e{R&azm+gY3;8jo(U)8swzj?S?T zq2pYBrLCQCPWb0u;-%zTC&EPcN^~Qs^;7X{Cn^6TIfS>$76I1myrRO4#-MCmf|)bS zwmZPH%6m9y_XU-1MXWm5+l(kq#(zLQjl86XjqfN@s*`JriwBrfDUt?|J3VL zzdJ!8#zAMdPdys3uD$EoCIfUa0mWEBjFP|1T{t~WCWa|0is>`# zu;{UOl6q~c=cRnJ)&Bw4WYv5%aO=FRv96ta()?UX_>bXpTB%v|5K*irZo(#e`yr(B`ysCQ(Y6+M)G z*i2wVDLC9`W0u=$rRJo9TPhzjn9ap>69qj?E<)gKf?3@iOq!J_QVQsVEu=yjSYT38 zT6$AqN^8`U82|f`F?L&O50tXbRPBf{%*s6Acr#P;goY)iC919HtILHNrgy?TeIbMG z!BR}ifJ1QUve6xi(1Wk#1I8 zXLIkmYL>>_;AEc`y%>?13|GbZu7v#^%>txgpL`vmB1{hqY+HTU6(60Nd?M}f=fybU zI}&g3-kO(V@2iE%RA+cQ<;R3l?Vc1gg_!w?Bk>pcU$ZD%CZ-I{GfDX<_u5e=Iv@35 z>;4+wCJst{8aj+?C)>7AK%9PFU03o_Tec{gH8OMOJBA6EX{_J*cIKx_K&Rss+sD40 z>KM;-!d%QlhH?`Kt1PrO+j-HJXAx0 zeRo7}CNWcRq8X4d!{y=t|1A7WfVcNnTY!1*1g~T$lFgh%n~5`BpvpZeeZZZ<>!g;5ht4w_M8*iK z_F*hzl+lYAr@Y}l5U=h71{O28ee&BlDq2*+{Cyumz>s|c-c)EV&&p!E&XhFJ7+8YD zA|@`ILb()~;O8Btt?kd^ZBK6C92(%wzP_*6nx0`_=vdUx2b37=bFKO_iF$`0pXAb% zd6@yyo_?dwlJzvXCK4ns(Wj8C8ofpnPBwZe`KE5R{$i@2HSKT88@^feAn(;~?fxld z6TX8dj!2NWm?1$%CW?y6VH@_{w#a^UEgVhl7>l}+QKF4y%-oNY;;ZSc9{YzP`=W$6e}lnTr`SeF2cH)-Ma~bAq@k*@?pYpvu1K`UV!BT1Yr0a6e|B;A}USb5lGBv zKj3MD!-JpD#=~^CgKVSO_KoQ*CAIht>SY29N92{uhgK}_yRwfQqg^97bcsk-O>0io z*@YX&l!l5j{A>MAN!!eSf~vHP;2LV*kYH8?i!oOI16<0$C+?SZQdTr=F+ukd<@%noZjl@C28O>`3#!w+1t)C& z{->0RTtYw#X|qTtJ4h$+hKH^dZ+PUIW3MM9usGY_oE?_cBC^usiUXtA80&$gO7zh>{-sfVi?oV`hA5&jV173-| zgW&HjldYc2cN_fp77)lyX-?G0qZ%1*IJ06>u*n4L+I~E07Z7dlTTP z$NpcK8C}rF&-8^6MtI`Ut>3}&6*NE4E3sF6u{o9%_f{*w$puOIw-hpX*0l5ZLpFLF z$^$a$yxa)U>7;FxK~RjnWo5}1dn=Mp3tt*1Gwy|wu+zgN*uW8{>`K6o0C|Mp;VQA5 zV4@^K6mfbq5#OfVqvHkUoyT;8RBw$&XySTv2<40kAW4VCyzxus%`F^`k2l=hN&Zio z-Vejk92pcX1PGV>9srS(SJguT1tsvaGI48}1}ZEM$M35!hJ?1fpB|YM)GAUHXP8p4 z7?1REC*2Muc~FwBVXN{~eozt0qY10_J=Ktvxm#0^&@KT)gqTB9UzV^@fjE4sld3Qc zCR{0_T1#lN3)F{%*eyfEmlI@^^aXBF7w*h0v=v5Is+i8#C}43|r3s)0AVFamXO*uM z$2yIkY|t5KNFmH-rdZNGZW;|_BhI`%9M)yUKl7aew@BZZbGU&wfvPtC z%0|dySRPwo)GT%lmAvd)>s%urA*={tky_EDU|E%2gX%>9l0&&S-)D zbszOiA@^6SZ3zLmI45ClNj!*eDd4<5 zT3H2(qJ>RLdfxB6k1RVdd*n=*9F4^Tnv}(T&MfJTZmgo!c&id+z1J#N0r+>EMQCVT&39TE+>f=1 z8mZ)oBh15k9kHp(>%)ks53$T4$xO5cTa~Bm&Hv=xw3-fL|9#0PO2<5-|FQm4`0qf) zc9;_%=gZfW4Rl2bm5QKCbzh6=n>MFZt(BnlA4rhEYQ*o%D$3GT#B1|O`K4Ub_LjAC zDWDnt@GiwDj{-YwltCBrYPs9Nkwusx5rIbwf3#d|{N|+mbx1p~1D|yl@*5-4y;~Ao zTrlQGdPNX~qK@z{f~!nvy7scHv0tL)GN#d&pWYr@F6m{$BwKWI+huS#j9~>J*k#%I z9O2!vrE!98KWP5qT}Z^82dq9%3Tux#EHpegZwDZgUj9{dIy3&lwxk^1IEOHKC__|x zYqE4C=GW2!egA1uA%~Kt&&Twe9L8B9Z~pY!$4h?acLuz4Vs(b0I@A-_3S6f%^@CLbXayV$|J(@zssWkezW0A;C#5Yd zq2QEQGP=r?&Gh%yd^dj)um_+q1>thD%9yDaL2?uI>AdEvs%f#%B+?<}rG9}pZVxbLIXQAU0a*K#B5(_u*n-xIf3J-gp8*6iRD6b3In6i6A8=nq z)4~PaKxq2qu%1RQZ}KB-=+KZkzTWj#t;G3?V-_1Csx1^0WOH%*GC#O!^*j+VnUu!b zG#vKH0nR#1i9(+q$MzE0m7kZ~9u)s|&-WS4Bxf~-Jl09vn!Ncjpn^V*voCZI@u{U!i#xK_y9Jy*80g&1ktxX$5pmMup*VgUI!G5}&Pe$B((+L(Vh){vuVAC2 zY*yBC-kVW^Ls#ki7nkRnZHi^}EXGBesxGLstMJj0)S`m^VgboVWQNVlX0QPN6|?*E z35qQ=wVH3lkYuGL`u}?*69N-3#(bYu*5Esn-HJkWzFC3l`nCa+zi#_Rd1L!YX&c~P zpc!%!vuu2bj>QH84iH`nIc2*Wr&z@6LtY?CVCKQ(Y7dpi-O1tLgfL?ABx7+Zm=NPs zuT^HsiW>ApQs4sKl{okE@b%8o_#;K(RpD<`19Sgwlb$(Ni9^s%sRuG{A5hZs8#IiR z<9UOF5Dfj3hkLFqP<+1+#}7dwI2{xd4L9>}vGG>_A}^*qzTD_Pm+ltSpyMoJMbl!< zAI8`#Tb@xzRUb=PhaPs!bVa%kHEd=lGFTo=eyDkssnkYv(>zgvd*u{)Hp|Zz7NE4+ z?Jt8}WR3q%YWPNN8{HcO3PqDn2UxSh>Ye=Hw6P1V`iLDE&vWIE2iFlyka+9&4KY0j zEBbt=IC8O?WWwfcvjoa2s_P51QPU|z2Tg08O5*Y5HGV&IWKA5#aV_&l#q=1?512%N z$%+IKnaXrv`0(Uf@4eDzZ0hI9i4bJltNFqcPN;YS8~F(}(I`@WV_Yt6!ojj7vk%TT zTsBE29}r?qO-yM ze6=PpV$EhT(sdg^P{Ja@#_PzVoBwz!UYd=gB`NV8@{+bc2Gw<=lieE({8s2zBGaC; z361+JN1gWJ4*5z?#Ol}yLmyuBio9q$9_$98e#%d#0_!x zP*FDD3vc#)a^5VkNQab!?wBEsHLC;G@40}wfVO*rZe?;HTr;ZJ7@CXLcZw$=ZOxYs z)M?nOUTnujFYEJ=lh`n4jSe-0B?y2c*caQJFnKU%ryC_qUJilM9=ir2|L(c#?p6re z`%b*KG_H~(fAg&Ek8Ng;E)R+6__Y9&)=X;(Fjq zPjR{bRZ#_TLHs2QT?e4So7+&X0VGtkA1Hd_sfRCyuenyqPk6(`-g+j!B-{Jmd~Bmb#7I@feZ^kUHjY zZVt&|>b)h8D1IAElE6LqwB?`h$U+rl$~JVX*GQ?EnTk_K#q@Y%4^LqShYO*|Ig`}NjyQbLkXGQ&q)>#|7w5vFCVg!+KV1spr<*{TVxn351N zSmP_KrcZ=jgqtEb7z<b@R(`Wlovf_=j42wCO@41V+-aG0iR1|`i4M<%;7%U_C?R~V`53ygmo%=f6UTX-qN-t zo3#jB^lP1L3P8&9k?bhz1y-#X)cTydqF$|lfaIzDk$=*a^brN=uAO3h?6HZC@LuYE znEPzCoN`AMgY6@Fvmzyie8uq-;%gHw&f*{m&v=KKz6v1v>`J~pk|4MoF3}5-4j&4^ z!gvl>4CYcJW*vkxal-c4C`;nbn*!Dhc01Zjl;6rIWi~|x?uwrm>t9(KWUTl5)&)b2 zjLM-T-HFQcU0ViK@9d&EO-hs#5rqjMyGWK8*K_-84@~2fOBopwmPYBH5WgehhhZ<) zoMz6>LCse0`+3J1DxUbkSL@fK5XF>CU4yQ%j4ige-NobY*UlO<%O0v!sK57Or(%L= zBB^72%>=3G@wBR=JtQ=o4=8jCcmhB?KJ~Xz0jvNW0}rsD^z=8l?3nb*Z@rnuCMJAm z)Rl_4wFDtLErprE&v%<0ySrAy!I%Wm8EY6=`aZSudr`bW0LCcQZfqq^R*mI~8 zY=uIgvm6yX?PmB2TbN?J(hsE%z-sPW0bB0Q0gxF)+~2*5d~P-sPnTk5^0~xKOK2Da zObl@Qq3_0Xt%?V2VJ0%|P#HubvzFIor~{E2+mKMZ4Y;2u-QPrpZ)CJKJ!1vu-Fk-==47* zL#OdW-I&0-o4`h2zbHO<;{w4C;Gx}4HdcKc=H*CY+c2iPnkA?tmXvb-l6Y{~Wta*E z*JPOWq&Y5cXQl{b0M3Kd5&Vv@GqY9DS#ona+?3x1l)kH(?nR>F+I;eZ4@~s*KM1^g z&minj<%uz5{KH3~dAOJcMw|V5IAnTz?0{(k0uIM5#1;mNii_KfHrw$hcQk<#DE;Mf zvx@*f9v;gakw0J#)j**rCpXqLo>?U&lE+5zP|Mlih&bG=1O7T(YYz9h9^3eD4XS0k zyW)Q}D3yPR2b1Es4-_QHLfRWV((E^Vx10*PKMZt0i3mSV$42$)z=u{tDzc>yB0?VM zAIo#`;US@2gEpJodO6J_-?}>WiSGs{dr=i5M&{SSx{svEP%=}Lga<~X)eNjnLklqo zkm*5bW7JZl9ZQK^!KC5INt{om$@pjube(ejkrpwezC%a17`NXbqxH9>T~(PG$R4B- z<1kdlfnKlybhM*sF^0}NcLDp6&oCBekQKjMp6i`7^w;3!Oz9b9qcy0N)|cw^bVLLW zjO$0I+u~D;1i=t9wO<76m2P0lj-eaB^4aa{@hvUPWzLzbGjPlEcaTeRTEbr6Gc868E{7Gl`*BcqEz$Qe;l$fpFWWY1H>}5f6-^$60xY<55Q9s)Nea-RkNe zITe(+WPTs$WX70e`=KE)WtTlg6wQRHaDOz7Wvdh}B>Myz`qwI`s_@+d0KAZl_eXJi zT}rCTcLlkio^cKr_w2=!yPzNvt(25!J;abSJeR>v&Lliy%y5ZV;a2;g)4&(X7<{z! z^w&C|7P-CWv0TAqvxz)bz7ET8bKYffPEACg`g}1#{rYHF6HD@RDC8x> zsXiVfJK%Q8C7G!2C-BuY)3AaJbP{+|#A;kbXW8@?U25f0QJ7*{%OJWdH1hM(bkw3g zc}(mw3{a*(aUj7;PW6%M+3VQjGXWQtTJrOHx)4Aj^QnjxTn_IwPu(X)+KCe0qV$Y& zS$z6Cp5p!#0MW{GEeO&DdGpvN_CFRN8WTy@J_b3`_Ci8mKV(dEy!T-{tBr(^N=6%_tXfkD;qbb(CRbiry zB5p<6QW5?Tlg06RrdQNw7#qtSopj+dhn<>gI$7t4GpQ^wE~}&_NrH{4ULAIr;!{!iQ^X8$Yh5s)9phiSKXXimaEzfN%Rs_Q9FlfURn%M1MD z4XnwLiTMEbYDt3hQhG@u7HPf4+;-8fdwsqH0890$X_yi&dqKY$(-_^HwxNCwuNlAP z1*~u5adJFV;F9UNpHjg><&y9=uwstIj%&iLbTG-5TtfJrI4y%~P0053YaZ!j3gBp# z#5cct0hu`^K}}|7U$h3<#ARlBCaY<4IlJ<2?3$@B2We@Q@t6o+=2STeKc4GANBwvF* zN1*KXU+2v|Zx8iTd`;;%yUeaVZ7EzND2)6X=}Lmc-QW)Krs|Cg~;_ zoCulIfFwzdSqmrD)Nmk+rt6dkKzSJGW6X8>M;{${a2foF`hhl7fLC2@p^J%M5AF{om`aJ91a!v$}dyVx%#{woDmP zEu0!+HkB8L{q?n+S?0SskH_zyILzN*PSq_<9`W{?T&rrP+cPJ7FtC!eLfuUX?0QBC zlR1nRYfSy}fj)|aALC9C%$T)LT9Tj}T*UX?Id|5Qf`vO@JbuC2e{l$g;ES|1#J$P# zQVJ-RZgK%{LREc?#>5|g-6CjGt`JQlu&|KHcX?GRt13vNOx%mJ^B-_&G&_>eZZIO{ zkrQo8I5;2dhT-=!rbeCuE`HTkJ=irDEGc#yXoR_M&!}7250p~< zF2fNxQi|br_f2lh^szh{hU|t6xNFLP!e64z(voIy+Q0iN$W@KexAw2GjmMv@S>SVt zeY~r3?*Iln+`87uc(1JH4hLyvI(mH5rJ=bHBVYk;J>r3}X93T3sNZ(idZmHqU2{Of zcQ<_3M6ecu*gPjRw3kseSYqJ9{;#I#+&1C4ZK4tsawaT647eF?hQW1}>x}5|T#OkS zFemPd{px_r`-d8-?;Tw|b5;QEtCPtQnW-VDryO2{=Qm>V!_gFy52C3?W2}Kcgrz!_ zKJ`et%++5BJE54wfn+_ETdf;2D9!Clo!gmHi__DE@BADYa)Q(cfTLKuJL!jLU6~wA^@F_Et?pKO!rAZ1M70!Vn0KYuo!CZXr#B zHOHnPsO$Y^_pI%DqXhxTICgD^IuY406@K|fU)Hd^2Gi5EamfQHs_8*H#Yv^NgiW)q z%Pz+Ke5m8`*UyoA#e{7FkGAr-rRS>^Cfw`Cj_dAYj$Y~anB5caxR{`5B?|z(Mz!$Y zC$SHbcBK*i{5_|@wf&%!hz^SXsR`3aUTpi$XQlh*gLk2gSZjdmp!+_#8vAHfO^o36y(Fj@u+8@STXmnOced+0ddWr6v=ZgrowYs&Sk1)HY*V@8b=r_0;7b4?wD5aGl+NRWYATkz+3_pVak5$m2rY_2 ziY)^80WI6PVJ%yk%Z;N=7U0Dgcvt5v$^l(GO3gn>oRH_!SFIFvhoUgAvqrOAD9TR5 zs~dn)6CN;-r@|$1WFpknQt-ykB_?`7O(88rRlABrCykjwv zWb`)c%=DED$gGT&!PV8oyg*Vt**Id8nVCHF{+Qs1IM0~i4A8Y~j69F`EMmseu~}~e zBJ#HDZZDnxMdTs>i^wqpdMGXg6WzjrvCyh$uFiEMtxG!!HG+9SLoWn$BU@bChz6LF zkMxZk$ho!-PJT#;;C;xV-B{BK2~O!(X*J^E@Ea7O_6?GlF(1-MY`Ft5e-tR0)k>HL zL0Dl&m(^4UkXJT;Zbf92KK9-qF8!^qISBG_zxR4;A{0$28vBzaBg%=ZIjk+C zh`N~$t|HYv-uqF1mA@8|)LkMAJJ8rcFD$1>x(CarsA?USC{95yNxdL%MTIv0fdlQR ztwUz-k)Bn3%X;{h(i#3eGjEGH3g@Ci|Ese>_2<|RoaTc zl!wQRFN`K(VcC?-f3{XeNopyzg$4LGK|4GAY@vyXh5AgFe1KYH9KWZ;|7wvSqW=Ir z(gd#%#EO4CFGte+LgWl+)kNR0uUKR8u%g?XLkYRp6!aXQb9FltSbqFM(c&LUq~)5r z?Uj$dHXA$zYTNK)BBY}SgW385!&#!>h%x?1-h%YKfFf;s4q&+_dQ66`*8gNlY$4AN zZyF<(;XOlTm~1nG1b=Fg#=0^xxbK#ixHWs8%dal2aCWt<>Z9B@5`AA}(nt(icu`$k zE?G$?|GDS5-|x8Ag<)j&VxuiQ=Um*3n_6UA^x3JN60W9{>EWIX@~6WUG4igU9Ii&K z@2huREN@PX*a0Slj{oyPMRy#zbeSrAHb-0djel_1w!f6YdvZvJm}U59I;SHfzUK++ zl^}%UE?W{-Y9T+uCKdZ7+p;WlGp%kbqD&gSSPzvC<4fkM!|w=tQ6=C#jiVXX8(LT+ z@Xm%tK=zF9^PsPeYf43cK9+s4g%=Fyblm_|_k5-w98EYKXI0kL%_fi|#{iTf{Jx!l zUtlBWG(ST{+d0|U8>OmcevH4|mM7CU1AlMmYS?Vy4%XimW-ukNp3o_dJl%l`yUUb(J))#_qbRs(+;KUo6F+jRK#j^kVo*aQzf%C{vWp9 zDZb8V>mE+h*mfFQjg7{(8{1AA+s=+{TaDG&jnz158r%9mJ?A~Y@8-MT7yDTgYs@*v z9P1ff3a!fDRq@vI(NFE32zg`;p1bxDy;JBN87iE$`g+iIQ$KFxw#8fzpVNY;?`1Q5 zXSBna^jDhS_2)32L!(_-AzYf^u39sLt~iH$m@oquWEt}r@z{+0w`5-_zo*{OjRqW~ z6he%fY5iQ}$~r;cu$`X>;>XIsZooNSU>+@VPukqpECu(>UtzI7NuFGTeP5C(YtVeA zeO}I%U9Xnt0;$R0Jww~2m=uD;n{b{X@A>ice#jC7aB9UztE=l27X9^VCwxrau*6}@ zN5MKUJmdW#%whIXMZjuryLQX;HGcS)h!J3USxU zVE#*m<%HqTT1mE zb7N4@zvR7_6H)9oi!d*3ZwL`)Jk0I1|aVsvYCaxBLpmki0;pcs=H= zHJvhM92R)Xx;hW3@%wk>Y@I>RwF)hBtBJHJ7+Z`3JMeHZIT{)uiKJX&0E7JaD`&H2 zOj6u~PDNy?OtA+<<>X+*kg< z=?!Z{PtWQ9V>0tU?c4p2$xKZ3kI78$yH6a^C&2Fi`}(}ITt-3gkFE9!!j*hQMEaQ_ z)g|fxlfM@>EDXg%l48QkPIxjQRe)g=o*<`Q$RS+dX0C)mV6ymqHmCeppgHg+JG^uc z&Y|bGraQCFxY;RrX`OM;LR_kCnztbwWd+t!Q`5NRwAVQ?9=VI7`ECE96gqm<9&fI> zCz8g~^<_1t(n-n+x%>AQ;>(?d3luTAyuyF2-&JxY6_uYu-`d9Mq&-0Z*7awH06dfb zvd@>@PELL6Xv$YZSGN)?0X0BbWp_meNlvDl-!fIlz(J|5m1>3S`c6i_N!dw0?l9@! zYAcfpQYZrfc&1wmO9i+KuJCHs2mWO90Z4&(Ae-NzbFw!1O{{|uCZdbF9pS$ zePl(VGUBX{Pf6=y=JZP!ImB0LSZvzmcwX|&L&bh2_b{ENh(Q|^{Cy*o)%u~8u&BQu z+?~DDwG5#(;ltN_T21F2Lbp;|gsO3vgW|fC|6ku9Vq`aZs9abO8><*Z)HME>uJ;v=um z2K9bCKiecn$@&_R#>D-eC5dn};}j(f-H?b6BmYhel@AMss%@ftg`W1r%Db3W?<2xW zWPC}J-=EPq%=C&@zr*YCB?dyoLqWjo>kzKoa|N#>m^i;;X5wK)a*4nTIy2@|=P2U( zbESf!*e*qm`R&@#wfW z>4LDq4X*cC9Z62p&m!^IVQ2Il`!8bB1$8BbCG(pkNpfbe#wsJo);cHYfNr288QHH4 zu!(qvnp%OM1a>^%pL|}iG!d&*?|}4P)}fbUQ!ksw zIQY?hhuo-wpbkA0Pb_1RD#7z5dY2Ge#sHlUm(i@e&`DGJw_q}wE$oM=%y5Vc`d?An zoy2Y>0c+l<;1|GPc0@mf9$#t>D+N8_@Z15|dDk1SL;b@)s&yES!3JY5mnc*l+MlzDk zwyGxNOK@jmo2L+K(seRPK)rP_vu1~qHzE<@OFjwi!$rT%C*ue^F%13xu&d9}1J@mT ziRuzv(h?GcogKE$S?vU7l28MIdsRV%#uaCS0Rq3;wTZxwwXD-<;3oN84wz8_`X;d3 z3MQkvpq+~29VPXkKsV{j+A+zUOt;6U!(ge^tOA)vNa2w1PI`=CG@Wv3`35sRYQGq8>1^p zfR6K9O!J^Elr_aX2KI5~Gd>?DB2OInY~BQlcgSeeRw9v1rJ zuYFs3Yl8Oq5fE!c3@E+_DViM<&3F8Y#*plWJdyoNdT!~kK!h9Fi!b9#>FXmO!1oq6 zO49zB*$Qjv#q3Kf)h+nGSwY2{?}}pHK}CiO=o2gNtvfi3RHjJFe@*A*K?Xwzvqt~BRRQHh+nJxS*L{xD^9?Rf1}=`Xqh(2A-$D5pH9N$04tuNc>`-V1qU#@jzqXh_0(oI%+x<}XqB!Yh zyZ?yYa9kbCcrTS<=moaxn9f5X7tzIpXqwBmAC^$;I#?e#3@$jVVM8PdEXF+^hCphj-128vksq zow)So8uHK9Xy+n0gactn#7bZcXf{g}CTGv=m}$!ce@_wpuQgsRW`f2h2$Xr&S!m2C z{hmAz8^Ypa!dc_82?J+UpJzj6(I#SpmGK1>#Ob29Nk1l-ckF8gmM)c_(f39R=_o@P z;7yE{^`X)di+0p3`hOLdNIgA!SATQ6EN|aW?4eSK>MM>EP%^uSO5w>JJr{zy?|vx+ zg}kwk0hS_U;5cu`Y-$U;1_+$Xf9?^U+jE>zq zD!Uj8EEd}z_++*idntIvF3ykBZp79*I%HB}Kd-aUbLU`cmi!smX;lC6&V7FhS9dA= zD4&HW>WGVq50{j+*ur^o)|$xU-$V9eeUdV?kJ&s<-OtD|23W7s-7O#k4V$Cnjxb11 zz2YRk-+c!fD^Wpdk1db4@WCI0EMK4#ABBAQDf{K%bt9uPM)5TpDXQBO%{25m7~I)g zilqWj4$W~05oaPXj0!>NurTaY!{m`2H}RV{tp+KMr^cNSiN0t{{H2!sOZwYBhGj8D!^?_O{bAm?Q0Ttr zrzfJqXG-VZgZ0(|pBwW9&1K;j{8-)nPLRp292Ai4JZ9i5WrU(|8ha9bV^ z)Di;D^1qQfX}$ry5M1X)BQzJ-Zn@=-Xt!!EX-%BWC_@xu%jU&Jw`q3!3-jBF!h?|` ztIE?W;n9c~Y~%{vUj0%fEIT<7A1>tYMakFB-T5030XKxBBIx0gk4S_v=`1@8T)pays-cg$mzz*yX|kvt!K zVl1xh{K8aHI5;JV=*s@rmLw#}M23};L@Xo{84?3tR8$UM%854?&PR*d8u|fqR=mvi z-7@`=0h>HN)Nfd+im54aC>*fGWLBoaSv3KoV;eX~u_4)MtOqZ^!^003DrCOOdC=wW zI|&?w$a30?A>I8(@PC#D#{p+>j(dge6&rou^>Wzugit$Rtr&YZEV@7qG~+f6{6D6k0a zuY%zLaD@%EALdr=M>%xgX}od%LVJ`Y13uLN-F@RoIw}Czz@YuLQIQ3cp+{qim&))Q z4aZ8?9)Tm$1s3H60d^p>HJPE`i1(FiD@GUsC6T(83XEnOLU=zCY8#fjV($WJGJ^ek zGmgFt3P@YvZ!*21n6R>-JPjo|*=Gi4Mjp-aq0BsLyyVaELda?FZ^|j4Aer+pY_x@i z>sOg8kAnS5kdnFo@u8FpF&nhNXJ0k5$U%hCY!iBuQc0P?V@q_}J_%NasTXHzR1iu= z`ruJ1`7b>($1UH7ovON?pi6E*tT&WN;EctGDS7UJHa9~Jh}!pYSj)a^O$mdCja)Q< z2PaUpE??*CqD+b}mEWqk5{7s!J7)~XZFxP`ga;FI7%-baYHH1u;gkJigtj<1}-Tp6y|eL4&HX8fCIO4=gD zAo4iC``ZpcCOl{l$rJ(##1fl*S=l zCIyQtX&?1_5|YyS0e&|bCuOsmrhC|V=ShPi1l8ZV0nL}1vp9SvEH|f^{@Kp_zVyA# zH}v7MuOdw`V6XUSWuGngz~rvJT0bnfuFHr~-p1V2Dk}~D2K0u@cgO#`Y(li-s!T+& zyGp{4gl)98wsxi2N>wwbFjtd0CIFft=d$#O^urv;L$eME82EuJHT3mD<9IM#Fomf0 zf7Np%PL~Y^GMTGGJgkiWeW5bDOL0ESE{NgrF^QW3iCff31k=iQAij->9WR*dbdd+3 z-LM;}#jeImH<>t2r*o%hsX(dN%FP^Xn)F%{K@!K1yQa|(!aVdV)AN*p=ek;z|WhkQ{{Cn>s!0cjE z!*`4s9Rl0!ThW1YdpMSQJi?YWf4KP8U4~#&py(7Q@z@FC!RDe-@8w<$V`qk0e@bQg zF57t)0$jB}THgm1fB(F$=^URhyu20WmPgxQ^c>a0h^{fH{pu%Cz-o<|Qn#&2O=^5< z$bBC#QIW)KZFXg#|5e0?a-0^=cC`tnwAwW0nofl(Cgt8Gif7GgC zrA7AYo3)9iu@*D6+{wrm!IV}vDF$C9gwn|l%mv%DQV%oo>HH)=Dj^}7iYpjpxJv!U z%|$|5LUF_s6$HNGcfLX0?@U2qx8kK14$17?g-iY7XcuM5uG`L2-*~PZczuDq-Ae*7 zBlOXAt%{aU_D%clL;~U7ORe*~vK7-8H7M5A>`E)QT5(Cjv#F$; zk4PL1Uk)0A>isZF>yLKsC$qAZ6egeRMbbX1C*+O*wfWMRZM4#OEGi*QlBo3CyTcx1 z!FER1eu5sR>FF9pl#SG6Tx=b0wGAvFfnj=S1(iDpYmhCDtZ053dqplNfTb|na{0|I zzKgRrGQ2BN3CEScT~;Ea-vPstFy15I>5~Rz#jZe0bWlBZq3{T;|;p**I)fQ9e2Sl_%wwgtK7$ zyspZ>t{ZBgPUYp|jevvk{ajoYyk13$>a5bj8,HKpOdD+}e4{BetTwg22H^ zr_92j0#-ad$sX_dw&h7k^l8ZOvR{tM%FEQs5Bk9ASIV2lF}T?4XUO3Vk#*%lKF%B* zi3N2tc%yurKbNST$jShsy*-1(;v9IyFX&3-pXrQH1R+O8rLq|Rwx9jlki@dvOzk4K>Es7b+YeyayVR>K0Wfcz>+ zL$>Zz&|^mA{-NbUxw4*hN4!eU>#9Ybdhv5DXDgFi(XDA5;1~?gNV6H_06ED5c&6C) z6lm#ZUu$sdv$>#M44sNTzCBc>A*3-&BAW@(!@*{n#(vACF$|T62Y2gHJpCURAQ=*g z9=bh-)@0XxvN%A(bCk_kEu(arra?W12r+M~<0hKsBlFv_EcQAk}uQ zw~}s9Yoov_7yRF3W0i#!Tt1Tjh+=I<6Le#HsX%DU49jFlkNNB&x#fENSXqMzN>Nqd zDGA=-5FjK9#2^l=wT90SKM)$L)Ez!d9K`}!5Wg}2kRof*@y)Ax3izZbKcVad*kn{x zUGK9NsRM|Qw%9(=?7cVhsh}-!oPxj%Oz_X127VR4&-`m5jf!sqz+t=o;Cs{;%d(Qu zLSj(bEEo1n%0zr{I8uncDy8c4G_qHPZA(m78J3C_C;Hc{zP!+Hqq&a&qM~HxsTCjZ zT$S^4ei&*z3H%r03NoXyT$Ow9Juk@Gx9Mo%-UOrV(I)MH%%_4>*PS?!znvjF=(O5z zrunV_x;EXXQOhWE08{>2{m(Z5ERZgAa3qb}m+cTSLyjl%hYjcG4h>n8!P71}`u5y9 zsOg+44+?id_SoMF$fMWHsJ(s;^cWKD3XbX2&#?qx+?^!eqeu0`ghiNLjhntWo(wz~ zyIxg2&VO}gT!<&#P%(yiD?Mt~ zH6qkukm@1tf>hO#ck`sohfN(|TA!U`W(;D<;K3O5vjY~`&CRq#sHShxk|{pBxFZru z#EE9CBGI~&mKPc0!bFXWh9}4b?5KhYpYaEJLgJhJWSRV;>O_rlF!UiF8U#W7C}l79Bj6P}13IR;FfLjDV@f81?Z4~F(Y&McLa zK@QRGAC;pEKx!p7o1N#}&PW;^dwLGxJXv2oI}r*j@lX zogzNE(T)RWz$}V%GRz1EH?DiV`>pin0y(23BFCyE}P@=M00KmZ^%*xB)HxBzOa} zS797o_jxff@iwEX0vu$_brTCc8cB&KQ*-rWEs*))am?2inAwpU^lp4MW%2wb!%g$S z^D346(Hy)INy&JsHvDzu@4^NulKFdL`Bi}_cI!Wkxbx)6G^?A6hz@;AC9e4v7a-OE33e%}~5-4^@9A9!2kT1p8-Wb47z{}L?; zI@S_>X)~TK>Hd=68}A&mg{K+dsqL%GV;ZzrKD&rjYK`zZg^lPwE(%sdJ_W~jc_qmn zs@s4PtF~8oi!+?#2QMOBIO80@uZ~!5Pa!;3)S>0X1C*C|9ILB;9YzN^G!gsqdy-}T zC|`Lyf4S)7-;eDDn+}FyJNY>oor4Fk8!ugLg%Od9*eO3v9KJPnPI0QKGC@heRTy6drI~v^^VDAMdA5-h`^26mhe&|%aWkWt zQBv^D*y-iy&~^18C^tPWKx`X3HN;P5u}7A<8*}$|b9G&OfA#HlUXiY9cWkBsKva5^ zK&Qerg>SXxu%KUNxu=)f%zdKbl#(wFGzHuHsQWn64FxSp?U7beWdG)Ts@H(Q!?(Nm z)8JL6tBa7u%D4>(z#m?!OuOWzeRlUymc?EgPn+HKK5w*P65d8C25fRjZd#qks7p1n zUyTAwtQ6kg$Y&2{VU$AW`>RSA-|$9gWS|+kvIx^)FF(iP>*>vBw4Z&WS<8V-?vY z8yCX;wF?8qEgmpjRv+LdeXG^)##b$s>t~zc50*^-y7cct{f9Ga-6cCWeE^*4^>AA} zBef|e!p)Ir$yB0{s3=f^{RauIGx2We+vxh|vdPbO^8E7r0z_CwdOEd3kT?7DXwK_) zVC-rp+aPCbCJ+PJm6V;(me8al@3i&k3k6AvQ{Qz5vE;FRPb;*$Ffn2q?|5ef0EQ1hbQA8 zx42>K2PA0}llFT*h$vl49W24)2LJUb$$6-p^||EMd0<%2(GGY?{ zQ#Al87P60snLI93`UM`NM9FN+fIaCY|Jl>$JKw`^z@EP!E|`hCL-P%vZ;$pJ*y%n= zj@3TS$_@tay8&H(%y|?_V1kxn^LmwOYDg&UjPtZbQhC;fj92)c`!a+xTB;c79P6-Z z*+ugwI!^7?IiIcTV+dy;)I1t~|JNtdJOsoc4y)N>IeAvDX-J7$7M9CQF-+F&f!jNC6>gnl8DnCCQ_~;GNe}Ns|`TOZldB4nIrv;JqV01c< zXJ|H-lh1?seV^2kkt99^owlL5pbVFT#JJFVppH|Vg(@Bv4i2tXDdnH&!r_DIq26qV znV~M{CTi5g7&+cRNf#K8q|VNc9x!~1rJvD=jr1u4h^H`!uFjh4@^^o~*^T!Q>;T`>A~r7o~}6l?W{ zZB=+>NB4c!Jt2C;D1_Cf_W4<&*qwVIMvpBm+fNKWek$;8$nuNSBkMA0c7s%b>qV;X#ZNM-IkSkyO36%&6KCZT1K>ZbA zto0N}^!gpUtMdAbV}KAoglMALLD=y&O&be28Fb8jPY(qs{g;*+Sefn;=&*#`ZB}tq zflW4^TV;rBm*#8N=`W%53>*}P zQ$D4Tj((G!K2J}O1KIYFRQ{ZnE@V>^IidRynZ*ovG4r=*YjZRFsw(xTti&4>feTy8 zPF|@EF|4=slH!L4JqGJm;)+X7)P_rX zx(JO5YSTU4iDL+HB2(Vy8)hn)txrb53Nnh5li^r4>jkh`l#$cdis1hY^V)7Cgiy|D z%0xoYp+SP%e=0OG_K&@_fvcXDFw+O0>v>1kjyx)-a75kpx6CIuk8Gznh-@MZu3xc2 zAJ>HiNkyhr$A%v0yPHAbMySO^un#o-KwU4XbJ$ZinCnsyBHH1a2@USeW9?3!j8;`Z zclKKiu0~onjEt8Q@HGhPj!pN}a1gsqkI2Mle$CO%&@y)|mCq_=WyFAs`*%>MXfy?X z#VEl$Fu0KT+Y)D2*S<|QZ;EYh{0v2K0&jQyS6YtzD=mpGyhgH{py`QjdR(KF?aHV7 zMkY-ObsmWrUhWH`#O|c`M7|uZ^-tn@(A`x9v-@DyCAMU_?0nw|h3$IxN|%Set(G0h zn2vO`sTNz^!R>*QnNa8s&9JwU68Zo;78;jD#OTA8@o~y%jgnhPz(26UK&nQL*MI z&BL&7`-6FVOba{~@}kp1r=4OGnkams5Eo%#hZdI3_NA5u9BNGa@$pPvt0~BNpb&Sd zx~`mtnF3ej(&@}{fBh*xXs&9=W+^}UGhGoG;^W7C?WdkfGVeS!6_OAok-tR6ktBr? z>{v<*E%a4PwR)~@ck#6yOD*&rwcUmndT0!WpNbzo9|@2qLqfnEecT{*U7}yl>9+%l z*HiC}pe}EV=_m6)Jx}LW{=^%qye+a{?sSw!(Y=fqw30#WCQ6+jFJ&EViz(BMde7rJ zv}=vZJ-%<68P8S6CFgb#X?VQFv9t670=f!32MR^!1eG(QnT&{c)=HEFso29!kVDw{ z37=6t9(Tgc=8C0RRZO~qW)~ZPH^1g2HYEJt?lh-a&>YzzC>Y{${nlv|8;!FnUN1H6CD zad5fgemz#R|9tWy6ju;cmwOgMuxkzbXEV zjYAtq9)pQnCG~+*Yf>?g&hYInWl33^c~2l_vE8PzShlb$*QKy{q$MF}qf=f^=7&a| zV1cUbkrt}cY9k`~&EMGv8Dcm2V0%yV1u~*4Ee`02q^zqec7@56^F<5T{@HOU~ncKN`#I*)s4qWSu*5 zOj-TxJkNPni(n$36QTa#W2Q}x(j*`-c{HjFskSnt%m_W_$$gl)g_;!Pb(M2Jxrrth zqiB3@*)P>mGz+#>Lr3ehiOw$6AlD?7#q`PMv`gZD+)e_d-u&~xdvx^Xg>_JWPk3PG z^^eCv#0b}euuQpZYmO!x%FtAYB_JdENFk-P+R&@T0!)WwZi)DRRQdHE9U`WJvVS&0 z5o6(){+6*trJqvZRiLOyOhy!tEL>}5W70f2=1i%r@P|_0L%~TSL^qW?jMzkca$%1I)$(*(-a%;+$Hv)J8 zZ0l|NrDWR1w<)gJ6iVHTz=>6VVEQ3pY4%vTw()(7QT5iZSW+V8C1Ox4QWD?PH!BlJ zfV0Y(t5q$e;+CtKaF!#T7n$rsRA-IQGew!c4cLv5A~8dTDkfp94Fzu{KG-$F!)fqLs)Kc(FYy zbknS~Ht>5Y;lH_G56WajYL4mu(4+zygZ zWc0pKh2sCsEy`$*T0E-~L!d7tO~M%!Cy;;0${#f9LeD;KZg)8xw~H5II=iJFR{yH6 zH+^3P1=XVWMSnI|ApE%OuNE%Gbv~sf+Jwf(bD9{3tw*^>$>#Scb9e#)Qz^Hw`)B;Y zratilU{u3?#USPO$|VmoB>{OF*0<7N0>uo?)V2-rwXb7?AonZLof*s=R`2yVy*p0Y zH5&K?8i`SZ4?H0y*jQ9i={m0&JsF)8((@?!@_1K@&W7J$=$z>SjcSA7$-@?5eOGT4^az7nZEqi{{pN$}{wR z-C>?VO@pr++Mc#gD8&mYL^x{O{hE#0>*H19R{$Nf4+2puya=06uNI3|cZmc+LEqD# z*sT^6KwTL0EtSDjZcL{1wWBp-(7-Jzq@o4FRNU`XSHd+O1pbzJtWKG^D*NCJBN*6w>J!?YkGXG=Dmy zjD~vmBn8sGw9v^Y51Cjcj!)SCsy49W8>2S*M4`G%=`)ZwXR=1v?sRL}YpkVx7-P|Z z=!Hy32CG{+L&#soX`{RzcDy_G?|i3FNsKD+^t(F#z$R2L5VCD5%R^R@(fy?=+eXUh z;838No(B1LD<<(W>PU(CbcwwRD%(rxlM2LJ8A`Zd8Hw#kLADQ&Ise?6PUx|?Pi)$K zJ|-<=EP1(|1vZsd-*|Ni#2CFC^k2}6dEe-9v~Eq(k~7Vcltw2lXZ zlRazL%Size&rhsf7syIcwJ(2bPko(Rhs&irLiVjos|a6u0mfZOUyn+ z{#{VN=dz-nYphvNwSlcBs;|X7Tc@^5WdOY>R(15qcv3nnGw4@wuxa%yX{_{GCN9L% zB$rAjqA!&On_`K{?n?(#bSRTY&VzYjmWu`Wz7HdzC+3k;-h3o%*l@}YcTuvcMD}%m zytmG<-2M<9Zt{pGxp;sMgqSMSEMA&{-QZGQ+2gd`^8e_LA>>iXUHnOTw!+11Qc_rF?>lLRD5Tm+KA({$5fndsg_yY^m=C zzgb44vZ!;DX&4nEXA*KfE*2_4RoX$wG?C+5KNe9d3cGx0mtLk93KOKLZAXSZu=%E= z*i19oEaJwh7k}7&J6f*u%6Nu|og}G=Z`R8rw`umnAV4F5=n)MF8Tzi(SSAWYha=@9 zVqhjJ7Gh>f4x@#oqfJ4FA1SoB!O&+)S+yjpIb9oKcK$;`mkp+xsm7aV=3*_qp(u8w zD?W#A$_;j@o>IHCC3`&O+;0F6E{Wd$jFpMC~5SMhb#(>szKo45-I{>A0_8h#-#mWmOuDy z(Tv}Ih|bO3Ph8=P-T(uWB@IZ~^MQ5KwpzQ54)t1<#s~(fns2Q?#ITX^GhtUktNW&G z0H{mFG_$8t1PL*{B%8S$%vIB8tu;g7Mu5WRPlWLx{M!x$Cj-<6g z!WFz(sX9Y$ zQH%XQb^ww}^al&_9h#Jeh;P_ic^;P-l<}0#L%6G5r@njj29-mM0Zp&sIvEQ-J$i|D zTZbO2Nao!cDUXvhs00cZLH4J(yM@$JhdkA{mAHqkG>behIcP*&T^l4#t3M4k7u}j( z27Y0#1U}W(3a3W2AE9E&emGOvO}t(sp%F!UTp6oPfH+NElf@Pzlf8DH=EUx0cH(*s z3V2JI=FreCVUF9Gl_gsyj!qdUg4A7>GF``E_b;~UGP0dsLRISA5Hgt0Of~J>OhdR5 zPPJY3i~3ur<@Dh$2D0d*Exwv_65cz4`2zpmmz%B=ULA5c29KQB|Ft0opF>99@5yXp zL2eNTeZ(?MsM=t#qS~N$^YtD0-mK(t0d@|ae`zT2Yd{F)7w+&~8VaDg^^@mN7IzM#N}b%{fK?i9o&L?F+1S^qfZ@rrLGHu1`*bzK zuKA=QJf@W$BfZtGy2oxxB`CSxI@MKrGO1Mi#Pn(*g>`S4qmkMqFBuajtAj~ey21IU zx`phLc&m)EM{)9gc}yqULEnSWs0DrkFD1ZglwOv}s1lW5Y}3Aq1m1w3Iq-sc)IE#-UMN75cCeK~ma2F7OlKkht3A3!oQE zi(}x^u&gwt-gp(F(FF5#e5Fti0!HO2h3Y*V;5J{b@C8Kh=Q&E;{-3VqZ&;;Bb zh5)8!Sla$vT?DFzJeh>jvNyoMiijV2*o|h+oV%LUVJn$kwUEWQb3)Oiml%d29z}km z{Uwrs#nDDj1i)VXqI?B?=Yiqa#&`dZBww$3T8Tw36h;vgE;#BO)8l#)v_5b*m(^n0 z0RP!wK3y4+n(@N;-T!d`>^8f!hpnla0XE8SEw$|jl*XWYfORk?j-!WZO{bcNDhkFC zs)PW?sKN#(cs)vf&CK{b4nWp`J0K@(3BmM}fse`5PbP;tKL?i!=cI8QT<~QsRt5GP z#mw>&KRPsb*pS#$iqgwDs4tUaut4$Y3LswNL(njS9Ov z4j4uWEbgm3XtWKbZI_!f&Vkhk<3l1qtEY$PtvYat&=Ki$J2C&=qjUV(9Kd~jg8wcP z3#L;BxUr}lixKF?r|5FwmXGO2&#)#hYk5NQ(axBaK(`-Q%Cvt{Dx zYSRcL^&U(r)+et2r?X|G>ouFYj2KY`o7(VjRb&~3 zEQ4bkf5_|~Fgc}lZ<_fIlp(TOS)6u0>$KiCv=AC+UqM)T3MQ7W*sz5V#pX4hvTq0iw)*SHh=)Wg0k@38kozT~fA!Pn&(_8-`2<81}5~sxA z16P}o_S(E3Y%H#lna6r(wX}f+CY2%4uN!~tZuu5uuSbyKl*Txbz(sO1$q4MEUEt?= zlyOvj)=?P9ct!_TgyptF;gvV2^&vClf~;N(rl5EK28TU?K~o69A(Z}6P>g90(iW;q zwwmX(vK6zhxTpEaZK-5)#C3}+ZS(7^IVDQs&%t4pa;u=N=LrL!xVad-qy;;()YDiS zhF+ZSiKjgSCB@}Z?v`E$dZS?}P3xm|_GdXV3yzu>pF4v^5|x z5WaMO09(oVW#XLSv6|;N3RXj_?J5PZtKsjQ-zIin>Y5lLTbIC%q$|*7pJV%(O99z3 z-}B8&83a;Up48S^dlzLr>CIbi9#LRmvRD+I(8vn=i3*N@=D7CRHM0ksi4j>Il1{9z zQb4NlCzKT`EW2`l`mzn(>=23o&5-zz8N8s3Sjd93Lh5BYZiSFz{@@P>X17J>z~I1 z!Qmfn>vqn$D4*Wn3bKTrn~w_)Q1n))(O@P1>sAh5YNf{s*I>0;V5Bufy!F&&`RF6y zAqn2LK4gx+Z%HSX0>YM{0N&5#7U)Ib?pHdOEVV8ck!o`RWQip3JXM+#jQBoVGm8DE z4@~+DM?}0*>2YbTZdI6v`%-`Q$D9pUSy$_X!ivhXS!8kxo2Oyt@b`Lwn{;d_7+M|S zM5$x6GF*ekNJ=jv0C=b8KMv%u1bsmX@h<$IL)wjBMJyDoA)^cUo5^Bg+JJ2w6A_yt zahOZ*B;cK?*59Bb3B{oqb$`KCyt7>@-}rrvUDe-gj=t`(25gUucUn>>iPYi6eeCrB zhs|$iIwv!fVP>$7!jke7vgLANJ`+08+AVS+D5C9;))cn;Nhl8VZ1szT8sODEiMidV zf!mUOR^Gp?o}oYBOP~wF0@S?|Oeq&MRFG~PK;^=d;lw=>&Mr-68Q4CEotGDLt_w7@ z8WYk+8mXpl_gRCd8>BT&8U)K#DK5)0>q{F4{?@Tqn(LW~Ob))+&69aQMCN{&XB^*A zKJQuENgyXmn0zpz8z{nmKTGzls50vX)d0o7+gV}sD`l$POUrSA**9StTr}7(5DM$T z3iDij6OjXGfplo~)+nHAH6D%v&%i}7sPfWM!CLV>8Pnq+xeSf6*1?=QQ%VE+0spH| zv8gBRY5tzt+l#b9&D7EAjBk`ey;Zv3H>Uh@5<;VMK_#-B;~{Vrjh;6>a}7GJ4iuki zg*2B?dStE#iYQ5aV{QF*#83YY_My6}LELYJG#>F73h5vh6It``V zRA}Xh{|&rP%Oyk+@P^EEUQ=4~8Z{HCTzc+}bCcV2fO2)AyT$0w8a4ueQn8v+}1 z%d<5Bna^=a^9lqz%Xr^{v*t6^Q5eg1HZ%$kB|^#uP-mz_0`LK7x9g(_O<)QO1~ zl~WXQ*fpcctwO4@;xDSj4a2n|%Qf`Ms?_7^Q_He>3Qo|8cx*o`*S6_P^g8eT#4QhG zkRF+JRCF%Uf~xsJX~aFtH3N2+K%E}-6L##_x)bzOhNo^g=JSj7(f!~3qJ9#! z_b-e8Cle4hQk{vZf$>-`ewZBjz{%QEsW2K}h|iTuA+JbSpxwL6>z?dbQ$eQu+~n7?Uwn~F zwDnDIyn?pD>7jIK7anU#o5lumP`rlzm|ikmh42s z67FFq7u8pym+3#>prUkAu&y+n$)SJ3uLHH3MJHQoe4(ZJh1q{s5@`;{N8etd%jaw= zYM_zgDa}EFZQlEjnHl*j)0U zONM2Ae17UW#r;eC=JCv*Z0fNWd)2auo}Q;BfKdO06G+cNt7MnO&(Fb=3ObLSnR}AkGepNc& zpO>6mnuYhVYfeB_wfZEq;RXXl9ItRX6xRnhZ^Vjw4&63uz3M16nd4(8k;3I<+sy)h zV|z&Gqp=x5p$Is1i4kdjZ<#dUv>>bbx!VBW5Gli&!6EVS{I9g21XM;gi_(cyMwmDq z5$e2b2E7i7@z*ClvoVl>r0-^tb7H z(wm|Qz4tDipfu?qU3v!r0R=<>>4aivp-2a*DjkuIbVWg$)bEPi&-c9Vz4!jT`N44{ znQLa&nl*FHtaYw)T)rghWd$B=vbnWi_;!4&9fFY;&_k|9(XUovmkOu1qBtBV&^W6m%x(?(t; z!Mi&$tZxncpJ)rd=Gu8CyI^A6Q0`L%?{kvg`2G>&sCxfSVX@({EXVJui?Jqsu0Ovb z$UwYrnDKtEFInUN;lZJR_+l29_oFWmoI(}3z(1*JU+T1sS@sWSLGdslavJXQ$p%hT zi)m}3;2#T#s(DkhNDBH+o#}7s?WCFdx4-kXWcy~^8kZc14eJh$*Eh@!u6HdupJ+%R zII%i@dd0;hG4$NI`p3;5UnPYaFPmJe6R!d)hAoAlCkiQkt;NA`sFH{e6q7;*Bn-}wA6LHn{Y<`p+~`C zSPlK>?)@v3y9qnlo15+eLQMI`v^m0qjXD`&h~98~I7u{zX&JUj>%@Hsm`FG5=zjGd zi)^3aR4tT+k%0P(>HC&9iC#QXn_qa(x%<+NW^$FLu8MV`sEwcO790iBQyAZx1d;>i3=_@3R-!AmE4?h*o zqK(~1NhORD3Mj(z;FuRLW3UCnerv4Pb67Zzp=aJeRUuy^3#A$H-Aj#tC|1qW6G;rD zP4pl&a6%2GPBrbJDuB{QaNvelgoa2x33SaY>}M1v3sslYH4xT>nZ|5r--^0d`>UFrU4Ph~UXV9uY)-5Xl%$%x)9z7E@qh`3U$az*u!=kLF? zt1GCcp5GJI%&cc&_etL2OFi6HEyQbF%`lp{lpS+9WcB**r=R4`lhTm;hsB%y_d-MZkT>B!(>x(`1i_vZDKfShx#O^^QH?OC# zASx~Qz1HsgV=3v2gY|$K+9b(y{aR_k=dywO!=B|2B-JkeeA;zVz29e|Rjl!aSNr~Z zh0L8HF=IyA=C^ZCtXRve?wd^^2h#9aOsrL&Rj^52b>g3?G`f-?t}a3T=X<@|vhEz5 zZXc2l<@KUdZ$8yyBAW_$5FpxK&oW^nnTC{d>H1OVT0=o&eSA3mX6MrbyuJh3D9R^W z4vwA!oW;Hb5E!s!SJBwD+**`Uz4Y0!$n3ZnRc0Ni{dCW{k92(cajEU%!O=U)%n6fy zNe8vnrr(@_ogki3bf%RUXYn{gyU8nw)ro1>>ovPN0m*Tz*qLGxyN@?q!e`sJX3P8=05qDsrtMjUF%Ajl_W#=t<1~CTGam9yAQOy`KD&4 ze<~Y&jYY;DFo?$sKRsJX@bMf~Y)=ol=j~9NlAizQ({12tnD1t8RBr2yDEQB|GuP*& z{)G=JB_dp(>e^*FUY05Nmfm*hDFIAzveSnaC!m(SCUnOg$c8|$a;0_3LJtkyqX zhs>UzVWKN*fO9IM!dTtJ^7XlJaC7!iee?T>?DjSjCNP^JC&-fRKW5|kYYET)WO;S1 zZah23)6}i4N$s_tZQK-G8bP6=5}VfYbC+}4YH@PHJnOEhbGR(3Mk8Q_(e19%X(oia_o{HaJK^=vYME{siuvF)bHOxe@<5GQC^Qsr;B=e z9GbqPNXO6~$e_zV0RVk#EYVA6dUH?JJJMT)#ZDey4Ek_~5C5dF@todjukWk-J|R5C zTpu83h<68X##q5fDT%>8Ui$Wf295d4%QD4#Umf1(2Jc&qToUjN07U6Uin2S7bGlYd zSC?m)fYoP{VuT%Y6X56MM3^L0v*m^@yKC+z#}2$Jlr$9X}U*~_PxXm0u}`v zKDT$+t|}WBL=-s7ZRB}IHNR@8!Xn@i9Csy*MDCqwkZwm`{yLm4$`5fh?3Um9z@x8V zC&*dusP8Bggcf5Gmb3j@|NJ6>Ziv>0YRI%{tW{T44w)2@Es2kh->G027rICeI06oo ztcnGXzKZaVd(@=TFf9Of|H!d?@n=n1#|7hU?m%Z0YisD;%ac_Se=O6^dSeS8L;7I2 zHHL1RetCc7)A)9f$PJUIC7MLo|ojE2=v(QF>gp3vEA?z!@4X{6#ks-*fPt(?)kx4|%Y*)a-+@ z47MS2o#j{zIji(vk}C7}a(AcHn#h2h5M7%Pr|I4_FaK9Jp;Q_ZU9I~U-txqsVG6E# z(_TH#T8n%0_CS;h4=+v+qmiM0-rr~5C3fw)T33--8+O*85clBTk5%?CHL@1(G^u%& z*IB;miGvdt#)(IprOe{5Fx&8WXFLuVN1j*Thp9mMFau&!(>wAF4KBB{bXE0CC9E-Fn}% z1q+LWb!y_jc~RXR?(A{jsVFa5&BmsQ^uVj9Wr<;K=k?KyxK`;PxdsB))mlD=lm_i4 z?ljSFqQA7a_w4C;x1V}XZ!fUNn-?GGQj<4=v6wZwT5y^+Y0po?VO4FXPX3$uF^PxZ z5k;e4KS$pxzhL8Q2b>Lw%y*{H2}$&#eXUqgQMj25RuXA6Rs{oXyb4f*SipE4f3kqU;rrZul@eBo=+8^_?4vg}X=X?n_DsY(o#q+H!1ifW zpH_+*D@T+RR;s^vvha$l{i+$RHqn~UD8#{+sYQd&1xl9h$mtFg3SUcV6GWj91MKzT z9{@7BI5qZoL>cXo;;b#54Yn>^ZN=`{V+YWtan*3zcnqrr@Mx6amMeE63$WCc5Nr_m?8b23!4q*GYVQW;P*e=IQ0N2E=4Cx3U#V zni2NXRTj4%asp?9i&c`v}~uLBUa%QeZFLP>c?dpDLSHLN<3_0r+weVbL}h z0F0#YJeWBO#!W%Pef)iQO(f4InnNWSQLT}2yqJBvwzyI%g!q%fmqEEb^!*?V1gIa}=k0#cI=qLV+D557XwCta;r~*kQ^Wv9K)3Gs6#2mV) zSg5cftTeKKSaR-H3|`sBbbxB$|J>2wl)08-b~L|cqsHv6m{e!q2#$wXag7&09&3D{ ztj8kZm#HtZ&=#lA#u6Pmz~ zci?@Vj(4&Dcj6=JE2K4ksIx=+16z2>Nx84+~uwQ$q87!qC8YNY>2aHs$rp1p~ zjH5#Gw7Fl+Wac5j9v5PUzWpU=BWSNTpt3^5cx;^PJ-_p3s9AfUR(is1SGN_dhr=qy zA|h6moAgEMOP%7OC1yS_1Ud8M$#rT*;(&TMMXML~*#Pj-tXa2biVx0Y7&-doZsy!K!1z}9E%t@1N9 zLm17L>hoJ!&Py*yu69pO{2o+X+^;;V)3uvUk=+C~C=wxmURd~=!tC3AG<+4qD~K2{ z`sQT#qcfE7Mrdd2=(M7dp8g95!r6z-8)i9lTC71eO0{tNY?!|oIW_g;)|L3=^|gs< zfHO`#AiHU5QcrJXLT^kpqMC90(bu(c?dcpklPbI}uggD=#r;~c3X69q#p=tlNss&4 z?g54`mnmFo4A7~Kub78xbSch@D8naj1?#n=_850Sg?eg z*gT)djcQ8K#H9%b(!R}o-uo?=%Gca6^}qbHF_Ht^KJjEHXQJv>62}~wjVXN6`rCVD zqfC8qT7vzSF|C!)vAo?X%Km`wGbcTBH#4KIPV9LmV(1XP3OF%uaoc1+>AvT5tz<4l;Ud?1-6VS(AU?O$F!5}2EIvQUZncR0j@XvjSB(JJf>k$wo^#c=!sBt zUJY%ZubUuhtit%V*U5(&?)^jUBbBEzHa;kceuVRLb-nVbKfgb{sIGIcwre(rfS!u zzglwdWC`b)XDI){&&9=lQg-|cIM^I<<3=gPf3N_!F&_P7AnX_HL8O1I{MTqiC844( zB~w%mblXFMN3y*$*(9J3p`@?feH)SI7eAj${w5)IhbUiwsEu$sy&92FL+*aUkd%Vo z076d08RSE{Bo`}o6=%mB;!SL0gMll2e}Mj zvl+UG^%AHzp-aH&NP+_wRX_@k7yYLWb8wYdbYdKdbJQ zU!Lo*u01FngrRI3-L_HtDae_?kZ?H}%8b01w+Q`jU~40Ar^4^-qPttOlp;8n0Bpl# zw)CTy-9n_O8uCz=r62dROWIplzj-)BpW!bYyk&cs2L#fK5V(an_;>0OZnw>(BoYat z^M-?(`Uw#OgM%WOSgivea{QQ#;BqjdU$l&wpgO=)nN0_I(C8}8@g3ky6pq9qnZjX0 z+gNz?BJ--h)IQ3IurJZdxXB5~=}g?0(xSV?NzWWQz(#cFqcADIt}nSrC}|OZwCuP);Ijw7WtV%oK)z=WbOlWUYK8je-~t@v_Ra1c}UG4rI*`;XLDRP z1v7&6Km7R05doy)y&wUaRG@dJ@{o1tpz~5htuUJcU@@&Bxd9kYy2+NXe8BnPRQpCcUclEH`k&hB&GBO zPx**a3Vc_#Zm9wMgrCW1l>AK?$P~@uHV@<0;gkZr7=rERo|SN+k4)Blr)MbpAvFO$ z!0GWydN|j6OtsjGscvVYOkd3irePfh>-K|+zwReo&|4Ka1#SU+xNsyt_3hg?JyiI+ zJpAmPyf~0mjmi@AC%fqh6TV8~8atnqb%7hYxzmTZN}kW~*sT%Z$FZ ztUXft^|w%Q5SaKlFBsr!+CN!+_9Bf29oiWm?mNg+a^qMqMXB`yKOZZY6~@93t7V{ZU|U0eW*P ziz{)-*JRWzVt6-`hFmMf^@(K7J_0jm_;O0>@lfH?c&73ZYvf+wTzI(fR~_Hs2BU{g8g*enQX>FHgb@a>sXeBZTWtP|dzo9gK z5oA^u@t34SaeNPP_drrLO%Mo@-u;tjFEUi9BRkxP#uUCTkivn!%jOCad?+>3!q0cY zNV@M3tBlRo*-7EqJqBVPwN8b(kgiyo1Lrg&06{9@*0Zb@6`1d=rl!V|Hp#{pTiG$= zo-db3NQ#QhHGO9rr7WHI;poR#&0zwDG)C*!=9wAWDKzBwOw!zcDMz@vkB2|tjSb~` zH9tVO&Jszm$K>AVxY+i-vr%M-P$-DxZ7*DQ{ZTW(raEeB z@~|bBjOk6wKAPKU`kOgJ`F6cl*!jq04|K}xaRs9t+zBESV-ZEZh$u2o0A|;!45U2; z5=Wr$f#vCy1Yz)r5I%HH02M2Z2D~BP01Os?1ceIj3LWrvu!DeD{G^7-7$uMgBteQ# zm4~AfkV|>Vl5b;8!#J^AHT(jt7*XM9+#aV6Gpv>H#+e$G4hE2<(06qc9QV-PWoCRI z6K?Crorg7Aq0}8RVcp#P+=8g^Ht2Ei@%$rOL-GXdu633`BW6_i3?ujyhp$lL5+EDU zY!FDfrR@pBM|;72(Me&jP>sn*WXCLc2*!Ct8@-x2N|&eD?H6UZL)fS zE!zpxtTUK5z+rjhHfeynv8S6seo75mWrc@AG(W1;9|L2NX_8W*TW|ddB@5fu1;CP20-?_t$Yd4?nXOmWaI4?V)+6nnE8*I0J>T8Zq<}B~Y&z z!Fb89!ZnE7w`2x%-#fC6e-#_8S} zz!;}i^O0%ImyLWAn5(r?4h1GRSCrjnl!&nxPHUOvuwtCS6A}Df7lc{G){o(8)(xNK zp`QakJAnbL)1;qQ5W5Zw20noEUBD!PgO@h+BU^AXERWT!lq9_IODq+v`@y3^wEdlM zETlH{7NlQ!SrIKR3)~LW7vD=8009S(nI&Oj$P8}D+5i}csTohjfJtVLtyF@HlufG4 zfTtAWiUTk?@cJ7($eZK$I`S>m9 zHM9xa48g&R4a)8Y10V+$Gi?1791855zYz(s;Kyy}+^=!2Q5j(Ccd4adECeZqI~V{b z;hO8-##c}hGRRPVh|HEi6w95?4GFd&iyMvnFMt=iBPx+C!PuSzSBy(D+ra+mWiytK zeTo>?J}N`;8e8G{o(j8#&3clB!*uVr8dP^rwB!4N2&Qh+Vs`=jqiE#a)6KVL9xXa7 zeoJ9aNy*NszV!DE#S8mJK7Eob%i(iY8BMgl*p@&z$&=7niBmf&1k<~f3j$Ebmcvyb zC@L2GqhW!Y?7I6W9zRk`PbkcNA4`LbWb62i=OVD)1ntL_QH382mYV$>>;hh5+@!H; z2i&%CcqF90D5r{cqA-jf7OT_$4xp=v))8}CFjq>v!Nwg)kfuv- zid_a@6n*qjY;w%PaD85Y@8axOvU%R)19Nmw9_$u`aH>n5OcwDi%pA&7+L|1Hz#R{< zjTqeH27Lhz_Fg|#0SGQ(K!M*naGXK_yk2Q(Y3$l}_ab@D<7{)FJYMU=`S!it1yBCk zyl>Ey?yW~RuZ^g?`KIn3PU-hCUkC<*!A#CePP$$ClGGWOK}FHXD09i(iWvneaPK1E zy3sXOs{2-t28f>mM-%WA<3XJ7#o@I2`+!5hr{wXF*n}hCaGMjKlu3vK*Kh-P%>+FY zHyV6kWL^IH@_!3#-c~ zCFNJ(p55|P58SD2OeB5Ir7bZX<_*8y^O1v#E9dGK2gl1#)+FIkPNM~im~|Tu`<~bL zlY_S!T5{K@u~kE*f)zX1m)ysgd2Fu?v##G9eH-%*FWn7T`1v7FT6Y}zHGgzK{>z)E zaNJXP1YU-j(Qf-yNL*r~n4s3>`Jr+;A8dJZW^$FN4B--PC!^Fcd zJ4yNSB?-KpXUXq-TV;>DN$Zj}(gXZV;0tc(3gxK z*K$~sW05`)AP0+~t(URLjD?<{(w;xJgFqO}Yhh59pkHvRM`JBd+^EJeNYVj-7*eo5 ze9hIg6Z`3MSJW8NRMhJ}KlAA5DCV>;+BaM8Owtspi0_JkyoxCT?Qzu@p<^S7+5vCq zH}DjRHiA=Jd=i};$P|lqv zRZLIM_b6Fe-OT&U--)M?3Ey$2vI`CFtyuUQoUU$KXYjYO;Ip9tXH8vI9OzOO-^Sljx~duM9o zoFtRYIwCJPCF`Bthe4!itwvWU;M8U?Mhh`u~7YeL`o3{p#%DzM;R z*>VoAJwRwA9*m2>`ds$hB}+_V zWs8zAs_HY(pv?80ZUk}@w@UDT6I(2nsV&q>x@9u?Bpghn1stV!HpkSaw^r-Z4dkB6 zaVQ_-tLX83@o16OvZ5w7>`E#5l%2$&-Y`;BYpI|Au~}Pt0?c?gTmM`jyS!CK=J>M$ z{SUz=g|Uh4Y?+W&>hdBfW2#3>U!v(G#2+sVyJ>##+&+x01RR)~-=CLCd9N^6Nwk{` z3SybiVQ%N}%ER08JDfC5TI*Icia$t+kfI`IFrn6IFZ9`&T6YILQEzfO0!-wV9v%Xj zAdDj6Gtb($u_0ln?&95HR~WxQ5B8pbV58_06sXL)*AEB(7BfEfNy>UUXhp=5Ou7U6 zozQ0r?8};89TvpF-ATlIcV!Q2qR+JM?kU)X?b`=@vz{OP>$`XEk2gE=-ChoP#4$$PA@7DCL{Gp$)Y{rQnrFO#StSSCZfrxVrS50qfTb+QM%tyDY6A;R+ZdRid z*CL)uJ9OGZ)^yGj8r}2RaVjAYfSIADkg1bSkHH?&<;)F`=&i$%^u$Kp@RaK5%8AGu z_zkXy8hHk{$X_J`UQ~LrOk#4TX8@l1nf{AWJ6ANkU~-m7T{XMyZmGs2lXMxY;Q9&U za2#iX-Mv!Lxfz3G-&6L2vNn^j-VNbSCq&1_$3Qiy=gcNx;JhAvyG=@@9m;h20L?OWbAo};n44+tLB*X%sN$K0 z!m|1o?Bj28iol4Q=GDE2P~2swA1;-=WV>n-HM};n14tXt+N@dC?>yY``JM)Yy{C3|9Gic0``|hk$w(UJN^aHq4G6ZKuA(f8 z)ltnhB{wQG=hXfxR*xR?TpgpAk%;~Xl`{*XLBUCTW?d%GB6CmDKW?wsdmAO_=DXZR29Q zU{Cai=!r?$?x{vACvVlAMVy=7_&+c>Ri-Omk8`?oh1YY7VqVNQ5lhRc} z`|}Id#}Les_EKy!`BMEY*d=!6$+uig=ca- zM6sb(n0y2PhLA#2IIFaN&p5$=XaJgY5t_lFDM02dE?5MirL3n#lP<1t)qKJsQ>oS0 z&hSpMGkqI&0A+yU(%8>*y=N9|(MX>BMqiVMoJtIJKOCG=pm~jo#&oj9nooEwYPC_gOQkQm&%nW*t- zy9y8VO?6}S>NhJ~NY?hrRH;jp6U|_y!p3R_Vq{zaD*pKOI$haJ>NaznIAOXu+a0I~ z3tsbxe!*8`0Ua9g=|}yEv56@vytaxJ@ree9{)QrfwfGg=EvQcxtI>{TLzMh@5}yFi zpSurv*iFoacZG=@o8299jZ>%u{F{YPSS$Q^7uB61tS-R$n!&uzEZ4u7fE#}q>yP_0 z^|H;jVut5qdZJgIKX$Y^32v#stZ-Gwm4szB@KW&$L-A^M(+yHAzxX(}n#s%pseSK= zACGAS)^v0YGL2@=P6ZTcbVz9Aq1#TJY(oWo{Zxgw9hq3+aBih@)l|{yxSW|hDezoHVkz>5< zHj*~?-ga`d_XcJdkGD$RNNkPix)Cb6AD69FRGG!<2p!>#_(rF1;!LndWgDtw1p#NZ zEcV*c+ffETYkKlb1ogU)KTEMpG|eJi1A(-hm&8+kd6>Y>eoWfkgH<)@XD^ObWG#?A zl&b}3fo-e&Ujhj9PE||c>*n6hG0$?dSskpC;vCnszUE|WQ)x|$OC4f5$2olfOfBF0 zU9{ddKbraykFN9fglBZ!@2Y6;!_Uq!ee7)YvhlcYQ+B~VTk`TUC+@jqiD#+B<4QKx zgE$X2P@cj|L(XL)(A1Sj>Vo) z2aN%-O4-P|j@{`9?w9;FYV71HR#ugykHrLw^I3W}HrW`etZBAFg~`1r%VI1{?6SA9 zS#f#vCwKLO%e4OUI@r-2C`$wj`pK9im{OPqhub;LQJuHP8 zT$Y)BPs}K@%~sPY>Pd=n^8yoJ!YgKK%|dI-(vx*tK! zq4rQts6Kabg79VW77}g=)6wBTXMEhFZw{F|^GyP9(c^~n9MjKB!2=4q!=X1ZuhFG0 zPZ&FS_&+-cf|}`OjxvT%sfDKXDYJBCp*E)2Tm93}Ba(m{N}T>^$1oW52D31W`v_k;4w66%U=osul=|`813rFCx{7taW5UrpD4shHnNB77LTggHe(<eI$2`y zi23F_uSdTFTUiDfOV_NEAF@?A{uXO5MJLNkAqlxz&geK37@DDUd~LhJ98x{qV=M9M z;gjFgGjI@VaLxI|mD;Lqnb-le$LjD;ZYLrUfFKw@#dt{MmmRg>!H0a0N;#hgAR~0&geRjY%GR1Tgap z)!cB&z54|`{x;xl_;8XBypjoBUB$xmplm03;IxPqg20zQUEvSD({524m2dUje#gB# zzb&enaB?(&FE-*!1ua&}%S34}#EZ5vd^mjlwlPjw_#wWhxS{}^Y+b|*w3LM>qV}*O z5orU}cej#j5Gj;VVt#=aV6DWYp4jp+U`e3btIH-=*r=7o*QV)9`2}O{q~40|qofGO z;+PNwKF%LUBzm}_r+#>x_CTy%DzZBsWXx5!thVh=j!%y@8oGuZ6KMXVq4`sAc^oAJ zZ&i&!>tM83g?4TztY`>!UU?4ntWU!R%~ z4WdPvE#;xCTw6KLCI;kJHlQu>OKcxC-e#6YpK-q^t?g_azLDl<_cP6t?#z^cd-S6P z(Eho|UFACyKkyZ~YQ=Ks_<5j=H1@O+{Ey0_u<2VHR@>EH9+mrGp_=tLTimcs6t(nM zQmVlYCCOpKwovtxz0%*mKdIx?6K0H>R*Jp$-mMbUk6pz6@}NTI=AkfRyT~zpnZa;; z-7&;Q8g{ooWRg>#fS#YPCMcA=gOga82@^u_;P6WS-q{t7b1sp=TxDR_m$>I(8g>Yp zA~>L_$b47wI$*G;%0R(L%V-7vn7^m>yp)5~)uJi;6&4tKDjCdK4&?^?O-w}Q<0<4= zJp`_1v8H7LfD8TX*+YArW%$$n#C6ZWifRPKYBRrLjl#&7izk`$-uTb@b+Q39O=H^> zbL|334k|@q0Y%^?5>XWH<<3sd{(p}*0sV8uF^Aqhz5Cu+AI3uY=$zi>?cd>N=1ws& z#p6fcum9}*zNQo%zF9FynTd4k($%2ciq)T-#6LF7=G2%^pSAQ(^-z9r@$n8y*-lVR zEVElb!kOObZ3ktou0`5Xh*8!@cRKkwB5$Qx1bJz>w-OU6Kkr#a58Kp-qS_3a?^Z#3 zid14`WB9h%k^&7kA)ir{>=j`OoC>$noKBdrfh>g(x?~)3Z2Z3-)}*#RXwE%#EG){G zstRxe5{(@ng>AU+53V;ao4H;yAZgsGB8tGmY_W`ReieJu_9c<1Y~GqsgcB1HMA7~m zjve5Z>A%Q(SY}ofiR)^fF%ZeX?=CJ+l3~bjKr&rDSfy=nTuplF%PI^EA~evnNT%ZK z#i*%|auCTFgK>GS8GA|;ziymC@xvXtTOyk-oTjS!jrUB{k9c{a#EXHDJgFb0ft6xf z#r)XD`bsgQUUC}Q zx|>Qxxp)F^$L@^L-ws~SLhTx%Ed_XM%AuRghw9e$ux#6uXQqww4{hbta`<-WKsyRfmD6CsPcW}*D6_DwzOC4Z5a>9yiC9?7OVUsL9tYZhn<)Gg0?lC*mE3(#caQ?Wm`T`?r6Fy2Yd!Z2J)LxYf zMhL`KE@i;E0`Cr;$j8qCTu}@=Hr`XiMr%Gw zw6{(4viW!_-hNxnqeR+nA`z}73lA(G^#g}VsR>=V^yKRPO=^$^=k*ehZ0yZY=IPZG(h4Q7%4uxdF^wyt@GuR_ns}E{>xbqs zIPF8hg!OvaPN~Y|*oF6$Xsd0L#J?1kMWh-MXF|ZMEex^pb|kbh_Jvu4QJ}P%Sr>iw zlrj(AQub#u0#(EIC&aEMB;uv-mpwjY9klgp;OW&`)he>pzHC}3s-=V?PQyPQ9yCj3 zklDHFzPR0=X=J(4y%lQ%j~ngSEzXuh>(~#D@jv*YcCy5RpPPD0uK=lhHWimu?Q#3R z4ml1!xXf=3Ubu`0^;b{uNw4i6Y8|YYe===o3~ORqCOQCoe8wCcWaNBmh9HoiPbI|p zHc99;H~&PPNHd>kXxOaM@=b+@P*(N;kx_a)gHz?f6m?5W#;Z^;+lUbAF_XXdulP_03|ttf}9nyy_-YoP4o%*wUu?S(O@@LiOf;PVS03c`_X`X@HlL zjiT3yV1L54{)EH3s`^k;!jbdHyRy_Wh1=YlE9LT<~F0RrAh)3x2Vs>JJ#mCv#z zfb^PTJL$s!zz%c#0XxhQig&()QGE+fK8#fU+6wvD`JiAZFT_llqL;)f*naHDC=;9L zOQ($EV+!zci8IMFO()zk{vEpTRX8cRI?C9h0&j~68DA_i-Cb_WfvYCf` zYcF6jKd!H?PEU@yIJ4k>Moou6Wg4Rz&S7fR4ft_vPMN_Y%?KB7BRTN2c*?6mz{3)U zLu-)cKm6QfVYs@xA*6DW)3i+7JFGobf%Df(ub$8HfNt|8OD4F{|KvBMWVqEW^t;NQ z+$?2LzzsX>-;7G{h;wqBDXTKOQ>PdBCj#AM`QT-S`;Y=U+580+1As`Y%qou@2qe*P zUr3Px`IFZx;~h%@(x1*j(T-{|Fygvz=-4!}(G!Ys@*7sV-{Z{qHO9je*YC|eE6ybQ z?Il$+cTQ3$uNwKM8n4}1+MA-@+JVPw6tx=D=bp6D)**yf)%{ewJCjKYT0r}fGKq|! zqMw9V1m?@hXV!J0vzQ`p=TKN+n~G*ZEzNFk6Ej1Jyra!e-t*=jo=Pw%|K9!mY1;2> z*eLwD8TM$ohjMGa9=KI{2k?Eo&!SaMrJe~Q&x(6v6pB%4$mS*xT0!afzyKT-!LL#-#}6TD!5*?|ADsN9~GzNP}` zOu5O&!Rz~AHl51=qY|2OKfT-RI{N>F`ZcFhyMcI$tL3aWFb80^_V80L!`2SBS)jIj`tzX2@gx;4P7 z8-m&K0Te4|l~QWoyfHuoxTcYc!K=2%rR^DigSUE*k~P8KBmc>tA2)l;uMnDdk`B+M$yr^3=rd_VB_GO)EN6J0-T^e6z)IT`Knt{&5htgpP+T{;eoDS4qJ`i zp6wPuFqKq@+Rma%&!nNuV5k(Z)BvA{cK}>KnAqU$;97lPg90NAf49rSfqAL}s-vR=Ra8`@q@ZBa)zwvqx^CPh7FI(}`}H}{ z2xFCNyaJ|?QgE2G*Lr_631cA;sUNGhx^D~U3DdZQBJ>6%p%O6JcuivoAXWmjYY>j5 zx7BvG+aeNhusIh00i1YUGe9RaPmu5!Q&yHvtmwLI6xM*6A!N@BBX;O}@)}W_cK~`u z_uVw8SPUaWST+=f(xa;L1AsI@r&%B~88tJ>7~8k&)FZ?^1sFX5u@UeD44xdD-C6+T z%fa8k4v0D>sFSRP>E-tvL1dZyblB~ zhk$tgHz23-$mjU`-wFXP$HdTFNP+-noZc8SwQyl%1e1piJm(r3%-}0>o~{ycnW@1_ z9?riWj}BviRj~%R=2gWYsJ?K94Ab%dj_faHkS~-!6Ei6n1#TVv)$e}`1SN$|M)rze z=EP1>&*gQ6|9Lp{Cq+$Kjfotl;`Z2?oByhq4rD};8HyRWrvhxiZ2w;mpT~sKL~`a~ zq<)$ZBTI$R#P{$HfV7fRQqtJg&aNor;?$QS!Sk<@z@aD0ES|(bK9Ek?@&Nt zOUp5=KnCrtf&SE+Yrqf_f#P`Bue&h;4uer6Pr&#A{&eH`tc6yH@Bhx@%QbOZwZSAn-ey_HRoc zYy z)+R5kV>+_;5l~muPR6x$|5w{ql(cUEHP8sE0XqKg*T4sJ$Vq&SA7+U{bN}t$|F8@0 zXQ8(t3DXE%x%U8f^*(@=7yy!9i!^g2Uh(|9p4d<{1jzlJ=K%5-?2;(<2uwRm$s-kt z`c8i1Vame#+5Y$BW-DQ(`8(f$`NXzFqWud%PGq9=hp7sS z9BN8{)z1`;DZ9i0HlZHFr272r{-q*-s%$?&J;9U=T?I;d%%$tw{Qa~DeA;8I`~LFp za~ha&lKwgIx5Xtg;L~{+?->WiNThCHr_tbR-!uF>u}(0bSaAk-|0+%k1KZr<3qAci zT0t=YhxgAKgf{RL(3w0)BE6{6y~`6jdU2<83~fqJ< z0hH&O8YUf^m{B4TdMzHXwuu9aLw$6zB;{Xu|GT0tVPJCSae`;JFuerY17!UBYu*%K zlM@Uw3o8G6bYnyB1Fd4H)pP!5ap2i7Gl0@q&w11DUsDzey2Q}&zu82&{nZ%`#Z1eS z>Tm1oY5)jmqS|UP45DLy-R>{o<^jGoxwMPxj)cPhJr!^A{->8tNx+n<%wJ8q{sQ2O zL0W(EfnRsFO%7<#SOwUr{1rzC5XGJCpE|2CLk1-O#$0zFm^paY5_gmU#ZIWTd;$7F zj0)&4tLz+;?33eEeG^=hBCvpE^MDXAGfdc#hzpiHT)!#0OO44Ehf2xXF K3RQB};r|EI+gsWI literal 0 HcmV?d00001 diff --git a/perception/autoware_image_projection_based_fusion/docs/mask-cluster-fusion.md b/perception/autoware_image_projection_based_fusion/docs/mask-cluster-fusion.md new file mode 100644 index 0000000000000..d2a6dd675de23 --- /dev/null +++ b/perception/autoware_image_projection_based_fusion/docs/mask-cluster-fusion.md @@ -0,0 +1,38 @@ +# mask_cluster_fusion + +## Purpose + +The `mask_cluster_fusion` package aims to assign the label of the mask to the cluster by using the mask information from the 2D instance segmentation model. + +## Inner-workings / Algorithms + +1. The clusters are projected onto the image plane. +2. Find the mask which intersects with the cluster with high IoU. +3. Assign the label of the mask to the cluster. +4. For all clusters with an assigned label, check if any cluster intersects with the same mask. Reassign the label of the mask to the cluster if its IoU is lower than the previously assigned cluster. + +![mask_cluster_fusion_image](./images/mask_cluster_fusion.png) + +## Inputs / Outputs + +### Input + +| Name | Type | Description | +| ------------------------ |----------------------------------------------------------| --------------------------------------------------------- | +| `input` | `tier4_perception_msgs::msg::DetectedObjectsWithFeature` | clustered pointcloud | +| `input/camera_info[0-7]` | `sensor_msgs::msg::CameraInfo` | camera information to project 3d points onto image planes | +| `input/masks[0-7]` | `autoware_internal_msgs::msg::SegmentationMask` | masks from each image | +| `input/image_raw[0-7]` | `sensor_msgs::msg::Image` | images for visualization | + +### Output + +| Name | Type | Description | +| ------------------------ |----------------------------------------------------------| -------------------------- | +| `output` | `tier4_perception_msgs::msg::DetectedObjectsWithFeature` | labeled cluster pointcloud | +| `~/debug/image_raw[0-7]` | `sensor_msgs::msg::Image` | images for visualization | + +## Parameters + +{{ json_to_markdown("perception/autoware_image_projection_based_fusion/schema/mask_cluster_fusion.json") }} + +## Assumptions / Known limits \ No newline at end of file From 06983b614e658d32c696936c5b76d0afae6e6d3d Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Thu, 5 Dec 2024 16:57:57 +0000 Subject: [PATCH 14/19] style(pre-commit): autofix --- perception/autoware_image_projection_based_fusion/README.md | 2 +- .../docs/mask-cluster-fusion.md | 6 +++--- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/perception/autoware_image_projection_based_fusion/README.md b/perception/autoware_image_projection_based_fusion/README.md index 34db7f86f02cd..d71c90f6fd5ee 100644 --- a/perception/autoware_image_projection_based_fusion/README.md +++ b/perception/autoware_image_projection_based_fusion/README.md @@ -69,7 +69,7 @@ The rclcpp::TimerBase timer could not break a for loop, therefore even if time i ### Detail description of each fusion's algorithm is in the following links | Fusion Name | Description | Detail | -| -------------------------- |---------------------------------------------------------------------------------------------------| -------------------------------------------- | +| -------------------------- | ------------------------------------------------------------------------------------------------- | -------------------------------------------- | | 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) | diff --git a/perception/autoware_image_projection_based_fusion/docs/mask-cluster-fusion.md b/perception/autoware_image_projection_based_fusion/docs/mask-cluster-fusion.md index d2a6dd675de23..b8315cb014cab 100644 --- a/perception/autoware_image_projection_based_fusion/docs/mask-cluster-fusion.md +++ b/perception/autoware_image_projection_based_fusion/docs/mask-cluster-fusion.md @@ -18,7 +18,7 @@ The `mask_cluster_fusion` package aims to assign the label of the mask to the cl ### Input | Name | Type | Description | -| ------------------------ |----------------------------------------------------------| --------------------------------------------------------- | +| ------------------------ | -------------------------------------------------------- | --------------------------------------------------------- | | `input` | `tier4_perception_msgs::msg::DetectedObjectsWithFeature` | clustered pointcloud | | `input/camera_info[0-7]` | `sensor_msgs::msg::CameraInfo` | camera information to project 3d points onto image planes | | `input/masks[0-7]` | `autoware_internal_msgs::msg::SegmentationMask` | masks from each image | @@ -27,7 +27,7 @@ The `mask_cluster_fusion` package aims to assign the label of the mask to the cl ### Output | Name | Type | Description | -| ------------------------ |----------------------------------------------------------| -------------------------- | +| ------------------------ | -------------------------------------------------------- | -------------------------- | | `output` | `tier4_perception_msgs::msg::DetectedObjectsWithFeature` | labeled cluster pointcloud | | `~/debug/image_raw[0-7]` | `sensor_msgs::msg::Image` | images for visualization | @@ -35,4 +35,4 @@ The `mask_cluster_fusion` package aims to assign the label of the mask to the cl {{ json_to_markdown("perception/autoware_image_projection_based_fusion/schema/mask_cluster_fusion.json") }} -## Assumptions / Known limits \ No newline at end of file +## Assumptions / Known limits From 6c7a76cfe51300456c65452857912fb97a531f9e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Bar=C4=B1=C5=9F=20Zeren?= Date: Thu, 5 Dec 2024 20:30:00 +0300 Subject: [PATCH 15/19] fix: wrong file name MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Barış Zeren --- .../docs/mask-cluster-fusion.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception/autoware_image_projection_based_fusion/docs/mask-cluster-fusion.md b/perception/autoware_image_projection_based_fusion/docs/mask-cluster-fusion.md index b8315cb014cab..189b470395c3b 100644 --- a/perception/autoware_image_projection_based_fusion/docs/mask-cluster-fusion.md +++ b/perception/autoware_image_projection_based_fusion/docs/mask-cluster-fusion.md @@ -33,6 +33,6 @@ The `mask_cluster_fusion` package aims to assign the label of the mask to the cl ## Parameters -{{ json_to_markdown("perception/autoware_image_projection_based_fusion/schema/mask_cluster_fusion.json") }} +{{ json_to_markdown("perception/autoware_image_projection_based_fusion/schema/mask_cluster_fusion.schema.json") }} ## Assumptions / Known limits From e475af47f5fd5b77dd6f120e92b8988963e4a95b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Bar=C4=B1=C5=9F=20Zeren?= Date: Mon, 9 Dec 2024 18:37:53 +0300 Subject: [PATCH 16/19] refactor: update msg type MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Barış Zeren --- .../docs/mask-cluster-fusion.md | 4 ++-- .../autoware/image_projection_based_fusion/fusion_node.hpp | 4 ++-- perception/autoware_image_projection_based_fusion/package.xml | 1 - 3 files changed, 4 insertions(+), 5 deletions(-) diff --git a/perception/autoware_image_projection_based_fusion/docs/mask-cluster-fusion.md b/perception/autoware_image_projection_based_fusion/docs/mask-cluster-fusion.md index 189b470395c3b..4cd00ccc34971 100644 --- a/perception/autoware_image_projection_based_fusion/docs/mask-cluster-fusion.md +++ b/perception/autoware_image_projection_based_fusion/docs/mask-cluster-fusion.md @@ -18,10 +18,10 @@ The `mask_cluster_fusion` package aims to assign the label of the mask to the cl ### Input | Name | Type | Description | -| ------------------------ | -------------------------------------------------------- | --------------------------------------------------------- | +| ------------------------ |----------------------------------------------------------| --------------------------------------------------------- | | `input` | `tier4_perception_msgs::msg::DetectedObjectsWithFeature` | clustered pointcloud | | `input/camera_info[0-7]` | `sensor_msgs::msg::CameraInfo` | camera information to project 3d points onto image planes | -| `input/masks[0-7]` | `autoware_internal_msgs::msg::SegmentationMask` | masks from each image | +| `input/masks[0-7]` | `autoware_perception_msgs::msg::SegmentationMask` | masks from each image | | `input/image_raw[0-7]` | `sensor_msgs::msg::Image` | images for visualization | ### Output diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp index 7881b8cfce8b0..d4d6ffa473f26 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp @@ -20,7 +20,7 @@ #include #include -#include +#include #include #include #include @@ -55,7 +55,7 @@ using sensor_msgs::msg::PointCloud2; using tier4_perception_msgs::msg::DetectedObjectsWithFeature; using tier4_perception_msgs::msg::DetectedObjectWithFeature; using PointCloud = pcl::PointCloud; -using autoware_internal_msgs::msg::SegmentationMask; +using autoware_perception_msgs::msg::SegmentationMask; using autoware_perception_msgs::msg::ObjectClassification; template diff --git a/perception/autoware_image_projection_based_fusion/package.xml b/perception/autoware_image_projection_based_fusion/package.xml index bceb805b10977..335c4712071e0 100644 --- a/perception/autoware_image_projection_based_fusion/package.xml +++ b/perception/autoware_image_projection_based_fusion/package.xml @@ -17,7 +17,6 @@ autoware_cmake autoware_euclidean_cluster - autoware_internal_msgs autoware_lidar_centerpoint autoware_object_recognition_utils autoware_perception_msgs From c93268b4aeb7e5d83d5e09abd1caf5a01f0d966b Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Mon, 9 Dec 2024 15:40:41 +0000 Subject: [PATCH 17/19] style(pre-commit): autofix --- .../docs/mask-cluster-fusion.md | 2 +- .../autoware/image_projection_based_fusion/fusion_node.hpp | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/perception/autoware_image_projection_based_fusion/docs/mask-cluster-fusion.md b/perception/autoware_image_projection_based_fusion/docs/mask-cluster-fusion.md index 4cd00ccc34971..de287c648002e 100644 --- a/perception/autoware_image_projection_based_fusion/docs/mask-cluster-fusion.md +++ b/perception/autoware_image_projection_based_fusion/docs/mask-cluster-fusion.md @@ -18,7 +18,7 @@ The `mask_cluster_fusion` package aims to assign the label of the mask to the cl ### Input | Name | Type | Description | -| ------------------------ |----------------------------------------------------------| --------------------------------------------------------- | +| ------------------------ | -------------------------------------------------------- | --------------------------------------------------------- | | `input` | `tier4_perception_msgs::msg::DetectedObjectsWithFeature` | clustered pointcloud | | `input/camera_info[0-7]` | `sensor_msgs::msg::CameraInfo` | camera information to project 3d points onto image planes | | `input/masks[0-7]` | `autoware_perception_msgs::msg::SegmentationMask` | masks from each image | diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp index d4d6ffa473f26..0bb4f27a0af70 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp @@ -20,8 +20,8 @@ #include #include -#include #include +#include #include #include #include @@ -55,8 +55,8 @@ using sensor_msgs::msg::PointCloud2; using tier4_perception_msgs::msg::DetectedObjectsWithFeature; using tier4_perception_msgs::msg::DetectedObjectWithFeature; using PointCloud = pcl::PointCloud; -using autoware_perception_msgs::msg::SegmentationMask; using autoware_perception_msgs::msg::ObjectClassification; +using autoware_perception_msgs::msg::SegmentationMask; template class FusionNode : public rclcpp::Node From abe7d73197c070ea9b19a8747844bc22ef4bd117 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Bar=C4=B1=C5=9F=20Zeren?= Date: Thu, 12 Dec 2024 13:13:30 +0300 Subject: [PATCH 18/19] refactor: msg type MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Barış Zeren --- .../docs/mask-cluster-fusion.md | 14 +++++++------- .../image_projection_based_fusion/fusion_node.hpp | 4 ++-- .../package.xml | 1 + 3 files changed, 10 insertions(+), 9 deletions(-) diff --git a/perception/autoware_image_projection_based_fusion/docs/mask-cluster-fusion.md b/perception/autoware_image_projection_based_fusion/docs/mask-cluster-fusion.md index de287c648002e..a984e44ecc3ca 100644 --- a/perception/autoware_image_projection_based_fusion/docs/mask-cluster-fusion.md +++ b/perception/autoware_image_projection_based_fusion/docs/mask-cluster-fusion.md @@ -17,17 +17,17 @@ The `mask_cluster_fusion` package aims to assign the label of the mask to the cl ### Input -| Name | Type | Description | -| ------------------------ | -------------------------------------------------------- | --------------------------------------------------------- | -| `input` | `tier4_perception_msgs::msg::DetectedObjectsWithFeature` | clustered pointcloud | -| `input/camera_info[0-7]` | `sensor_msgs::msg::CameraInfo` | camera information to project 3d points onto image planes | -| `input/masks[0-7]` | `autoware_perception_msgs::msg::SegmentationMask` | masks from each image | -| `input/image_raw[0-7]` | `sensor_msgs::msg::Image` | images for visualization | +| Name | Type | Description | +|--------------------------|------------------------------------------------------------|-----------------------------------------------------------| +| `input` | `tier4_perception_msgs::msg::DetectedObjectsWithFeature` | clustered pointcloud | +| `input/camera_info[0-7]` | `sensor_msgs::msg::CameraInfo` | camera information to project 3d points onto image planes | +| `input/masks[0-7]` | `autoware_internal_perception_msgs::msg::SegmentationMask` | masks from each image | +| `input/image_raw[0-7]` | `sensor_msgs::msg::Image` | images for visualization | ### Output | Name | Type | Description | -| ------------------------ | -------------------------------------------------------- | -------------------------- | +|--------------------------|----------------------------------------------------------|----------------------------| | `output` | `tier4_perception_msgs::msg::DetectedObjectsWithFeature` | labeled cluster pointcloud | | `~/debug/image_raw[0-7]` | `sensor_msgs::msg::Image` | images for visualization | diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp index 0bb4f27a0af70..2af1f3b3dba96 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp @@ -21,7 +21,7 @@ #include #include -#include +#include #include #include #include @@ -56,7 +56,7 @@ using tier4_perception_msgs::msg::DetectedObjectsWithFeature; using tier4_perception_msgs::msg::DetectedObjectWithFeature; using PointCloud = pcl::PointCloud; using autoware_perception_msgs::msg::ObjectClassification; -using autoware_perception_msgs::msg::SegmentationMask; +using autoware_internal_perception_msgs::msg::SegmentationMask; template class FusionNode : public rclcpp::Node diff --git a/perception/autoware_image_projection_based_fusion/package.xml b/perception/autoware_image_projection_based_fusion/package.xml index 335c4712071e0..c0542e52159ce 100644 --- a/perception/autoware_image_projection_based_fusion/package.xml +++ b/perception/autoware_image_projection_based_fusion/package.xml @@ -17,6 +17,7 @@ autoware_cmake autoware_euclidean_cluster + autoware_internal_perception_msgs autoware_lidar_centerpoint autoware_object_recognition_utils autoware_perception_msgs From b8529733680e1b955c4239c1db69f69ad02c8669 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Thu, 12 Dec 2024 10:16:24 +0000 Subject: [PATCH 19/19] style(pre-commit): autofix --- .../docs/mask-cluster-fusion.md | 4 ++-- .../autoware/image_projection_based_fusion/fusion_node.hpp | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/perception/autoware_image_projection_based_fusion/docs/mask-cluster-fusion.md b/perception/autoware_image_projection_based_fusion/docs/mask-cluster-fusion.md index a984e44ecc3ca..d76ac010fb955 100644 --- a/perception/autoware_image_projection_based_fusion/docs/mask-cluster-fusion.md +++ b/perception/autoware_image_projection_based_fusion/docs/mask-cluster-fusion.md @@ -18,7 +18,7 @@ The `mask_cluster_fusion` package aims to assign the label of the mask to the cl ### Input | Name | Type | Description | -|--------------------------|------------------------------------------------------------|-----------------------------------------------------------| +| ------------------------ | ---------------------------------------------------------- | --------------------------------------------------------- | | `input` | `tier4_perception_msgs::msg::DetectedObjectsWithFeature` | clustered pointcloud | | `input/camera_info[0-7]` | `sensor_msgs::msg::CameraInfo` | camera information to project 3d points onto image planes | | `input/masks[0-7]` | `autoware_internal_perception_msgs::msg::SegmentationMask` | masks from each image | @@ -27,7 +27,7 @@ The `mask_cluster_fusion` package aims to assign the label of the mask to the cl ### Output | Name | Type | Description | -|--------------------------|----------------------------------------------------------|----------------------------| +| ------------------------ | -------------------------------------------------------- | -------------------------- | | `output` | `tier4_perception_msgs::msg::DetectedObjectsWithFeature` | labeled cluster pointcloud | | `~/debug/image_raw[0-7]` | `sensor_msgs::msg::Image` | images for visualization | diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp index 2af1f3b3dba96..3f035ba0201eb 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp @@ -20,8 +20,8 @@ #include #include -#include #include +#include #include #include #include @@ -55,8 +55,8 @@ using sensor_msgs::msg::PointCloud2; using tier4_perception_msgs::msg::DetectedObjectsWithFeature; using tier4_perception_msgs::msg::DetectedObjectWithFeature; using PointCloud = pcl::PointCloud; -using autoware_perception_msgs::msg::ObjectClassification; using autoware_internal_perception_msgs::msg::SegmentationMask; +using autoware_perception_msgs::msg::ObjectClassification; template class FusionNode : public rclcpp::Node