From 4d556e4f2d920ee07df7564ac553419fa2fe7303 Mon Sep 17 00:00:00 2001 From: badai-nguyen Date: Thu, 3 Feb 2022 16:25:26 +0900 Subject: [PATCH 01/27] feat: check segment in both directions Signed-off-by: badai-nguyen --- .../dual_return_outlier_filter_nodelet.hpp | 2 + .../dual_return_outlier_filter_nodelet.cpp | 49 +++++++++++++++++-- 2 files changed, 48 insertions(+), 3 deletions(-) diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp index 6e46123cfba4e..0350628dc84da 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp @@ -73,6 +73,8 @@ class DualReturnOutlierFilterComponent : public pointcloud_preprocessor::Filter double visibility_threshold_; int vertical_bins_; float max_azimuth_diff_; + uint weak_first_segment_check_size_v_; + uint weak_first_segment_check_size_h_; public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW diff --git a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp index cc442ed081b5d..fde2582d31cc6 100644 --- a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp @@ -44,6 +44,8 @@ DualReturnOutlierFilterComponent::DualReturnOutlierFilterComponent( weak_first_local_noise_threshold_ = static_cast(declare_parameter("weak_first_local_noise_threshold", 10)); visibility_threshold_ = static_cast(declare_parameter("visibility_threshold", 0.5)); + weak_first_segment_check_size_h_ = static_cast(declare_parameter("weak_first_segment_check_size_h",30)); + weak_first_segment_check_size_v_ = static_cast(declare_parameter("weak_first_segment_check_size_v",3)); } updater_.setHardwareID("dual_return_outlier_filter"); updater_.add( @@ -111,12 +113,23 @@ void DualReturnOutlierFilterComponent::filter( vertical_bins); // TODO(davidw): this is for Pandar 40 only, make dynamic weak_first_pcl_input_ring_array.resize(vertical_bins); + const uint ring_number = vertical_bins; + const uint azimuth_steps = 36000; + float * distance_inputpcl_array = new float[ring_number * azimuth_steps]; + float * distance_weakfirstpcl_array = new float[ring_number * azimuth_steps]; + for (uint i = 0; i < ring_number * azimuth_steps; i++){ + distance_inputpcl_array[i] = -1.0f; + distance_weakfirstpcl_array[i] = -1.0f; + } // Split into 36 x 10 degree bins x 40 lines (TODO: change to dynamic) for (const auto & p : pcl_input->points) { + uint azimuth_ind = static_cast(p.azimuth < 0.0f ? p.azimuth + 36000.0f : p.azimuth); if (p.return_type == ReturnType::DUAL_WEAK_FIRST) { weak_first_pcl_input_ring_array.at(p.ring).push_back(p); + distance_weakfirstpcl_array[p.ring*azimuth_steps + azimuth_ind] = p.distance; } else { pcl_input_ring_array.at(p.ring).push_back(p); + distance_inputpcl_array[p.ring * azimuth_steps +azimuth_ind] = p.distance; } } @@ -135,12 +148,39 @@ void DualReturnOutlierFilterComponent::filter( uint ring_id = weak_first_single_ring.points.front().ring; for (auto iter = std::begin(weak_first_single_ring) + 1; iter != std::end(weak_first_single_ring) - 1; ++iter) { - const float min_dist = std::min(iter->distance, (iter + 1)->distance); - const float max_dist = std::max(iter->distance, (iter + 1)->distance); + uint azimuth_id = static_cast (iter->azimuth); + uint segment_check = 0, segment_check_thresh = 2; + uint weakfirst_ring_min = 0, weakfirst_ring_max = ring_number; + uint weakfirst_w_min = 0, weakfirst_w_max = azimuth_steps; + + weakfirst_ring_min = ring_id > weak_first_segment_check_size_v_ ? + ring_id - weak_first_segment_check_size_v_ : 0; + weakfirst_ring_max = ring_id + weak_first_segment_check_size_v_ < ring_number ? + ring_id + weak_first_segment_check_size_v_ + 1: ring_number; + weakfirst_w_min = azimuth_id > weak_first_segment_check_size_h_ ? + azimuth_id - weak_first_segment_check_size_h_ : 0; + weakfirst_w_max = azimuth_id + weak_first_segment_check_size_h_ < azimuth_steps ? + azimuth_id + weak_first_segment_check_size_h_ +1 : azimuth_steps; + + for ( auto i = weakfirst_ring_min; i < weakfirst_ring_max; i++){ + for (auto j = weakfirst_w_min; j < weakfirst_w_max; j++){ + if(distance_weakfirstpcl_array[i*azimuth_steps + j] > 0.0){ + const float min_dist = std::min(iter->distance, distance_weakfirstpcl_array[i*azimuth_steps + j]); + const float max_dist = std::max(iter->distance, distance_weakfirstpcl_array[i* azimuth_steps + j]); float azimuth_diff = (iter + 1)->azimuth - iter->azimuth; azimuth_diff = azimuth_diff < 0.f ? azimuth_diff + 36000.f : azimuth_diff; - if (max_dist < min_dist * weak_first_distance_ratio_ && azimuth_diff < max_azimuth_diff) { + if (max_dist < min_dist * weak_first_distance_ratio_){ + segment_check++; + } + } + if (segment_check >= segment_check_thresh ){ + goto exit_segment_check;} + } + } + exit_segment_check: + + if (segment_check >= segment_check_thresh) { temp_segment.points.push_back(*iter); keep_next = true; } else if (keep_next) { @@ -220,6 +260,9 @@ void DualReturnOutlierFilterComponent::filter( pcl_output->points.push_back(tmp_p); } } + + delete [] distance_inputpcl_array; + delete [] distance_weakfirstpcl_array; // Threshold for diagnostics (tunable) cv::Mat binary_image; cv::inRange(frequency_image, weak_first_local_noise_threshold_, 255, binary_image); From 6a14e9093fcbd84a8e38cc241bb1c81651a04234 Mon Sep 17 00:00:00 2001 From: badai-nguyen Date: Thu, 3 Feb 2022 16:50:26 +0900 Subject: [PATCH 02/27] feat: add free-space ROI setting and mode switching Check normal pcl surrounding weak_first_return pcl to get free space. Signed-off-by: badai-nguyen --- .../dual_return_outlier_filter_nodelet.hpp | 2 + .../dual_return_outlier_filter_nodelet.cpp | 45 +++++++++++++++++-- 2 files changed, 43 insertions(+), 4 deletions(-) diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp index 0350628dc84da..e83b3f630de4c 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp @@ -73,8 +73,10 @@ class DualReturnOutlierFilterComponent : public pointcloud_preprocessor::Filter double visibility_threshold_; int vertical_bins_; float max_azimuth_diff_; + float neighbor_r_thresh_ = 0.5f; uint weak_first_segment_check_size_v_; uint weak_first_segment_check_size_h_; + uchar ROI_mode_; public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW diff --git a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp index fde2582d31cc6..e8edafba92d7a 100644 --- a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp @@ -44,6 +44,7 @@ DualReturnOutlierFilterComponent::DualReturnOutlierFilterComponent( weak_first_local_noise_threshold_ = static_cast(declare_parameter("weak_first_local_noise_threshold", 10)); visibility_threshold_ = static_cast(declare_parameter("visibility_threshold", 0.5)); + ROI_mode_ = static_cast(declare_parameter("ROI_mode",0))azimuth_steps; weak_first_segment_check_size_h_ = static_cast(declare_parameter("weak_first_segment_check_size_h",30)); weak_first_segment_check_size_v_ = static_cast(declare_parameter("weak_first_segment_check_size_v",3)); } @@ -189,11 +190,47 @@ void DualReturnOutlierFilterComponent::filter( // Analyse segment points here } else { // Log the deleted azimuth and its distance for analysis - deleted_azimuths.push_back(iter->azimuth < 0.f ? 0.f : iter->azimuth); - deleted_distances.push_back(iter->distance); - noise_output->points.push_back(*iter); - } + switch (ROI_mode_) + { + case 1: //dynamic ROI free space + { + // check surrounding normal pcl + uint neighbor_check = 0, h_range = 3, w_range = 10; + uint min_h = 0, max_h = ring_number; + uint min_w = 0, max_w = azimuth_steps; + min_h = iter->ring > h_range ? iter->ring - h_range : 0; + max_h = iter->ring < ring_number - h_range ? iter->ring + h_range : ring_number; + + min_w = azimuth_id > w_range ? azimuth_id - w_range : 0; + max_w = azimuth_id < azimuth_steps - w_range ? azimuth_id + w_range : azimuth_steps; + for (auto i = min_h ; i < max_h; i++){ + for (auto j = min_w ; j < max_w; j++){ + if((distance_inputpcl_array[i*azimuth_steps + j] > 0.0f) && (iter->distance > + (distance_inputpcl_array[i*azimuth_steps + j] - neighbor_r_thresh_))){ + neighbor_check++; + } + if (neighbor_check > 1){ + goto exit_neighbor_check; + } + } + } + exit_neighbor_check: + if(neighbor_check < 2){ + deleted_azimuths.push_back(iter->azimuth < 0.f ? 0.f : iter->azimuth); + deleted_distances.push_back(iter->distance); + noise_output->points.push_back(*iter);} + break; + } + default: + { + deleted_azimuths.push_back(iter->azimuth < 0.f ? 0.f : iter->azimuth); + deleted_distances.push_back(iter->distance); + noise_output->points.push_back(*iter); + break; + } + } } + } // Analyse last segment points here std::vector noise_frequency(horizontal_bins, 0); uint current_deleted_index = 0; From 2c3780444c16a2db5d352bc8759fd185109bf85b Mon Sep 17 00:00:00 2001 From: badai-nguyen Date: Thu, 3 Feb 2022 17:07:23 +0900 Subject: [PATCH 03/27] feat: add ROI-xyz setting and mode switching Signed-off-by: badai-nguyen --- .../dual_return_outlier_filter_nodelet.hpp | 6 +++ .../dual_return_outlier_filter_nodelet.cpp | 38 +++++++++++++++++-- 2 files changed, 41 insertions(+), 3 deletions(-) diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp index e83b3f630de4c..b29eb39e0d4d9 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp @@ -77,6 +77,12 @@ class DualReturnOutlierFilterComponent : public pointcloud_preprocessor::Filter uint weak_first_segment_check_size_v_; uint weak_first_segment_check_size_h_; uchar ROI_mode_; + float x_max_; + float x_min_; + float y_max_; + float y_min_; + float z_max_; + float z_min_; public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW diff --git a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp index e8edafba92d7a..8078b877a36ef 100644 --- a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp @@ -34,6 +34,12 @@ DualReturnOutlierFilterComponent::DualReturnOutlierFilterComponent( { // set initial parameters { + x_max_ = static_cast(declare_parameter("x_max", 18.0)); + x_min_ = static_cast(declare_parameter("x_min", -12.0)); + y_max_ = static_cast(declare_parameter("y_max", 2.0)); + y_min_ = static_cast(declare_parameter("y_min", -2.0)); + z_max_ = static_cast(declare_parameter("z_max", 10.0)); + z_min_ = static_cast(declare_parameter("z_min", 0.0)); vertical_bins_ = static_cast(declare_parameter("vertical_bins", 128)); max_azimuth_diff_ = static_cast(declare_parameter("max_azimuth_diff", 50.0)); weak_first_distance_ratio_ = @@ -221,6 +227,14 @@ void DualReturnOutlierFilterComponent::filter( noise_output->points.push_back(*iter);} break; } + case 2: //base_link xyz-ROI + { + if (iter->x > x_min_ && iter->x < x_max_ && iter->y > y_min_ && iter->y < y_max_ && iter->z > z_min_ && iter->z < z_max_){ + deleted_azimuths.push_back(iter->azimuth < 0.f ? 0.f : iter->azimuth); + deleted_distances.push_back(iter->distance); + noise_output->points.push_back(*iter);} + break; + } default: { deleted_azimuths.push_back(iter->azimuth < 0.f ? 0.f : iter->azimuth); @@ -245,9 +259,8 @@ void DualReturnOutlierFilterComponent::filter( noise_frequency[i] = noise_frequency[i] + 1; current_deleted_index++; } - if (temp_segment.points.size() == 0) { - continue; - } + if (temp_segment.points.size() > 0) { + while ((temp_segment.points[current_temp_segment_index].azimuth < 0.f ? 0.f : temp_segment.points[current_temp_segment_index].azimuth) < @@ -256,12 +269,31 @@ void DualReturnOutlierFilterComponent::filter( if (noise_frequency[i] < weak_first_local_noise_threshold_) { pcl_output->points.push_back(temp_segment.points[current_temp_segment_index]); } else { + switch (ROI_mode_) + { + case 2: + {if(temp_segment.points[current_temp_segment_index].x < x_max_ && + temp_segment.points[current_temp_segment_index].x > x_min_ && + temp_segment.points[current_temp_segment_index].y > y_max_ && + temp_segment.points[current_temp_segment_index].y < y_min_ && + temp_segment.points[current_temp_segment_index].z < z_max_ && + temp_segment.points[current_temp_segment_index].z > z_min_){ noise_frequency[i] = noise_frequency[i] + 1; noise_output->points.push_back(temp_segment.points[current_temp_segment_index]); + } + break; + } + default: { + noise_frequency[i] = noise_frequency[i] + 1; + noise_output->points.push_back(temp_segment.points[current_temp_segment_index]); + break; + } + } } current_temp_segment_index++; frequency_image.at(ring_id, i) = noise_frequency[i]; } + } } } From 242a25ffcbf827a9120639be88b5d336ac6cd48f Mon Sep 17 00:00:00 2001 From: badai-nguyen Date: Thu, 3 Feb 2022 17:16:32 +0900 Subject: [PATCH 04/27] feat: add ROI-azimuth setting and mode switching Signed-off-by: badai-nguyen --- .../dual_return_outlier_filter_nodelet.hpp | 3 ++ .../dual_return_outlier_filter_nodelet.cpp | 44 ++++++++++++++++++- 2 files changed, 45 insertions(+), 2 deletions(-) diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp index b29eb39e0d4d9..39889bf65f790 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp @@ -84,6 +84,9 @@ class DualReturnOutlierFilterComponent : public pointcloud_preprocessor::Filter float z_max_; float z_min_; + float min_azimuth_; + float max_azimuth_; + float max_distance_; public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW explicit DualReturnOutlierFilterComponent(const rclcpp::NodeOptions & options); diff --git a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp index 8078b877a36ef..07cdbf27a127a 100644 --- a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp @@ -40,6 +40,9 @@ DualReturnOutlierFilterComponent::DualReturnOutlierFilterComponent( y_min_ = static_cast(declare_parameter("y_min", -2.0)); z_max_ = static_cast(declare_parameter("z_max", 10.0)); z_min_ = static_cast(declare_parameter("z_min", 0.0)); + min_azimuth_ = static_cast(declare_parameter("min_azimuth",13500.0)); + max_azimuth_ = static_cast(declare_parameter("max_azimuth", 22500.0)); + max_distance_ = static_cast(declare_parameter("max_distance",12.0)); vertical_bins_ = static_cast(declare_parameter("vertical_bins", 128)); max_azimuth_diff_ = static_cast(declare_parameter("max_azimuth_diff", 50.0)); weak_first_distance_ratio_ = @@ -105,6 +108,26 @@ void DualReturnOutlierFilterComponent::filter( uint32_t vertical_bins = vertical_bins_; uint32_t horizontal_bins = 36; + float max_azimuth = 36000.0f; + float min_azimuth = 0; + switch (ROI_mode_) + { + case 3: + { + max_azimuth = max_azimuth_; + min_azimuth = min_azimuth_; + break; + } + + default: + { + max_azimuth = 36000.0f; + min_azimuth = 0.0f; + break; + } + } + + uint32_t horizontal_res = static_cast ((max_azimuth - min_azimuth)/horizontal_bins); pcl::PointCloud::Ptr pcl_output( new pcl::PointCloud); @@ -235,6 +258,14 @@ void DualReturnOutlierFilterComponent::filter( noise_output->points.push_back(*iter);} break; } + case 3: + { + + if (iter->azimuth > min_azimuth && iter->azimuth < max_azimuth && iter->distance < max_distance_){ + deleted_azimuths.push_back(iter->azimuth < 0.f ? 0.f : iter->azimuth); + noise_output->points.push_back(*iter); + deleted_distances.push_back(iter->distance);} + break; default: { deleted_azimuths.push_back(iter->azimuth < 0.f ? 0.f : iter->azimuth); @@ -254,7 +285,7 @@ void DualReturnOutlierFilterComponent::filter( continue; } while ((uint)deleted_azimuths[current_deleted_index] < - ((i + 1) * (36000 / horizontal_bins)) && + ((i + static_cast(min_azimuth/horizontal_res) + 1) * horizontal_res) && current_deleted_index < (deleted_azimuths.size() - 1)) { noise_frequency[i] = noise_frequency[i] + 1; current_deleted_index++; @@ -264,7 +295,7 @@ void DualReturnOutlierFilterComponent::filter( while ((temp_segment.points[current_temp_segment_index].azimuth < 0.f ? 0.f : temp_segment.points[current_temp_segment_index].azimuth) < - ((i + 1) * (36000 / horizontal_bins)) && + ((i + 1 + static_cast(min_azimuth/horizontal_res)) * horizontal_res) && current_temp_segment_index < (temp_segment.points.size() - 1)) { if (noise_frequency[i] < weak_first_local_noise_threshold_) { pcl_output->points.push_back(temp_segment.points[current_temp_segment_index]); @@ -283,6 +314,15 @@ void DualReturnOutlierFilterComponent::filter( } break; } + case 3: + { + if(temp_segment.points[current_temp_segment_index].azimuth < max_azimuth && + temp_segment.points[current_temp_segment_index].azimuth > min_azimuth && + temp_segment.points[current_temp_segment_index].distance < max_distance_){ + noise_frequency[i] = noise_frequency[i] + 1; + noise_output->points.push_back(temp_segment.points[current_temp_segment_index]);} + break; + } default: { noise_frequency[i] = noise_frequency[i] + 1; noise_output->points.push_back(temp_segment.points[current_temp_segment_index]); From 7d346b2a9bc63545c766d3e0b2f4ce3f7c2fe093 Mon Sep 17 00:00:00 2001 From: badai-nguyen Date: Thu, 3 Feb 2022 17:22:34 +0900 Subject: [PATCH 05/27] fix: frequency_image header Signed-off-by: badai-nguyen --- .../src/outlier_filter/dual_return_outlier_filter_nodelet.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp index 07cdbf27a127a..0af2624be489c 100644 --- a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp @@ -385,7 +385,7 @@ void DualReturnOutlierFilterComponent::filter( cv::applyColorMap(frequency_image * 4, frequency_image_colorized, cv::COLORMAP_JET); sensor_msgs::msg::Image::SharedPtr frequency_image_msg = cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", frequency_image_colorized).toImageMsg(); - + frequency_image_msg->header = input->header; // Publish histogram image image_pub_.publish(frequency_image_msg); tier4_debug_msgs::msg::Float32Stamped visibility_msg; From 40ba01384395981b346dc309222f67c1a6c4f0f3 Mon Sep 17 00:00:00 2001 From: badai-nguyen Date: Thu, 3 Feb 2022 17:23:23 +0900 Subject: [PATCH 06/27] fix: update frequency image issue Signed-off-by: badai-nguyen --- .../src/outlier_filter/dual_return_outlier_filter_nodelet.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp index 0af2624be489c..1a3fc511ee085 100644 --- a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp @@ -170,7 +170,7 @@ void DualReturnOutlierFilterComponent::filter( if (weak_first_single_ring.points.size() < 2) { continue; } - std::vector deleted_azimuths; + std::vector deleted_azimuths; std::vector deleted_distances; pcl::PointCloud temp_segment; @@ -334,6 +334,7 @@ void DualReturnOutlierFilterComponent::filter( frequency_image.at(ring_id, i) = noise_frequency[i]; } } + frequency_image.at(ring_id, i) = noise_frequency[i]; } } From e88f21d7e170337985030a431398ba293f2fc9aa Mon Sep 17 00:00:00 2001 From: badai-nguyen Date: Thu, 3 Feb 2022 17:31:04 +0900 Subject: [PATCH 07/27] fix: typo Signed-off-by: badai-nguyen --- .../src/outlier_filter/dual_return_outlier_filter_nodelet.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp index 1a3fc511ee085..420aca78230d0 100644 --- a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp @@ -53,7 +53,7 @@ DualReturnOutlierFilterComponent::DualReturnOutlierFilterComponent( weak_first_local_noise_threshold_ = static_cast(declare_parameter("weak_first_local_noise_threshold", 10)); visibility_threshold_ = static_cast(declare_parameter("visibility_threshold", 0.5)); - ROI_mode_ = static_cast(declare_parameter("ROI_mode",0))azimuth_steps; + ROI_mode_ = static_cast(declare_parameter("ROI_mode",0)); weak_first_segment_check_size_h_ = static_cast(declare_parameter("weak_first_segment_check_size_h",30)); weak_first_segment_check_size_v_ = static_cast(declare_parameter("weak_first_segment_check_size_v",3)); } From dd129eb22db479f025f7e68acdcf92fb2bdb6802 Mon Sep 17 00:00:00 2001 From: badai-nguyen Date: Thu, 3 Feb 2022 18:31:16 +0900 Subject: [PATCH 08/27] fix: typo Signed-off-by: badai-nguyen --- .../dual_return_outlier_filter_nodelet.cpp | 20 ++++++++++--------- 1 file changed, 11 insertions(+), 9 deletions(-) diff --git a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp index 420aca78230d0..55c82e402f2aa 100644 --- a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp @@ -266,6 +266,7 @@ void DualReturnOutlierFilterComponent::filter( noise_output->points.push_back(*iter); deleted_distances.push_back(iter->distance);} break; + } default: { deleted_azimuths.push_back(iter->azimuth < 0.f ? 0.f : iter->azimuth); @@ -274,8 +275,8 @@ void DualReturnOutlierFilterComponent::filter( break; } } + } } - } // Analyse last segment points here std::vector noise_frequency(horizontal_bins, 0); uint current_deleted_index = 0; @@ -303,17 +304,18 @@ void DualReturnOutlierFilterComponent::filter( switch (ROI_mode_) { case 2: - {if(temp_segment.points[current_temp_segment_index].x < x_max_ && + { + if(temp_segment.points[current_temp_segment_index].x < x_max_ && temp_segment.points[current_temp_segment_index].x > x_min_ && temp_segment.points[current_temp_segment_index].y > y_max_ && temp_segment.points[current_temp_segment_index].y < y_min_ && temp_segment.points[current_temp_segment_index].z < z_max_ && temp_segment.points[current_temp_segment_index].z > z_min_){ - noise_frequency[i] = noise_frequency[i] + 1; - noise_output->points.push_back(temp_segment.points[current_temp_segment_index]); - } - break; + noise_frequency[i] = noise_frequency[i] + 1; + noise_output->points.push_back(temp_segment.points[current_temp_segment_index]); } + break; + } case 3: { if(temp_segment.points[current_temp_segment_index].azimuth < max_azimuth && @@ -323,7 +325,8 @@ void DualReturnOutlierFilterComponent::filter( noise_output->points.push_back(temp_segment.points[current_temp_segment_index]);} break; } - default: { + default: + { noise_frequency[i] = noise_frequency[i] + 1; noise_output->points.push_back(temp_segment.points[current_temp_segment_index]); break; @@ -331,10 +334,9 @@ void DualReturnOutlierFilterComponent::filter( } } current_temp_segment_index++; - frequency_image.at(ring_id, i) = noise_frequency[i]; } } - frequency_image.at(ring_id, i) = noise_frequency[i]; + frequency_image.at(ring_id, i) = noise_frequency[i]; } } From 36725ff23dc511771265f33bb4a4eec94d85c8c8 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Thu, 3 Feb 2022 14:16:38 +0000 Subject: [PATCH 09/27] ci(pre-commit): autofix --- .../dual_return_outlier_filter_nodelet.hpp | 1 + .../dual_return_outlier_filter_nodelet.cpp | 278 +++++++++--------- 2 files changed, 144 insertions(+), 135 deletions(-) diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp index 39889bf65f790..cab8c5feed409 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp @@ -87,6 +87,7 @@ class DualReturnOutlierFilterComponent : public pointcloud_preprocessor::Filter float min_azimuth_; float max_azimuth_; float max_distance_; + public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW explicit DualReturnOutlierFilterComponent(const rclcpp::NodeOptions & options); diff --git a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp index 55c82e402f2aa..7db3cdb6abc25 100644 --- a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp @@ -40,9 +40,9 @@ DualReturnOutlierFilterComponent::DualReturnOutlierFilterComponent( y_min_ = static_cast(declare_parameter("y_min", -2.0)); z_max_ = static_cast(declare_parameter("z_max", 10.0)); z_min_ = static_cast(declare_parameter("z_min", 0.0)); - min_azimuth_ = static_cast(declare_parameter("min_azimuth",13500.0)); + min_azimuth_ = static_cast(declare_parameter("min_azimuth", 13500.0)); max_azimuth_ = static_cast(declare_parameter("max_azimuth", 22500.0)); - max_distance_ = static_cast(declare_parameter("max_distance",12.0)); + max_distance_ = static_cast(declare_parameter("max_distance", 12.0)); vertical_bins_ = static_cast(declare_parameter("vertical_bins", 128)); max_azimuth_diff_ = static_cast(declare_parameter("max_azimuth_diff", 50.0)); weak_first_distance_ratio_ = @@ -53,9 +53,11 @@ DualReturnOutlierFilterComponent::DualReturnOutlierFilterComponent( weak_first_local_noise_threshold_ = static_cast(declare_parameter("weak_first_local_noise_threshold", 10)); visibility_threshold_ = static_cast(declare_parameter("visibility_threshold", 0.5)); - ROI_mode_ = static_cast(declare_parameter("ROI_mode",0)); - weak_first_segment_check_size_h_ = static_cast(declare_parameter("weak_first_segment_check_size_h",30)); - weak_first_segment_check_size_v_ = static_cast(declare_parameter("weak_first_segment_check_size_v",3)); + ROI_mode_ = static_cast(declare_parameter("ROI_mode", 0)); + weak_first_segment_check_size_h_ = + static_cast(declare_parameter("weak_first_segment_check_size_h", 30)); + weak_first_segment_check_size_v_ = + static_cast(declare_parameter("weak_first_segment_check_size_v", 3)); } updater_.setHardwareID("dual_return_outlier_filter"); updater_.add( @@ -110,24 +112,21 @@ void DualReturnOutlierFilterComponent::filter( uint32_t horizontal_bins = 36; float max_azimuth = 36000.0f; float min_azimuth = 0; - switch (ROI_mode_) - { - case 3: - { + switch (ROI_mode_) { + case 3: { max_azimuth = max_azimuth_; min_azimuth = min_azimuth_; - break; + break; } - - default: - { + + default: { max_azimuth = 36000.0f; min_azimuth = 0.0f; - break; + break; } } - uint32_t horizontal_res = static_cast ((max_azimuth - min_azimuth)/horizontal_bins); + uint32_t horizontal_res = static_cast((max_azimuth - min_azimuth) / horizontal_bins); pcl::PointCloud::Ptr pcl_output( new pcl::PointCloud); @@ -147,7 +146,7 @@ void DualReturnOutlierFilterComponent::filter( const uint azimuth_steps = 36000; float * distance_inputpcl_array = new float[ring_number * azimuth_steps]; float * distance_weakfirstpcl_array = new float[ring_number * azimuth_steps]; - for (uint i = 0; i < ring_number * azimuth_steps; i++){ + for (uint i = 0; i < ring_number * azimuth_steps; i++) { distance_inputpcl_array[i] = -1.0f; distance_weakfirstpcl_array[i] = -1.0f; } @@ -156,10 +155,10 @@ void DualReturnOutlierFilterComponent::filter( uint azimuth_ind = static_cast(p.azimuth < 0.0f ? p.azimuth + 36000.0f : p.azimuth); if (p.return_type == ReturnType::DUAL_WEAK_FIRST) { weak_first_pcl_input_ring_array.at(p.ring).push_back(p); - distance_weakfirstpcl_array[p.ring*azimuth_steps + azimuth_ind] = p.distance; + distance_weakfirstpcl_array[p.ring * azimuth_steps + azimuth_ind] = p.distance; } else { pcl_input_ring_array.at(p.ring).push_back(p); - distance_inputpcl_array[p.ring * azimuth_steps +azimuth_ind] = p.distance; + distance_inputpcl_array[p.ring * azimuth_steps + azimuth_ind] = p.distance; } } @@ -178,37 +177,43 @@ void DualReturnOutlierFilterComponent::filter( uint ring_id = weak_first_single_ring.points.front().ring; for (auto iter = std::begin(weak_first_single_ring) + 1; iter != std::end(weak_first_single_ring) - 1; ++iter) { - uint azimuth_id = static_cast (iter->azimuth); - uint segment_check = 0, segment_check_thresh = 2; + uint azimuth_id = static_cast(iter->azimuth); + uint segment_check = 0, segment_check_thresh = 2; uint weakfirst_ring_min = 0, weakfirst_ring_max = ring_number; uint weakfirst_w_min = 0, weakfirst_w_max = azimuth_steps; - - weakfirst_ring_min = ring_id > weak_first_segment_check_size_v_ ? - ring_id - weak_first_segment_check_size_v_ : 0; - weakfirst_ring_max = ring_id + weak_first_segment_check_size_v_ < ring_number ? - ring_id + weak_first_segment_check_size_v_ + 1: ring_number; - weakfirst_w_min = azimuth_id > weak_first_segment_check_size_h_ ? - azimuth_id - weak_first_segment_check_size_h_ : 0; - weakfirst_w_max = azimuth_id + weak_first_segment_check_size_h_ < azimuth_steps ? - azimuth_id + weak_first_segment_check_size_h_ +1 : azimuth_steps; - - for ( auto i = weakfirst_ring_min; i < weakfirst_ring_max; i++){ - for (auto j = weakfirst_w_min; j < weakfirst_w_max; j++){ - if(distance_weakfirstpcl_array[i*azimuth_steps + j] > 0.0){ - const float min_dist = std::min(iter->distance, distance_weakfirstpcl_array[i*azimuth_steps + j]); - const float max_dist = std::max(iter->distance, distance_weakfirstpcl_array[i* azimuth_steps + j]); - float azimuth_diff = (iter + 1)->azimuth - iter->azimuth; - azimuth_diff = azimuth_diff < 0.f ? azimuth_diff + 36000.f : azimuth_diff; - if (max_dist < min_dist * weak_first_distance_ratio_){ - segment_check++; + weakfirst_ring_min = + ring_id > weak_first_segment_check_size_v_ ? ring_id - weak_first_segment_check_size_v_ : 0; + weakfirst_ring_max = ring_id + weak_first_segment_check_size_v_ < ring_number + ? ring_id + weak_first_segment_check_size_v_ + 1 + : ring_number; + weakfirst_w_min = azimuth_id > weak_first_segment_check_size_h_ + ? azimuth_id - weak_first_segment_check_size_h_ + : 0; + weakfirst_w_max = azimuth_id + weak_first_segment_check_size_h_ < azimuth_steps + ? azimuth_id + weak_first_segment_check_size_h_ + 1 + : azimuth_steps; + + for (auto i = weakfirst_ring_min; i < weakfirst_ring_max; i++) { + for (auto j = weakfirst_w_min; j < weakfirst_w_max; j++) { + if (distance_weakfirstpcl_array[i * azimuth_steps + j] > 0.0) { + const float min_dist = + std::min(iter->distance, distance_weakfirstpcl_array[i * azimuth_steps + j]); + const float max_dist = + std::max(iter->distance, distance_weakfirstpcl_array[i * azimuth_steps + j]); + float azimuth_diff = (iter + 1)->azimuth - iter->azimuth; + azimuth_diff = azimuth_diff < 0.f ? azimuth_diff + 36000.f : azimuth_diff; + + if (max_dist < min_dist * weak_first_distance_ratio_) { + segment_check++; + } } + if (segment_check >= segment_check_thresh) { + goto exit_segment_check; } - if (segment_check >= segment_check_thresh ){ - goto exit_segment_check;} } } - exit_segment_check: + exit_segment_check: if (segment_check >= segment_check_thresh) { temp_segment.points.push_back(*iter); @@ -219,60 +224,65 @@ void DualReturnOutlierFilterComponent::filter( // Analyse segment points here } else { // Log the deleted azimuth and its distance for analysis - switch (ROI_mode_) - { - case 1: //dynamic ROI free space - { - // check surrounding normal pcl - uint neighbor_check = 0, h_range = 3, w_range = 10; - uint min_h = 0, max_h = ring_number; - uint min_w = 0, max_w = azimuth_steps; - min_h = iter->ring > h_range ? iter->ring - h_range : 0; - max_h = iter->ring < ring_number - h_range ? iter->ring + h_range : ring_number; - - min_w = azimuth_id > w_range ? azimuth_id - w_range : 0; - max_w = azimuth_id < azimuth_steps - w_range ? azimuth_id + w_range : azimuth_steps; - for (auto i = min_h ; i < max_h; i++){ - for (auto j = min_w ; j < max_w; j++){ - if((distance_inputpcl_array[i*azimuth_steps + j] > 0.0f) && (iter->distance > - (distance_inputpcl_array[i*azimuth_steps + j] - neighbor_r_thresh_))){ - neighbor_check++; - } - if (neighbor_check > 1){ - goto exit_neighbor_check; + switch (ROI_mode_) { + case 1: // dynamic ROI free space + { + // check surrounding normal pcl + uint neighbor_check = 0, h_range = 3, w_range = 10; + uint min_h = 0, max_h = ring_number; + uint min_w = 0, max_w = azimuth_steps; + min_h = iter->ring > h_range ? iter->ring - h_range : 0; + max_h = iter->ring < ring_number - h_range ? iter->ring + h_range : ring_number; + + min_w = azimuth_id > w_range ? azimuth_id - w_range : 0; + max_w = azimuth_id < azimuth_steps - w_range ? azimuth_id + w_range : azimuth_steps; + for (auto i = min_h; i < max_h; i++) { + for (auto j = min_w; j < max_w; j++) { + if ( + (distance_inputpcl_array[i * azimuth_steps + j] > 0.0f) && + (iter->distance > + (distance_inputpcl_array[i * azimuth_steps + j] - neighbor_r_thresh_))) { + neighbor_check++; + } + if (neighbor_check > 1) { + goto exit_neighbor_check; + } } } - } exit_neighbor_check: - if(neighbor_check < 2){ - deleted_azimuths.push_back(iter->azimuth < 0.f ? 0.f : iter->azimuth); - deleted_distances.push_back(iter->distance); - noise_output->points.push_back(*iter);} - break; - } - case 2: //base_link xyz-ROI - { - if (iter->x > x_min_ && iter->x < x_max_ && iter->y > y_min_ && iter->y < y_max_ && iter->z > z_min_ && iter->z < z_max_){ - deleted_azimuths.push_back(iter->azimuth < 0.f ? 0.f : iter->azimuth); - deleted_distances.push_back(iter->distance); - noise_output->points.push_back(*iter);} - break; - } - case 3: - { - - if (iter->azimuth > min_azimuth && iter->azimuth < max_azimuth && iter->distance < max_distance_){ - deleted_azimuths.push_back(iter->azimuth < 0.f ? 0.f : iter->azimuth); - noise_output->points.push_back(*iter); - deleted_distances.push_back(iter->distance);} - break; - } - default: + if (neighbor_check < 2) { + deleted_azimuths.push_back(iter->azimuth < 0.f ? 0.f : iter->azimuth); + deleted_distances.push_back(iter->distance); + noise_output->points.push_back(*iter); + } + break; + } + case 2: // base_link xyz-ROI { - deleted_azimuths.push_back(iter->azimuth < 0.f ? 0.f : iter->azimuth); - deleted_distances.push_back(iter->distance); - noise_output->points.push_back(*iter); - break; + if ( + iter->x > x_min_ && iter->x < x_max_ && iter->y > y_min_ && iter->y < y_max_ && + iter->z > z_min_ && iter->z < z_max_) { + deleted_azimuths.push_back(iter->azimuth < 0.f ? 0.f : iter->azimuth); + deleted_distances.push_back(iter->distance); + noise_output->points.push_back(*iter); + } + break; + } + case 3: { + if ( + iter->azimuth > min_azimuth && iter->azimuth < max_azimuth && + iter->distance < max_distance_) { + deleted_azimuths.push_back(iter->azimuth < 0.f ? 0.f : iter->azimuth); + noise_output->points.push_back(*iter); + deleted_distances.push_back(iter->distance); + } + break; + } + default: { + deleted_azimuths.push_back(iter->azimuth < 0.f ? 0.f : iter->azimuth); + deleted_distances.push_back(iter->distance); + noise_output->points.push_back(*iter); + break; } } } @@ -286,55 +296,53 @@ void DualReturnOutlierFilterComponent::filter( continue; } while ((uint)deleted_azimuths[current_deleted_index] < - ((i + static_cast(min_azimuth/horizontal_res) + 1) * horizontal_res) && + ((i + static_cast(min_azimuth / horizontal_res) + 1) * horizontal_res) && current_deleted_index < (deleted_azimuths.size() - 1)) { noise_frequency[i] = noise_frequency[i] + 1; current_deleted_index++; } if (temp_segment.points.size() > 0) { - - while ((temp_segment.points[current_temp_segment_index].azimuth < 0.f - ? 0.f - : temp_segment.points[current_temp_segment_index].azimuth) < - ((i + 1 + static_cast(min_azimuth/horizontal_res)) * horizontal_res) && - current_temp_segment_index < (temp_segment.points.size() - 1)) { - if (noise_frequency[i] < weak_first_local_noise_threshold_) { - pcl_output->points.push_back(temp_segment.points[current_temp_segment_index]); - } else { - switch (ROI_mode_) - { - case 2: - { - if(temp_segment.points[current_temp_segment_index].x < x_max_ && - temp_segment.points[current_temp_segment_index].x > x_min_ && - temp_segment.points[current_temp_segment_index].y > y_max_ && - temp_segment.points[current_temp_segment_index].y < y_min_ && - temp_segment.points[current_temp_segment_index].z < z_max_ && - temp_segment.points[current_temp_segment_index].z > z_min_){ - noise_frequency[i] = noise_frequency[i] + 1; - noise_output->points.push_back(temp_segment.points[current_temp_segment_index]); + while ((temp_segment.points[current_temp_segment_index].azimuth < 0.f + ? 0.f + : temp_segment.points[current_temp_segment_index].azimuth) < + ((i + 1 + static_cast(min_azimuth / horizontal_res)) * horizontal_res) && + current_temp_segment_index < (temp_segment.points.size() - 1)) { + if (noise_frequency[i] < weak_first_local_noise_threshold_) { + pcl_output->points.push_back(temp_segment.points[current_temp_segment_index]); + } else { + switch (ROI_mode_) { + case 2: { + if ( + temp_segment.points[current_temp_segment_index].x < x_max_ && + temp_segment.points[current_temp_segment_index].x > x_min_ && + temp_segment.points[current_temp_segment_index].y > y_max_ && + temp_segment.points[current_temp_segment_index].y < y_min_ && + temp_segment.points[current_temp_segment_index].z < z_max_ && + temp_segment.points[current_temp_segment_index].z > z_min_) { + noise_frequency[i] = noise_frequency[i] + 1; + noise_output->points.push_back(temp_segment.points[current_temp_segment_index]); + } + break; + } + case 3: { + if ( + temp_segment.points[current_temp_segment_index].azimuth < max_azimuth && + temp_segment.points[current_temp_segment_index].azimuth > min_azimuth && + temp_segment.points[current_temp_segment_index].distance < max_distance_) { + noise_frequency[i] = noise_frequency[i] + 1; + noise_output->points.push_back(temp_segment.points[current_temp_segment_index]); + } + break; + } + default: { + noise_frequency[i] = noise_frequency[i] + 1; + noise_output->points.push_back(temp_segment.points[current_temp_segment_index]); + break; + } } - break; - } - case 3: - { - if(temp_segment.points[current_temp_segment_index].azimuth < max_azimuth && - temp_segment.points[current_temp_segment_index].azimuth > min_azimuth && - temp_segment.points[current_temp_segment_index].distance < max_distance_){ - noise_frequency[i] = noise_frequency[i] + 1; - noise_output->points.push_back(temp_segment.points[current_temp_segment_index]);} - break; - } - default: - { - noise_frequency[i] = noise_frequency[i] + 1; - noise_output->points.push_back(temp_segment.points[current_temp_segment_index]); - break; - } } + current_temp_segment_index++; } - current_temp_segment_index++; - } } frequency_image.at(ring_id, i) = noise_frequency[i]; } @@ -373,8 +381,8 @@ void DualReturnOutlierFilterComponent::filter( } } - delete [] distance_inputpcl_array; - delete [] distance_weakfirstpcl_array; + delete[] distance_inputpcl_array; + delete[] distance_weakfirstpcl_array; // Threshold for diagnostics (tunable) cv::Mat binary_image; cv::inRange(frequency_image, weak_first_local_noise_threshold_, 255, binary_image); From 7122a4c1617ea0c1a9d7e3d41f25c5556242e245 Mon Sep 17 00:00:00 2001 From: badai-nguyen Date: Fri, 4 Feb 2022 09:58:49 +0900 Subject: [PATCH 10/27] fix: typo Signed-off-by: badai-nguyen --- .../dual_return_outlier_filter_nodelet.cpp | 26 +++++++++---------- 1 file changed, 13 insertions(+), 13 deletions(-) diff --git a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp index 7db3cdb6abc25..40b7abd2c0d74 100644 --- a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp @@ -144,21 +144,21 @@ void DualReturnOutlierFilterComponent::filter( const uint ring_number = vertical_bins; const uint azimuth_steps = 36000; - float * distance_inputpcl_array = new float[ring_number * azimuth_steps]; - float * distance_weakfirstpcl_array = new float[ring_number * azimuth_steps]; + float * pcl_input_distance_array = new float[ring_number * azimuth_steps]; + float * pcl_weak_first_distance_array = new float[ring_number * azimuth_steps]; for (uint i = 0; i < ring_number * azimuth_steps; i++) { - distance_inputpcl_array[i] = -1.0f; - distance_weakfirstpcl_array[i] = -1.0f; + pcl_input_distance_array[i] = -1.0f; + pcl_weak_first_distance_array[i] = -1.0f; } // Split into 36 x 10 degree bins x 40 lines (TODO: change to dynamic) for (const auto & p : pcl_input->points) { uint azimuth_ind = static_cast(p.azimuth < 0.0f ? p.azimuth + 36000.0f : p.azimuth); if (p.return_type == ReturnType::DUAL_WEAK_FIRST) { weak_first_pcl_input_ring_array.at(p.ring).push_back(p); - distance_weakfirstpcl_array[p.ring * azimuth_steps + azimuth_ind] = p.distance; + pcl_weak_first_distance_array[p.ring * azimuth_steps + azimuth_ind] = p.distance; } else { pcl_input_ring_array.at(p.ring).push_back(p); - distance_inputpcl_array[p.ring * azimuth_steps + azimuth_ind] = p.distance; + pcl_input_distance_array[p.ring * azimuth_steps + azimuth_ind] = p.distance; } } @@ -196,11 +196,11 @@ void DualReturnOutlierFilterComponent::filter( for (auto i = weakfirst_ring_min; i < weakfirst_ring_max; i++) { for (auto j = weakfirst_w_min; j < weakfirst_w_max; j++) { - if (distance_weakfirstpcl_array[i * azimuth_steps + j] > 0.0) { + if (pcl_weak_first_distance_array[i * azimuth_steps + j] > 0.0) { const float min_dist = - std::min(iter->distance, distance_weakfirstpcl_array[i * azimuth_steps + j]); + std::min(iter->distance, pcl_weak_first_distance_array[i * azimuth_steps + j]); const float max_dist = - std::max(iter->distance, distance_weakfirstpcl_array[i * azimuth_steps + j]); + std::max(iter->distance, pcl_weak_first_distance_array[i * azimuth_steps + j]); float azimuth_diff = (iter + 1)->azimuth - iter->azimuth; azimuth_diff = azimuth_diff < 0.f ? azimuth_diff + 36000.f : azimuth_diff; @@ -239,9 +239,9 @@ void DualReturnOutlierFilterComponent::filter( for (auto i = min_h; i < max_h; i++) { for (auto j = min_w; j < max_w; j++) { if ( - (distance_inputpcl_array[i * azimuth_steps + j] > 0.0f) && + (pcl_input_distance_array[i * azimuth_steps + j] > 0.0f) && (iter->distance > - (distance_inputpcl_array[i * azimuth_steps + j] - neighbor_r_thresh_))) { + (pcl_input_distance_array[i * azimuth_steps + j] - neighbor_r_thresh_))) { neighbor_check++; } if (neighbor_check > 1) { @@ -381,8 +381,8 @@ void DualReturnOutlierFilterComponent::filter( } } - delete[] distance_inputpcl_array; - delete[] distance_weakfirstpcl_array; + delete[] pcl_input_distance_array; + delete[] pcl_weak_first_distance_array; // Threshold for diagnostics (tunable) cv::Mat binary_image; cv::inRange(frequency_image, weak_first_local_noise_threshold_, 255, binary_image); From 99b6df0f4655aaf7f25624e47925f05f2af65ccb Mon Sep 17 00:00:00 2001 From: badai-nguyen Date: Tue, 8 Feb 2022 09:38:51 +0900 Subject: [PATCH 11/27] fix: typo Signed-off-by: badai-nguyen --- .../dual_return_outlier_filter_nodelet.cpp | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp index 40b7abd2c0d74..594e8cdb3d79a 100644 --- a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp @@ -179,23 +179,23 @@ void DualReturnOutlierFilterComponent::filter( iter != std::end(weak_first_single_ring) - 1; ++iter) { uint azimuth_id = static_cast(iter->azimuth); uint segment_check = 0, segment_check_thresh = 2; - uint weakfirst_ring_min = 0, weakfirst_ring_max = ring_number; - uint weakfirst_w_min = 0, weakfirst_w_max = azimuth_steps; + uint weak_first_ring_min = 0, weak_first_ring_max = ring_number; + uint weak_first_w_min = 0, weak_first_w_max = azimuth_steps; - weakfirst_ring_min = + weak_first_ring_min = ring_id > weak_first_segment_check_size_v_ ? ring_id - weak_first_segment_check_size_v_ : 0; - weakfirst_ring_max = ring_id + weak_first_segment_check_size_v_ < ring_number + weak_first_ring_max = ring_id + weak_first_segment_check_size_v_ < ring_number ? ring_id + weak_first_segment_check_size_v_ + 1 : ring_number; - weakfirst_w_min = azimuth_id > weak_first_segment_check_size_h_ + weak_first_w_min = azimuth_id > weak_first_segment_check_size_h_ ? azimuth_id - weak_first_segment_check_size_h_ : 0; - weakfirst_w_max = azimuth_id + weak_first_segment_check_size_h_ < azimuth_steps + weak_first_w_max = azimuth_id + weak_first_segment_check_size_h_ < azimuth_steps ? azimuth_id + weak_first_segment_check_size_h_ + 1 : azimuth_steps; - for (auto i = weakfirst_ring_min; i < weakfirst_ring_max; i++) { - for (auto j = weakfirst_w_min; j < weakfirst_w_max; j++) { + for (auto i = weak_first_ring_min; i < weak_first_ring_max; i++) { + for (auto j = weak_first_w_min; j < weak_first_w_max; j++) { if (pcl_weak_first_distance_array[i * azimuth_steps + j] > 0.0) { const float min_dist = std::min(iter->distance, pcl_weak_first_distance_array[i * azimuth_steps + j]); From 8cec26f7e471a4b448cfc3683eab3a6916a3e210 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 8 Feb 2022 00:39:58 +0000 Subject: [PATCH 12/27] ci(pre-commit): autofix --- .../dual_return_outlier_filter_nodelet.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp index 594e8cdb3d79a..55cf5e21240f8 100644 --- a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp @@ -185,14 +185,14 @@ void DualReturnOutlierFilterComponent::filter( weak_first_ring_min = ring_id > weak_first_segment_check_size_v_ ? ring_id - weak_first_segment_check_size_v_ : 0; weak_first_ring_max = ring_id + weak_first_segment_check_size_v_ < ring_number - ? ring_id + weak_first_segment_check_size_v_ + 1 - : ring_number; + ? ring_id + weak_first_segment_check_size_v_ + 1 + : ring_number; weak_first_w_min = azimuth_id > weak_first_segment_check_size_h_ - ? azimuth_id - weak_first_segment_check_size_h_ - : 0; + ? azimuth_id - weak_first_segment_check_size_h_ + : 0; weak_first_w_max = azimuth_id + weak_first_segment_check_size_h_ < azimuth_steps - ? azimuth_id + weak_first_segment_check_size_h_ + 1 - : azimuth_steps; + ? azimuth_id + weak_first_segment_check_size_h_ + 1 + : azimuth_steps; for (auto i = weak_first_ring_min; i < weak_first_ring_max; i++) { for (auto j = weak_first_w_min; j < weak_first_w_max; j++) { From f3c7ff6dfd2aa4384e1ba72d63d0e41003ecddcb Mon Sep 17 00:00:00 2001 From: badai-nguyen Date: Fri, 18 Feb 2022 14:56:26 +0900 Subject: [PATCH 13/27] fix: add normal pcl noise for visibility Signed-off-by: badai-nguyen --- .../dual_return_outlier_filter_nodelet.cpp | 50 +++++++++++++++++-- 1 file changed, 47 insertions(+), 3 deletions(-) diff --git a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp index 55cf5e21240f8..c18920b399e7b 100644 --- a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp @@ -111,7 +111,7 @@ void DualReturnOutlierFilterComponent::filter( uint32_t vertical_bins = vertical_bins_; uint32_t horizontal_bins = 36; float max_azimuth = 36000.0f; - float min_azimuth = 0; + float min_azimuth = 0.0f; switch (ROI_mode_) { case 3: { max_azimuth = max_azimuth_; @@ -353,10 +353,12 @@ void DualReturnOutlierFilterComponent::filter( if (input_ring.size() < 2) { continue; } + std::vector deleted_azimuths; pcl::PointCloud temp_segment; bool keep_next = false; - // uint ring_id = input_ring.points.front().ring; + uint16_t ring_id = input_ring.points.front().ring; for (auto iter = std::begin(input_ring) + 1; iter != std::end(input_ring) - 1; ++iter) { + // uint azimuth_id = static_cast(iter->azimuth); const float min_dist = std::min(iter->distance, (iter + 1)->distance); const float max_dist = std::max(iter->distance, (iter + 1)->distance); float azimuth_diff = (iter + 1)->azimuth - iter->azimuth; @@ -371,11 +373,53 @@ void DualReturnOutlierFilterComponent::filter( // Analyse segment points here } else { // Log the deleted azimuth and its distance for analysis - // deleted_azimuths.push_back(iter->azimuth < 0.f ? 0.f : iter->azimuth); + float non_neg_azimuth = iter->azimuth; + while(non_neg_azimuth < 0.0f){non_neg_azimuth += 36000.0f;} + switch (ROI_mode_) { + case 2: // base_link xyz-ROI + { + if ( + iter->x > x_min_ && iter->x < x_max_ && iter->y > y_min_ && iter->y < y_max_ && + iter->z > z_min_ && iter->z < z_max_) { + deleted_azimuths.push_back(non_neg_azimuth); + } + break; + } + case 3: { + if ( + non_neg_azimuth > min_azimuth && non_neg_azimuth < max_azimuth && + iter->distance < max_distance_) { + deleted_azimuths.push_back(non_neg_azimuth); + } + break; + } + default: { + if(iter->distance < 15.0f) + {deleted_azimuths.push_back(non_neg_azimuth);} + break; + } + } + // deleted_distances.push_back(iter->distance); noise_output->points.push_back(*iter); } } + std::vector noise_frequency(horizontal_bins, 0); + uint32_t current_deleted_index = 0; + // uint current_temp_segment_index = 0; + for (uint i = 0; i < noise_frequency.size() - 1; i++) { + if (deleted_azimuths.size() == 0) { + continue; + } + while ((uint)deleted_azimuths[current_deleted_index] < + ((i + static_cast(min_azimuth / horizontal_res) + 1) * horizontal_res) && + current_deleted_index < (deleted_azimuths.size() - 1)) { + noise_frequency[i] = noise_frequency[i] + 1; + current_deleted_index++; + } + if(noise_frequency[i] >0){ + frequency_image.at(ring_id, i) = frequency_image.at(ring_id, i) + noise_frequency[i];} + } for (const auto & tmp_p : temp_segment.points) { pcl_output->points.push_back(tmp_p); } From 450857e95098310aca92ea8e902f6c6b59530176 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Fri, 18 Feb 2022 05:59:01 +0000 Subject: [PATCH 14/27] ci(pre-commit): autofix --- .../dual_return_outlier_filter_nodelet.cpp | 17 +++++++++++------ 1 file changed, 11 insertions(+), 6 deletions(-) diff --git a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp index c18920b399e7b..ac650c130bc7c 100644 --- a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp @@ -374,7 +374,9 @@ void DualReturnOutlierFilterComponent::filter( } else { // Log the deleted azimuth and its distance for analysis float non_neg_azimuth = iter->azimuth; - while(non_neg_azimuth < 0.0f){non_neg_azimuth += 36000.0f;} + while (non_neg_azimuth < 0.0f) { + non_neg_azimuth += 36000.0f; + } switch (ROI_mode_) { case 2: // base_link xyz-ROI { @@ -394,12 +396,13 @@ void DualReturnOutlierFilterComponent::filter( break; } default: { - if(iter->distance < 15.0f) - {deleted_azimuths.push_back(non_neg_azimuth);} + if (iter->distance < 15.0f) { + deleted_azimuths.push_back(non_neg_azimuth); + } break; } } - + // deleted_distances.push_back(iter->distance); noise_output->points.push_back(*iter); } @@ -417,8 +420,10 @@ void DualReturnOutlierFilterComponent::filter( noise_frequency[i] = noise_frequency[i] + 1; current_deleted_index++; } - if(noise_frequency[i] >0){ - frequency_image.at(ring_id, i) = frequency_image.at(ring_id, i) + noise_frequency[i];} + if (noise_frequency[i] > 0) { + frequency_image.at(ring_id, i) = + frequency_image.at(ring_id, i) + noise_frequency[i]; + } } for (const auto & tmp_p : temp_segment.points) { pcl_output->points.push_back(tmp_p); From 29ee27727746a8c8993b664dd65ddadb8bd84306 Mon Sep 17 00:00:00 2001 From: badai-nguyen Date: Mon, 28 Feb 2022 13:34:55 +0900 Subject: [PATCH 15/27] fix: typo Signed-off-by: badai-nguyen --- .../dual_return_outlier_filter_nodelet.hpp | 15 +++++-- .../dual_return_outlier_filter_nodelet.cpp | 44 +++++++++---------- 2 files changed, 34 insertions(+), 25 deletions(-) diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp index cab8c5feed409..8466814824d48 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp @@ -31,6 +31,7 @@ #include #include +#include namespace pointcloud_preprocessor { @@ -48,6 +49,14 @@ enum ReturnType : uint8_t { DUAL_ONLY, }; +std::unordered_map roi_mode_map_ = +{ + {"No_ROI", 0}, + {"Dynamic_FreeSpace_ROI" , 1}, + {"Fixed_xyz_ROI" , 2}, + {"Fixed_azimuth_ROI" , 3}, +}; + class DualReturnOutlierFilterComponent : public pointcloud_preprocessor::Filter { protected: @@ -76,7 +85,7 @@ class DualReturnOutlierFilterComponent : public pointcloud_preprocessor::Filter float neighbor_r_thresh_ = 0.5f; uint weak_first_segment_check_size_v_; uint weak_first_segment_check_size_h_; - uchar ROI_mode_; + std::string roi_mode_; float x_max_; float x_min_; float y_max_; @@ -84,8 +93,8 @@ class DualReturnOutlierFilterComponent : public pointcloud_preprocessor::Filter float z_max_; float z_min_; - float min_azimuth_; - float max_azimuth_; + float min_azimuth_deg_; + float max_azimuth_deg_; float max_distance_; public: diff --git a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp index ac650c130bc7c..91409f26479d9 100644 --- a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp @@ -40,8 +40,8 @@ DualReturnOutlierFilterComponent::DualReturnOutlierFilterComponent( y_min_ = static_cast(declare_parameter("y_min", -2.0)); z_max_ = static_cast(declare_parameter("z_max", 10.0)); z_min_ = static_cast(declare_parameter("z_min", 0.0)); - min_azimuth_ = static_cast(declare_parameter("min_azimuth", 13500.0)); - max_azimuth_ = static_cast(declare_parameter("max_azimuth", 22500.0)); + min_azimuth_deg_ = static_cast(declare_parameter("min_azimuth_deg", 135.0)); + max_azimuth_deg_ = static_cast(declare_parameter("max_azimuth_deg", 225.0)); max_distance_ = static_cast(declare_parameter("max_distance", 12.0)); vertical_bins_ = static_cast(declare_parameter("vertical_bins", 128)); max_azimuth_diff_ = static_cast(declare_parameter("max_azimuth_diff", 50.0)); @@ -53,7 +53,7 @@ DualReturnOutlierFilterComponent::DualReturnOutlierFilterComponent( weak_first_local_noise_threshold_ = static_cast(declare_parameter("weak_first_local_noise_threshold", 10)); visibility_threshold_ = static_cast(declare_parameter("visibility_threshold", 0.5)); - ROI_mode_ = static_cast(declare_parameter("ROI_mode", 0)); + roi_mode_ = static_cast(declare_parameter("roi_mode", "Fixed_xyz_ROI")); weak_first_segment_check_size_h_ = static_cast(declare_parameter("weak_first_segment_check_size_h", 30)); weak_first_segment_check_size_v_ = @@ -112,10 +112,10 @@ void DualReturnOutlierFilterComponent::filter( uint32_t horizontal_bins = 36; float max_azimuth = 36000.0f; float min_azimuth = 0.0f; - switch (ROI_mode_) { + switch (roi_mode_map_[roi_mode_]) { case 3: { - max_azimuth = max_azimuth_; - min_azimuth = min_azimuth_; + max_azimuth = max_azimuth_deg_ * 100.0; + min_azimuth = min_azimuth_deg_ * 100.0; break; } @@ -144,21 +144,21 @@ void DualReturnOutlierFilterComponent::filter( const uint ring_number = vertical_bins; const uint azimuth_steps = 36000; - float * pcl_input_distance_array = new float[ring_number * azimuth_steps]; - float * pcl_weak_first_distance_array = new float[ring_number * azimuth_steps]; + float * strong_return_distance_array = new float[ring_number * azimuth_steps]; + float * weak_first_return_distance_array = new float[ring_number * azimuth_steps]; for (uint i = 0; i < ring_number * azimuth_steps; i++) { - pcl_input_distance_array[i] = -1.0f; - pcl_weak_first_distance_array[i] = -1.0f; + strong_return_distance_array[i] = -1.0f; + weak_first_return_distance_array[i] = -1.0f; } // Split into 36 x 10 degree bins x 40 lines (TODO: change to dynamic) for (const auto & p : pcl_input->points) { uint azimuth_ind = static_cast(p.azimuth < 0.0f ? p.azimuth + 36000.0f : p.azimuth); if (p.return_type == ReturnType::DUAL_WEAK_FIRST) { weak_first_pcl_input_ring_array.at(p.ring).push_back(p); - pcl_weak_first_distance_array[p.ring * azimuth_steps + azimuth_ind] = p.distance; + weak_first_return_distance_array[p.ring * azimuth_steps + azimuth_ind] = p.distance; } else { pcl_input_ring_array.at(p.ring).push_back(p); - pcl_input_distance_array[p.ring * azimuth_steps + azimuth_ind] = p.distance; + strong_return_distance_array[p.ring * azimuth_steps + azimuth_ind] = p.distance; } } @@ -196,11 +196,11 @@ void DualReturnOutlierFilterComponent::filter( for (auto i = weak_first_ring_min; i < weak_first_ring_max; i++) { for (auto j = weak_first_w_min; j < weak_first_w_max; j++) { - if (pcl_weak_first_distance_array[i * azimuth_steps + j] > 0.0) { + if (weak_first_return_distance_array[i * azimuth_steps + j] > 0.0) { const float min_dist = - std::min(iter->distance, pcl_weak_first_distance_array[i * azimuth_steps + j]); + std::min(iter->distance, weak_first_return_distance_array[i * azimuth_steps + j]); const float max_dist = - std::max(iter->distance, pcl_weak_first_distance_array[i * azimuth_steps + j]); + std::max(iter->distance, weak_first_return_distance_array[i * azimuth_steps + j]); float azimuth_diff = (iter + 1)->azimuth - iter->azimuth; azimuth_diff = azimuth_diff < 0.f ? azimuth_diff + 36000.f : azimuth_diff; @@ -224,7 +224,7 @@ void DualReturnOutlierFilterComponent::filter( // Analyse segment points here } else { // Log the deleted azimuth and its distance for analysis - switch (ROI_mode_) { + switch (roi_mode_map_[roi_mode_]) { case 1: // dynamic ROI free space { // check surrounding normal pcl @@ -239,9 +239,9 @@ void DualReturnOutlierFilterComponent::filter( for (auto i = min_h; i < max_h; i++) { for (auto j = min_w; j < max_w; j++) { if ( - (pcl_input_distance_array[i * azimuth_steps + j] > 0.0f) && + (strong_return_distance_array[i * azimuth_steps + j] > 0.0f) && (iter->distance > - (pcl_input_distance_array[i * azimuth_steps + j] - neighbor_r_thresh_))) { + (strong_return_distance_array[i * azimuth_steps + j] - neighbor_r_thresh_))) { neighbor_check++; } if (neighbor_check > 1) { @@ -310,7 +310,7 @@ void DualReturnOutlierFilterComponent::filter( if (noise_frequency[i] < weak_first_local_noise_threshold_) { pcl_output->points.push_back(temp_segment.points[current_temp_segment_index]); } else { - switch (ROI_mode_) { + switch (roi_mode_map_[roi_mode_]) { case 2: { if ( temp_segment.points[current_temp_segment_index].x < x_max_ && @@ -377,7 +377,7 @@ void DualReturnOutlierFilterComponent::filter( while (non_neg_azimuth < 0.0f) { non_neg_azimuth += 36000.0f; } - switch (ROI_mode_) { + switch (roi_mode_map_[roi_mode_]) { case 2: // base_link xyz-ROI { if ( @@ -430,8 +430,8 @@ void DualReturnOutlierFilterComponent::filter( } } - delete[] pcl_input_distance_array; - delete[] pcl_weak_first_distance_array; + delete[] strong_return_distance_array; + delete[] weak_first_return_distance_array; // Threshold for diagnostics (tunable) cv::Mat binary_image; cv::inRange(frequency_image, weak_first_local_noise_threshold_, 255, binary_image); From bc6ba3fa9e3bc08758301e72e83afd7225122ce2 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Mon, 28 Feb 2022 05:32:36 +0000 Subject: [PATCH 16/27] ci(pre-commit): autofix --- .../dual_return_outlier_filter_nodelet.hpp | 13 ++++++------- 1 file changed, 6 insertions(+), 7 deletions(-) diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp index 8466814824d48..49d17f0a6bd6e 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp @@ -30,8 +30,8 @@ #include #include +#include #include -#include namespace pointcloud_preprocessor { @@ -49,12 +49,11 @@ enum ReturnType : uint8_t { DUAL_ONLY, }; -std::unordered_map roi_mode_map_ = -{ - {"No_ROI", 0}, - {"Dynamic_FreeSpace_ROI" , 1}, - {"Fixed_xyz_ROI" , 2}, - {"Fixed_azimuth_ROI" , 3}, +std::unordered_map roi_mode_map_ = { + {"No_ROI", 0}, + {"Dynamic_FreeSpace_ROI", 1}, + {"Fixed_xyz_ROI", 2}, + {"Fixed_azimuth_ROI", 3}, }; class DualReturnOutlierFilterComponent : public pointcloud_preprocessor::Filter From 01dc9d601679200825a1a6b6bc9f9eeedb1f50b9 Mon Sep 17 00:00:00 2001 From: badai-nguyen Date: Tue, 1 Mar 2022 12:34:45 +0900 Subject: [PATCH 17/27] docs: add ROI mode Signed-off-by: badai-nguyen --- .../docs/dual-return-outlier-filter.md | 19 ++++++++++++++++++ ...filter-dual_return_ROI_setting_options.png | Bin 0 -> 64264 bytes ...tlier_filter-dual_return_detail.drawio.svg | 2 +- 3 files changed, 20 insertions(+), 1 deletion(-) create mode 100644 sensing/pointcloud_preprocessor/docs/image/outlier_filter-dual_return_ROI_setting_options.png diff --git a/sensing/pointcloud_preprocessor/docs/dual-return-outlier-filter.md b/sensing/pointcloud_preprocessor/docs/dual-return-outlier-filter.md index d2ddc3315256b..64cb3617180f7 100644 --- a/sensing/pointcloud_preprocessor/docs/dual-return-outlier-filter.md +++ b/sensing/pointcloud_preprocessor/docs/dual-return-outlier-filter.md @@ -14,11 +14,25 @@ Therefore, in order to use this node, the sensor driver must publish custom data Another feature of this node is that it publishes visibility as a diagnostic topic. With this function, for example, in heavy rain, the sensing module can notify that the processing performance has reached its limit, which can lead to ensuring the safety of the vehicle. +In some complicated road scenes where normal objects also reflect the light in two stages, for instance plants, leaves, some plastic net etc, the visibility faces some drop in fine weather condition. To deal with that, optional setings of a region of interest (ROI) are added. + + 1. `Dynamic_FreeSpace_ROI` mode: Visibility estimation based on the weak points in the free space which defined as no normal points region. + 2. `Fixed_xyz_ROI` mode: Visibility estimation based on the weak points in a fixed cuboid surrourding region of ego-vehicle, defined by x, y, z in base_link perspective. + 3. `Fixed_azimuth_ROI` mode: Visibility estimation based on the weak points in a fixed surrouding region of ego-vehicle, defined by azimuth and distance of LiDAR perspective. + +When select 2 fixed ROI modes, due to the range of weak points is shrink, the sensitity of visibility is decrease so that a trade of between `weak_first_local_noise_threshold` and `visibility_threshold` is needed. + + ![outlier_filter-dual_return_overall](./image/outlier_filter-dual_return_overall.drawio.svg) The figure below describe how the node works. ![outlier_filter-dual_return_detail](./image/outlier_filter-dual_return_detail.drawio.svg) +The below picture shows the ROI options. + +![outlier_filter-dual_return_ROI_setting_options](./image/outlier_filter-dual_return_ROI_setting_options.png) + + ## Inputs / Outputs This implementation inherits `pointcloud_preprocessor::Filter` class, please refer [README](../README.md). @@ -31,6 +45,7 @@ This implementation inherits `pointcloud_preprocessor::Filter` class, please ref | `/dual_return_outlier_filter/visibility` | `tier4_debug_msgs::msg::Float32Stamped` | A representation of visibility with a value from 0 to 1 | | `/dual_return_outlier_filter/pointcloud_noise` | `sensor_msgs::msg::Pointcloud2` | The pointcloud removed as noise | + ## Parameters ### Node Parameters @@ -47,6 +62,10 @@ This implementation inherits `pointcloud_preprocessor::Filter` class, please ref | `general_distance_ratio` | double | Threshold for ring_outlier_filter | | `weak_first_local_noise_threshold` | int | The parameter for determining whether it is noise | | `visibility_threshold` | float | When the percentage of white pixels in the binary histogram falls below this parameter the diagnostic status becomes WARN | +| `roi_mode` | string | The name of ROI mode for switching | +| `min_azimuth_deg` | float | The left limit of azimuth for `Fixed_azimuth_ROI` mode | +| `max_azimuth_deg` | float | The right limit of azimuth for `Fixed_azimuth_ROI` mode | +| `max_distance` | float | The limit distance for for `Fixed_azimuth_ROI` mode | ## Assumptions / Known limits diff --git a/sensing/pointcloud_preprocessor/docs/image/outlier_filter-dual_return_ROI_setting_options.png b/sensing/pointcloud_preprocessor/docs/image/outlier_filter-dual_return_ROI_setting_options.png new file mode 100644 index 0000000000000000000000000000000000000000..22be70a642309ea9317027ece2aa7fc526d24034 GIT binary patch literal 64264 zcmXt91ymbb*To4Gin~LLTX6{%w73;_r?|VjySo>6DDLj=#R(L5hmZH(|DUX^BzM-z znz?i4+`aeNH%wku92pTG5ds1N`MZROA_N4KF9ZanAOP-TgnnY;p93(aLNY=S5VbL% zUi4uTrLWNjWunV)f!MXR8%^`d0MtTa_>F+$kEuT$?kXa== z!bcnjB2p;hS~+u~S5XCa*B}KZW^5z`1~NpntPn{^Nc?u5kyJ=a9b#G%44pWW?R5&E z4}*}FkWk}nmxLa> zOiH%BDvB7G2%tdoMIZ>6PB&8dF7cZy!&&@Jiha`a2;oK1s(y%+?7!GBtbu|4}@nCPc!NnQBKw#196oD!M8jRuZ zQKBjdg8`Vwk6^8|IG|8$q+wlB!Oly~5pvtb9~B|uGI~K9o~&_$1~JWGyv>8fv)%pE zS-Vd|KF^%8!5a78iCU0jp*=umlT2TD;(JT0Ws___qIsjD1x{@C0gArr&ja5; zr0Gy{00a$4{02}iWE84i8v0QD?xfi~DHLhrx(b^izPh$Q)yF&_+PM#D20RfRwQC~5nLA~nprYUJ2Pha}(|AfvY!Rp!B#fg)6C5jc)l6l1{ z*7>}9JD>l_(kfVDhobrGd1UyWmGjaUqa;i!6JXhyqj~0yC2-eCa?sNu`i0ryru^lN zC#7bk z$>*3hA3Nxmdtg~$F2xr#kOx4!hoifZo#vAwcA<7am1npoqcCMwkKM_#y+qxtE13$+ z*3n$a;}*PtM5*%M!!M*odonie7zG6dBYW|&wg~i0OxLwBUXhoVc6&S}vNIaHT%R`| zvo=T0HrhBnmN1%N@PqoYsyzv+`4hpKIgh+=mkB;SB+={r69P}NttmPCUGIP1ht9pO z%$?U?AU2Uyg0MnA8i`OsI=4ykayed+duQ*A0@=2Jn;I z1FMM=ZKuUP(=fzR;-Z`5EeE4TRABKGTp{4_Lkd_t%$V76jd(&Az7q21Seq;rH}j2*|qYV7F$yZ z@b~@a-a?_O;f(q8I*S&3cXLX4(dQs=pTq5T!1k3SnfRTMKdsQmtxR5?qP_#x(HxcZ%jXj81q*w)p<>E2r^jTSHHqb)q&IB}`b$#x?DQG;r1GFI&s9la_t>S|1?Y9_D|K$_pcHZfyLvQxk5 z8T#10{ig@5^^|85XqQ@Aw->#34xa4rk|1wL+plUn0}sZ%kAYw9&3@@N}2QB+IDdj6s#{zWI@pTdb?1wfMYJdE*9j`5L44fOZA?@T-Q z8KXPIKptISLAJcw&@PlFg{dUVVwz5xK$lT2bwg&ZYNbFR0?`cY%(5uek4cX&q-uY@ z5XC-1qR4VppGS>v)Nx%x->olj-Tyq=+-%PHrgO4h`v z1OEkz`JZB$haA;wG$q4iB%OIsA2a0u4zSr0eRiKotYyH7K&}2mstmOw5QrSpdhU0m zhqq{Q-tQE%h`5Q8nwbsme}G~&7Sb;2{@XWNWII{=qAQhu-rG+{2RAG0mjycVrX+AG zmQ}WulbKD)&;#4X<-L(d8|u!f^oT%Ee))(Bp@jW6RWHu-Hp4WZ$LcraoX3Zd$HfR6 zupbePnAp&v9aOg0lU?*wXIdvD4g-0%+nHUobmHMA=eVE^vB|9yIZYF`B#q=gVhI%v z*Ee;OTI+y~hz2FK;+8u4>c-Bq4FL^9J#O=cguw`q><|1*PlK>__Oa|4AaAfc^yfeN(y?y8-0M-vLwAVopdX1V1-y;7uZPVG-P>PH60pGA z641tDi^J#<#^*ZkePZTkaP#`T;@v&3$XwXVnnc4QJwuA?*#n#Df!C-IA_aSRTK!T# zcY{a_+jzYv8@tB9_jFz+B=*)MfL3S{8*BO6j2RIX3XWn`)V-AyGee--V{?*J%_B{N z;)Kxwgx#wh4UC4k-R#jdOijbNDWRHy0j_#OLJ>YJ(9^(=Vz&hExbe6C5=0Q_EL~D0 z3(y_-Phcs-AOZ>iR!)~?OYcfLS7|mEE+kJ7Or7_ro7euluJ8Bnq@TKOJv<)`efm@0 z{(z2A&G&!5-=1%W{CQJsEi_OW8u7wHBgkBOX$8@VmTK*{B(M@@R47r!=-+Suc7Ewx zZ1{vt218rH?C_WCmejJdq{o)#^GSZJRHZN#EXWMh6%00Cx1@}w)j7oi3Cd>~n_MC3 zz(D!ww;8p<9i5$l!joN-a`}=?Db*NLLKC}XUFJ3fL{>S{r65rURhwJn#h)q5fH$m@1< z)Z~$et4>Vk?|C_TQw1fqFFbxM+zkd@HZtz8z zrJWn?r&*g*pfglq^C(FXy`j>jV?sXe3Dy$2!~&pmS#?^9O_D>Uo4?*8+S?1bGemrH zoT3ndD6gLLib&v2BE-yAsp^QIknYZBMmEBt=GdDZj&j9UFvE3lo@z7H9BIIE;R zV2FJlVyhO6LLDRc|I|~-PH1`X}A+Kax0dXeNpi1tlf~gnSAFH7Bt-{>(X1amHS z=MUv^+8vm!h`4oDJ*spd0a9L96qijO-u(jI?OK~R8-7eu0}}5Lf%lG0 zBOxTaiz?39j4STT2k_(i`-|u(a=^LA=KY+Zg(D_9Y|oE9F6}lTeW70hjUtKz(9=Fn ziB-JCT#l(gxFdC~0cqpz#0m6In3`)iH-rNgM0G4QT&B~h!zbs)%XC#SgDkodY!?#g z*t3Dap14wo)6WJb>y3sUVbGP0gJ&H{sy<6ob*c@$xE*nBv)4Vm~JoUJ~1&~H`QFc7<_y--ROoz|i(W;+K1*W7v<9a?#c}Guq?tWospY(b2lbd!KLb;sldZ@oCUJ{F> zV>tZtN^0}qms4W#m-Xe1$p>eX=Ni+Y{>NSDuID3$&q#wnck}Dk`NbV)C(M%kIR9J9 zOHbFk9r63i`}U=3XHv>WyR5mEV>=r?>+3i?a_7Sy;WK!Ya8*E>F=M5Wb!YTDjNZo_ z_43S~`7LOu|6EZ2AvyH<1YcQ6o~9BNWFQe{$ z5qIa~4N``G2|kwFe2U!V!24|ku1?Z;70!&d1nX_3!2Z&hELu1*=&}j!V}OBzc#R+e^9Ul`z$c$8iMr@JI4o=w3IcL9gE= zYzj5`z|+i;j&Al!>At%MJ9oxLI(g?6Q;<|Q4euS5e87?21CJ3*MS3}s-SLq*qoF_D zL`yKw`dlv)foiD5XS>IG!1tFKAF!*(VyvUDTYNy@;W@{f&I^| z)jjj|H2lMTHCI{iJZp2v<9#26oRWWXR?bTRgDS_U2Y)*{r6YLi z?OcH3uq7zvHG#xXe38$lt1yr2b^_(X;`~)gxj=gFWZT%ro9Q`(=zt36*CJ_$p|4g7 z#xrVuTq$ADnKzPCqK1=S=xsHqJ|0A=WHcjp9W(^~T{OG3mA!3M|D~PJJ?*24*96TR zIuvIzBdV9pr>R%fsa?}NQ#J~snn4#vuxS_SQ&>^Rdf81LL-iJ`z_f{y)xyRAu8MYryZ#?!!5U%Qk6<)XV+@tov?5NUDEfOX_nG1%xGL1tx3+}TTDz1eu=(0TovvLhKA9Az%Z za03ulspiH)3+6|}=&RARn>d!FlNTXnw!$&~e0_0=2R#46xyc;9%XPdSP)_w<%Bc28 zVp42{knL*(j1(c7V*gd92pJysRp@6XDm09buQaX(=j4mjj|V5hrEHE&Rp`08x1H-I(LfG!a;gT|(QbWEUgXJ95M)x&EVeGG8(Ih{OR(qK#$%9oBrj@_E$ZzwY0>9Cmn5RPES;t9wLi_0X1; z;~VP_qxrnf9vs%4!{1kmAwGRX?EW-ZbCU$;t;J|yOkb23I!-zz%`|->YY&#;l_**- zxAgJ)zk*^s%WsZAcHtQ_5`?}hMLhRI$ZW4RldO>KTOiP)s#9_;Pz6Ai{@p@`&3sy$ zt-%ENi^bbLER$W%M~qo(d^Tgsimt0LFjb?Yhckz(FH97Nb%RJM>hmWzeIBDLQG0Ff z#6^kH)iTKH?2=jPy6Y{-3MQ|}5dK$%JL58GuUi|gTGUyWA#Efh>F8?j)`jj>D+G)_ z^oOw$?z@}aLj#Z}~_{Tv*)5Dfa?R8gMPS66!jas87v|Tu%rdGeJbG#-BQv9FZ zQUmmVF^(->Lqu2bIV*qja2RZiV&d2M*VGjxYbD!(oKsu)$)ECUx)>nREJ7}B+B~^Z z#eJjFe!;T-PCuxP7NlbRFW5a+zF;@t)eQ_)ic;zkqliUIv(k{XMML=5V5tdXXOiVc z+3lY)|GC-y;FQjk=gvDW-Pd`az2>erNdGIO$o4?h_O~cZ=`a-q)=L*luQ}?5@bm@I zZkcm~rA{K?Wh2vtfX}`M9`Ht`^WD@tdBz#?7lk|`k*LV3(UA7$WW?Ds7s*?1&gF<) zN1#i`D^~l3mB8dof|BPh0m)tr@jG)gov1jc2Z%YWBWMoRBL=*|dD27|o0JHE~$Zc31-{CSQ@WOY%}DPY0=M+QZm z^c>urP$|@|P|}FuHInJr$=TG5<}i8nHq`xE7Bj&0rNu6qfeTl5DZKmq%j^+&I$~40 z+3OSckkDrQ@F6n2>62y@zuEL;f^C!WHP{A~2y$yUAM6Sx<$et#KqJy_|R2Lq~6+H@ZEO&Q)!0yTV4q9 zj*HK|i@KK9hpyqbh~LNTI>h^@hxgBAH2diySSs^v2P3lc&}5eHae_D`Fi*L zi5!dPdDL%hb%sZej?FPT-N(`BPuN&u^h6n?6&$F8 zcQ{0nG{xA-uGX!i?KwhRqS6+}ydD;nfOf=a4Fhrho#1U^MH#AFiy3^}AhgF??^!SH zjE$r*VT)`&=k$>1psl;=Qi+)snTo|(tLjFAXPnu)t^65{flnE9kW~JSw;rlNyQBAx zCrd*sYoT3UllM!D4@nlyl>_RpGjs*DO_Vksy6Kwnc24M(KQtTTkp(h`^`h5Y0H06r zL@mFmM)pJf!xd~HR|gbYRKP1EUu9FI8(70vqzCLe0b7+K76y$Qz_?M{-wor+=IH^# zcw*tO(sS*UqFc^JCf;#F(W*0d0Q-Gc$GhJZ%GTze5>c%lPge)#B{NUmL^fABrrggx z*M4{3uX&kItu%4n^ID8f+jVw^F2b)u$#Lu=Mpe@oW4XQbo4dCrA09JUyD~8jF2)!9 z0}?a?lc^OozVUYrt41^0w#SPb1%Int09tCQzx1qX)F|Ss9g(wpP@zOw5c7W%Z&_4B zBXAE$8AVqyXTt}2y9NiJ2;&cy$?5cRh_VGZf61Pi!Vow8;4c{)rR@Jv{cU=U9VP&D zHaF`S=TxBbI9jG78qFR)-9VGD1=8H$Fp@*rpNXZIDb_YEjWA{zk*x#Ut8t_RV}d@( zO8PuXO9zdStx8OcuOSJh#hh*8783trJy1gO0~$!abm?)iRy|u=TKFf-oYw8_+T>W# zY0I88=Tsf;PB|4VVNNzhc)kdXHPnJel&M_GjEXAjvdeR}E&>=GJ_wVGMWIM#Z5fjt z=O2CdBPw|60!;Fhw~xhfxOQ(zH?l3PLDu&PER~pfZ2?23(%E=&B3pw6X{kDTBT`lo zzWIS;;+&Od5mA^WRA7!aUb_FT*>3@>d1QcPlk11+3T}_%^-=@w&(n-VxKX05mVKm{ zoOCikpM`r@Gr9t<-N`uma?k~3cb6*(H1SsMF_cyKMo9E?zGXg6}Ma#fu?Y@g+RSex@y<1rDL z%xLGpmA!d=8`Qriw#_5nzwex;MSWe#N{s9P(dSsjx?P_h-e((;X?b&TSlWUmrPurP zjlE5Rlw~5*4Pl7|B#BQuaMHVo>ieDeAC7;VeN@B}BlGmI2vKaFlcb!S6xdkVZU7o? z0$Q=@22`4N%z%wB6()>2PH8Mx=~8fI{gl{aOH5k4R0R~Pl8+_r;ha$`)vMU1$v2a4 zS`4F_-?W6<3~tXEJalXXU~-W|6dV1+^SL&rDC7T|fN*C>iXgo_t?lhOV{9i9YMF)d z9au!BNC0_|B3&JmirWNCL;j=JSnP6ff76#_eLXz5;6&WuNTtC{)3)PAfe9Qy61ieH zwW6zjD2W(M9=US5!~hmHn*qCmb-RlMWHDJSa+p;*P`z1D#@4KYWR2w;5=B*2P4u$^ zADSpy6h!QS+fbc$Q&yIZ;;~8A1~sS@P=rN`7}o1c9iA>grhtnsh9+sAs4`s4P1!BJ!*$-ZExt`0b#9u zZv@ROc^2OaU(Q~@BpGh_p zj2Xd;W<>s1(>#KI0eQmHXdm+|?PrztahKS>7MtryP64tAf3;lm9UJ?MvBZ)~aB>}gow)8-SyY>B3lcYph9L=>PkI=~@Q zXjyIOe$=43(Xbe(FR^ey!4v;_a@ z*0}O;y2A~aFu2uWZe&e!6$mEg~wT@XX@X*;HvCr>D*!rHT+%6tJTQ6PZG z7g2Btl}C^kMVK>Iq*kzjL3*r*c>*g!f6SebuBaZpOt=5MspI*ng1EY~ntMtB$6CH( z@pI>4iPM~h_vDbuezx^yPJISuZlhoje{ogKeRns0bNB@Lza?&oO$e1)mzK3w*{}{% zfhwd%T>U3~ozV^H#@j)@303GojDD(Ks+oaLTdU&yUt)&^9z4wi7Y3H9dND3-L=b=+ zOX1#gG|Jar7)_5N5{L^|HxX0K+BPSRmVj@q!5c~g>tduD$` zXY`%hn*5Csn&#{Mx)TB4fOY4~AzpF-Qk1;nHGylM*owMD39}52k{YSTSc54;i}T)1 zN2b_nrH4TyW3@^yMFXOO5EfGzh6uYQjQY~oEZOZ=8hWZI{XrBN4c(DD-sbXjDO6t~ z(x3FRR*ZIQei?YgCqt`7$0Yxiy>yXXc*wbkvCQ;pR&Yz87?T)J1OxKVM&o3B^h^Wz z0g_BBC5(PZ3S4xn)ZDqm0$<6MzEYJV$?u3qn8oI{{2p3u>@qZ>Eh?s^#PXkH$hXO5 z;A!@s7&@9fzamEj)3UTNk6m;Fiudywa2(?hx<>o=ShVY}Blo@gOKrc zkkzXVM?|$8vJ)-h#$0xb>m>S4y1B_0UmUzG^7-FgCW*(Q!xV)u-Q{x*iuD5s?uou+ zjA-4ux`h8Lc55lY=y&h+vJ9D))5EDJ@`cAa*QR4gRMNvV0p@`6GTDx(HyE8YxfE z$u4Ls7s##&>b9>lqZ+e6tZ&!a-kSyTMo=2^!Lrb}$Q-pC<5jZXx@SEOu#`}yq^4FY zpb#~r38&JGw@;`EDgK&I&HfnrD^X8V*lcd4C$w&(U(_vGF!P`gS`8(+fL}jW|9cRo z#WL8EBP3%~Z}lwwo2JK~ig4{pWlM8qG!1rWg9Z>yP`L7o2Az8sUeD%JhZ94U$aOPp zSHIK(`pk>AL>MMqFLU~RMA9GaL&0h_(Y`?zQHwB5YZ?}wd5`GL6O;Nz_k@1{T98>~ znl7WAYiqwFUsRooLE$M!9wt0DJw20r5rmjS{>nvIBh48S27?SJ%b-rtutldR_1j31 zq6E#1hSD_j*Ul*=nxy%2lf)xbJ# zF5=V4QRB+WW|VmaR@2fa4U0s@@d+k7lb?PcB&(?P`(qw<*X-W9sJMYh%;r7rbOaot1+yeKAI zpilty1%hV`=>?-_Iy06>Wl76hG=A_uC06BDlO&*k+k9ss!SB-0TjcmB*pw6)&?Lqu6ORQl~ zuZ@RX5DVzTaLA<1fH^=F(0L|bRJHCLBwdgS8djIIxqjG4sj1xrfHO(VT&VC188#XvJ_dtgZFd4C z0D42w5>zGDmSb8z#rd-m0;`Aus&ZO`%&~$+6xIJTS`umiOEBP@Xdn$%)$vZNIXzX- zJfwQXlZ{v&=IrLzb1jM?vVxS!7A0SxNjR7|(0?Qgl)+3S_G4q&erjrkR>j zv&BcbQ9{N3wAbRM+|#%%C|@IH@>06LG5O`XpRk&rOR6Y*))RWD=8$g3I$|!DfMhk z<39Su^YciLp23bh^OJ0NCu{lucdfuox8bpR2T-= z(6f32Huelt{)H-5!pFh7l}m0{<3Q7&+=Xjv4Nux!xa3GcY&zsb_I3L0CO7klwdRTp zv^)h&`AXGNamrO`PAV56Ze`a6IQ5}^7UYi%0Wp7{%Of_SNlH07a%SX-Gp{r}HYv+t z)k(XG!?VU4nb}O*M1Qt#oF_n*jhecezZ6aG0|v7OC)BHk?9qy*TNm#fF&qpR6PX-H z(X&G(#)Vh``L{DjfT68xT+Ca%e6*D0jWkz%#R;L>`;YR2wmOd;9G zb2~_$=7=~XGqfPZ;kW1|Q3^m?II;)9xjPhUg*^Oi>X}40ABaa(w-m|bR_f#ClbOUb zt)UXubxE!QB|GwTm^uMq1F~udweypZwu?84(H^aWAJ2~8jrkR)x&b!tvU5sd$;jXh9BE>>T$_Se+$rN&%M zPt9!ZYi>phwVri;q@79J*$tEz?8ve_)4&;&nE33r7SF$aq~$9!qD^VjWGSF~v84J9 zMWy3fp~G87F{(fHje6Dm%$*sbL~ReKfSt^&65&T6j+^TPwI*6A#HK1W6@0K$UI*zc z$HMSX3Nn3PA3%oCY8RIym~H1S13LkEjjFE~gL^bdw6zVs<=2B5Mp^LDR)jurTKd2z z@G|FoTctli!=iE-do~ZtNF0r*+1)NCORb4+iI*A9Q?UNDCVlL8_SAGbg*&f?I5A)h zmS+~cagnSu<~#zvar-KZ_m{A7C^hp~*|}M#eLrc?v6}P<5P5%>VQKg`@sYIit5QWn zm0{7eepDs~^Kt@3mUCE2Gt@>*PR6>G z@nAL1|8izO4#ZsFFwQBrP^#I7TfA`)<6u{|V2sZb75gDNwXkDVE1v`SfJb@j0BL#e zKwWs_1GKB1W&^S>tF{1;A2ZZ&;JkmV*w%L7XPUmAL`DVC$>j${h1Coq!l@Mx38zatRLE*$|(MX@m%v|B}FH8^1iY5M< z^U_3qMTUxi)Y9QG%hA!9dHoY#mo9iUPswh8bWBW>BaV@IpEK3fI<9v_De`vpg!uRa zW!0qXm=OJ|ee@<589!!dGhR*~!DX}h(@b!6jD20V{eh`iwxFQmGk0&Z`?Qf>@k*Ur zY!PS;Fi}EvC)1J1HKN4!NvRR2O`00KhuJdZ$*l<0P@}kjVxbK(RwMW+gApvuC!tiH zGy=}ih2ZFFMBk^K4FJ}2MVZsr+5E!&w820N<+TY;E5HD{tx_<<+tyF$27!zCF`)yZvIHhw%MT)55wGUIN zRmIDM6tbp$&KAEk%v40|<>BVl`=}N?SsD&m+Gi%K&kM6I#aU3iGGA}p?92Kuk60t` zr0aZ^NVS7r!k16J{P)Pz0mxG6lH3lJqk{QbcW%5(Ii07<6_Ald+zrQ=8Yx3G)Jm+` zrlX+{{EHvT(WxFf=&9a{fA#m?v!UwokkSL9eD}p9D5VovIESgq+z81(y009}RuRrlmqRHB{%SOI`VX{kmZ$1lS3nc1XzYkSA9wvO33AGCva-z zaxV&~J4=EimP+*6vVx;OtN5a1w)|oti;*S#WX;RGk+G;}P4HX(BzLQ1>9LA779;q> zH92sD+8A7N*QVwil$H;mc%MC*5+BNy%RC?B5~LTdQcJ6(h~@k!uPi<;E;ym5kx3zz zJq06R)~@pr#iwUij$e2W$!^HvPv1uKc@U|H1P0BLyJvdwcOM&^H07+LAlf8S7}kZj z-L7Ivr@h@I(_c#jA23c9nY{l1Oo<7~pOE%Mre}&9!>Jl&lDCLL{A(l~)8mKKVwvs$ zrL<_F3!#s@T*{a@c|CrEj&Z$vLZG2{UPY!zlOhWwx60a6{8!VHu*uRY{sI>l z+^D#)tN0<^l;QZMZPavDqxr}}Tdq=00=n`;Mez067<^RiF>H!*Q8~Ofz96QrVMAHU zY*Z;l{QOm%Gt-*S4)|`iSE`(n!K7W4qw3(Z4oRF5nX2AC>&!DXYacWv;2BI)jl#On zVX)GH`Gt(??NarD^W4o>;C0$`CdIu1R-z1eTe`V3<#Vt4IGQ3bv~5akP>cBIM)h$y z=Y=?g>Oe5tSl2QeXT>r-t8W8okK9NN)F>NES2U4D_KQJ2omZxm?D72|nCixxw4dvsarGc6*jP}rMR|Je-r2Wgt9`93tHY*6I!3zq`usd1H7O|pOU zfTVz_?erW5`)>kGr}w{*Ze7kr(Erkr9%`vD-ozCuQ0SREyM|M9EZmeC(``S|EZAm4 zRauW&^oC9H4W;ijQ|bM!Xt$`dA+qM`6hwzL8~QrkP*i%%LylU=YXsSXUGVUB3-r+H2LK%CdAIFvC6fBv1oLm8$OeHb;s+XRLhPd@UYsTcL6J#o5 zl!Rc5G=GY)PX5<_GK-)PImYh|^Kt!P|1jdd$jW@VX1bLBppQ`3`)78?^;hdv0m)IP zYS)+lmLucPgmT)?atz;eru17^q@wSvK3K6v2R75YwFt9_(#t|0oD-eSooGaH(@fxx z9A-(sg&ts_21TI=4Sd&!$*HP1Z@Q_t_!u|N&tmzQU+9y$LJa+j7&2#8mp|Oj8(#2; z{rp(MF6(;ZT5s(svW(4KzGCI|!jR#m>FN>t<0hj^*CfJ@Ww^j8)8$RdTc*#$8VYNz zT7l_(gxkf$=9G5x=gXTCfo^cu6{ZMejOUH2I`D}{=dO(G?ULy|`Df{Ph|lTTdl#8UdHts|sWA~h%NWyMdo zrpRrJW_@{R<|0L)GdE8t_S^zgyoJLtkZ!H7)tbeiJss(EYO<6W(&f!Oy2IE|%kCEG zYsZG_{E!g>*FRN@)ORH4YcwN%s`X`E^7^WRg2Y5jw}h42W&m}r$$XCvomwKv&hrNd z){aZqs%&WP48T`R%yo^`;3MEbj-gU&& zTH&@Wf)VN#mdiFMOCM@59Mh$O^~HuF^OW^`ynjsCe8GxlTs>Lt$OsaD%S3rwWV+}t zWaW31ynH|xc3#wp9f>cV{4f)E2Kn8hG7xhz<@DagsRELZ}f&mpoe9A!Y6DK6E9D3 zSafYX@b=UjyOK9bwbz>5_0?LN+nzA;+YW{9&Ww2RL)B7O%q5tAtkx%U_fPX1l#TlZ z+%#3%!%hj;E5ksW&hiR!-|s9D>7V$GH3%dyS1 zu}QKj|3oJD03h+o_C_w_k9DN*ENT=K2~XVD;{RAzPQE*qD+Tn@^5GpaId5|jWYFD& z-<7hzX&A230NMLFW5(t0CvE%A^y$Z1_nQ8bAHGg&T(0jyNwvZsqsJraB2ATJge$kd zv_%(fYAlwD?V<4qwHN2B&UFViLKMx}hPAv^*>3HeB4p$elOadNPV7r6?P~Jt=*6*Y zESB9oMFyo6pH1W{2kL8OEn|XEQ~7{=+_Gd@;jft-zNKlf*}xy-#lb3)%T6z;2!6Wi zCeHSmHHrrb@24A{VxYYRGgro>BJ;$KPh*J_Mm>y8yQnk-bFl!(;{6@2&peTg7GbkZ zR$_3iBSjX{Oo^qipX(T`NWb`6 ztF(x|(@nTT0luEs+b+xIK#~T(HzEO8|8rl-TjDUoZ0z)8_I#y6+BsfgEigOeh~pJ9 zEC7V>7gBI~TMzX!DwfiZ0|1TE_uG-KKWLRzIwZ*54}(>TkdQ#_{`<j+P#>qMRw1%(a;ie0f31%aM@?Y1-x?2oR*MUd$ zpjgZ+b*&)-le}I7cEL2fLbhoQ1*QpkbF;*`C6kd2LZNxYWNxaiLKU-0gUS%GAg5jl zJ)V!MbNE{% zbI~HcyPEJm8Fj%f%Bbjeluzgbj zb7TddU!FK74eMw>b)aiB@*H=f+`&D(n_nc#nFZ0!q_RDu&XXr9s0m2TazB5@Pw4*i ztpYI9+9n04L}j}8j^N^TaOJuy!V&~tvRg0L;96vh?UDME4E*iZ&_hyVr_P*k1hnN{g&AunCvhj3W&2L&R3&diaTaiB_2ae5xR3(dqN-N$9HpoZvg1P-zQQ@ z#S<8P>4nNmF06aKi8=k6((q&czdmW`-As7ffyVf~;RqHov>pisZY%NXFK^*n*ltpt7 zokI>K*l5;1;;E7mYIN4-#-5N@vJr&{tISzR}pTt~70?C!F=CURC{1qL?ZO zUKzi<2m`ec24~Fz5o;L&a)F}edEsEXz{KI=pdZJ}1*$ujG4FRaK535{fr;pJ3j^J6DHq``uV0wj&N-wJ^pC#iJ`dYmmv+75mQYe% zCJ9w};Ba<6@VfQ6w5RX|z$S7|f!{CSABQO@-%q+;*qOSFsSd{kl24PIKm{45l;GM* zn!9u2&R+u7|8^`nf)*9OZ(MT$=eliOD%Y#3#kd0X1p|YACw_r9mATQNNsOKrp~lKb zn4w16*26z?NH&GSLdQq@a77(bli#qd+AcN5KEuYvGqZi`<06HDfc8W~H4oC7+CvEr zAQ|U;cW8XxXn@i%AEd)J9K(W(&_3QNVCQQa_FU+f;3N^`neFUmh^%wilzEU;(#{qy zh;{ZOO+4}3zQ4}Sp}$y>^GwAs%?9yyoV0m6)Rf+}P@?e~A5A`46& zW5dc3a!1v%7_DQPiZ|-mpRdvlP@|w4eR@@HCv6HxsOLt?Ah|7X1eu`Jp8MJK(F#nA zga`~M+-}O=_F5iKC&rj zF*c_D>#Cx;Oc6k*pWz_qY`?e8Pu~C88!|u^P(18yA~KlYkm{im+DHLjmgZlzp3=){5EkaL{RR#wS`j1|i9?^Ki%~ ze$eICvH6kceRt44aDX(^M-{Wf&z6$u^!TO$7B;)L^>p_C18TZf5v)whj!6h^tMm=| zoXfm?Ih%6;)_q9;M<(iP0BBma2i_w)m|kQP!%0L6^~r-s^FK^r*C@ZAweihY8&qiO z4ezf{1-v+IA}~StxWSMqsIZ=7fvACgQ+xAl*(-9Zl7=gg3+{px@@D2%alU}4IPPI& zl+K(^W!RD{%Ff$)g=FlqLvOCjQr)fEKJ5F~2m#}FiEt&|2PWWMQH&zP5}=(WPEoDJ z!)+tx9oWkj*E(9C^UOf})D7lhU((wuUb>9Fe?@Qpy!6md@>3VVhc|n4<0g=`2l=sC zahdIB6kG{5MPOEhb~P{aN}#?k`k))Ep2r(&C8m&C5w?uHiyX#{Yyo^q>?^;DfSPDn zS_-Z@w0`zl@@%+#ARu6&h_VQQ0AJe0!HSZ+3978dYLKO8iN94C3jDIh4rml|Y}_Bx zm|%~|GcQWDDooX+b!s0&o-%Zw>8oLNlzd_Lh+(6rU*kR=vVMvfOlI$E*j-{E5FSl3 z7F+S$;40tKESH&M#hBXhwi+~xc8#dLpr}3L7)(|aUnkY{4#6Vpzr_a&9 zd@xPR(iUu`*t4&NRSrV#?G~mm&wRs-dF_M0L}c1Y+Po)NcRu!J4kz@yMX9r>A;}{v zo3!0KGR5n>mRYYW51G?_r{jMOlT)A^T0YaHE|g*U$dkeQSJOXt$(*yNzpnqD{8BK` z|BEY5@&+|0g{%n8dnDWPkPzcw;GQ;r_`2={j^Yv{99CR^wzuZvl2qm&zr?6NX3eY& zweHhjq_chKSI#^;0Di&#$MzxvVr@|~rjg$Lt%}FKx@dwaN;+$W)>2+kXsX}@15k*VwyB3gln3QC z45|%y#*8O}NJY_Fqs1pbMb~k71~}j!F!ec(0PGi3lHIlMgzWmF9IOgRSUmw2B!>^9n83l$ zn}K|<_rSYlQ@b{CiIVl=80~CL-Djr9vvY4&hn#mA+4sLw-#DF+6*#( z_oyB3effne8<1`)=6u;H;wqs+hUDrDe@VNzEOF;Z(*I+!$^hYtWu{i^|K1?7P_n>! z?$hnQRJRB!!Twb;nfpA3E9$pBywL8JB2n&_0WR_rmnC#Bi3E5_=qSP|MBAu?M!PQ@!KqzC&xT47@ zV|{OYUFS;1CC<6A2JdG2get9YElJYE<|^>yHJM`H&3OmG5PIss+VZpiQmlO>M|q*x zFSrdaufnYbdZ5-d$9x3wVt0C`)kJnNhz0@p9lrg%)yn}So zgS+h&p4)X!CY2}ue%j*qd63JlM3DK48VKFZ3E1HtBN+0aLloHEuz2lfc#F$n6jwl1 zq5wv~{BL#$B*&^PoLi*1B@MZp#fhF59`mi)MR;<_OyvjA#l$KOu-jlLGPyjUrfXqQ zTUuYr{bQ+F@{$5?6)C>|2)v?5Owv6?ncx>CHbEto246vA1PanbP@9oX{N}SV%NLxX z@i=~LDh;FiZcF^>Bq_g93^9!AlQcc!T++l~NF_8_x=5q%6S-r7I}Pu0ldAjvI}VRe zAhXIWbYmw5ID*$@-H26JtGx^Hqd8&UA&3tLC2t|=o%KWe06j#Q^aB6KffWDfnQ%@? zn0$(fGn`k}yVEtl@Zz1j!0tqr&sAbM_iR|x zw$JvZqd`fa*md|npC9~TX6_Sx?@LiuWP{5;cFSWzz5)40Xl zoypnfO>=fG;#dI|p?S5PPA(W|zBMeF>AD8@vn+fAjVNpXF(~=KP^l6bdX7OC{Wynbc;Lcxe)!A=o7=f|r`bI5joWo#U)#w48SNmliAQ=6^bWg^<^ z5(?}|U=Yg`8wsLHOsUReL{ed!)j?(>{8j}OjGxKn9;fTg$gYS+K!L;%3+IUGZ#vYdf^BT8Lh}D=p_@t#yp}p?|M|&l6L%zn*>{{dqpJkNV-{Om=JE z8L(9R_h%#Gbrf6S$-$WW#1L0Gf*(YYytg1Gg5%s&(`)^XKLIA#DyP1QVsfSU%P;!= zMY>ZAnv8ADKZ554y8FxEcVE95G%y;WX>dh#F-ptdrzVB>-0!}*U-SK1 zMT+P_Y78c^sdtOc=98Xfi!J_cbq5e9enpy*V1hQ}jJKQI;H8ma32?cpYi^GS@!3~> zoY#HD<0N`;bH4dAseQjbnBa4b^>zmRo_*+4T{Kqe@F3+g*f)fI*s+^MxVnHs@3@EA ziL02dES$3Ph|V`q#a@u}Z{roYWYvsW69dpzKSqilHEV?t4HqQ0kuGvSAD67Yt#%_|P zQRBw8lg74f+xBuLV60CwZ;iY%0+mGuc<}g{YCqA%lr01H_==L}yoH;iH523o~x+{l*^B zI>Oi{Pn4BarGg@dnHqJ>>L!lDeH|ahnbu#2!zp9NYcMdG%4E_OtqY%)Jy|!O7y+8! zc9EZMK}glI%+~VH&WGxjhpUo@ckW8>A%b7Qqr7*-{Lcd)5tOmAIf!`0JsO9r?`rE$ z6MjFx@^}@=`UV}mU&VTI`w)le-Oz`6t=-r)CbCrBDY$0e=vepd_HtS_!uC*Csl8|D zgEb678e%9G_e&p?X+SQJ=YXH(3&Gd1GoB)(v@baAz;_H{f82jujjDen@m=`91)bF^*F@6B?Zr`T#DGnN-b*w{#(Wyg}e#W(~4@v7kqP}04zX!|vT$B4O@aT=T zZM-X|r@nEuzfOK^O=Lb=BNPLKWgS0GJVx9*27voq}G0XjSOFi=8EEFmjF-=iapb2ER}a9n8!Z0M7<>; zYGw59QT6MW)>3P@#VWOEgWQkca6(iwqe=0|G(XfwH9(Pj! z%(38Smr^g?3A37zqjgjC1f(mA!H>FeogY6let_JN&hqrvX@Iv}`M&=4#!D1Adqxtf zX>!oEA==bqlE*Nx?d&%oJZE$}&oR9aFYf7_?s*%}`;ygcYz#G@us z3Ml-bIQQE@MnhbapNH$>1JN!n77mvmKJ80IW~b>3scY3m2t>1ZU^DoQyi~bugqZr* zi8p^_y(4^kphPuGl=?c=db9WEq|n{rWPyLE+L+QZm|`tAtm!Cop~|}sIY4-X_C^0% z_m5YsNg3t9bNC@=^1cpN&eY|g*?-`@q=*!gvYmfD5}tUg%@Gq~_ID1jBincjA;M*@6f=#+Ab=xq`-D`lU& zpI&OLrs7I!#xs-k3Rj@4!UQe%|isqFy-y!%=- z-)H%e+Kx8*)EXxTW?fsv?9E*^d?mo8L=paM7cNmExI9twgLtHUKlyvpHg0%M@dnWo zGIyju&OWvKP!O%L3==%O(wtAi<&)%4k@0yE+CO!{Zr`g0D^1p)i2iwRLuNmD5GyL! zFr$eQ^ctXfq!f5A*>~UWtX&VP+{p-ApS(})KU<$ztK{kAqp9~-oq=U-xP`Cn%&>pa z)FU$5kjtNK(P0q=K-eml&kvcYkFZkwONM^E>hW)m>~>)xu;a?iBcKf0F`*6-uYO3V z4kf72m<9YO=yXud69H#{y9`31JToF`B4c0$$1SH8A#PXCS1VVD<%M9jDD`J0&ruX# z)HJcEkU0ki5R(Qk3348dq~@`Wl~5>xaT75kLP#5>T9@+$5Nu+M`~F{X;mIIEX;pnKaUp{Eh*3HebcdTTEuK$RZ@QGJFb5Z(j zm}YAWID&=D180~e^Oe+HYR7l4UGAt}#X_{|h3nZR$6`?wA-~QI4%famIN@2B5DUCu1Ax;c z_Qh}@`6tlJeF=&Y7Oq^sQi(I%RMh4S_(De%{O3`1@k{h7+;=V-V7uuXmjBk%W42iN z>^8rA=~;c!#M0%{&qf+D)CO{t2HA3o@nyFachSMca(e@>XTKZJ_uBgN!e*W~Zu61s zpUeCQr7VH&Auiu8+YI}S3B*gTmo)2-!ik$C3+@yhkErd{kBXyxE(V>VTxEiA@WJ2`cZesfjOjmdulJ=>U(|TIE#5> z(n$3$i&c}Wa-gl&8 z&hk4N;e~?J#&*D>^KnanEvfN7I0;1wQaJlmb`&d)3so`|Y44f5@Z^N1?xZpgui$(- zr}@qT##~oin)V*7pj`DrXu=^TmrMKpZ3#z-+V8JQF+#(VeeaFfh+1e=K5QN&nvMAbYqoQ7jAtCf2vD{zpuIk#@IRk5q$<~_cnWu=Nu(%xVF~6b zsH(YQo}G&nX!~iG3)yC!g%HwNh3}*bX>!x%5e+xz6p>nJK?QG%y%W(a`&wTX#0@tU z7e+>8Yo&v&6eBu3Rxw2BUQU7-pGtWJN!Zvk(rMj5O5VmN`nidvCk`E**VijO^!Te5 z^`??9Bsqw#8p_e(`u#d$;AvIhl}W$#LrBl}f#1ovkwxi8`nP*R&+E(9=8t}%;QJJh zXJuaZ5*f2ylw4A-x{YSvX;A))z7=Uz($O&{9|zXi?{VW;e5AMKTbqjYl33zc2U zq>qH-V!iL2;H$>`GQ#iwPCkslOnEj|)c)r@5;ahAmOJ_s9wkG`M!LvBG_uGt{(?zz6EMG`{ z0<732bScFW>zFNJCW`U2^xG<`@DC>f+L_-VH@&>n`6z~o6)GZr@|g*EFRz*C3XY$)@3lN_BD=xP#%gOvc9QVKj?Ra()cyY} z!TE{;VFem2#vk*~t6r~FB9j6^8D}OhW6X{xY&_{~k|}Pf=@}G><4W3@If`ER5$s@+8<#6Z+l5O76+8;!Ea`2*&N^N5Hjf*H#G{GjnE5j;;W6Wb?ZcZOL5p%J7 zyM`=Mxi2Gw8j+*j2rM@{tR|?Z-KN-?T!aOdN`ttI zh_O;@l+&`-o1U-xb#P38!93Y%8nq7RmlgK9qQM?i*XKy~K4EZ6oUw;_Y6#z`+<+=Y ziXL8$i?Lewh4HBQF}c44y>1xd%Wi48cqtkONJPscI{hDh3~2q09+!f1ly*pPZl@cJEduM!d0hh@k~YR7j^|wX5D>RAG}3Y5zIYeO()2a=H^$M{ zi^mM|I}(G(84E3KqQc_ti#v0Tu>h`kPGUFx>A~H{wcn-DTu;oOwX1w7V#F5jFp2!y z(b3T=jnbSo{yf9lpNy|?(1|F4F2j8_!e3Nl#c|U>ifE=7K%+_yS z@T(FytAbU=8+xYq&34{41`9?H=OCbUId3dE$`A(u`F<*K;(Bz71wW-?E3HjpMw6PP zu%3*=3H#x^sWrt*B)eYnp`x|fd!o$(Gh0PRvVRz%>Sf;WzAO*Pa{s4wq;?N=&Br%f^6)_5BRT$(0TIpNc&f{u@@@?uPXF?X(`m#~S06mGKH?c1*fwkS}kL>6Zq6!DUMNu8kY_~CD< zc_f_Eu{g;>`X=NBcq!_fXWpJ>VB;y_?~XiyX`uL^j5D?3iB1S!(xCqikRy2RAywpq?Xr9pLJHc>qZla25#yX-Z#{~ zr0B3q)2ErbOd1!f7#q3$d@6~cyfH9i8f`cnYQT@MzAv`*)5=<9Pr@*q20&*=ayM`K zJ*}Yx#$|tt)a3#d{Ekl@0Rxtz4C}4N?Br21hcR$g;wV@+#zwm(Axa5PZEAD+^0P<{ zaTIUBo4pc(tC-dvKcf%>avPTC6~m3gXdoCHo}qu0i0LN_RhN1wb~IS0%sFBQf5YVY zwU% zm#@_+7c9Y^D*5gdv8@JZe$JS;#(vbbtap0qXRALkq04%2XI+x<(vCgAoWVa(%bclV zpHQe6x8*>d+;I0)>u~#@*ITd}=IsPm5Qr56Og#YFF1<}nKludUir9FQlC3QKPr0Xbu$m9Ee-Vt4_i8YLp`QZpQf(}~jYk|2b(Rtd@wRN}(o`dE7SM2WKf zN`UN0b?OTp(mv(<+_e9p^mD>==%D618;~~1N@i4!QJ)DgW*3}D4q#)E=9ek}6T*;m zF;JLcSKJM-n6yr@2{S+=CR2oxI&!_FYGX#|F&H>RSqs6JC(PJ=)XA7U7D`pm(lV`` z)QTV8#U*ea9GzfpWtB6yBOWclIr$w@`-W3O)vKWD<@9s?yu#UOQI~^tK>g$~dm8DW z$#Qh7GjlCZskqdN`@fwqa2|y%nSp1cK@9Jk_=SbxZtd=vLiV`h4q4Q?`l6yQ_1jkl z!9^@?6cHiljt2klC3&)0f6%9A4yI?;f=)Pb#_~qXBV>!~rOmZ0ce`^}Ri6lGJ?+L6 z0?fE^HdUTbZlkY!n9ciAHe7L?bYZ;UKo#y3W>~*UX&IH-6ck~$OpL6Bak4+fB}ED6 z)HT`$MnDGw)F8+kKt#vuCwzt`wz1Afj99`ngXXDd7w&j1QtO}VXK00rA}G|C#<4i=uGk_a*z(e-3Ba}K{KyS|~ldYte)N!A%jhSS7S2b(L> zI7^%)YXhp`&<(ArRaG9h-%;6(gByr3G!j(%4ot_-%KyVEUVofjX7{6bPAS(0 zer=(l5~a92?QxkA!7T=HMtAUPH%>BULRC?YFceq2rXjkL-1Z<5#l>)M18pRF zbKugPlaZ*|as#Pm>8_dozq5)E;5#R()`2z_TCt1^?3j=+0031|0+5HUBC9gd@!io9 zB>GVR-No+s%mW_{LqOaZt%ZWo+S>Fm&-zwK>AC$#ZB>Kp30HG(e%DavokDuUHx4uyd)3%mEQ(V;Rv-Nz{u_K&jl{0dT&z zUW>oE^9GioL-dN#Ny1h9;ec286~ZbQD8(q{AW~q~ov<}R7dx6iQc}J22^cl40lFZgiIuxbBES^VWrZ*XEq@0RgEVqhE&nqg#>wdbJ|U2o)CQ%XDzj z!)QXjxR%X0VyOW-5q2Xx3!`)G%T0ahjRtUi%1aiXyeCB_h^{!yv4U85eIsmNc)r z{Jv4SY#%rm9F6AL+*uAAb&7MeQ6;kQ-{A};7=<$_;6A6+{`3^oEd|TEMy;o9tCyB# z^Y{v3&}rlABCcDEM88`!QLvzt=Nx-25!$Gy=I3a;O@`hyPTMo0+>+H9kMKsktWE`( zi2{kms97(!uQCEP1g27#j|h3uy!7lb`7wTyxuA(8Ezomkg}zVGyi!nQ7}8w z);%Epz}{v%lUFOY=j$b_@*L|hy`7R}YpJnllayq8Ype>z$muNxI(*b&5nx(aL=~Tu zByG%yohDx=cDs^I&+w46&GY_VWYy`b&E3ji^?%HkP@-TWQ)v~trsw|gAo82TNRa3c ztbGnJ8(IkmKpm$9(nKz>oQ&xELJfVsDE%n%KOWqmBYWPMaSOc=)7 z-T5e~^YJBLdBb4yv696KKeryO@y{(;Sk_&H-HVV7WkutcDeDthd-Q}z2idCcXOv0H zsKV0=D?M*Z2;%Z`SF^>AytT-d1*s7|jj@7O7lo#UIQUE8=>i)*|egypuJyn5k`!0 z$}8ZhG+bel`1^N9X{rY7?CG=YzERiH;C22;$Y*S92D8~}p%1&i_+5#k4M|yw8?5}j zd{mtnfIXPK%S_Sg=6E>d4bli*%gBCG>3ASw@&$ zUVvFq|N6ZkxGV4=NXel%eH6QfvN#cr6{p>pQ zZJYd(l79Ng59Twx?mj;cDEcjNK&#|b+?_l}1R&I`Q=nFAJF5o<#AL4uqE@oXOkn+? zw9P2#&u zxyR>?UgW=uweZEPaSX%+HG-J+?|mv#2s;y*V%RF;nI$`~6A;-ulI1DQWzKOe{>0?e z)F@|x^-rzjtPL2+ZFH8uM3{pjmu=|A_{B904z?#G12n>Zr{5K*vXPkfN#AJK0|yg- zO64~_b;`kbVR_tMvN}ieE}yp;SsN6qkVNJnqT)-50{r4W7xu1a;3}Qd1EbA)U(Xf0 z8Fy!I@#7PL!{hq!u}l%mp0I&00|$?st_iJ9{9?m_e*ruN|diD|@5s z3NNdA?m4Tn03bjuvaM#k{hXe@v_E5h@rb@;?Lj&99d0eBW%@#*>$@+W+eI{BD)RSQ z=(ePF9@1bz`j{@IjyNbJbod?XL*G*?KETDxCS-6&D&uX6KtI<_7u?x!=K8=A70BI? zYWl$V9WlDXrc%M;1fG!^h`O^wXta*Xi;5TX^IlV_DX*!UzBYa!Y`5LHHyos2O>kR&vADirjWb0AEv%tWt3 zfWrNXkSRG(^%jLjsN^{2sERLZ@i<&bfhd_Rf+C?n^l?U?!&s?)#oQPXO51kkdNq9` z#gNbNUaS35*VztB`WL#N%;aIu*QckguSEW8X?6|aO=seqPW#|0N36f-&nGi>U);*; z$QP&?cDzVXs0eG(KzUp<}!Otj0)oPhnZ^t$yKs5Pd8c2;QTruw3Q?duYR7e{`a%vvUF#WCg|gK(*ho&XS!rNXWP*;L-7fs1f_gwJU=Py zcmiuwm4w< z2J0DR<1>uEVze4tZ$^XwW~u=GC$CSD)pGv-alS zkkDtM@YA@yt{wJOvCy1jYd=BF3GOa9&hm0Z|H5Ca#anP~e0^$m%|E&eWfYWddMm%| z_#k{O%nDiO_PJ%)S^~|+C2R+h-vboyCBdcm2m1R&R#$90OT>JlOC8a)sUy zb#$}_9LoV>b8(R_uYAvNbi9LIyWK1PoK%vAU0qA(K(@wV#FoO!fn7(pv}#oa`!ryu zV@Nz84Ccw@_!w`spckZjc;4nK@Nh04rwZEPm9%+BpYi3(*$jQ-0=au^d1OI?YyGYn ziD!C4T&)zIb*9zEd9f?*t+#2)MbG$B)bso#wsdv#B6rYU<+z_YXZy-I&d(K~uAbvH zz#0+8K9zW*oO=_WVqH>pKvG(5iaI<4e4gPay#e2ju{YUTcPiJo;bQ%u+b`K3hij{x zC(JG+gu6wV5QY@G4801zn-(6u%JS*KvCAe0x`&7Kur*bGH^fsnlbDq45GZeyPFWqn zDc(nNBQf8GK@D+*QA)kVx+`6l0PUy~&b*Euf${K;R+zcUsQ0!9q8MH{@A$2) zK5mE)KcrmOKWa=7X|dod%tbO+5SqQ^`ZL;4r%?=5!$&r~cdAqB zusUB`mX3@VUL~eK-&uq90^NJyrA|EI+jzE@>C3Lkw^Rq?w)v}JIEgK3sPvN^K@eo? zi+Znq;SEDWg?2t`gKf3@0GRu^>=Y@b!X1~(jDVZ6WsIakTCTR-^|p58s^`tRE#*5= zHJBY8nZs_><&A!@U>D>?sQx?CAsWgP3Pc0E+Y7XT{|*=`)VtY*kZ|`+4%_Ywb;}yF zb6jk~3HDHNeRqAN3*CCxHA`&Hg9>AffBP*4&}$6sa{gYlMaPIIbe+BUwoWNeB&1!~ zZspc9mys^Yw^f|ljqav5j#`d^t&`daN8Jo@);|U!m}5kvqU(IB0yD05JF7*`$R=Nx z`0#w#S$lYEb{38D;227caN5auq7zXns8*>5TOm7kYr=5{41cvY-iE!FF3EdB+=zZz zN~Dv{-v8tJ!od79P*9!!8-r>vJtS74VZoUDaB24_!jDj41{;lW!YT8gI3aGt( zk#_zA+mrrNtu`0BwGfY*EC)IL{@!e%dRqVLD?{(~V+MBql|cv`&)XK%=36&;%o=_G z@gcRF;|GDaXP2EMHxA`BP4ZNr-jlW``Sg~h9qt_dGDlT^cYR!-IAqLDmAyD&<3$5i zq@#+lA$g5&ZojH^v=yzgK_K?$@43~^&8H2RejwzsJOl>jzU$!?@aG`$a&e)rQt zy;H8q5gXqR3PK{{^_mG5FCeJ-4&S$EIe3K;)wP8(oN&D)kmHUUP zLWORN@43Q$uJZFo`167oFo(-f-chEX|2V_8x_vj$fs`z5{P?V6ZGmWpw0_6`c!<3f z`wdUe4f)R_%wxqxaOKCB*J0%DWPR{8aGxW>t*XF>Kk(LU*oV7B&;9YXeVYs~fUX)-aznHftd8~p%k9jy z@W#0D1u0S52A~A4XVQNjG%ce27PnJd_zAbaYWg4=W`igEeD}%+^enW`Cc~z(-zRWJFUZ$L`OerkX9*5@pB}Ig zsOBeZ8{zJdAHt0D@msS_xcP8+26L9G9gKrbK~0Kr$6KF{(akTt_T%_a&E^Gh(AE$h z!x8<=_r_X7Eyx4ck6{GMg@Vb&yk%DDRHR)`&=a!zjPtUiPVFq zPzUSeURnPfByX|_fb-nj-RqH)>7XFGn6n_5NPT}{%ZqP2W@qqS0ru1lrL{`Fe0|)B znx!bXEcbL7|GEz$0<8N!8Lg_%B~8%wPCM<6ZJ>I|d}LDa095Va`x zot|3B1cD+Mq;AB2i+F zNy5;CAm?{XQy?p|HeNN_r$20#Ndz}oi%aJ5Zfj=129Z}?q*~`FT3Y(;7J4mfxSFon zQG~h4e1o|oY6&1)m@(xSs{A3-8I0=;Pomb@UCGiAWQHu8<*m*l1FLV5SJP%RfYBx0}`V^i0rc(f56 z%DvyRQ>p;wW14+~&E;svnfX)m zJDw`?*RRZjVs!E^yQ%Y?(ytZz6AHoAABf7o=|cZ{FDkkAFObSNdG z1!DLW`KlXMwJ+5%fB+0_4uFU?W1#5$?NT0rd(^#?HM(e|0#EoTBXfox?pIic)Gpal zrcQ`Iz<^YkCZ`S^RCr0x-H9gRSK4Q^U=<8%x&4jEjthR9mtiMtDe5IIZV7qy81tA3 z2dnBxH!lV&M3pZP_L*@u(O$IyXjq4>ff3*${){q6zjF33mvxw8I%Q z)V{~!C9Ke$XX1FdnM~QiTY%tLYBLVctYDTWOf$^EUyw`+1&MMk>*sA~ZWloM-eR;` z%%OB-O4L|_?rgF7QXbAXP{YZZF78o_m%8`y^JR$b7fb;;SmR=EAsdx_KpWrBb2F)* zm5d#n!=Qn#RPp%aK%ROZod(YKlSpt-a>~ z--3T=AM;8qK7$nU<0mq9XJrtnwVB10OVy}V_lNQjaTGn|e`1sT{9wsr+8(lRs>KhK?C;;E$Pjn5)5CM}mxZpTZ9Y1VXdt`aw7n2gh zJAy~Vio>P8DmJ-_P?K;rM6^H*cd^Df~QSP07`JEe8q2xiTWojE*d5v{+%J4%hL@t2~-0TBr>(~OJ= zAeqv!k2Lc(JED9?-AwcU&_?DuyY99pghoUj2|w#6NV{k~7c6RMVEs^Axb2T+Z6kg4 zP6>N;7Nr}nM1~9z{f;k}XqGgQjZ3;q3jg5~`4+Ozxoyx$cfu-JDi2A`Nmpan_$_SE-T&J;53D36#8^xPQAUHg+ zn&L~WvP8d3roB8dPyejL|UYEtOIk&H?- z$O#LrAzXhiMw3|lStrsd%kvz5iy)qKz@*G~739T|auRxf0HlS6HK_Z!a~!?eY!wv@RJyC5r8eF~Oe-MZCG#a=tz;1mCws4uA2ItRpeU;$OIm@`|V|t!Hat$coup}zu9{v z-+Z#srJQsVkM+ZVd2|+MJm`>P*Xkq^Bn6C6e;H|2=t2H5{4hY+zCH{3w*DoZZCjKx zQ;u^0%qQmdF!< zp>5pQ{&D*rm+61@N-SE{(LyLmAw}OAroi*^a6~)7va3O{Cnr>};aW(5#~H0H_^Vr0 zSzTf;CDJ=u)FBVZCHXF(4>;n|S|GFv??#hO`1tGH;fKza4cXvYVo}0U#eReJ7SsQ3 zsTa*VsbQDO=iZ*#;d{%tQ4$s$8a1n!HXMtoK1O%Rc3{_TYfsqfhBR=Yv-d=V;t|cf zzfEfLof+VH5Bozn9$vnR^#Q}^a@>qR?g0(8w0)hoGPG&?u7w^(?$Ez3VDxsXOtqDb8sgnC26mo8W5ldl>e5_m(oFQ`*^_S zA$lwsQ)0)wluVKrFt45(C`sh+)i%yyHmowpp^s(m`=#AZ9uy(S(K*dn2uw3pKKo4i z>t~YZ?=zG*(V`O3Py*V5!e{T?kth^9L7ASFK(!nTYBJ+C-BrH*X}SWyvGl^uvFre2 z9$5LjDS~_h6R&8E>tOW&_z{|kTN!>T# z-jTUrcqu1%5Tn$#Z`czi^n1q!4@N^!vx;Q+VHSy&2f71oaOiJ`$odS6|iOdo0{4 zY5Zl~-@iusC9}{+HbS$(D;s3os~pCy4uMdMiYZ0RAxh6B>Y^bi8rw?aw9!jl)-(;X zc-VY}qRs}}Mh*)Hp1=On;lQMu`puR{5XN(l;J6S@gqPV>IhH$5#&(`p*351Tr6eH| zb`92WpgN5W0R#d$U_j5D`&P&_tXu56aioJmhSVmvOaEfVY0MY_xA=m}X_#f>=SScH_F)mlNsu zI2eHiA;`#{&{=C%6ymg5jDJUB13x zuzZ~8VV{WrdN;&dx6yw3;LR9qWTv0gh62~nVm9x)Ea8oH^NKTrv&5mf znb?bI71WRSJkCS8n%>Mm?q~?NMzqLRhzq;LKCC`D#dp9xJs)sQPn-}$JFQN!D6gi2 zKbYjf)%OU`sPE|cX|?BLM;9*#{~{Ho|vJ+Pg0fsb)k)n zjgYjHJuTM@5B|R&)~YTMAqi8X%qMfX?AIR^Z9N*e?zOG1W54VBnPvOEq7d8;K-bxD za=ERn`0WHNSqOV6(my?Fj;>kx1d~VSuM|21- zv~l*rg;TrU0}3GCa~R?0yrxHLB`?%EkcJ@E3`1wrUfAK1FGD$4W~nG3U^-QpyN}0i zWgw~_i;KBcrVsvb%w%yzKd+Idqo41$v3Dt(642$M9Rw~=Bo$^FHn0XT>Q1-4;2f@m zm}=`(ZX^HejiE)kB}gj9;~XKe*pvBf&E%TnD~V493i5s$X_v~?joOu8H`Kd_$qQL ziEs{wrxQ;G7K4XrKP89FM|OAemtnv0Mwzd7>l{H9q15E=hS^bUu;9S@yC{7Bgqo#W zV9C6^F<{|GXr7j~V2o+PW}841PxE7Zt@U|5m8togy1_rg!J%AZ_l)CdKc|VL!n`$} zkqaz`8EU7k)mvxIBl2erDGiz}ox!RAKf~_>7tMggS>!Y7Zg1lg+oF+K=qJK@}1G$y|n@_&u|a3#V~)#0J<&pb%Htq=2yKajg6 z$L$}@w$C;xXLM=nGOK$uvCJ*Z@51GyfNf&P!`qZW5`^a%>sZsVesG$Q~W%j(3 zKYe3sQ4DZkQbL6a2F8kfgm~kA(_rMW;E2JbSgm0=^AiA$)(A)jL5aDgw5E=i-ny#%h2I2@f1lsEgNPR9`9%Y zq~RX7LNWZ&h8zU}LZgH^uHtL~Eo!H@c5nys-H917Uf-Q`C1cP;g;YE3Y7HBg28U$$ zab#IQ<`4npQ8?&iq={(ZtB8Xo!@_UfCt|5nOPHKhhzm?}tiQCBkblg%BCH9j&Y29y zoZm}cRb3b+Ex1#33~Yt{eJv9OYQ$EhRbF`+mZ;)jrjC@C<>ypgxd$X(uNPu) zi`1BcBhE9v(uW4i2lr`I#0U4nST4;Y%QXnW+gHDiouAxBN>mbLUm>W$$bT9KSJ4K_ z64ad)QB2Q=G;)TGR);LI#3+8|9{MDD`!4UagffQ8t};L#CxP_+@5`r1pr$Gq&-Usc zOVg@6(=kRf!g&~!~C(NuYm=IAQ#{f_g8ZSRS!vGIsPaj*=kM_1~&{a9;rZ zMTCTlNC`}ej1baLGg!OTVogu9sUF>3kD~n(IVUqO)iH`JE=imO*-zr2zi&fDgAYDh z)RiB|^g>7u`lGpXiDf!+qz7sy4gr`4mLP$IPGdN&x+1(XZiSYOgPRLCh@(20F;m&$ zO$llRZD@=1uSI}+x-Bdli=LDWx%JU%&f4i+mr76*5-{X{ZGk05jhU*Zs{L2s8Ev!6S zbGr9bv-A`_xC1ihXX@1S^TfXfObWsYM&zZ5u*P)M1l(V92cwwCf0ld>*KsK;i=WX)AHLx1LZ(oEYwLwSBQT{!$9yAuL!qS3}d4f5>44JbGF>WsWBmukSUHsp_{3!f@`i(*a z)m``ef+G=%+Km>x^7?n;7iZ&Wx7gcp3K(S^W1^t3k2z&^2_sP5H;Bh42HgyB7O?ALZ_I;~m7H^A z>|mBZbR+rC{M2t*FG?zyX#){kZku%D6j%{90e@6v{W_467}|3{ZtMa+HBO|O3zuC!pb4 z3qR$v4i~NmoX;Y!oC1dB8Lrr`YN!lM#JY=;ufMP~(Zzr8GZU^6OE*dWU6<3?ka}R} z3xBI!Zxq1T)qihtIoQ8e)Dp?VfvzqG zQ<3h%s<~w-feIgN!BCl7n}eD*Ao)JDbBSS+eXRBWE&)FA8`J+KrwHzz6&v(BBE1QB z4f(|8KB>AQ^Sd2!tYT+Win5#xRy!4b%uIrbQ=)pC;;+xRsTqsyn8eVK7@P37jL>%| z|J^bqkm8An!5&0eT+;a&Vq}n0jNu~cU;(rBD0X+s+B4rlzCu0vcLyh(p`jBCLhzGi zK|FEWrXD1*cKZ|~Qz?T(|8KpbGVg-A7n$?>5D4l;`jRCX2~*A)c%bZ=iyG@>b?fKW zg%BDBba^4H(2k0?>VFgc%5rf18L9aq30T1aD%9%rW3R!;#}Tf0gk; zmjZCOPpdBc{Qh}OGpHvyw2=xgY$9lECqW1b5@XF$oXw>ycxglTUjrtS%(PIO?NlYH z7(t{?@rmLs-N9PifA^_6N9@$GPLO}`2;d6lEai7>3JSX~DzGMcFb0zL%xtXv_q+o0 z>A&YA`PQQ8#zdFHb+)?zU7_qCr~brRXDIKi=rU}=nl`neo9L3uV_TFe#fx%&QSr}s zW((YTh^nwmlNqg0Snn3RjV2=?M*_Ny1>q0Zun-hN>+fH|*X+Jdu^M$r__>Sz^9i9S z41Yo)kk)wo$1(kjzYG~&u)*GNVqIMweogtn&ep85e4kz8gL`A_r^tdF9vje@2AfLi z%l?}`};_^BZdD~1L)vs-3txAVCYkY6IfFA*!YTNtWgVIa(ou=G6e=0o`hE&tIF25r8Ep)16r`lkM<*omrNGCHK(A4?O6%T8a;@nI z*86pG$L7t`bL-0Amg5j`LNh%NQE2ts)3e@A%}>|c(qdvjhpOYIlZw{GKc3Dd(U=_7 zGVp7bJdu2oG1x6Vp;b_3tkht5czDeZ>)zfG0{$W-U9}VZBO4#@?%P)$e(u`;rV6~L z3eBH@fZ+Aa-p_a&Yc!TtP!uMzl!At5}b-`kHfNZTxWy`M90R4 z`HBQt_urP(D)rVj){_2uib*G98Pp~$p-*QNL;K=Eiv$@pMKDTlOZOoXPb!8#B$}u) z(`t+gy`ZYHBPTwrjlRDA1gMFJH`?I;`lucn4fb6um-l**R3vxmZ5}sNNKQ`f_(Fpy zL58!;TD%5+=#%gqD=0Y7Ao|Wow`zy1TqwtPXuj@qBfIYVu=al50vf7x2N)~H9YIqn z82Njy@%Qu2h@ATRMAcHYyXK0freDp@2NWMDfgX%M%eZ(tp*OSXkF&j|Xi9$8fx(b! z6o{IM!C>pUObH3hOip&L*mp!*4ggu@RVJSE`xaZcFf1`X$(<2PV&d&Z>1qbv`mP7zIYNS7yF&MlcF;snheL`|FVNLn} zG4+*EQGe0eh;+Afm(n31ozf*O-67rG-Ju}e-Q6u9AT3==cXxTu{O?`wdOyl?80O45 zdq1_$Z)X2VvoQ#sx6Rm2-hi9cbOeW1?z{cu>Eh|_<=ti+hu_Q7%SqRN$Le{c<~#IS zlMT^m3d^Ze=9t+gNA|tkNMdpW6cWn(WJxBU>J%}Ts{ASuVnrEPq1u#1J!Kq}{=Mr~ z0k0dB)@k?u{w(6R;LjS|JXcM7vqwUlTlS8CfWT`xG@rgL)Qkvk5IktZY|nx#)13!t z6>ogPdxxW-xVU(!q)f)aflaTPyRia%P;eanzrPB@|B)7Pd}3l~e?@!4X6IL`iMjb} z0~)zs_9*E?h$uerlfAKj9gGIC0D^@oEG&%1XQOOfN=iyS_q*9~V@=$Bw|&Sg1uZT3Qb;}SJdtCEi4S%d z2A4c+`RA(AEg2caU1uRIS61~l%Uoa?d+3DjrOEHv$*BS$RfBzn01x`CA6*FMParZl z8*03~y#6L7ZhCrpWtF&!@!{gN9vS_VFy1xBhqX|HSf!@*W@87}nY37ldhUN=A(e&A z?AP~~le+)Dj@N+{EKp3Nl=vtcm-jr^zg0Xg$GBAvixe`K7$hPIxY?*2P;Pr-ppuUU z?D=Z25V2PAg#A?%1-@~N^WFZOr%}%pw8h;&IKaJ*1(X(`3VL__Z z@We!MUY=;A@PC!;OK1pG!}9U3wD(cF*?xlGpntHU*tYx)ReceXLJ}UERBkYI(1a6+ zEHZ3q{{pS;KD!V!F%9kFiKt@wsGEz= zSbz5tPGlSdmD^zr_!pL;5$wl5?ArIEa$mjsb_=Ro%F2q)$2d{}lP}be)f9K+LGgHH z(Y&0>ZAV(JUP+080A+tMOy@NAe*S1)eM*&G@{Q4eJns!B$}pCd80xAe9cF~_fY;+y zs}8em`!Sc`{jg$D(Y;3HX9+_?ihA>jd=wv#h%JQB|6Maj<%Kw#%EQ~*8RX9$TZD4_Y>kLtHPU5rk-WV-V!=<1Sy z!@xt#KK);R=uZLrNllFgAEnM|S7Ca3y5;$1xfT3x^aVX-@=8whF|*08a@X!siQyj6 zW+M7D8ODWXMSV-lw|yYjQy7X4-Zq{bUvUm!0s_B_Yx6TjepwK!&7&>QvarNy z+qQq7Jl7gBP&-jprT@5~hTVc4g-KzpnoB9fnJxfo$c<#Rg`k(~q686zWviF3>x zSvjU(Xb?nhwmxx!!7=TARtrnZ+^VYB#KgoG(!l>Mo`W?Q{=EkA;75A16lm}o3cM%Y zWXGnBElwO$Buy`*GDu}j-b^EA0U~jr6n0tQ&T^5k^iuPujx_0Di6V*1q@~92xtL~PtgcJ2_A}0}EdQ}X{=5mrY(bK^Ar2F! ze8|?G3?JI0#yan}tv-Zns~X)sLNowJlLF@a?r*lYPwt`(08{7oC@|y`qrMb?_jzeC z5l~&8;}Cl|*UukH%)1;M9%71Kc?5wcdTMKrg2e)V;IHp&#!?T;K*|_CALNwhvZ>B_ zPmVSU*beQYCE*NhEPq~({P2+RB-vlkr)oT}tw0m~F5tzbu$!P2f(Fl#MLvf+$UPpG zCv!bd_CrkhbCar(qT42s{>q^jLRkOZvoA_NITO=y4mX;FvioKX_Z`^a@~*BozK81o zu=rjiWh?3G##9~Zc%KhE?QnNf2ncj`qX&RxLwP4RQ;^FPs?Q)I@O4G0htv2w$+aAp z{97nRsGtXgl$4aqN;{vZLfMo=P{od$*T>zuE;IG)2t~t#6z(PRm0gdQLMC>pSXinR z%atgJX)q%Ug??GgU=Q1;j-vnyw2z|Xy@cajEYR3dSC{B@+L_|E?vv8cz**I@fmGG? zV6}46)y*KGywK*t5Fl(I^y=h3P!`tKTUlNwe+!ZnHm+tA6&t_U z*wElbUAM*n#D3ECXp6`6Ssav(?x$^*)DKQOzQ>fuuTWBagbM?dacHicc#h%tBC7yn ztPWn$)zy7^+7;S`fY5g}#(-VG0E6ozAot@=>I_odBP?S=@3=_?L z7LPa8;y>$o{j{&>2R>+x>b!VSRm)Fu5>4 zsSsmSmZ_GriwkHaXsPh5I7rIs>aGjJIjH?T$F4~U2?49NWUL!g`?6vj&Vez`j+S)3N6Yq7A!!gpgQx;$A>e%P1bY(p}JY*(G(8AK@ zPQFxxMO7WPtlEBzAsiT{%l`Ev0y{2Be>=elfE|9czDnOb5=>O~7%JzH=i#Dn2oAYYw;gYWvk+3W68pEp$Ka93_qhA}h1uLQ=;11% zp1}9@;C<)j?0g0`%H>S<3yyzU8lh3`f-hdpZkAUpzW6? zLwCPlcjo5@0jLsz%b-5Fw6wJQ)x@tJbT0KOo#BiRPLMt~JUqNV|3Y6D$TuMg9O)&!%;Oq<~SoUKxeEbqJp0UYzxLgltu`T=?sdfPulY+9*vpf|$N zh$1kK_SIEj?{HVqBNdraR21~~VQu87^hV~9SD5h4a4K5p-yVzk9W{63H$b1QI8AK- z4I?WmFE5{W9IexAbu^Xv@&5gLL;R1`maD7nZuKU^iGt1TuE(E2y?V>Y2t$5=PRSS` zaJhgW+`T?AqbM|{ZPzKmh{tEG--RtbF$Uo^+-vSZ2CP3_=5-})ZEd@6Ml;hzM(2 z?#kP6Z66+4O6RU>YfHO6oWE^deR}fd&+0T{*+I`;az>e-di+O&g^0(Z_iMUPHezV= z^<3U>r;XbVRG+h6c=t}ds_qw0Vl>I_YgxA?dlUDw`9@a16K??X`;l2XCd=0av*X

5~U0sV{a>~j~%*?=fDXFY9y*XMGp0=|e`TBOn_wm>p{K}(++WdK6mewt- zBDvIQyG_Uk&o}&CqU_TqN@9m~&ckWbN|tvsr{w`|2ks zG?Tje`c}a8?*>?WUkS^~B1=d}==eQfKOJav8x2I_>NpJGLbd2r>3OU)*{#P~rs3e? z0-#LKz#v7I5=n9EPfwc6d*{#pnu=_ zCW^(4pLA&3iafU+jS4kdRCL~cla_-+rD&D+6$%>eG<;f-!{3lM>_$Hj$Srlfc2dnP z?Cf^azEtH_R-#HNn78Rv{eI0)jCQ$T9Ov+`UwjEbX-$f04Itu*-W%AZ-D4JkB|_o- zDXzcmUMHK@dR&?Tr~tp6E@5s?N9KF?S6M^t15h{hf-%IG+90*?!)eFmr^AhNp6afL zcSKy)f6Rp*36Sv^|D>8{Nmpv9;l>RGS*Dd<=I7=Ha7^%H18{aZ&Ij}l3FVfXr7vJ< zM7m?OKp}^tD)k@euiHZW^AnnwMsf&fk5Ep#K&!>J906(P)`T1J4uG%Wn zz$s8;fpTEmd9AMJ_v`}dNvf6G$lGF8^YM(|>*q=^3|T!{u2+RUfxYAa2_Ct(zkzgON#w}wfYB+R>BL5EoC|0jZ%HDxz z)@ytke~Q04^#bxhs-O>Vy!Y!V7m{?QeI={<#g_9yqSBI*KY;Mab=vS`Ds+MG{>F1b za;c4VW!yLsiWdiIYHdxhWZjmRj}H+p=y?f#%=XXEE3AEl`0yW^E%p>bcfIJJ)>){# zFaLq<_IrN*60%hqb(FuVwr5!yXHN``d}9DuUak5$!(%7)>BOx&zo4K%e~1CJ!2XC{ zZXqsrg5S^>iFg_9Cv6O-uvnrsj@vTe?Nn@>brmIq7LQ#aZ6!ZWaH(AMCo1aN&pfh~l2P)aniOGFF zD(=<`HMtsSt)NI}rrWlaYCLN)B$MMIB&jDxm63ER2u^Q}z5W)!3g;CHuQn6j;PQ85 zn4E(niSM){DKHQkG{si{RJ2vqgX*td`FWr(1o`&RPjUJf)W&-6dq>~P^!0)#Atxs% zm2V~xzISmx$r%Hk{d#phIIm>YBMbJJ#P>6=sEN7znW_6;?W0zkv~8Pi(F(5!isvf? z=>Rvt%N^D{b}=KwTeg$6OG-+lDo=;Mz+*&+yI)O74v&oi*N+u&W?w+t*bV!F^_HU_ z#K>W8oNp7HB^;qAt$~P-0v&SK6@3SYT{3gI5#eg+;hd~@LF*x~|?*cx==kDygHk^3*9eJdFlhPk;1tS*~ zVl`L|oef8XmTMLZ)~^wbeiECisi~NDLr^KH=N?7ZRUu2EifAzq zSb-X$CjuiN&i5KY_Rr6FX#1R8t9L-GPvbrXZlBR5ZKVrZSP&36sAg?J#rOV;tZy)u z_WoBoH~LhjA!#CB59pxan;rkAp$Bfia_~c!g-{pb(6La%`l;!;-cS$rq9RoaS zB%>p_6^-A7D-!lMFMf`X5P#KThhq@?2z4SWBJv8-TAP|^N2k7mMK;g@DfHn&wZNDpFe|yD*}vv!Ra0-qX5&3u#kyB1RP=kQG}%>K6krS=DCyF zaD0h9*9plyZ`era(0;qw1 z+4mA($C_ zlbGOpHQPe{$YBEer!YltWM?cLygInw5bS}4Rwp{(HH2MzfHHTZ+X!=@T?lm~SrIJV z-^Na9<9oDkyV9BpJZ^iF!rWz>9Q&U{{l$XUZ%IA2Fx%SNENpCG4G!lj=_C8VCth3^ zgP?7ZILkCuRqh%~H#%Pi?A2`vWt?CPNyatKRbdMc)w^~JZH@ll%KOob!{8G1q3;x4 zoS6!A;E;n8jDZwVQdVYkywvD@U9K-sF+pTY2Rz^2LDy+X+?-|fU8awYziMG3?7uc7 z64%kii8t;`dUK?5*$}F!sr?@U#F5A?FOSO0%TtZ9_-~ayNUtA|r;l1K&g2;pz~ZB6 zkA$6Wem+T@>*0h(glBMTnp|j#+Q*JOZ_%A5bdSbQ6!ed;xXYzS0?nVC7)?cAKW=o} z2mn8@N)l>k$y->Kr<6+sd#8UPL4xFP5$+1MP)(7Y>+)(4gptUFNq|>bmE+td~N3_kjK1$1A;-;E>T1uvp%N~*9N;CX27DWd~G zDpn-NkXq%Do1vzolkAd)2oIQ42qAqH%N=32O)gUuNURwIC8dx1wXM}RE7`aby*nf1 zIk=Z=O;F{)Z$p3)5lo4T1aC``3SSk*z3vU3pCL)6+{N8*Ih1)yrL-POK#<|$9R^*N zONBM3EMc+>G{7~l)2X>RIBH!OZ$W)Obcpp1hYK!ZQ(69@UG7@jIUKP~FU);3v??`i zjQT@MSgSm&d0tgXcb=LmBrcGG3F@}-L{&}A;h?mbv~~cz5726a#kBp<%@^_(QGzXt z%38gNY30+z$uW9PZ;M~DILsCP?`=?XmA<1lAMLC%kvNBoa+;g57oQ9vT=9Iuk$9CL zM_T!TW3T4I!_A5Buvr~!tjEVm6q(QlC~yZ79UUFKR2IKp^=)|b-=9~2Tq1Ba7}FH2 z_eOkF#^FqlHT@he_#_yN5q7=v!EsA!Fq$CgfsdOzTfm6Nln#`~DGiHnz&1lA(d=M?8C!m)6FF%Dyo3%*b5M-v?1X~m+1t`BxHP4<*z zUwjNS96pB`3eeh(0D<7i91l|Xm$r&Wt9wdfT4wdmlFHF?O=n7%Wb3Cy!PXw=j_Q>D ztX|qs8h~d4mKHLzzm*roZ1i+@4!;tbM~^?aCS|KTZz}U@*gvneFer46JaXw#kR~`} zrieX{^^w)7OqzNq7MN<|tJl_*XxQA2QyB_4cbfaUvACsI>}8QB7gKm{wa&)a*imiY zS&J}IW)|1OY?N3Fvi*Ve^p-&pw4d?U88|U9F;9Ti6%`eQD*8RlFlyH1%tsuL3=2=G z{--nW)1BBzLOVY~rKwvXE!6#2>`z)Y(VDCm1Ix-f&ias_Hr{mq0jyi-kG$pjL!v;k zAqe}B!^BkT9@*ad@9Z_1IBUq^;^{SJu2huZ_$OkAnrbyPG}aqRzK#(=FRO>qRZCL0 zkl4S4;x#4vl4HhG(_q9k-#GKTD~tf!ad_;8q+zSvBpexd9e_YV$)&OvPGs2SDuwI+ zdzfDVV$_dKhc(YbCIF46^!ANVQb-iL;;Pc{*gw9>TMWH2B(kS2_8 z%)&7xzeeQN+C3S`hD_Wd6TMReVkgdD8nC1V1rwx#FCyWZ)WagIJfzFB*;%_Mvc8C_ zso|L8$veCm<>KV1ZHaQALbm56d0riOHCm(0oTB=X8CuFDFwBh$a4I{($<2xurtzkc}WE#H4^*R$FSW#;IQ0veb16DakoFWbk zsmNZR2gaLwv7_h0NA3j2e@kv8tB>NZn)@TP6$Vh>1=m>E9Ga+Ty>9e{kL*P7A)7A^ zpndVYWq7OLlAhF}_9L`RJ#E>I!^c~2Q7iRz)9LeY{2PA(eNRu%2j4>=Wq1I5i5Mc< zncNMGXy9D8rzoZ}(2=a#QYp;`^66*E(IsY)V+7}vwn9W3;+kV@MgCsX6x~4r^NiYc zUcl#yECGJlo67%hC8VhF^1B*IW|kxoa*uF7#$$1aQcFbBwD~NB^cYpQ$Rbj{3Q!7f z()3Ro-@>t>C(PqmijZhVSk}Ogh-LV3Xhis|Qfa2jx9- zAkZ|b(vJxCDJ`1+6NpJd43zCW{*}p!B#|&<9~7X;IdW3=u}KvU;q9V@!mWSf!?k?e zXt1!_dmJ}rm%rp=Uk<+Wj!Y~h!1A=2!_Y{Fc0gUZ^TX>j1LqM)_)Y6TZ*|o3K9_*- z!{6*ft2CiZ@1ud2f*nUrY#LpukPC9a4Fx*OK5|G~Zcr{ZEsq`>cnxv6lXuSQpvHE?lt zXW2MObmwEOaFF7aaHo%Ky~jC~5{C{ng)neo(jrm56aD$I$#$dqzNR%VihR+6S<$Y1 zo&4VmP9n2TU#gf5tJF{!svHw4yOp?JbxzOUk(@XFwVKgkq@Ljr*|VdA|39VRMK>fQ z1azfm;$q`keAyIc*u-AS$DJe~ZbHH}t9JTaaj(r4;6OC9W8gzcTE-F&CVga}l?8R4 z!}O((j`Ng6g=Q@!%?^%)A<)92$%L{XN@8*{9{5*%Hq_PQGrV)odV?i4_%RibM8yz# z^CY4)+g+K^`Oo}u0)jB))s%yWYq5Mfn>**(t!Geh5>Sfnc(Ck+khLj8bN4$Rm>89C zI7~YQmn7?~-Y&R!u`t}#X6<12iE5~M(tf3RjY45@dR5={zTpRA0!R@5f1i^wq&jJ)rSO}+b8X|G4aX&YLNGGQoqQKPIJ-8RB1k- z5-WcGBJ{X8aT9rkE2^ZWH4Mb+mdBI!;nC5}2)e8VJMh@sx{P&6mb;xDGl&D5%&eP+ z6)uXP=dq0oq2)h6iT$@2JTKCQsAIx0ZjV1m3a1?k-nw%@yLXVdcVw25*?H2P{DLWS zu(q9-(dkw4>V70sIfwTTDJuK)gev??JWxRGn(<#vvH*!5j=7%9Q*RII)m_U~v?M}6 z(LVl~XxS4%M}1ZDg~0p%hZn&TSOZB(cyysB`?4+u>Mt)ZK#7rl*8TJ;aCAEl=&2T* zX`j1*XaE}DFA}$vUce~!_x7L?=|&sp^`b^+Z*i(YB2rBS@ptph?O7OVWLXXYp&8>V zXc<}AdtfCc$(+Ad($E+JoI#o%2cUsFiFajQ`kpWbfE>T0K>>Ls{vMz=KCaw?K#|vE z4)$=5_{?t;lmUmT3_}ZEPn~rl?(Vv@MyaUpIuN*k zeWPRFc!<)q1NKhB`UF7FjIRUSBLe-qDxBw39tA z60tfu&k-0R9VMg6e~7(hdG(!5$JHZ_nErc_v;@!(=G5!jSECNzew?|b#U-;+?-t7y zo<7+BW$Y$NI4W3Ss;IVFQxAt`^-5D+{UdA3Kh>j9R3gnTZ;t~z3FVTCilf;Z?Cd+3 zP{Xrozh?#-9BVEj{pSM>0zOyk?8ka6S{u{GJ+z=JOb;mql*qKJR}C8xs>j11hTwZ1 zrO*0hu0qddbad1MAo}k-4jaDeJz1w7OAVH9k^ekgA8K{`K8xITTg|@vtX(+Z#+qCH zj`=kshwl{;A3|i_A9Wp!{Y+%L9LkM94H-iMeY)7nE3W${>+9eqhy$b=*BM*E1&9JrQDglD;e&p&dN!{cYi6MCe~iYjU4PO3 z{24sb``HJdTGGGBvc(#ykGBgN12!WKo2jfAiyU1w7^6fPH|2nT9FHu3)`-XCt7*59 z7VUeNn2z?Y$YXglIj>h~hD1M$_Ye!`zt-4_Ip8YI9qeSj|E8+WT_6*OW(rKK;ODV9 z)!Iio&Tx~wf_m^xsf~snZr!Q|8Wv2og9#n$a$oW<#RZJm=W!G|{O$Oq}CL^D_mXHm}9G2CGeUTwdS` zg%-Yn5<_bJIB!&v0&j%N;oPg?u%~L@YX%&NzfH@w{o9Tp*ETRP@SoLW&TY5$3!+#9 zsTaL98%!HKp73@^d;nq&`l6oW(K(LUl-4374<0Lb>PxAkHmj<72Ju`4Zddw2$TA*j zZy(bi6sN6inrChsE+P<8+KlBp`2%TMr}8X7-pYR3qLa(yZR`$X`S2;2e9UyHC|DZd zuqB1+a%rU@j6{6J5J&d|oO16F1}vkj0s8XU-pS?y%c~Lu4!KZ`LneOep*Iu=l9Wd) zxUhNu8%H_t9ErU%FjLac-5iYBbjp6z zVbQO);2Z%xWH^k>H+6w`Yw*-Stre^Lz1((B0QIZ%g|uzUm>eo@CO{>E{Kt6=44!CCDWTx|*EA()Jo>@`{um~j1PfQ2 z`zgib7$s)kor_Vgd9(>>q!~vGa$CQ-&8yXvj+2`)2y+zN@p;0ujYaI!o5*&?G;4fQ znV*ct5F6sQS3(x{2le+*$LqMUGdZN+5TZ{rjslKYB%dA%6gD-rS2ZB;H$5{$z+v`_ zqM6KUzW|JD{F(|`=p34N`{-y7{JWM*pN5oK;IM#E5Kx0FbXwWBZ|65B(=#*WeSHO? zh`4RHa>GcMs+sLSeG>(CLPM8W}Vr_NMI4$f;$`0_Jymv2P3p z;H1Ru6}hpXH72FoR=rk2N=?&v8hA*Hbsy3*p#X)^c2hq;88jozTPzu`u>H#v_dJz! zm8ziTDb7a^Lv^5+MjdepB?+04&bZva$_e>BIKeHe<&P zsocL%CLrA3--lJeS`1<}oK_5+@kp_ZCB0xjN0)suiDd$rY%m9E@4~PM4GQjzA9LYKu3VHiRzXhocq&IF zQG{zmH$YFKQ`~{%EXe-d!2_2b64C+w_{CO|qT~H`N^y~&+tGpuFqME9`YTJ|F@72K zcQcmNae=`N3}?FozCZ%89k4B@KW7q7PV30GTiCF;b`<%G~gfppTRx%I4+ zV2Hs3+U-f}F6p@7qcunm5(8xt1eDx6*C@7k*)q;OG8VomRBY<3t12hXWTW*fC@@Ba zR(%xzEHtZnjQD^74UM$uK*rq8Fgvl?s+|xXzdy_B?9t7y_ajevgyC>eorJbxE0murEPE?6>r8s2MGu8=J4QVRe~mPy`s50Nv>bl3hP{CoZ0m2FXYU z^$LhtQo5H3&Ma_^adC0IZ`;=e_HH(E>23JFoNYbcMDc#RB8$w6XDjmuvAE;*!{Kx` z!fmMW9Z0})Lhz9>K-eFIm7s_B97gNhj~nNCfQickq>@+mJjA7?hQpJ+mdy#<7@R+- z_J%$@M~FJU;~CqbA&r>HYouJsYyUlm=*{I8C4`A(63YIw=9KByMF+MNqa*_Df_+u8 zn`zirGg(5iI9s0Yu=JX*#yZ5}ZTZQX6A$ee;Kp$uXPe?W}a1bm-w$yjDMYZ;N{XVA(PLNJ_E=mX_y$Xof*jK9Z z*S{CM0le>c`+Y}eQD~VzI&tgUb2@Vd1=dv-m9nzj4^Ab>yJt5Ko=xA>uww>eeIM!K zDQKXCMl6dnKLU0DUJHW9fZc)b4yfKFoW+V@y2xDO^?soTFn^u}P^8Jg_)%@K7Z}JH zh`!bBo;r2~d37xivIR%nnfC+84r{eJzXj(Yd0#gaanaJ27zT5wm6`P@(?|^`#5z5$ zA|Aahw)!7M4fh{01cbLHFzi3M>Lyijdm}Iqk<=@q`kaYExlCx2A4n)*Y>qQKnr+{F zaT|(QkeNKr`i&fdjmehVN2%?7=SHk1g zVByKM%c!Ts5qoj9711z>(-~Mz*2xhE|CDwbK0Lt3j2fU{RvAtIVpW1vU6~hmX}lEMdeyTd=r3_N|f_Kd_NIe*fCPB zka`rg_68d-wXJ$Ww@4s}vK~q!44cEkPzySjI6VsirVr~o1+rv%P@lNqqJsWA#LEaQ zV|7Z=WU7y$LrnR8aaa^EnJ>)hwhLorbqLD&2>nyo-)W1z;fYsYfoo)QmRDh}Db>FX zX|@`2lVtkBIm%>#1n?V1&7MRWSq#z1l@&P`m+M!Rei0S`rG6&fCj|lnm}MBIPs|&l|WzMlueiw@1km~`k8t8 zo+aDwjmP6PJ}{?50qA=HhBICdBVjHsF8Va7slHE@kxphM-$kGDS{w;*@| z#R>#5@KL}E6u=meBQz%U^B*K1OVx(PNz;eP2L{DVXxILaSy^I5sUp;*6!@r^b$!$g zFv(-koqQ1uX&ImUpygnhstkX;*NMb#J{ZhhW^>LbBWsgkztykEOt`Oles>^+7AH;Ja%b(jvHVJmr#Ij`vcXs;^B*RV`ANGdO zmDs&3!lht^n<*MZZ=4@2*Oi8TD^tiIIiV2-dr}fyXjJt7B?rzcfJ4|)aB#$Xq5HpN z`m_EP)#s6#tEW{w^7UYfVqAx@uAp(|pQnMMHfwiDBKgsm8+FV07J~%m|Oj6lmZ<}zkJm;71J@suC ze5Ve=SDy()nrkeW)$BK`W4FqNKG|Zc*$2LF_ALu?a!T;Njs6=}iTfAUL{DE9z?UDd zOsD%ZP|-VagOMc?Dwn#L(CfI`O{0DO?P@iSPxeCRL+5E(e@E!IxY~{UF!jY-4j(=D zM?ca16Jsxa83_qkY}t-qA1n#?SMe@iOh8&%s>|>LFin)OFf{p>q7|`+M8FG{pD03uJCQNc5s$TNYSM}E0#ev-<)bF( zBD8Xzm50F2WqLB*{G)XRdLQ40$BDJ;O4yt{gFz~oXI-AiT{d59W+u}wnwJ}77AMh; z&%1Wyql?dZq^OutLn2ePA9VIU--2r_I7mTi*bs5jna?$h>aA8K%#;$sz|M~%F-~H* z)qqvA_)md8nYMY4Lh$$#0de!au{LB~ZJlUkd-Z%|Ht)VVa~++4MOQ}Z!4B#F3klS9 zfJAJVv(gRT?qqFoz<3$$Q7Wm27*UVrc>&ZFo+()k;m@{|`Gwn<2xbhi0 z9aU6*k=SD&n;FV$uZSQ(|8#_+vM2kXI%@2()sms$c!^YF8Xahy#&>e(_a@Tz@5Du} zk&^ecn$Ev5qMD|su|A2Ok~Bp zLu39OyD+9fY&}rRZ~!jOMw;DpMU6Ju2SZj0X`B&YETqo;d_$~hmV|3sa%;M)JT`g? zc3}o?@D0skwm5xYO+`=<$jlqKzBy9I2>}e|%B`8^S$u-2qbEf{M3U-#EqUk|6_bV} z(08=(6zXHxTJ<-Q}pLonvplC9~;r=`O?@nqB_XJB++%=(m(+xbudwbQvI zop`Z{LBSU-r)!qwg)pE$5gCr+LtE`GF-Dt8p0Z2FVlpun=h#q&YC z`?0Wp6*nN7%dXZdhM5suO#mR-CL z6UmstSJ<}(@5hSIZ=&6Q+yf@HyNgnx9}Vrw zv*q?7W4{&M#C;`t6s^9n5O*MzNgo9*s-W<9blC9wB?6WB8HV}Xt)C99#CQDfNHP;d z-a#cf%5h}SM<^^UiOO|eXzR3`sUGD;-4qdu*7A_Z{u@7CZ$}T7V8o)$&q=c25mh-( zXY{z%ay_Y{#zUP_UWeYoh%2@t+W5&AQqS_tX^g~{sRcIya91w zAj84qLIZ7)X}DK^RZc@58C<#WylOKn$-0TS(aRc(f?nqPC;p+Wjn~S`3aaI9BWieL zuFBJY>nt3e3JmDqpiGD?gE@tn z-@jpmrKN}chr6lwg*+?NL#sF{e}ri?7^I!6VrfY0Q#1IMoO2DDzBNJhM;Oc%RqjG> z#_Ow-gG;$P6zR1${lxxEIo^2(ZG>B0yEm}AFURwfiBvX?BeuJf#O|*gt$enmh%d!j z12Jb>Nokqn#P^^3DSiQ39D~Lf0=W@OiVK*Z5?K^&ndJ0bKl-`R4b;>^W%=AJf{7q7 zwh+4Rw->zv=pDF#1#C4X6~28c)BTzNaen;4$aJ1*bY>_oXknv$o$$S_H~EG3C#RETc3Ffd^K5KSXzkKxw&?8i$$Pd3^t{} zLS%d&W4XK56KyK1b$!rT!E=u@p62nkc--%sh6aD1kZ)UTg)`qv6WT|Xj?6DC*`f}X zuZZTXw?c%xgK$0J)vobEjgBkBjS(wO9D{<0U^zC5Ip<@CHU%HXNT@<%VC{kK29kWD2` z2wXZWiIazjZQlD<$9 zKTdI&`07X3E0p|8pWw~0uP#mbAG}v1+~CuN=FUHSG@}$PnjQfUZpm0(!~sfJQ$eu@ zfyS1RiVb`u2ZI)-u|Juyp~zGRi{s1+QQM=Hp&{!|hj#1niuR`$PnjE>@vfKo442A< zb~$BX;qf0)tv5Hw?Hsb@^gYAozNKDXGc7yjiga#VJ#hmfaoFS=y3ym!38|@T>#O?% zJqdZQalka(jWai}Fn_f)K;LkK%QME(Z~y#~p>neRD?%m?CV)y;;((s|H97gl?Uv?s zG$|&CLMKJmzjb+JGk)t=#US>`LhiX>45;KJWk#78n*(!zDeb%37WL?%G*b#O z88I3kog#CO;d|p$M1rrJ-}k%BHIpM|tju=qGF~M;nCgR(c~!MY3n=V(H~-L*->QvtDn^|K-R8#~ zjz;ky3x+&CyEXr<@B7ow+?*}%?V9Zz8opW55Q5w*Tm|}O4W@rv6^G~5Ufi>XTLAj1 zVZZ(?b)`SucY7x~rsXmzhG7~X)fdBc3?RJA@esrHm=R@Y-O$h_lVV!TxD>_wG}8Hq zz_7BAnQvn;eaX%kOpbZ{Lz0OjN}!b8ZW`LfNLei=!Wbzvo<%D7^Cy|FzS>t zoW$f@6=xSZd(1U0dug$(Eat5GDpqb{Xf1i`EW$O! zVyOjLvMs$rno23|kI@4d83&;n;dQ(oVE6u#VHwCZA-lm10K4Cw(8k)Pg4T9ajN9|c zJ@jL+eVmI50y3s$;cpTHM+Yv2$F(b&*K^SCg8?%qz>Z?Og5y$qZ~OshP%#0{Yj4YP z4ptxUZpF|i3DuNvNEGJ~2FKc?otV1<6B+H;qu)(Q-yiI1HtoTVxSmolXKY0agxv4y z53MZH{pIBR8jH$*Ii#&QuQ!6qz21MtCdl~3A8{=xzU<0SE8HG?<|Dowfkto@y3RSg zm?l)HC$cgRy*hTU%ybU7yF( zflUXnatg(lInsovDG17zuaYIoSdwByD z;>5dqoUq{!LBZ*K!+e&+5O2wbaTF5i?EqFd0>yvIERgmI zthsNZ&Q)rs@RC999q8`E?B8HKw@)H(OhC zIoL8@mAL8^NzR2a!vmxj9NzSgs-grs#)N4=*!t=q(UK`&v8X4nI?-F>C6&BGguk1K z!ArI4n?=-hp=Ct$um9Qaj$oT;t+4U=bH{_{n)eB&RgmEL^K^CV*@{Xnw!tHj-$t#U zz{oNS|Hu^q9h-u3VxFR5&%@|7+u4Z$I_sw4N&~yoCqk;IOE}fK-5@q_pAQ%=a$9kL z2Sy<=6!1uyS-S2hA*Mrh=M7(AIv8a?$+in9k@{g2{qrZyd_pL@`M8wo_i;*M`io zxphD4x*p3Eg+grEJFqcFAX9tb?(J%Jd!UD-0gILt4BK`ioJB?={b$zOuJC~D#(edV z7W>&=>-eey9f#!Nu$8T`qzY>0xg3h*U{34eEqQQYDuQ8Dvr<~Jfwc&iLRh}nY7Yi( zVyDGt_IUEuO@pyH&x7{Bg%zz;mA-;tseie^l9!$sq1$T+$jc#cRTV32d=k4+olE#| zewpF&vK{@i**K5=U*MtU?Fr=?i?*zUJgTuQ{QUc`#IDmWl$f?u^8{N35guD6k8rcs z99uAuxwM~P%rNnRk2LNQj0%I1m5ZOKc-8jpMRVF4gx|Kg zZ}oaC&2{8_lV!%zK8lL`WW?rk!A>UFIUaa=3(Hj}1xpW7Id zW2)mYypmd}qLP*8!odFoZ4U+%AoIrHHlXLZ>pTBfoLpSsF_jaw&ikLh$qV_)Y7Hhs zz$_EEf#}TN?iw(a7BoG-CKlD=m{=+QovIs=w@^&7IjzU^3MBo@{}7qh!O2|%V~)?s z@X)UyqehVE49E(^S)_wYTXqv9Ng?+1;pty#IC=q6KhokLaP=1b1^lA&y0Glek8-k- z&0g>s5=v0&l!1h&D~LEuFg6rs`vfhsGu|gOGn@fOJWBF0d@I`#rutfBk+lXNG5HIdjeqhk4HZ+^_3;XafG$ zdq3P8OnbYVSd^)bmQlGDP0ig4Ljq=z&q zF_cpjCyItst*U&(Anv=1+ngzo%IiW%8;_y+Qr~4QC^^r8AtqAzci)`K2nHk;R+7Wh<@q~a zf>@gH*AQh$J^=er-gvW(rQ#r-si~7@Z4b~Ui}nI(;2r?b0w|UYOt)KkbVhdGE3| zwf4Wtffws6^PLwyw&S9)v*i>+oUf46Om$E%7bTQE@AHO|&*Wfjn$VSD=`*cS+i$DDN^(Vl$@gMd7_$ba%=FkA- z_Wn6+{7T5aI4w8D0ua!4a}a=k|BHP9xP6YWSCuFZokGH_iye};s>?Kc}#tgOce0!%^-vL%{;fNY}1q~i_<-RHAh zdUpa89l<{u_HMqVYk;{tzZb}jCkv;vTKoQ{ZTJ_^c+0cO0UYR!Y%0pHW91J~D2PWRovm013f*4T8`bRL{3Cs}_T=Le9X^N(Q)Ay**WBbTiJ1jl`lr zIa98!K%~c@3o|gsL4}ySsH!<TfHE)$Io`_Pet!vk-Z9g-q=@a5? z{kSxTEJUuEDd@%AuNrg^eZgh<>aU8l+8#c9RFKYEl*M9dtzd7&b)_+Eo9K>@C2Hbh zZ`CJMB)J}yennZ~k4zQ~1!!?`s|jor@hhh)s^vIxFHi9&8rXoBvmwBOHUy9xK`Jdj zgC4xQZhzE%9HGy01LoXOEsGbQ0IgfWzmyd4REY-(B)|Fxhy&A&3edy;=hOLC)BZuR z3*}uBPUYd|pADAwmlRnT$zvJ*s7Adsg^GaA7SDEO*)I0$uDULPr>dNut_~o+eGA~b znTtnO;Ns*b6KHS$GdORc=~B~hrK6(CwY2_chIzl5&c`rYg%+V{zVN<6hWEE-7nhU6 zPZD0DYRE~;{~2MulQzJFO;01gE#N+;(sG$h4jXZ=~AkW^YZ zU0r~H9Z+MGLlKfK*31P`dJY)BS4qB>@~Uwa6_HYSMhh^%>@Y#S7u~r3`CMru=Ij?J z;-5-p8mWq)zm#$KU1Lgt3+>82Ei3Pfyb1p5+ES^?5C7m}U@~!&zP$mW){sQkz;GaW zMV@wA$`gwdqgWoAY-8}aO^FaZ6Ay{*1D+)*8=F$V-WzMJQNo0-79EZ&hYhsqfU-BD zPqRJDg4FP_sc8W(Mqifw4cZCn+{-FLAgfun3%jz%?u6*cV1)ynn6%C-rHxadFOG`T; z^HB;Lu*#;O!X-a9CsDyAKS?gq5J$S{zfKIVJU|_YDqi~SX{1G5C0y~rhiOI%+CFt2 z%^!toLCwZ%5ZRYdq|Xh)m8r*D#6l^@5_NGC(U}od6h41iyU>Kw#}PwA49K#hlVlMpyeE?xGtlMqN6LN{Z>a+N?X@c zwT~-x`Yfu(irAm$%H)uvw2Fl(uIY#z!=E`f9kRo{qc6b*_{jjRf+C%}bU#44_=*;m ztS5~R-CX`-asS!4UeE4Hqq@7htHs=?qfQqnoZTfG#i;<#!wwS@I#b+WR|~U9A8q8Q z2GtE6ut~wmi4z(25H|sfSlNyh;8EHJ!XttVx)Rv0sFBsm@jKRlICL5rH$Z$@&U{sR zT1&)_vmgc*Apxsq(t|P(%uo}g6a3i2n`)urQy^-C zbcdx(_af&Hs1CRzGRKJ5biJD6i?NqW8Hz|6Ab_x&_{@(TyCeBef&D*^+W2RF_kXt! z0K*pl{OA80_hAAa@&ApZNdD=t{~KfS0(!Efeo}!(cnD%V(`H2pGZK?{s7U9F>`aJk zh0zrsrRW7R`%RHmH%y;#u2y`s>J_+TB4jJoUpb02>{q6M0c`)Fa&`SzJ+LvRy$Otz z^*kuM-Nbn)L@@TXm+ND622?`MG2o>2yv7mYKL7X>eCt##hCSrs#(QA3V`LWcspUK< z(`{JxqfN@&fM>Hc-Ko8rLQgd=_$CBSh;BwVLww?Z<^B@!McX;8%*Sg^zPbCffhH7G zWky8Rx!d3ZM^7m^_+!5jv<`wOG+#-DqDJd>YEPLj@7LJH_7z~=eUzYGaUPs`e zF}{|To8l<5-^>_qy)x#Raq2f3Te=5FFJ8{e<24)08{Zq)2Hlgba!8#b)_@i3pRvUx z6)gIf#P8-u*jo3!<h0nEz85YLxuvr#a|Q#aCbFrdxi!(sTi)eg6Ts7Q+#`6QBlOo zW40hQ=6iO8shKXc^G)H-$r9s9rA9F;?#w^04Q)+=`CatV;}{YB0SMn0vvu^f8Tw>m z=X7e_`$Xv=;fDaX@aNx3;(kCMBTm1O_PnD)MtxRznDz1Oyh|>M-EUGBT5Y+F?`owc zT#y8{Lwq-8>0{fs!uCH>C1#m*01dM%kz}aKh;fa)!#h-F*8nIw1!v z41wDr#A5R)hU;BdDC_M{8!GS#>v!cu%46JXarR15@P zm6M0rI4)jX(CWA>hvy39py>rAjqIxpDIzZhLRG5+I`AgAG+t+45+|kA?)8dvg$V?i zE7pci$CprP{fNAhQ|6MNqG9bwn+WlZZ18#SaT(;3R(o1x=|xZCF^>)CmA{lP=NS8v=*y|Y;2 z$~SH=fv!r%Gy#@mnO*iD?MD^<0o+*A&)=!%MyL|$XC}GKYU&&;x5eeMCt4Tq5tZ7! zQMI|T@2XEP4B$~yrCv9cdAd*ZO^wbB{58U_==%G$Of&2BU$gE-ir-?DFpK?UkyZ-p6`wWA+%z0ID>Ad=2x)4Z( zNfsr7h8r?20;LTiE$myo{S6{KzAF$fFW3v;RqUGL z3~jbvp{4PpL;2t!@DoOt7e&=X=!8Rw^Y#PZeE&#+M6y%X3*Ag^GM((Amn=l=WlNf) z6=_2y4xco*PK4v0Z;ClCHGUAWg^%QW22mKat%VIF%rqQ1lYT%!u>-5V&rJMVTJKek`ijjyvy^_U@ZkK;*$MdLrqU8pT8ZO3;t6((e1S*D&^@`bpt zY?y=(=k><;Y1c6>R|G*#giA<3g?y>Ex~#Ef>el0x+T56tzK(C_&VxT?@J6PlK^y`h z&cZ9SBmFB#Nh;`jU^VZ}p3w(1nzwn(Moq*EJKD^|Ir45}D{LW$UWOtRo2jlU7Hd;3 zJEw?hhM-Zt>tBSK?0)zmL*ZqjP?s8eege>gnwp>l}doh3=1fc+*cOnZNu=eW|anbi4@sQe@g z{j#zAT*D3Vwwle(pXbX9oEF;~h|xj04khaZ8a|Hr@ies}dt>pq;^HdOIMnGTZ|3g- z%Wla9a+lXBBUT?JRfGk)rzQo~83QH*c^cmuuKS0X)N;_?|K1)iB(OYGHQVZgu8b6l zC*92tE&e<(p}|2!x7qEL2;~#=r$s?GN_h)MVzh1ldM&@wQCgMaL?V!rqfX>Ddtlx- zl}Ib-{+S{d5>$xAX_geU<+6T1m^^YfZ)F^`Z&x>vyLi99;`B6pNFbWdU?xn#qq>Jv=PL6R8!gszcJg+ z6;4rHV#w#6`nBE_KPdcW|8XCsEb;8?W9-9XLwmyfscypE=5~6aXr?vuA7ZT9r*MH_ zxInHEGP>poJw#}`P=d?(tY`s3JfNeQObuK5NS| z&-^L(G|AuD==!&cS6$k5WAc^HvraDeYIj{0k! zz=~<4W^Oz8$@7qj;S<6SncwL$z0mER&Lv2ArHdZxADC8(XxOC8XCa+e84{`9qa=cI zv^U>cHiZw-IUbMK5^@fTZc88ZA7{H~axRJ^MCuboz!-42k$mzEuH*XPD0qEzS+B){ zgr(P=>t5N%?QCM<^WK#<{BNz_eh8R$Z#+tasK$ZF{p>s#DAA!kQ)s$!x--O(?`H0o zEreTU{+#N;_W?THErs(rCQiX;{mebisFFLHN2br_`0PLN(7L6;Y!*kJ;-tBa=wo-X7s+rW5|ecZji1LU+}q`ZC*->#@_H-7oT2Lz&E(EZwh88{ z1Sw62#*d4Q(XT(P4JmnW-FNtSEG_I!x9*r0{=BmNu(2WuSrz8*y5^{XneA+aJf=29 zW%+I{zgfEaqdnew;`vTIh?kzoxNnrww5NFJjUcRMC_6-+@XAsM4+JXuOX@|s|9DI? z2qK}|XGUQ{4{axRx_baueq$>CzC7rVtoFs;i36R*7Q!!ncbObB)se#rzsJf&+<2IF zIttC6!31dcjhfg3!ssPn_=yE9-n44HLP^>oH;%T2Z$tH$jM!lJ(8aE{7aPEo`J#gx zN4w3(IWTg;r9J#e9;FZ6%73WwZ(+Cl%#s!No0huU+U_E6AEW_vyoxFrX2CS&tbBR- zT&agWAN`w$kXbEVwQ=#Rv3;CBI>Q((jQR(;*5%v)_ zVpTol;D4;S?iH^+{b-EaZZ$N2)M;A=Ssupe()H-cy|*ydHONyF!fiE_6|85}O4 z(U4UCbZbvcbN=DEC%J+*T3T&;Hl}NKJC4s*jvIf;K4|u8(vk0nRCRm)k*<*G|h^SF@k+V<6R%<3eF!X^Yl($e%ai8@H;m<*SwqSXx%*3 z6WYE~;`{mZGV$g#LV(?3;GD8I-}5cl59U<^JBBJ&2Sn*6b5i^3D=@3o0dU)fY3~_5 zSs*%sKp-ZgXnOtRl|{bOqWsA_#O;6?8M6-OMux z8H2VaIx0$Kc7|MRb-+9gyF?TX6P6^8I_hR1P zYfu{F2X|dx|7PHV&&;~{0snJ7`*&9}Eq6QW66%JzX^)MZw*A$8uM3fS>FPYl2>=1< zzzhzm{E4+16OE3kyk6eBoExMf~Na_hM&U(7~GOX6Vqx76uvZvJwm$sTT`Tt_|Itw z7c`(^Euhl!Q99{HZg`##*Takfaa)?;%@kr6gHvp9HNK1yC8=2QONJy@nl}8Nj%YOy zEk#v%>8ItJXwM0~PqLrpar7GOM&9UjcB9SeO1{?=4!y!cmU}q>7Q_K_rWN~@r-_WJ zD!}B0myvX3=J)_v8ZK#7S&1h!;0xCQ`zK1di3^Lxx6e<5|5Vo}82Pdo!5eayZ#uXv zSt~YPSh;k@U`ES}J)g@Qiiw}3F85>$btutO@=Iir6kR^e^(Ukx!1_f4>1lIrBoJeZ&BQghriO*E&q;&W z31z2F@Qr}qVQ>3ikn`0V$m#vnUKD#J_Kpde2{D$ubfXulL6&X|m6?Pu5751T42>wY z{90P_Z1I%Xl!#_ImIU*efnwClxaXmzh@Bh)oHWnpDpp67;H|U`A)LO$p40K3vxYte zQ)V4?G~R9~Z52?<&OyHyA1s@>je6}{Y8QDy{0-kc+P8@;dTvlolCVWp4}Vv;9_;%>WLIL+4?y@ zpQzHXDSZ-Ft_8b&Y3$M6Ux8-u}dnC-%^2>^^q$wT*y=V5MS7 zBf8F}alihdLSW0&+rZP=NL5)Ih24fAyAU^hTqv@7#8iG9JQ?*i5Bo`%g|sV;h{xOK z^WFknRR-cs)5F9c!gxvi*KKRk<9FL0$-LM#PZDgweLlH{b|NS6^$|9XzY8{YR{e$_ zt>>FU-0k6!?+R1nG$p=lm!9@Xa=7oIZGlLaU;TLML{6DLkVSJ6`Al|Yx`zJdVKVi7 zMr$|m#d$%+xOqTUcv%tY6;$#MmHx<)QFs3b*3c~$+pFZ@fmKMkrk^@dW{rii`q`M9 zP<`7;wx&dEh1_Tt|EJnyYDOe{)kN7o25+;MaT60U7@WP(7J89986ES1?7rOFoWR zgd(5PTF$?d<;Ev$Un{&0pLJdgS|ZMjYM&DFpo(zV5fPmQ0<%GX2e=m$Gg=qwM{BP z6d)Ss2I9RbGvhf_cJ|bDwt|?QTkoDDC?{hff&=A9FZo-rP&Ayp`LNh#X-vDrf3$=| zdpYs}FA^_jl)V`@mf0lr>54UfJ0GkiP3AI^XORy5{*{n3B0fM9v23InnWw3@@yTw~ z3Hy|X4T;mr^&YLnc*PeA)Mx?Yp6<#X_NM0p8tj&*r*ueSWK_#bp%0EOIXed+{nES~BH3Rkd5$ zf|Pl9LkaX6Z(mH5NlMG`CjII$nVlA+0HLt)@pYv5ueX(t+l@0@88n`$vTUGfnb_D} z?@!UNv-_RDYszXonglnLjQ3TBJONqWJ&H3;=?d?`)oYQ#gY(9d5TeZ-zVMS?Hp4X+ z&$se_z=0Y^?}<_-sRS|VSD?6AFNTY`iE%T3nfkNXJ#8X1(@U+;>UIs`N8gQQF+WrVqJ+H~AE;?-PYgEZ`c52&y z)p=R_J>mXQkA%C5xUVKmL#te>+LoO)_{!sG3t#Y@NTTd3pA~`|>b1oDj^|FTf+-G| zhGPo%En230kHUMUPaL}%fAPp&!8$esk%_%e3U`#diyf85io66Xg;XvQtk2X#BAO4m z-*;&wyDl5^xQqR1pViz(qnRL=q`owdvF8dq8|imDflyKYS{Qnb`w6|5FSc2??zB?x z0JD_$X6H~a-#kGgPswfv0?$Jz40orkdbrZmF217i{^iVEr8G3}#dmhedzJJi8!^{b zZ49Agv!E|=?O34~is?Mxj&tAL+n)G1+Zw=F;LOnc*Z=)0q+2$gW9vGvw%>y|?W%c| z8wBq9vhu1<;5pWW?Qzg#rD?+uQOO4{kO|ytvTaX?rbAD=zA|I=a$xaPt~JnQyuRH1 z-lQeXfnNjGV;JFzCqMMi`EkWWb}%rt(FKNwQob|u<4|{AtfjCf3j2at^3(i8M{ERp z@vaT>3l@|}p=|PwN|T>h&}vHeWt=Yg(03!`*q8e07!bm;+@IOKK2bO*T4pK&ES6GQ@6MKgJR?#c;PnQnC1cn;F0tKB ze7CN^(qS{gh}6E=8F1UT!(B2|QjjBBN@B?!{h;w@rtiqvZOn2V0nuJm?~b~JXH-9} znUQcqlG8I=f0+*VtFv35Le0z}-7K*nHQR9q#-bNA(>+NckGZ;>C)Qgyh%6znaGS{R z5tpXUYMR>Sj(WbzX`V83$O(0oco5+LetBA9srJL|${$k?ibGXb&9*i|XlvuhFyz^D z+;}VcRL*%`xiT^TwhuffU&fEL-rL)n7>la;-n1}p5&5&pX+=r2 zhD__5{fVvo};kgmBCXva;5|Q4}*#*9K?k-e|4hA6=m>9g0}pv!>oos ze0I#-{mXUKb=Nn$l$<&CUMsXz3I?Ev zAsYjYFmFC{_XE7mOl%nO*rNz<5oh%(VDnBYNd6QrBn^_LUDeDcZ|cqct^3xfYAz)| zc%H=XU#%t(h^R8~J*R13>ohRn(>7K%tlnWCed2fyzh&^G6Pm`YAr+1S$THIk`e&_&>Wow6)toy zCW*Y4ni#Y#d%7AE#O8j*77bMw zOG`1 z%U&eoqTjl8ocIljJYwSm|I^WfXP1`ZaljZCqiH1Tgz{iaq)Nwy^?Jzec_(N+jJGp- zxq*rI?2eUIP56(Hg{2{(EnDb!YkuCEwg_?w--tOxVBrkdr2pEH!*&EAKE(=NN=UIU zZsg6%X)#lmO8RoPv{Ap~8h@}_AL}dFQjcWu;%4uLhqyhYP$I$l213>jQ5u7FGt0vxRl43vSVEc1v>z4ZKR zF8p#f>%rYd1NiDw=VKzd@3`R+|3gmT5G4t>hp-hPhxORikiq@;H;bB1S{r4SB-1kD zf#Z{F)lW~gmFP)(yk!dHu31|D$;{yU<4 z*+Z25v>Whl_0vrvUpIg1B)h79`DW==Tx5@62-vZH+(s9igZocGw7?9+c)KLWJy0 zd`Yx90z-dru1@e86%INrs`9x~@QR0UyYT+n+gR&gmdkTk|EwSd$>Y~Huk<`XIuzF?;-lcpe;kTS7|;%$@=bu?s-9l5I%{J z4+9LcmzLqm_-8RJl{@KBU}LgV9qezP7BZgPO|7^$&PyWZ%F~>TD$lwo^@UdI%)w5Z z=SS0mP8NFr<^ZIuXut@S&ug?4yC{ds)Hu=kBGuYBCb9m>ur5Ram;K3|@XdSn&CWY04dsH`U;)`Vmzgqz%DazE_ zq)PZuI2$`D}T*4z> zVokv3c>agu)Fl=j=AJRAE@>ZfJ0j$eTR6M_ScpIf1&PV%2U?&PTd?u-8X9qTH52pa z;cg>v&DRJzj}z( z?^E=#`+dBFWOv+)v`YIrvM@W@_vT<+hT>W`W(^mXR~$R_SMdI2s_nI$`<$;k-0do2 zTp=-c*}uBA<~q!nBe+$xsy5r68@T&XA<>59}6 zXdRtet=N$bbBAx1hsVpfQI0B?prTkJmc&gE6%)ZR^K&j+v+OWM;`q5wlho8d-dc?r zsL3@-3XhEcejT+%`kb8GT}1#czjYnrpBf70DB)=zNsi!pV;(FV+Ga_xoI*)V;-dk% z=0#?W|A_p^r2Rx^^9ttm12jLkjn=M+d6V*vd7Q-rUaNNgEq1OxGeXND{3 z8jAaLTPRu>dtAZ!=7H9vR)yfl&p4-#Y!GIwwi~Pi9*@Ou^O`$zslTK~?&X_eH8G2b zL-*vb#^N+m(VEWOi*bA`-!ip+Sh-vPl}Ja6fd-vsQ%S*8B?t8iZ$1}`r&r?QDbcRa zW21-r4bNJQ_ZQW*k-PSH$j)W-u9{PlG|C=Ey>}OjT#R?38!Fc@h`;>7uRXIWn)jl7T)tEx z*y``_8?xZ7xB1DGJ4G){4jQ*Rx|MRLYm;Um1JJKFH(~b1DK^)ITm&W}BObO&-hmT4 zmwJ943&-gvA@Q$nosHy!*1O*-AnIj|58wp5WzHBNgF#S5x%&{|i4fxAI?V0WxXH=h z>Lz}FIWI<*0s%^b+M|(=mf@l4qq&@v+EiMne^gq4_cTO-)PO9iosZP( zvoHd&XCP#$*TCUIf5r9RAR-_k8wov(3N?&s)e4TBtVV6b-Kf%rgoH%zDW~sgZQ*Gn zY~^kP{6OO2;^ATE;$`RJ*5T$6=6);8C&0=jB+SJ%vK@`}|D53LYVBa__y3*11z6ts z|93*2u&F3;0?EHCXuH~a`dGNzAlbRNI@_>&02i}y@vwLGJb%$G4*U|5lAM}sjkI~# F{{i5MYD@qC literal 0 HcmV?d00001 diff --git a/sensing/pointcloud_preprocessor/docs/image/outlier_filter-dual_return_detail.drawio.svg b/sensing/pointcloud_preprocessor/docs/image/outlier_filter-dual_return_detail.drawio.svg index 7ef64eba8e84c..b5c01fa3c6b64 100644 --- a/sensing/pointcloud_preprocessor/docs/image/outlier_filter-dual_return_detail.drawio.svg +++ b/sensing/pointcloud_preprocessor/docs/image/outlier_filter-dual_return_detail.drawio.svg @@ -1,4 +1,4 @@ -
input pointcloud (PointXYZIRADT)
input pointcloud (Poi...
split  points by return_type
split  points by r...
ring outlier filter
ring outlier filter
weak points
weak points
normal points
normal points
ring outlier filter
ring outlier filter
combine
combine
good points
good points
create histogram
create histogram
noise points
noise points
diagnostics
diagnostics
create binary histogram
create binary hist...
estimate visibility
estimate visibility
output pointcloud (PointXYZIRADT)
output pointcloud...
Viewer does not support full SVG 1.1
\ No newline at end of file +
input pointcloud (PointXYZIRADT)
input pointcloud (Poi...
split  points by return_type
split  points by r...
ring outlier filter
ring outlier filter
weak points
weak points
normal points
normal points
ring outlier filter
ring outlier filter
combine
combine
good points
good points
create histogram
create histogram
noise points
noise points
diagnostics
diagnostics
create binary histogram
create binary hist...
estimate visibility
estimate visibility
output pointcloud (PointXYZIRADT)
output pointcloud...
set ROI
set ROI
Text is not SVG - cannot display
\ No newline at end of file From 804326e8d986697c2210d847a3a1ce364c5af86e Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 1 Mar 2022 03:39:23 +0000 Subject: [PATCH 18/27] ci(pre-commit): autofix --- .../docs/dual-return-outlier-filter.md | 11 ++++------- 1 file changed, 4 insertions(+), 7 deletions(-) diff --git a/sensing/pointcloud_preprocessor/docs/dual-return-outlier-filter.md b/sensing/pointcloud_preprocessor/docs/dual-return-outlier-filter.md index 64cb3617180f7..736423ec8befa 100644 --- a/sensing/pointcloud_preprocessor/docs/dual-return-outlier-filter.md +++ b/sensing/pointcloud_preprocessor/docs/dual-return-outlier-filter.md @@ -16,12 +16,11 @@ Another feature of this node is that it publishes visibility as a diagnostic top In some complicated road scenes where normal objects also reflect the light in two stages, for instance plants, leaves, some plastic net etc, the visibility faces some drop in fine weather condition. To deal with that, optional setings of a region of interest (ROI) are added. - 1. `Dynamic_FreeSpace_ROI` mode: Visibility estimation based on the weak points in the free space which defined as no normal points region. - 2. `Fixed_xyz_ROI` mode: Visibility estimation based on the weak points in a fixed cuboid surrourding region of ego-vehicle, defined by x, y, z in base_link perspective. - 3. `Fixed_azimuth_ROI` mode: Visibility estimation based on the weak points in a fixed surrouding region of ego-vehicle, defined by azimuth and distance of LiDAR perspective. - -When select 2 fixed ROI modes, due to the range of weak points is shrink, the sensitity of visibility is decrease so that a trade of between `weak_first_local_noise_threshold` and `visibility_threshold` is needed. +1. `Dynamic_FreeSpace_ROI` mode: Visibility estimation based on the weak points in the free space which defined as no normal points region. +2. `Fixed_xyz_ROI` mode: Visibility estimation based on the weak points in a fixed cuboid surrourding region of ego-vehicle, defined by x, y, z in base_link perspective. +3. `Fixed_azimuth_ROI` mode: Visibility estimation based on the weak points in a fixed surrouding region of ego-vehicle, defined by azimuth and distance of LiDAR perspective. +When select 2 fixed ROI modes, due to the range of weak points is shrink, the sensitity of visibility is decrease so that a trade of between `weak_first_local_noise_threshold` and `visibility_threshold` is needed. ![outlier_filter-dual_return_overall](./image/outlier_filter-dual_return_overall.drawio.svg) @@ -32,7 +31,6 @@ The below picture shows the ROI options. ![outlier_filter-dual_return_ROI_setting_options](./image/outlier_filter-dual_return_ROI_setting_options.png) - ## Inputs / Outputs This implementation inherits `pointcloud_preprocessor::Filter` class, please refer [README](../README.md). @@ -45,7 +43,6 @@ This implementation inherits `pointcloud_preprocessor::Filter` class, please ref | `/dual_return_outlier_filter/visibility` | `tier4_debug_msgs::msg::Float32Stamped` | A representation of visibility with a value from 0 to 1 | | `/dual_return_outlier_filter/pointcloud_noise` | `sensor_msgs::msg::Pointcloud2` | The pointcloud removed as noise | - ## Parameters ### Node Parameters From 76677022628bf4314bc970f2ad487fe3d0a0f00b Mon Sep 17 00:00:00 2001 From: badai-nguyen Date: Tue, 1 Mar 2022 12:44:33 +0900 Subject: [PATCH 19/27] fix: typo Signed-off-by: badai-nguyen --- .../outlier_filter/dual_return_outlier_filter_nodelet.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp index 49d17f0a6bd6e..6ac545e073b8a 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp @@ -29,8 +29,8 @@ #include #include #include - #include +#include #include namespace pointcloud_preprocessor From 2a12a3bf0ed433377d80b63923e59f926acfae36 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 1 Mar 2022 03:45:48 +0000 Subject: [PATCH 20/27] ci(pre-commit): autofix --- .../outlier_filter/dual_return_outlier_filter_nodelet.hpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp index 6ac545e073b8a..30bf3be553b1b 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp @@ -29,8 +29,9 @@ #include #include #include -#include + #include +#include #include namespace pointcloud_preprocessor From ab16c0502da5fc56ac7f031f2919c9588e4e6b1b Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Tue, 1 Mar 2022 15:38:21 +0900 Subject: [PATCH 21/27] fix: typo Co-authored-by: Shunsuke Miura <37187849+miursh@users.noreply.github.com> Signed-off-by: badai-nguyen --- .../pointcloud_preprocessor/docs/dual-return-outlier-filter.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sensing/pointcloud_preprocessor/docs/dual-return-outlier-filter.md b/sensing/pointcloud_preprocessor/docs/dual-return-outlier-filter.md index 736423ec8befa..b3f02f51c8fe8 100644 --- a/sensing/pointcloud_preprocessor/docs/dual-return-outlier-filter.md +++ b/sensing/pointcloud_preprocessor/docs/dual-return-outlier-filter.md @@ -17,7 +17,7 @@ Another feature of this node is that it publishes visibility as a diagnostic top In some complicated road scenes where normal objects also reflect the light in two stages, for instance plants, leaves, some plastic net etc, the visibility faces some drop in fine weather condition. To deal with that, optional setings of a region of interest (ROI) are added. 1. `Dynamic_FreeSpace_ROI` mode: Visibility estimation based on the weak points in the free space which defined as no normal points region. -2. `Fixed_xyz_ROI` mode: Visibility estimation based on the weak points in a fixed cuboid surrourding region of ego-vehicle, defined by x, y, z in base_link perspective. +2. `Fixed_xyz_ROI` mode: Visibility estimation based on the weak points in a fixed cuboid surrounding region of ego-vehicle, defined by x, y, z in base_link perspective. 3. `Fixed_azimuth_ROI` mode: Visibility estimation based on the weak points in a fixed surrouding region of ego-vehicle, defined by azimuth and distance of LiDAR perspective. When select 2 fixed ROI modes, due to the range of weak points is shrink, the sensitity of visibility is decrease so that a trade of between `weak_first_local_noise_threshold` and `visibility_threshold` is needed. From e0dece34fc603c2e518a2c0029cbd7fdee433f6d Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Tue, 1 Mar 2022 15:44:32 +0900 Subject: [PATCH 22/27] fix: typo Co-authored-by: Shunsuke Miura <37187849+miursh@users.noreply.github.com> Signed-off-by: badai-nguyen --- .../pointcloud_preprocessor/docs/dual-return-outlier-filter.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sensing/pointcloud_preprocessor/docs/dual-return-outlier-filter.md b/sensing/pointcloud_preprocessor/docs/dual-return-outlier-filter.md index b3f02f51c8fe8..b2694d1f92029 100644 --- a/sensing/pointcloud_preprocessor/docs/dual-return-outlier-filter.md +++ b/sensing/pointcloud_preprocessor/docs/dual-return-outlier-filter.md @@ -14,7 +14,7 @@ Therefore, in order to use this node, the sensor driver must publish custom data Another feature of this node is that it publishes visibility as a diagnostic topic. With this function, for example, in heavy rain, the sensing module can notify that the processing performance has reached its limit, which can lead to ensuring the safety of the vehicle. -In some complicated road scenes where normal objects also reflect the light in two stages, for instance plants, leaves, some plastic net etc, the visibility faces some drop in fine weather condition. To deal with that, optional setings of a region of interest (ROI) are added. +In some complicated road scenes where normal objects also reflect the light in two stages, for instance plants, leaves, some plastic net etc, the visibility faces some drop in fine weather condition. To deal with that, optional settings of a region of interest (ROI) are added. 1. `Dynamic_FreeSpace_ROI` mode: Visibility estimation based on the weak points in the free space which defined as no normal points region. 2. `Fixed_xyz_ROI` mode: Visibility estimation based on the weak points in a fixed cuboid surrounding region of ego-vehicle, defined by x, y, z in base_link perspective. From 4c70a3969f1c4fe69cd38df72a46ee7d4c1290f4 Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Tue, 1 Mar 2022 15:44:52 +0900 Subject: [PATCH 23/27] fix: typo Co-authored-by: Shunsuke Miura <37187849+miursh@users.noreply.github.com> Signed-off-by: badai-nguyen --- .../pointcloud_preprocessor/docs/dual-return-outlier-filter.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sensing/pointcloud_preprocessor/docs/dual-return-outlier-filter.md b/sensing/pointcloud_preprocessor/docs/dual-return-outlier-filter.md index b2694d1f92029..b28abf8592ef7 100644 --- a/sensing/pointcloud_preprocessor/docs/dual-return-outlier-filter.md +++ b/sensing/pointcloud_preprocessor/docs/dual-return-outlier-filter.md @@ -20,7 +20,7 @@ In some complicated road scenes where normal objects also reflect the light in t 2. `Fixed_xyz_ROI` mode: Visibility estimation based on the weak points in a fixed cuboid surrounding region of ego-vehicle, defined by x, y, z in base_link perspective. 3. `Fixed_azimuth_ROI` mode: Visibility estimation based on the weak points in a fixed surrouding region of ego-vehicle, defined by azimuth and distance of LiDAR perspective. -When select 2 fixed ROI modes, due to the range of weak points is shrink, the sensitity of visibility is decrease so that a trade of between `weak_first_local_noise_threshold` and `visibility_threshold` is needed. +When select 2 fixed ROI modes, due to the range of weak points is shrink, the sensitivity of visibility is decrease so that a trade of between `weak_first_local_noise_threshold` and `visibility_threshold` is needed. ![outlier_filter-dual_return_overall](./image/outlier_filter-dual_return_overall.drawio.svg) From 648c78f32999a2ab24de5146249fb29c2df4cf04 Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Tue, 1 Mar 2022 15:45:07 +0900 Subject: [PATCH 24/27] fix: typo Co-authored-by: Shunsuke Miura <37187849+miursh@users.noreply.github.com> Signed-off-by: badai-nguyen --- .../pointcloud_preprocessor/docs/dual-return-outlier-filter.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sensing/pointcloud_preprocessor/docs/dual-return-outlier-filter.md b/sensing/pointcloud_preprocessor/docs/dual-return-outlier-filter.md index b28abf8592ef7..e7b75d3c978b8 100644 --- a/sensing/pointcloud_preprocessor/docs/dual-return-outlier-filter.md +++ b/sensing/pointcloud_preprocessor/docs/dual-return-outlier-filter.md @@ -18,7 +18,7 @@ In some complicated road scenes where normal objects also reflect the light in t 1. `Dynamic_FreeSpace_ROI` mode: Visibility estimation based on the weak points in the free space which defined as no normal points region. 2. `Fixed_xyz_ROI` mode: Visibility estimation based on the weak points in a fixed cuboid surrounding region of ego-vehicle, defined by x, y, z in base_link perspective. -3. `Fixed_azimuth_ROI` mode: Visibility estimation based on the weak points in a fixed surrouding region of ego-vehicle, defined by azimuth and distance of LiDAR perspective. +3. `Fixed_azimuth_ROI` mode: Visibility estimation based on the weak points in a fixed surrounding region of ego-vehicle, defined by azimuth and distance of LiDAR perspective. When select 2 fixed ROI modes, due to the range of weak points is shrink, the sensitivity of visibility is decrease so that a trade of between `weak_first_local_noise_threshold` and `visibility_threshold` is needed. From 0c1b65c4362f2914e83c51dff58334c36ae9e752 Mon Sep 17 00:00:00 2001 From: badai-nguyen Date: Tue, 1 Mar 2022 15:54:06 +0900 Subject: [PATCH 25/27] docs: revise documentation Signed-off-by: badai-nguyen --- .../docs/dual-return-outlier-filter.md | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/sensing/pointcloud_preprocessor/docs/dual-return-outlier-filter.md b/sensing/pointcloud_preprocessor/docs/dual-return-outlier-filter.md index e7b75d3c978b8..3d1d0913b7f07 100644 --- a/sensing/pointcloud_preprocessor/docs/dual-return-outlier-filter.md +++ b/sensing/pointcloud_preprocessor/docs/dual-return-outlier-filter.md @@ -63,6 +63,12 @@ This implementation inherits `pointcloud_preprocessor::Filter` class, please ref | `min_azimuth_deg` | float | The left limit of azimuth for `Fixed_azimuth_ROI` mode | | `max_azimuth_deg` | float | The right limit of azimuth for `Fixed_azimuth_ROI` mode | | `max_distance` | float | The limit distance for for `Fixed_azimuth_ROI` mode | +| `x_max` | float | Maximum of x for `Fixed_xyz_ROI` mode | +| `x_min` | float | Minimum of x for `Fixed_xyz_ROI` mode | +| `y_max` | float | Maximum of y for `Fixed_xyz_ROI` mode | +| `y_min` | float | Minimum of y for `Fixed_xyz_ROI` mode | +| `z_max` | float | Maximum of z for `Fixed_xyz_ROI` mode | +| `z_min` | float | Minimum of z for `Fixed_xyz_ROI` mode | ## Assumptions / Known limits From 30d104f5897751c9c5db6e9c1b157b8ac35f131c Mon Sep 17 00:00:00 2001 From: badai-nguyen Date: Tue, 1 Mar 2022 17:38:59 +0900 Subject: [PATCH 26/27] fix: remove unconfirmed ROI mode Signed-off-by: badai-nguyen --- .../docs/dual-return-outlier-filter.md | 5 +- ...filter-dual_return_ROI_setting_options.png | Bin 64264 -> 87959 bytes .../dual_return_outlier_filter_nodelet.hpp | 8 +- .../dual_return_outlier_filter_nodelet.cpp | 157 ++---------------- 4 files changed, 17 insertions(+), 153 deletions(-) diff --git a/sensing/pointcloud_preprocessor/docs/dual-return-outlier-filter.md b/sensing/pointcloud_preprocessor/docs/dual-return-outlier-filter.md index 3d1d0913b7f07..dca02739797bd 100644 --- a/sensing/pointcloud_preprocessor/docs/dual-return-outlier-filter.md +++ b/sensing/pointcloud_preprocessor/docs/dual-return-outlier-filter.md @@ -16,9 +16,8 @@ Another feature of this node is that it publishes visibility as a diagnostic top In some complicated road scenes where normal objects also reflect the light in two stages, for instance plants, leaves, some plastic net etc, the visibility faces some drop in fine weather condition. To deal with that, optional settings of a region of interest (ROI) are added. -1. `Dynamic_FreeSpace_ROI` mode: Visibility estimation based on the weak points in the free space which defined as no normal points region. -2. `Fixed_xyz_ROI` mode: Visibility estimation based on the weak points in a fixed cuboid surrounding region of ego-vehicle, defined by x, y, z in base_link perspective. -3. `Fixed_azimuth_ROI` mode: Visibility estimation based on the weak points in a fixed surrounding region of ego-vehicle, defined by azimuth and distance of LiDAR perspective. +1. `Fixed_xyz_ROI` mode: Visibility estimation based on the weak points in a fixed cuboid surrounding region of ego-vehicle, defined by x, y, z in base_link perspective. +2. `Fixed_azimuth_ROI` mode: Visibility estimation based on the weak points in a fixed surrounding region of ego-vehicle, defined by azimuth and distance of LiDAR perspective. When select 2 fixed ROI modes, due to the range of weak points is shrink, the sensitivity of visibility is decrease so that a trade of between `weak_first_local_noise_threshold` and `visibility_threshold` is needed. diff --git a/sensing/pointcloud_preprocessor/docs/image/outlier_filter-dual_return_ROI_setting_options.png b/sensing/pointcloud_preprocessor/docs/image/outlier_filter-dual_return_ROI_setting_options.png index 22be70a642309ea9317027ece2aa7fc526d24034..aad1eb144786f25466cd38a96a3eed6d9d031bf2 100644 GIT binary patch literal 87959 zcmX6^1yEc~vxN=r?g{Sh8rn&81LxIMoA)z;L#(_1xn ztM~SF_c>=ks>(8`NJL0bP*A9HvXbghP|$xq#u5VDhh<0PndRdGV=bm61_jlWi2MSC z{g{)P%c?6uLHW`^K?R3HK|Ot#g8xE6d9p!49h*Wy31mS*;k)GhP!sz20?tf9MiT1% zzfVzbW$K3o(M49z{o`u#zhRWU8T)Yq?;)oo1%L1f0AT+t({BR&FkzSjmA#;#KIwk^ zoaK-4?ZXD$={fl2<7rTGl46?Q)=ppVGpWYX50L|>rliJ~^s>v5wdicbFdV#EayL0I zrl)f6y=Du(K0BYQIL{Vv-W;4xwVJl9I$+_D!H^@19@VB58)p9^o%%XN$Bnhwytaq+dfAIL+eICdmX()A}+TRffgTuCPpcqH&u?!pN#Dj z4AVZxSLeExNB8GrK8A5fGNf0_!*?uNC`B*5CW=1~` zo6p>3M)>3)Zyc02j!Xd!2*==~?^!<`K@$F0Q!=^JZ7pxA;C~O$MHEeY_uFR-ANYEr zoj;CD4!8*Hea{Sk-=ch}7luQBIfoweuLvMBtoo+1bn&qqNT>&<#hLF=8H$SbI_VmN zp%DoLiCX%U<`sbQ<@@(Zf|H+gUz0!9#@7p_6&V4&6peIAEY)YxtyW!h9@j}oAv9fd z!qabomQN;j)4dKsG{VW1H0NT^W3T<+mPiLEiN#VI3Kb*q<&<$QK|%$5QH&CJ>avp4 z6rRh6%VFwW5Jlj-Abal|UsT;|{Zj!37C9^+s^v|PR(2Pg-_3RT?!36q@Xh46>5nRF zox)EEZmCB!H>F;!SB7-Mj3xfeb~h1M&u_eDr*K$pN`vI9ruo(97QAuW43CRYsL(AysTEV(e7%^lBprItubmYWO)~FH6 zKW_k(R6qhu*btM(0#EC_@mN~;Z!X}8Dw0KWmC0`sHcgPns21H56JqzJD6>@ddd4xQ*1 z$o&L!H?}&*4vY)coK(fa&R;m}E0taCY(tbuC}2BVHjeXPV4M_j!?(6}8~Y}_T5R1D z>x9G{gb_YNjq(72kv-xiV554ldT5bGaL~=m*r`#6LXXLkA{PzKow<97yJ!pB%aCUd(%FfG$lb6xN_fXP) z-|SnbFj0Z)ZI+e($29b}OX#479ikOpF9HiV+;&~VufxkazxQ9gfA4QH9_rai{c4?! zXAPWvzg6kq%ix<$wnP1LVJ#EN+rTPmQ| ztt41wuSpUi#64$w3(h3y7LnBdAFS=1m20086Z1+#(6G+$&5{P(_!*%a9hF5MdhdoH za6{1T{Y!_*Yb5LW-FQBQDj@D4_hjYa>ABz=&-(+${f zkZm0%AH%!+h+*K)nC-rF` zrzlpDH*8Xq_ZX3vBMBD6!1$HfhN2ih|GO*ahi8-57?Hrm(w4yNd*i;Tu2DFj3p5k| zE9<__H`>5`0G{?tb34~q#L-K6&Zu9BugacjRal{7l}Bs|*(~ycBIg7WTxs6mchfAp z<{>p*kQX#w1TJQg{C>5NTyn~|{Az;Hm|}!Zua1wl?dOt_5s5x}1}Qpzl8`fS%o<;; zYsLnDcvDfn&J1O|IQDqBDuMXE4LHV&vt$#+mRmf>RhA?w94K2<-RahqP0(>DNl#k- zzZm7fgi2w{+1(iJczFE%f~u3-{X)*;;QX2**nQvG-6A8RglX{mYW1-2`f>X6-h$TK z@x>eZ+wQZon{AUAq`1=>1US=IE^9;qPqF0j;wk(9@O()0g92r7R_EW3nDb z8P`WS#R?@gPEDO{f@^prX)mKSc!RDLm7S|m*({l?cS!1c4lE-L(s%Vf6>fMV#n*se z4-ErGC4g_~EM6qP7UUr_NrJI1aJEc-UDO2n;^|oMh;_1ac64j;!P=BXtI;+*L?f=@ z>c<22!YF&56zH`7?Ue<(LUaOUt9j-=t`Th+7EOy}>R2K0DSY|Oy*{xg9p{ae<}-%A z`TY-9Di1%`b#xsW6q}`WE-uejOfGNXc{^Qi1f3kuuY760P)ex8ZIQMw;X0L*G2Yj* zM+&W!=?&6N6VmX9X>!V=ly0OPBoT@M0VvSXP~;M2NEqrR3^jKlX(dtR17DS>_t5m4Z|^3D!Y3*rYn2o_inKW`h9AqxIE-rwJelXs^#AO=A?~7WjkY< z*0Q3q`q?6mLslu+i#&sXHcjV;t7x#0s+!VIpsiD)Shee^x)}vJN8;zWIx{;+wQ6=E`--ODBt_HZ|cen z)8dl1JWS<##CJS#0s~w#66ahdl-c55SBfzv_%SbLsbWHEt#H+XT1!Aq4u!yIm)y(sb1fAbT%^+N>0Y;a`Kj8R7D-oQ#t;sbKxrZFDNP21 zt#Xku%f5W7jq=A?mUfF6C0gaiVhb<~J3HgQ#H7MB6A~j(n;(!pS%Wz|ePXzd*V-M+ z#4@$$DE(bc7H5=89F~SwPMWG~kPH#G2swtyl1qL(PAU>p4F@xg9+UQZICWx;8HsfL z3{}JHPTJv~!xxcCx)>x1j%E{&*9f)3f4Zt~$jE+PVzqj@4d?6iHGg>mqFjfit%fng zDcz2VwK@6kc;TejD^{k#2dJBbdPFFE$SPA#7MC^ZZff*k|ml_8zWhg+M1 z8=J@Mh9(vB7&iHhZ9bXn#JMPLHr|K2S@zg6(24{eDtmrRp0H+h)T~I6rD^$F(PzDB zn<2m~1-Erk>>Udz4mzVLw~0By@y`>&`);*58e>9_?g=75d2&CvDH-D5W7n?|PuA-B zihq*EMYkP-z1YFHWuS^oyp7GzY%3&=~_T1EyJ>-eK{yM>*Ug z!)24Tuz#naxOO_wJ6YC}2S1Iq8mzEhYf05TIfwr-^}c{MpGp_o)gPUHs?=!6caQpx z8|7(PgC^u!#pB3dNRzJeQmMWKWtqNXArCSrrCrXfU;w2*PHIV2tnrU9t%AjvbJy}7 zf?(b{WI-CxGu-pqEvYpB7US~YqDPe{j?HEk{A0a75|>0;btT(t=?-jC|ny6 zIm?lu37;+h-Ot9)4+?LO>&_30V?lrNbyyo;7Lc6#Uh!YL{R~h7AEAG5Jw%&0_)Afu zunAC4bH|rYzWjYHylUw%*`M-9=H391tI1=g;hHc=Z(>J7Vi`T{XNVM1EKg74JG;M{ zwPbRR<8(O!EyEEc!v7gg-u^2F;UYlxsCpfr{QPjhicEGe9MQJZ%!@}JlS$y$b&o<; zA#gM{0+aONUqkcc@N#axx+%t*)shzBuwF;$Qp~lCKa#i@Bg{ExKKf@oK(@~&p6x}l zQE_m7RC1v_c*WvF(ox#h1y-eEMHBxRD}SbbjqEjAASs!_%CEo3%~>=}!Ty@AG1Y0N zx%}vfOoAJlWP{&Qi7eesC^$?WD@X~+(643kvh6SnB{MaQ-hn5f6;>Odz1H3FevHxf z&c4AnK2S=&S$M+A=c97s;eTE*cv(*DH^=dpz$A(shGB;2bw9uby}C=x8SbGMn(Q8U zB__8=yQD{yFZTG~I&KABeBJ8nl;_p%xsWMGcKetj1I*_TFP z|MNPp*LbLR6Z8HK$x9~bFM$LKgSZ^`0nHaubA|#sml@L*C8vNpR{y8x-_5I}>bkQ? zmQtciUnlpy-@Z2VKl0d57O#l4+s%$JpMLL(ux1)^T_1B=lVez1ay6Y$*hSChTzkq9 z?BJ2r{d1b0sh4-*>-ICpzz_k{LK#V1c(ZyDIJmOXXO;A9e2d*Y-vU%wm^DO~Aj^DSEB zeVcbzXW&fVDWnHiFK_;O{ag<;ljCWNAO=B%)a&M?3qfeW3DINlN`d5CfozNOmI z{L9p~UaDo4ZgWAzuYo$x z4ErjOXJCUVFSn$>eQhrSbUNZ4 z4SefR@-<7i$%JIb%DaV-LJVKOfNstYsLcJm$Mes^<9kEJzL-g36OPbTp-~OHshw1zdf~IQ(N~y@Nf5922EPp zvXx|!X0Qg5H6=%?yK@qotQ(x1Sc+W+K1#k<7#~UnkDdq>zuLeU({pVrRpWB)YWTUYp zJnh+=3J3u_f*gkA2=20xk2GPMUiT%#%?T?|EnH2J^e_TlWA-o;FwMq9sR?a-`gwS z%0@0~y{r_4umdC>!7OdjB{u4qQ^!+`rJJ7;|5Roh!$TGZ7w;9-IZvgEwM{~E#!f_y zqdafJHDDq9z8M;$&t+h=BOTsMSh|_J@$%yB|2RJucfe(B+$GMKHs$@JRezd;=9qP4 zyAh(gN596PuYk|*cSO>(YJPIS&C~bB>%lg*vj(fJqhp)v$kX?L8}yX+Nf0Jz_XSdm||*ymU7WlNn5IrDtstfjOQYO1fk*6gFk zK&Wz|0RIdgIoLQa|F?+Q9TvC9=$LUJ$VJSqE_bo@2Cek>Bh8O+Xw}M)TpqcmDl8d# zc=9iZ85QetwD@NS9Gs$0ubm$15S zUP6nMgKKJ*o+oT$-y?vMd*+4k8*Jg*k+=WzH1A$KbiY;X1xxQNqw_oNM*@S}v=Z7D zXdtf%15?~&1`c%x-FMVRcKhE92JMHT2Tso9H*|U5e<|I@NZ(DxFPtb4Gt z{+`?s^zS1Nto`l1csSn;+ClGs<-YHG`)pF+mmkY&QXYV`mxXX>V{1$cb!lsPK4^-? zh!df9YDu`NJVQs!p~z*g;P@jSPprr);r_K?_oI?Tut0$$d>51sK26My6IoOFF3fVF zBOwB*iC4t`Qq`{`<2|H-n2=z5>fhCIG&^z92W5r84Mcz6*l8aG27C) zW+GL5gsT2gVQj3)|N0_&Koni1r{BBC`>!cI6a`_OvDWxoex`9y;Uga%uTO%-3EF+% zD>LcaA}bqXLo**K$B!FWgGZr;YR=kxV~M}4kN-^Gk%L}#FS=T~B!JWmIp#;X4XeZz z!znII$eyBKZai_J>odgBw^x{@ z_vcvyYL!!q%M-3K``w=t7qT$C{PNhm-X~%Fb-&JOm4}y9k%dKip8}0C%1DEiuG=&G zQ#6!K1(BWj{+Irn-TN(5pFR-bmYJpU!umtx@1VfU?v;Mi-7OyL%!B(;*Ft}R&n`Vz zMB89uFM29vE*BmP8;)yZac!!-E}-LR^PD4=6mBl$-sA)L#FpP&5MnEZ9$01fo#U5B zo;7onW8aqNqASPM6RaS?f2jXU{Mv#8pg$?p(WWQi$v^H2OJsg_!$yCc0Y=Y12k_js zy=r>3siP|LZPYdZCWc{{LHdkg%<0}Z9ngdSYO6R{+&h(AERK?Qu?c9N_{U5g*^aKMUM|m@% z1(3G_KDUEZdZ+d~f~K-ReE72Jx$`GU91f7Th+|tgcy7c4Pwe2dMafL&Fg<_lkyK*Z z+VOL1hDF~?SHwMn6W_$l$ti&?EqqfeW2R^7sKxs6kne+|Z9LL+JdGU;XXx5p(To%xgI*&fO1*QYE)iGqn%3xgSKmfV#IK}E8z$RT` zGi5}cRsYxErNCqTFZP4oi4;91#>L;hJs&)uhdv2USUB)E_n6vO&QAMLo}cRb`jl$+ zZR7YY!^pin+#4W3(^z_3Xb8WJzUQ8?z7_B}&Fl3JEt9@7SFWLj4CjP$HF?bRPA~HY z4vjK4xV@Ff!t^F~-Ht|W{8*`UJ-6<8YLW>L>CY$foi(C6`5 zE8_sqHry^$s9?yP-@`3Yu<)I-znRx2R@i{I&te>_(!@8@{cv_J0oA)jxRff&Gz7AN zmEXl9kC=C3E34)ga{hu9ubN^NuuzuReo%#%&PV6GZp|!*L5?>#AUkC&T@hsw0d(wA zs9gR|zkPA2?@|&>Dr5E6;KY^D`~zRc0Vm-{Y7#FDrQk*m@gePwbMN6HeFBGyrD->Q zUs$(i$I$^`zX+;}laUlRk4#|EM+2e(ah?=0cG?Mrlh=Bz@Jzc><0hlM_~=$I zrl4PTcW$~SsChJaa8u+)>z#;4WzIvl@0!;z;E=V;Hetkc+Ijz20{*;Z_^$CqX)aTiYWtj}H; z^Z30Jy1ZbXzWg9aiF3=dna?&U5fo8rVYZ!Zm_KVr+~j%uu99I-ghzMdE~sGdahPG# z4ikSz5-%N{@`Wurx9Wu(jZiM!1wKl5qNB`i;W*FCwo0x!AUFAlt;09s2A{R1l}#q; zyhKy92&NNYv`64Lh?{9}_>sa=Kr$r0j{gyN6rTIJ zmi)v90e$PTzy30!x2rdqSX7E9nrr!cI3}@Ak52ZyyuE`@8u}CkoiIEz^z=le%K91E zk&%}F&e=Sgk*bGEks0=C;p(_a?IQ@YX`)LamZ^uke!_*>QlQp6`{2CHtEYa>RDXkJlE$|r9lvPIG~#<0qk2L#GO>Wf0DJ$BAh@@Eip7hRLS}ttrPUm{D25r-1kD|2kf$) zNt2P*fUKD8(%(5d-T|~D$KRILH(vs98@qjCd*6b^xuW%NxJohTX(LcE>=b{v7R6Qe zg7*-QY-Blz$Up7l-iLf9_kUWdsxb_Fwr)fytwZhWySMIpI;ET`;Fqwjlk?lgiJhDb z=j{U?f(swdV-xjk1v3tXke(nqK|A2vlQ_kJogIN#1%(kY*>^&QKda>yJzuN9(imz4 zgLgLJErbjN6y;@`F$&bDLAL?AsUKBA+{Ww^HzXC|10>l5&diL@O~O_ovNfYJM3T{+ zq)apo<-_VIPGX~!u;+Xek2_EL1IUXJ;tz2rsFYKZc22@bejmvstsmAOxx*)Qu{XzG7nmGc^EuE*y$~ss zy3wHzUT(@~-KMtuyW3J0=T+~1Qed z#Pw#S(B*a4#Qki@Qkl6=%KeDMnx%JWM~Am7;9150`s6)y;=HkaLF~eCcRleP)X?7@ zWp8Y8HZ+;1Z$yJ;FQrtygQ60!rlDS@bW#DEv8v7w?tMSg<7rHqfoHhq_;w6S|GFFt zBw9dgG+R9xBhu3kQ$hNyMC6Qha^$ltD;%E+Qt}EPSCu_Uv?Ku$Hz3NoAEnb4aWi|8 zMLje}j%(eQhU+>@VI|##yHQUVK6b5|m8cSlwaH9A@7u34fu3Q`=YiveZ?3V#`N0;4 z0tRv;3(Fl{9{ad>Yf4XwI1ifb(AfJYA)C;^)`5*7j99OSlQWgQTS^vOy482&# zbQ$wPw}9}aT$$um^BF7ZMBEl6QCMB#(z=R9SleXw1;Sy&#aSlg=};%mYrH0b4d&Mp z^e1e7{dsWX3bCu7{fP8z@*2%|0(uKa?ythGP#hFatQ`GrIW9nuG)cUz#w&>n0wHD_ zo}MnhlDX|q1C4#FW%B65S+|3>56^g!Ud=~2I5;<_2csP52Hm0>`@B1M`91>9A}K(E z9(XHy3*?(#i=T?a$)eZ(n<}QkJ5@!0Zvr1NUbyZw2!6!R1Nh<*&s zrHbB0@Q(bDVTS}kxMV&o#KbpI$M`*^7ri0*bi?Xqizai%&~m@L@ET%*>LM0vztUIE z`^&WE0)vCh@Ed3ne`~v~@CDwu%Xbvtr7?xFJl3y?^&Mz!9A4Yv;po#{DU7Zg7 zrjSaLZC8^2t+p`i!43V<;dCJd%Oc#JdoastXW3P%cRb>ei>dbK24sCw z5lHG)KV9zz`OR}w-#Zn5@|%5}X?{cCgtd3_ zqmFIr6Hxi7p>m&=csO8SOmw>;#@8qcl8G`qJM&8wr1^rPyblX zuhH#f(naNw>58jh(zPMbUW-Y0N`+)4TlEVytUR@rSBGM=df3)YVYcUJjQ;LVRFAKu zlIsd^PHZ?Yb4a9Ub;vBv5};qd`X{vs>*OfC@EbTsYNnMs^FmQ))uJszRI4l()&0*e zAkS{Gz@%u|E~96>e8Lq^gDUQ+J5E{xX;&4PYGoZ_RilIh_XlOvCR5BgN)vf!#x46W z*1CReo#o_|WiH=@EN!U89rd07?Fk1=UW!(C4mk6|rlzgZn<4UmSa)_vL0fl4^fW4$#Gb%S4Y}vr4lWiGA&G0+q;uF{!8Y+ zep528uO4}Tj&Fktk=wfv7Yka@j?{kuha$8_A2o~)y3bs3%ke##1=I#KJ1u02QD3R7 z{jyrPmrku>M!>qOq8S!f=qZQ&7iblU9y4Z2&^(kh9~_CUtwM$%=BAb2zHIc*8Js>| z*DTs}(rN%izol#OaFW<>;|SKGJ|3auBL;tEy1S1!Ud~c$NTnnf3%>5mA^~XpI#!oRXE?W<$iP98wooISmxAr#H0BShBb4PL_ zeE9#wAPt@gwR5NO9Ori&JW&ZDpr&S2V0iULqax2gK+|lse{vbe7VQ@j5K@o504HYd zV>B?CZ3t+|QQtmR_d=u`0!(NAz#%37i_ zjqh9t+b+-3Y{j6`+u4)%NLn(B-3qUkPI;LM$zq-0iF;JGu|^L?yT*kMaSFXSB71+0X$vB+iP*s3Z$rtS7*7*3gt{O?H z_#D|k*ZNz36>X`9Ac^<>*5H}}7RYZC7CJQN=KuVbRQ&JHWRQM)P z^lIMv3hQn@kg29IatJEHaNW3nQ<0{#`Owe6o!u7bt_$Mp|Lvvz9cam&+_0)Rf zjM%F=IuGtU7@B&4f$Q*wPcl(EJV}o5vkCXUK^GK<|-rl^&nP@ts=#sw?T!6lNq;J|_2W<$4V$bB`%)kO8k(aX*Yi#EjH-e2H`C&i zEo=mTH7yIeS}L;Aux?EU;AF?2D3j}224gczOS@R}m9f!V$5~b_QY8%0vq3;oFRvL4 zXEyG<=1KH;%DL1JbcUz1a9O8ag8WI# zTLarFcokPa>v3RHDtNs7T;fkQ&!lI|9>Q2qQ1^l-yxGk20x9_R2Ad%HO65oYVc!*ky z`YlrxDVec(--Q$E+P*#$!=g*u+t|V8^4-xE9-T*ON8Z z^ep?e4UR^DY9;av2)^CSi>IQ%cE{ktWXKZ3?9&zezMCZ1SC-{FD=|p@J=)Og*A(%_ z#^S~atwqGvVdPfk?l%h7Rz7ROa#+FFydgNUVe8E@>__N{Z$>Fdj70yUBH!4Cb#H2O z@5Zlt+k$)dPw?Lj?Y$xiJG_wFQ-X13wG43KMbt2(Cf|NF-pK1pqq6CtzM0_>)vI5$sw-HUlh zqL;xbi==+0u>@9Bof0k_2azNy62bsTQikB-I3!Z6xON^Q0Oq}X%mE15BP_3}O&M== zhj+#^o5fV+@kv(!>BFU+is&&uO4Q>bCusadMlE##Sm;eUL+o9+4*P(vO!5fRE=ELv z-onM_jGcc%w=*Ci*}O2SNkSUfHCQrQ+<}T_RCynQ*@fZwkg%VO3F;Mi z$O>u(0XD}3r?lLR|NZC>5!O~f-){>x2#2iOxn@Q~ZfAbY?*v?%y2jobTZRxm(VxnF zY*rQ7xM~4!|B$&!zMrDmyiPTsy;x~A0u2=d+{kxNFvWvWemcZXPZj&Z$`7e`?AOds zX{uERdSkf@v0l7^){;2Dn~Uo)=vdjK`8G)44H^bL{%8 zniL_)vDO0m3bpoYsedBzJP~@sCxkeeTEIYx^9Kb~#PoF7b`PtC^gspmj6nJqKXtYP zNj${?d2vN-FCi5TpJq+%mG}k<4M2G<^LvFc{gElMkNC?u>smJjbwqqqg=h*E-JoGh zh&s3W^D|T0Y|Y`HC>HZjiNm=ybpp|chl?;C<(=UEW10GcJe_M#q;X$0KVB9b)3KoS zYir!wT?+@5!iGKHf+nXEvf)*DYL=0ABg*Y6M}Z5Sh-b-y_6L{f_E5uhS68HO?2u%9 zdFYizbF?+T?&h0Cp+jSl?I))}F9;Rw0FZsAC|=4SipNPFGZVgkdJ~acs$4f62S&Xp zjZ76l4I?jK_Agy6jVWC%+ui>cz;lVX6+YSI7ZJm%Kva|QHjzDh`zgBpHb-e2^XU}ATw3K2dfKFdLzTQXoHcbDlMorc zPk3LH9~GagX(yHw`K_5Dt4G%ME|9`Wf&ND2FHS-kV=Q($>$(XiY+X$hb>RG#&obk z8HCO5Bn0+!9%3oD8z(_PP#iQh zzA_hCpxRIo49o)KzA7T193kzWr|{_8u^6^bkCh6g%4P z0N?gAK&!$9@dDN*HUF*H>7+Wk^Xl9m^a+1n;iKWj6deAnJU#kR`cKQwqkP(7qe581 zL8v!As5`#UYktJ`X*a8*oOPEjB`?*a)Z+OGU5|~+egpZ&siTosj@1S+`w#%XJ2)KW zH>XY)dIlD(HP;rKV?naM#n;SEaIQ>V#gme~BtWZaOJMEasUv*g0D5_nf4&;ZKgL_O zg=j9gm+25YsnJ`~%S(Q%qr4jp*qGA4LAXxZH4y^S%3R%!z0bb^FcMqEGm4o?-NO~- z)ImH4QVadF{eS|xbbVvHqY@5?x{XAR{emIql$%#1eTQG9U};vLV~JF_#1km?A4|o; zvL>!h){f-X?@%}BOC%ZdLA}Ndc~7|)7_>6#Bn(*v9E2fJECxB%v*xkG+}?It9S$wS zHeVZiT6rAb|=L8JKL%@;4OacNAIh zWHMlZwrv!7WDoo^=x}E_dc&#YQMEgP`3Hlt7+KqB0WQw}hqO`!YEE|xA_DQ*sQ4BZRE-W-OlE*} zahoe~dF15sii}`JC>5AA^oz~wG1*pP{*L^IF{`FeUPxsNh%l+i&)beMc>(U8{NiE& zjxPt03>I^Hlr@4lcAK+a7D%Yrwq!6ix$;B5m`{TO|CfA>=mExcLbD@R{bKAiYBAEf z>qPvHckBHh9FLL2i9shMaIr3UafFQ4A<%~=$d#DNl=BEZw2Jgcy(aSH>EiNQ`ZK~- z=f~`OzOH|s{1S;Ygkh+S?>|i${ySZqO0?QOyZy4W%{&$LBkt!Q&6pQ_fKYibqY;^d zav4%iU9^=@Vs-J235-uY&LvfbUXb&3HhU!173?p;zJg*qis?%5G{_HQz~Q?~F`yU&hHRo=iZBo({k~k7R|>UJ$5{n7A+JZc zY&$V%I%>Nb3~|FXsAaM}!ENIF!}X!1COYJTi*JSlQQ{!cf6^qtj3j43NMc~xosQD0 zOmzJ`cAJ_F{w%oRpxu>dqH@7e%Zx!&TnEs`mzb%YY3chRTZ(xlOWbPBG@A~nAJGyt zJ`6iuBS@+J&y&=VA3FkmsHBXISuKKW9k7Tz6*cdaOp_}CNz2V6?kl#Awox)-vEA-y z_b!q(T`di7J-V{iE*Fd(9=3bjW#^Q9yq-!LM6vya7fMNNg6q~OGp^ie+m>wP& zjWncxcC|}%W_Em({51OYn)Qo+(pWDX{0vdvG@@K~>?iHR1ODCxplz`P$r!fb5HiJV z1VH%jo$kpTB=nNdV^H$UvIMzU|%_Un$Bg;8NR)*<^422tPpRyXNSotp|?ySsIm_^qC zm#H1KPFfNNMuRwQ*XACi7|R@@zD5u;lw<`vtOhm~0Xk>Rlk#&ZNt!lBNOeOo8x$BA zMYi!Vqa%`GjXAUmy$zzjSZ>-iobcc(_rT9==SdsHx5H8}s&>&}@E1=Ye3B!H8gUJy zi|e7#wnI7hbrU(Z&~R@=_PstI^oNU*N*|qCeEaq60a=;f(ADw%96lG$0c^76>t3*M zELZ5*r1~bddS6fl@Ou8#8=P2WG1(RQ%?+c9ALKNA}jZ}<&s-dm<`ere{Msf^v!hz;T^rVY$fH;|sqhs$D z!R@G#^<ogsDH_Ah zoH5N11Tiol%G#rh6Dr5bcSCG6KgkfX1o0g{niz^uHt{NqD^-XgGj6rw*pS}F13PL` z%d)*a?FPJtamN~5=+mw8H}qpuKDCgU>N&&FL{%pW7&8>vZjmjYphSrKT>d;l?i`xB z^0XX8=SMA5t1S;POta96J5S^n=>ia7i}!Joi!_Rom1~&G+B&U;o9omvW<-);{!&q! zgCHy_uVv3?f{yh=agXe8J7~S%f^)z6^O>DVl+F+_x_PF^bK86rJcsgmS``!44k^h( z!P{NiCS@Z9Ct*o84!P*yAookqGxJ*|w`e6fvDS7ZT&ch0caAh9RXeOge2RgeP}Y=g z#2Q&?RC0v4uwhJ=P33wvW34+jc3}Y8jLXsqU<~gpatfDu*4{rE{$8M%^Y^35j8+UA z{Lna2=|2BTO-XSq$qY6I1R4G?$<)6j=ATFbRc1!?vuKTnUpk|_TZ-u~+3ct= zmJp;+z=TM-srdZ1Y8VHwK)dLnI6kE4(rB03xJr#Y!)(U0|Aze1W1r#C+6`Z?eagZ9 z`jmx=CiF0Ep<)Qf7-smIyVN+Pym)~tnrFJT5wvi*sJzyJ!K56L&ZCfLz^!l_o;9a< z=7OUQ1P=hoG+>(PupOD#6xfZWQ!#?R$c=sosi|YE+lreOn}Lk8&$%A0G0^sANs|#9 zC0Wpe@Ca51K&G`Yq%1)U&dsl2wAPj7C4fwI;|mC1WhbE{c;eiq z>3FI1ON{NDJQcr zsXu)j3gNBwVE%xG2o!mMB!8IslHp_FFZ4WsvMqUAWR@Kl%v;7gvPg2<;(5{Jadt(; zM^_bTWtdSgxct-KP16o>X0{Q~S|j@#)b9h8Zap7o!;L0q{WSO3Ss+D@$~pVvwPfo2 zu6!k!QCvH4YB-4@Al$zTL}Bbd{8>nGvlBkq2drhfTgnzIzUH`)DlV{DcVQU%plUF< zo>mkH^=vzi1u5uVLu)#OSQ2H@o(!hm!c=br`=xa<>~3Q(q!P`8S`c*Rk`R$mho96( zeD~eZ!m8NDVg-f@s$iMqdFvnk>u7=zT$NM!KaPf()|4~Hi<;$`rx{4Y;;@WlKz5jF(l9)s z#@tnVA`__)>B@)U3uEa;inE} z#7|Ou6GybL*-dBR<4`ANwajch)Jhz1!{i~q zZu0=eGRlH05m1I!Q!YnJBqMRqs5f=_;pIQ-2r*T_A`D&TA`%DW;G`=H(hjJ@;TeyDyN4C5?R%mrymnVjQq^nu%MC>Gqm6W z$3CBGY4#(^7pw$_Akw9TPuZlHjo9&)tjATJ1QoE^DE%ypY{9p$>+pI;Tz^g53{-Zu zASg>({ScQYVVdR9v|L1!>>0R~d*VkBRmw077Azjn+G8%`ZA-Z$vNr)@KPT7NcNJ7Ey-GJ#9*D2t!_pmqXG$ z#p_o&VK5f8W7TcOwMPeO@JJp2sNK{zHx+_$v67;abSTko-Hj@%9W*!zdk9$|ffD?{tj6v2hT!g2c`f8%? zjXMctZm#Yq+mgnHfDnpsXr)nBZ8^yLOJ0f(Gifzx+CfsCYENK4&2_57Y=%@HYpbS#q z<)L(pixe_jXS08kUOXFblRxr-upGo+2(#0~W#Kn6p<2&Jz8}jo%>})OSv-SG$_Vk86kskCRlQvPX zXQJDZBW&&tr&K5!N-dc4(Gn$e{|u4jGYF|Ti68MTwn)1H!U+F>b(UFHA2{E}nSs|$ zmSL+4!Ll-vYbB|5Rk*GnhtM8xySsuZM+CmD!l< zo%2KwUyA;FKvz3Hw=zd5r80M~oCVKB*YyFD=#f^yu$bx*=5BF6Vtw3Zt2@wCY;(_? zol)UE1kFxUzLfEIvFnPH64%G0s?CNz2yb+#e}eS3);k^L07^9!lU2+*5YVTnE{Smo zgBh}iCiH+;;3)QtAtLeJXmJBTn;p{kdc#Ee!zWX+hrw#^HBGt}32?{nboxH55K4@> z7-El{n8soPXsO@L{9Gdp#f0%Tl5 zOXK`{L_d>`>7OKrb&byDj6@fD^GBC1#ovehYR-~0CU9e9gE3dl zZo||0MrB@h+_Ru~=6ivB78Du4weOV%4VEgSp`3Of8t4{etO>l%tzJJy?uNnL3AeDo zrIDMfFJhzA{(-9R+L}0XEtX!=$I8(?&kas0BNXh#%oRk;{i?)@`+oq&Ksmppy5X(f zAVR4_awm_V=)4eK`O2m*Y7hnm!$gx5Ifb<)N?K0R$!eRg@(9nmOYhg&GZ#DSd9H;- zrYv0l?3J#=I)QQCD`15x-Sj@};^V?T)+xqH%z^a?YUi}i!8Qeeev)x#FXPSt2Bul^HHYQ>C{t9L}QB2ABIeC>#X%T^n+o_*6xVAI|*BTOJZWIY#_skU}lk?0!BT?!gSDvXX28U zG#e2?;9b&cR4~jng#+h2AM}*d@&(Yp^=9sGsw>lkDoeM(=p17-Mr&Vq0*MnbPQ^GC zGA@XMWWNiyiW!$@lqH`43S&JI+E|UTmdJXVP^Bu5#sTs6=R)y_aY`0W69`Q+v~-$^ zPAevk!ZOAy03YkF*38^la%&monqHO>^mAgB(r#pQn*rTcNT(IiZpJj?kT42MoXBKN zsPxM7poEV_0UxyEFviduW!&D&*hmyZ*TM#kDVOu~`n!J@=RsQ;sdg095Yq1X+0opO zySYk)_r)9hPS#jWVKjv{6a-jR?S$UZb~ao={6D(CYZ(70 z3pXGhRC_4`~uTm{f-He^{bC})ruMtO#|6~ezvD=Vun zJQug>AmWnx#W`1^mve9F7Fk(;+hLr<5&3y7!U;b+rD7a+{~=(l5=DK#zV^gE0%s-G zX>4IIHYYNMXv{S&$8DWG+tZm3ZfqzyELel2pb=Qw4MnFJ&}>Ad<$nM6jMEea2o%l* zC69#ns%2V}7)>uVY!3^%y*=hyL*_dX-FA~^BPNO_eX@V7KHWigYznwin%Wq4hZ(o_ za_$Zl32mILF;?yKeC>Bg|V})1bfiOs?Fjf&*ZxJh@kUW3o{i=8$Qej1dOb^L&pBFq~ z$2z1>>*ImiCQpVK+U#k8>nAvua#{#Fji^+@)8~KQ`s7K(T1%4V?DR(5*&1?pr(iD) zFrtZ!;&B{IxXH%mxIs^|p(Cifqy-J>K|_JeP@-T|6cpC^a+y?CA^W-2pSINM2UD{i zz0NFA%(_5puY7e;_;QR+Vr8S8(>_&52zh{Od6FJ99sjP*RDbrL@2iqlc?YF0@o22} zv1Y5W))6^Z;w+vnA&SRVO*T_*Z1ozHC}@Um#^pRwh_mx^RyVkPdq#m!q0e2%QCMF9 zXO!gZB`M8bO1GJ_(9K!s#LTrDw3-o76plIgpOqY`0^SD%v6f!q-OhK0ij)pc#uLl; zVa(t0u{3#}lN*I48pnR0^uUsS3JQ$WSY@%&^RpUl(OP&^s0=4Diu<^U zCQuAdZD%bQ;Siz2NuSc7jX_yO=t4pn5LCPEG3>wAx9|cc0&93eMpSq$Fw_#0= z$rFk^rO+B}6;^~e*#;R-fy^ekxDWD1J?Q!l*q%>$cDy2XPEt6H%{A6$xX2P#l$Iqr zyS`2x-CUS8=e&rhwhdZqZsxKk=6DMiP+H^2)bP znDHQYgO~*CjnQtRMUkVmL0gHT;VD#Q1SMGxVlv07Rbg_(Be;lq8rRhO(ytUkV5}t5g-2mq=PkbA zc+>SJPVUJ$oYg1_8lk1rP_$bi&DevZrm;R1uk_=deC*=!*aIhU_|mN2MO{#&-s7@2 z8nLjKvOE{FINze(Y7&;Ij8AioJUR=w2KBYpGDtG+_Hs6cl96qJY9g!n&La*$>nw%V zWZGdxtPs2X7?mmSJ^1&nc_5 ze_w?Tq_^WdN?D3>uT;J_w{mt8Nw;oN@tn zb{vbJT!!y`DHV-cTv&|?Mp;2&t*2Jx!EwQ(?cUnrE2`St#-|SzIl4$G@*HjO>~zvA zU&dt^YhCLq!i$439Y@&dRqH2hFF{(?3UZUK8xyPV6aOgKY0MmYy` zTG62{=O?|*`!=2U&5w}2APg?TSk2JnB*T<`lCw7)vOFqSp3j-@G)t<>Uy;om121e!hCIi_wK2a}I=5 zsGv-Zk&}~&sdIVaj*gTBN)oD^L8{4&#W+vg;lJm`>%!O*bYy*dz#IZOo~)g7ba#m%e5;$a;Ym{H=&rU(9&a&m9-)XH5b7{oMF6F6gnr@215mCmT(T3=}y8|y7!6X41iw$I-^5Q+9c85_-bH;Z*Z0YVsrbUuw(`AvZq z8VukdBt(fxWtC?Y3oSRw2pM2)KxQ0;(L~PTD@8rr=D_zu&HX~zC&Cwr-^m<7FC$bb zOPwZRpvKmTdx+ydYpM5x)`p$E0pH!}aeK!y&<(6?)bi-d-|&D9hVbAfXD!xfOrio0^8Gu^@n%VR?rh@%QX8;2%1MfX{%DWYg_M#aAi`hq6iyTSEO ze!+*o`6btH-6eHRR$lrGbiBe`HzeOn$#Q7TFVku@QBv%i%SzQ<(t==AFw6^b<8W3@ zHsI_}_j|&g9v{=$0#jrZc|wsFXaicrpqe;&NDW#co`WJVbyu!mTP71i;t0_WC^U$I zh7gbKjy?$GKIL+b+<`9VLtB0<{Z`MCDUGE%DTx#)!V-%Tv6rW$MaD2o8K#ESMa{xo zlVD-!YAb&^P6SvHk`*~kQxJsFBlO2ipVX`XAp}mvq{gu^ z?9&KxA|+`z;%7g89zv>lrnOy&NNf=0iVTqD9wk&wJpUJCi$fNad{pv&s zkTeA*8lr&} z6ISwE3#YxyITm!=A?>nspg5qjp7#6`WA9km?RC)6a&-qA(dh>*3uuQ zT;J$(YsWIw4V;Q=#2Sxr-^$;aY>(c(Z@F{h9;|PZX2ld}XdEZ5qkyd~_ns12qdTNX z8139(^Y*vwrGojF-siQq-s9z0-(qdGLw@gH_~Q5f!maES;pvw-wYo$jXiPP~e$S=w zv3ybHa)&`dKhY&hy38Js`(4ua?THxxUj2o07Nb*&bV!~T6i#7e(-Z!TQ;H7iZgF(0 z@iEC5_aMsjKj$rBQ5b~CiDRaC!S6TsX4P*U--(cJbYQoz-2Dai{q2RZjfg48uZMK!e0qc^io z?N;c5!h#jyB$oWlrBuGoc)*n`u*!~;!u>UP6tXD<)>efTCY4Q&OZ@ggVT?m+1HvJz z9WD;5EZS*uBav2mH+3yF<=IRRi4y^Z5foZutwyQJ3VytJ!x(Dh1VSjRYO+^o;z3Fy z%ve^EFnBiAI3HH5wG4(Sw>Jme-qs8X5B?cfk9yK&z?Cszt;>|P>E5ewCsrqndUx2q zbAz3o9Wo<`+RH4io@aUW6s=G*+WeZ^-+a#9dz%!-yI!Pf5Cj4{y3WndKH$qwK43#H z6EDtF?B3-3rB_&6KTD?-qa^!X-hh&dMl4ZMqQ)+1?TI_A-;`HrCl7z!ZffIdZGkBg z@+_gqHH8hZs_B7NqD1A_8}$N<$6k1ETv58Cr7WnJ${skL%5~ji0u92MlFPYtIX5HX zxa4wnV&6}ncM(D$Wr!1s%m!?Y5;C2W6@5+@mZkX?%|^+xcLZwqkyoHu_p>&Jong+# z&@wQMajtK9HIIbwEq_Ec(yIzV+6tVAyaKDC?Vg2HaRlQmMV05PtoMx9VpGmIY;LhN z(AAWUbrhqq4rp+$28L5(vJWAhf0W=FC&30Dtu3uYI6=Uq8c_w2IsT5E=4f^zKs#Rx z*=UWDAwoV*J8Dj*DN++fA)0Jwnz*0Si~_o4L5pgm=$?^#tS zs}VcbKjGW2K4atFF4;)1ef>ke6aw@v>nk~5eexlY?4)MyX}(=132YG0rvBK9C)*mQBv_F zV8ACzLrM$H)*xd$m1M4gP?dlD$xYO8ja*|fPL3_e^5jocAOIhia-TC5Pb3!#TY}cpKxb8VRHZljdEiX?RrT*xm8uZW`z8xNxPgm!#T0%vqH|2&orpY{mE*{5vtio!~745=W(vtwEJc7Hh66H!zO&x%9 z+zZcCh*#i5h_)$(sR#oeEgk7WC-H!<5N(_6<^`L>f<~m6YpI$m_Sxn~JLedsId`@O z-0L|~6C+FD$B~9F4m&>}D|ft37;atX&Uat3JIraXF0-(Dj>S$wzOX>xzNNQuot>SO zH-2=L^Os-di%)*fJu}DZOF!Y&_x>GM&Nmosb=mm%U-`0i7rk(ii*Nlc@4WLCD{~!` z3cS5_pIp>~J`2NuZiSK_d22W`&X+f=qoik;`zxfgSH9lzwW{q4C)9S*bv(!OBkrM= zzlRySQ%YD!td$g66BLE7GcG1X9b=a>not%V<=hHsHDbc>VDH}HZFt;kc);((H0t|t z`=wICQyz~JDUFITPO+VgaQAYY>mv|!+D(Gs@z$z`Qo#E!r~+PP>=hA4G$wK1hh@=u zz&V_?Xrs|c&o=W6C&L6O4BBb5&{$<~a%Q1+V70|+fps&e=cm;EvHBFEjP)q2wUc;o z=}4&J!A2Q>O*SB^P^C{T%vI;V##c4c0tYJxbQd#ys-Jr?Vs7E`>X+$A$ zcr?sFk0bT5pBDu?dn4{_=M0Mog2ohJ=vZ4g6EU*7AQ|-N?{1L}wn)DDEgz=0_$tsO zySLcd=@W(-d6q&Ddbe_@kTM{Q+cevAG}{qo)bgeAq{0Rfjn*9PPM1a_#*V!mhg(yXAc5mq&!p4(d=`_F+l1P)gykM;d} zU*p3KqT2jAM^ct9ngNgJl)$H#Tevs9-KI_CY!eWo{m zQ{Y+xG%a@0q*TH^&I*|8w2)FhvOD^*T+q4J?2dA_MvmMyKt)GxF<5K;LOdJ)eTHI7 zf?; zT-BG&1dSF^+$0JiI(3!qilV*tI;T%95e1T@PI5rC;JF(4K?P!}&coFA zAG)2jrB+Hs9C?&pB*Mu++PSW;rpKc z!nm*NG`?dL%Y(ueLgHM2HYGM>3{cdB!g!Z+E1=!n?{cnJW11*iH!iL))y%RDqULR@ ze>$cBowaytV{`g`RoCn$DWYPUj~r*Qb&%@g--HQZ)HK;mL2efWYJil2Zo4_&$UW@2 z9!de%0WDRbh3%ncpd)NW2r!L5e1eMvgu^;RVT>=nAf8RSh^wgf$_};8poPXrJJ}GF z3u6`gwWh3cBxe)Q>(9q4lUP^zN=R(U7cHbi3O9CXI$5SBS&ebw#0~9SX$e22#Yt3c zRv72wphpo0-Y3;0k^zNnu$ybX+Qy}`UJY6*Ogzc(ex1VrtuOM@+F{T1sX{j8O zIPmptE!G&26U``;LIx2sUSQ?oPk8GmKjZ9TgFrfr5rpk!mQG)!6C3uN-9P_psZD-S z^&mTIeAO;DqqHBb-zG!~VHkQY=^#gym6cNMyeA5UvxXv1CT{1lh{A-cVCu-n)zeQT zqU=9g7@V!U*1feVq?~MQoW*2&WP>fT+!3^vX>{iaD@Lc8o8-OkzNUDQkFcW+^0bdJ zj^&k8tjsMl-)T+}YfJ@q960O&g|TLgkBVR0_?+_k&GgrxJVP24_jgT+JB!hiapSL5 zA(a{vxKJu^YYXpP0fbbK9iyJDojr#5$pB-U?4$yv#D z?2K}DQh^ptgb1em}gcYWUQR4(y^;6zA? zz@YO1gWXMbw>JshJYf`%l|tE=2hNpA;f)%?-8qz!G#fEWDWV{!H!8eKT1$!|_kb&- zu(DOUoohgw=TzxVr)CwHbdS;Q9kOJEE&EEyh#>9~wHIl$<~*qeIqA-4-1+1m*xYf< zz4UX=y!t+Koz}EcDesU!hXfg*(*b+ef62`+KA=~0dF?O%AFQpd5`{tS-niQG>aclA zo~IN}5j9#K;XV$-*WA$CVl2E4vDbIB>S0NPF~m zHyI8GekE_7y|w^o`|r#-C3He9dWzbry}rN$X4gF`;jpSib^CNg7|d4WFTmffmA7 zO|q`0gvVB}zzK(y9`t6N9b3UqD<615*y3LdE z&}yu(cHs(h-+e&u=0|+>;Sy?aj;6{P4HLqJi(Ghfg+{wdSDCm${W&B;HfS_j#DQjW z>npzg{of<{cer@f4m0-pLq=IfUIb{_n2z~U z*=Wy}isrsoD)5_Vmy+#$$?XsS2iqGr$g}|@GH4QY*66Ii&hq(pSzJ9s99eX_#bD!8 zw(mMvc$HOcYM96U^Lq@ubee4MI-B4Aj?H|P^;iEL+6vEy?0k9C=^q+K+h23%#<%RT z#F>QnA+Y%t0Sglf{BKf|d@Z*%FDw>W$DEbT@JE@SuRhkWvHzu?xO z#rYrq2i|!5T~jwnqu!Rz?_%SY4DvQS?v@sSmx~cg~kW+ZpBb zGD$%LRWb5RvX_r!z&UF%&SIUw$tT#Ij!})JE4hj-l&|Yyd#{Wph~=sF;4oN>@YZiF z$OV8k7Nfxu;Ku1v&w$!--}O%}MU(+wVs2oN#S$*a2 zSh(~)Yb{UWpu(6S^uQ?Z1(K+6j>WZ0oLXCD-@yYU{2Ko|lAQdq3c&_#~1Rhh}W zRH$O??gob~2JBq_kk5Yi8#dGxXs*%ic71*Fk_%!S7IT`Sf1Mkj{xiS(=ie|gA&q8> zFpwZ)S}T9%UN40p=GB)k5=%|8^DWxrhp0FvUXS> z?{cPm?GQpDUF6x9M2#-eRqb&Y3`SU-D1juU5j{>jvSN~URNbKGAeCVpzZc#b!Fg1) zwH8(FZA2Lh76#+YB+l{FjRGI9c1X-PKKS^1)`#mKg%%NenPP9G=`;#j^63_-Fvjye z_eO@ygorSljN#*GhXatPc#gT1^Q@iiG0ZGV35?Et8jmh8))BSWS$*~Ic;6_R3%}v| zjhhV99!1civ%1dmsdLP=Bb0K4&1Du(U1BZhurSvp3;(e7 z!{F{03~v9PJ93Wh=~rma%@MXwGk@;KFb}O$XFUJ8GnisTKH4Ks2V?GaoIwgfv)LqQ z8KhDrE0)C;LxwxI+0c%{NP>nBOSBqIgv&^FzvI@|f8@(ge$P%bWpVv7-G*R!ah}fH z98r~`Bg(;NEvCrOP7yC(=JMq$bb=9^H$Lai%@6rZ%(1+Fk#pxyqhz1WYyZke|N7tf z@WanZ)gnvhUtxKn1L-E)x395v?bm#$1**Bk!u-!T)%7{czM@ruE{k{^-T0a;j1>mK z5;D@3yL&@gjS-D7pxtiG{BFNI&;qW0m}|{mlGD!>T6lEkByReogLi)llF$G33izPO zu@9y`VD|?c2k7rM|8)JTzt--)fQP#qY_}H^P3-M%SuU4zjb~`DX`YJWj5A#1ZNl@b6hb= zgk&yeH%VAXbDGi7qxuh$3bm=VVKB@XW)9;5)PV@mBRnq-WI%J}6<+>}{};`3Kld>; zst}Mwg_3RavI!zvnadh^s&d^s{Yf00DVVa{w zgD`G^RVZzJZE@>-p1i9+#s52 zYE3|C6)^3{??a7m!8rsHBSHpw#NC~oRy-t%LZYai4YOYkRlxO-jC0=l-5F^z=kw+e z6YYQ0Qdz*R;wYZ6BoECI8zb=y7L6sxO8;Zcbv2S8`LaU_}`RHh6yB>MEWddfVYGVCyK+j+V!% zSNd>LAsQ7{HR$Cjdx>VQrMCJm;+~V}QcrKcp%#1B%Yt8@#;wD%OEe0kWd$6Oy2{ z#Og~6EMIuXyD>}NVJT&85qpAuboIX-y2u%gQU<9-i#9Tdi5y62kiwE{hqe}rtbh^+ zAN09X!sSg=4dV70=GR|mF6>d<{xxx^NKAp%24^%y{{}nX{0p~l8S?femM^_RG`hv+ z=l_%MKL0(#VSV_uu8zd<&ayacVK5f9D%EfAeRyZhp?)d)u5p z^(gFWPjC-v1V0{9q|mOx&aj}po6>2g%$Kg{!%|W2_iMV324E8+p%?C{s?3xcloc5+BF& z3ihx?U}~c)B}zsIa+8g7R8@!yLLblFr_m)s&7jO@$rFxf)pX8~rXz-FL2e@mJm^XY z2t$FC7AXx`VJM8Z_-PYf5~@Wd`1?XX64e4SYA1eEe?SKr~nl}mIQ zK?!=Tb!PQ!G)1z@-n|>#DMsA6@g4ot5O$a7%qD-1%9$fj-XK^I9!S*0!Zf8g{j%YS3Ps{#8 z+}8yy@QAl0*Yr}uPzN{_*7BT=!%bGkYpqAb)~Ou#U%x1s7Y)|s7?EI9iVHJbs3Eiv zSf9lt850al6cQx?#NmivhrE3&YD=oK9kKTumyD(IUXlF~F z=)lzyeVj)`SNVL;V)ZFw)z%4bX&nQSd|$O403k7=!JyFel7e=_pdvZ`{&9)5mMqtd zGKX~vA*(5QT-%>Xw!Sw+9+J8Jp}yy)_LkN8#yeYg_(*@^`p=ce&N*~ZFdC(#g&0?m zs-H(GNi0B0fhtVtlJ@g>oHa1HqUTEqS9#(227BNA178(i5ZXS&tsCh04D;vTV`*iL zI0_imEDC|Z=0nomn+$ihA%214cUOq>=JI`oCfd!#j%%6UP zSAY5+xwz!G`(cChm%m_l=O)`bdl>aHD`&58YITLytscRtt6YBfKl1jQud_7Yrqxgg z?7lG}gv6w~Y=8Ajer;~@ahS1p?>Ymq$mv(#i2w8z9{LMX@#c6s$bgpuVP1nz@EgRJraZY1IhE^j?IKo94#1;_>pAB>nihAsF zs$#s=`(oc$Z3We;;>ML*vI1YZ08bP$QNRz?BjYYCQQ3A9?>zJeHHMeRvleQ|JtuKi z;EcmnRUWIym^9&8utHVHf=PAKH2sSKcF9!ow|Qj=vVNoFWqjHt8pRe7^Qprk~GK5a<~ zUAm+V*7*>KnCYYEO`I8!?tIDS@EdHAVAUe?m;RDdFaMN<%5;AD(cAxenpl~#B!j;DdN-u-Tm+i$h+Ql`>Zoe0Q^fZbunZZDzTjA=I2f$Ql$ z1w5??9a>v@sb*04xPxDij`IRtY1JO0IBRWlXtWrig8?Q^5Dkrp7#Eozr`gp1IiTs{ z;AWJhDiv0Gl72La{o;4cVggutvpGIN7Xu1#YeM zgVnl8-2>sU!UNcj7Ulkk{o<;7JlzM6)5{N*vVWzYIQ=YRlod3ikRXuE=EEPQSYycx zjW*SopJX3Ao#lUjF?)BQsp<~=U447(4mWSdao*z=tqVq@gv>~sh@rlrnKCYX`$Hkh zoMA(jdu!MibddWzCC4k`5k3=$piSI8L#Nv$+q+I?yTtQnnOi+iquE4=be!i6fHQsX{Z2cG&)bo zt-%0+EJ3igpeWt!LIwn3_()7tM|SsWeC;@JG9obrTYD)B-IO?v4rJpx&;>n7J#vil zfbTy)x>!>9vHRQ?&0J7ARoOu zq%Gb>ZmlR!IGxl#IpX2xnp}*<8H3dpMCfa=&W>1T5m=-!KGy8ify(!xmkLoO_DfI9 z5qP{gH4E52#=>(HOI2y3Gxmx+RWcKS6%iwo(oYNKT4r2o?6^c5LzWj5#?yf!3(6`Q zhj$P#VUDRwO=*k!FX@#Q_IG3HiVlJ*++fJH#yE*}^5{Gu_l-0?APhD3yiMkV2$txs zzt5S==g4mTiaXbDlK1a2+S^8-Iz?0`kP{B2pwU@mE_{_!r_a#)>LzzS`Y+_S=PCAX zVw-1JKK}+w%gY4HjDdDSDgqUj$b2UE9jGd=?W>ty$IZIho3$@F=aA7H-Sa={fF2o^K1oac+S5j(?-yzXN|QC0b=Z4O-Z4~NWcaqz2IquV)u98rtPIs9VdrYFVp$a{n< zcFwzmWmFP*%#I#|a0SAe@{*ol!5a6G^hFw+p#(jT5$8@+UWliMfUf$_l|VN~9RPKF zDLIvl5&a@0cM-jG#7eGdM$xe%VXd{~dB$k4%dkiYqGr{i+O^l-nR$E02A%mut^fAv zYKJXSvNR#fa&OHD#^fAf+#-%5l&WnAg+MrqHJRsB&OJ#3A|ME(vQR@v9Ghm@$s0?qb3f%}@ht#5I~5>aEGxwG%Ge(7~O?FQEDP*nG}-uY$7 zY|?2np$u!#*^qRw!*H-m&{U|fPN`ZyoI?aLt;LI6cBiajRSYBSF5r+&P zbYG55Dp$0xvpmcsy4V3K86h9Fk@x!rWF755g)RX{W-0`T9DQkYH$_$o026*R2I=A9QN^A zH2FnoDIIJv9gmDd2r|H$h<-j|RA{=^ppKCrT1r76EaW}%fgzLer2J-WNKYx>dV{BX z?tt#zuY3i7)g(LLaqGJ;xN&QfOdCJHRY=@gV1D^5tLx`jSePdcJ=wjpntZfNZ}SHC z?%rm1Zo4dRO_naa!rAlZX+?^M4rD!O z?^Vq;2St%HObZ4@j15B2Oi_PqDuGE|*{Vh;MKFlG~sChA%I^!kM+7G2c1MnU`K+ z{qxWGV&e-w`}O~YO73!IZ2>#H#m&!t#aG|nLATCu>eB11uP)IHWsMTmGGn73tBn0Q z!msCr2^c1ZB+cn|Y-zMjbnJm3Ea#ke=M=hhKL?1Cv8E2wKMtwNP>pktC)=yB@->YC zG;;>a)=q&*&ozIIlDxc-;HFU)yasr*W?EATtThg3|_T!6|QO6V80(4nBg(z~5OeT)mKRbEC&z zswhMgF=l0(^vh&O%mNdq-TPA?HjOV+!=-Rr;Sli&Y}Z?4~@KTI(t34w|_%&))7<+uNuH{N-lweB2B zYc~5gx&Ehrox?^BYh78M&w7;fm>}iRJu(ktF(0getG$-Mxv;D}SH_BvsA!JH-0Lh~e4Cw( z8*FTU!o6>=u)Nx#6-YwmeGNkRd{k*Hrbx-t9%+$)%g6@z81CJozju%H<-g$US{ErQ zr3UgE8nmN@g;U-8QA8|?kt2W)-wFZ^!nGd^#} zxMILyZ=2N3bNaQP^4i-!W^HMnNR52koUMR7PtA{4&k(gjU_{6$D;Om?#@LcwY$69+ zz<5H2B-4xvfky3v@*neMfGuz~8G`|w(`Y$F2R&Snf^-NYz*L}>$%U80;}CFFePRQ~ z;dBn#(=;MN5N-?_5he#xgw<1+B;`O=CEToM!*aGHkwAIHB_!h*u{dbbmgwgq2Ms8L zl?T`cRwHbV6dLJ5L=f&f%=nsWZytJ=T+Qj_3`*n##u5Yq;XqkMOim~=WL*Ity0NLf zQFGHxe=f!$fr%@>e$(p5&;)@aP^v_+AK(7#wkO z`W&4$gwm4i-eI?I$&4cIuF#!}2@X-fZf4wgNQB@)8$fF<7Db>_V&)-eA@+HbYJI@N zjVf&nVQ$E^MO#su*OT#l{8FksnGrTuXf0i!>jdq&6~cIquoJUz?tRv`ZeqT^hO&LI zhPb`V{OUy(tz&L+g(v{q?~`X4PKJbWlR$yXcNz3=(cj(15VJD>9&-!Jtew4tNS2tN zpC=5xA`Y4hESx&esrEbza~(pZP_0$gUivXt-?&5m=@*QO0i%A8EZ5V;7`(}gjJtG~ z&a!s8!Q$c~aTpRbmsmdk4p-m$2|MYB5Q5EDCqKb7sfKm4XIK8fA;?KNwOrp&jlY>M@2-+lHH@aM_~p8Ff-sKX;;`? zUM_9z{=xg@nyqm^aBX)l$t3|08Z*EEnC|K>l_JDZ?!F)VoQM;VktI_^X8B`X)mf35 z5l6r7um9fPixWB+e)k9Q8UwH(s1mhsXg3EcJdRdOAvs0mB_eTyc7R*fdAkU(uEFaL zOdlOOu~S$hNl?y_dV%Z$aIeC}HaK6R+V;X^V!e!`n?bvvkhTsS5{JQy(4;}gq3cD5 zYeTWT^$6#JI=NeOUhapr$hJZYi}5Mar^7wEu=~S*T+~kvzVZMT>1#6AlKW5wBZWf? zkCyH7f(mQuD*?u(?<@MVxcSY&Yg?|L^`#AoRvBrUEk}&2Sbd$h(J~JmMy}0*MbmeP zx}F9Np>aUM@$n&fQ81ZI`Rc`-ms8Keg%Pyq9AvIy&pjZ8z)Kg>hEk%^F^6CNYkv8! z{xwfVQ-1qr|4;tgfBvtWeDzzNfBS+Ofosor{tti3Z~p4fd0nPF`0@Y5@BP6q`TXG? zZuS-b{Fncczx=a5kXJpA$hO8OK=Pk%(7kI*JT zKlmx1|LosW9Q+2GJY;|GfKfK)@$da_n9n?u@BV<)o^kr@H%#ZA{L%08_~8#2j}oX) zc>Pa*!t>|PIQjZ-vG(UY{_f8xl9bnF!PDN`uDWiXPmTS4n_u0=+RR?|JnbA{NOu0{o!Bp?Kj^rUo@Z##z&v?`1?QS^Y8wE z!-EM%O1w{)Jo*V={_6kAWS;T#d*5M{cI`fHWXv=$a}kExO6IktXXTcHBuO?v$U?oc~9abnM<%vZ3N&xmp?poovPV|)_!ekX>3j7S{w;p^Xalpa{=dBVr@!R9%sBelzvU;t{GT`) z8{GVN{PTZlsAvC)($?r~%)>8!$`8K$18OTsiUW#Fg3K8|{y9GzeTT+LOuo-33nI02 z?{hx?y*&=U`wN=JAx%y;nvnNSSlx;8(qQ&~zz_cDh{wNYQR#&7cnpBb4tem!|3LoW zr_@%2_s3iTzIJq3jjSTCttOI^3P!mk+?Z%siv?j?D4uQ;F>P6^^GvNEV2rDe_T`Nc-Tqeeaj+C~w(R(TR&(>7a(ROelN-7^w>DMssSzx<^P4dt~`BwCW_8Q+{VoGfOPw#CU5F$gYw%KW{K>{4X7I@G~ZwW3-~ zSxo0FX6H1mL#0KqHS{&*$?tgi@>^y$=lJQ*_~OUE&v(E3J;sT`w|nUJ72o~d|C?X` z`X8CS{wH3%I$>T;U_;NolGhI{ z20!T!+oR2m>E7QUlLLzM2yh7BBC!}PNKJt;`&|n>mc6va_+i+r`X!5hUQo_nQk4nF z1f7ma5@_cQ*aoRGM*EN0+ke2`(PtdwCfxhZby^rjGCn5T>#QEV?d)Pfn2aJR7#%!a zW*%La5gc}?6DV}H&wg>lfuMUimeR%d{`|RZh><69iNKOo%&Qdm(MI-RiEZ2Xp-yJo)zmy6o z6xKr{O2ok&{n(=RRG1kK9jiWKlY#-f1*1d3w@-0S<7E&V;-dU_|X`70= zZm6xLaSbg3CnU~=TD#D>!ytu1dv#%OCWS$0iO>dNk~i=2=0!Gm+J+0D54;ZHElPmW z3Sl&u&;Voj@y>Z%YjL*4SdEr+>7?sepIu**4ZCwg5{mxw5Fiz8qbZw~s%gnnAA0jH z5AoG*(@@-KjOOrQLYgHMSx8C0n9f;Phm$EDGpNPfdg$KggK^EA)35%VzxgllB01x$ zzx`8A>y-U3e#Dc{zRO6$`Rq0G`HV)7DGop5U@|6E;B2U2ONs~V9Xw#1OU|ovX6G~N zs{M!!d*>Yh9L}~_+hSXXmlZ<3%~|fI*1gp+oak_LH+@bc;j6%ZCB9Y#x1 zr9x{_>#!I4?sZiewn6BetQe#Gb58&1Kk*M{&da35p8baB|M(BM+jQ#u`j;MP(XJ{Hp8#~+-mSO{F%#zc;Us(jOx{# zNADc2X{qX#x@q4YfIU#RmPPHUox;oB<>@A7A;X8SrS)^_>=kZrh8h!s@30X3(xds# zhlkZ->%jI>2&7i%t7y*Njl7&MaJHpsnh=PahN@|3yrcCc!b_yDNkkIF)*F&;EeY$h zN_DB(^%d^zM{)2zU9$?|+c0t#jy~QRtw~Knn&@D1zOlIMtfLj+>wW~cCbPX_23p_S z>O|8iZ=Fo2Y|Wx>*>esh<+YBYH&fE1JVQT_q=}|@HRGF;1*c_8D+-Xo@n@MzTV{pc zwl2Am>PO(}DX)L~fAS}<{}SyR8Y?Is{~O8Ww$kx%ijdkHS zy}#HzU)whD;ybKTrXGPqNsm+ltfFldc1@#m@jV1B!b~`N`ePovI_K4k|Hf}$|0PO- z5*}?PJpBH@;0IrRpG?-AzkbGSxn}zIsh3}U&>Q#V;t{_5UHz6{+^#@*6Yu!5;v;@{ z%TM;LY`k~4dP)J5Rf2QtBP6}~Cf<9hx@FNgTGA^Mf4ti+_@!N9>nkepigt1WlX|tK zes$A-G=uuKRedcX080^M`&VRZrqEy#jA==ehNh{h>z1mjkhX=kp|#*#vRor(Dg0@X z(xSEL8fCxPcY5h$ghO<4eAzi^Y2(q-qm{&HfzcAJ!XJ4_BYJ_rS&I{H;}fqs2;Wk` zU4HyE8Yd=o-a$X<#8F^1Zr) zee{V#DvePBO+{5Vor2uZw@n=!-EF`ArU zJ}p0eE%1U?0wuy9=_S4$WUSU=+WP!mr3V~;?-wYYbAIxix~cIfbTVdi_>_mA|A@z* zJtEUBZ8ck4BVE=(533;thh|%_+>Ec6tm19QzvYx%rUAO_=eC@OWzY9ZPr2Ck;v4p0 zwZpzkedB5pS))a$jeoNdhXC(9Wz$l&9w+obcyf(5({MqGZuZNRI(rFw3q7bdvxh_Wsp*%O-hosq^ZFuhmn@5nbEjKC}R?)t0~rAIOd+APf(9+T|{^8O)2SW9ZGWYIY64H~?! zuki{JlW=&TNK-?ePDx(Oc{!UiZynC1co~|0Z+l$4?d*6wDjhNY-XHVxFCXDw{WX96 zcVBf&CoT+imB!>_vNS`rbIP+9Ocx7k2bq%K8=C5r`S}Tp%A!UESy7-(ZwYu!YJuev z1(+mdytg0BI2J9nH#nJvAdK89#N2W)-gu-2XK4AF>8d4~Huy-lE!e)h$;N!mFK4Eg zl}HZHidY5+=^a8iw1Pwnj9v}G-+q3(zrDj~#bh+%^Y8u$Ege!4{GO%3BsnHcgVy1~ z6*AcGcL~6k9MHFEo|f0EUnRWXd}1z>(qB@1wh=$Q-~7fKH~%f$zIyXe4bvj2$xXx2 zp5Z%>#_UhV7c#1P<6UsxQ?-`L0#Ywki#LgN6^%Z{P0nCs5qe9zz>nD^|CWDW_S#3W zx*5F?2%*rO(pQ^=d^Dl1E2^rZt{sgNv|i$53M%bVj(X6pZWtV0r@n3xSd<6>H>8&Z ziB=dbLke4l*}d3E<-ciwadSR0JBE;0BvtD}`nBs#d}Bfmu^LS)r5F`CT6HSvmouKd zo^x8YSVBsAsjut;w^&VuFaMCPGtT7EPx;X=eo1k5#O(F|oqv4xm;Cnc{)!*`;D_W7 z64L#r>>nJG`ENP<_Sby%)mMD>{85U|YL^ym1a=Ep=n58&B&7U6r*Qd(DbO#S-*!+`Ea_Httb!i_0~MkcEnahBC#owx}t z(rVk%dV!;FA?P}>M-XBNZ$oNIxKOVs!@92STyV4wDLp~Agn(mB(4&Ae`@X`!19FYoiKybZdivhW_MEmC(X zX)AD{+XF*C>E&Txe}nMa;5jILSnEx6pSgO!c9q^aq;D`9@t9)JlW{j!C|DNu@=Nii;mYdF`^ zs&j09jwme4-UM3}av%ATs~x|-J-b9**X!Dr>OUb-IzcIeNi1m_)``oiqN?W9?Si(m zy7WSWkVqNUp|tWOT99bDT+>xs)^z>AlI_+6PIrbdD{yEUr>Gi>bq=N1%TsP-OEyx{ z#uyIvC!~oXOU_AN&UrCiFt+LuJtu$u8~*uE{}0ONf5q|P2v@%3#aDmNt8>Z0 z_x^w%{`?m_J~|{-vsD>OS59&rx7tuaE~O&P3Y5}lHABtj%&IxHwK$)3p7s*F=t>dS zkMW0XKsd%y^y%SHGhEk}#?rOz^WmHfo@GntweIw+gjPYbvAnMn9c)6E*TL#kZhMRc z4TwehmPEA_sbEqViY!5Ez0?eBYdiTqM)rN{&aK&yF)59`6MqrM}!n zautBPi>PTWRqJW{R$KzEw|=U>2?QR8^%ZS0#T5%wMpu)1-DM0nQ$8>h1o%DzZ+>j| z5D_K_OSD#`dQQEV($)){6F6al8dc|{X@)T-h^SO2l-YEwT55D+(0xCGp?d540PNo} z1$IqaGbsB~N>LOUPqm`RQ;HYUkdiJNT3H}evNDP2)0}+(Tm~J5GAT)tbq{7qGJeG4 zFMr7ofB667<$wEIUi|h?`R#9i#p9#j`rRG2I>tFu^FMs=AdH!1fiApCt z_~HM+PyYDd^9R5GGmiEOWIIJDjZQL>G}Jd=rKEFnU^0B&m;^bNXk$pGGtTD=7Pi5< z5nct0&$Sad%)5TTeKH&bC@D!35i}OPjb-1uPY8q;%VnK4iG}y{+Kog*I+*pY@89r) zS$1Vx4zyf5NI5IUc|w{Pq>`)b$Ysxi_t^JOd+fX@=#o|SdkZG_>l=9-Jc*Dpd2I6<5%S>1#wQX=W zD8zaff>}-PP$o%}8Q;9Fc{Q6+wzg9OuM9+n?Hmw_bpLyN=V$*bzbww!|KU$K80Sb` zFnRP7e)2E>Z?yUMIFpYVXBr_i`Oz1A|6lw&RC>&#@BKC3K7Y=lYC+|}67UCq$oGHr zFZlfN15z#VK4b6EkNMHR{P*lF_WADjzeABo#468vZA&6TN|Z3arTkL9n5lm4_hQ*f#jZ3&lmDqXU8kY@!8;kzu{JGu8mHB@hg<8=g)J z(qLpuk-#`N6qyOZcgIF-k*CXr7MHO5&YoQCrUEE$3y$qIERB!P*4pLW+7>o-$0`?^gWSZA4g) zb3)?0ptdg958hCF#5Zmj{cRcUk&u!elO&ofnUcI*@N&9f-a1;>2VuFaJ@q~`3{Q`L z$QQpHbM)heWb&A!gApLnqsM&q^M6b6_zzjMitOMCMXC`hVf^sN{BZn;M_>Gk>GYhs zu^lH55lr87FF43VUToWQ%Hl8Bi~zq!-M} z1+{ZHf;FN*uAXyOK>sdMND>o-k4jo(V`;3zdGKB?9sPpBqpMUfg4F1)WJPxSGJIFD zRzlqS4D=~yqb%bT#%n3(_3es$2!4=p34&MUx|H+S^VxCEqvJ87BHvItzqu}74?n>B zP|wykqQ1!_gU921gVi&9RwI*@D(`xQL!!$EU&Uu^FZ#Ri&|dbcv|tFi>1@iZl9V=~CF{~`2IThhC^ok#j)d13 z&K8`Pw3eso9^UMO&qt54ydhTIRoC+ z{ghIYrM;K5B1`9d^Qz+IY|5g|KxPQF@^u$dqO}>6pSb1PppapGxK|2#=T<3fp^(a~ zI;8bKGx*bw{G~J~orb{C3$bn}i?G(aTnLmlWKyD}LhCttRxz(;G_A#}9Iry!a2c{b zzz1O1Pu<$klx4Xz+hw|hw|MKZULZx+Zr97unY2?+<3TEc)_OgC-2LSt*kSqxBU*|~ zFv$~&%q&&T{jC0`nwi`OF1t28o!F`^NyUPrvE#{M#-pPV`;&si=np!`diV*>dm8Jp ze${~aW)c^Iu$o!o(;5Nj-HCpnnvw#dXkeUW98;oj6 z`}A@q$umu!hV>fVbtGE*to6V8jYezT&3Y0hMZ>(TIiEM2FKVV`LunftTVq`U!r*1! z?daX=yZeqgeee#yCT>-XbfbviY}7h|b$(e3yekN?e$5S4(upyo=A7i^BB-QWhqc)% zCEaCVwyZ3MKzYGfc<@=yUV8r5Q^Ic97+~A?Z|?X6q*NqXNE0e0(bEO9s-&_G=fk?N zmme<`^WIZ8EmdQeBGc~B;d&94cb(xzcYQT|h9wMWj0yLt+_+aSS2?HMvt!+9Vpj)@ zyT)bLbGR28q_43y(Z!VW`yT7H6m%beLrX8oQZs*zJG|0kSga`VX@f8u zL$)i}jLQTJ-uFfCeOZQBmP>3Kt#3QPs~_o7a(#N)HQ*YQZ&0Epl`XmPT|J%->1Cry zj6!u~25+BvZo5pn@{3erjA2w*4y%UQqTzH_bGE3MH=5d|opVys4Z9`76vuF+yz(p+ zt9@cH%h}w5;cVj`5xPEw2W0EQJ+eFDcVkNjhh9p#R7sEWgyO|H&t5G!ty)@N;MJ>8!RIb=~4r;yr$n% zCGDKYTHiHmQ0u=VKqwz>L4q>6-Be_I2Q4JVFQ0#5{O!QoF6G>*oQutr^Lje`zTJ~o z&aw$hKhs^Et`K}{l$$d)6;BQgpFNy#xIbDR^PUem&TA@Y=RA!IDQF>=^TF%g_vQaB zPE>f)BJ>rTZ>$~baCCigE-XZdy517{n&Z4jUoHROE7mo6lgR)_|u$-4+ zv|n07+a`FGB2^cRSqXcrb+m2hhYaAIr)?Ts)8cKI35J?S9sIKI^9?S#0PLZ4>%r%G zho>Kpl#(<}I8+2Dp2 z4SEH%4*^&UNG~VH)z*vhAj?_4c%#$Pu%W{BW zdfBxIS_}e9bFdByo6D5vLjL)kX8ZGsafSQ(1Y2C-@^^Rnq$n+d!NLD@H+ zN?CLxPy)u8r$`0zV>?FeFam)W0_)cMLce*4v^y+Q(tBZ0mY6BYtCAPzCG*D7`V3TO z+_5Ye-}Rxz#~qJh21iOolIERCdWsT*lr$O06u2m6dV3HaR&dDodY*<}-)`WX={s-X zmPA=b7gWyc?;Qj0`_l*CKFbh{HA-?_@nFm{wrF+TW+}H!w?yH3K?`>y@WN{5CZ%Ll8FO=Asj56{87C8_aCR`MjiTZ7|S~TT;>=@ELDo*|^@Xnlbe2y-KuX z+A+=*lRP0!S1IQ=)d@%5fj;=YN#(qea=xnj;(`%}UwX9MtOD8NK(-(+@mc#w*2)v` zG_Iy>rz~8>DW|-0uV|{T82j%r$-hsQPJ(jSHCR_++ZtPk8$tR8BO6j>$rBi*k~~Yv z6SZ8^?VYJaX9+m8yz{*)jO% zhuCsKtj*Ly@YgClh>Zy|@=4J$FPpBOc*?w%%o>TUCDt08$`LZbd57~ZDAi?ePg;jT z)6HEaw?r5;x&Dyev4`C7y6;ocM^cg)O_9xb_NwH?^qkV>_--~V)+T!QPwBpGjXDHj zO(uejdyg|0a6QqB*LCX9;gLJPsGL~p*Z zx+ZS+qEpSOO*`jLJ64_~sGZ~TEb z?&6zo)IP1Eq(p0p^Nzz=%gMY&J56J2%DSYq8Y{-D9?_ow>(wX0o#?JV@-~BTnkF16 zNn%u&lCF3;owBf5r;=VTp?Qxchj)^t|5R5|kY+_tNt*>`wqRPF)3h1BQ%SD^VQ2gL z#-Ql8eR5I!sDQugC#hLHh+2%sH(g6iyjZBmrPdrbL3LYMfn2ZJ~ zXT-JUz4XVw#T6Z>!QVIeiOZ=?cS3|MF_er_7!@g62*$Z*Z=@NIQj9U($?JZ7FvGnt z0}kJK_ea%oJ$K`^k31}wsU(MXec_=aJ9n*wEYk>4&^l1FId-qJLT9C=i`vC|^{xkkZA(La>&{SLpD%lAE4g4= zmBAalOV`th*M`5pmE|L6xMtG_UyJk&O1jX`TWZpzZ*M5q2hw-^c;7U`42Kt?ssmRe zeMw>JrONr?(U?(@A?0AOBd)I+2i5}c(Dq)3jlf&iySr8Zw-v ztjvt=hYQ%IQAIHB$a$<4S=VRyo0F2$%F#HF7pCj9b(gO0k3BxCfTwjrF;-|}(9jn<~g&FXzoNyt)ON5hnCxYGI^?xW>fv-Jo>hP~XoJv%qQMo}X zjgT^wWL=sXzNW3b#;5x>RqNV?>euEr2oa15gp_w{WO0S`Grs#8e1_L?nj{<@^eX8o zU%y=N;=G}BIi5V&ShBHh`jNeKca7DW?jTSKfs%?e%aKZvm^tUOl4%**8`7(!-(c}N zoWTY~yx^-furok?m}2hOz2C7up9VEI1yhoF}8uQ~f$r&TnHa z0E^I=E39#;-E+*@y`vw9fI)VVy-di+2ug z(17s5k-vs(!VlI$mLDKiX?gD)&RK9an8>s8^>yAOeP6+S*XM$lF%Zy&s>~bkg}Z&$ zQ__;uD6%A^q|a-Ib;CZo0Y6Y_-PhyO@1qooG|56bT1m88FfB_eYq35DmEtc`Ne>4s zzD4>LC2Z*bn`pF2R;D)Yz8=ZzXKirUH^;Cw%9o5y&GA_9q+9PT^6OPOzm4?(EId-& zhS7jPc!jVUtPGZGYGWg=&nd@qiXSYMJ`-7hS?qzkD~ zIyh*Z&nrsnXsrwD!rO`&JU~b}2QL9jViZY|p!6#J>F@Qx_IlXr_0KBhY`T>5lLO6X z4_7JY3+6>P%*7e7T-ih36hUpK5KcoYS9PV=F)+%&>q%wj0Tw|=uv_3IkKKIHgLQz*gw!{9V{h_EPW3n_IKZV z=RK_xOl`uc+vnH*`}`xHF{2>!6;IrAz7+q=WATC-h4mjZE*XsEZA(3Ujy?G`V){== zJH^WspFSc>KIh5)1H4Q@2-5u~X`3P_D!`J&##2k#ImI!}FZ_e+u92hla% z*qan+ElG_gd$r*C*@9`^()t{f30~5J4la&gXp)D<(;X6vLEsg{^A5)p(zR zPzdj!6Ivx&hV@=!5K>)mw2Hi)OG_(7&=7gspj=2fKiHEzIm$Uc95K4(l=CJVDQJO~ z0wH?S`D?Z~TGMVQgioPWU|ACbUBwn`^>Gy;tr&u=ArlEoCG2Gxj}8lt9_(R^fi5#3 zuK3|AgaB1AlaKg&_e1{5KIK2lKjPQwOXjj5^%bAlulR-gbN-OOW8b7$bAVJIP(8Mi z@#37NoxQ+6|1Tsj{y${%zr(m0R-{zP=cvP9l0W=6nEmgeOvd?CQ`Me%t&t`n&$G22 z!S|V7fF-3ziIpJlJ}9Bz#(GLxG3rv%S*l6RIp3btoK~LNc71e(ycfatO~(V)OAnXr z4U?2Y>!6Z8pW^I-vaG0Di&qXIJx01^%2{g@gpKrBsoUPWyH77{!_^pHvX^x!=Lh4E z#YxOs=eAwAR@cgqq!1V-koZn;(@$)!FA%Q^-!;moh(_a^4fmZZ`e@O${98R%yIMcd z8EbU^S5l%?XhEp8+Q`O#oY-VFa`Q-~P~)eZO#UUmX@9`~t9{B}Ctq@Ej&UM1g7~`q zoLBW@PWd5!G!ZiqVVzz`^{#GV-rc(&CYn%~zb9oO7yD z$oElcfzcYH6-u%+?f6vi-XrlCN$~d`-oS%ndSBUei%N_M>t{wY%4dB2vgG;Ml*;CK zmEloK)#-3X{IL(aU7A&I@3q_Y(pp`@k7uq6)T^#)X zinn_31QSA{e1@!2Y%PNy>Sme4RUfr}seAK+7sH3@`dsHKH$g~+89(G~@^k)ban4^i zM?5zNIF-;J?@DF-Mi>f?_-rD0GM_ur66 zx7>Z>DqQt9RHqLp_kKj19nyP)_eB}2&;0~C=6Hv|q9t8+=pOIuJJ747_r@~xoHjbB zq|X+dS1ql`K_$x@WnFE*dXEob%}`@QkZ$5F!=lE*~GRunxfiyX@@; z$?EY!GE*a-3&pt+xMYk{W;Kz2+h%QCxYjoK#kVAj-%$A1m_GP+@1-Q<_Kc$X2Nu)c z;r4%skfXKW8xF`VnWx-19*M(9kCp;?RYv@Gj0?scN>LQSvM)pmsz@G=RD z=2v*%^bcF-9L~8N3P^*Qgm?IMfoRXkuWD*{PSrG6TY=1irE5Ph-h8hvptPc; zX*_kUP->U<_aePD?@bL*hizqrtw}`5B(HhAr+E4>v=2;@^>Vpg96YZDVA-t!OW~JA z;MaS~`zL=eIglbjH3e;z;F}7suP0UD2VZOk-kUf@!x}Z`J*D-`9oS(J|8he-7Qq6+ z+8x(8E;sMrgaHYhH9}J%%O^m)>AYTuyBTUMOtqshgHX-EdZ& zGHps4Lb_foy@%HyOj-)?j;3jLHjwlg32SZFNBQc@HHU-Y{<-M}D(8p$k|#$Yc`XO_z55psnXfZ-nBkcSHzt@B;)|%Yq3btl2+grUL zF8SBhvVL&}K~rHA69u~M20c=C!8Tk(2G3YJ#zta3_<_>}d8xrnXw4yQYeH$!Q0(Tx zlF+Dqe0qpf*`Pth&DMwS1U|HZOuAmrk&aFiu&$EsQ__Z1pYzR0&1vbVYz8vL^YJNZ z=NxU@;+(tDl;@@R7JNl2N+xN=(HM>iFsg}#?i(RH47+Gttbe6th<=ojxT5uH!75jO^;{(l;2V)NRMkK~`tzo-g+wtQD z!xVHE+l-PJ1xh#?7aX9jcRyBg9w8)JWT<+Km}mH^32kWmQq$}B_`#y4?<4OudkzjS zQmqt6ndUpW;y33l3#V{Ghj7_hK2Ai-XU6e3Psxpj_Z*N6ZwaLgHh)B2e964}D-t^+ z^=;U956%k~;(&Sj0~mddN(!7?PKNJ&0(zNWSa!*>DCJ3X=!Wyj4M5()n^e+8cHX6= zEeq#@aR+MUg}l6s-%n>Dgg{D(*828lz~1A1i|`GpUT~PVJls#&A7`Y=YP;6NXWhT| z_F4`m6)(;jUd`%o&#NR1jyEO(yS~oh-}BtP&wH+3SQ%>wSCV!q=g*Ea9vx2@75OUV zd16c2Dund5KE}hL+s%n za#H>?%xWg?TQm(G$$|-|*-xns{unj>4$7poRlSjgxc{sgFj%y(WF}daU)`Y_{HEz= zrIT@ZD5i-ad%577lNslAgOx={yKV&TcV*SROWfKTUkC;@+Rqu8lA{qEPckN>^iq4n zzP%yPrD_#PQj;Y$uciym8%N^`gi1G5(z}Zg0_WT{or6I$jNZ$+Q#n7{S3Efyadc30 zDrd=ET@G4zbPxiiC8-e@;aFe?Dd?-T#kd?H1ey`1-p5W)@#6(vUt=elr4UOXZngvC z(qnd<8ooTpnKv!jNy9(YC8ZZ=0S}Gm=M%%v4|5LlbUh9Fz8l+{2Bc#+{0U`q&MTF% zSo}TO&G0D7*aQB+oq)@WtS<~A4`l97*(OC6=#*BZY^G=AT&bsYnekE%)1$A-sxx$_S1I<-8mO( zdqv4!-iDO(@rZ-{5$PRJIlqk!FKAFgl4?n!T10F6#QW+8t{s6A8K&K*J{#lqDtuxQ zS}fP8uj4a^3&VXK-u3UQ=!7JKqdemmj|30W8NWL(nKqV02_6>--`UT3FwQYbEq|vk zV|u@j>wj0Fi(`2FuPC#}%+CH9U!NhQL5x2mIrss|_z_a~^~gg*mivtuXv{qhg(dA$ z(EZ@&?%n1$$7UclMssv9AxjgA{G6{|EO>F=QaXz#l;fnmJCj~6~v)7M$0ig`ZbRa2Q)FZoh4n`5^b_9p2U`H)m{0jz^xONxC)VysVDj zxJS3UXN8n~ni>w3z-UQo8eUFAy1sP{STm`(p<0ZgD3eb3V@pyNOtNN` za?aDWS=h%Ot5r%`VN^-drKBtCa6TQVq{Y%Fe?2R8N3YN2=8I*P0aue!v0nt0^W&ot z2YVyZ^zNseH@V>IFN6rAR3kC6#o~r%`+68yPWE3)p)r0;vUossTH*2&{KO&DDtdlY zLV6HL`nBJizLZyXlKr;$RlM8M_+dGF{fN)o+)LjNX2kj&SFC<%kf86<1@}7mc01=i z(l=zvlP4N=4{r7wXK=kPRnm#!=x{=s8H)6ruU;;AIkS|`;Y7M@Z@3cRti9E>uyrlj z`(S|K7NlavVb=0s-*C{C7)iNN*UZ}k!shq;&s|SRrx>Hi(~|VG;nnP%g|k?4kY@e4 za7SbBdWye0&(7gpi*O<3d_3|zJCj&*w(;(84&xF^Ng{sIG%*s-bs-RQqEoYxS|hGbw+&PUvytBA+?cx+{kb)#%_+PUu4 z*7rY;t8%9MbsKCP>rMa?)_(dr7c2Tw8nm_`7pkkKz9H#2C~>Vzk8Q3Nx)aD;;Iq;#9U_+;MkU z4c%8Mes3!hQLt;IW9QZTlaFlYxTYF%EcM52nQ$Cig7A=SvIt;4NbRijMYIG zLXr4=+@i+5Dskon_ANrMYKDBbF7iR=XCUwvw;WkEKl=J_u!};G+q-H^SR`Y5eOidgaUK)gucWXf0 zZLISSI%ADYEI1ljK6{Y!_;|1Lavn75yN7|d=RyGX2!se_7o${Rq^0uhTKlK#WtdJ0 ze<>1De}tPglrJq_p5gZ`Lb6O-!=}CLJG$!hosfJV^kZ}E3-ltaW%~I}-SY3ei_45> zxBgpbPmw5;lHEGyz1!{Eqo3J$&{{Jd1t0o6HH==)d3G}AylQBdDd{T;!hXX`U4)b~ zLzQzUv>F#l$bM|B_uk~dScs64KH3wcCKz|TIG=J}H#EIUTF6z#Zio6NZ?&cD20J0; zJZEfbo*ZhP9)}J_S(bcK{l>Sh0ec_ZT8c!G>xM;RyLDi-5(?eqi4_7xMrI%2&su8b zapD{?wuDkSv8>g5-|Y%!>UY;k<;J<6@weNz?&0h$nubv#$P&diL0shH87{L(sg`0J zqgN{FlliPmNoPo7h6*NeoI! zbeED&&Z~ifd?O{jL#?{jdN|W%mpWsO{i5aZLBiwXmCAYZc-(ikt^s>O=a<}QMhTp^ zEtRu)xw!^%JqKtrE#o_5a!oL91_r4qNzNKx&DK-WAlKSO-Zsm@ zYj0%YD>7MfJaRle&O-aZQFgC|R&U~B3c43b2ti^rd#U7g*;3jXycwi?Z|)$i+UF_^ zV`!ctP83!94bGk+_F6C2qr#v85nwi}kMuk3v~r~f@zJ9hUh2oKVd-aE8! z86}<~HRx{E^(j3RZi8WooYsoTC=2B{Swit*$~UiPoHs4rO7O1#rS7*c6zpwDfBMee zaHVqAZpO%zJQxd(yOgsrdM(|3Tct1SB~hz6yzElahkJs=C^A#?@;s=d8($#0u2b7Q zsMn9#&9GFm+ZyFNmGi#h>4OP}`y=u+Su@u7)b6v(b2=h4X4uOU@>#`sQ{jCc($I(- zRzwdsOJV#N8sJP)TaB$x@%t5`08}TG=`Y%~;qMlci9sRwPzAmEfe38W0pC+XimX9X zGf5?Ra*N$|K2iExR4PT0OSF>p_Q~wY<@!#E3D% zD#W>_ZZvIuf<{xNYOz5q_Je@~3@KY_d$!3lGk3E9tu*c#m*3sj8Xe znnZ_@`KLB2zdZ)!g-@mz~hV?KighZw=m!&>0gSU48pg&k&df&LXXGXs zK9rSGj7J&9XuNBfoxkSU>ocm>;l*Uo-f)ZmGTorj)o2&m2Of`ErkoR_wkoW5Ehr3) zieNDHk&+}a9PUXHQwi|S(%!yHIZrxcji(Pr9PAZjX>w&2 zp7(+6D(LS2LI{+UOftu@p~8No)3` zz-U2YDqc<-P8R2sw#CaFKTt_u)&6a3LgBjF-c*zvjvS8D$*gSRev z2mwWE*vlGT%xg;5cIykbc_4@BB2dyG#U9${)blZQc|tos!4~JZqQd1ZBpzW1Ys3l= z9^ZnuEWNHpH$uGm)so$3bzJV&!|5%1wcH=?9nx2fQp;XpFgnhDcZ2oJS4g`iJlty- zRgROzg44=U+7{TZq3hI@)l<_~sQBfi$lC_#JR{RARn8BOCZCkC#{2Td0K8m>F^0WNGf7J7 zy2iSs6D-_>Vd6T&ZYkYXc47mG5(%j|MEeo8JfNwjG-qeD`W%;(xU5B_7LhtI9^ZO= zDG)BM0l$gT@0&A2*#P=sAxE=E38XEX>RjD zJghlisUQVXXrxytm!SO!)9hp01-2@2vkIqbysB}k!CQ+c6OnSKA9vyS)gbqMw{0j|)e`n{0p4O3q1nZv$#F94 zv^-+HQsjL;r;}JaXKAY`nJn4g&-uZ_$2@(s$KE(!^Ky=C=dCH|eg=>whQlJ^`E)_u z)Hs(SJ7bR9o+Yfx4^|eIQYoa*QDk_(hxZoS)VQj~(%^iJ_ZES|=sl!Rtc$Sj`YiA2 zxlbwRFr(^4It_-B{fut*tCl}=--aA_ow{u~oz=WJt3fJ^);MoaTB2KvXy$k;k;%`kF%3>=y}nI&3%B{dBw-b^`AlRo!x438sDzB@5cFNsLz>V=SZ0 z(zXtxCE94LlDKXlWv#`?mWh$<9~^SHKi;aI{!pBCET%6wo&E!M`VG?8@3(*6q?8|h{dw<0=3r6r;$*?I*A=IwpcN)`of7XkWAE12mA4eqGd2mif}_2h zB44>$-PaCASIHY^z=EzfZ5N1Bqc|QXoK_80Rf11eB|h7lTHhF*iH5lR+d>Eg8^W4F z9I>vwh3&pOh;AM3uHR0pl-_Fgn~0jj9448;Y?v{`=g02gyvJHk;|x~k$aEiXf)>RC z%6l^B!o)!eq?F6zIRSWUaej^$HA*L>X?k^{Bq6YEOMNy+zy1>@r~j3l(+k!?|cXxM!y9IZ52n2U`hv4oK zU~ou+ySw|~?(QywCU?#`@ApT1_qo6AXV|mZ-L^bgQ%So4a-@C}AIeG?vUp@GEd{L%?=rEIL*^GxtN!aTT&C4S6hFM?zp%P?dM;?FW3GBb zezhoBm3)&zZ&J?K?Ku*$Dp7sh^q;F#t}{w`y6Ilm{vy=`O@<3who4EbYUyImri_C| z%cG5590Ec~k#jhvV!K9Ou7AFowHO?6 zn(l>gzd75?{rC*BD|>GQXGvJ?_(+NB%{QryK{fj-Xmz(%FRw5;UO~H{>TNEsfY1yr zsJ%lYKy>&oVy6mU^OLdhW+gJ`|dNj)z=d0 z=)Mj#4Lcdg>&{*_YzvEFXWhomJl5Y6DNDAU`cCVfydf?vPN9Fdd(?9(_N&VaSlz>1 zPB5xtutD3YN-`5p&NH6y*E1r1@yj!TFX0>u-j-yUE0rYaH(l2E_pZBa~xGn zz}!BCE=%jcW!;37>#NUS+0S2IX6pM{J1RDCz)~OUPVFF;H5NW%p9E=!)m}0LI#27d;Kx#wl z<7={mPez~o7Uz~Qe@`&|E!VBv`c}joy|RgUJiEN|H!kYA5C_JjW`9e~?xW9om6jg| zmAA9%&5ku%6lgN?4#>GP#TAMjqGs#OC-;LJ#iI#)?BlLW@CRrpz~4W@^&mC4^J8Py zW5o3e~28^BZF93X0?~>*)8Z`UC~_(*1>L4BUBMTMyS^Xd$cm+l_D6B~Wx@ zu%3dXtL1@i8aMoTQ;2JGF9fuskBLkC6D5%rLCPw<<$l=;I*QaoN5VU>1vvj4rmYl0 z5Q!WiAEFwccI5sSmyg03s;Q-crAf57ne_PUBv~LdndYJJS5}4iqdq>1*|ddum~@Q^ zP4{o@?!Q{ia{N*&l@ASDcbAAh?~u%~tSH!$#)J8!QcSCtI$!^G*=>X~Ik#Z+4T#yQ z(n9ZC6*$WKEC~vE3ZPfqtaLQ2wHEs~qQs@8$bqqv;+)oO-P5~zqzt>=(bU8ntDB*{ zku0-aOH=8!!zf*TV1gmAUm`t3H)1%rJUdX9^jdCiyUxP?zO^>J^@O?swdDsZ z#I=6HuJ6Jp|Jy*}vHhrI(fgNJnV?t7-s|-tvQ=-#RZf?>FkHu28q7%Bp?8XU$=En+ zr(0*cUFeVsR?kz9;6RRhtY9PS`t|om#Iq)=piT>s>_mAnwB=BZV*b36w5gD%%7aPy zFnZ&v8pe(I2HZ%m^%I3;Pi_0%mX(Osj6qgDMO#uO%%_ZUtJx1c754+e(-Gu#E*!z( zoa=LiZak;_#J$kmZr0yLr3JFciBH5$Ro2sZ%$1O{M0sA9(M$ehUN;vkzj_5*9alq9~&hbLdd;1lCR?nboL zBhl*a?kP({_tm}^NcB;HdaH0FMA-1o92xD2qh8n59prQU^c~8p+hEQ7xX?8sT;;ca z$Rj2VbD1^0xfJCZ_wIbWQ5GdKW~Ce7I_yV6!>)lkWx5!n+Ze}GwFvYTDj9KbB%K)_ zk+!-kAF!5GU+31J;x~qD6XT06(BJDotd-%s^@C+i$vnSyGwaQ9W^*)h*YF37Uk}o}@YD&qvG3m$i$^As(8`J?L+_d+V4K#G}Z`7lpA< z?i}K$9v!<)EiwM+I?MJcT3t12F#~Eb9;C-aM%pH{8;K>a!)XK#dU+)JHnnU`(iF$?^W4ovo4y}YqAl3#4o z#?<8MkV%(W>K}q1jlonWF4p%?K_)??`BC||cK0x>Ll{l6vSmIyMt2e*(0lR+Qs7n4 zK%KWz?BGkG$O~ahW5ub%IfLU9GW%abt$cDr1n*8oXG=5#;o(Hl$h}YMboQ1wo=5D? zaBXuCor*G0WoqCvs!D?$WjiCSnKj6?PZVCjYFDpjb6#)*+3*#L**ROWDZkk%f98H| zY*%1$=i#lom##dpTOA=8H6}hIz48B5`x7I|*)z@i%1}C4CySl10etberhvvny;PoDa zoglHh9PfhBNr@#$yvz6nN03S>HNKU8Ng{A0=?Mr#C>d&^Y0eYduRBDzT)jrWubH`I zN~=KUBaYF=T{)m|d?%6ogPvt8dDO1=pk;(k$^b1O+AI2QmNy~s=c)2YGz0CK^PYxv zQi3pRuS2f`Ni&-}f*o!YWp zfKYb)hZM9`m{qu*ZEI;0R-#3~L4c8;qBD>V4CY0sLgGfFB}l*o8*bTzmRYkMbMiry zEbue~RjS3AYAsj&uqrPOm-U&&5}>xsST1HtBw>M3TVq)dW2cTClwn7>GK8V&P&rH{SU3z)2m8jM?v0%7~)j1Z!!58|Bvy&32T^($P&})a+ zfR0_Zn+!pZ@r#=dg$uWni~KrIZ-j27x5$wjs@o#N)+*MWCj9Ho?^>Z%1wLYnI;AyX zNpKDi8;)v-9?E9g`1bf<@oy;m-!G=)f9RG2r~SliWB}aTJL$XLU@DYcwIhEi78e2q zn~ici=*KC8f7P^4DNWT3{4R#w>DppX)m$gGpT7fitbe}y-yd8`9VrFp=;gll2D{~0 z?jOXLc<^nQ>`!(V-3opPLc_}|M>JFK248*Qv#6!F6OYHCZY=3a{y>gn4eSfg6iMc4 zbuzOwu>>=Fr%=KUowZo4%?8ymg?CUvV~hFbriyxnm#OyykbZSTEv`ajyO4YlyS@lzw1>eWABFkd5mzfWkl z;VaVz8YEtJ_q-q#>99r3Y!yg3ZwVM>a(mdZ3PIG|5k3L;vk|vHCv_YC9Ate9EB!NI z5XR!tJp2~NWKDB3=63lBUt3HUUTg`*ghp&E0`H#R4SYn0WXKP@$Gol7#B;>4TpvG> z?Ck%wW}ZkWB76MY0Lm!;(h+F<#z7V9%pC#qCO1^92H(9;DK(aadyi}z;Pkd5RUK9c z*9Dr&iPfkEdb|xhrq<~@0v5dzpF+B zda&`09(UL`BuKAW_$FS-yMm6z z-<_+>--4?^nyn`9V$`3tHlbf=;_vO`s@IZsZX$8HQ3XOYNai?ZbMS7r;>$BX zh}L@*WVIR>)U+aPlkewmc8GVfl+~eht~kF-34}BX#>PE8diEtG&ToyV7J)2D!l#(2 zw8-jkIJIidAx$Tx`7$9g?=C#BaVUd?Aa0m4vUcRX__ye5w;XaG*>rqqK}QhFH%|G6 zZ}5$2=0Eq=ZN|>)3mXYeh|5xL8VpCWbDpdc(5^lDS@4$X!)|nf?pZeDT6dC;a={8A zhevT*L!lT#0BT}v0=;^}DZ=UPfS)-OzHqHmPKI#~B#?;@q`Mv1*Eq|y5y7A38ckV~ zFK`H=GpO6C`JKECfmsF$=NzgC>c2~$k71iD-+~sFzZKw_c$8ug z6!~0-uvS&b>eXg07~UwYGP%05HWN1D#BF%>Bdg29F!mvZl6eZPbV9>ws9w`3mJ`Y!Y)DH^#^P^h2I;O4%3kb#ETb8Vov(_cV3I65g9;T-A<@2G1BDHAS6CvOR2Mq z)I56%>{piA*niI?Frp7jftM(3CDl zMqR*{&L2)2*(6~ZHy+)~^=0m-^cXHI7|j)BOqc!1TFfM{x%Mt0`IexOr;LbMrG4#% zVyg+>4T7r>y8DnN|lvN?^HI>l-_Tl?M`W%BqK!umE^tu z2Do zu4lP=hE-V=4zxu(U*{-(FMgUjdHXS@kv0aaL{x3sQBY&2u72n3GmFWq$hvwK`3rdm9 zA0~a8PbEnF@dV>Y@LP&9X)<*Lr2?C@nFD&?kl)QmTRQfGRR5{AJUfu4Ozj|=k{74u zh}+6T!NyLXXo)3kp@QIc%@AZ_wwfNe4~z8mn*2jO*xL%GWc#(|k;@HT7e>o6)Ey`K zHvtU_T-Nb#wu?mdJ8Fc-u37;9Akm+BsT^##8yLqYnMu5$*y_KYUD!6{8;@V4l=a@x z6aFN*-{F@I6knHD7qhXSD8xeV3muM(_yIIop1>^wIBUEY8Ev7J;Y&az{ce@SqAbvV zk7j@53;j?n8EZ->L)mT^<(S<6by1dY_INFu*F&D4pWLpI<`ldGV>rPcd%!t4kWbZp z4`-g(6FW9M@mZtmu{N>%1Z@voAXCd_voDBWwMxctH&~mg)0wB$nLW*4!)Tjh7C^WZ zSaM-0;X2j2AMkn2!H#q<X8F}Z}~kb=7Iy9g%~?w=>A6nv`4Dz^X-$D^)|W7MDKZL5eEPKgF^OxP`u9rQi?wr zgZT--gJfCx*zd->W+(9$A0d*}^4(I~ZBAYvns7S#>D{^V$4xWQ1~ORN)O7Og=|a9k;@FrYD62 zy0y%;Y$gWCB{#6N5}q<)G9qreCMlrag~>V6tB20ES6pt^v#_58-cg^zll~#KxbJae z#XIXAWWtt@kZ78s)V^cyVq`+h-odsxB7 zC-4?;t0Jj{;dFoL7Ubl(J&bIE|KroszpLa55x$ zu-7=0jZk}wU4ck|y zOmlFe;#S2(ZB3bLxK%z}1a?^w5qZ{BQ#B zMQT*JcX9Cup?4xyJmh)u+lUvh`7it1E(CGbBK<&z%%HFqdP2to6fz$yad|}%>8v>WYlP-1aYQYfG-b7)b~Ehs0i8>i7^bn!k_E7+ zes-pp@qs!;Imn1(57qR)7!K%+>R3WUGr)kI=FqkKEoZg$+TeQ zePeTJWzNm7x`iq*e|rtl7Vj0K1r>nDhejH?#O*^l!)WA;hi=kE&l|I3U@Iy$##XMw z;k`nO83$P`F6?EAt!Fx#;vA@HmFHp-UC2okCB}PK=zX0T{k86^vMZkHm6D;E0Z9fc z!Rq#~N03WaVjsumQ+%S=@nXaLr&g~y?jMqRJFmr#}-Ry^)+$sE8kAn zFI!t+w$I5vfnG5$KK?OPzdqsUcU1}ay80;dCjVL+P68;01L>98sn}&h^X1ltPu{7E zT}{b9pUy?8!^Ouv#2T;FwSoKquTgE|{S}{FAhjZsQU>)zN{K@Qa?j5g%NOzu9;5_G zkqll#nOnlx3l0!11YGlD9dV#vF~i_YzbnIY`(;3@U?nYHh2nsPN8ha&ezYXz`9=do zCvd50|L_}84J#4yV0ba_z328azCBg4?7`*N8qg}LYuhO66GULplHtJKY^)?@ve&WE zbTF&gy6^2yM@yHFR|MZ|Josa@D0*Cx4$yq}Hrh(W52i{U&7~AMpaO;ea}7pL8;mJL0vJ=W2e?uH zJRf{%K>p7wfiE4u|KEF48)YZR``XEmlhO-1V4VmZJaACF2|6y>9axnPYfoZ}p?=~& zcO#P{a}GzJs2TVxd@W3YyIX_rd@cI#+>YX4sL#x-Wi;Ek0K2XQAs`uO^z9n8+0nPn z{+rZ9bH4i~psOob9MfKTF(UZ2nqt9g?08ZZER=})G;Cev=m(-)mi*U;UBg$F?q1!2 z*G7|ix}oSPUWN!y-p(2QjSz~`KFGZwu%-VA9`fkHBLX9x^#Gl0`74S8K@m%-7RL)h zdke{9N*z%zw|bcz|TS5f7CYBi!;KSoR~v+#n_kz3QU-*SKwn{m`v%`sC*5 z8VC&A{1ATEeG1T+6k7q8e6GCz0!^|yJAU-#v;2_*ENS;&Ch0vtIrsh;Fg)z`sSN9i z%9grlf&aqEYWae!MM-zNF+LNR6t3&nV7NA|oBw`0NbnDc=P%S%LqKTV*X?K>&G{Y8 z!d}UIP+-7$#dPm}ce{cD{H!KB76!t|RPIRgH~#DdY)zWIjLcq|)q*>Wzq+A^-bViC z4V(`))8*w5Grk~F6AL}H&$tWeMa|seZ6N1tKe zIkNsM!!9t&T@mCNQm9SpbXB!*l;$^{XdQOS$|KsVt=GabV0X7%Jn5mm6I)Qmc^0%3 z+UReA^%We}*TPEkNk18e@k`<=vaconnbQNHaoq07NmM8%C{3oBom~Hd| zgLoDw=Tl3{f<>HkUe||kJ(o!)6x){+YHTSCs2e}bfBl)$8cb6kG1qHuI8TVJH+?Us zWD+Y!E}IlY!|nvNYNxyaZguN>g1+RHwsa{tNil>k3H*q>SSzrO{GaECp&RCibTxch z@e@m-#=pE-BQFW;fruOMR!Xt1=c1WV_w;~8cDV$Z{p-ma2s~sD9nU+UEhmpY-+Tz> zjEoG^n~rNoD}pw`!LR_ZhkyMvfzU>Vjp8%ip}g=$5b(|Ypol!^y?(R z2kkX--@%$93V=gGHF2WV>EJD}VdqNcyP?rz{8ya+xx(J9_p!^8N!`R!$n`_V)_&!X zPvm)3qbYBRpTd8DqzNml0LQ2=u@Or^3~T7ZvJepIIkAHsM(`3M&0>9K?MSGdYQ2~o zmc|MQ@E_U{)#N$Guo9$c?kzuwd)_Y2bFnnkm*g#zL(3(r9xzBpl3(5ykVsMDAHvdD z06w<<=XXq!OjF=o=bWTQ3o5$z^$%7?qg-vxQVAQVtzzq}l9>I_G|Fjoamc&{dfHUt zDjasm?Qj2iER!U|*dOyj@3h^@VjF{>_bKHzb=2^wDdk*~o>Jjhq*XX?`)O(zmILYx zY3hbw5;k=H_q_r~lX7Y2g##ssvFR4pOEiVbs)8IK4 z;&=3M=A)gSTiMvj!}@m#;14~pbKdpqQXM$`ZR+{;Fa%FS?36>5U;Wfk%B%E;G>tA3 ze-+GQMND~?+G0jzBt`rtFF$-fRT0}O>A!vj#=t*%-n$q6z~$-bmsgJg8yjnj?=!Fz zi)WEiIz9()kOl>P8tp@95n?Yj^DeGPcW{vYkAj8^R8Cy#op{@&zY zZFAumY)W9&+!;>!?|qf^4Dv+WFXA~d%}l3mNT~k{{Jp+t-;Osp4&NVReb|<)kpS`- z{p2Oat<`U8lx2=n`2Kid9gim1;y)Xq_Y+>%V^;TY@`Z_SZ=A*ReubvFw{W}gbk6@b z7O15m^}OaLK<>29AK!lj$5^dG!j;4hqe|{3>`te(aZ;zzA@g6%<$N%07?EuBYo`-Z1@w z#y$nPQ{-vj5py}e#p2z=ce9`rR;{_@O#&K+`3)23oq20t6;b|7_$eB)z(IulM`4XLAq`mK5|T@MJ^+#SWq{>+U}zV zkwGFR%ope8GQc$O*#FITn778x2x$Jx6$sW8Q03nq-fYqTmeHrst|73+e6Z)hi z@vB65_{DHNP_yH%UQwT(GxXYakPTh7K*DI5N-kv&1V4KiCWYSZJ#QscLEo9db3%Kl(c_ z=8LK}C~HJOrtP=)t?#hTw3SePf8|u@xE^8u2X5=w!#&TSbIDe06$AzK?=)?CBORK> z`;?cxM-Cdp1Dh5{5{#h^FcWBQ3~AHDfTM`yQ6I5Qd;J=^vih6HP>WRL~t zp}oPxsyle-mSC00qs6c4?bxi5!-NLy=$n=h>#~_FoD-DzUVL;}&6s}L>P?(S78Aw$ z7=HVv#a$-IgDrB%y@KL)ELQU{tjbKd@$ki~pLVrf@K5=+6xj4rfAV4ngL`2KV6IvK z+%!D~PG0~{M!@G+t*J3_GmF_a{jt)>dxvS?77kenFV?UEMrd)HPG;T4m{;%`DlF|` z-)yAM$l3`X?xsZr{EtE!5>7jh4i(uPFab#vBq(3-FA=Xt&BJF|;QUykmko&;NPNh@ zV&yQrymj{^pPR58+LOfA?;Vb%Z3hVM5AjbrB+L_t+kUZsblw`Wb6U4w0{InaRGw?h zfmKHw!EzDFRs`}xPZ2F+%CI|&QTGGseb>`ZX-@fPx67>*0cKZAV*6ZHD2h4!I5~=$KEaHt3ej`uI(4X zVK-5wwI+|TkbfhlAFm(g4$Fh;j*8~D+0v`{U98f64xY1RJXVdQg%nM>eC`vB^g>-G zYlt^)B_NIzR%G?ttmz{3O_gVG26_ZBFEuqfbS%w3^jG)XO1|*^9hDy80k=ND`f(^z zoj2u2UIMUF28xfrte$72a+Cn1ez{%+IW1dtt*|jK_mP0yp9~()5ti5+rTO z2px;!x>TPd^~d(w!WYB~j)c~7hW}jghg@QdiW(#=#A-Jt*D99Nj1q*t;1POm*<-@F zVL@T_G7Tc2uGDrkuKP_7{=IT6TZ@p+Xf66q{T@~$?66-}Wo|?WJVs1JVw61|VC$=a zMH=|7NM`=QHiP=jN?3S#x;mZ*-{A(>@Iz-sD&7@mX8pPfP37JBSHEBt+1svH^T$TU zfNf)uELJ_WPa+jjH1Z9&eu{GI8O|DR(f`c8W4N!kk8;)Nx>R(&^~7POpzIgRw#1>xFS>@2XZ*z_N4wpTe0+(WScX%Ez*GQ58kg zzcjdCtHaXa+-s{T9WOXYEeep5>7jxU>$y%f=M2VcD0PN`u*T=a4duJ5dINf?VIzG zR;N&HMgd(NE-$W;;4A_I6Nv9DWK06&=F*cAwo!}r{*@B7%j|x?V!w`ZOk9NBI1k8R zSI3_zD3PXSFgjOolDo~&*=qbL`Xe$7!rrcTuTGNE$*f}h&NY7mes7KcRHG_ z-wSj*OjWGHveg@AAtzuSumBGHF!w_Y9-B8i&f>`+hST3E-Jd;qASB>1GuTYiZ6`fT z?;_M*)_NjR-m65rpNb&B$1RL9dL6c(mzEaj#}&U^p`W3A@_rLt{>%Pc@6@TZpWO6i z1$(#QW=-8^<8OhCKr|OQR=A=hKJr%+BW;L&Ur8oeMP+HRpBm5wCE`p?^#>gx)9n|6 zTYi8Rc-DSznW%KiTt3>w%7!dg5y5;G4ImxTW*MNR1aNxY_ZA>kRfWXqO^aBkC^ucT zlhY7Wp4;$SA6z4`niDspZ>Xxb4chn6xUh%7g)BjrElV0NaBsfFT5ciyJ@ccFvR*T0 zjXUjUKVjrW;+mF22n2<&dL`^9XBR^Q?Y^jjhHx8BM($l^ixMaAC`)hY@UBj=x~F zH%B!5d0hTpDDT@|;Al7g8b=p@Xv{*h*)tR{O}v5JK@^O!8M;g*UN@C7ms!yTp-m-O zR~`hDmPTKLZiKw<@NIV_GOQL%(qWFFg)ThIi%2Omu>s<2!)^J6;n5eW${RXQ z>Qz%24xqH^>)$Xh=9qdcP$lCGq%~M{|MSy7uETmHBno1-k4ObmA1n$s^>iw7%$=F> ziBpYe9CG(O+6vyA&DC=6^fvEyoF$X3)Mx^Rz;k!i5g+Bzbrmlh5$WNsE}NDlOIPcd zg<^y>N2ZMTKy!kvzHMyaHx}AQ6+U1dD2(#CH6`nmW9R^8E*yfn<9qLv--zd@)`>7l zN{RO`a;wc54d9Avuu$o%*3fx)kuSK{H*ib45>1v`oKPqwd|pV9i6MvKzW!(|6yeQK zzWp0*%q5CwLM}?LcyOAjg;$KsGm~$+$j!g3?f>;9Ck{D-sMM<8RnmiO%LZWOy2`6(~3H2t^3zT1^)bqG&coQM#FLd z)pegbP1UV>y*160z1Sv?<`jWSc}D0*2s6r*F|1M+C0Xwk?9OKx66ldY?#s?_LB`2o zoVjo=a5A`9r|%3BmmW&qt?;v#hoY`Ux8Hf|x$J;olE}q<{IYB{o?Juwe7;O2#IpIHgB~NBez>Q7!%SbEOTx2>c~V z=oh5DfEN?6DWqqF{b4W@?@=intvN*b3!iAy8mdOujSaaXCgHFU7y(b z6g;yHEE`dUcT&tQHecTCu*my18d-?%1^lt8uXb$~JA8LtD+Az^PB&Ko%w_`UmJ&3a zbQh2oN`_+rZR!32+Uh)RM-~IA`(s~dx()*mfL)}A` ze8M`jkuJMxmO+gj{@*&`ENIs3(llGpZ`zq7;dWW1L)2RM(4#ge&ofH9#@kf*gZ$=P zwQUG7Isv7+iE5v4(IBrr(E|Lpu^X!uy!Dd;~3N`4d#W>a{6ia;$wk~f?P{p)$bjOd525( zl~isW#`y85^2@>2Tqa7BL%wU?t;a9dycPn-DcymZ$Ff8*&;SNhK1gdZR5B`V$;OBk zH_by%FJFToRt24ZU!Wj9Th0#?3Z2cGFmsCTp5uf;cYO1GuisMf(g1#K;T^ta@Uv z%_cKqAFI!eGY^L2FaIb!yLAgU0n!mr2!6ZURANNo4QsjS)!Z7IdDR>=JGiPxapyJe*f;sUPSlL1;kCh%{ygV~e z1g<`rT7&}QDC4P2=ZoJBOWF6q(UUL_r`vPAAK<;*nfo{|E1tifC4YsYEdNBK9b~k(1 z-pwO{sEq7|QtBnuW?a?}UzJ%wcS9fT^#mO1DhetwukyKxrQm8CGwpyZ7uoG3TiHf^ zrk8eG7;kgD6D^>HEPoH+{(X}3x)TsS7g`$G_lVCLmMiuJzLv7ogQKM6n|9h%qk09F0gNnb?%XKXb%! z5eY{*S%o?L+~zY^{Regne4mNG|X z?)>`GyT#3e+<4Nlgiz=r%Sh*Kn9;~eIDVA&Ys5oV&Pr_PPZ_I z6Z3hW<4doU2=R1#-LUj{o06bed?9S%eD}zF_r3cg!-Pi>662{3jTWcD&k`A_=8MXQ zvikc^y5ysnN+$Z|t2+QFp9Z_{5@sL~?&{K?H~bz3W<;?XxP=0sALn;Ae^lRZCLRf* zDrszT)JFZ=p8Rq@0=Ju^NfY~17*uSr)ysgHo-aBFsP!4Hj`~0=w>)9deQ*+tuC$OA zPFRs2jr1g0u$SDSd8ic%BTg_cH-ouc?Egm;2wLdv+pS?C9CpO9L({H~>$x47|F+2nDg%PfArYY>xw z3rjqrNJd`WzbS zvc}xN%tQ>V3~NsU1m#Q!Jt3l8s3or-bdQ}P{#AWcilNu z?B-a~<#oO4X}wfR^oKUZj|#`1jDk_ONh(gybQdnJ)F&0Ky@>Bfdq5T9bqdKv?G4yT zQcocmqQ~iUB-G#Dn}rX$XObNFOyQj*tDeQ-Nvb1gIcZY|FAPAy>MR-{+8F%4{>PQf zpGis$FODF!{2_z&sV}>+!CD{jl0iK*qh3KGkdSvjz?kpe16cRZ{uq_<81Fd2CUq`l zw?k|@{QEcLPEf2!#gZL_Kw&u^qKfn-bbpui4hA)i>wO%i+Qu zf>d!sw$T*8I9XZheyPmI!K^VWo}9c}Ik1=qgT#zmqjN+&fpi-2xyT5)`Rn~-;bK8K zj!!PZTT13P~xwdF2RpBb=W?hjHkm4%8X)*+6$L}dQTxf<{xo)GkS6n0yl4?j&M7> z5sX9hiwEWASA+mByYAYSzMH+b znz3>~9g!Mx==HGv#1xzrVp-cf!o!o zo2b2AOt>Z_t+FV^=6yEvs$R`$z40|oj-K$RGVX{{g^14NwtX9{)>ufizl$>))O8n; zze%~DvZS>f>$?!MCQSNOKw)eZF=Gi#d)o;VErhlvKkIBRBN`4l6;rrB7;7${dbY_ihhd9lR zhc61i?R>LBTP}`-t5V^ghgYl`6YSHfc8%lORef2{F>n;11efH1JrzdJv^~qmTxXS; z-F7|Wel_Iy-z3HD`=rJia*gXjeN*YR<9x^8ow%=`KKx6V60wUwDcS(-ly;V~Z19_U z^O*{b&kBT9z7?fxokDCh08He^jFQ>1mjSHfKpZ<><=~TFZsG-{Md&bd^6tf19sEsp z&cojkS&+9|H_0&Yy6$%%n9$?N%TT0pI5DX>a*M(U;guqXNdNwQ`g5U>K&5aG9YhJH z!o^+-;zClxV?t*dGZSDC=y7lAY5h`B@|rH=RJj)lniT@R0p<-nWVE!Ur7fYeFwB#n z`(WO>pS#zqJ0?T3+j0bngG0qIoqN08Ha0gD7d16CB}I~%K!Ko_#bR{?4umm$cD;$g zh4|y{9?{<2f_B573l{m>z${L2I}>aT2bD|g3jUAF;S$EnVm*XKUPnd|MIpoRypf)*gV=kd!(g3{N+ zJy{|RPA}Mj<3e|j8I*@|B^nGuQXiS5CX|v5gX+GSCsPxvo))^wx=nMJt|@)tLV~qH zjz!lkJJ*O!Iv>fr-vZtS$L#5@Cz54Q6TspXt&a0>Kih)Rtn_9fw4kA1tE=Xw^l!hN zWqjxEyTh-;sKk1O;VIZqLOZLHZKR&nf>Wee~Jtjwsi-r2>$(PJ9 zmA?N(*Vj33{uaE$(B&Rki*p*odq%4j$gEg`B!2(T< zm<7$pQD98OcT|A|<(=l7G}d-}*x9*Tw-u&rU+jAd^>$$J)^PO2smTA~rq#1-q0q)R zSOQ$(RKcYe$`x%YCyX7oE@HA#v@e64&QX@xSXdmkku^ouRJR{ax09FYSQBoip3;DV zsI1tvi$SC9h4bz|0S_0c`S29Zy=zK?t8G6UE#O_KQX)m|8#gD{RT?fo5T1YFQS%yz z`CaylG$za33>Arj-b(-Qk|Oe|fl{|IZSR%44n%Ye8~kV%0{?pN%(rLS7x`kkN;N0n zN_#HdwVPGj^RRv?{KWCBK-Nno;@7Ebl8~(fiNX|fve~PjavK#}k0g#(!2#%k+E|5I z^kut4v=dD{Ml*eASkg=}?+KX?vz3cfylV)b5^Pj!C3w~-;;Er6Jg0hYgm{lYelowD zergsMQgBDpQfF`=q$IH+-V_HXC8)>Tx5Shan)ul9xE_7E^WL88j zG?RrgJhSHDo&pI0zLf}-ckD_b;=t*0l$@Nb9Jyr-5bt0-)cEi7U1bA^m@Aufo#^!o zrKs(bq(OzWiGgr_a>rTPv58YsFJ=~|pVBB11fO$pyUEZixJLCp!$3f2v&cz`X*R0D zquBhw&xp0qv(6TJ*o^Mko5#c3c4`CZDoLKvkkE!GO^K$XQk5{ zbpF3c+s<~!pB4m86YV#G>d3m@qPn*e8O968A6iedS1>MY=tQR4N1mQ|%odT0C1?;| zgoZH;P{>FiEqOI%urQao=-UXJ$f*_mHF>E|rK;ZokLe7pPt*rAVdYn;87b5d)KZeD z+3U_QomtB-JT3Qt^cbtWt!L zD`V7DuYB)i-hkdQEjMC+qv-&QdG8KyqS|lWC&@moYkq(Jm_6Z% z$;)9jt#tn7))D<+`4-?7Zdp>8gWK+C%qJy}^^5<{kqW=hnMcF~404;_H$mD98P4VF ztpSm{ZHB}(uVYj#SddN@GKggTPNW`Vd!zBx6n!1I5 zU1fc2FXW@D)n>YDJXSma@XB#f@tIZGIc`S<*$?9qEKUT00y4kW!AFNBDWa!T!KBD7M@Z zL{$Lkee0R%QV7~RTV%55UKKW6jHXApOoe5%^xajlwz-`1eAX33=U_C$5Jk%|h>7!_qZT&1&abpaMSiXQ<73ZNTrrSf%hl{Jid3HH~$M;;1NeYQ`P;;d^3zTI+ZKsga&&Qf}yO+fe4!A8g zY{-#?B;Hl? zLgONd?RnBj)M$Vb0?#!+-= zwrv|5YlDqXY-?kl*mknviEU?Nd!vnQ-}Bvj|IE|#XS#c)s;26#u6qBSkVor@XN%gO z;FbbP(Y`st-Jq4ztY3W7)>b)~zx?O?U=UAFS-N_IBq8EF@HR_fOoqDI>oIEpgJY1? zemHCG3YYRrO^@W67({cESh!53iT)G)dn0;OO|Ut>k1)yKq2MpBN+u`h2E&qa(6au# zA3_VXpRR-p?<9{+CYO9d=53pSe4=nB0a^C~dCu35ZWozMOPBr%LXPExB12F6l+FKC z^}C0=2-0*m??#CO;xHV*ysMfQ!=Hbe*1x6q_+>2eY*}=&i`nl(k8A_WUC}uW=5)J; zQyvg_{#}CV9n)gHv#KfsaeJDi8YmnOw@fac0HrF~rWW={BXjL0q}I#pZ{aoTIA6N# zr0LKV4F=Al3wh}=o{MC94bH~#%5IWV6eTASSAf3g1s;na;IM?J*X(6_5(+BVc%2BR zR4EU0zdZPVt=z^z6Y?|MoN;1AR*!~D!X?9+iT3dm%gf^3_X&Ud0T(eqeIM%3w$vIN zBlIR3k0&s4%|YULwt@+?t#9|wyT1p!mvB61Gd0ykk@&fn7@ls;%Q!1rH9IouD;B9g zD&$E|p#8%o=|ZT<0DEpHjr?SwO{_Idehc^HRhQ4yN0F!aifgnVG|}c(ujtDnAO8mD z?Qh_Wmw%UvQsJ`qaU&y{8V7y!In6Bf6xi$&CH*GY;SyW}0nw*~;X8{s7`)r+1Vp2G zd(nu-mBsl^O)kv1@dUGQa4Pn)e;&1_hM9{_M1QB3yX8#+H<$Sgeu@t4vn-sk;R%_HMH=# zMyxSvAAP&AmY=Cc=GNvu3PJNqiKjfP8VpUKQsG2VCKG25Z|&g5PNzo*PqeLADgd6&ycNq2#vH=voJfZzJ){tQ1Sk z@5;AIa@WODD;bRj*qW4!cN9m?e7Q(dJl;}K@7XQQ(aO0p^qDHig9;Dc=QY}$ajc6C zU)hz4oo6yO^osu|Q_z1U;1%-wr5;zH5zc=}A&o`K*uhXl?r=@**?FP)#4$4JP&tZW z6J(Ph%ah|>$@F9(dkJNN~#wbFvH%kw*q23%d z4HU`so+Ub5{yb7kbWsfBATz|QC-Nq3%(0b&68w569Y!fe34u3RmY9I~gFq=s#=hsD z=Ab<{#jn%!eZrh3X~}$(AVwt!c9j)tU| zRoK!!6I|F*{e1pcW=oN`z*%_|w6BAaq7BYwn;}EB_D+}M+KknBivFHq^CWM{CQpG3 zO{a|2OFo8?UD05|@#;#S?IzJq>-~;b#z0DG8p^{X-sXEkj!r)h!e^>cWq#2FeltxM zZV6`IIVh|Ln6L^Wm{J@vikS&uZmXCzIEg70{=1UaQqgu^R!ZW95m%;quap0XiV&5z zSxVT{B1lSEm%6nVw0sne z&L~!m@IoxL$xO3$jztI{vEn>w9%xj+ZY?&DmRpR+5SgO!ghmv#T><1BwW{vm^7_y2 zLg+11KTVlK_>JJV1WiV+K;Q03TGi$ohEWu3^Z=FF3bh7GN!vHx_ZQyMq!A}3D_fBB zsSEQ2*WIweKW&>QG&7&HEnUGgrLYIam@4g*n zQjc{|4O0|Ez?h~P$lTr=JbsZ%T9?+HRYntg`cM2YxnGH@(jImK2 z%d%~fDC8BTGhLSV9!x3{A%?8bPq)uiWF7?BaaNcf(8mx8OkXFZt-d`F>nnKZ=n71a zUh4vLUa^|AdSlnW>Ga(4>3>5GnE@#@q?;b1>H+6gBIe`=|asno~$) zrDFCoa;9cJuXn=Gka=bfDgcX4rMqtf#1~aU?|z|V_<6M*d`qQJxgJksYUP~jOl@Iv zO(yq%TT&Hmj#IAKH3hOD_B-PZt;&K8>`G4Y|FTe1q$}Uc)($r+5GCK&*Zk+up#KsH z5`&f*o5PgIf}AkfDl7i>kGg5nZS5RI-UHMCLx>UNo}|NTHbJrCE$icw;awD5 z7mZmtVD^LHTyypDoW{81dxFfC6`KGhAGape-rC(mUmU(6KjekSS>#^Gq(ykRJ_Lgu zl#v-)W*dhNVLHBDpk==p$cr9@6~J}|t%!|GuS*~?Pt2x7{NFY^<)M*K!_aK9-0Y`# zbbia3FfE2*i{Hukk$5RIu3erj@K~I|e>-{2Z;^>v3HW?R(D= z)wj-Yqp@iFtNVpvNu;hOp-DORUTFFr23{CF43fb%S`42xZ)Vu7-_hfjvj8|XgebhM z*-qsl6xO5sL`Ru=rF$RFPWFdv5?BCMX~n$jVu3Mq%)V%}cDq9G6%$bab#Ii+3rZzw)wa<}HVj}u_iT^1w4849m zO+%YX;hgVq^yl=6^X0e;4MMPt_V~LpK;`LVOH5@$1gDGrj>yC8^mb;&a`r5CUM`SH zAO_RzcZo*qSvewOmj-kvi4c1;QjYTyc?6c~WEr+-)sJF}GvVHk{6~mfc)(%AtY&!U z4qIlDh6{Fcg$TP&=Uec|#5b`Mw44e4m}H5}9BLb-JknXzxfQaVB7WM7J`|igXSd7h zNSW=^*E?1_gYuD@s>iT5V!x!1hWs)LQEg=%Dzs9#a4N+PC%q`(4#e$%qQl!%>Ek1{`3eM^4)yZ16J75H`p0|YDrMLevva+ z;;e2t&RZpWGSHxDtq}?}NKd(i!-b#0Sen~}{vPHr-ia`O$Bcwm&`xo@B4@AZ_}TU} z!%g}&BVUD1&d*9Hj8_=uW?hgH#Q$dUn@W8p6O`(%_Einw=F9r1A9b%$#ZiP1)7P&_m#7^?I9GL|wj*LJc_smjWx?KhE}N z{SerQ39+sgl6ZM1|0tVLv4Fv?3bz>}sIF!V3XHfQELK%+T;@afexP9(z84*QYj_S8 zD}V-^$p9%yCyVb;;1f4}M`OS#!0Yfq?)5K=gm8Z}^}er2L=^&*SsWrE9Wt^5n`nmq zeqrG$UKni$V-~m~wy5?`oD!lg`3$&D8hhOy)jhxSqF-lniXUmhRV$d3BHpe2I($Ye zinNSGPP}EyJ|DaF?moRLKxN9WzRnux6zF+Xc&u7Wc-0o8txF1AZ2=YVtt3M4-^rly z*3C5FD2c3G%fq8+-9ok3EhQK8l*Pn!IhA)U#>h;qcaw7Rv{8;x8) zgmx23o;piG;ASRams?RUW$msEmYA9g4z1)EO^*GB3qz(~Y5B~C-jG`yi04!MTy$eP zuoN)yg#&6`lc^+V2@sRwaCRf`qIc`LhA`l6684KlrFA*!)s&(tYnaG!pw8j%Q~gbo zLJZq!&iS~;BCl3cw98MV?xkDD(6&z2~0FqsGVt0EpD05yjQ5mvB+c z6`a0Sx5OhM7+|Af{|$0FRQd5Vk*9MLmCgIPef`kpQGsn+{GDYx_X^?#Lf}I{UhHhg zir7>tc5H`ns5838Mqqm1yiY-;_p4Y1GyFQNS|GJhjQ42i_Fx=3`lPfh5r}4U892PF zu=oX~JSV3cwC!510SStuT1&2qpZ$^PH{PUF%)7#P=e)f5<-JZZM}Ag{PAZX8x5mv% zMpT8)=Iht+yUuu2NLjc{o2sqXF#TsxJ2yQNihE@S#_-b zM)#A-kGH$HjV=+Di8%KQgN^P#Z}022_I558G(8sf&bTz!00-f}JCleTcF0LNywk_| zS!jT`h!KUr_kKA8gFsh(hF`70l|C_8Fi8^3L!H5Z&TNf)=dDEu)Yk`(6i7PC8ap;} zs<0)o%1~QxJAM$k9OKL#QPSPkRbX0Hh)1yOAdsg_o?LSGCt_SZR_QJ^AHh0j!fW=H z_q|Z>MBFJDmx{;*sMv(QUQiUVO5P@>i%ea5VOJ`e5gLRAZ2g@HH6PK-b=St)@=>?I?v^X4;=Um*_7xmt^(@zP5 z^f9W8`*n;`=wCw&3ARsBrO_h2VaPdN*5c&V!Wm>9ahVWG!#Fe)@Dw>pD*T5)X)v`& z5CcWxMDfBZ6EhY2gh)yzi+)=A$eF6LRoNQtYQiUqg}JyUj+h0+UL|vrxEko>N!&GO ztjTf%F;O*<=D0rlUyX9xasTShZnr4T8<%HG$VW00Fxqk-OR~v(v^({`zD%Qm6c}JK z!MM^pvBUcfkK)1lpMYnhr`wSLV?Wc}*hS5?YHo|0z;GUB$HNB$U(;la%MYKaoPfCN z9YIyo+-HZ+NEYGe^r6s+jqV$)k+{5K!MSMq3kB{c6YUWrqr6R{DAynsjJTK`HbeQz zsSVJyIbyF`Imd@&kLY@kO=Lm~SNmfvS_7OuLuby|^ z$x);absFJ8cxscf^t#d6raw>CfXh#+-IoyE0dQn>Ou^Q4(bOsbzf4bQSxBQO`s*ZYd~#EseQaAW+cJ3g+&-2& zKOV9)5V++mGYbzuZLZ<>4#f4s0a=SpTo&@WA!lhCzGA0;J2ciYxa+Xs<@Sph;)00S zw779AEx=wvdg-jt=K(Uj-vONGWv&H@7u>IcQ%ny0Qf83rw+6iWMLDYxw#a(4IZ4^) zT@=*mh|RZZpY2mGKAZ7@1Y#);6W&VIDZbX!$mFkwcYeAj=7E=CTh`4uBY+G#c!GAx z99yD6Z-NJTN1rm56r-q^*!2=9ZI|M0hbYnrjQaWEBR0Lyh)$yaf_WA( zo7ngC9q2nXG}B>mNHNFV&0xp}c`=e3zD~p&g4(K;$-C7A$?lf7Xc4W4i%P>R-w#3-1IXW^oP(?`8__6(+$XQyHi=x7U=%yyLz((M;>-F@~{E`-m5Z&)( zOrFlwpe%km{}jJ@)%a)ifOmrwDnoL8ySytQX~->PGaXsPo1K~YSX^V?fzTw5R1M2XkI)5Iv9F6RJB4rz71P6{pIp!rnh{lWXW=zbN^3y zLNlWEJ#}=CI`i;?Y~#)oc8&2}e(v@yWEj7(lReVTIp~czp?U%}6Fk_=WZcZbCP?l~ zw5%Nd^HI`%$jJ+9xl4|cKEy_qPHjcA<+A-i%pkc|iB3GBVk?O;F1l9g8uPP1vafE| zh9!8fU$%+bOA{t|t<+31_%Ecx7xl8*4>8~g06MbI<-P~e&0X{Q5G^hLbP<+RRl{Z5 zG?YI=mZ#s7_ZpH`hPmaX08#Q}v)=mJ;^$j&3-Nj$>{)}9axvbK-t%JJ>|M+Bk*c6L zpiCbSj~O>c>qnFq&WL}TBsWSh1jOUawsCu@uEG3h2X`|dp3QHgbVQ3LA8+tUPPUj4 z9pJ76SSzT{f4f@2O5fCv@l)2KPw`Th3(+7eg{$Mr%SKaohAxSbS^}}T`KegqS9yQs zWqetW{V#|##m5Jhm}V$xHA7nGV2k0RPh5m(Sx5NklfT|?<`H1RP4U%X9 zSKCF7A0L?&j{=$$Cy%FNJ2QtB%=h3t{ElIQg1p$xe`7lSDDUOujMDwO%uVY7*{mn5 ze~xnBI}**bJ1BjA_D#Y2SvbJAysP$+N!^3$S`FDU0op1uoXPJ-T6`=enVnmAeUQ_& zI5}d(ElRsM80l)+v?tuPE&b&A9|sfma#odH3qS@1%q|302ZeKH~*A5eAZ7BMXJ zMmX_~cdz~VbfdFsTWaSbc?9<20_Jf8+>s=UrP$ODqIgU>mMkG+I#e37hbeZqFy=wNGdLgN;j!aS|DX>fP4*3!K59yLT^9kwK9AQ)l;TnlnKz^OXerrd<;f-BmJ{ZLiu1BG&$U;r?4*B3 z^0$4Lwx5v=WR_hC=SeNY_igje-DNis0a9#+gs8)?a#a}cLW}(=njb&h8^(-Erl zuvlc8A<8ji;)E3Brj+}3Vq0uuE7`cF=xgjqfjo^h#5!q0z63ij{R;N&O!r{dVOG{Ll6Sl?2GEw5iJH!_9Cte%B# zO6aJ8ITlY#L>Em{0IOGv0+#Bd*DupVuLEDWloBUbbW+9GPV00X zK;4TLMOy_suOXn6%+eBAai0)7sQ`omlDbI*Xz@|kEO=2Jv&xZl{(I)6Wd}#MYwE`u z1G9@2`1<)G#oUkhW$b^e_I`aY)d2_nYh3j;kvFHD%{=gCk=IF=w`&nT6)k>mqok=?+8N5*ZdPl{T(3v(y&ieh#vLrh zKTRzs_M`r`E3aK{A}nUOWc$9OpH@#a@(|ZGw)XxR)Rmt<^t!c#=$~>qU2|LFX|b{$ z0-H!8ui&=5OXrsyBj=ZWHfJDwwodJqb;O>lL|V7caSx9mvjHi%U>+R*4?&P$ zgUm$9D9ZPd$Gx(Am#Fu2I{sN0ZiK$y_67!i`xUI!+hwu9v1knrT&aP8_$G{gTJi{! zPSV1IGP8|HlQ&v2Me%+~R0gp`ILt(7xk5=E2CFpJp$kDBS2-RbJu=Blw;*bCB&DCS zp%ql=_&V*qT%14DN7&sI4Mt|T8tq$0a`9}pg@iAsgnKK4-wWvVmKp7Isqsb%)0=1) z1#Fl6n%B{oM24gN3Uz2OsnzgDx1vr0>(cJUUma^jXE5o7jiNnBE~=7YV1)&}-i(QV-55Lx+-yD>9Mq(MREdp@32i zM{pz@_EXTro>=kBgKVjGOIr@Nun>CRc=}TJYTvPFfib&0gi=+~NgP$mQ%sR2=BhuP zGzz{bg!UILnq(xYmQd!VQUs}_e6JcUXM!+w^{ZYQf;tYbbbC8jtU>)^iKI2;D#cBi z;BueKr@d?<^q0!?f$D#3KfaQEb$hPzq_ohW>!7egEGBJa!28t8nNv}#5+W{Tkl0Bq;E|(2QOHlO60q7(- zU-YBLbfd(j%YHc0V%75kBWIC~2-CCjVjv&_zIld3yb?*fcUEA@6-Fe5@TyXF_0W?= zVH8TDQAP0{BMYDLnne&FkGqyI!N`(<8J_{@2IF@ebO~ytQZF8sDs8Ve0VDF!{GLkz zOt8>z62@tqNt9%85`rxGt0?7MLd}^FO%{^#+Rz|iBDQz~Y98Z{`nAO^R}XUW z(30$>`)@*|2T$@&Z+DZ8>t^ilm4H|woWSlP52kLBY~mX+#K;_w_&qtTxJKgewVs~j z6gDP1{&S2RnQ4-flI_GG=Y37NywN7ol@5~Pj0oz3J6~WjYe{nYagTs(Vu&OiddYV= zhre=>9XK;vSxOHUf4V+H<6qm)AP$aBpM!b-l^zmw zpZcL1f|`}+T-lc*8geA2;bu%cg?Kl`8@wdn;eIzp!u1W!x0A}!zKxG#T-2+_K&X4= zc@^Tw+s*UDcXl6ir9jwxApyCIf@dfW?sGn4RvMzeaK@KWwTCu8abeqQlAP@5hZu87 zW^7+=m)C81{4#SQlyT81@l^|xDDgq8sN(BRo|uKFzE6X=Z(UuEpFuS=qx27NB|W{H zM`0uPEy8nKhrX*q@3V2li1$YmP%0ZO_?PgvlyWVCa%rxnlw@HMtg)Ql- z&BDE7rxh5RGz?e1%fhd`U5|H6i;p~18)hTHe4-TnbLfN$@gPcF8H&@jeRgc1IoPKT zE4U0nKi}RX`n$?T`j-T+4u1P_h27p`L0F zrUbmHzs!ZKO^E-#_5}v!VRYN53$K98X4qgo-L6`z7WlM>d2u}$<2JXq9s!m7gymeBaoVjre3K;f2?}HtUay$eW{&T zzL{OPnOtZ+lAT@r@&yo2p*Cp6-WLxamTG*AuskxbucB>fh_7U zs&p~vr7Oi*TU16Kne3n@0(cb7yF%BCq2Sx=qoNCcIZN`rgJGj)K!d(Nsm2ioKJ$wN zl!UepzYc$T=^)7U$NEK$tsCP&FDs|3fyA)q|_0KoXR3$tiW~=RJVXcXml8O$avbtr1VXy1A996 z@%oO;3;(-_vc@$wmq#;mb>zTel^7Z^gkRKR^K;N@VbBIp2I@y@g*NE(3w215c2?=q z?MC+Q0Z0-u%bdm3c#7|NB(Ttey5o0(Lh4+bzNx%mN>ki!h34B68`wjLD8-#?Z6wRDsL$RhNtD zV)sDEMPS{uDB)h{!2c~)n^?t-^90dPK5qNn=#=hA@VHSzlHmROKCjMmcPm)lz;m(o znt}+R-VA7MNh1Y&lSn^bYQfutfc@{1ixr1@Mf%U?|8M<0k9w6)I%Le0{(BQNMKtd` zbzCT5L79dlN^rJMEM~K`?(Ky_a`bei`sI^b_20w4gooC2aEmX?_In!pgGKxDOQ^gl zn;l}oL?5{)__@58t{v%8L-2BmNW-yU!%%|?ImsUXLR$CV8h8mM38k$qKRv+Xr>P@4 zJTh1>wg2WWlfcO&tn&SD2wv%5nK0q>ivJ|`zZv7=exZ*1@8}CSTaN_y-z@*T8L0n% zyZ9nm@^*lhr5q+3Q`d#K-Ep}_?xzriZm#^l>EdC8@kt1Ny0sQvL zs9^-0A0g`S`SX*S(l2u2D^%a@z|?-?z@tn;E{;d@aaHxay(Df4y?sdpfIviTK}vk# z_x!3(*?bgRG}eYQ+WcHz(f26wYdzPcG{7>XS*fIj8QjEDKplMh2{i=v`{!c-v5aJ_ zlAcXgNaQa~ykRDb8RT=_+QzJZPd-EpD9fKd(YZz38lCabNP$t2{7jv(OhL^ug&Hc2 z_+Ngm;Xb1)lSThLsmQjNDRnwTM@%C|?MPDeO&4on`eSLQFpWSaN=0cHyVf+V+sdhu zEHt%W8!#1bXWHG`^oHsBb$f=wcIn8LCo-sReHL1rXJ(Vpf;s$P?O0M~XfTIctP8k( zf;vLVgu{_HGTv_0E(v27^nz_zEwxbFTZ$=vf|~*9UJ?R$cZ8b%5Sh2Xltkjfik=LlOw33%CmULc@*y}&g8(lwIa-QyCf8ku97u6K;;r;m` zOvKlb9jdH;4xqll$Tv1m@QGBzG5?L*gE}^ zQW+8&vU_?+3nm}@uNCy&yd{cHOa}csBiCf{68SGwKlWe)w2#eOirppbb#39pi_7jl zk{8s+Nf*o!hIEzoX_-HwkY;)D1G$f@IU#~-OErK>58>hi`G*Q04=Hl*$D2E|&8Tuv z|Gyy-r_()$^6I6zq+(zyU3`Y{*wv~_Ob(w|sc~?N()$!vYWG`WlYX=-zcGrEI-gH& zq)V+j;TYO7w(jeh=|zBZ#)~(`VziWYpk}G-gOJ7Nd2Klm=NY)y`(+y^B#@E}-~f7F zlo5QoL*&NJqEz)L$)YrFUBR$S|CnS+7Yu;ZPeTotym!NYtZ8_&i&b+98$ZSX%%5kJ z=B;fFZH;A|(7bn1pVv&bt#8f42e-V$r}X#^PS&2r3`-;{XOkK^p*YR^RknSw83$x| zAIK-lXr;Qou539`lUpxY3AgsG9dO0e$=+|a$Q`m#X_F3c&xM-15?iqBlK?|((=;@(h zmZ*izUC|(~om$c+x&F&yRR7_aBncmnKR33gOkCvsKxpcaOKCJl9t2zc%A?!v_-m2C z1JHtTHwS&dafs{licFt`Wo6fJJ#^`HwW@7f)2O=1UQP*HCi$@6LHKz;jmyUeyzZ}G z-Mj9`)}<2u_y?6L{2bw9v_aqrHNLj zH#N8AtX_xTjnD6n)wW3-WRr8rnHr|APQemvhJQ)#-O&fuP! zIM+LhT{l6+xU6`2FjhhVaF}ns$9nvH&Rfwzu0xPQ(l68qdb+V$x@5!{{LEc#pcwqt zvwI=(rhW1DY;&?s>{N`ZmAXjqc)gA`^7)U^eWOp`$n11jQ_Df5*QN=cA~Jzt2W66M zg5$|h);Xe`;O~fN&`lPnz0vLt$!EgQD};A*;JF?gdPu?$a+Jm?(=H{sb;~hh_1upY zN=ga$KUDhTMFe^tS4i*#>#oh#gOR^!NUVoK`VWD_(OQ~ zKXLWiofRO1q={;0#S4-`(8T9w3BTg`g!qTBa;yvyX5L)!w7@~m+?r>L!$!vSG=(l- zq1vOBrOV(5=RE6I`M=26f9{am`DKb)sE&k>p{(JuOSS(3` zU7ZoeOuyLa!g2Fm{<9%xs?{+YOFoVYw{E?ON@;tUV_8!-8U0B(yO^9 z^#_;AYd~B>9mp_OsdZh00!>7x;Zj`xS6t=cAWE^?81-!8K4;h6VfuA#7WU6cCcR31 z=y5WeOj)Iee+tJZcWY^kMn+OG*=Bd|x5*5NQ|Askt)4kr$z|RjG%@Ym_*CfyO zsy8g3qiX@4%+JfyZ2s=B1Ns*C(JVSXE21Pq!!wa&K|b26o^`R@53uSa-BM1)fmd0a zmxd-g(GyR@v?*Zv8l9+>r!yDs3+7#z%~dz_Br81Uktx=Xk5?q6wE18Abl*WLD=Ya; z?b5xtC3_BPL~K`S4h=Vxn*Ul%Vs>=pL#e@sj#C6a?_^R_$vk$ULv0mbKZuq-Z&+wM zb#|<(8l+b!7jSuq6<%n!g*750dk-gA$=l z5P5)=;GodagUpN-a!>SaiYSHbjQz^!_W)+tBc8K=G1i=MwLA3s&8s*$fYbfcM+C7O@FUI`F~cqt#_P zq=VT#?wk^RMql@Y>LH~2W+|=q3NgaOVv@t{z;gn?w8Dz36G-%{lWSO`=ik< z1RmSD_JGh5hL$Vwtijv(%t+PW#u2dRvDo#TlUMp>W1~zuR|v&JPc;V^tgn9&)e^zc5~84M&Ro=YAs(wX6>xbYfwj1+IZ-8xdso# z;p3Wem_@U#4fHrZdh}TC)Wiu1$vBPn=k*LMg~rJ>5@w9yWjB~-kL@AlZ1#VniUy}} zZ1_WG_cXQz748?1>}NOGDoD6Gd!doy1HV-BDj&S}?8SbL)Y74tqtc7vVoTQq9_UFb z=yQ_%u)MxiS#9;oOFdNc<|%MIu^Y$0s)MG#Ibz(}@4FN!&G92LS{t3mJ|%hQsd@j< z4?0=b8JT7$d~U>Hx&2G>$&SEQGl8m%i;6wbNgMuVp}A*l6&>z0mJ^I_LJrt z^JEe)RsAB;&bY){?3dTNeZ)X=d;7ZQ`@B}4Y9)VAusuWeTFb`sd4R=FRke5Xu(t@g zy|u%Q=Xa|9G0mzm_zihtT_f|o%DA?Vo_EBZqiNJ44Bq<5r4$w~&mGuUEzvpqxz!DF zRC8(n)xHd2DL`igKxk~Z!w2d(H~N==PwMgKRi5X0EMfI2NrCmLU~8B1`4&{OgU3p{ zYsTaO%EPsh^G(3Vx0qNN+qdh_eef6~OS{MXez+qh_X$4bHbBAs1p4_mscqFR(*f>B zR=~({&nJ~B2h5oXtRE`nqY2sZL-4h_;^+J4U}RpW@{+u$Z1J%P*3D6&QdxKZzm!_9 zr=ewA76%Nxy{9(1@!Fhxoyk(_qbct7G?Bdr9EEfb0a^X{XnW^Nl8ZQ6-+WiVy3a@`e_-T^EkFF%zHGN)VqWSw}*78c5o*P z4!&dO+aI~-?!DFB9uk6_% z=d(jLSt@q%hb1D0(Slo{+xSc)#Z!%l9){eGMm^wD#QE)w^W-A04cpG;JzDbw@z!>0 z35|ytz z?#Ipa#_N*{_c~SBwpaLgM6uf`LgjLgSvR|~eKGU{eI<_Y&z(vF&lhM4hi(bBc{96r zY!J@fhV(a&toC3oPUYtn%G>QX1_B)6-BhiC3ZtJpFXY!Vd{HBD2}I23Y3vckNo%nT zRoh0UcTc=8OX%x7HTBPqh#vI8nv8qNh)6k~c=g`dOT!53+RRtRAH>~%ekBe4;ghYl z(c+inoA+(mv@9TyRg#FGdI()WB_~_aDFD?;%Z3%GJFvNb5Mpo`b6(b89ZOkHOmJdr zUHj2${Z0o`^00;EG|k%KSb8SD-65?O)acp=;vk9_n^gj=+J9LbSxI|L&vGVYh9z@r z0iqHf{Sn4#K8`R_iEHMz?9oHnXj3vREB7$VMnEiEX6F-ety!1G9v7gSdjrT*Hv|s# zeR=ASIdg2`7t4zPudiV$?AI57GtZ=^Xt2+GP?kQBv>#oz11^#JyuoAe-~lOj4vek> z24CFtT6`1Br@!rf$F7Jl_DT6Sjt`+5WeH5+BCs|1NR3s%(Mk6UKDm~w=U{#~VjK3q zQP@~zT4Q+B?RlcR@3^HLX7r{GHwVa0_R=e{-YvaCSEJs~;v=>!0cw`v28s!U@zA-N ztypSjQ+1=Ha;#iJ*Ca?9Jdq6CuCy=euN^af%#}8D%e(NA>z|^Iu+d+`H!lO2nT+ig z;0K_Kbf^M$DTgX*S9Q*Mui&MH-?%6m_L7xz$-ypv$#U0WVEHQLmGM#RvLi?0(F8bl z?H(Op%wzSo2KowrYGAldgCt$6QPh?b+9@x>jOZ%J+#*hGT(NPEpkaqFEb)Xsg)wMc zov+y^@_gmbr|9pWVfcxp0FCm@mNQNHP z#11UrXlrC+M%%FgoAwtUr_}R?PfTv+FjK6mS4W_bMrd`oEwi_zb8Vm8L^2(i&BUdr zTc+}Xh0);2l7E>g2q?X?p_1{wIE{zTLaN15?|)37WzU!oBq_UFBZ!$kwtb$cGHmTX zY1vj2azScn>>G|H;LO5r%lnK;`n4WKzxiJQ@9`Bn9VX`K_LjwS|FUhhHBw%N#Zz^Q zQ!q@>x>23~Gya5;k;RE(!u|yl*i%H)E&B5@x$W|T)9{q$cCuVkw~2QAaaJ(n*1}GB zc7j`iVZPCZvA<7$y^E}M$=KlcNj9mMq*J@AnD?`pUuI>)cyB@km3gBVFLpHdGceLa zS)Dfhs6C9EbK)pmq7^3G?3P-;GCD#yC#VrazBps3`VX66+0n)$fCYEoLfLc_KTARB z%{$3TmbCcS!f}|6yPS&kF{Nx0DYP^oc2>ILZJw^iLv(kKY5V83(FeoMIr;Ss z(^8u6S;aCgzi_Bc^}H3AtSfRABKYo`}g+&l`7y3sazB1#oxIoWBp&4=-dScT-N(JyL;O*7zgVl~$oY+S98@2aV|SquU-lO8sy z#Cw8`)(gAp#c0+_8+2vB1a0c`$%a`aGm&&kD0|qc@V^E;jp50@)4OSmEB5pae!Z-7 zJH=l9ykklL<73Y)8J?GR@{34e#7TI0MVvgLe&;s$9uDe0yisk9vUY8u!oE>+XOwM) zu@+XOFmg70n*<%+d8`~G3)2CUXFisrICjOT;dwj=q$tOXhCjQzN29PY!Vz3<7&$~f zu^LFS#kce&hv2R7GXbuTf8B~L3Xk#0;pKMIdF9++kqJjzf>*Y2P{l>(`t;j|-b5Tg z*BQa2(ydqsmtHFaNg9^nGsuV(m323|Nb90ees+p*A@)fbLX$_Ym-R2_%NuX|?B|~8 zvpw%v7$n^ifX%x6eU2iKNn`%G*GO35BO+p7YKYzJ))e%QtSS%f^+T!Iq^8&E1!LngWFa-3*_b z0&{1Le|@>O&fNpi^o6N3;GIV?J7=JIzK*7#3?)vBEF6$kaT)5}=pPFBi9K#64{vKR z(}3*`3Id(yS1(5HMNrN@<}L9gT-Y^2^^5AEv;)Z8h|E`TpUJff0*{M}i6rDL#7Af` z>9TpH?pN5@W3ekG%#rM3S8OmsA>hN4l`$cc<9Zs$`!9KP7qLKj#xdE(yJ=wM?c!KD z4fsg~{4P$)gaJ5$!y{9Inp{Amq*Rqfr#jxRu&na=a{#0_w1QM#7KhBJh!?n~#;~+- zVyBjuI|J<@O%{utb)X6`KgWraa$;2e7@|9fCkM0ctVl06u-TAFWvx6$z6DZ7MXV#Q zF+|I5Q^PB=kEkT!Wl$t}eBYr5k&v4~47jnfbMvEwo#tnN8<i4U--> z!h^{$u|UxgOxN|vVd4M4ETN8tBq6Lnph?O}WaAn$cSh^IM@I1265mE2iczbYOW3d9Fw2Q5 zCy5Tbxo8&?C6UM~Eyoo5HQD(x!dH~<1x5>aa`sRX3|SnhN?hoDK}4S*~0rQ6qFV?=!RFal4o|S?V+36PkIAgrX2e{=r+Z9o9sl;y5)8@4podza`3>!k^ z0#XRI`@~B+;^q83uNv5HwH`h&Dk)8L>)W=EN(z;?W}zxya4gm zF#fq7fjK5ygD%p9WYkteLI=j*Cgk}JX8&Vlg6#)`SMc+*!75yr~YeZ zmR$;*_^4L7P#v}3psy#WrSI^=!i0Bn$y%C2ueK9Gj*X_AeL%P$!g|Xf5BphaW_BVw zF+`kO{5E{b+bpYXo*?1=fZJx0+Pg5%jS)Ji8X*sv*h_Kp1i;<;xhf$!n1jsS{T%Z( zpuIOW)8Zm0Nh4g3a-v12V|(L1{D@!0-sm~|mBerS#ajGgV>xE>&v;zcCsIEh?cv&NuLkfiP84gfAc<4?n_l>Y{3UmIP`n}{F^D{-x{aS zskZBnQnmzRh!#oE1RUDE&i6zdKEDlSESf*v6IChL;@eVBD@iG3ZBpu8W<@C=W308-#v91^de;X*-mpd2)fJ<>$^k%j(+PXxBB0MIF%Nk>H<5P7%An@R1^(ddpah zlDZJzL|3hd>1`HQ@=r2)hwuE{vHGLr8WAlY@dqNGh#sGJSjav7gR3qTUZ^BJXcUvK z#_O|%elG)G$Yz|eZpyYy=EmmR-Es(wwoUJMrMRb*Ig&}pdALLT5AgpBlbnya?#|Pj z6tq|MY>HBp6Nw0h>$!H7bF6$~rz~Rg=M9b*xUFhyclhuWdEC$m;x7@QOTHj)GRG6; zmALM5IcqtXFKcSci<7gEKJa_qYn{O1g%27c_NWfntl_4HekY#nNYi=Qg|tzC2N$6x z-DieOET@0&yT~V*pY5S&IYn$ZqH#EmDiWIB1?Q=b4mKWM&Q=9;u?ML)Ix0{x>KART zdJ7AK6HjcF zNxnOGdpPN$VJA-ri?j!zHeW5Jme(?3aAR9BJD@(XDd&x3#Iti<{!TAn>|NI>YXFeB zP-g-z2L;P^iG8R@A79J}n_)Y)LnYg#>PM7042h`qyhYFBJajs)U~C*F+4O!V5|NB> zU(B_;WGpI_jY^_4Ij}S|=}7Rp?9&W8ao~^J%mAw9*H)-)zfu-RudEbyHA{~`3nbaM zA^%SRs}EH0l(2pPq-{`wW}sOnx@GR_nkErRdz;$bn{3>>PkrGbOW)j~xxPi{-(m63 z|BTvxz|iRv6h<8U+ZTB7$ro%lOe!D#hMCu0);{_jOZUF!{>Rglr;3aYO;A34it<S-Q2Xj*Zn|x9<_0Twmg)EjS>nTY zdKKWU++*pJk65_23`1{l>~G$~t$)M4kG^K(%RlkpwPR$8?@+2{Fw0{Uj-Mc({Syx_ z-6PD;G5qEX#i?QJtO5QS?R%Ga@UNe+eElI&$)vq-orQmCvEf*l>L^8`6bgZsEt8ve7<>CP3s?V{t#2-{@a@|aelkq?%o$3T?y+*?FWmh9HCQRc zwC-G|={pqPKg-a`N%Ulcjf-Eh_}N7k|MF+n?yuw3o2-2NTa4Bsjq`6Y@zZxHR`cjb zG`!&DL^>cVBtq|!i`f%vQb35ew!qf4>ufEoQNMM8mD`JWwL06^FLM9)8o}a8ipP(W zwd$;V{wWVH-X<=+#@zqy=eV7_EPVVa8=rs7!{gKBD(7*><`{nSHP+T{QonYQ`+tO- z6VSYOA73A3$R49IS0z6?M{%OW+L!m3|Ko2_o0F*JD{QXRiIVD0`JWDn&@2qcLDwSM ztM^#B_!(ZV&Gu$HbuL=D!}{&}RI3Te^$R@spj4*Y@E?!R8OC# zSc+)ezRA|Td1~{wSh}%5dwY}c-en&C%Rds{8KW|4(QZXMB-sDcQ@%=60z$*cmBoiMW-DLIZ1s1YFoH>RqI@G?pz|zHw%ztr_l{+hRwsh7%`#o2!HtT2JW#)so zsZ0-{zwm7KC|=+qYiMQ$yD~&3DPw1?w4=kWwV@XuawFuY3OMCFrl~z)4=jZc zqyp_L^K9K+CU(XcdiQ4>``Zt3>Se->4esCCVEfiB8gHKxGe-om# z9EI5v6skE)9aN`7*x15rga|u>smFK^uClOp8;OoHdxj)8LUC&3sRS&#d*?>3L}qw| zq?ARsEX;C=>O1c;`t@ysyA7K2i+DddLFwF2nOj~b{?~75KDb6lDbQVtZ=YrEmme~6 zVgxN(q;cmm3xD~X)tk#i%E59Z!TeQLLLX^nD7^V5xylROKwm9L4Lw`H9U6gL0mIaG z9h-JqP()B)W#iimEL^@vePw}WGr`Q5#2XJ-`=T4_B5V?OovnL|_!OwV{|jb*@k?^i z6r!;~=ZhukckWVOJZ2}Jr*F{g7G_GC5yQ_ijQg|akFOTBrKHJy7;o)bOsBLV}+=|d_ z6I!cmT=;}=ahmx2X_U-jmn%@nU}Ph#VhPuCFkJ^dSHvlKP{?5qO;CCBZHDhGvAnRs z*3FwF)huRpl0w`hQ^=z05)f#1fx^i*7rf&9nf%2O_!#VjbQ*WOnUlJG}{t_=R*;o^3Dn?-0p?%)F`4X2P#6Il3d{CbFrlE*Y%0h&gP zgFF2uQ$IIRTy!T-{?xn7{F`m`%S&h#2VuBmUpvp7VPcKUuzGVL)q)KfQeD#dr2B}PWns7u?$9K5d7MhDK-ZC)foYjYkq}1;b7+>)56>|4vkw`Xoy5T*`c<9C z`j#+fqrwoGpP>4|Z@|it`}!)Ii<>0U!Wlcx@VR#xJ3B`v?;_mSnE2Iyhq4MR-`zwM zCn*eNptVVTGp2NG7*kIZ1q5BKXR-e_NeM(qm(trm<9MKBe|3jI7Ad}dmSR;STDr!{ zy=~0VB4#FwF@Bt}pZpEZu_j6y-923enwutyv2}zNAx#tAcCpI_X1+oxR$T!T2h+9D zoE%o}1f$A9RA(quV{Atfj~SGv#?YKMAwL1LQ)I`c&@;axj&J6I9-Qmx*`Zq&%8Ov;vGmmF(m!RaxDm(M_g8cBF*i z7)N%j5K0{)R^~@WY6=MnTQypXtN4+QRT?5&E%c?yN=+n5(860^OZ8a&m_35!0Gf$a zDr30@Npl;&14gk*X1I)@L(<-+wYrAaj?jz4WU56>OQzbh8*8+;n}nf4voqM`DsCx{ z(bb<-frq!bMr)%+6l>_&EV@jcvXVri=`pS41)6KAOdTB1=`{T@&rGq;>jGeKOag*&!f8z50_y5C{PuI!*|NH;N?CDW#GgbWx z>YFr{*9qGG?%qztF+d)3H>N_(CIyQ zX<`;DWXDFZ+*FQo5R&x#(Axu4p^vw@n(CEnS=`YP?5sl?a@zIsB_?cc(_UVoQ)>}- zHOPB`38@cP7OPxF7d~OVNhBwR)gjzc4vmnown=+q6R*)G zK}XLOaVr&^d=^blvynyZ8l82+g&K8(TCV&eLxBBnJ_&0?jRw zot~pOUPMN1IvX|OM8_;vuv{J0*``zPfK$ZDIf$@9XJaeP{6kufRQpH6$W?HMtJqeI zx3)@aqt;g^y`%~PVcIz55}F2arvp|V%j#-dhY~BFhaiogCsQF)%AqA4yp1(lTdj1$ zozEgwK-B7hTgI)Fak3^o=Tm=clh*nse#=J*4Lw)FtyXbz7OJ(CrX!4Xtm+7E!9~Vx zI_v9n>MgKL;>I?u(D7rIQ36-r6FqjZK11+&5MvAdS=~WpoHT=XU+uj@DT5 z;u7%gf1vsU3H!a?_MG&DyA*rA?lB1{4{*2LH`{yM!`-ygB&HT7F(aRRr-x*_6)S!0zHtW}J z(`tAmJBbtePZemH61lmPR8LHiDY&WX-u~IQmYnBqwjccRrU(H#2>wopyz=X(gc0f@z++Vc#P>PNkW3nW$N=wv}yr*X_(x^ zIN4%0RiHX_#+UD|wmeX#8sMnmuj-HD&`AtmK0JYJ4+rtGE?mDi3<&rrV23oj8Aall zBeSaefwW^{L9a%BK#Zf|X6EpuaXWo2%2Xm51y S1HV2100006DDLj=#R(L5hmZH(|DUX^BzM-z znz?i4+`aeNH%wku92pTG5ds1N`MZROA_N4KF9ZanAOP-TgnnY;p93(aLNY=S5VbL% zUi4uTrLWNjWunV)f!MXR8%^`d0MtTa_>F+$kEuT$?kXa== z!bcnjB2p;hS~+u~S5XCa*B}KZW^5z`1~NpntPn{^Nc?u5kyJ=a9b#G%44pWW?R5&E z4}*}FkWk}nmxLa> zOiH%BDvB7G2%tdoMIZ>6PB&8dF7cZy!&&@Jiha`a2;oK1s(y%+?7!GBtbu|4}@nCPc!NnQBKw#196oD!M8jRuZ zQKBjdg8`Vwk6^8|IG|8$q+wlB!Oly~5pvtb9~B|uGI~K9o~&_$1~JWGyv>8fv)%pE zS-Vd|KF^%8!5a78iCU0jp*=umlT2TD;(JT0Ws___qIsjD1x{@C0gArr&ja5; zr0Gy{00a$4{02}iWE84i8v0QD?xfi~DHLhrx(b^izPh$Q)yF&_+PM#D20RfRwQC~5nLA~nprYUJ2Pha}(|AfvY!Rp!B#fg)6C5jc)l6l1{ z*7>}9JD>l_(kfVDhobrGd1UyWmGjaUqa;i!6JXhyqj~0yC2-eCa?sNu`i0ryru^lN zC#7bk z$>*3hA3Nxmdtg~$F2xr#kOx4!hoifZo#vAwcA<7am1npoqcCMwkKM_#y+qxtE13$+ z*3n$a;}*PtM5*%M!!M*odonie7zG6dBYW|&wg~i0OxLwBUXhoVc6&S}vNIaHT%R`| zvo=T0HrhBnmN1%N@PqoYsyzv+`4hpKIgh+=mkB;SB+={r69P}NttmPCUGIP1ht9pO z%$?U?AU2Uyg0MnA8i`OsI=4ykayed+duQ*A0@=2Jn;I z1FMM=ZKuUP(=fzR;-Z`5EeE4TRABKGTp{4_Lkd_t%$V76jd(&Az7q21Seq;rH}j2*|qYV7F$yZ z@b~@a-a?_O;f(q8I*S&3cXLX4(dQs=pTq5T!1k3SnfRTMKdsQmtxR5?qP_#x(HxcZ%jXj81q*w)p<>E2r^jTSHHqb)q&IB}`b$#x?DQG;r1GFI&s9la_t>S|1?Y9_D|K$_pcHZfyLvQxk5 z8T#10{ig@5^^|85XqQ@Aw->#34xa4rk|1wL+plUn0}sZ%kAYw9&3@@N}2QB+IDdj6s#{zWI@pTdb?1wfMYJdE*9j`5L44fOZA?@T-Q z8KXPIKptISLAJcw&@PlFg{dUVVwz5xK$lT2bwg&ZYNbFR0?`cY%(5uek4cX&q-uY@ z5XC-1qR4VppGS>v)Nx%x->olj-Tyq=+-%PHrgO4h`v z1OEkz`JZB$haA;wG$q4iB%OIsA2a0u4zSr0eRiKotYyH7K&}2mstmOw5QrSpdhU0m zhqq{Q-tQE%h`5Q8nwbsme}G~&7Sb;2{@XWNWII{=qAQhu-rG+{2RAG0mjycVrX+AG zmQ}WulbKD)&;#4X<-L(d8|u!f^oT%Ee))(Bp@jW6RWHu-Hp4WZ$LcraoX3Zd$HfR6 zupbePnAp&v9aOg0lU?*wXIdvD4g-0%+nHUobmHMA=eVE^vB|9yIZYF`B#q=gVhI%v z*Ee;OTI+y~hz2FK;+8u4>c-Bq4FL^9J#O=cguw`q><|1*PlK>__Oa|4AaAfc^yfeN(y?y8-0M-vLwAVopdX1V1-y;7uZPVG-P>PH60pGA z641tDi^J#<#^*ZkePZTkaP#`T;@v&3$XwXVnnc4QJwuA?*#n#Df!C-IA_aSRTK!T# zcY{a_+jzYv8@tB9_jFz+B=*)MfL3S{8*BO6j2RIX3XWn`)V-AyGee--V{?*J%_B{N z;)Kxwgx#wh4UC4k-R#jdOijbNDWRHy0j_#OLJ>YJ(9^(=Vz&hExbe6C5=0Q_EL~D0 z3(y_-Phcs-AOZ>iR!)~?OYcfLS7|mEE+kJ7Or7_ro7euluJ8Bnq@TKOJv<)`efm@0 z{(z2A&G&!5-=1%W{CQJsEi_OW8u7wHBgkBOX$8@VmTK*{B(M@@R47r!=-+Suc7Ewx zZ1{vt218rH?C_WCmejJdq{o)#^GSZJRHZN#EXWMh6%00Cx1@}w)j7oi3Cd>~n_MC3 zz(D!ww;8p<9i5$l!joN-a`}=?Db*NLLKC}XUFJ3fL{>S{r65rURhwJn#h)q5fH$m@1< z)Z~$et4>Vk?|C_TQw1fqFFbxM+zkd@HZtz8z zrJWn?r&*g*pfglq^C(FXy`j>jV?sXe3Dy$2!~&pmS#?^9O_D>Uo4?*8+S?1bGemrH zoT3ndD6gLLib&v2BE-yAsp^QIknYZBMmEBt=GdDZj&j9UFvE3lo@z7H9BIIE;R zV2FJlVyhO6LLDRc|I|~-PH1`X}A+Kax0dXeNpi1tlf~gnSAFH7Bt-{>(X1amHS z=MUv^+8vm!h`4oDJ*spd0a9L96qijO-u(jI?OK~R8-7eu0}}5Lf%lG0 zBOxTaiz?39j4STT2k_(i`-|u(a=^LA=KY+Zg(D_9Y|oE9F6}lTeW70hjUtKz(9=Fn ziB-JCT#l(gxFdC~0cqpz#0m6In3`)iH-rNgM0G4QT&B~h!zbs)%XC#SgDkodY!?#g z*t3Dap14wo)6WJb>y3sUVbGP0gJ&H{sy<6ob*c@$xE*nBv)4Vm~JoUJ~1&~H`QFc7<_y--ROoz|i(W;+K1*W7v<9a?#c}Guq?tWospY(b2lbd!KLb;sldZ@oCUJ{F> zV>tZtN^0}qms4W#m-Xe1$p>eX=Ni+Y{>NSDuID3$&q#wnck}Dk`NbV)C(M%kIR9J9 zOHbFk9r63i`}U=3XHv>WyR5mEV>=r?>+3i?a_7Sy;WK!Ya8*E>F=M5Wb!YTDjNZo_ z_43S~`7LOu|6EZ2AvyH<1YcQ6o~9BNWFQe{$ z5qIa~4N``G2|kwFe2U!V!24|ku1?Z;70!&d1nX_3!2Z&hELu1*=&}j!V}OBzc#R+e^9Ul`z$c$8iMr@JI4o=w3IcL9gE= zYzj5`z|+i;j&Al!>At%MJ9oxLI(g?6Q;<|Q4euS5e87?21CJ3*MS3}s-SLq*qoF_D zL`yKw`dlv)foiD5XS>IG!1tFKAF!*(VyvUDTYNy@;W@{f&I^| z)jjj|H2lMTHCI{iJZp2v<9#26oRWWXR?bTRgDS_U2Y)*{r6YLi z?OcH3uq7zvHG#xXe38$lt1yr2b^_(X;`~)gxj=gFWZT%ro9Q`(=zt36*CJ_$p|4g7 z#xrVuTq$ADnKzPCqK1=S=xsHqJ|0A=WHcjp9W(^~T{OG3mA!3M|D~PJJ?*24*96TR zIuvIzBdV9pr>R%fsa?}NQ#J~snn4#vuxS_SQ&>^Rdf81LL-iJ`z_f{y)xyRAu8MYryZ#?!!5U%Qk6<)XV+@tov?5NUDEfOX_nG1%xGL1tx3+}TTDz1eu=(0TovvLhKA9Az%Z za03ulspiH)3+6|}=&RARn>d!FlNTXnw!$&~e0_0=2R#46xyc;9%XPdSP)_w<%Bc28 zVp42{knL*(j1(c7V*gd92pJysRp@6XDm09buQaX(=j4mjj|V5hrEHE&Rp`08x1H-I(LfG!a;gT|(QbWEUgXJ95M)x&EVeGG8(Ih{OR(qK#$%9oBrj@_E$ZzwY0>9Cmn5RPES;t9wLi_0X1; z;~VP_qxrnf9vs%4!{1kmAwGRX?EW-ZbCU$;t;J|yOkb23I!-zz%`|->YY&#;l_**- zxAgJ)zk*^s%WsZAcHtQ_5`?}hMLhRI$ZW4RldO>KTOiP)s#9_;Pz6Ai{@p@`&3sy$ zt-%ENi^bbLER$W%M~qo(d^Tgsimt0LFjb?Yhckz(FH97Nb%RJM>hmWzeIBDLQG0Ff z#6^kH)iTKH?2=jPy6Y{-3MQ|}5dK$%JL58GuUi|gTGUyWA#Efh>F8?j)`jj>D+G)_ z^oOw$?z@}aLj#Z}~_{Tv*)5Dfa?R8gMPS66!jas87v|Tu%rdGeJbG#-BQv9FZ zQUmmVF^(->Lqu2bIV*qja2RZiV&d2M*VGjxYbD!(oKsu)$)ECUx)>nREJ7}B+B~^Z z#eJjFe!;T-PCuxP7NlbRFW5a+zF;@t)eQ_)ic;zkqliUIv(k{XMML=5V5tdXXOiVc z+3lY)|GC-y;FQjk=gvDW-Pd`az2>erNdGIO$o4?h_O~cZ=`a-q)=L*luQ}?5@bm@I zZkcm~rA{K?Wh2vtfX}`M9`Ht`^WD@tdBz#?7lk|`k*LV3(UA7$WW?Ds7s*?1&gF<) zN1#i`D^~l3mB8dof|BPh0m)tr@jG)gov1jc2Z%YWBWMoRBL=*|dD27|o0JHE~$Zc31-{CSQ@WOY%}DPY0=M+QZm z^c>urP$|@|P|}FuHInJr$=TG5<}i8nHq`xE7Bj&0rNu6qfeTl5DZKmq%j^+&I$~40 z+3OSckkDrQ@F6n2>62y@zuEL;f^C!WHP{A~2y$yUAM6Sx<$et#KqJy_|R2Lq~6+H@ZEO&Q)!0yTV4q9 zj*HK|i@KK9hpyqbh~LNTI>h^@hxgBAH2diySSs^v2P3lc&}5eHae_D`Fi*L zi5!dPdDL%hb%sZej?FPT-N(`BPuN&u^h6n?6&$F8 zcQ{0nG{xA-uGX!i?KwhRqS6+}ydD;nfOf=a4Fhrho#1U^MH#AFiy3^}AhgF??^!SH zjE$r*VT)`&=k$>1psl;=Qi+)snTo|(tLjFAXPnu)t^65{flnE9kW~JSw;rlNyQBAx zCrd*sYoT3UllM!D4@nlyl>_RpGjs*DO_Vksy6Kwnc24M(KQtTTkp(h`^`h5Y0H06r zL@mFmM)pJf!xd~HR|gbYRKP1EUu9FI8(70vqzCLe0b7+K76y$Qz_?M{-wor+=IH^# zcw*tO(sS*UqFc^JCf;#F(W*0d0Q-Gc$GhJZ%GTze5>c%lPge)#B{NUmL^fABrrggx z*M4{3uX&kItu%4n^ID8f+jVw^F2b)u$#Lu=Mpe@oW4XQbo4dCrA09JUyD~8jF2)!9 z0}?a?lc^OozVUYrt41^0w#SPb1%Int09tCQzx1qX)F|Ss9g(wpP@zOw5c7W%Z&_4B zBXAE$8AVqyXTt}2y9NiJ2;&cy$?5cRh_VGZf61Pi!Vow8;4c{)rR@Jv{cU=U9VP&D zHaF`S=TxBbI9jG78qFR)-9VGD1=8H$Fp@*rpNXZIDb_YEjWA{zk*x#Ut8t_RV}d@( zO8PuXO9zdStx8OcuOSJh#hh*8783trJy1gO0~$!abm?)iRy|u=TKFf-oYw8_+T>W# zY0I88=Tsf;PB|4VVNNzhc)kdXHPnJel&M_GjEXAjvdeR}E&>=GJ_wVGMWIM#Z5fjt z=O2CdBPw|60!;Fhw~xhfxOQ(zH?l3PLDu&PER~pfZ2?23(%E=&B3pw6X{kDTBT`lo zzWIS;;+&Od5mA^WRA7!aUb_FT*>3@>d1QcPlk11+3T}_%^-=@w&(n-VxKX05mVKm{ zoOCikpM`r@Gr9t<-N`uma?k~3cb6*(H1SsMF_cyKMo9E?zGXg6}Ma#fu?Y@g+RSex@y<1rDL z%xLGpmA!d=8`Qriw#_5nzwex;MSWe#N{s9P(dSsjx?P_h-e((;X?b&TSlWUmrPurP zjlE5Rlw~5*4Pl7|B#BQuaMHVo>ieDeAC7;VeN@B}BlGmI2vKaFlcb!S6xdkVZU7o? z0$Q=@22`4N%z%wB6()>2PH8Mx=~8fI{gl{aOH5k4R0R~Pl8+_r;ha$`)vMU1$v2a4 zS`4F_-?W6<3~tXEJalXXU~-W|6dV1+^SL&rDC7T|fN*C>iXgo_t?lhOV{9i9YMF)d z9au!BNC0_|B3&JmirWNCL;j=JSnP6ff76#_eLXz5;6&WuNTtC{)3)PAfe9Qy61ieH zwW6zjD2W(M9=US5!~hmHn*qCmb-RlMWHDJSa+p;*P`z1D#@4KYWR2w;5=B*2P4u$^ zADSpy6h!QS+fbc$Q&yIZ;;~8A1~sS@P=rN`7}o1c9iA>grhtnsh9+sAs4`s4P1!BJ!*$-ZExt`0b#9u zZv@ROc^2OaU(Q~@BpGh_p zj2Xd;W<>s1(>#KI0eQmHXdm+|?PrztahKS>7MtryP64tAf3;lm9UJ?MvBZ)~aB>}gow)8-SyY>B3lcYph9L=>PkI=~@Q zXjyIOe$=43(Xbe(FR^ey!4v;_a@ z*0}O;y2A~aFu2uWZe&e!6$mEg~wT@XX@X*;HvCr>D*!rHT+%6tJTQ6PZG z7g2Btl}C^kMVK>Iq*kzjL3*r*c>*g!f6SebuBaZpOt=5MspI*ng1EY~ntMtB$6CH( z@pI>4iPM~h_vDbuezx^yPJISuZlhoje{ogKeRns0bNB@Lza?&oO$e1)mzK3w*{}{% zfhwd%T>U3~ozV^H#@j)@303GojDD(Ks+oaLTdU&yUt)&^9z4wi7Y3H9dND3-L=b=+ zOX1#gG|Jar7)_5N5{L^|HxX0K+BPSRmVj@q!5c~g>tduD$` zXY`%hn*5Csn&#{Mx)TB4fOY4~AzpF-Qk1;nHGylM*owMD39}52k{YSTSc54;i}T)1 zN2b_nrH4TyW3@^yMFXOO5EfGzh6uYQjQY~oEZOZ=8hWZI{XrBN4c(DD-sbXjDO6t~ z(x3FRR*ZIQei?YgCqt`7$0Yxiy>yXXc*wbkvCQ;pR&Yz87?T)J1OxKVM&o3B^h^Wz z0g_BBC5(PZ3S4xn)ZDqm0$<6MzEYJV$?u3qn8oI{{2p3u>@qZ>Eh?s^#PXkH$hXO5 z;A!@s7&@9fzamEj)3UTNk6m;Fiudywa2(?hx<>o=ShVY}Blo@gOKrc zkkzXVM?|$8vJ)-h#$0xb>m>S4y1B_0UmUzG^7-FgCW*(Q!xV)u-Q{x*iuD5s?uou+ zjA-4ux`h8Lc55lY=y&h+vJ9D))5EDJ@`cAa*QR4gRMNvV0p@`6GTDx(HyE8YxfE z$u4Ls7s##&>b9>lqZ+e6tZ&!a-kSyTMo=2^!Lrb}$Q-pC<5jZXx@SEOu#`}yq^4FY zpb#~r38&JGw@;`EDgK&I&HfnrD^X8V*lcd4C$w&(U(_vGF!P`gS`8(+fL}jW|9cRo z#WL8EBP3%~Z}lwwo2JK~ig4{pWlM8qG!1rWg9Z>yP`L7o2Az8sUeD%JhZ94U$aOPp zSHIK(`pk>AL>MMqFLU~RMA9GaL&0h_(Y`?zQHwB5YZ?}wd5`GL6O;Nz_k@1{T98>~ znl7WAYiqwFUsRooLE$M!9wt0DJw20r5rmjS{>nvIBh48S27?SJ%b-rtutldR_1j31 zq6E#1hSD_j*Ul*=nxy%2lf)xbJ# zF5=V4QRB+WW|VmaR@2fa4U0s@@d+k7lb?PcB&(?P`(qw<*X-W9sJMYh%;r7rbOaot1+yeKAI zpilty1%hV`=>?-_Iy06>Wl76hG=A_uC06BDlO&*k+k9ss!SB-0TjcmB*pw6)&?Lqu6ORQl~ zuZ@RX5DVzTaLA<1fH^=F(0L|bRJHCLBwdgS8djIIxqjG4sj1xrfHO(VT&VC188#XvJ_dtgZFd4C z0D42w5>zGDmSb8z#rd-m0;`Aus&ZO`%&~$+6xIJTS`umiOEBP@Xdn$%)$vZNIXzX- zJfwQXlZ{v&=IrLzb1jM?vVxS!7A0SxNjR7|(0?Qgl)+3S_G4q&erjrkR>j zv&BcbQ9{N3wAbRM+|#%%C|@IH@>06LG5O`XpRk&rOR6Y*))RWD=8$g3I$|!DfMhk z<39Su^YciLp23bh^OJ0NCu{lucdfuox8bpR2T-= z(6f32Huelt{)H-5!pFh7l}m0{<3Q7&+=Xjv4Nux!xa3GcY&zsb_I3L0CO7klwdRTp zv^)h&`AXGNamrO`PAV56Ze`a6IQ5}^7UYi%0Wp7{%Of_SNlH07a%SX-Gp{r}HYv+t z)k(XG!?VU4nb}O*M1Qt#oF_n*jhecezZ6aG0|v7OC)BHk?9qy*TNm#fF&qpR6PX-H z(X&G(#)Vh``L{DjfT68xT+Ca%e6*D0jWkz%#R;L>`;YR2wmOd;9G zb2~_$=7=~XGqfPZ;kW1|Q3^m?II;)9xjPhUg*^Oi>X}40ABaa(w-m|bR_f#ClbOUb zt)UXubxE!QB|GwTm^uMq1F~udweypZwu?84(H^aWAJ2~8jrkR)x&b!tvU5sd$;jXh9BE>>T$_Se+$rN&%M zPt9!ZYi>phwVri;q@79J*$tEz?8ve_)4&;&nE33r7SF$aq~$9!qD^VjWGSF~v84J9 zMWy3fp~G87F{(fHje6Dm%$*sbL~ReKfSt^&65&T6j+^TPwI*6A#HK1W6@0K$UI*zc z$HMSX3Nn3PA3%oCY8RIym~H1S13LkEjjFE~gL^bdw6zVs<=2B5Mp^LDR)jurTKd2z z@G|FoTctli!=iE-do~ZtNF0r*+1)NCORb4+iI*A9Q?UNDCVlL8_SAGbg*&f?I5A)h zmS+~cagnSu<~#zvar-KZ_m{A7C^hp~*|}M#eLrc?v6}P<5P5%>VQKg`@sYIit5QWn zm0{7eepDs~^Kt@3mUCE2Gt@>*PR6>G z@nAL1|8izO4#ZsFFwQBrP^#I7TfA`)<6u{|V2sZb75gDNwXkDVE1v`SfJb@j0BL#e zKwWs_1GKB1W&^S>tF{1;A2ZZ&;JkmV*w%L7XPUmAL`DVC$>j${h1Coq!l@Mx38zatRLE*$|(MX@m%v|B}FH8^1iY5M< z^U_3qMTUxi)Y9QG%hA!9dHoY#mo9iUPswh8bWBW>BaV@IpEK3fI<9v_De`vpg!uRa zW!0qXm=OJ|ee@<589!!dGhR*~!DX}h(@b!6jD20V{eh`iwxFQmGk0&Z`?Qf>@k*Ur zY!PS;Fi}EvC)1J1HKN4!NvRR2O`00KhuJdZ$*l<0P@}kjVxbK(RwMW+gApvuC!tiH zGy=}ih2ZFFMBk^K4FJ}2MVZsr+5E!&w820N<+TY;E5HD{tx_<<+tyF$27!zCF`)yZvIHhw%MT)55wGUIN zRmIDM6tbp$&KAEk%v40|<>BVl`=}N?SsD&m+Gi%K&kM6I#aU3iGGA}p?92Kuk60t` zr0aZ^NVS7r!k16J{P)Pz0mxG6lH3lJqk{QbcW%5(Ii07<6_Ald+zrQ=8Yx3G)Jm+` zrlX+{{EHvT(WxFf=&9a{fA#m?v!UwokkSL9eD}p9D5VovIESgq+z81(y009}RuRrlmqRHB{%SOI`VX{kmZ$1lS3nc1XzYkSA9wvO33AGCva-z zaxV&~J4=EimP+*6vVx;OtN5a1w)|oti;*S#WX;RGk+G;}P4HX(BzLQ1>9LA779;q> zH92sD+8A7N*QVwil$H;mc%MC*5+BNy%RC?B5~LTdQcJ6(h~@k!uPi<;E;ym5kx3zz zJq06R)~@pr#iwUij$e2W$!^HvPv1uKc@U|H1P0BLyJvdwcOM&^H07+LAlf8S7}kZj z-L7Ivr@h@I(_c#jA23c9nY{l1Oo<7~pOE%Mre}&9!>Jl&lDCLL{A(l~)8mKKVwvs$ zrL<_F3!#s@T*{a@c|CrEj&Z$vLZG2{UPY!zlOhWwx60a6{8!VHu*uRY{sI>l z+^D#)tN0<^l;QZMZPavDqxr}}Tdq=00=n`;Mez067<^RiF>H!*Q8~Ofz96QrVMAHU zY*Z;l{QOm%Gt-*S4)|`iSE`(n!K7W4qw3(Z4oRF5nX2AC>&!DXYacWv;2BI)jl#On zVX)GH`Gt(??NarD^W4o>;C0$`CdIu1R-z1eTe`V3<#Vt4IGQ3bv~5akP>cBIM)h$y z=Y=?g>Oe5tSl2QeXT>r-t8W8okK9NN)F>NES2U4D_KQJ2omZxm?D72|nCixxw4dvsarGc6*jP}rMR|Je-r2Wgt9`93tHY*6I!3zq`usd1H7O|pOU zfTVz_?erW5`)>kGr}w{*Ze7kr(Erkr9%`vD-ozCuQ0SREyM|M9EZmeC(``S|EZAm4 zRauW&^oC9H4W;ijQ|bM!Xt$`dA+qM`6hwzL8~QrkP*i%%LylU=YXsSXUGVUB3-r+H2LK%CdAIFvC6fBv1oLm8$OeHb;s+XRLhPd@UYsTcL6J#o5 zl!Rc5G=GY)PX5<_GK-)PImYh|^Kt!P|1jdd$jW@VX1bLBppQ`3`)78?^;hdv0m)IP zYS)+lmLucPgmT)?atz;eru17^q@wSvK3K6v2R75YwFt9_(#t|0oD-eSooGaH(@fxx z9A-(sg&ts_21TI=4Sd&!$*HP1Z@Q_t_!u|N&tmzQU+9y$LJa+j7&2#8mp|Oj8(#2; z{rp(MF6(;ZT5s(svW(4KzGCI|!jR#m>FN>t<0hj^*CfJ@Ww^j8)8$RdTc*#$8VYNz zT7l_(gxkf$=9G5x=gXTCfo^cu6{ZMejOUH2I`D}{=dO(G?ULy|`Df{Ph|lTTdl#8UdHts|sWA~h%NWyMdo zrpRrJW_@{R<|0L)GdE8t_S^zgyoJLtkZ!H7)tbeiJss(EYO<6W(&f!Oy2IE|%kCEG zYsZG_{E!g>*FRN@)ORH4YcwN%s`X`E^7^WRg2Y5jw}h42W&m}r$$XCvomwKv&hrNd z){aZqs%&WP48T`R%yo^`;3MEbj-gU&& zTH&@Wf)VN#mdiFMOCM@59Mh$O^~HuF^OW^`ynjsCe8GxlTs>Lt$OsaD%S3rwWV+}t zWaW31ynH|xc3#wp9f>cV{4f)E2Kn8hG7xhz<@DagsRELZ}f&mpoe9A!Y6DK6E9D3 zSafYX@b=UjyOK9bwbz>5_0?LN+nzA;+YW{9&Ww2RL)B7O%q5tAtkx%U_fPX1l#TlZ z+%#3%!%hj;E5ksW&hiR!-|s9D>7V$GH3%dyS1 zu}QKj|3oJD03h+o_C_w_k9DN*ENT=K2~XVD;{RAzPQE*qD+Tn@^5GpaId5|jWYFD& z-<7hzX&A230NMLFW5(t0CvE%A^y$Z1_nQ8bAHGg&T(0jyNwvZsqsJraB2ATJge$kd zv_%(fYAlwD?V<4qwHN2B&UFViLKMx}hPAv^*>3HeB4p$elOadNPV7r6?P~Jt=*6*Y zESB9oMFyo6pH1W{2kL8OEn|XEQ~7{=+_Gd@;jft-zNKlf*}xy-#lb3)%T6z;2!6Wi zCeHSmHHrrb@24A{VxYYRGgro>BJ;$KPh*J_Mm>y8yQnk-bFl!(;{6@2&peTg7GbkZ zR$_3iBSjX{Oo^qipX(T`NWb`6 ztF(x|(@nTT0luEs+b+xIK#~T(HzEO8|8rl-TjDUoZ0z)8_I#y6+BsfgEigOeh~pJ9 zEC7V>7gBI~TMzX!DwfiZ0|1TE_uG-KKWLRzIwZ*54}(>TkdQ#_{`<j+P#>qMRw1%(a;ie0f31%aM@?Y1-x?2oR*MUd$ zpjgZ+b*&)-le}I7cEL2fLbhoQ1*QpkbF;*`C6kd2LZNxYWNxaiLKU-0gUS%GAg5jl zJ)V!MbNE{% zbI~HcyPEJm8Fj%f%Bbjeluzgbj zb7TddU!FK74eMw>b)aiB@*H=f+`&D(n_nc#nFZ0!q_RDu&XXr9s0m2TazB5@Pw4*i ztpYI9+9n04L}j}8j^N^TaOJuy!V&~tvRg0L;96vh?UDME4E*iZ&_hyVr_P*k1hnN{g&AunCvhj3W&2L&R3&diaTaiB_2ae5xR3(dqN-N$9HpoZvg1P-zQQ@ z#S<8P>4nNmF06aKi8=k6((q&czdmW`-As7ffyVf~;RqHov>pisZY%NXFK^*n*ltpt7 zokI>K*l5;1;;E7mYIN4-#-5N@vJr&{tISzR}pTt~70?C!F=CURC{1qL?ZO zUKzi<2m`ec24~Fz5o;L&a)F}edEsEXz{KI=pdZJ}1*$ujG4FRaK535{fr;pJ3j^J6DHq``uV0wj&N-wJ^pC#iJ`dYmmv+75mQYe% zCJ9w};Ba<6@VfQ6w5RX|z$S7|f!{CSABQO@-%q+;*qOSFsSd{kl24PIKm{45l;GM* zn!9u2&R+u7|8^`nf)*9OZ(MT$=eliOD%Y#3#kd0X1p|YACw_r9mATQNNsOKrp~lKb zn4w16*26z?NH&GSLdQq@a77(bli#qd+AcN5KEuYvGqZi`<06HDfc8W~H4oC7+CvEr zAQ|U;cW8XxXn@i%AEd)J9K(W(&_3QNVCQQa_FU+f;3N^`neFUmh^%wilzEU;(#{qy zh;{ZOO+4}3zQ4}Sp}$y>^GwAs%?9yyoV0m6)Rf+}P@?e~A5A`46& zW5dc3a!1v%7_DQPiZ|-mpRdvlP@|w4eR@@HCv6HxsOLt?Ah|7X1eu`Jp8MJK(F#nA zga`~M+-}O=_F5iKC&rj zF*c_D>#Cx;Oc6k*pWz_qY`?e8Pu~C88!|u^P(18yA~KlYkm{im+DHLjmgZlzp3=){5EkaL{RR#wS`j1|i9?^Ki%~ ze$eICvH6kceRt44aDX(^M-{Wf&z6$u^!TO$7B;)L^>p_C18TZf5v)whj!6h^tMm=| zoXfm?Ih%6;)_q9;M<(iP0BBma2i_w)m|kQP!%0L6^~r-s^FK^r*C@ZAweihY8&qiO z4ezf{1-v+IA}~StxWSMqsIZ=7fvACgQ+xAl*(-9Zl7=gg3+{px@@D2%alU}4IPPI& zl+K(^W!RD{%Ff$)g=FlqLvOCjQr)fEKJ5F~2m#}FiEt&|2PWWMQH&zP5}=(WPEoDJ z!)+tx9oWkj*E(9C^UOf})D7lhU((wuUb>9Fe?@Qpy!6md@>3VVhc|n4<0g=`2l=sC zahdIB6kG{5MPOEhb~P{aN}#?k`k))Ep2r(&C8m&C5w?uHiyX#{Yyo^q>?^;DfSPDn zS_-Z@w0`zl@@%+#ARu6&h_VQQ0AJe0!HSZ+3978dYLKO8iN94C3jDIh4rml|Y}_Bx zm|%~|GcQWDDooX+b!s0&o-%Zw>8oLNlzd_Lh+(6rU*kR=vVMvfOlI$E*j-{E5FSl3 z7F+S$;40tKESH&M#hBXhwi+~xc8#dLpr}3L7)(|aUnkY{4#6Vpzr_a&9 zd@xPR(iUu`*t4&NRSrV#?G~mm&wRs-dF_M0L}c1Y+Po)NcRu!J4kz@yMX9r>A;}{v zo3!0KGR5n>mRYYW51G?_r{jMOlT)A^T0YaHE|g*U$dkeQSJOXt$(*yNzpnqD{8BK` z|BEY5@&+|0g{%n8dnDWPkPzcw;GQ;r_`2={j^Yv{99CR^wzuZvl2qm&zr?6NX3eY& zweHhjq_chKSI#^;0Di&#$MzxvVr@|~rjg$Lt%}FKx@dwaN;+$W)>2+kXsX}@15k*VwyB3gln3QC z45|%y#*8O}NJY_Fqs1pbMb~k71~}j!F!ec(0PGi3lHIlMgzWmF9IOgRSUmw2B!>^9n83l$ zn}K|<_rSYlQ@b{CiIVl=80~CL-Djr9vvY4&hn#mA+4sLw-#DF+6*#( z_oyB3effne8<1`)=6u;H;wqs+hUDrDe@VNzEOF;Z(*I+!$^hYtWu{i^|K1?7P_n>! z?$hnQRJRB!!Twb;nfpA3E9$pBywL8JB2n&_0WR_rmnC#Bi3E5_=qSP|MBAu?M!PQ@!KqzC&xT47@ zV|{OYUFS;1CC<6A2JdG2get9YElJYE<|^>yHJM`H&3OmG5PIss+VZpiQmlO>M|q*x zFSrdaufnYbdZ5-d$9x3wVt0C`)kJnNhz0@p9lrg%)yn}So zgS+h&p4)X!CY2}ue%j*qd63JlM3DK48VKFZ3E1HtBN+0aLloHEuz2lfc#F$n6jwl1 zq5wv~{BL#$B*&^PoLi*1B@MZp#fhF59`mi)MR;<_OyvjA#l$KOu-jlLGPyjUrfXqQ zTUuYr{bQ+F@{$5?6)C>|2)v?5Owv6?ncx>CHbEto246vA1PanbP@9oX{N}SV%NLxX z@i=~LDh;FiZcF^>Bq_g93^9!AlQcc!T++l~NF_8_x=5q%6S-r7I}Pu0ldAjvI}VRe zAhXIWbYmw5ID*$@-H26JtGx^Hqd8&UA&3tLC2t|=o%KWe06j#Q^aB6KffWDfnQ%@? zn0$(fGn`k}yVEtl@Zz1j!0tqr&sAbM_iR|x zw$JvZqd`fa*md|npC9~TX6_Sx?@LiuWP{5;cFSWzz5)40Xl zoypnfO>=fG;#dI|p?S5PPA(W|zBMeF>AD8@vn+fAjVNpXF(~=KP^l6bdX7OC{Wynbc;Lcxe)!A=o7=f|r`bI5joWo#U)#w48SNmliAQ=6^bWg^<^ z5(?}|U=Yg`8wsLHOsUReL{ed!)j?(>{8j}OjGxKn9;fTg$gYS+K!L;%3+IUGZ#vYdf^BT8Lh}D=p_@t#yp}p?|M|&l6L%zn*>{{dqpJkNV-{Om=JE z8L(9R_h%#Gbrf6S$-$WW#1L0Gf*(YYytg1Gg5%s&(`)^XKLIA#DyP1QVsfSU%P;!= zMY>ZAnv8ADKZ554y8FxEcVE95G%y;WX>dh#F-ptdrzVB>-0!}*U-SK1 zMT+P_Y78c^sdtOc=98Xfi!J_cbq5e9enpy*V1hQ}jJKQI;H8ma32?cpYi^GS@!3~> zoY#HD<0N`;bH4dAseQjbnBa4b^>zmRo_*+4T{Kqe@F3+g*f)fI*s+^MxVnHs@3@EA ziL02dES$3Ph|V`q#a@u}Z{roYWYvsW69dpzKSqilHEV?t4HqQ0kuGvSAD67Yt#%_|P zQRBw8lg74f+xBuLV60CwZ;iY%0+mGuc<}g{YCqA%lr01H_==L}yoH;iH523o~x+{l*^B zI>Oi{Pn4BarGg@dnHqJ>>L!lDeH|ahnbu#2!zp9NYcMdG%4E_OtqY%)Jy|!O7y+8! zc9EZMK}glI%+~VH&WGxjhpUo@ckW8>A%b7Qqr7*-{Lcd)5tOmAIf!`0JsO9r?`rE$ z6MjFx@^}@=`UV}mU&VTI`w)le-Oz`6t=-r)CbCrBDY$0e=vepd_HtS_!uC*Csl8|D zgEb678e%9G_e&p?X+SQJ=YXH(3&Gd1GoB)(v@baAz;_H{f82jujjDen@m=`91)bF^*F@6B?Zr`T#DGnN-b*w{#(Wyg}e#W(~4@v7kqP}04zX!|vT$B4O@aT=T zZM-X|r@nEuzfOK^O=Lb=BNPLKWgS0GJVx9*27voq}G0XjSOFi=8EEFmjF-=iapb2ER}a9n8!Z0M7<>; zYGw59QT6MW)>3P@#VWOEgWQkca6(iwqe=0|G(XfwH9(Pj! z%(38Smr^g?3A37zqjgjC1f(mA!H>FeogY6let_JN&hqrvX@Iv}`M&=4#!D1Adqxtf zX>!oEA==bqlE*Nx?d&%oJZE$}&oR9aFYf7_?s*%}`;ygcYz#G@us z3Ml-bIQQE@MnhbapNH$>1JN!n77mvmKJ80IW~b>3scY3m2t>1ZU^DoQyi~bugqZr* zi8p^_y(4^kphPuGl=?c=db9WEq|n{rWPyLE+L+QZm|`tAtm!Cop~|}sIY4-X_C^0% z_m5YsNg3t9bNC@=^1cpN&eY|g*?-`@q=*!gvYmfD5}tUg%@Gq~_ID1jBincjA;M*@6f=#+Ab=xq`-D`lU& zpI&OLrs7I!#xs-k3Rj@4!UQe%|isqFy-y!%=- z-)H%e+Kx8*)EXxTW?fsv?9E*^d?mo8L=paM7cNmExI9twgLtHUKlyvpHg0%M@dnWo zGIyju&OWvKP!O%L3==%O(wtAi<&)%4k@0yE+CO!{Zr`g0D^1p)i2iwRLuNmD5GyL! zFr$eQ^ctXfq!f5A*>~UWtX&VP+{p-ApS(})KU<$ztK{kAqp9~-oq=U-xP`Cn%&>pa z)FU$5kjtNK(P0q=K-eml&kvcYkFZkwONM^E>hW)m>~>)xu;a?iBcKf0F`*6-uYO3V z4kf72m<9YO=yXud69H#{y9`31JToF`B4c0$$1SH8A#PXCS1VVD<%M9jDD`J0&ruX# z)HJcEkU0ki5R(Qk3348dq~@`Wl~5>xaT75kLP#5>T9@+$5Nu+M`~F{X;mIIEX;pnKaUp{Eh*3HebcdTTEuK$RZ@QGJFb5Z(j zm}YAWID&=D180~e^Oe+HYR7l4UGAt}#X_{|h3nZR$6`?wA-~QI4%famIN@2B5DUCu1Ax;c z_Qh}@`6tlJeF=&Y7Oq^sQi(I%RMh4S_(De%{O3`1@k{h7+;=V-V7uuXmjBk%W42iN z>^8rA=~;c!#M0%{&qf+D)CO{t2HA3o@nyFachSMca(e@>XTKZJ_uBgN!e*W~Zu61s zpUeCQr7VH&Auiu8+YI}S3B*gTmo)2-!ik$C3+@yhkErd{kBXyxE(V>VTxEiA@WJ2`cZesfjOjmdulJ=>U(|TIE#5> z(n$3$i&c}Wa-gl&8 z&hk4N;e~?J#&*D>^KnanEvfN7I0;1wQaJlmb`&d)3so`|Y44f5@Z^N1?xZpgui$(- zr}@qT##~oin)V*7pj`DrXu=^TmrMKpZ3#z-+V8JQF+#(VeeaFfh+1e=K5QN&nvMAbYqoQ7jAtCf2vD{zpuIk#@IRk5q$<~_cnWu=Nu(%xVF~6b zsH(YQo}G&nX!~iG3)yC!g%HwNh3}*bX>!x%5e+xz6p>nJK?QG%y%W(a`&wTX#0@tU z7e+>8Yo&v&6eBu3Rxw2BUQU7-pGtWJN!Zvk(rMj5O5VmN`nidvCk`E**VijO^!Te5 z^`??9Bsqw#8p_e(`u#d$;AvIhl}W$#LrBl}f#1ovkwxi8`nP*R&+E(9=8t}%;QJJh zXJuaZ5*f2ylw4A-x{YSvX;A))z7=Uz($O&{9|zXi?{VW;e5AMKTbqjYl33zc2U zq>qH-V!iL2;H$>`GQ#iwPCkslOnEj|)c)r@5;ahAmOJ_s9wkG`M!LvBG_uGt{(?zz6EMG`{ z0<732bScFW>zFNJCW`U2^xG<`@DC>f+L_-VH@&>n`6z~o6)GZr@|g*EFRz*C3XY$)@3lN_BD=xP#%gOvc9QVKj?Ra()cyY} z!TE{;VFem2#vk*~t6r~FB9j6^8D}OhW6X{xY&_{~k|}Pf=@}G><4W3@If`ER5$s@+8<#6Z+l5O76+8;!Ea`2*&N^N5Hjf*H#G{GjnE5j;;W6Wb?ZcZOL5p%J7 zyM`=Mxi2Gw8j+*j2rM@{tR|?Z-KN-?T!aOdN`ttI zh_O;@l+&`-o1U-xb#P38!93Y%8nq7RmlgK9qQM?i*XKy~K4EZ6oUw;_Y6#z`+<+=Y ziXL8$i?Lewh4HBQF}c44y>1xd%Wi48cqtkONJPscI{hDh3~2q09+!f1ly*pPZl@cJEduM!d0hh@k~YR7j^|wX5D>RAG}3Y5zIYeO()2a=H^$M{ zi^mM|I}(G(84E3KqQc_ti#v0Tu>h`kPGUFx>A~H{wcn-DTu;oOwX1w7V#F5jFp2!y z(b3T=jnbSo{yf9lpNy|?(1|F4F2j8_!e3Nl#c|U>ifE=7K%+_yS z@T(FytAbU=8+xYq&34{41`9?H=OCbUId3dE$`A(u`F<*K;(Bz71wW-?E3HjpMw6PP zu%3*=3H#x^sWrt*B)eYnp`x|fd!o$(Gh0PRvVRz%>Sf;WzAO*Pa{s4wq;?N=&Br%f^6)_5BRT$(0TIpNc&f{u@@@?uPXF?X(`m#~S06mGKH?c1*fwkS}kL>6Zq6!DUMNu8kY_~CD< zc_f_Eu{g;>`X=NBcq!_fXWpJ>VB;y_?~XiyX`uL^j5D?3iB1S!(xCqikRy2RAywpq?Xr9pLJHc>qZla25#yX-Z#{~ zr0B3q)2ErbOd1!f7#q3$d@6~cyfH9i8f`cnYQT@MzAv`*)5=<9Pr@*q20&*=ayM`K zJ*}Yx#$|tt)a3#d{Ekl@0Rxtz4C}4N?Br21hcR$g;wV@+#zwm(Axa5PZEAD+^0P<{ zaTIUBo4pc(tC-dvKcf%>avPTC6~m3gXdoCHo}qu0i0LN_RhN1wb~IS0%sFBQf5YVY zwU% zm#@_+7c9Y^D*5gdv8@JZe$JS;#(vbbtap0qXRALkq04%2XI+x<(vCgAoWVa(%bclV zpHQe6x8*>d+;I0)>u~#@*ITd}=IsPm5Qr56Og#YFF1<}nKludUir9FQlC3QKPr0Xbu$m9Ee-Vt4_i8YLp`QZpQf(}~jYk|2b(Rtd@wRN}(o`dE7SM2WKf zN`UN0b?OTp(mv(<+_e9p^mD>==%D618;~~1N@i4!QJ)DgW*3}D4q#)E=9ek}6T*;m zF;JLcSKJM-n6yr@2{S+=CR2oxI&!_FYGX#|F&H>RSqs6JC(PJ=)XA7U7D`pm(lV`` z)QTV8#U*ea9GzfpWtB6yBOWclIr$w@`-W3O)vKWD<@9s?yu#UOQI~^tK>g$~dm8DW z$#Qh7GjlCZskqdN`@fwqa2|y%nSp1cK@9Jk_=SbxZtd=vLiV`h4q4Q?`l6yQ_1jkl z!9^@?6cHiljt2klC3&)0f6%9A4yI?;f=)Pb#_~qXBV>!~rOmZ0ce`^}Ri6lGJ?+L6 z0?fE^HdUTbZlkY!n9ciAHe7L?bYZ;UKo#y3W>~*UX&IH-6ck~$OpL6Bak4+fB}ED6 z)HT`$MnDGw)F8+kKt#vuCwzt`wz1Afj99`ngXXDd7w&j1QtO}VXK00rA}G|C#<4i=uGk_a*z(e-3Ba}K{KyS|~ldYte)N!A%jhSS7S2b(L> zI7^%)YXhp`&<(ArRaG9h-%;6(gByr3G!j(%4ot_-%KyVEUVofjX7{6bPAS(0 zer=(l5~a92?QxkA!7T=HMtAUPH%>BULRC?YFceq2rXjkL-1Z<5#l>)M18pRF zbKugPlaZ*|as#Pm>8_dozq5)E;5#R()`2z_TCt1^?3j=+0031|0+5HUBC9gd@!io9 zB>GVR-No+s%mW_{LqOaZt%ZWo+S>Fm&-zwK>AC$#ZB>Kp30HG(e%DavokDuUHx4uyd)3%mEQ(V;Rv-Nz{u_K&jl{0dT&z zUW>oE^9GioL-dN#Ny1h9;ec286~ZbQD8(q{AW~q~ov<}R7dx6iQc}J22^cl40lFZgiIuxbBES^VWrZ*XEq@0RgEVqhE&nqg#>wdbJ|U2o)CQ%XDzj z!)QXjxR%X0VyOW-5q2Xx3!`)G%T0ahjRtUi%1aiXyeCB_h^{!yv4U85eIsmNc)r z{Jv4SY#%rm9F6AL+*uAAb&7MeQ6;kQ-{A};7=<$_;6A6+{`3^oEd|TEMy;o9tCyB# z^Y{v3&}rlABCcDEM88`!QLvzt=Nx-25!$Gy=I3a;O@`hyPTMo0+>+H9kMKsktWE`( zi2{kms97(!uQCEP1g27#j|h3uy!7lb`7wTyxuA(8Ezomkg}zVGyi!nQ7}8w z);%Epz}{v%lUFOY=j$b_@*L|hy`7R}YpJnllayq8Ype>z$muNxI(*b&5nx(aL=~Tu zByG%yohDx=cDs^I&+w46&GY_VWYy`b&E3ji^?%HkP@-TWQ)v~trsw|gAo82TNRa3c ztbGnJ8(IkmKpm$9(nKz>oQ&xELJfVsDE%n%KOWqmBYWPMaSOc=)7 z-T5e~^YJBLdBb4yv696KKeryO@y{(;Sk_&H-HVV7WkutcDeDthd-Q}z2idCcXOv0H zsKV0=D?M*Z2;%Z`SF^>AytT-d1*s7|jj@7O7lo#UIQUE8=>i)*|egypuJyn5k`!0 z$}8ZhG+bel`1^N9X{rY7?CG=YzERiH;C22;$Y*S92D8~}p%1&i_+5#k4M|yw8?5}j zd{mtnfIXPK%S_Sg=6E>d4bli*%gBCG>3ASw@&$ zUVvFq|N6ZkxGV4=NXel%eH6QfvN#cr6{p>pQ zZJYd(l79Ng59Twx?mj;cDEcjNK&#|b+?_l}1R&I`Q=nFAJF5o<#AL4uqE@oXOkn+? zw9P2#&u zxyR>?UgW=uweZEPaSX%+HG-J+?|mv#2s;y*V%RF;nI$`~6A;-ulI1DQWzKOe{>0?e z)F@|x^-rzjtPL2+ZFH8uM3{pjmu=|A_{B904z?#G12n>Zr{5K*vXPkfN#AJK0|yg- zO64~_b;`kbVR_tMvN}ieE}yp;SsN6qkVNJnqT)-50{r4W7xu1a;3}Qd1EbA)U(Xf0 z8Fy!I@#7PL!{hq!u}l%mp0I&00|$?st_iJ9{9?m_e*ruN|diD|@5s z3NNdA?m4Tn03bjuvaM#k{hXe@v_E5h@rb@;?Lj&99d0eBW%@#*>$@+W+eI{BD)RSQ z=(ePF9@1bz`j{@IjyNbJbod?XL*G*?KETDxCS-6&D&uX6KtI<_7u?x!=K8=A70BI? zYWl$V9WlDXrc%M;1fG!^h`O^wXta*Xi;5TX^IlV_DX*!UzBYa!Y`5LHHyos2O>kR&vADirjWb0AEv%tWt3 zfWrNXkSRG(^%jLjsN^{2sERLZ@i<&bfhd_Rf+C?n^l?U?!&s?)#oQPXO51kkdNq9` z#gNbNUaS35*VztB`WL#N%;aIu*QckguSEW8X?6|aO=seqPW#|0N36f-&nGi>U);*; z$QP&?cDzVXs0eG(KzUp<}!Otj0)oPhnZ^t$yKs5Pd8c2;QTruw3Q?duYR7e{`a%vvUF#WCg|gK(*ho&XS!rNXWP*;L-7fs1f_gwJU=Py zcmiuwm4w< z2J0DR<1>uEVze4tZ$^XwW~u=GC$CSD)pGv-alS zkkDtM@YA@yt{wJOvCy1jYd=BF3GOa9&hm0Z|H5Ca#anP~e0^$m%|E&eWfYWddMm%| z_#k{O%nDiO_PJ%)S^~|+C2R+h-vboyCBdcm2m1R&R#$90OT>JlOC8a)sUy zb#$}_9LoV>b8(R_uYAvNbi9LIyWK1PoK%vAU0qA(K(@wV#FoO!fn7(pv}#oa`!ryu zV@Nz84Ccw@_!w`spckZjc;4nK@Nh04rwZEPm9%+BpYi3(*$jQ-0=au^d1OI?YyGYn ziD!C4T&)zIb*9zEd9f?*t+#2)MbG$B)bso#wsdv#B6rYU<+z_YXZy-I&d(K~uAbvH zz#0+8K9zW*oO=_WVqH>pKvG(5iaI<4e4gPay#e2ju{YUTcPiJo;bQ%u+b`K3hij{x zC(JG+gu6wV5QY@G4801zn-(6u%JS*KvCAe0x`&7Kur*bGH^fsnlbDq45GZeyPFWqn zDc(nNBQf8GK@D+*QA)kVx+`6l0PUy~&b*Euf${K;R+zcUsQ0!9q8MH{@A$2) zK5mE)KcrmOKWa=7X|dod%tbO+5SqQ^`ZL;4r%?=5!$&r~cdAqB zusUB`mX3@VUL~eK-&uq90^NJyrA|EI+jzE@>C3Lkw^Rq?w)v}JIEgK3sPvN^K@eo? zi+Znq;SEDWg?2t`gKf3@0GRu^>=Y@b!X1~(jDVZ6WsIakTCTR-^|p58s^`tRE#*5= zHJBY8nZs_><&A!@U>D>?sQx?CAsWgP3Pc0E+Y7XT{|*=`)VtY*kZ|`+4%_Ywb;}yF zb6jk~3HDHNeRqAN3*CCxHA`&Hg9>AffBP*4&}$6sa{gYlMaPIIbe+BUwoWNeB&1!~ zZspc9mys^Yw^f|ljqav5j#`d^t&`daN8Jo@);|U!m}5kvqU(IB0yD05JF7*`$R=Nx z`0#w#S$lYEb{38D;227caN5auq7zXns8*>5TOm7kYr=5{41cvY-iE!FF3EdB+=zZz zN~Dv{-v8tJ!od79P*9!!8-r>vJtS74VZoUDaB24_!jDj41{;lW!YT8gI3aGt( zk#_zA+mrrNtu`0BwGfY*EC)IL{@!e%dRqVLD?{(~V+MBql|cv`&)XK%=36&;%o=_G z@gcRF;|GDaXP2EMHxA`BP4ZNr-jlW``Sg~h9qt_dGDlT^cYR!-IAqLDmAyD&<3$5i zq@#+lA$g5&ZojH^v=yzgK_K?$@43~^&8H2RejwzsJOl>jzU$!?@aG`$a&e)rQt zy;H8q5gXqR3PK{{^_mG5FCeJ-4&S$EIe3K;)wP8(oN&D)kmHUUP zLWORN@43Q$uJZFo`167oFo(-f-chEX|2V_8x_vj$fs`z5{P?V6ZGmWpw0_6`c!<3f z`wdUe4f)R_%wxqxaOKCB*J0%DWPR{8aGxW>t*XF>Kk(LU*oV7B&;9YXeVYs~fUX)-aznHftd8~p%k9jy z@W#0D1u0S52A~A4XVQNjG%ce27PnJd_zAbaYWg4=W`igEeD}%+^enW`Cc~z(-zRWJFUZ$L`OerkX9*5@pB}Ig zsOBeZ8{zJdAHt0D@msS_xcP8+26L9G9gKrbK~0Kr$6KF{(akTt_T%_a&E^Gh(AE$h z!x8<=_r_X7Eyx4ck6{GMg@Vb&yk%DDRHR)`&=a!zjPtUiPVFq zPzUSeURnPfByX|_fb-nj-RqH)>7XFGn6n_5NPT}{%ZqP2W@qqS0ru1lrL{`Fe0|)B znx!bXEcbL7|GEz$0<8N!8Lg_%B~8%wPCM<6ZJ>I|d}LDa095Va`x zot|3B1cD+Mq;AB2i+F zNy5;CAm?{XQy?p|HeNN_r$20#Ndz}oi%aJ5Zfj=129Z}?q*~`FT3Y(;7J4mfxSFon zQG~h4e1o|oY6&1)m@(xSs{A3-8I0=;Pomb@UCGiAWQHu8<*m*l1FLV5SJP%RfYBx0}`V^i0rc(f56 z%DvyRQ>p;wW14+~&E;svnfX)m zJDw`?*RRZjVs!E^yQ%Y?(ytZz6AHoAABf7o=|cZ{FDkkAFObSNdG z1!DLW`KlXMwJ+5%fB+0_4uFU?W1#5$?NT0rd(^#?HM(e|0#EoTBXfox?pIic)Gpal zrcQ`Iz<^YkCZ`S^RCr0x-H9gRSK4Q^U=<8%x&4jEjthR9mtiMtDe5IIZV7qy81tA3 z2dnBxH!lV&M3pZP_L*@u(O$IyXjq4>ff3*${){q6zjF33mvxw8I%Q z)V{~!C9Ke$XX1FdnM~QiTY%tLYBLVctYDTWOf$^EUyw`+1&MMk>*sA~ZWloM-eR;` z%%OB-O4L|_?rgF7QXbAXP{YZZF78o_m%8`y^JR$b7fb;;SmR=EAsdx_KpWrBb2F)* zm5d#n!=Qn#RPp%aK%ROZod(YKlSpt-a>~ z--3T=AM;8qK7$nU<0mq9XJrtnwVB10OVy}V_lNQjaTGn|e`1sT{9wsr+8(lRs>KhK?C;;E$Pjn5)5CM}mxZpTZ9Y1VXdt`aw7n2gh zJAy~Vio>P8DmJ-_P?K;rM6^H*cd^Df~QSP07`JEe8q2xiTWojE*d5v{+%J4%hL@t2~-0TBr>(~OJ= zAeqv!k2Lc(JED9?-AwcU&_?DuyY99pghoUj2|w#6NV{k~7c6RMVEs^Axb2T+Z6kg4 zP6>N;7Nr}nM1~9z{f;k}XqGgQjZ3;q3jg5~`4+Ozxoyx$cfu-JDi2A`Nmpan_$_SE-T&J;53D36#8^xPQAUHg+ zn&L~WvP8d3roB8dPyejL|UYEtOIk&H?- z$O#LrAzXhiMw3|lStrsd%kvz5iy)qKz@*G~739T|auRxf0HlS6HK_Z!a~!?eY!wv@RJyC5r8eF~Oe-MZCG#a=tz;1mCws4uA2ItRpeU;$OIm@`|V|t!Hat$coup}zu9{v z-+Z#srJQsVkM+ZVd2|+MJm`>P*Xkq^Bn6C6e;H|2=t2H5{4hY+zCH{3w*DoZZCjKx zQ;u^0%qQmdF!< zp>5pQ{&D*rm+61@N-SE{(LyLmAw}OAroi*^a6~)7va3O{Cnr>};aW(5#~H0H_^Vr0 zSzTf;CDJ=u)FBVZCHXF(4>;n|S|GFv??#hO`1tGH;fKza4cXvYVo}0U#eReJ7SsQ3 zsTa*VsbQDO=iZ*#;d{%tQ4$s$8a1n!HXMtoK1O%Rc3{_TYfsqfhBR=Yv-d=V;t|cf zzfEfLof+VH5Bozn9$vnR^#Q}^a@>qR?g0(8w0)hoGPG&?u7w^(?$Ez3VDxsXOtqDb8sgnC26mo8W5ldl>e5_m(oFQ`*^_S zA$lwsQ)0)wluVKrFt45(C`sh+)i%yyHmowpp^s(m`=#AZ9uy(S(K*dn2uw3pKKo4i z>t~YZ?=zG*(V`O3Py*V5!e{T?kth^9L7ASFK(!nTYBJ+C-BrH*X}SWyvGl^uvFre2 z9$5LjDS~_h6R&8E>tOW&_z{|kTN!>T# z-jTUrcqu1%5Tn$#Z`czi^n1q!4@N^!vx;Q+VHSy&2f71oaOiJ`$odS6|iOdo0{4 zY5Zl~-@iusC9}{+HbS$(D;s3os~pCy4uMdMiYZ0RAxh6B>Y^bi8rw?aw9!jl)-(;X zc-VY}qRs}}Mh*)Hp1=On;lQMu`puR{5XN(l;J6S@gqPV>IhH$5#&(`p*351Tr6eH| zb`92WpgN5W0R#d$U_j5D`&P&_tXu56aioJmhSVmvOaEfVY0MY_xA=m}X_#f>=SScH_F)mlNsu zI2eHiA;`#{&{=C%6ymg5jDJUB13x zuzZ~8VV{WrdN;&dx6yw3;LR9qWTv0gh62~nVm9x)Ea8oH^NKTrv&5mf znb?bI71WRSJkCS8n%>Mm?q~?NMzqLRhzq;LKCC`D#dp9xJs)sQPn-}$JFQN!D6gi2 zKbYjf)%OU`sPE|cX|?BLM;9*#{~{Ho|vJ+Pg0fsb)k)n zjgYjHJuTM@5B|R&)~YTMAqi8X%qMfX?AIR^Z9N*e?zOG1W54VBnPvOEq7d8;K-bxD za=ERn`0WHNSqOV6(my?Fj;>kx1d~VSuM|21- zv~l*rg;TrU0}3GCa~R?0yrxHLB`?%EkcJ@E3`1wrUfAK1FGD$4W~nG3U^-QpyN}0i zWgw~_i;KBcrVsvb%w%yzKd+Idqo41$v3Dt(642$M9Rw~=Bo$^FHn0XT>Q1-4;2f@m zm}=`(ZX^HejiE)kB}gj9;~XKe*pvBf&E%TnD~V493i5s$X_v~?joOu8H`Kd_$qQL ziEs{wrxQ;G7K4XrKP89FM|OAemtnv0Mwzd7>l{H9q15E=hS^bUu;9S@yC{7Bgqo#W zV9C6^F<{|GXr7j~V2o+PW}841PxE7Zt@U|5m8togy1_rg!J%AZ_l)CdKc|VL!n`$} zkqaz`8EU7k)mvxIBl2erDGiz}ox!RAKf~_>7tMggS>!Y7Zg1lg+oF+K=qJK@}1G$y|n@_&u|a3#V~)#0J<&pb%Htq=2yKajg6 z$L$}@w$C;xXLM=nGOK$uvCJ*Z@51GyfNf&P!`qZW5`^a%>sZsVesG$Q~W%j(3 zKYe3sQ4DZkQbL6a2F8kfgm~kA(_rMW;E2JbSgm0=^AiA$)(A)jL5aDgw5E=i-ny#%h2I2@f1lsEgNPR9`9%Y zq~RX7LNWZ&h8zU}LZgH^uHtL~Eo!H@c5nys-H917Uf-Q`C1cP;g;YE3Y7HBg28U$$ zab#IQ<`4npQ8?&iq={(ZtB8Xo!@_UfCt|5nOPHKhhzm?}tiQCBkblg%BCH9j&Y29y zoZm}cRb3b+Ex1#33~Yt{eJv9OYQ$EhRbF`+mZ;)jrjC@C<>ypgxd$X(uNPu) zi`1BcBhE9v(uW4i2lr`I#0U4nST4;Y%QXnW+gHDiouAxBN>mbLUm>W$$bT9KSJ4K_ z64ad)QB2Q=G;)TGR);LI#3+8|9{MDD`!4UagffQ8t};L#CxP_+@5`r1pr$Gq&-Usc zOVg@6(=kRf!g&~!~C(NuYm=IAQ#{f_g8ZSRS!vGIsPaj*=kM_1~&{a9;rZ zMTCTlNC`}ej1baLGg!OTVogu9sUF>3kD~n(IVUqO)iH`JE=imO*-zr2zi&fDgAYDh z)RiB|^g>7u`lGpXiDf!+qz7sy4gr`4mLP$IPGdN&x+1(XZiSYOgPRLCh@(20F;m&$ zO$llRZD@=1uSI}+x-Bdli=LDWx%JU%&f4i+mr76*5-{X{ZGk05jhU*Zs{L2s8Ev!6S zbGr9bv-A`_xC1ihXX@1S^TfXfObWsYM&zZ5u*P)M1l(V92cwwCf0ld>*KsK;i=WX)AHLx1LZ(oEYwLwSBQT{!$9yAuL!qS3}d4f5>44JbGF>WsWBmukSUHsp_{3!f@`i(*a z)m``ef+G=%+Km>x^7?n;7iZ&Wx7gcp3K(S^W1^t3k2z&^2_sP5H;Bh42HgyB7O?ALZ_I;~m7H^A z>|mBZbR+rC{M2t*FG?zyX#){kZku%D6j%{90e@6v{W_467}|3{ZtMa+HBO|O3zuC!pb4 z3qR$v4i~NmoX;Y!oC1dB8Lrr`YN!lM#JY=;ufMP~(Zzr8GZU^6OE*dWU6<3?ka}R} z3xBI!Zxq1T)qihtIoQ8e)Dp?VfvzqG zQ<3h%s<~w-feIgN!BCl7n}eD*Ao)JDbBSS+eXRBWE&)FA8`J+KrwHzz6&v(BBE1QB z4f(|8KB>AQ^Sd2!tYT+Win5#xRy!4b%uIrbQ=)pC;;+xRsTqsyn8eVK7@P37jL>%| z|J^bqkm8An!5&0eT+;a&Vq}n0jNu~cU;(rBD0X+s+B4rlzCu0vcLyh(p`jBCLhzGi zK|FEWrXD1*cKZ|~Qz?T(|8KpbGVg-A7n$?>5D4l;`jRCX2~*A)c%bZ=iyG@>b?fKW zg%BDBba^4H(2k0?>VFgc%5rf18L9aq30T1aD%9%rW3R!;#}Tf0gk; zmjZCOPpdBc{Qh}OGpHvyw2=xgY$9lECqW1b5@XF$oXw>ycxglTUjrtS%(PIO?NlYH z7(t{?@rmLs-N9PifA^_6N9@$GPLO}`2;d6lEai7>3JSX~DzGMcFb0zL%xtXv_q+o0 z>A&YA`PQQ8#zdFHb+)?zU7_qCr~brRXDIKi=rU}=nl`neo9L3uV_TFe#fx%&QSr}s zW((YTh^nwmlNqg0Snn3RjV2=?M*_Ny1>q0Zun-hN>+fH|*X+Jdu^M$r__>Sz^9i9S z41Yo)kk)wo$1(kjzYG~&u)*GNVqIMweogtn&ep85e4kz8gL`A_r^tdF9vje@2AfLi z%l?}`};_^BZdD~1L)vs-3txAVCYkY6IfFA*!YTNtWgVIa(ou=G6e=0o`hE&tIF25r8Ep)16r`lkM<*omrNGCHK(A4?O6%T8a;@nI z*86pG$L7t`bL-0Amg5j`LNh%NQE2ts)3e@A%}>|c(qdvjhpOYIlZw{GKc3Dd(U=_7 zGVp7bJdu2oG1x6Vp;b_3tkht5czDeZ>)zfG0{$W-U9}VZBO4#@?%P)$e(u`;rV6~L z3eBH@fZ+Aa-p_a&Yc!TtP!uMzl!At5}b-`kHfNZTxWy`M90R4 z`HBQt_urP(D)rVj){_2uib*G98Pp~$p-*QNL;K=Eiv$@pMKDTlOZOoXPb!8#B$}u) z(`t+gy`ZYHBPTwrjlRDA1gMFJH`?I;`lucn4fb6um-l**R3vxmZ5}sNNKQ`f_(Fpy zL58!;TD%5+=#%gqD=0Y7Ao|Wow`zy1TqwtPXuj@qBfIYVu=al50vf7x2N)~H9YIqn z82Njy@%Qu2h@ATRMAcHYyXK0freDp@2NWMDfgX%M%eZ(tp*OSXkF&j|Xi9$8fx(b! z6o{IM!C>pUObH3hOip&L*mp!*4ggu@RVJSE`xaZcFf1`X$(<2PV&d&Z>1qbv`mP7zIYNS7yF&MlcF;snheL`|FVNLn} zG4+*EQGe0eh;+Afm(n31ozf*O-67rG-Ju}e-Q6u9AT3==cXxTu{O?`wdOyl?80O45 zdq1_$Z)X2VvoQ#sx6Rm2-hi9cbOeW1?z{cu>Eh|_<=ti+hu_Q7%SqRN$Le{c<~#IS zlMT^m3d^Ze=9t+gNA|tkNMdpW6cWn(WJxBU>J%}Ts{ASuVnrEPq1u#1J!Kq}{=Mr~ z0k0dB)@k?u{w(6R;LjS|JXcM7vqwUlTlS8CfWT`xG@rgL)Qkvk5IktZY|nx#)13!t z6>ogPdxxW-xVU(!q)f)aflaTPyRia%P;eanzrPB@|B)7Pd}3l~e?@!4X6IL`iMjb} z0~)zs_9*E?h$uerlfAKj9gGIC0D^@oEG&%1XQOOfN=iyS_q*9~V@=$Bw|&Sg1uZT3Qb;}SJdtCEi4S%d z2A4c+`RA(AEg2caU1uRIS61~l%Uoa?d+3DjrOEHv$*BS$RfBzn01x`CA6*FMParZl z8*03~y#6L7ZhCrpWtF&!@!{gN9vS_VFy1xBhqX|HSf!@*W@87}nY37ldhUN=A(e&A z?AP~~le+)Dj@N+{EKp3Nl=vtcm-jr^zg0Xg$GBAvixe`K7$hPIxY?*2P;Pr-ppuUU z?D=Z25V2PAg#A?%1-@~N^WFZOr%}%pw8h;&IKaJ*1(X(`3VL__Z z@We!MUY=;A@PC!;OK1pG!}9U3wD(cF*?xlGpntHU*tYx)ReceXLJ}UERBkYI(1a6+ zEHZ3q{{pS;KD!V!F%9kFiKt@wsGEz= zSbz5tPGlSdmD^zr_!pL;5$wl5?ArIEa$mjsb_=Ro%F2q)$2d{}lP}be)f9K+LGgHH z(Y&0>ZAV(JUP+080A+tMOy@NAe*S1)eM*&G@{Q4eJns!B$}pCd80xAe9cF~_fY;+y zs}8em`!Sc`{jg$D(Y;3HX9+_?ihA>jd=wv#h%JQB|6Maj<%Kw#%EQ~*8RX9$TZD4_Y>kLtHPU5rk-WV-V!=<1Sy z!@xt#KK);R=uZLrNllFgAEnM|S7Ca3y5;$1xfT3x^aVX-@=8whF|*08a@X!siQyj6 zW+M7D8ODWXMSV-lw|yYjQy7X4-Zq{bUvUm!0s_B_Yx6TjepwK!&7&>QvarNy z+qQq7Jl7gBP&-jprT@5~hTVc4g-KzpnoB9fnJxfo$c<#Rg`k(~q686zWviF3>x zSvjU(Xb?nhwmxx!!7=TARtrnZ+^VYB#KgoG(!l>Mo`W?Q{=EkA;75A16lm}o3cM%Y zWXGnBElwO$Buy`*GDu}j-b^EA0U~jr6n0tQ&T^5k^iuPujx_0Di6V*1q@~92xtL~PtgcJ2_A}0}EdQ}X{=5mrY(bK^Ar2F! ze8|?G3?JI0#yan}tv-Zns~X)sLNowJlLF@a?r*lYPwt`(08{7oC@|y`qrMb?_jzeC z5l~&8;}Cl|*UukH%)1;M9%71Kc?5wcdTMKrg2e)V;IHp&#!?T;K*|_CALNwhvZ>B_ zPmVSU*beQYCE*NhEPq~({P2+RB-vlkr)oT}tw0m~F5tzbu$!P2f(Fl#MLvf+$UPpG zCv!bd_CrkhbCar(qT42s{>q^jLRkOZvoA_NITO=y4mX;FvioKX_Z`^a@~*BozK81o zu=rjiWh?3G##9~Zc%KhE?QnNf2ncj`qX&RxLwP4RQ;^FPs?Q)I@O4G0htv2w$+aAp z{97nRsGtXgl$4aqN;{vZLfMo=P{od$*T>zuE;IG)2t~t#6z(PRm0gdQLMC>pSXinR z%atgJX)q%Ug??GgU=Q1;j-vnyw2z|Xy@cajEYR3dSC{B@+L_|E?vv8cz**I@fmGG? zV6}46)y*KGywK*t5Fl(I^y=h3P!`tKTUlNwe+!ZnHm+tA6&t_U z*wElbUAM*n#D3ECXp6`6Ssav(?x$^*)DKQOzQ>fuuTWBagbM?dacHicc#h%tBC7yn ztPWn$)zy7^+7;S`fY5g}#(-VG0E6ozAot@=>I_odBP?S=@3=_?L z7LPa8;y>$o{j{&>2R>+x>b!VSRm)Fu5>4 zsSsmSmZ_GriwkHaXsPh5I7rIs>aGjJIjH?T$F4~U2?49NWUL!g`?6vj&Vez`j+S)3N6Yq7A!!gpgQx;$A>e%P1bY(p}JY*(G(8AK@ zPQFxxMO7WPtlEBzAsiT{%l`Ev0y{2Be>=elfE|9czDnOb5=>O~7%JzH=i#Dn2oAYYw;gYWvk+3W68pEp$Ka93_qhA}h1uLQ=;11% zp1}9@;C<)j?0g0`%H>S<3yyzU8lh3`f-hdpZkAUpzW6? zLwCPlcjo5@0jLsz%b-5Fw6wJQ)x@tJbT0KOo#BiRPLMt~JUqNV|3Y6D$TuMg9O)&!%;Oq<~SoUKxeEbqJp0UYzxLgltu`T=?sdfPulY+9*vpf|$N zh$1kK_SIEj?{HVqBNdraR21~~VQu87^hV~9SD5h4a4K5p-yVzk9W{63H$b1QI8AK- z4I?WmFE5{W9IexAbu^Xv@&5gLL;R1`maD7nZuKU^iGt1TuE(E2y?V>Y2t$5=PRSS` zaJhgW+`T?AqbM|{ZPzKmh{tEG--RtbF$Uo^+-vSZ2CP3_=5-})ZEd@6Ml;hzM(2 z?#kP6Z66+4O6RU>YfHO6oWE^deR}fd&+0T{*+I`;az>e-di+O&g^0(Z_iMUPHezV= z^<3U>r;XbVRG+h6c=t}ds_qw0Vl>I_YgxA?dlUDw`9@a16K??X`;l2XCd=0av*X

5~U0sV{a>~j~%*?=fDXFY9y*XMGp0=|e`TBOn_wm>p{K}(++WdK6mewt- zBDvIQyG_Uk&o}&CqU_TqN@9m~&ckWbN|tvsr{w`|2ks zG?Tje`c}a8?*>?WUkS^~B1=d}==eQfKOJav8x2I_>NpJGLbd2r>3OU)*{#P~rs3e? z0-#LKz#v7I5=n9EPfwc6d*{#pnu=_ zCW^(4pLA&3iafU+jS4kdRCL~cla_-+rD&D+6$%>eG<;f-!{3lM>_$Hj$Srlfc2dnP z?Cf^azEtH_R-#HNn78Rv{eI0)jCQ$T9Ov+`UwjEbX-$f04Itu*-W%AZ-D4JkB|_o- zDXzcmUMHK@dR&?Tr~tp6E@5s?N9KF?S6M^t15h{hf-%IG+90*?!)eFmr^AhNp6afL zcSKy)f6Rp*36Sv^|D>8{Nmpv9;l>RGS*Dd<=I7=Ha7^%H18{aZ&Ij}l3FVfXr7vJ< zM7m?OKp}^tD)k@euiHZW^AnnwMsf&fk5Ep#K&!>J906(P)`T1J4uG%Wn zz$s8;fpTEmd9AMJ_v`}dNvf6G$lGF8^YM(|>*q=^3|T!{u2+RUfxYAa2_Ct(zkzgON#w}wfYB+R>BL5EoC|0jZ%HDxz z)@ytke~Q04^#bxhs-O>Vy!Y!V7m{?QeI={<#g_9yqSBI*KY;Mab=vS`Ds+MG{>F1b za;c4VW!yLsiWdiIYHdxhWZjmRj}H+p=y?f#%=XXEE3AEl`0yW^E%p>bcfIJJ)>){# zFaLq<_IrN*60%hqb(FuVwr5!yXHN``d}9DuUak5$!(%7)>BOx&zo4K%e~1CJ!2XC{ zZXqsrg5S^>iFg_9Cv6O-uvnrsj@vTe?Nn@>brmIq7LQ#aZ6!ZWaH(AMCo1aN&pfh~l2P)aniOGFF zD(=<`HMtsSt)NI}rrWlaYCLN)B$MMIB&jDxm63ER2u^Q}z5W)!3g;CHuQn6j;PQ85 zn4E(niSM){DKHQkG{si{RJ2vqgX*td`FWr(1o`&RPjUJf)W&-6dq>~P^!0)#Atxs% zm2V~xzISmx$r%Hk{d#phIIm>YBMbJJ#P>6=sEN7znW_6;?W0zkv~8Pi(F(5!isvf? z=>Rvt%N^D{b}=KwTeg$6OG-+lDo=;Mz+*&+yI)O74v&oi*N+u&W?w+t*bV!F^_HU_ z#K>W8oNp7HB^;qAt$~P-0v&SK6@3SYT{3gI5#eg+;hd~@LF*x~|?*cx==kDygHk^3*9eJdFlhPk;1tS*~ zVl`L|oef8XmTMLZ)~^wbeiECisi~NDLr^KH=N?7ZRUu2EifAzq zSb-X$CjuiN&i5KY_Rr6FX#1R8t9L-GPvbrXZlBR5ZKVrZSP&36sAg?J#rOV;tZy)u z_WoBoH~LhjA!#CB59pxan;rkAp$Bfia_~c!g-{pb(6La%`l;!;-cS$rq9RoaS zB%>p_6^-A7D-!lMFMf`X5P#KThhq@?2z4SWBJv8-TAP|^N2k7mMK;g@DfHn&wZNDpFe|yD*}vv!Ra0-qX5&3u#kyB1RP=kQG}%>K6krS=DCyF zaD0h9*9plyZ`era(0;qw1 z+4mA($C_ zlbGOpHQPe{$YBEer!YltWM?cLygInw5bS}4Rwp{(HH2MzfHHTZ+X!=@T?lm~SrIJV z-^Na9<9oDkyV9BpJZ^iF!rWz>9Q&U{{l$XUZ%IA2Fx%SNENpCG4G!lj=_C8VCth3^ zgP?7ZILkCuRqh%~H#%Pi?A2`vWt?CPNyatKRbdMc)w^~JZH@ll%KOob!{8G1q3;x4 zoS6!A;E;n8jDZwVQdVYkywvD@U9K-sF+pTY2Rz^2LDy+X+?-|fU8awYziMG3?7uc7 z64%kii8t;`dUK?5*$}F!sr?@U#F5A?FOSO0%TtZ9_-~ayNUtA|r;l1K&g2;pz~ZB6 zkA$6Wem+T@>*0h(glBMTnp|j#+Q*JOZ_%A5bdSbQ6!ed;xXYzS0?nVC7)?cAKW=o} z2mn8@N)l>k$y->Kr<6+sd#8UPL4xFP5$+1MP)(7Y>+)(4gptUFNq|>bmE+td~N3_kjK1$1A;-;E>T1uvp%N~*9N;CX27DWd~G zDpn-NkXq%Do1vzolkAd)2oIQ42qAqH%N=32O)gUuNURwIC8dx1wXM}RE7`aby*nf1 zIk=Z=O;F{)Z$p3)5lo4T1aC``3SSk*z3vU3pCL)6+{N8*Ih1)yrL-POK#<|$9R^*N zONBM3EMc+>G{7~l)2X>RIBH!OZ$W)Obcpp1hYK!ZQ(69@UG7@jIUKP~FU);3v??`i zjQT@MSgSm&d0tgXcb=LmBrcGG3F@}-L{&}A;h?mbv~~cz5726a#kBp<%@^_(QGzXt z%38gNY30+z$uW9PZ;M~DILsCP?`=?XmA<1lAMLC%kvNBoa+;g57oQ9vT=9Iuk$9CL zM_T!TW3T4I!_A5Buvr~!tjEVm6q(QlC~yZ79UUFKR2IKp^=)|b-=9~2Tq1Ba7}FH2 z_eOkF#^FqlHT@he_#_yN5q7=v!EsA!Fq$CgfsdOzTfm6Nln#`~DGiHnz&1lA(d=M?8C!m)6FF%Dyo3%*b5M-v?1X~m+1t`BxHP4<*z zUwjNS96pB`3eeh(0D<7i91l|Xm$r&Wt9wdfT4wdmlFHF?O=n7%Wb3Cy!PXw=j_Q>D ztX|qs8h~d4mKHLzzm*roZ1i+@4!;tbM~^?aCS|KTZz}U@*gvneFer46JaXw#kR~`} zrieX{^^w)7OqzNq7MN<|tJl_*XxQA2QyB_4cbfaUvACsI>}8QB7gKm{wa&)a*imiY zS&J}IW)|1OY?N3Fvi*Ve^p-&pw4d?U88|U9F;9Ti6%`eQD*8RlFlyH1%tsuL3=2=G z{--nW)1BBzLOVY~rKwvXE!6#2>`z)Y(VDCm1Ix-f&ias_Hr{mq0jyi-kG$pjL!v;k zAqe}B!^BkT9@*ad@9Z_1IBUq^;^{SJu2huZ_$OkAnrbyPG}aqRzK#(=FRO>qRZCL0 zkl4S4;x#4vl4HhG(_q9k-#GKTD~tf!ad_;8q+zSvBpexd9e_YV$)&OvPGs2SDuwI+ zdzfDVV$_dKhc(YbCIF46^!ANVQb-iL;;Pc{*gw9>TMWH2B(kS2_8 z%)&7xzeeQN+C3S`hD_Wd6TMReVkgdD8nC1V1rwx#FCyWZ)WagIJfzFB*;%_Mvc8C_ zso|L8$veCm<>KV1ZHaQALbm56d0riOHCm(0oTB=X8CuFDFwBh$a4I{($<2xurtzkc}WE#H4^*R$FSW#;IQ0veb16DakoFWbk zsmNZR2gaLwv7_h0NA3j2e@kv8tB>NZn)@TP6$Vh>1=m>E9Ga+Ty>9e{kL*P7A)7A^ zpndVYWq7OLlAhF}_9L`RJ#E>I!^c~2Q7iRz)9LeY{2PA(eNRu%2j4>=Wq1I5i5Mc< zncNMGXy9D8rzoZ}(2=a#QYp;`^66*E(IsY)V+7}vwn9W3;+kV@MgCsX6x~4r^NiYc zUcl#yECGJlo67%hC8VhF^1B*IW|kxoa*uF7#$$1aQcFbBwD~NB^cYpQ$Rbj{3Q!7f z()3Ro-@>t>C(PqmijZhVSk}Ogh-LV3Xhis|Qfa2jx9- zAkZ|b(vJxCDJ`1+6NpJd43zCW{*}p!B#|&<9~7X;IdW3=u}KvU;q9V@!mWSf!?k?e zXt1!_dmJ}rm%rp=Uk<+Wj!Y~h!1A=2!_Y{Fc0gUZ^TX>j1LqM)_)Y6TZ*|o3K9_*- z!{6*ft2CiZ@1ud2f*nUrY#LpukPC9a4Fx*OK5|G~Zcr{ZEsq`>cnxv6lXuSQpvHE?lt zXW2MObmwEOaFF7aaHo%Ky~jC~5{C{ng)neo(jrm56aD$I$#$dqzNR%VihR+6S<$Y1 zo&4VmP9n2TU#gf5tJF{!svHw4yOp?JbxzOUk(@XFwVKgkq@Ljr*|VdA|39VRMK>fQ z1azfm;$q`keAyIc*u-AS$DJe~ZbHH}t9JTaaj(r4;6OC9W8gzcTE-F&CVga}l?8R4 z!}O((j`Ng6g=Q@!%?^%)A<)92$%L{XN@8*{9{5*%Hq_PQGrV)odV?i4_%RibM8yz# z^CY4)+g+K^`Oo}u0)jB))s%yWYq5Mfn>**(t!Geh5>Sfnc(Ck+khLj8bN4$Rm>89C zI7~YQmn7?~-Y&R!u`t}#X6<12iE5~M(tf3RjY45@dR5={zTpRA0!R@5f1i^wq&jJ)rSO}+b8X|G4aX&YLNGGQoqQKPIJ-8RB1k- z5-WcGBJ{X8aT9rkE2^ZWH4Mb+mdBI!;nC5}2)e8VJMh@sx{P&6mb;xDGl&D5%&eP+ z6)uXP=dq0oq2)h6iT$@2JTKCQsAIx0ZjV1m3a1?k-nw%@yLXVdcVw25*?H2P{DLWS zu(q9-(dkw4>V70sIfwTTDJuK)gev??JWxRGn(<#vvH*!5j=7%9Q*RII)m_U~v?M}6 z(LVl~XxS4%M}1ZDg~0p%hZn&TSOZB(cyysB`?4+u>Mt)ZK#7rl*8TJ;aCAEl=&2T* zX`j1*XaE}DFA}$vUce~!_x7L?=|&sp^`b^+Z*i(YB2rBS@ptph?O7OVWLXXYp&8>V zXc<}AdtfCc$(+Ad($E+JoI#o%2cUsFiFajQ`kpWbfE>T0K>>Ls{vMz=KCaw?K#|vE z4)$=5_{?t;lmUmT3_}ZEPn~rl?(Vv@MyaUpIuN*k zeWPRFc!<)q1NKhB`UF7FjIRUSBLe-qDxBw39tA z60tfu&k-0R9VMg6e~7(hdG(!5$JHZ_nErc_v;@!(=G5!jSECNzew?|b#U-;+?-t7y zo<7+BW$Y$NI4W3Ss;IVFQxAt`^-5D+{UdA3Kh>j9R3gnTZ;t~z3FVTCilf;Z?Cd+3 zP{Xrozh?#-9BVEj{pSM>0zOyk?8ka6S{u{GJ+z=JOb;mql*qKJR}C8xs>j11hTwZ1 zrO*0hu0qddbad1MAo}k-4jaDeJz1w7OAVH9k^ekgA8K{`K8xITTg|@vtX(+Z#+qCH zj`=kshwl{;A3|i_A9Wp!{Y+%L9LkM94H-iMeY)7nE3W${>+9eqhy$b=*BM*E1&9JrQDglD;e&p&dN!{cYi6MCe~iYjU4PO3 z{24sb``HJdTGGGBvc(#ykGBgN12!WKo2jfAiyU1w7^6fPH|2nT9FHu3)`-XCt7*59 z7VUeNn2z?Y$YXglIj>h~hD1M$_Ye!`zt-4_Ip8YI9qeSj|E8+WT_6*OW(rKK;ODV9 z)!Iio&Tx~wf_m^xsf~snZr!Q|8Wv2og9#n$a$oW<#RZJm=W!G|{O$Oq}CL^D_mXHm}9G2CGeUTwdS` zg%-Yn5<_bJIB!&v0&j%N;oPg?u%~L@YX%&NzfH@w{o9Tp*ETRP@SoLW&TY5$3!+#9 zsTaL98%!HKp73@^d;nq&`l6oW(K(LUl-4374<0Lb>PxAkHmj<72Ju`4Zddw2$TA*j zZy(bi6sN6inrChsE+P<8+KlBp`2%TMr}8X7-pYR3qLa(yZR`$X`S2;2e9UyHC|DZd zuqB1+a%rU@j6{6J5J&d|oO16F1}vkj0s8XU-pS?y%c~Lu4!KZ`LneOep*Iu=l9Wd) zxUhNu8%H_t9ErU%FjLac-5iYBbjp6z zVbQO);2Z%xWH^k>H+6w`Yw*-Stre^Lz1((B0QIZ%g|uzUm>eo@CO{>E{Kt6=44!CCDWTx|*EA()Jo>@`{um~j1PfQ2 z`zgib7$s)kor_Vgd9(>>q!~vGa$CQ-&8yXvj+2`)2y+zN@p;0ujYaI!o5*&?G;4fQ znV*ct5F6sQS3(x{2le+*$LqMUGdZN+5TZ{rjslKYB%dA%6gD-rS2ZB;H$5{$z+v`_ zqM6KUzW|JD{F(|`=p34N`{-y7{JWM*pN5oK;IM#E5Kx0FbXwWBZ|65B(=#*WeSHO? zh`4RHa>GcMs+sLSeG>(CLPM8W}Vr_NMI4$f;$`0_Jymv2P3p z;H1Ru6}hpXH72FoR=rk2N=?&v8hA*Hbsy3*p#X)^c2hq;88jozTPzu`u>H#v_dJz! zm8ziTDb7a^Lv^5+MjdepB?+04&bZva$_e>BIKeHe<&P zsocL%CLrA3--lJeS`1<}oK_5+@kp_ZCB0xjN0)suiDd$rY%m9E@4~PM4GQjzA9LYKu3VHiRzXhocq&IF zQG{zmH$YFKQ`~{%EXe-d!2_2b64C+w_{CO|qT~H`N^y~&+tGpuFqME9`YTJ|F@72K zcQcmNae=`N3}?FozCZ%89k4B@KW7q7PV30GTiCF;b`<%G~gfppTRx%I4+ zV2Hs3+U-f}F6p@7qcunm5(8xt1eDx6*C@7k*)q;OG8VomRBY<3t12hXWTW*fC@@Ba zR(%xzEHtZnjQD^74UM$uK*rq8Fgvl?s+|xXzdy_B?9t7y_ajevgyC>eorJbxE0murEPE?6>r8s2MGu8=J4QVRe~mPy`s50Nv>bl3hP{CoZ0m2FXYU z^$LhtQo5H3&Ma_^adC0IZ`;=e_HH(E>23JFoNYbcMDc#RB8$w6XDjmuvAE;*!{Kx` z!fmMW9Z0})Lhz9>K-eFIm7s_B97gNhj~nNCfQickq>@+mJjA7?hQpJ+mdy#<7@R+- z_J%$@M~FJU;~CqbA&r>HYouJsYyUlm=*{I8C4`A(63YIw=9KByMF+MNqa*_Df_+u8 zn`zirGg(5iI9s0Yu=JX*#yZ5}ZTZQX6A$ee;Kp$uXPe?W}a1bm-w$yjDMYZ;N{XVA(PLNJ_E=mX_y$Xof*jK9Z z*S{CM0le>c`+Y}eQD~VzI&tgUb2@Vd1=dv-m9nzj4^Ab>yJt5Ko=xA>uww>eeIM!K zDQKXCMl6dnKLU0DUJHW9fZc)b4yfKFoW+V@y2xDO^?soTFn^u}P^8Jg_)%@K7Z}JH zh`!bBo;r2~d37xivIR%nnfC+84r{eJzXj(Yd0#gaanaJ27zT5wm6`P@(?|^`#5z5$ zA|Aahw)!7M4fh{01cbLHFzi3M>Lyijdm}Iqk<=@q`kaYExlCx2A4n)*Y>qQKnr+{F zaT|(QkeNKr`i&fdjmehVN2%?7=SHk1g zVByKM%c!Ts5qoj9711z>(-~Mz*2xhE|CDwbK0Lt3j2fU{RvAtIVpW1vU6~hmX}lEMdeyTd=r3_N|f_Kd_NIe*fCPB zka`rg_68d-wXJ$Ww@4s}vK~q!44cEkPzySjI6VsirVr~o1+rv%P@lNqqJsWA#LEaQ zV|7Z=WU7y$LrnR8aaa^EnJ>)hwhLorbqLD&2>nyo-)W1z;fYsYfoo)QmRDh}Db>FX zX|@`2lVtkBIm%>#1n?V1&7MRWSq#z1l@&P`m+M!Rei0S`rG6&fCj|lnm}MBIPs|&l|WzMlueiw@1km~`k8t8 zo+aDwjmP6PJ}{?50qA=HhBICdBVjHsF8Va7slHE@kxphM-$kGDS{w;*@| z#R>#5@KL}E6u=meBQz%U^B*K1OVx(PNz;eP2L{DVXxILaSy^I5sUp;*6!@r^b$!$g zFv(-koqQ1uX&ImUpygnhstkX;*NMb#J{ZhhW^>LbBWsgkztykEOt`Oles>^+7AH;Ja%b(jvHVJmr#Ij`vcXs;^B*RV`ANGdO zmDs&3!lht^n<*MZZ=4@2*Oi8TD^tiIIiV2-dr}fyXjJt7B?rzcfJ4|)aB#$Xq5HpN z`m_EP)#s6#tEW{w^7UYfVqAx@uAp(|pQnMMHfwiDBKgsm8+FV07J~%m|Oj6lmZ<}zkJm;71J@suC ze5Ve=SDy()nrkeW)$BK`W4FqNKG|Zc*$2LF_ALu?a!T;Njs6=}iTfAUL{DE9z?UDd zOsD%ZP|-VagOMc?Dwn#L(CfI`O{0DO?P@iSPxeCRL+5E(e@E!IxY~{UF!jY-4j(=D zM?ca16Jsxa83_qkY}t-qA1n#?SMe@iOh8&%s>|>LFin)OFf{p>q7|`+M8FG{pD03uJCQNc5s$TNYSM}E0#ev-<)bF( zBD8Xzm50F2WqLB*{G)XRdLQ40$BDJ;O4yt{gFz~oXI-AiT{d59W+u}wnwJ}77AMh; z&%1Wyql?dZq^OutLn2ePA9VIU--2r_I7mTi*bs5jna?$h>aA8K%#;$sz|M~%F-~H* z)qqvA_)md8nYMY4Lh$$#0de!au{LB~ZJlUkd-Z%|Ht)VVa~++4MOQ}Z!4B#F3klS9 zfJAJVv(gRT?qqFoz<3$$Q7Wm27*UVrc>&ZFo+()k;m@{|`Gwn<2xbhi0 z9aU6*k=SD&n;FV$uZSQ(|8#_+vM2kXI%@2()sms$c!^YF8Xahy#&>e(_a@Tz@5Du} zk&^ecn$Ev5qMD|su|A2Ok~Bp zLu39OyD+9fY&}rRZ~!jOMw;DpMU6Ju2SZj0X`B&YETqo;d_$~hmV|3sa%;M)JT`g? zc3}o?@D0skwm5xYO+`=<$jlqKzBy9I2>}e|%B`8^S$u-2qbEf{M3U-#EqUk|6_bV} z(08=(6zXHxTJ<-Q}pLonvplC9~;r=`O?@nqB_XJB++%=(m(+xbudwbQvI zop`Z{LBSU-r)!qwg)pE$5gCr+LtE`GF-Dt8p0Z2FVlpun=h#q&YC z`?0Wp6*nN7%dXZdhM5suO#mR-CL z6UmstSJ<}(@5hSIZ=&6Q+yf@HyNgnx9}Vrw zv*q?7W4{&M#C;`t6s^9n5O*MzNgo9*s-W<9blC9wB?6WB8HV}Xt)C99#CQDfNHP;d z-a#cf%5h}SM<^^UiOO|eXzR3`sUGD;-4qdu*7A_Z{u@7CZ$}T7V8o)$&q=c25mh-( zXY{z%ay_Y{#zUP_UWeYoh%2@t+W5&AQqS_tX^g~{sRcIya91w zAj84qLIZ7)X}DK^RZc@58C<#WylOKn$-0TS(aRc(f?nqPC;p+Wjn~S`3aaI9BWieL zuFBJY>nt3e3JmDqpiGD?gE@tn z-@jpmrKN}chr6lwg*+?NL#sF{e}ri?7^I!6VrfY0Q#1IMoO2DDzBNJhM;Oc%RqjG> z#_Ow-gG;$P6zR1${lxxEIo^2(ZG>B0yEm}AFURwfiBvX?BeuJf#O|*gt$enmh%d!j z12Jb>Nokqn#P^^3DSiQ39D~Lf0=W@OiVK*Z5?K^&ndJ0bKl-`R4b;>^W%=AJf{7q7 zwh+4Rw->zv=pDF#1#C4X6~28c)BTzNaen;4$aJ1*bY>_oXknv$o$$S_H~EG3C#RETc3Ffd^K5KSXzkKxw&?8i$$Pd3^t{} zLS%d&W4XK56KyK1b$!rT!E=u@p62nkc--%sh6aD1kZ)UTg)`qv6WT|Xj?6DC*`f}X zuZZTXw?c%xgK$0J)vobEjgBkBjS(wO9D{<0U^zC5Ip<@CHU%HXNT@<%VC{kK29kWD2` z2wXZWiIazjZQlD<$9 zKTdI&`07X3E0p|8pWw~0uP#mbAG}v1+~CuN=FUHSG@}$PnjQfUZpm0(!~sfJQ$eu@ zfyS1RiVb`u2ZI)-u|Juyp~zGRi{s1+QQM=Hp&{!|hj#1niuR`$PnjE>@vfKo442A< zb~$BX;qf0)tv5Hw?Hsb@^gYAozNKDXGc7yjiga#VJ#hmfaoFS=y3ym!38|@T>#O?% zJqdZQalka(jWai}Fn_f)K;LkK%QME(Z~y#~p>neRD?%m?CV)y;;((s|H97gl?Uv?s zG$|&CLMKJmzjb+JGk)t=#US>`LhiX>45;KJWk#78n*(!zDeb%37WL?%G*b#O z88I3kog#CO;d|p$M1rrJ-}k%BHIpM|tju=qGF~M;nCgR(c~!MY3n=V(H~-L*->QvtDn^|K-R8#~ zjz;ky3x+&CyEXr<@B7ow+?*}%?V9Zz8opW55Q5w*Tm|}O4W@rv6^G~5Ufi>XTLAj1 zVZZ(?b)`SucY7x~rsXmzhG7~X)fdBc3?RJA@esrHm=R@Y-O$h_lVV!TxD>_wG}8Hq zz_7BAnQvn;eaX%kOpbZ{Lz0OjN}!b8ZW`LfNLei=!Wbzvo<%D7^Cy|FzS>t zoW$f@6=xSZd(1U0dug$(Eat5GDpqb{Xf1i`EW$O! zVyOjLvMs$rno23|kI@4d83&;n;dQ(oVE6u#VHwCZA-lm10K4Cw(8k)Pg4T9ajN9|c zJ@jL+eVmI50y3s$;cpTHM+Yv2$F(b&*K^SCg8?%qz>Z?Og5y$qZ~OshP%#0{Yj4YP z4ptxUZpF|i3DuNvNEGJ~2FKc?otV1<6B+H;qu)(Q-yiI1HtoTVxSmolXKY0agxv4y z53MZH{pIBR8jH$*Ii#&QuQ!6qz21MtCdl~3A8{=xzU<0SE8HG?<|Dowfkto@y3RSg zm?l)HC$cgRy*hTU%ybU7yF( zflUXnatg(lInsovDG17zuaYIoSdwByD z;>5dqoUq{!LBZ*K!+e&+5O2wbaTF5i?EqFd0>yvIERgmI zthsNZ&Q)rs@RC999q8`E?B8HKw@)H(OhC zIoL8@mAL8^NzR2a!vmxj9NzSgs-grs#)N4=*!t=q(UK`&v8X4nI?-F>C6&BGguk1K z!ArI4n?=-hp=Ct$um9Qaj$oT;t+4U=bH{_{n)eB&RgmEL^K^CV*@{Xnw!tHj-$t#U zz{oNS|Hu^q9h-u3VxFR5&%@|7+u4Z$I_sw4N&~yoCqk;IOE}fK-5@q_pAQ%=a$9kL z2Sy<=6!1uyS-S2hA*Mrh=M7(AIv8a?$+in9k@{g2{qrZyd_pL@`M8wo_i;*M`io zxphD4x*p3Eg+grEJFqcFAX9tb?(J%Jd!UD-0gILt4BK`ioJB?={b$zOuJC~D#(edV z7W>&=>-eey9f#!Nu$8T`qzY>0xg3h*U{34eEqQQYDuQ8Dvr<~Jfwc&iLRh}nY7Yi( zVyDGt_IUEuO@pyH&x7{Bg%zz;mA-;tseie^l9!$sq1$T+$jc#cRTV32d=k4+olE#| zewpF&vK{@i**K5=U*MtU?Fr=?i?*zUJgTuQ{QUc`#IDmWl$f?u^8{N35guD6k8rcs z99uAuxwM~P%rNnRk2LNQj0%I1m5ZOKc-8jpMRVF4gx|Kg zZ}oaC&2{8_lV!%zK8lL`WW?rk!A>UFIUaa=3(Hj}1xpW7Id zW2)mYypmd}qLP*8!odFoZ4U+%AoIrHHlXLZ>pTBfoLpSsF_jaw&ikLh$qV_)Y7Hhs zz$_EEf#}TN?iw(a7BoG-CKlD=m{=+QovIs=w@^&7IjzU^3MBo@{}7qh!O2|%V~)?s z@X)UyqehVE49E(^S)_wYTXqv9Ng?+1;pty#IC=q6KhokLaP=1b1^lA&y0Glek8-k- z&0g>s5=v0&l!1h&D~LEuFg6rs`vfhsGu|gOGn@fOJWBF0d@I`#rutfBk+lXNG5HIdjeqhk4HZ+^_3;XafG$ zdq3P8OnbYVSd^)bmQlGDP0ig4Ljq=z&q zF_cpjCyItst*U&(Anv=1+ngzo%IiW%8;_y+Qr~4QC^^r8AtqAzci)`K2nHk;R+7Wh<@q~a zf>@gH*AQh$J^=er-gvW(rQ#r-si~7@Z4b~Ui}nI(;2r?b0w|UYOt)KkbVhdGE3| zwf4Wtffws6^PLwyw&S9)v*i>+oUf46Om$E%7bTQE@AHO|&*Wfjn$VSD=`*cS+i$DDN^(Vl$@gMd7_$ba%=FkA- z_Wn6+{7T5aI4w8D0ua!4a}a=k|BHP9xP6YWSCuFZokGH_iye};s>?Kc}#tgOce0!%^-vL%{;fNY}1q~i_<-RHAh zdUpa89l<{u_HMqVYk;{tzZb}jCkv;vTKoQ{ZTJ_^c+0cO0UYR!Y%0pHW91J~D2PWRovm013f*4T8`bRL{3Cs}_T=Le9X^N(Q)Ay**WBbTiJ1jl`lr zIa98!K%~c@3o|gsL4}ySsH!<TfHE)$Io`_Pet!vk-Z9g-q=@a5? z{kSxTEJUuEDd@%AuNrg^eZgh<>aU8l+8#c9RFKYEl*M9dtzd7&b)_+Eo9K>@C2Hbh zZ`CJMB)J}yennZ~k4zQ~1!!?`s|jor@hhh)s^vIxFHi9&8rXoBvmwBOHUy9xK`Jdj zgC4xQZhzE%9HGy01LoXOEsGbQ0IgfWzmyd4REY-(B)|Fxhy&A&3edy;=hOLC)BZuR z3*}uBPUYd|pADAwmlRnT$zvJ*s7Adsg^GaA7SDEO*)I0$uDULPr>dNut_~o+eGA~b znTtnO;Ns*b6KHS$GdORc=~B~hrK6(CwY2_chIzl5&c`rYg%+V{zVN<6hWEE-7nhU6 zPZD0DYRE~;{~2MulQzJFO;01gE#N+;(sG$h4jXZ=~AkW^YZ zU0r~H9Z+MGLlKfK*31P`dJY)BS4qB>@~Uwa6_HYSMhh^%>@Y#S7u~r3`CMru=Ij?J z;-5-p8mWq)zm#$KU1Lgt3+>82Ei3Pfyb1p5+ES^?5C7m}U@~!&zP$mW){sQkz;GaW zMV@wA$`gwdqgWoAY-8}aO^FaZ6Ay{*1D+)*8=F$V-WzMJQNo0-79EZ&hYhsqfU-BD zPqRJDg4FP_sc8W(Mqifw4cZCn+{-FLAgfun3%jz%?u6*cV1)ynn6%C-rHxadFOG`T; z^HB;Lu*#;O!X-a9CsDyAKS?gq5J$S{zfKIVJU|_YDqi~SX{1G5C0y~rhiOI%+CFt2 z%^!toLCwZ%5ZRYdq|Xh)m8r*D#6l^@5_NGC(U}od6h41iyU>Kw#}PwA49K#hlVlMpyeE?xGtlMqN6LN{Z>a+N?X@c zwT~-x`Yfu(irAm$%H)uvw2Fl(uIY#z!=E`f9kRo{qc6b*_{jjRf+C%}bU#44_=*;m ztS5~R-CX`-asS!4UeE4Hqq@7htHs=?qfQqnoZTfG#i;<#!wwS@I#b+WR|~U9A8q8Q z2GtE6ut~wmi4z(25H|sfSlNyh;8EHJ!XttVx)Rv0sFBsm@jKRlICL5rH$Z$@&U{sR zT1&)_vmgc*Apxsq(t|P(%uo}g6a3i2n`)urQy^-C zbcdx(_af&Hs1CRzGRKJ5biJD6i?NqW8Hz|6Ab_x&_{@(TyCeBef&D*^+W2RF_kXt! z0K*pl{OA80_hAAa@&ApZNdD=t{~KfS0(!Efeo}!(cnD%V(`H2pGZK?{s7U9F>`aJk zh0zrsrRW7R`%RHmH%y;#u2y`s>J_+TB4jJoUpb02>{q6M0c`)Fa&`SzJ+LvRy$Otz z^*kuM-Nbn)L@@TXm+ND622?`MG2o>2yv7mYKL7X>eCt##hCSrs#(QA3V`LWcspUK< z(`{JxqfN@&fM>Hc-Ko8rLQgd=_$CBSh;BwVLww?Z<^B@!McX;8%*Sg^zPbCffhH7G zWky8Rx!d3ZM^7m^_+!5jv<`wOG+#-DqDJd>YEPLj@7LJH_7z~=eUzYGaUPs`e zF}{|To8l<5-^>_qy)x#Raq2f3Te=5FFJ8{e<24)08{Zq)2Hlgba!8#b)_@i3pRvUx z6)gIf#P8-u*jo3!<h0nEz85YLxuvr#a|Q#aCbFrdxi!(sTi)eg6Ts7Q+#`6QBlOo zW40hQ=6iO8shKXc^G)H-$r9s9rA9F;?#w^04Q)+=`CatV;}{YB0SMn0vvu^f8Tw>m z=X7e_`$Xv=;fDaX@aNx3;(kCMBTm1O_PnD)MtxRznDz1Oyh|>M-EUGBT5Y+F?`owc zT#y8{Lwq-8>0{fs!uCH>C1#m*01dM%kz}aKh;fa)!#h-F*8nIw1!v z41wDr#A5R)hU;BdDC_M{8!GS#>v!cu%46JXarR15@P zm6M0rI4)jX(CWA>hvy39py>rAjqIxpDIzZhLRG5+I`AgAG+t+45+|kA?)8dvg$V?i zE7pci$CprP{fNAhQ|6MNqG9bwn+WlZZ18#SaT(;3R(o1x=|xZCF^>)CmA{lP=NS8v=*y|Y;2 z$~SH=fv!r%Gy#@mnO*iD?MD^<0o+*A&)=!%MyL|$XC}GKYU&&;x5eeMCt4Tq5tZ7! zQMI|T@2XEP4B$~yrCv9cdAd*ZO^wbB{58U_==%G$Of&2BU$gE-ir-?DFpK?UkyZ-p6`wWA+%z0ID>Ad=2x)4Z( zNfsr7h8r?20;LTiE$myo{S6{KzAF$fFW3v;RqUGL z3~jbvp{4PpL;2t!@DoOt7e&=X=!8Rw^Y#PZeE&#+M6y%X3*Ag^GM((Amn=l=WlNf) z6=_2y4xco*PK4v0Z;ClCHGUAWg^%QW22mKat%VIF%rqQ1lYT%!u>-5V&rJMVTJKek`ijjyvy^_U@ZkK;*$MdLrqU8pT8ZO3;t6((e1S*D&^@`bpt zY?y=(=k><;Y1c6>R|G*#giA<3g?y>Ex~#Ef>el0x+T56tzK(C_&VxT?@J6PlK^y`h z&cZ9SBmFB#Nh;`jU^VZ}p3w(1nzwn(Moq*EJKD^|Ir45}D{LW$UWOtRo2jlU7Hd;3 zJEw?hhM-Zt>tBSK?0)zmL*ZqjP?s8eege>gnwp>l}doh3=1fc+*cOnZNu=eW|anbi4@sQe@g z{j#zAT*D3Vwwle(pXbX9oEF;~h|xj04khaZ8a|Hr@ies}dt>pq;^HdOIMnGTZ|3g- z%Wla9a+lXBBUT?JRfGk)rzQo~83QH*c^cmuuKS0X)N;_?|K1)iB(OYGHQVZgu8b6l zC*92tE&e<(p}|2!x7qEL2;~#=r$s?GN_h)MVzh1ldM&@wQCgMaL?V!rqfX>Ddtlx- zl}Ib-{+S{d5>$xAX_geU<+6T1m^^YfZ)F^`Z&x>vyLi99;`B6pNFbWdU?xn#qq>Jv=PL6R8!gszcJg+ z6;4rHV#w#6`nBE_KPdcW|8XCsEb;8?W9-9XLwmyfscypE=5~6aXr?vuA7ZT9r*MH_ zxInHEGP>poJw#}`P=d?(tY`s3JfNeQObuK5NS| z&-^L(G|AuD==!&cS6$k5WAc^HvraDeYIj{0k! zz=~<4W^Oz8$@7qj;S<6SncwL$z0mER&Lv2ArHdZxADC8(XxOC8XCa+e84{`9qa=cI zv^U>cHiZw-IUbMK5^@fTZc88ZA7{H~axRJ^MCuboz!-42k$mzEuH*XPD0qEzS+B){ zgr(P=>t5N%?QCM<^WK#<{BNz_eh8R$Z#+tasK$ZF{p>s#DAA!kQ)s$!x--O(?`H0o zEreTU{+#N;_W?THErs(rCQiX;{mebisFFLHN2br_`0PLN(7L6;Y!*kJ;-tBa=wo-X7s+rW5|ecZji1LU+}q`ZC*->#@_H-7oT2Lz&E(EZwh88{ z1Sw62#*d4Q(XT(P4JmnW-FNtSEG_I!x9*r0{=BmNu(2WuSrz8*y5^{XneA+aJf=29 zW%+I{zgfEaqdnew;`vTIh?kzoxNnrww5NFJjUcRMC_6-+@XAsM4+JXuOX@|s|9DI? z2qK}|XGUQ{4{axRx_baueq$>CzC7rVtoFs;i36R*7Q!!ncbObB)se#rzsJf&+<2IF zIttC6!31dcjhfg3!ssPn_=yE9-n44HLP^>oH;%T2Z$tH$jM!lJ(8aE{7aPEo`J#gx zN4w3(IWTg;r9J#e9;FZ6%73WwZ(+Cl%#s!No0huU+U_E6AEW_vyoxFrX2CS&tbBR- zT&agWAN`w$kXbEVwQ=#Rv3;CBI>Q((jQR(;*5%v)_ zVpTol;D4;S?iH^+{b-EaZZ$N2)M;A=Ssupe()H-cy|*ydHONyF!fiE_6|85}O4 z(U4UCbZbvcbN=DEC%J+*T3T&;Hl}NKJC4s*jvIf;K4|u8(vk0nRCRm)k*<*G|h^SF@k+V<6R%<3eF!X^Yl($e%ai8@H;m<*SwqSXx%*3 z6WYE~;`{mZGV$g#LV(?3;GD8I-}5cl59U<^JBBJ&2Sn*6b5i^3D=@3o0dU)fY3~_5 zSs*%sKp-ZgXnOtRl|{bOqWsA_#O;6?8M6-OMux z8H2VaIx0$Kc7|MRb-+9gyF?TX6P6^8I_hR1P zYfu{F2X|dx|7PHV&&;~{0snJ7`*&9}Eq6QW66%JzX^)MZw*A$8uM3fS>FPYl2>=1< zzzhzm{E4+16OE3kyk6eBoExMf~Na_hM&U(7~GOX6Vqx76uvZvJwm$sTT`Tt_|Itw z7c`(^Euhl!Q99{HZg`##*Takfaa)?;%@kr6gHvp9HNK1yC8=2QONJy@nl}8Nj%YOy zEk#v%>8ItJXwM0~PqLrpar7GOM&9UjcB9SeO1{?=4!y!cmU}q>7Q_K_rWN~@r-_WJ zD!}B0myvX3=J)_v8ZK#7S&1h!;0xCQ`zK1di3^Lxx6e<5|5Vo}82Pdo!5eayZ#uXv zSt~YPSh;k@U`ES}J)g@Qiiw}3F85>$btutO@=Iir6kR^e^(Ukx!1_f4>1lIrBoJeZ&BQghriO*E&q;&W z31z2F@Qr}qVQ>3ikn`0V$m#vnUKD#J_Kpde2{D$ubfXulL6&X|m6?Pu5751T42>wY z{90P_Z1I%Xl!#_ImIU*efnwClxaXmzh@Bh)oHWnpDpp67;H|U`A)LO$p40K3vxYte zQ)V4?G~R9~Z52?<&OyHyA1s@>je6}{Y8QDy{0-kc+P8@;dTvlolCVWp4}Vv;9_;%>WLIL+4?y@ zpQzHXDSZ-Ft_8b&Y3$M6Ux8-u}dnC-%^2>^^q$wT*y=V5MS7 zBf8F}alihdLSW0&+rZP=NL5)Ih24fAyAU^hTqv@7#8iG9JQ?*i5Bo`%g|sV;h{xOK z^WFknRR-cs)5F9c!gxvi*KKRk<9FL0$-LM#PZDgweLlH{b|NS6^$|9XzY8{YR{e$_ zt>>FU-0k6!?+R1nG$p=lm!9@Xa=7oIZGlLaU;TLML{6DLkVSJ6`Al|Yx`zJdVKVi7 zMr$|m#d$%+xOqTUcv%tY6;$#MmHx<)QFs3b*3c~$+pFZ@fmKMkrk^@dW{rii`q`M9 zP<`7;wx&dEh1_Tt|EJnyYDOe{)kN7o25+;MaT60U7@WP(7J89986ES1?7rOFoWR zgd(5PTF$?d<;Ev$Un{&0pLJdgS|ZMjYM&DFpo(zV5fPmQ0<%GX2e=m$Gg=qwM{BP z6d)Ss2I9RbGvhf_cJ|bDwt|?QTkoDDC?{hff&=A9FZo-rP&Ayp`LNh#X-vDrf3$=| zdpYs}FA^_jl)V`@mf0lr>54UfJ0GkiP3AI^XORy5{*{n3B0fM9v23InnWw3@@yTw~ z3Hy|X4T;mr^&YLnc*PeA)Mx?Yp6<#X_NM0p8tj&*r*ueSWK_#bp%0EOIXed+{nES~BH3Rkd5$ zf|Pl9LkaX6Z(mH5NlMG`CjII$nVlA+0HLt)@pYv5ueX(t+l@0@88n`$vTUGfnb_D} z?@!UNv-_RDYszXonglnLjQ3TBJONqWJ&H3;=?d?`)oYQ#gY(9d5TeZ-zVMS?Hp4X+ z&$se_z=0Y^?}<_-sRS|VSD?6AFNTY`iE%T3nfkNXJ#8X1(@U+;>UIs`N8gQQF+WrVqJ+H~AE;?-PYgEZ`c52&y z)p=R_J>mXQkA%C5xUVKmL#te>+LoO)_{!sG3t#Y@NTTd3pA~`|>b1oDj^|FTf+-G| zhGPo%En230kHUMUPaL}%fAPp&!8$esk%_%e3U`#diyf85io66Xg;XvQtk2X#BAO4m z-*;&wyDl5^xQqR1pViz(qnRL=q`owdvF8dq8|imDflyKYS{Qnb`w6|5FSc2??zB?x z0JD_$X6H~a-#kGgPswfv0?$Jz40orkdbrZmF217i{^iVEr8G3}#dmhedzJJi8!^{b zZ49Agv!E|=?O34~is?Mxj&tAL+n)G1+Zw=F;LOnc*Z=)0q+2$gW9vGvw%>y|?W%c| z8wBq9vhu1<;5pWW?Qzg#rD?+uQOO4{kO|ytvTaX?rbAD=zA|I=a$xaPt~JnQyuRH1 z-lQeXfnNjGV;JFzCqMMi`EkWWb}%rt(FKNwQob|u<4|{AtfjCf3j2at^3(i8M{ERp z@vaT>3l@|}p=|PwN|T>h&}vHeWt=Yg(03!`*q8e07!bm;+@IOKK2bO*T4pK&ES6GQ@6MKgJR?#c;PnQnC1cn;F0tKB ze7CN^(qS{gh}6E=8F1UT!(B2|QjjBBN@B?!{h;w@rtiqvZOn2V0nuJm?~b~JXH-9} znUQcqlG8I=f0+*VtFv35Le0z}-7K*nHQR9q#-bNA(>+NckGZ;>C)Qgyh%6znaGS{R z5tpXUYMR>Sj(WbzX`V83$O(0oco5+LetBA9srJL|${$k?ibGXb&9*i|XlvuhFyz^D z+;}VcRL*%`xiT^TwhuffU&fEL-rL)n7>la;-n1}p5&5&pX+=r2 zhD__5{fVvo};kgmBCXva;5|Q4}*#*9K?k-e|4hA6=m>9g0}pv!>oos ze0I#-{mXUKb=Nn$l$<&CUMsXz3I?Ev zAsYjYFmFC{_XE7mOl%nO*rNz<5oh%(VDnBYNd6QrBn^_LUDeDcZ|cqct^3xfYAz)| zc%H=XU#%t(h^R8~J*R13>ohRn(>7K%tlnWCed2fyzh&^G6Pm`YAr+1S$THIk`e&_&>Wow6)toy zCW*Y4ni#Y#d%7AE#O8j*77bMw zOG`1 z%U&eoqTjl8ocIljJYwSm|I^WfXP1`ZaljZCqiH1Tgz{iaq)Nwy^?Jzec_(N+jJGp- zxq*rI?2eUIP56(Hg{2{(EnDb!YkuCEwg_?w--tOxVBrkdr2pEH!*&EAKE(=NN=UIU zZsg6%X)#lmO8RoPv{Ap~8h@}_AL}dFQjcWu;%4uLhqyhYP$I$l213>jQ5u7FGt0vxRl43vSVEc1v>z4ZKR zF8p#f>%rYd1NiDw=VKzd@3`R+|3gmT5G4t>hp-hPhxORikiq@;H;bB1S{r4SB-1kD zf#Z{F)lW~gmFP)(yk!dHu31|D$;{yU<4 z*+Z25v>Whl_0vrvUpIg1B)h79`DW==Tx5@62-vZH+(s9igZocGw7?9+c)KLWJy0 zd`Yx90z-dru1@e86%INrs`9x~@QR0UyYT+n+gR&gmdkTk|EwSd$>Y~Huk<`XIuzF?;-lcpe;kTS7|;%$@=bu?s-9l5I%{J z4+9LcmzLqm_-8RJl{@KBU}LgV9qezP7BZgPO|7^$&PyWZ%F~>TD$lwo^@UdI%)w5Z z=SS0mP8NFr<^ZIuXut@S&ug?4yC{ds)Hu=kBGuYBCb9m>ur5Ram;K3|@XdSn&CWY04dsH`U;)`Vmzgqz%DazE_ zq)PZuI2$`D}T*4z> zVokv3c>agu)Fl=j=AJRAE@>ZfJ0j$eTR6M_ScpIf1&PV%2U?&PTd?u-8X9qTH52pa z;cg>v&DRJzj}z( z?^E=#`+dBFWOv+)v`YIrvM@W@_vT<+hT>W`W(^mXR~$R_SMdI2s_nI$`<$;k-0do2 zTp=-c*}uBA<~q!nBe+$xsy5r68@T&XA<>59}6 zXdRtet=N$bbBAx1hsVpfQI0B?prTkJmc&gE6%)ZR^K&j+v+OWM;`q5wlho8d-dc?r zsL3@-3XhEcejT+%`kb8GT}1#czjYnrpBf70DB)=zNsi!pV;(FV+Ga_xoI*)V;-dk% z=0#?W|A_p^r2Rx^^9ttm12jLkjn=M+d6V*vd7Q-rUaNNgEq1OxGeXND{3 z8jAaLTPRu>dtAZ!=7H9vR)yfl&p4-#Y!GIwwi~Pi9*@Ou^O`$zslTK~?&X_eH8G2b zL-*vb#^N+m(VEWOi*bA`-!ip+Sh-vPl}Ja6fd-vsQ%S*8B?t8iZ$1}`r&r?QDbcRa zW21-r4bNJQ_ZQW*k-PSH$j)W-u9{PlG|C=Ey>}OjT#R?38!Fc@h`;>7uRXIWn)jl7T)tEx z*y``_8?xZ7xB1DGJ4G){4jQ*Rx|MRLYm;Um1JJKFH(~b1DK^)ITm&W}BObO&-hmT4 zmwJ943&-gvA@Q$nosHy!*1O*-AnIj|58wp5WzHBNgF#S5x%&{|i4fxAI?V0WxXH=h z>Lz}FIWI<*0s%^b+M|(=mf@l4qq&@v+EiMne^gq4_cTO-)PO9iosZP( zvoHd&XCP#$*TCUIf5r9RAR-_k8wov(3N?&s)e4TBtVV6b-Kf%rgoH%zDW~sgZQ*Gn zY~^kP{6OO2;^ATE;$`RJ*5T$6=6);8C&0=jB+SJ%vK@`}|D53LYVBa__y3*11z6ts z|93*2u&F3;0?EHCXuH~a`dGNzAlbRNI@_>&02i}y@vwLGJb%$G4*U|5lAM}sjkI~# F{{i5MYD@qC diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp index 30bf3be553b1b..1aa4acc63b93a 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp @@ -52,9 +52,8 @@ enum ReturnType : uint8_t { std::unordered_map roi_mode_map_ = { {"No_ROI", 0}, - {"Dynamic_FreeSpace_ROI", 1}, - {"Fixed_xyz_ROI", 2}, - {"Fixed_azimuth_ROI", 3}, + {"Fixed_xyz_ROI", 1}, + {"Fixed_azimuth_ROI", 2}, }; class DualReturnOutlierFilterComponent : public pointcloud_preprocessor::Filter @@ -82,9 +81,6 @@ class DualReturnOutlierFilterComponent : public pointcloud_preprocessor::Filter double visibility_threshold_; int vertical_bins_; float max_azimuth_diff_; - float neighbor_r_thresh_ = 0.5f; - uint weak_first_segment_check_size_v_; - uint weak_first_segment_check_size_h_; std::string roi_mode_; float x_max_; float x_min_; diff --git a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp index 91409f26479d9..93c72619df28f 100644 --- a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp @@ -51,13 +51,9 @@ DualReturnOutlierFilterComponent::DualReturnOutlierFilterComponent( static_cast(declare_parameter("general_distance_ratio", 1.03)); weak_first_local_noise_threshold_ = - static_cast(declare_parameter("weak_first_local_noise_threshold", 10)); + static_cast(declare_parameter("weak_first_local_noise_threshold", 2)); visibility_threshold_ = static_cast(declare_parameter("visibility_threshold", 0.5)); roi_mode_ = static_cast(declare_parameter("roi_mode", "Fixed_xyz_ROI")); - weak_first_segment_check_size_h_ = - static_cast(declare_parameter("weak_first_segment_check_size_h", 30)); - weak_first_segment_check_size_v_ = - static_cast(declare_parameter("weak_first_segment_check_size_v", 3)); } updater_.setHardwareID("dual_return_outlier_filter"); updater_.add( @@ -113,7 +109,7 @@ void DualReturnOutlierFilterComponent::filter( float max_azimuth = 36000.0f; float min_azimuth = 0.0f; switch (roi_mode_map_[roi_mode_]) { - case 3: { + case 2: { max_azimuth = max_azimuth_deg_ * 100.0; min_azimuth = min_azimuth_deg_ * 100.0; break; @@ -142,23 +138,12 @@ void DualReturnOutlierFilterComponent::filter( vertical_bins); // TODO(davidw): this is for Pandar 40 only, make dynamic weak_first_pcl_input_ring_array.resize(vertical_bins); - const uint ring_number = vertical_bins; - const uint azimuth_steps = 36000; - float * strong_return_distance_array = new float[ring_number * azimuth_steps]; - float * weak_first_return_distance_array = new float[ring_number * azimuth_steps]; - for (uint i = 0; i < ring_number * azimuth_steps; i++) { - strong_return_distance_array[i] = -1.0f; - weak_first_return_distance_array[i] = -1.0f; - } // Split into 36 x 10 degree bins x 40 lines (TODO: change to dynamic) for (const auto & p : pcl_input->points) { - uint azimuth_ind = static_cast(p.azimuth < 0.0f ? p.azimuth + 36000.0f : p.azimuth); if (p.return_type == ReturnType::DUAL_WEAK_FIRST) { weak_first_pcl_input_ring_array.at(p.ring).push_back(p); - weak_first_return_distance_array[p.ring * azimuth_steps + azimuth_ind] = p.distance; } else { pcl_input_ring_array.at(p.ring).push_back(p); - strong_return_distance_array[p.ring * azimuth_steps + azimuth_ind] = p.distance; } } @@ -177,45 +162,12 @@ void DualReturnOutlierFilterComponent::filter( uint ring_id = weak_first_single_ring.points.front().ring; for (auto iter = std::begin(weak_first_single_ring) + 1; iter != std::end(weak_first_single_ring) - 1; ++iter) { - uint azimuth_id = static_cast(iter->azimuth); - uint segment_check = 0, segment_check_thresh = 2; - uint weak_first_ring_min = 0, weak_first_ring_max = ring_number; - uint weak_first_w_min = 0, weak_first_w_max = azimuth_steps; - - weak_first_ring_min = - ring_id > weak_first_segment_check_size_v_ ? ring_id - weak_first_segment_check_size_v_ : 0; - weak_first_ring_max = ring_id + weak_first_segment_check_size_v_ < ring_number - ? ring_id + weak_first_segment_check_size_v_ + 1 - : ring_number; - weak_first_w_min = azimuth_id > weak_first_segment_check_size_h_ - ? azimuth_id - weak_first_segment_check_size_h_ - : 0; - weak_first_w_max = azimuth_id + weak_first_segment_check_size_h_ < azimuth_steps - ? azimuth_id + weak_first_segment_check_size_h_ + 1 - : azimuth_steps; - - for (auto i = weak_first_ring_min; i < weak_first_ring_max; i++) { - for (auto j = weak_first_w_min; j < weak_first_w_max; j++) { - if (weak_first_return_distance_array[i * azimuth_steps + j] > 0.0) { - const float min_dist = - std::min(iter->distance, weak_first_return_distance_array[i * azimuth_steps + j]); - const float max_dist = - std::max(iter->distance, weak_first_return_distance_array[i * azimuth_steps + j]); - float azimuth_diff = (iter + 1)->azimuth - iter->azimuth; - azimuth_diff = azimuth_diff < 0.f ? azimuth_diff + 36000.f : azimuth_diff; - - if (max_dist < min_dist * weak_first_distance_ratio_) { - segment_check++; - } - } - if (segment_check >= segment_check_thresh) { - goto exit_segment_check; - } - } - } - exit_segment_check: + const float min_dist = std::min(iter->distance, (iter + 1)->distance); + const float max_dist = std::max(iter->distance, (iter + 1)->distance); + float azimuth_diff = (iter + 1)->azimuth - iter->azimuth; + azimuth_diff = azimuth_diff < 0.f ? azimuth_diff + 36000.f : azimuth_diff; - if (segment_check >= segment_check_thresh) { + if (max_dist < min_dist * weak_first_distance_ratio_ && azimuth_diff < max_azimuth_diff) { temp_segment.points.push_back(*iter); keep_next = true; } else if (keep_next) { @@ -225,39 +177,7 @@ void DualReturnOutlierFilterComponent::filter( } else { // Log the deleted azimuth and its distance for analysis switch (roi_mode_map_[roi_mode_]) { - case 1: // dynamic ROI free space - { - // check surrounding normal pcl - uint neighbor_check = 0, h_range = 3, w_range = 10; - uint min_h = 0, max_h = ring_number; - uint min_w = 0, max_w = azimuth_steps; - min_h = iter->ring > h_range ? iter->ring - h_range : 0; - max_h = iter->ring < ring_number - h_range ? iter->ring + h_range : ring_number; - - min_w = azimuth_id > w_range ? azimuth_id - w_range : 0; - max_w = azimuth_id < azimuth_steps - w_range ? azimuth_id + w_range : azimuth_steps; - for (auto i = min_h; i < max_h; i++) { - for (auto j = min_w; j < max_w; j++) { - if ( - (strong_return_distance_array[i * azimuth_steps + j] > 0.0f) && - (iter->distance > - (strong_return_distance_array[i * azimuth_steps + j] - neighbor_r_thresh_))) { - neighbor_check++; - } - if (neighbor_check > 1) { - goto exit_neighbor_check; - } - } - } - exit_neighbor_check: - if (neighbor_check < 2) { - deleted_azimuths.push_back(iter->azimuth < 0.f ? 0.f : iter->azimuth); - deleted_distances.push_back(iter->distance); - noise_output->points.push_back(*iter); - } - break; - } - case 2: // base_link xyz-ROI + case 1: // base_link xyz-ROI { if ( iter->x > x_min_ && iter->x < x_max_ && iter->y > y_min_ && iter->y < y_max_ && @@ -268,7 +188,7 @@ void DualReturnOutlierFilterComponent::filter( } break; } - case 3: { + case 2: { if ( iter->azimuth > min_azimuth && iter->azimuth < max_azimuth && iter->distance < max_distance_) { @@ -311,7 +231,7 @@ void DualReturnOutlierFilterComponent::filter( pcl_output->points.push_back(temp_segment.points[current_temp_segment_index]); } else { switch (roi_mode_map_[roi_mode_]) { - case 2: { + case 1: { if ( temp_segment.points[current_temp_segment_index].x < x_max_ && temp_segment.points[current_temp_segment_index].x > x_min_ && @@ -324,7 +244,7 @@ void DualReturnOutlierFilterComponent::filter( } break; } - case 3: { + case 2: { if ( temp_segment.points[current_temp_segment_index].azimuth < max_azimuth && temp_segment.points[current_temp_segment_index].azimuth > min_azimuth && @@ -353,12 +273,10 @@ void DualReturnOutlierFilterComponent::filter( if (input_ring.size() < 2) { continue; } - std::vector deleted_azimuths; pcl::PointCloud temp_segment; bool keep_next = false; - uint16_t ring_id = input_ring.points.front().ring; + // uint ring_id = input_ring.points.front().ring; for (auto iter = std::begin(input_ring) + 1; iter != std::end(input_ring) - 1; ++iter) { - // uint azimuth_id = static_cast(iter->azimuth); const float min_dist = std::min(iter->distance, (iter + 1)->distance); const float max_dist = std::max(iter->distance, (iter + 1)->distance); float azimuth_diff = (iter + 1)->azimuth - iter->azimuth; @@ -373,65 +291,16 @@ void DualReturnOutlierFilterComponent::filter( // Analyse segment points here } else { // Log the deleted azimuth and its distance for analysis - float non_neg_azimuth = iter->azimuth; - while (non_neg_azimuth < 0.0f) { - non_neg_azimuth += 36000.0f; - } - switch (roi_mode_map_[roi_mode_]) { - case 2: // base_link xyz-ROI - { - if ( - iter->x > x_min_ && iter->x < x_max_ && iter->y > y_min_ && iter->y < y_max_ && - iter->z > z_min_ && iter->z < z_max_) { - deleted_azimuths.push_back(non_neg_azimuth); - } - break; - } - case 3: { - if ( - non_neg_azimuth > min_azimuth && non_neg_azimuth < max_azimuth && - iter->distance < max_distance_) { - deleted_azimuths.push_back(non_neg_azimuth); - } - break; - } - default: { - if (iter->distance < 15.0f) { - deleted_azimuths.push_back(non_neg_azimuth); - } - break; - } - } - + // deleted_azimuths.push_back(iter->azimuth < 0.f ? 0.f : iter->azimuth); // deleted_distances.push_back(iter->distance); noise_output->points.push_back(*iter); } } - std::vector noise_frequency(horizontal_bins, 0); - uint32_t current_deleted_index = 0; - // uint current_temp_segment_index = 0; - for (uint i = 0; i < noise_frequency.size() - 1; i++) { - if (deleted_azimuths.size() == 0) { - continue; - } - while ((uint)deleted_azimuths[current_deleted_index] < - ((i + static_cast(min_azimuth / horizontal_res) + 1) * horizontal_res) && - current_deleted_index < (deleted_azimuths.size() - 1)) { - noise_frequency[i] = noise_frequency[i] + 1; - current_deleted_index++; - } - if (noise_frequency[i] > 0) { - frequency_image.at(ring_id, i) = - frequency_image.at(ring_id, i) + noise_frequency[i]; - } - } for (const auto & tmp_p : temp_segment.points) { pcl_output->points.push_back(tmp_p); } } - delete[] strong_return_distance_array; - delete[] weak_first_return_distance_array; // Threshold for diagnostics (tunable) cv::Mat binary_image; cv::inRange(frequency_image, weak_first_local_noise_threshold_, 255, binary_image); From 7edd2cfc1cf7b82882aace4fa7a30389b4c30e46 Mon Sep 17 00:00:00 2001 From: badai-nguyen Date: Wed, 2 Mar 2022 15:27:33 +0900 Subject: [PATCH 27/27] fix: typo Signed-off-by: badai-nguyen --- .../src/outlier_filter/dual_return_outlier_filter_nodelet.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp index 93c72619df28f..964f43c3616ee 100644 --- a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp @@ -262,9 +262,9 @@ void DualReturnOutlierFilterComponent::filter( } } current_temp_segment_index++; + frequency_image.at(ring_id, i) = noise_frequency[i]; } } - frequency_image.at(ring_id, i) = noise_frequency[i]; } }