From 6a6ac7d220e1f4fffaeab9fcbacea93582449f8e Mon Sep 17 00:00:00 2001 From: anhnv3991 Date: Wed, 3 Apr 2024 14:31:21 +0700 Subject: [PATCH 01/29] Initial commit Signed-off-by: anhnv3991 --- .../ndt_scan_matcher/map_update_module.hpp | 12 +++ .../src/map_update_module.cpp | 92 +++++++++++++++++++ .../differential_map_loader_module.cpp | 20 ++++ 3 files changed, 124 insertions(+) diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp index 04c762ae950a4..d91a539f69021 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp @@ -60,6 +60,11 @@ class MapUpdateModule [[nodiscard]] bool should_update_map(const geometry_msgs::msg::Point & position); void publish_partial_pcd_map(); + // Looking for PCDs in the vicinity of the specified location + void query_pcds(double px, double py, double radius, std::unordered_set& maps_to_add, std::unordered_set& maps_to_remove); + // Compute distance between an origin and a pcd segment + double dist(double px, double py, int idx, int idy); + rclcpp::Publisher::SharedPtr loaded_pcd_pub_; rclcpp::Client::SharedPtr @@ -72,6 +77,13 @@ class MapUpdateModule std::optional last_update_position_ = std::nullopt; + // Metadata of segmented PCDs + std::unordered_set all_pcds_; + std::unordered_set cur_pcds_; + double pcd_res_x_, pcd_res_y_; + double pcd_lower_x_, pcd_lower_y_; + std::string pcd_tag_; + HyperParameters::DynamicMapLoading param_; // Indicate if there is a prefetch thread waiting for being collected diff --git a/localization/ndt_scan_matcher/src/map_update_module.cpp b/localization/ndt_scan_matcher/src/map_update_module.cpp index ca56a93cec859..18a2aec2efa45 100644 --- a/localization/ndt_scan_matcher/src/map_update_module.cpp +++ b/localization/ndt_scan_matcher/src/map_update_module.cpp @@ -146,18 +146,54 @@ bool MapUpdateModule::update_ndt(const geometry_msgs::msg::Point & position, Ndt request, [](rclcpp::Client::SharedFuture) {})}; + // While waiting for the requested pcds, look for indices of the candidate pcds + std::unordered_set pcds_to_remove, pcds_to_add; + + query_pcds(position.x, position.y, param_.map_radius, pcds_to_add, pcds_to_remove); + + // Wait for maximum 20 milliseconds + std::chrono::milliseconds timeout(20); + auto start = std::chrono::system_clock::now(); + std::future_status status = result.wait_for(std::chrono::seconds(0)); while (status != std::future_status::ready) { RCLCPP_INFO(logger_, "waiting response"); if (!rclcpp::ok()) { return false; // No update } + + auto cur = std::chrono::system_clock::now(); + + // Report an error if wait for too long + if (cur - start >= timeout) + { + RCLCPP_ERROR_STREAM_THROTTLE(logger_, *clock_, 1000, "Waited for incoming PCDs for too long. Abandon NDT update."); + return false; + } + status = result.wait_for(std::chrono::seconds(1)); } auto & maps_to_add = result.get()->new_pointcloud_with_ids; auto & map_ids_to_remove = result.get()->ids_to_remove; + // Check if there are any maps in the pcds_to_add not coming + for (auto& name : pcds_to_add) + { + if (maps_to_add.find(name) == maps_to_add.end()) + { + RCLCPP_ERROR_STREAM_THROTTLE(logger_, *clock_, 1000, "File %s not coming.", name.c_str()); + } + } + + for (auto& name : pcds_to_remove) + { + if (map_ids_to_remove.find(name) == map_ids_to_remove.end()) + { + RCLCPP_ERROR_STREAM_THROTTLE(logger_, *clock_, 1000, "File %s should be removed but it was not.", name.c_str()); + } + } + RCLCPP_INFO( logger_, "Update map (Add: %lu, Remove: %lu)", maps_to_add.size(), map_ids_to_remove.size()); if (maps_to_add.empty() && map_ids_to_remove.empty()) { @@ -200,3 +236,59 @@ void MapUpdateModule::publish_partial_pcd_map() loaded_pcd_pub_->publish(map_msg); } + +void MapUpdateModuble::query_pcds(double px, double py, double radius, std::unordered_set& maps_to_add, std::unordered_set& maps_to_remove) +{ + int lower_x = static_cast(floor((px - radius) / pcd_res_x_)); + int lower_y = static_cast(floor((py - radius) / pcd_res_y_)); + int upper_x = static_cast(floor((px + radius) / pcd_res_x_)); + int upper_y = static_cast(floor((py + radius) / pcd_res_y_)); + double rel_px = px - pcd_lower_x_, rel_py = py - pcd_lower_y_; + std::unordered_set nn_pcds; + + for (int idx = lower_x; idx < upper_x; ++idx) + { + for (int idy = lower_y; idy < upper_y; ++idy) + { + // Skip if the pcd file is not within the query radius + if (dist(rel_px, rel_py, idx, idy) > radius) + { + continue; + } + + // Generate name of the PCD file + std::string name = pcd_tag_ + "_" + std::to_string(x) + "_" + std::to_string(y) + ".pcd"; + + if (cur_pcds_.find(name) == cur_pcds_.end()) + { + maps_to_add.insert(name); + } + else + { + nn_pcds.insert(name); + } + } + } + + // Compare with @cur_pcds_ to find out which pcds to remove + for (auto& name : cur_pcds_) + { + if (nn_pcds.find(name) == nn_pcds.end()) + { + map_ids_to_remove.insert(name); + } + } +} + +double MapUpdateModule::dist(double px, double py, int idx, int idy) +{ + double lx = idx * pcd_res_x_; + double ly = idy * pcd_res_y_; + double ux = lx + pcd_res_x_; + double uy = ly + pcd_res_y_; + + double dx = (px < lx) ? lx - px : ((px >= ux) ? px - ux : 0); + double dy = (py < ly) ? ly - py : ((py >= uy) ? py - uy : 0); + + return std::hypot(dx, dy); +} \ No newline at end of file diff --git a/map/map_loader/src/pointcloud_map_loader/differential_map_loader_module.cpp b/map/map_loader/src/pointcloud_map_loader/differential_map_loader_module.cpp index a8d380fd81b86..00d6bfbee5df1 100644 --- a/map/map_loader/src/pointcloud_map_loader/differential_map_loader_module.cpp +++ b/map/map_loader/src/pointcloud_map_loader/differential_map_loader_module.cpp @@ -29,6 +29,13 @@ void DifferentialMapLoaderModule::differentialAreaLoad( const autoware_map_msgs::msg::AreaInfo & area, const std::vector & cached_ids, GetDifferentialPointCloudMap::Response::SharedPtr & response) const { + + // For debug + std::ofstream test("/home/anh/Work/autoware/test.txt", std::ios::app); + + test << __FILE__ << "::" << __LINE__ << "::" << __func__ << std::endl; + // End + // iterate over all the available pcd map grids std::vector should_remove(static_cast(cached_ids.size()), true); for (const auto & ele : all_pcd_file_metadata_dict_) { @@ -67,6 +74,12 @@ bool DifferentialMapLoaderModule::onServiceGetDifferentialPointCloudMap( GetDifferentialPointCloudMap::Request::SharedPtr req, GetDifferentialPointCloudMap::Response::SharedPtr res) { + // For debug + std::ofstream test("/home/anh/Work/autoware/test.txt", std::ios::app); + + test << __FILE__ << "::" << __LINE__ << "::" << __func__ << std::endl; + // End + auto area = req->area; std::vector cached_ids = req->cached_ids; differentialAreaLoad(area, cached_ids, res); @@ -78,6 +91,13 @@ autoware_map_msgs::msg::PointCloudMapCellWithID DifferentialMapLoaderModule::loadPointCloudMapCellWithID( const std::string & path, const std::string & map_id) const { + + // For debug + std::ofstream test("/home/anh/Work/autoware/test.txt", std::ios::app); + + test << __FILE__ << "::" << __LINE__ << "::" << __func__ << std::endl; + // End + sensor_msgs::msg::PointCloud2 pcd; if (pcl::io::loadPCDFile(path, pcd) == -1) { RCLCPP_ERROR_STREAM(logger_, "PCD load failed: " << path); From 9d125e0ea8b6c4132aa7d24b83783cf352f38d45 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Wed, 3 Apr 2024 08:39:31 +0000 Subject: [PATCH 02/29] style(pre-commit): autofix --- .../ndt_scan_matcher/map_update_module.hpp | 4 +- .../src/map_update_module.cpp | 51 ++++++++----------- .../differential_map_loader_module.cpp | 2 - 3 files changed, 24 insertions(+), 33 deletions(-) diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp index d91a539f69021..4e80042709ec6 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp @@ -61,7 +61,9 @@ class MapUpdateModule void publish_partial_pcd_map(); // Looking for PCDs in the vicinity of the specified location - void query_pcds(double px, double py, double radius, std::unordered_set& maps_to_add, std::unordered_set& maps_to_remove); + void query_pcds( + double px, double py, double radius, std::unordered_set & maps_to_add, + std::unordered_set & maps_to_remove); // Compute distance between an origin and a pcd segment double dist(double px, double py, int idx, int idy); diff --git a/localization/ndt_scan_matcher/src/map_update_module.cpp b/localization/ndt_scan_matcher/src/map_update_module.cpp index 18a2aec2efa45..9fbf9e412b229 100644 --- a/localization/ndt_scan_matcher/src/map_update_module.cpp +++ b/localization/ndt_scan_matcher/src/map_update_module.cpp @@ -161,13 +161,13 @@ bool MapUpdateModule::update_ndt(const geometry_msgs::msg::Point & position, Ndt if (!rclcpp::ok()) { return false; // No update } - + auto cur = std::chrono::system_clock::now(); // Report an error if wait for too long - if (cur - start >= timeout) - { - RCLCPP_ERROR_STREAM_THROTTLE(logger_, *clock_, 1000, "Waited for incoming PCDs for too long. Abandon NDT update."); + if (cur - start >= timeout) { + RCLCPP_ERROR_STREAM_THROTTLE( + logger_, *clock_, 1000, "Waited for incoming PCDs for too long. Abandon NDT update."); return false; } @@ -178,19 +178,16 @@ bool MapUpdateModule::update_ndt(const geometry_msgs::msg::Point & position, Ndt auto & map_ids_to_remove = result.get()->ids_to_remove; // Check if there are any maps in the pcds_to_add not coming - for (auto& name : pcds_to_add) - { - if (maps_to_add.find(name) == maps_to_add.end()) - { + for (auto & name : pcds_to_add) { + if (maps_to_add.find(name) == maps_to_add.end()) { RCLCPP_ERROR_STREAM_THROTTLE(logger_, *clock_, 1000, "File %s not coming.", name.c_str()); } } - for (auto& name : pcds_to_remove) - { - if (map_ids_to_remove.find(name) == map_ids_to_remove.end()) - { - RCLCPP_ERROR_STREAM_THROTTLE(logger_, *clock_, 1000, "File %s should be removed but it was not.", name.c_str()); + for (auto & name : pcds_to_remove) { + if (map_ids_to_remove.find(name) == map_ids_to_remove.end()) { + RCLCPP_ERROR_STREAM_THROTTLE( + logger_, *clock_, 1000, "File %s should be removed but it was not.", name.c_str()); } } @@ -237,7 +234,9 @@ void MapUpdateModule::publish_partial_pcd_map() loaded_pcd_pub_->publish(map_msg); } -void MapUpdateModuble::query_pcds(double px, double py, double radius, std::unordered_set& maps_to_add, std::unordered_set& maps_to_remove) +void MapUpdateModuble::query_pcds( + double px, double py, double radius, std::unordered_set & maps_to_add, + std::unordered_set & maps_to_remove) { int lower_x = static_cast(floor((px - radius) / pcd_res_x_)); int lower_y = static_cast(floor((py - radius) / pcd_res_y_)); @@ -246,35 +245,27 @@ void MapUpdateModuble::query_pcds(double px, double py, double radius, std::unor double rel_px = px - pcd_lower_x_, rel_py = py - pcd_lower_y_; std::unordered_set nn_pcds; - for (int idx = lower_x; idx < upper_x; ++idx) - { - for (int idy = lower_y; idy < upper_y; ++idy) - { + for (int idx = lower_x; idx < upper_x; ++idx) { + for (int idy = lower_y; idy < upper_y; ++idy) { // Skip if the pcd file is not within the query radius - if (dist(rel_px, rel_py, idx, idy) > radius) - { + if (dist(rel_px, rel_py, idx, idy) > radius) { continue; } // Generate name of the PCD file std::string name = pcd_tag_ + "_" + std::to_string(x) + "_" + std::to_string(y) + ".pcd"; - if (cur_pcds_.find(name) == cur_pcds_.end()) - { + if (cur_pcds_.find(name) == cur_pcds_.end()) { maps_to_add.insert(name); - } - else - { + } else { nn_pcds.insert(name); } } } // Compare with @cur_pcds_ to find out which pcds to remove - for (auto& name : cur_pcds_) - { - if (nn_pcds.find(name) == nn_pcds.end()) - { + for (auto & name : cur_pcds_) { + if (nn_pcds.find(name) == nn_pcds.end()) { map_ids_to_remove.insert(name); } } @@ -291,4 +282,4 @@ double MapUpdateModule::dist(double px, double py, int idx, int idy) double dy = (py < ly) ? ly - py : ((py >= uy) ? py - uy : 0); return std::hypot(dx, dy); -} \ No newline at end of file +} diff --git a/map/map_loader/src/pointcloud_map_loader/differential_map_loader_module.cpp b/map/map_loader/src/pointcloud_map_loader/differential_map_loader_module.cpp index 00d6bfbee5df1..3b270b0084ccf 100644 --- a/map/map_loader/src/pointcloud_map_loader/differential_map_loader_module.cpp +++ b/map/map_loader/src/pointcloud_map_loader/differential_map_loader_module.cpp @@ -29,7 +29,6 @@ void DifferentialMapLoaderModule::differentialAreaLoad( const autoware_map_msgs::msg::AreaInfo & area, const std::vector & cached_ids, GetDifferentialPointCloudMap::Response::SharedPtr & response) const { - // For debug std::ofstream test("/home/anh/Work/autoware/test.txt", std::ios::app); @@ -91,7 +90,6 @@ autoware_map_msgs::msg::PointCloudMapCellWithID DifferentialMapLoaderModule::loadPointCloudMapCellWithID( const std::string & path, const std::string & map_id) const { - // For debug std::ofstream test("/home/anh/Work/autoware/test.txt", std::ios::app); From a181ab9b75efabd1bbcbd62c7bab32bb0e400dbf Mon Sep 17 00:00:00 2001 From: anhnv3991 Date: Fri, 5 Apr 2024 08:46:51 +0700 Subject: [PATCH 03/29] Keep timeout only Signed-off-by: anhnv3991 --- .../ndt_scan_matcher/map_update_module.hpp | 5 -- .../src/map_update_module.cpp | 83 +------------------ .../differential_map_loader_module.cpp | 20 ----- 3 files changed, 3 insertions(+), 105 deletions(-) diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp index d91a539f69021..2eb14b6004282 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp @@ -60,11 +60,6 @@ class MapUpdateModule [[nodiscard]] bool should_update_map(const geometry_msgs::msg::Point & position); void publish_partial_pcd_map(); - // Looking for PCDs in the vicinity of the specified location - void query_pcds(double px, double py, double radius, std::unordered_set& maps_to_add, std::unordered_set& maps_to_remove); - // Compute distance between an origin and a pcd segment - double dist(double px, double py, int idx, int idy); - rclcpp::Publisher::SharedPtr loaded_pcd_pub_; rclcpp::Client::SharedPtr diff --git a/localization/ndt_scan_matcher/src/map_update_module.cpp b/localization/ndt_scan_matcher/src/map_update_module.cpp index 18a2aec2efa45..9bb32b69dcad5 100644 --- a/localization/ndt_scan_matcher/src/map_update_module.cpp +++ b/localization/ndt_scan_matcher/src/map_update_module.cpp @@ -146,13 +146,8 @@ bool MapUpdateModule::update_ndt(const geometry_msgs::msg::Point & position, Ndt request, [](rclcpp::Client::SharedFuture) {})}; - // While waiting for the requested pcds, look for indices of the candidate pcds - std::unordered_set pcds_to_remove, pcds_to_add; - - query_pcds(position.x, position.y, param_.map_radius, pcds_to_add, pcds_to_remove); - - // Wait for maximum 20 milliseconds - std::chrono::milliseconds timeout(20); + // Wait for maximum 10 milliseconds + std::chrono::milliseconds timeout(10); auto start = std::chrono::system_clock::now(); std::future_status status = result.wait_for(std::chrono::seconds(0)); @@ -177,23 +172,7 @@ bool MapUpdateModule::update_ndt(const geometry_msgs::msg::Point & position, Ndt auto & maps_to_add = result.get()->new_pointcloud_with_ids; auto & map_ids_to_remove = result.get()->ids_to_remove; - // Check if there are any maps in the pcds_to_add not coming - for (auto& name : pcds_to_add) - { - if (maps_to_add.find(name) == maps_to_add.end()) - { - RCLCPP_ERROR_STREAM_THROTTLE(logger_, *clock_, 1000, "File %s not coming.", name.c_str()); - } - } - - for (auto& name : pcds_to_remove) - { - if (map_ids_to_remove.find(name) == map_ids_to_remove.end()) - { - RCLCPP_ERROR_STREAM_THROTTLE(logger_, *clock_, 1000, "File %s should be removed but it was not.", name.c_str()); - } - } - + // Check RCLCPP_INFO( logger_, "Update map (Add: %lu, Remove: %lu)", maps_to_add.size(), map_ids_to_remove.size()); if (maps_to_add.empty() && map_ids_to_remove.empty()) { @@ -236,59 +215,3 @@ void MapUpdateModule::publish_partial_pcd_map() loaded_pcd_pub_->publish(map_msg); } - -void MapUpdateModuble::query_pcds(double px, double py, double radius, std::unordered_set& maps_to_add, std::unordered_set& maps_to_remove) -{ - int lower_x = static_cast(floor((px - radius) / pcd_res_x_)); - int lower_y = static_cast(floor((py - radius) / pcd_res_y_)); - int upper_x = static_cast(floor((px + radius) / pcd_res_x_)); - int upper_y = static_cast(floor((py + radius) / pcd_res_y_)); - double rel_px = px - pcd_lower_x_, rel_py = py - pcd_lower_y_; - std::unordered_set nn_pcds; - - for (int idx = lower_x; idx < upper_x; ++idx) - { - for (int idy = lower_y; idy < upper_y; ++idy) - { - // Skip if the pcd file is not within the query radius - if (dist(rel_px, rel_py, idx, idy) > radius) - { - continue; - } - - // Generate name of the PCD file - std::string name = pcd_tag_ + "_" + std::to_string(x) + "_" + std::to_string(y) + ".pcd"; - - if (cur_pcds_.find(name) == cur_pcds_.end()) - { - maps_to_add.insert(name); - } - else - { - nn_pcds.insert(name); - } - } - } - - // Compare with @cur_pcds_ to find out which pcds to remove - for (auto& name : cur_pcds_) - { - if (nn_pcds.find(name) == nn_pcds.end()) - { - map_ids_to_remove.insert(name); - } - } -} - -double MapUpdateModule::dist(double px, double py, int idx, int idy) -{ - double lx = idx * pcd_res_x_; - double ly = idy * pcd_res_y_; - double ux = lx + pcd_res_x_; - double uy = ly + pcd_res_y_; - - double dx = (px < lx) ? lx - px : ((px >= ux) ? px - ux : 0); - double dy = (py < ly) ? ly - py : ((py >= uy) ? py - uy : 0); - - return std::hypot(dx, dy); -} \ No newline at end of file diff --git a/map/map_loader/src/pointcloud_map_loader/differential_map_loader_module.cpp b/map/map_loader/src/pointcloud_map_loader/differential_map_loader_module.cpp index 00d6bfbee5df1..a8d380fd81b86 100644 --- a/map/map_loader/src/pointcloud_map_loader/differential_map_loader_module.cpp +++ b/map/map_loader/src/pointcloud_map_loader/differential_map_loader_module.cpp @@ -29,13 +29,6 @@ void DifferentialMapLoaderModule::differentialAreaLoad( const autoware_map_msgs::msg::AreaInfo & area, const std::vector & cached_ids, GetDifferentialPointCloudMap::Response::SharedPtr & response) const { - - // For debug - std::ofstream test("/home/anh/Work/autoware/test.txt", std::ios::app); - - test << __FILE__ << "::" << __LINE__ << "::" << __func__ << std::endl; - // End - // iterate over all the available pcd map grids std::vector should_remove(static_cast(cached_ids.size()), true); for (const auto & ele : all_pcd_file_metadata_dict_) { @@ -74,12 +67,6 @@ bool DifferentialMapLoaderModule::onServiceGetDifferentialPointCloudMap( GetDifferentialPointCloudMap::Request::SharedPtr req, GetDifferentialPointCloudMap::Response::SharedPtr res) { - // For debug - std::ofstream test("/home/anh/Work/autoware/test.txt", std::ios::app); - - test << __FILE__ << "::" << __LINE__ << "::" << __func__ << std::endl; - // End - auto area = req->area; std::vector cached_ids = req->cached_ids; differentialAreaLoad(area, cached_ids, res); @@ -91,13 +78,6 @@ autoware_map_msgs::msg::PointCloudMapCellWithID DifferentialMapLoaderModule::loadPointCloudMapCellWithID( const std::string & path, const std::string & map_id) const { - - // For debug - std::ofstream test("/home/anh/Work/autoware/test.txt", std::ios::app); - - test << __FILE__ << "::" << __LINE__ << "::" << __func__ << std::endl; - // End - sensor_msgs::msg::PointCloud2 pcd; if (pcl::io::loadPCDFile(path, pcd) == -1) { RCLCPP_ERROR_STREAM(logger_, "PCD load failed: " << path); From e579421942aeb93424085f38bc4c746873f552e7 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Mon, 1 Apr 2024 18:44:18 +0900 Subject: [PATCH 04/29] docs(lane_change): update documentation (#6544) * docs(lane_change): update documentation Signed-off-by: Muhammad Zulfaqar Azmi * update validity check flow chart Signed-off-by: Muhammad Zulfaqar Azmi * explanation for the valid paths Signed-off-by: Muhammad Zulfaqar Azmi * Add prerequisite in the requirement Signed-off-by: Muhammad Zulfaqar Azmi * update diagram Signed-off-by: Muhammad Zulfaqar Azmi * Edit the parameters Signed-off-by: Muhammad Zulfaqar Azmi * Explaining lane expansion Signed-off-by: Muhammad Zulfaqar Azmi * fix lane expansion document Signed-off-by: Muhammad Zulfaqar Azmi --------- Signed-off-by: Muhammad Zulfaqar Azmi --- .../README.md | 404 ++++++++++++------ .../images/lane_change-lane_change_phases.png | Bin 181969 -> 33850 bytes .../lane_change-lane_expansion-with.png | Bin 0 -> 25187 bytes .../lane_change-lane_expansion-without.png | Bin 0 -> 25525 bytes 4 files changed, 280 insertions(+), 124 deletions(-) create mode 100644 planning/behavior_path_lane_change_module/images/lane_change-lane_expansion-with.png create mode 100644 planning/behavior_path_lane_change_module/images/lane_change-lane_expansion-without.png diff --git a/planning/behavior_path_lane_change_module/README.md b/planning/behavior_path_lane_change_module/README.md index 8eb791ab4f5e9..874d542b445d3 100644 --- a/planning/behavior_path_lane_change_module/README.md +++ b/planning/behavior_path_lane_change_module/README.md @@ -4,6 +4,11 @@ The Lane Change module is activated when lane change is needed and can be safely ## Lane Change Requirement +- As the prerequisite, the type of lane boundary in the HD map has to be one of the following: + - Dashed lane marking: Lane changes are permitted in both directions. + - Dashed marking on the left and solid on the right: Lane changes are allowed from left to right. + - Dashed marking on the right and solid on the left: Lane changes are allowed from right to left. + - `allow_lane_change` tags is set as `true` - During lane change request condition - The ego-vehicle isn’t on a `preferred_lane`. - There is neither intersection nor crosswalk on the path of the lane change @@ -60,6 +65,89 @@ longitudinal_acceleration_resolution = (maximum_longitudinal_acceleration - mini Note that when the `current_velocity` is lower than `minimum_lane_changing_velocity`, the vehicle needs to accelerate its velocity to `minimum_lane_changing_velocity`. Therefore, longitudinal acceleration becomes positive value (not decelerate). +The chart illustrates the conditions under which longitudinal acceleration values are sampled. + +```plantuml +@startuml +skinparam defaultTextAlignment center +skinparam backgroundColor #WHITE + +start + +if (prev_module_path is empty?) then (yes) + :Return empty list; + stop +else (no) +endif + +if (max_acc <= 0.0) then (yes) + :Return **sampled acceleration values**; + note left: Calculated sampled acceleration using\ngetAccelerationValues(min_acc, max_acc, longitudinal_acc_sampling_num) + stop +endif + +if (max_lane_change_length > ego's distance to the end of the current lanes.) then (yes) + :Return **sampled acceleration values**; + stop +endif + +if (isVehicleStuck(current_lanes)) then (yes) + :Return **sampled acceleration values**; + stop +else (no) +endif + +if (is goal is in target lanes) then (yes) + if (max_lane_change_length < ego's distance to the goal along the target lanes) then (yes) + :Return {max_acc}; + stop + else (no) + endif +else (no) + if (max_lane_change_length < ego's distance to the end of the target lanes.) then (yes) + :Return {max_acc}; + stop + else (no) + endif +endif + +:Return **sampled acceleration values**; +stop + +@enduml + +``` + +while the following describes the process by which longitudinal accelerations are sampled. + +```plantuml +@startuml +start +:Initialize sampled_values with min_acc; + +if (min_acc > max_acc) then (yes) + :Return empty list; + stop +elseif (max_acc - min_acc < epsilon) then (yes) + :Return {0.0}; + stop +else (no) + :Calculate resolution; +endif + +:Start loop from min_acc to max_acc with resolution step; +repeat + if (sampled_values.back() < -epsilon AND next_value > epsilon) then (yes) + :Insert 0.0 into sampled_values; + endif + :Add sampled_acc to sampled_values; + repeat while (sampled_acc < max_acc + epsilon) is (TRUE) + +:Return sampled_values; +stop +@enduml +``` + The following figure illustrates when `longitudinal_acceleration_sampling_num = 4`. Assuming that `maximum_deceleration = 1.0` then `a0 == 0.0 == no deceleration`, `a1 == 0.25`, `a2 == 0.5`, `a3 == 0.75` and `a4 == 1.0 == maximum_deceleration`. `a0` is the expected lane change trajectories should ego vehicle do not decelerate, and `a1`'s path is the expected lane change trajectories should ego vehicle decelerate at `0.25 m/s^2`. ![path_samples](./images/lane_change-candidate_path_samples.png) @@ -89,67 +177,112 @@ lateral_acceleration_resolution = (maximum_lateral_acceleration - minimum_latera #### Candidate Path's validity check -A candidate path is valid if the total lane change distance is less than +A candidate path is considered valid if it meets the following criteria: -1. distance to the end of current lane -2. distance to the next intersection -3. distance from current pose to the goal. -4. distance to the crosswalk. - -The goal must also be in the list of the preferred lane. +1. The distance from the ego vehicle's current position to the end of the current lanes is sufficient to perform a single lane change. +2. The distance from the ego vehicle's current position to the goal along the current lanes is adequate to complete multiple lane changes. +3. The distance from the ego vehicle's current position to the end of the target lanes is adequate for completing multiple lane changes. +4. Intersection requirements are met (conditions are parameterized). +5. Crosswalk requirements are satisfied (conditions are parameterized). +6. Traffic light regulations are adhered to (conditions are parameterized). +7. The lane change can be completed after passing a parked vehicle. +8. The lane change is deemed safe to execute. The following flow chart illustrates the validity check. ```plantuml @startuml -skinparam monochrome true skinparam defaultTextAlignment center -skinparam noteTextAlignment left +skinparam backgroundColor #White -title Selecting Valid Candidate Paths start -:**INPUT** std::vector input_paths; +if (Check if start point is valid by check if it is covered by neighbour lanes polygon) then (not covered) + #LightPink:Reject path; + stop +else (covered) +endif -partition selectValidPaths { -:**INITIALIZE** std::vector valid_paths; +group check for distance #LightYellow + :Calculate total length and goal related distances; + if (total lane change length considering single lane change > distance from current pose to end of current lanes) then (yes) + #LightPink:Reject path; + stop + else (no) + endif -:idx = 0; + if (goal is in current lanes) then (yes) + if (total lane change length considering multiple lane changes > distance from ego to goal along current lanes) then (yes) + #LightPink:Reject path; + stop + else (no) + endif + else (no) + endif -while (idx < input_paths.size()?) + if (target lanes is empty) then (yes) + #LightPink:Reject path; + stop + else (no) + endif + if (total lane change length considering multiple lane changes > distance from ego to the end of target lanes) then (yes) + #LightPink:Reject path; + stop + else (no) + endif +end group -:path = input_paths.at(idx); -partition hasEnoughDistance { -if(lane_change_total_distance < distance to end of current lanes -&& -lane_change_total_distance < distance to the next intersection -&& -lane_change_total_distance < distance from current pose to the goal -&& -lane_change_total_distance < distance to crosswalk -&& -goal is in route -) then (true) -:path_validity = true; -else (\n false) -:path_validity = false; +group evaluate on Crosswalk #LightCyan +if (regulate_on_crosswalk and not enough length to crosswalk) then (yes) + if (stop time < stop time threshold\n(Related to stuck detection)) then (yes) + #LightPink:Reject path; + stop + else (no) + :Allow lane change in crosswalk; + endif +else (no) endif -} +end group -if(path_validity == true)then (true) - -:valid_paths.push_back(path); +group evaluate on Intersection #LightGreen +if (regulate_on_intersection and not enough length to intersection) then (yes) + if (stop time < stop time threshold\n(Related to stuck detection)) then (yes) + #LightPink:Reject path; + stop + else (no) + :Allow lane change in intersection; + endif +else (no) +endif +end group + +group evaluate on Traffic Light #Lavender +if (regulate_on_traffic_light and not enough length to complete lane change before stop line) then (yes) + #LightPink:Reject path; + stop +elseif (stopped at red traffic light within distance) then (yes) + #LightPink:Reject path; + stop +else (no) +endif +end group -else (\nfalse) +if (ego is not stuck but parked vehicle exists in target lane) then (yes) + #LightPink:Reject path; + stop +else (no) endif -:++idx; -endwhile (false) -:**RETURN** valid_paths; +if (is safe to perform lane change) then (yes) + #Cyan:Return candidate path list; + stop +else (no) + #LightPink:Reject path; +endif -} stop + @enduml ``` @@ -165,6 +298,27 @@ First, we divide the target objects into obstacles in the target lane, obstacles Furthermore, to change lanes behind a vehicle waiting at a traffic light, we skip the safety check for the stopping vehicles near the traffic light. The explanation for parked car detection is written in [documentation for avoidance module](../behavior_path_avoidance_module/README.md). +The detection area for the target lane can be expanded beyond its original boundaries to enable detection of objects that are outside the target lane's limits. + +
+ + + + + +
+
+
Without Lane Expansion
+ Without lane expansion +
+
+
+
With Lane Expansion
+ With lane expansion +
+
+
+ ##### Collision check in prepare phase The ego vehicle may need to secure ample inter-vehicle distance ahead of the target vehicle before attempting a lane change. The flag `enable_collision_check_at_prepare_phase` can be enabled to gain this behavior. The following image illustrates the differences between the `false` and `true` cases. @@ -333,45 +487,38 @@ The last behavior will also occur if the ego vehicle has departed from the curre ### Essential lane change parameters -The following parameters are configurable in `lane_change.param.yaml`. - -| Name | Unit | Type | Description | Default value | -| :------------------------------------------- | ------ | ------- | ---------------------------------------------------------------------------------------------------------------------- | ------------------ | -| `backward_lane_length` | [m] | double | The backward length to check incoming objects in lane change target lane. | 200.0 | -| `prepare_duration` | [m] | double | The preparation time for the ego vehicle to be ready to perform lane change. | 4.0 | -| `backward_length_buffer_for_end_of_lane` | [m] | double | The end of lane buffer to ensure ego vehicle has enough distance to start lane change | 3.0 | -| `backward_length_buffer_for_blocking_object` | [m] | double | The end of lane buffer to ensure ego vehicle has enough distance to start lane change when there is an object in front | 3.0 | -| `lane_change_finish_judge_buffer` | [m] | double | The additional buffer used to confirm lane change process completion | 3.0 | -| `finish_judge_lateral_threshold` | [m] | double | Lateral distance threshold to confirm lane change process completion | 0.2 | -| `lane_changing_lateral_jerk` | [m/s3] | double | Lateral jerk value for lane change path generation | 0.5 | -| `minimum_lane_changing_velocity` | [m/s] | double | Minimum speed during lane changing process. | 2.78 | -| `prediction_time_resolution` | [s] | double | Time resolution for object's path interpolation and collision check. | 0.5 | -| `longitudinal_acceleration_sampling_num` | [-] | int | Number of possible lane-changing trajectories that are being influenced by longitudinal acceleration | 5 | -| `lateral_acceleration_sampling_num` | [-] | int | Number of possible lane-changing trajectories that are being influenced by lateral acceleration | 3 | -| `object_check_min_road_shoulder_width` | [m] | double | Width considered as a road shoulder if the lane does not have a road shoulder | 0.5 | -| `object_shiftable_ratio_threshold` | [-] | double | Vehicles around the center line within this distance ratio will be excluded from parking objects | 0.6 | -| `min_length_for_turn_signal_activation` | [m] | double | Turn signal will be activated if the ego vehicle approaches to this length from minimum lane change length | 10.0 | -| `length_ratio_for_turn_signal_deactivation` | [-] | double | Turn signal will be deactivated if the ego vehicle approaches to this length ratio for lane change finish point | 0.8 | -| `max_longitudinal_acc` | [-] | double | maximum longitudinal acceleration for lane change | 1.0 | -| `min_longitudinal_acc` | [-] | double | maximum longitudinal deceleration for lane change | -1.0 | -| `lateral_acceleration.velocity` | [m/s] | double | Reference velocity for lateral acceleration calculation (look up table) | [0.0, 4.0, 10.0] | -| `lateral_acceleration.min_values` | [m/ss] | double | Min lateral acceleration values corresponding to velocity (look up table) | [0.15, 0.15, 0.15] | -| `lateral_acceleration.max_values` | [m/ss] | double | Max lateral acceleration values corresponding to velocity (look up table) | [0.5, 0.5, 0.5] | -| `target_object.car` | [-] | boolean | Include car objects for safety check | true | -| `target_object.truck` | [-] | boolean | Include truck objects for safety check | true | -| `target_object.bus` | [-] | boolean | Include bus objects for safety check | true | -| `target_object.trailer` | [-] | boolean | Include trailer objects for safety check | true | -| `target_object.unknown` | [-] | boolean | Include unknown objects for safety check | true | -| `target_object.bicycle` | [-] | boolean | Include bicycle objects for safety check | true | -| `target_object.motorcycle` | [-] | boolean | Include motorcycle objects for safety check | true | -| `target_object.pedestrian` | [-] | boolean | Include pedestrian objects for safety check | true | +The following parameters are configurable in [lane_change.param.yaml](https://github.com/autowarefoundation/autoware_launch/blob/main/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml) + +| Name | Unit | Type | Description | Default value | +| :------------------------------------------- | ------ | ------ | ---------------------------------------------------------------------------------------------------------------------- | ------------------ | +| `backward_lane_length` | [m] | double | The backward length to check incoming objects in lane change target lane. | 200.0 | +| `prepare_duration` | [m] | double | The preparation time for the ego vehicle to be ready to perform lane change. | 4.0 | +| `backward_length_buffer_for_end_of_lane` | [m] | double | The end of lane buffer to ensure ego vehicle has enough distance to start lane change | 3.0 | +| `backward_length_buffer_for_blocking_object` | [m] | double | The end of lane buffer to ensure ego vehicle has enough distance to start lane change when there is an object in front | 3.0 | +| `lane_change_finish_judge_buffer` | [m] | double | The additional buffer used to confirm lane change process completion | 2.0 | +| `finish_judge_lateral_threshold` | [m] | double | Lateral distance threshold to confirm lane change process completion | 0.2 | +| `lane_changing_lateral_jerk` | [m/s3] | double | Lateral jerk value for lane change path generation | 0.5 | +| `minimum_lane_changing_velocity` | [m/s] | double | Minimum speed during lane changing process. | 2.78 | +| `prediction_time_resolution` | [s] | double | Time resolution for object's path interpolation and collision check. | 0.5 | +| `longitudinal_acceleration_sampling_num` | [-] | int | Number of possible lane-changing trajectories that are being influenced by longitudinal acceleration | 3 | +| `lateral_acceleration_sampling_num` | [-] | int | Number of possible lane-changing trajectories that are being influenced by lateral acceleration | 3 | +| `object_check_min_road_shoulder_width` | [m] | double | Width considered as a road shoulder if the lane does not have a road shoulder | 0.5 | +| `object_shiftable_ratio_threshold` | [-] | double | Vehicles around the center line within this distance ratio will be excluded from parking objects | 0.6 | +| `min_length_for_turn_signal_activation` | [m] | double | Turn signal will be activated if the ego vehicle approaches to this length from minimum lane change length | 10.0 | +| `length_ratio_for_turn_signal_deactivation` | [-] | double | Turn signal will be deactivated if the ego vehicle approaches to this length ratio for lane change finish point | 0.8 | +| `max_longitudinal_acc` | [-] | double | maximum longitudinal acceleration for lane change | 1.0 | +| `min_longitudinal_acc` | [-] | double | maximum longitudinal deceleration for lane change | -1.0 | +| `lateral_acceleration.velocity` | [m/s] | double | Reference velocity for lateral acceleration calculation (look up table) | [0.0, 4.0, 10.0] | +| `lateral_acceleration.min_values` | [m/ss] | double | Min lateral acceleration values corresponding to velocity (look up table) | [0.4, 0.4, 0.4] | +| `lateral_acceleration.max_values` | [m/ss] | double | Max lateral acceleration values corresponding to velocity (look up table) | [0.65, 0.65, 0.65] | ### Lane change regulations -| Name | Unit | Type | Description | Default value | -| :------------------------ | ---- | ------- | ------------------------------------- | ------------- | -| `regulation.crosswalk` | [-] | boolean | Regulate lane change on crosswalks | false | -| `regulation.intersection` | [-] | boolean | Regulate lane change on intersections | false | +| Name | Unit | Type | Description | Default value | +| :------------------------- | ---- | ------- | ---------------------------------------------------------- | ------------- | +| `regulation.crosswalk` | [-] | boolean | Allow lane change in between crosswalks | true | +| `regulation.intersection` | [-] | boolean | Allow lane change in between intersections | true | +| `regulation.traffic_light` | [-] | boolean | Allow lane change to be performed in between traffic light | true | ### Ego vehicle stuck detection @@ -380,9 +527,20 @@ The following parameters are configurable in `lane_change.param.yaml`. | `stuck_detection.velocity` | [m/s] | double | Velocity threshold for ego vehicle stuck detection | 0.1 | | `stuck_detection.stop_time` | [s] | double | Stop time threshold for ego vehicle stuck detection | 3.0 | -### Collision checks during lane change +### Collision checks + +#### Target Objects -The following parameters are configurable in `behavior_path_planner.param.yaml` and `lane_change.param.yaml`. +| Name | Unit | Type | Description | Default value | +| :------------------------- | ---- | ------- | ------------------------------------------- | ------------- | +| `target_object.car` | [-] | boolean | Include car objects for safety check | true | +| `target_object.truck` | [-] | boolean | Include truck objects for safety check | true | +| `target_object.bus` | [-] | boolean | Include bus objects for safety check | true | +| `target_object.trailer` | [-] | boolean | Include trailer objects for safety check | true | +| `target_object.unknown` | [-] | boolean | Include unknown objects for safety check | true | +| `target_object.bicycle` | [-] | boolean | Include bicycle objects for safety check | true | +| `target_object.motorcycle` | [-] | boolean | Include motorcycle objects for safety check | true | +| `target_object.pedestrian` | [-] | boolean | Include pedestrian objects for safety check | true | #### common @@ -391,53 +549,51 @@ The following parameters are configurable in `behavior_path_planner.param.yaml` | `safety_check.lane_expansion.left_offset` | [m] | double | Expand the left boundary of the detection area, allowing objects previously outside on the left to be detected and registered as targets. | 0.0 | | `safety_check.lane_expansion.right_offset` | [m] | double | Expand the right boundary of the detection area, allowing objects previously outside on the right to be detected and registered as targets. | 0.0 | -#### execution - -| Name | Unit | Type | Description | Default value | -| :---------------------------------------------------------------- | ------- | ------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------- | -| `safety_check.execution.lateral_distance_max_threshold` | [m] | double | The lateral distance threshold that is used to determine whether lateral distance between two object is enough and whether lane change is safe. | 2.0 | -| `safety_check.execution.longitudinal_distance_min_threshold` | [m] | double | The longitudinal distance threshold that is used to determine whether longitudinal distance between two object is enough and whether lane change is safe. | 3.0 | -| `safety_check.execution.expected_front_deceleration` | [m/s^2] | double | The front object's maximum deceleration when the front vehicle perform sudden braking. (\*1) | -1.0 | -| `safety_check.execution.expected_rear_deceleration` | [m/s^2] | double | The rear object's maximum deceleration when the rear vehicle perform sudden braking. (\*1) | -1.0 | -| `safety_check.execution.rear_vehicle_reaction_time` | [s] | double | The reaction time of the rear vehicle driver which starts from the driver noticing the sudden braking of the front vehicle until the driver step on the brake. | 2.0 | -| `safety_check.execution.rear_vehicle_safety_time_margin` | [s] | double | The time buffer for the rear vehicle to come into complete stop when its driver perform sudden braking. | 2.0 | -| `safety_check.execution.enable_collision_check_at_prepare_phase` | [-] | boolean | Perform collision check starting from prepare phase. If `false`, collision check only evaluated for lane changing phase. | true | -| `safety_check.execution.prepare_phase_ignore_target_speed_thresh` | [m/s] | double | Ignore collision check in prepare phase of object speed that is lesser that the configured value. `enable_collision_check_at_prepare_phase` must be `true` | 0.1 | -| `safety_check.execution.check_objects_on_current_lanes` | [-] | boolean | If true, the lane change module include objects on current lanes. | true | -| `safety_check.execution.check_objects_on_other_lanes` | [-] | boolean | If true, the lane change module include objects on other lanes. | true | -| `safety_check.execution.use_all_predicted_path` | [-] | boolean | If false, use only the predicted path that has the maximum confidence. | true | - -##### cancel - -| Name | Unit | Type | Description | Default value | -| :------------------------------------------------------------- | ------- | ------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------- | -| `safety_check.cancel.lateral_distance_max_threshold` | [m] | double | The lateral distance threshold that is used to determine whether lateral distance between two object is enough and whether lane change is safe. | 1.5 | -| `safety_check.cancel.longitudinal_distance_min_threshold` | [m] | double | The longitudinal distance threshold that is used to determine whether longitudinal distance between two object is enough and whether lane change is safe. | 3.0 | -| `safety_check.cancel.expected_front_deceleration` | [m/s^2] | double | The front object's maximum deceleration when the front vehicle perform sudden braking. (\*1) | -1.5 | -| `safety_check.cancel.expected_rear_deceleration` | [m/s^2] | double | The rear object's maximum deceleration when the rear vehicle perform sudden braking. (\*1) | -2.5 | -| `safety_check.cancel.rear_vehicle_reaction_time` | [s] | double | The reaction time of the rear vehicle driver which starts from the driver noticing the sudden braking of the front vehicle until the driver step on the brake. | 2.0 | -| `safety_check.cancel.rear_vehicle_safety_time_margin` | [s] | double | The time buffer for the rear vehicle to come into complete stop when its driver perform sudden braking. | 2.5 | -| `safety_check.cancel.enable_collision_check_at_prepare_phase` | [-] | boolean | Perform collision check starting from prepare phase. If `false`, collision check only evaluated for lane changing phase. | false | -| `safety_check.cancel.prepare_phase_ignore_target_speed_thresh` | [m/s] | double | Ignore collision check in prepare phase of object speed that is lesser that the configured value. `enable_collision_check_at_prepare_phase` must be `true` | 0.2 | -| `safety_check.cancel.check_objects_on_current_lanes` | [-] | boolean | If true, the lane change module include objects on current lanes. | false | -| `safety_check.cancel.check_objects_on_other_lanes` | [-] | boolean | If true, the lane change module include objects on other lanes. | false | -| `safety_check.cancel.use_all_predicted_path` | [-] | boolean | If false, use only the predicted path that has the maximum confidence. | false | - -##### stuck - -| Name | Unit | Type | Description | Default value | -| :------------------------------------------------------------ | ------- | ------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------- | -| `safety_check.stuck.lateral_distance_max_threshold` | [m] | double | The lateral distance threshold that is used to determine whether lateral distance between two object is enough and whether lane change is safe. | 2.0 | -| `safety_check.stuck.longitudinal_distance_min_threshold` | [m] | double | The longitudinal distance threshold that is used to determine whether longitudinal distance between two object is enough and whether lane change is safe. | 3.0 | -| `safety_check.stuck.expected_front_deceleration` | [m/s^2] | double | The front object's maximum deceleration when the front vehicle perform sudden braking. (\*1) | -1.0 | -| `safety_check.stuck.expected_rear_deceleration` | [m/s^2] | double | The rear object's maximum deceleration when the rear vehicle perform sudden braking. (\*1) | -1.0 | -| `safety_check.stuck.rear_vehicle_reaction_time` | [s] | double | The reaction time of the rear vehicle driver which starts from the driver noticing the sudden braking of the front vehicle until the driver step on the brake. | 2.0 | -| `safety_check.stuck.rear_vehicle_safety_time_margin` | [s] | double | The time buffer for the rear vehicle to come into complete stop when its driver perform sudden braking. | 2.0 | -| `safety_check.stuck.enable_collision_check_at_prepare_phase` | [-] | boolean | Perform collision check starting from prepare phase. If `false`, collision check only evaluated for lane changing phase. | true | -| `safety_check.stuck.prepare_phase_ignore_target_speed_thresh` | [m/s] | double | Ignore collision check in prepare phase of object speed that is lesser that the configured value. `enable_collision_check_at_prepare_phase` must be `true` | 0.1 | -| `safety_check.stuck.check_objects_on_current_lanes` | [-] | boolean | If true, the lane change module include objects on current lanes. | true | -| `safety_check.stuck.check_objects_on_other_lanes` | [-] | boolean | If true, the lane change module include objects on other lanes. | true | -| `safety_check.stuck.use_all_predicted_path` | [-] | boolean | If false, use only the predicted path that has the maximum confidence. | true | +#### Additional parameters + +| Name | Unit | Type | Description | Default value | +| :----------------------------------------- | ----- | ------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------- | +| `enable_collision_check_at_prepare_phase` | [-] | boolean | Perform collision check starting from prepare phase. If `false`, collision check only evaluated for lane changing phase. | false | +| `prepare_phase_ignore_target_speed_thresh` | [m/s] | double | Ignore collision check in prepare phase of object speed that is lesser that the configured value. `enable_collision_check_at_prepare_phase` must be `true` | 0.1 | +| `check_objects_on_current_lanes` | [-] | boolean | If true, the lane change module check objects on current lanes when performing collision assessment. | false | +| `check_objects_on_other_lanes` | [-] | boolean | If true, the lane change module include objects on other lanes. when performing collision assessment | false | +| `use_all_predicted_path` | [-] | boolean | If false, use only the predicted path that has the maximum confidence. | true | + +#### safety constraints during lane change path is computed + +| Name | Unit | Type | Description | Default value | +| :----------------------------------------------------------- | ------- | ------ | -------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------- | +| `safety_check.execution.expected_front_deceleration` | [m/s^2] | double | The front object's maximum deceleration when the front vehicle perform sudden braking. (\*1) | -1.0 | +| `safety_check.execution.expected_rear_deceleration` | [m/s^2] | double | The rear object's maximum deceleration when the rear vehicle perform sudden braking. (\*1) | -1.0 | +| `safety_check.execution.rear_vehicle_reaction_time` | [s] | double | The reaction time of the rear vehicle driver which starts from the driver noticing the sudden braking of the front vehicle until the driver step on the brake. | 2.0 | +| `safety_check.execution.rear_vehicle_safety_time_margin` | [s] | double | The time buffer for the rear vehicle to come into complete stop when its driver perform sudden braking. | 1.0 | +| `safety_check.execution.lateral_distance_max_threshold` | [m] | double | The lateral distance threshold that is used to determine whether lateral distance between two object is enough and whether lane change is safe. | 2.0 | +| `safety_check.execution.longitudinal_distance_min_threshold` | [m] | double | The longitudinal distance threshold that is used to determine whether longitudinal distance between two object is enough and whether lane change is safe. | 3.0 | +| `safety_check.cancel.longitudinal_velocity_delta_time` | [m] | double | The time multiplier that is used to compute the actual gap between vehicle at each predicted points (not RSS distance) | 0.8 | + +##### safety constraints to cancel lane change path + +| Name | Unit | Type | Description | Default value | +| :-------------------------------------------------------- | ------- | ------ | -------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------- | +| `safety_check.cancel.expected_front_deceleration` | [m/s^2] | double | The front object's maximum deceleration when the front vehicle perform sudden braking. (\*1) | -1.0 | +| `safety_check.cancel.expected_rear_deceleration` | [m/s^2] | double | The rear object's maximum deceleration when the rear vehicle perform sudden braking. (\*1) | -2.0 | +| `safety_check.cancel.rear_vehicle_reaction_time` | [s] | double | The reaction time of the rear vehicle driver which starts from the driver noticing the sudden braking of the front vehicle until the driver step on the brake. | 1.5 | +| `safety_check.cancel.rear_vehicle_safety_time_margin` | [s] | double | The time buffer for the rear vehicle to come into complete stop when its driver perform sudden braking. | 0.8 | +| `safety_check.cancel.lateral_distance_max_threshold` | [m] | double | The lateral distance threshold that is used to determine whether lateral distance between two object is enough and whether lane change is safe. | 1.0 | +| `safety_check.cancel.longitudinal_distance_min_threshold` | [m] | double | The longitudinal distance threshold that is used to determine whether longitudinal distance between two object is enough and whether lane change is safe. | 2.5 | +| `safety_check.cancel.longitudinal_velocity_delta_time` | [m] | double | The time multiplier that is used to compute the actual gap between vehicle at each predicted points (not RSS distance) | 0.6 | + +##### safety constraints used during lane change path is computed when ego is stuck + +| Name | Unit | Type | Description | Default value | +| :------------------------------------------------------- | ------- | ------ | -------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------- | +| `safety_check.stuck.expected_front_deceleration` | [m/s^2] | double | The front object's maximum deceleration when the front vehicle perform sudden braking. (\*1) | -1.0 | +| `safety_check.stuck.expected_rear_deceleration` | [m/s^2] | double | The rear object's maximum deceleration when the rear vehicle perform sudden braking. (\*1) | -1.0 | +| `safety_check.stuck.rear_vehicle_reaction_time` | [s] | double | The reaction time of the rear vehicle driver which starts from the driver noticing the sudden braking of the front vehicle until the driver step on the brake. | 2.0 | +| `safety_check.stuck.rear_vehicle_safety_time_margin` | [s] | double | The time buffer for the rear vehicle to come into complete stop when its driver perform sudden braking. | 1.0 | +| `safety_check.stuck.lateral_distance_max_threshold` | [m] | double | The lateral distance threshold that is used to determine whether lateral distance between two object is enough and whether lane change is safe. | 2.0 | +| `safety_check.stuck.longitudinal_distance_min_threshold` | [m] | double | The longitudinal distance threshold that is used to determine whether longitudinal distance between two object is enough and whether lane change is safe. | 3.0 | +| `safety_check.stuck.longitudinal_velocity_delta_time` | [m] | double | The time multiplier that is used to compute the actual gap between vehicle at each predicted points (not RSS distance) | 0.8 | (\*1) the value must be negative. diff --git a/planning/behavior_path_lane_change_module/images/lane_change-lane_change_phases.png b/planning/behavior_path_lane_change_module/images/lane_change-lane_change_phases.png index 411a72c30b88a29add6202a6de3916d202bafb7c..efd1df086544dab24323fe247b38d1591119d9dc 100644 GIT binary patch literal 33850 zcmb5W1yojFxAqN4hlHeb2~sy9-Q6kOAfZS%(%mVY0-|(>bazQfNsFX(=eKVE&w1bH zoacOFeBT%j9RqLn-fQi(=Dg-_Uh585QIf_$eU1tP1A`$eBcTQZ^F$8@29^^U5&Q(( z;0F2+tdp9w7)<#X$qoz*1&pkOsJgr1eiqs{jG5bhBh~n38rp^gdD$S9a?1F^U%Iv^ zNsf_uI8CyN>T(J446|~%&e(Zzcln>`DHA*s^@{Ft4u=-nz3aWl(&jllFVfQvKV)ae zI9dGoFuRrIap`s0{DWU7hFsW3e@;!wxH|+xt;u;OaZ&V%j34~J|M^K77i>CA8mHt* z#BH1Dy!T`D9k)QvfBT3`2NoQzUI(( zl<+$q$9X}PC;^^HHt7A=_lQsUYu%Yp;`~U#-Tt|xKLxh&9a;kSJud+m&Rw6eaTxVm zL=^Zqm<@TDtf80jFeuvKPL?RoFy*LVBg$yH>ZUjY{YiBn_*@TuHaaf3%nsfjwnJw1 zouXCyAiA|OyE7$p9F}8=8MaM>^owt!Ji#+RywPd>;BpN0z;hDuImp%B0*87Xa0_*u|mZ()j0$ja=s#lG4ePBS4^6{@ZKDtW0o47km z%?$+I^UniKhw;lrNJp*+=-qA{*`e2s?pzg?zB?TkcD%cCIR8_KGFmS9_;6c+ORpkA z=5^E=Hpgy4wlgnMWnS&}vnKi&tgF_N!5l$V>+2~yTkX-SEkwzSwIHxyo_%1+CayI; z8sk44IG;6wkb52ZkEF7RTa0HjBVm#y%0pV!vps$j6{+Tjr!FSw(_rS?$g{YDF3)n&~B`^VQ~7rE}&%o|gw20oG%g zyw&e#S$I!JIA(CfS$VcHoz%(6z0czHz0YSN23tH%f6ZtaB|SlUD%0q=`K#z_b^@Qv z?q^Q~-Oaq-9~pLSFIRjYTU)NyBdhIJggE=cu&JkU#FyAJ+J&CF3f=D4oOELfBllRQ zv73L^sxX{v^S+fa()8L}|ATi^9)NFz5q}eW)g#xz}->z)nzHb@Zm=KH|+mx|~E3UPlQ9F{W+@_jraj98)AiS3UyzkLX3o59x;iz6nYt6A&1=GUJg$ey)KZBC95{=MIFrGu84T^&1jrw zBWeK4b_~skkJ42sTR_L>_768+4)_!^rr=rJ9e4rN7NgHOZTH#5N`97JkjEMo$R$l% zijQXtZu%pUsW_l3*tT6;5D9sG%lxogBx@4t9!B`o_i(vY&wKDkrHQ!5dN>^w8_5&? zMl$wh!z;J<@Pv=04(qCe)FM?$0`>JDp6ar8JbZqkm_Bg5l>=#5{!ntWy4dF3{L^*O zM(%92^Namjm)zCrlilKy@&wb~h@zZhKYt`5f$a*zR$aj>eb;&OU08VXgY9Qji1Uz= zjn!@vOjRr#cPs|OmT#r{jcVsh^)`Co4Md!1NnMz^KIDprnjNqA$_cFdmx74~A@kk! zuaC-;VP)+PH}Wj)caGP`{p6eR(qz~IOvXiP_m?XW%N+0ebPlp*d=~w}Z^j4O>2p2Pryaf>QWRtL zQ-n|~caTw`Uc#0?o;|;LKam$4K^~UEr@0nMxX&i8(BTd4(q23_TOdzh-rs!KR?_E3 zC}u70*^ z?i(1r`M!@2Lpi#IO@mLJdI{cLp}*9vEwo;!l|AmaBryFpwMRMeK65Ke!S6U$OR^Y6 z#kyeO30)tiE^Df=ZyOG>`%y=?pDo`lhvP4q#;t5mni~`Hbun&%)KA7wgkBv}d|o`; znJQ4s;9`IOgX!GZ)P+QViD-jnnQjphB{I4IVS#1r%qh3sG83(QvN|T! zhjC47e{^JiUiPv&T5Eb7!}K`8LW^$0{_0%1ELr>vM}ZO>o5#kxeTACin!t+7zl zsWy}S44H#5DebT1^A+%FJDZf3!!fO2?85;>{(-!2}@HY@H+=#?At7XtEB_wK7FH+l;r|#jbm1k*`Fn5aInUK#t z-V6}h0?|Wu))~2ZN?F(-yoE`px^N?IM!K{^Fc4BfQEx1L)*1_Wb+n1yRyyhWjTbV4 zlt%645Tt?B1ZG09_czF)Um5FbTZtTMrhEn5k6yBS4bZGdzFfj0KIS*eT1DfY7ey9_ zr$!66PPa{^Ypd+GR0QFU)BrQwa6{nG3@*yIg+Wcx&y;b7jEBwVdw{>sobSW+)(m$` zQ!Wl+TdvJ~bpejrjfqht#9ROJV9EUM>UcM!dz+RIOY&;9f2BW)=oz+NTJ*>4jQGyZ zKooYKE2&q4o~7A#lGdU!ikUpBK9Bd811FManEnBnZ_O%?+-%T(hhy3;#k~}VeTu9c z*6TjX;>(oZv{&9tWw3*8B=u%>Romx?x=m3kx!i80ZP%ZsUgx}wvcZC41XG6v=@mWlQW@sibSd6_BhLr5u#DRQ}QmdRv4l~W+Z*#1GsGRr05 zdf&{hNezUGm_Z~ql%!sjQvVJSSsSQF_dR7kdx)D{7Y@@9R+DV zc%Qahf#~LL{y80{SF>2q-t_Jh!jt>TSUa<-3d*LnC#WkTK38j@*rNXC5beHv;^fKI z#ouSTr@u#Mgjh>9K9QS+QZO7rw%_-A4{t)^wXpGCG3 zRAH=twwfunGTgzd_}<>%hGBNS&RL?rA7v6u?k=V;PQS7C#K|90^-K0pvSwFL+;&tX z6}$E-q42e7FTMmC*#LHAB?K39;w^aRUz;o(Nb?J{^kLikJ?7|w%m=l}GF2l-kG9{O zH|9%44^<}Q;PHR|nsF+|g=PwO%d4u&*+i+AHNh^%c(Je}Os02*Yt&`3W9i&YVDGl# z-QaaGZ|T^Jr=@+8OX^B*7Yo6t3c@ymF}?QO`%zZ#ZtBYrI^C>z-YoZcq%t%pNd0?I z_>Ot&F4E8bZ962o#~oSvIO>e-;@CfUAN7H(!sL`^s8Ej-DI>8e7LJIL$tb9@YZAwc zg4zj}vEFor-~8N*(G)G1wGtOOt#l5NYc9~QmE1K*#adXiQJb`T_pXj~?p5qMxqDb} zPJEU`Jf^^z_J3PoRi{1fa+%CI z3*@cV9k4B!Ee#{c-22@^q1o{wd#>w5re`9GUGI1q4WC)<&sh%mks*JpvK)CJl_34d z6SmL*1>2f#o-0QbMhq;wDt!`3|H=gzMz~CUuqjsrVof7w{nCKWML(ARP8Kq$*B62* zsXo%xja+PAa9QcwPwF-R^3Du*?QwG6y9OQ7uTEQI#Q_AxFs4P>wpU;9J)_v4>1mEP zP}NrwpnB$+ZiT=RyU%sAi+knUY9RME2bDQi@rBG>_tzj;A4dxpS9h}f_kgBr4R*bx zTq1q$#ZM9Ioe%}Q>Ppw%A7fekGn4F0{gQ}FN>lP<6w^ltakg{gL9`+CYJrcX$cPPF z!KI`erd6d(l~}=e#1f6ah1YLO%|^Yg!$m+`^L+E_6)7ll@7PTuE8O;+@XmPL8M5y)BgPghCG+b z{T|SY8lDKHF@asr2F4^HOWjXm%2|=)gA{-7%)dGJy8je-(tf$*mc!0pFA~CXf_^)ghVKgHWu5me_+eAj;;S)4P+A8xTJO4^?*ygw{v-n8BNWo|fZok06XvZ1&? z`u;``Pe;{TzP26OZq0prPs9Eg($_}rYiQ3(xxQmmoOM(;j-Z;ECC^ubsO{P$f(ZZA z=Lg0G6&dwd{#AI!e%sYLn#3rd>B+a{nflBxe0XO6LS9W6kk??$#^B=T3dvSCzfm z6NmF%lh2smcao?m5%n9l!*YER7cqsvaBVkJ*5hoFGuD@mk!v7Tc_B%{RgOQoT|a^e zKzf!q5&|i^`4Okbfo1Vm*d)HK3ij3+5Tclhu~q}64uX;Usyyty6$-9!Wz7nby!kPU z$j?VC`!I*AY6STtY)hHknJgzE)~@2#=6$`pgqmBip=|b& z9v{rmRF%j#t5oMPG>~0-Ss4GD=x`m!m%zI?|Md3h0e>QUXh$czk=Ym35u_?uHmVvV z7n^58)f+-m^A4|=YQ**Z{Dw*?$tc>)&(z*9x_%Rc>_dXxds0-eXs)Ob97rlYb*M>u zy$r#xc%F;rS#|-9SOh#xI1KEbSbW+y=*dl=+wpQE9?Gh_c?#XbHn7K4X`Z}Ub%Dh) zvDL>+Gl1MRa{?jpgXg&L7dBXyWO{mnNX&$9s|r$H&jpxl7+3UFnIvF`CPZS}vi602 z>Lqy75%LpjKe(%n8#i1=s%El1$?;*ZGTQql6x8{?UU=&AfCL;{1399Fd21N`X29HZ z9^J7jiUAi1k-06X>m8yZ&ahv6YZod)R+dyBCZ0(=QO`=&E4usF*1VMDF-}B}U2B#f zEoH0B!`uS!(OW*uU0RWdvpgHNh>J8=&*fo#drXU~#PK#^?lCBU(!D}G^eO2yT4I$1 zCPJi&BdI*?|Nm=QClrqGd^mes7mDG@M(IfL?Z}pmTQ?6pQKP8voHy$O!eYBmDk-2F zhNi5nJ=m`T;o)Tbj%odrHWL9bVFJ*hCMX<9I^59NP zChMZIG@wG0_~zPV!CEOE*`EM|GDq2QW%|!0k#S)A+9^Dya-4GK*n8~I5dk@}h!cT9 zVQqu|UX+OgxC$+}Q!?xECmI~EGN|cZ}j%cE%f_ z6p0)0$zO^@;RiSg+_t(>IJ`^;xRbDas=Epfs2pgq%d^Uf(Eo*fT#;GZ{&mR!z;_@r z%V%5q(Da$H(`h_YtfAKEXfFPC0t&PE;T2*buD`pWx0mU73N8ugk2O1BSG0jvaNg-; z=n4%G*k1y{@M7YAmv(RUN5jE@d$5e}HfZCmKx!(w=mk_ksm{5$X2gLtce^kQlXDEj>SERj>DP&b7(}p zB$f|Wi~vQ))fTMT)6S7(@^aXzK>wYK>(2h#cz88Q@a)9{PWm_${_4++@8s){c!W6g zLiC?}L3%RvhodJtd9+ZiAi``oSuq)6WP6=yMxy<1FiJt{GWq5#J$QCQCm`-up!?$s zBGzVr`&g5~?yM?Di8g^EqJ=YK<7#h4&C+{e@P~1}GSN&Sg!nEN~o@=`_Z>+cH;R{djj8i~jtT%nRjgruO@bjGJ3f z$0vo|0mNZGn$Ec^!0+06vs-fV(`kG#1cR97{g2X!!SA`^1%|C3uoufBm>Iour`(o3 zq{+O`RCStN%hr9*XS9YZO}c-9Ur9Ri!W+%A7)?I`#p56t3Kgha!{=TlGdF1a4`*M~+^ zJQHMKPFJA>G+X(eiy9t^xotMdevsx&S33 zC2bT`i*@hm0HM;L!Zuxhd^mheOckl2sxQ4j5MtJ?jeB3wsyS-1(&lZoY?%R?}NuCQkYp7@zT+uZk^R2(9#8f1Df`JIV+FW&gJ*MaR#+Xv`FEKLqDnG zZqe5vz-O7Tj5qpYQ&1YY~sUn6N8iWYl-E^5qkA`2o*EqzhU_|l`cIg~_gI$UfJD|nF# zkbwkH!h&_&=r&7DE{?~&1dOmjOz9d`=5-Kc9;VKq)G3{!G!9ESkm7!U_ninJn~Z>w zWMobjzndIDI8Y{eGW}XvQhRj;(sq@%KUXDgj#{>mIPXpfBP3asVAp=HX$~_Hw-m5) zdAI`6tG8BduNhj7iv!6ckNWL15aqYv6?}Y-Nf40~Pyi86G#2(y0Rd_7f)`H@OU%76 z#;`sF>3!HogJ#zP2hBeVbs9fVeIsWdZuTIweR0?stR?|NV-lAoaz^$x!*|gUAJP*|~*3>t4f9P_> zH|HQJ(D8s-uU>r^E553$t>8zQp8V7oMd~eyNM^GdilMm1MgZZb&h!AThOUDJgvF}q zV-Qu;=PANOUNNQhRP!*!)-cqUp4B;S%GIsdOc$yWX=;xs+;x1>GW3wNZT`chQ)iU~ zrJE=7mN_WNo~DgPfW0LyX zgDbn9=IssWL1^@Lk_mo5j?mu@xqmxAl4ph!JOWFc4wGhSDuZr-T=ZK_ zn`)~1IPV^u-sXcQc@5hrTP!1bhH95RO%0UzH0Ba5{#a^g8_Wqg_3qB}DXngT0tVcrN4_(D(1QLa2Z9pK9 zWBpVrko-(4vg}QNOi|u*?T}Ea=S`!aTf!_H#T*x(hJ5!s!w%l`nd>LDeA^G0IPl{= z;m>9&I7+16eudx;TmeX(Br|!)AZ}6Nu+hivva7Cf49TuAEqT(#LK4dmL0{=ln+EN` z=*EOw^uJ)-5Zzu6o-2e27qoec6`rE+7(S#@Zq#mgA7eT!C9;tVR1J+WGVI43BXm&- zjsyiDDF^+^T>mEOHqg2mya|G{*6 zO5s)LP{2Sk#mAtLr$gU1vh?PNlL4XqxLgzb2Jpjtx!4u^Zj4=?JK|o>O6M^p3$)v6 zxn!o7mYEJA>As*$Od=F?-i{k8HPN9;-ZZIDvoIZ2G6H2`GPCJ8UJ$|1Z)$!dY*bI6 zGqUFb%8s5zM6X)f&m_V9nKLsNu;E@F4jv&1!Y_A27C>GGJ-BewVJnIahrfd({5v>t zNv8w}FgRJ`Kd$fpsu1Oe;JYH1v zy%cz@5h3)Hm}`OS&$P)xt-`TB5hBeKGyh&69kepS5_jjuBkcDqV!MgiDseYO>!*4a zB4|sm=1(9X&0WG}f?~X1hixZdM$(A{i4E!KHRKID-OhV4Vm%*iC6Enm=c*}#t&}o7 zm5X4A^=a-TpgNfCuh6uFt%6{7qNP_oqV{sl$xx`mwfH`x?LP&-a;F43qlaW??f1~$ z>35**n!H24v6*mGwxiCM0Odn{V#s2aJ(SE`!mfVBPmDq%2SjGxFLyE!{Z~*}AFh`I z9~yE%{v-dZqJdm}VU5V}C)XY!LezQtyXeKA#jnX5xw>S@w5E{f|6hKekNpWATopG8 z5%a#U*fA<{d9g+b-);)sM<9U>pMbY#LJRu6n&TN9cF?lj1iZH;A@QFw95Nj;U|`YC zXwjhMd*la1D^eVl5sfhos0XB)f~CO6+(p3Kc``skB@V(% zh(5)C>3C2>M$vTK&dM}=rw3sO6V!elFlpjf^41uneCqhjx-{Aw+6}e_MOqcviS(*s zM^E!8xc^oP2-gd%KV>>zf_o^ToOpp>ZpQ)TOUYKin+DaiGTDzWUYc-voS5;tAAK6h z=W`mo%4P2+1@Oqpo8*;&vn1B$Cy3+Z*`Qg_Uu9yPL#6amYY8NmjGCY``{^R zd42A_r87Q6Zw3wG@M`)eGwG;t*({iy+b{M*#a6>OmwmPf z93>UFjKtV)bx=S}LQ6ITP_p%fm(7_6UU6U8Ls4td}shf;m^s0Vo{v7 zKed;AAHD0&>_Kb8aY~VUu-<0zGqgkMer)RElf~yUeGUFn>(9*{4@M&>_N_2z)@1p% z3OC>A^py`^O!<(yn|A@ffzU#?QkP&SV{5C<&P>gw} z|IOZnw(UDb;StA;WVgqF@mdS#`yT^^s`*rTOgds{8~+rqMBGTXH2$BkR_}>%l^w~z z@^l67W}dchW9fx)=3E!N3nE(D=WRsFAar%-so~q3vmNT|lg-zr?|%)%pZsZ9`SP+D zHaDbwXETfk^N~fPIB~jE=d}wFV`Us~cN?2oy>s%g4bt|*-))q_)Lv%ldaGWN=G<@Lo&zryyrDl}O+FBo+N!Zu<=i zBQZ*<45+-r4RaO25DlS~cL00;K$xFh5B>|-c!ag7PojYXlcHJCU5?_dpH;Ltqq2Eo zBJquMD@_hl4ATj{(StOS7&NAFr0#q`RZ<`Hqs?v>^?`AwIJ$uGpYWGV!Ow%d-VAC3 zE0khGs|co-<#k|b6lc4r5+HRSspH6?`d6;B%lZ!~ffeT^3brVLEoyCi8;+jONl*Mz zv)R1&ebV68k8);newV@TUVk?p?dd{?kQj1tnO;LNZGm_QdU#7Z%m&p)uy?>9 zb=BeOGvw2IVy{ET5HL0(P>OAw|Ah~-XC078p?JIgHVPf(aTXoWlUH&6y8$5Kw(9eY zX0>sfJ^ZV26A}2DSGOJhPhQq1?7(0A2@^>@G?HF*X9tV%5V}*BgWGbTl*u4$|Hsz- z?a)f-(<0UCtauKC33KQoZlh^po8)BIud|v_ODo$RO0242JnF)a5ruOF(Xj4+G8-No zJ>jv`7sQrIms=yR-*Q&#Uk@jLJP|xdCb7g*Oa2F6ptcTzR-UtmA)(B%gUxJFn|m^+}~=PkDTw# z4&Pm$&XBP#ef4Q{1#5oBV<0d06WT@e8tsyNGE+P-loZVpe?q0|A%7l2B>18BhNxY7 zYKBww2;s17${QbIC~!i?>&;T^(3K2qIShK|w|`oUhuIS3K|FW7u6Bb8K`^~(dl{A5 zQUIDMzZw70YUdhvSw`X)pQOLCWD*+u{XjPWu z*`)LR!5ihR7YhToD@P1)`%gf;N?SnsQe)0jZrmBb?(|!Mv)reFB*Na9BohfcD2KA# z*<6A|57f|5bHmLo$G8Bs`z1*b(K2=D>2W#F{Y?-+18OK7xcA?OsgHFLG9!7#+)dEy zjiE6DUDy#HEV2t|jIiwE_z9HvCd>G%R?3p3&BRg%4xOs*f8t8GZIp9a3byGuKD+Rh zo3jN9l2{>>A04#a+Mah=GpAEHes}IehLgAKwts3U@27>n%460@(L>=*5qHE*lHZ#$ zRw`;O>Lp6ErhTW^en#vqssP+ITDzB5nEjvL<%ZjO=B=CuYDVd=f|UD*`F7jd!BY8 z(+=L)9)a?N5?E*r;EgpZCf?7}#+{7(fSOsRr<8}^zy2~;m(~AO{FBDs4|d~K5#Eg` z4*fSh#^$62K7(vMNrqpvs!V%jq-4=3%|7N4S6gVO7pB08A+N0%G&!r@mgil*-*NNI z9YCzM)J8>iKrjhz)t##ejv^QfC7cR?EW0uCGyrIF((_E2-pQUR!p?p?*(E2#hX$Y{ zL5W*1LkW_g+SDc9{GHn0ox5AgRaub!}x*gW~^VANUEdZdkfJmE|wD z-kB^ubo)J`s;3$Uji55xeQdv#JlDZ^p3}%V1gFw5GdJL z$O$fp5&Uo#hTBTWVWD7_W^!hI_KkiQ7TfLiPs3M_*wpj1Q<>LLSUbZ}8wtqHJRmy> zimCUOQWWN=l8c{dYZv)9bmwBJfvzoUR!Om-Yr0%%tFQJ@)SEH&|LC^1v<}NM>ghUh5)$L8o zcCQ_+b+hju_iI!|sfRH^vH(V9Dbg-V`03M63TPJIY>45}alfNhESZ&TF7Yr0Q7O9{ zM)C~?36Bc1fA4T;zL9$7_52RGe+tcBNUKH@a>z%a*A52@Y~!*QHDd`>=jD0ZCv&i1 z+ar#xLAO2VHCRS5ioKVS>-kZWFFlO*rf-0EE1MBb=$dA9vhz`|P7Vrg`F-v+cxf%i zGS%9=JVam6*V`;tOF~_2yp_JbY9wKT=5Mc0x3mtGB5Zk`HWR!&PUQwq$5X6zY8J?R z`^U1XKb%`#Z}hOsA&>8+bAAj(#KcEt{rV@z_aUCI?)`A~QgeY_yU%2q9=EgsyEboE z|3^vqv@+$xeU^F0--+vr>1xg%?ixoA=U7~!py*(Y07ZxD0dfJ`OKd%6z1ldtwri<_ zomu53sc^p}My;W;EWW|2H~lnj*#gB97i9)bg{DuMD5rvlf;qk@$L?Rs6>O=vw(hvh z%7(^}YKX!&|H;P`P8|IBVlc(Xr$`B?$l54kVZ+wLfp?zA!31V!9OH#i^Y86i)(ZI% z8Ktk>Pf*~758IWW-c^c%#QvHlQpMTB*&I9|@~cov@PNQ_o8!QOk|hcr5N{|&>u^H1 z(mogWrJ983<9!G0yPw~x_Lpj;?`_9gJl@HrMxQtCF8kD=ROvLN-;ozG% z5+-Vd*ESqE>*^Sp;OBk=H`yQX>;?cB)}xcXl5y}~4d4;;N29~gKqdZBQNi=DvOA;H zgaduTgb(cOQqrz}|F$k_m;Sg{eDhY zZ^{newz#fN(#lT@kuuE&X1VN6$5(Ci72UseUF?e{-VA}t@1`bIYLAP?t$kOA$z$Va z+PL?#Wlqxsfl1U}vVtBf4e!l2Ms{RLyGO@N?3{JWw4*6280I z_?Wyl({du0#9ORWl3Z+6p)MjeWkc{Iex?%0D&n?C6nFWdj72f^bv5UU*H zbS5(wI6&6Vk=cSHj|{r><6u;;A)$Z0~mkn~(i$jJaf^o$Aznm~GNvytZB9 zD{|g8_@=az5=~8=&eI&T%V~#apKTiSo~6f5eO#a4 zs8!BB6!iCA@nHng^CKKVQVN=G-NmvWR_r(HpRb7K{*+@qTb%}?63mJzqgVDJ@H>A% z7%$bSiArt3HZ9Sa`ciGujkq(_P~i;PGp~%x-%ZPK*)7nx{q*>H7Qql>0^iCb^=XKz zm^qL6dcP*9MsJqOmT9gV&rYWxt5Mwg&z?*4{=r1Y*gHCM{(~p+w$YjAoi*TwYU0K} zk<{`QF&z3?D0!7`yis^JKCj@#p7MKV9z1!BakI60F{%naC?lf1%J_+(6AjWr(Xiy2 z@rl9RI)4r)eh!WZcvOZ<)K&2wm%a9w8^3vZY(R+SP%|bh+OEIoI}XyK%-^j(!5k<} z<0x30(JE=x3+IX`lNdY}z(K}>jcsQNr|S}V77z``EHaDtRSZsuqGLpJH#4Zq;p#B) zwNf~tKOa)nVR_wqN-Ke1!zs#u&k$TL)#B=L^(Nz67*!Y$Yqc)8s8q-HFPB9swb-E@ zf`&u0tC+ay4o$L3GJ}TP@3u=rG4EBHh_axGV+kDOr?9cTnpCUn;gx)9D$YMj%W)Mx z>t&0BUEv6*MYsWswu383v%_0CzAR8D?b+dq(LvK5OXscaIPVq-ls!*#Ff0JmIRx5k znJLj429{LD%b!lM&VLp(5HZP^hLf2;Y8iQJJSE}z)H9JlD{lsBH^;MW)t$wL3aG0b zucJh_u2=y4&hELid!1Uje&eq!x8-<~?vOz+LXA4dGpDs+0y$tB-vm@Pfx}YC<7Ve; zf!;K~r-^duTsqLu0uNUk)gGr7oCHyeHI~Ze{J-nm4h?4>K}*mas5fBW_VhRzq?=jc zsD9>4&S4QHa6bKdsLyF!Q0p8+X=3!sJm`3+ht73Atn_Xj&Er?Rv|0Dfxmu$fo`?N+ zikDjD`guzQp4s(jro%3^`*A>JV8aPv>1lpBUt#YhVcdl9j24p|3-!)6Hu%D zThjSLfERtYpVlCL$UKc#=4t*>3vtlEK}-vu6NwDXEqR3rx!tO{}ChoDccg3(z;BmZD#?l(x=Y0qgu_hD#upn1hhnf$<_Z z007TP;0#*bsn5~6SgHAIEXP^ScV}M1sgC1q^lB<%2G4!4TNc<^{2FWO4ouqe_aPYO zeP=t>zowM&;u~V^0(XA51A(1iBgxoe)`0RTsO0K#BR@Cu7P{G{J})uyz1Ki#aJO0S37`C;NK9K# zaTDh)CT@YA#vaDQZ;ICSR347)>x$2GHY1iNrtIeiK_1{Xqq2AD52>^2stu#TuJ+ zvqlZRoNCsMeNm)TR2LUI3(M{Jg3TR8C2CVu4}ZYF*F*CeU4qe9?c)Al( zsu7MutFDUL(4z@j!@tIbAJx;?Ua4b1)INt5uf?U!iTz-p=C2Axzu!^7uYL=JpQh8U zlc}V^+n!_}Ev+p*yCl!UX5|7b)oXaMy};|!%>-0DvoDblp$&GiTW+p#&=!+{9x)19 zvx4p03`L>-6;2bU2HgY4;;-~S>=ZEU1<|@gJEpH}7Sx%0r{>9UoBcj@2r=Piikypp zwGd3FVuMAL3wE86q0hB>owFT?q0p|j1$}*-tk?vaS=&(JOX^0aEhUb@ZL1&vq*U=R zRU2T}ku`8;%k;h`^O@QXd?-kn511PoP*UfW(8QGFSE0r3<*5vP4_d{OV0VNm<_=i5 z^1e?Nuz$R_n#|&JO9r592!Klj&&JBn_6uh_YHO47e~hAcGDWL4pUb&|GhM5QVA{Fq zrEdIS_UI+k?j4gD_^JJWfrf=#6k~+YCqH-z)Cf}wPZtoxO2(FbZf!KyNn9{hib>)2 z3sMZ#@_L8Z#m@XE|7<_G%{t=fSpq2ZGpJ3|Eb8M}MQ4Q7af4C=Y$lj>t#eDEj$@6@ z?mWrJV)j4aoX~5rV~}k$dpX!~^oZuenPo8rj{Jtwb29}a?41vn4N$&quB?e!W(z*5cC5Ka<^V1HT0wthN2ha=O zq&w*@0SCw4CW`G-G2rD=vHr)))!|;{;*rE)bvmD6*Gfx}0?CoUJ#fa*GvQbm;a*WV zRpa2N7P#to!v6lZ!aMi#nG+xz7kN2HtF$M-Rm^f$H%kWw-Kx-ixT^d@uANC_eQ(`@ zo5bt{m$51H8!31{Y}9csm1uAG!vtcd<&YHSq0t*ZLSy6_Lqs0`7eU#86>dZP6Q8ge zTJNmm|5Zo3OZ=N1>>Mz4H+tFbu!{-fLXqkYgZnLW?M92=s;qy0Qzd&YpuMoNePzraOYHQjyt38!u!QZ5u4!hR#yGG@%!WhZmEA!6eplYoSK zq*+KQN0YpS#1hk460k5i{T_>M8C;mJ{piGHxccLNN=-!Fe@RV^H~$FDF$HTK&bZDY zhL_+rzp;;Q9`18sx>I-`%_WZcQEML!h?@owFFcMT8BPy~ba6@G4Ex(x<2Dq2QW*!$ zrSn_HoHcKeX=Zr!f}hYh8hW%EZ$ljbRd)9&Re1gdh33QSqF;z8x|lWj*W6FoR}dcPM7R0oUc&{ye*V2h6!` zDb(qbN??>YrNlo1dEL8EWxr>A6tk0jzvaH;qdsTqC=`vMBj5T72eP*LT#MB zE-ED_hLBCn>PKl>RPLN53^F|B140KzZgv2hX$h#?b`iSW(N00pHb7*ViS2-HSkCpY z!tJ~nxUb|Mfl|rPtyjN|SDQ~}(a8&<2oTyYef>2iij-R^oVFRmvsNXKY#6)3c3LLe z`+&FEAk$f(H~CG_K7jDb6x*1@e2ia$393yW!)u-)hX2ar8(yPTqYmax{KH!?(tKmhHYg21=!knA1Nxt*Wk1zxJ(*SA>15n{4^DMqQbQ2h)RFZI9nroyncN}I7 zP?(*1(AE(#pMUhFRo+qT?~JCz`VH{NGcj9$ zNAQc!bFEec?{8#hZI`H6v>P1@el8S!go-)Gt-<`Z)}}gn0{_BE8*m(weRD<&Dp1}9 zDHY#^ZAK|pG%N8r@6($PC)e5ZNt64~f231PfO6w3y)Ozx9y^;U1>gW){cVKcS}%d2 ziac?NdQo0a#>YP6%^01m&V^7HVJCag$1OhX4k_R*qao2^hq93>h;diimnE)3coE>et6t5WI(Wjgrsc z08sVDtWnbIO0!B};8QEruKJi+>oJUf4SH3-Iv(z29aayPnl;)7vU^#yB)FK3mRrb-1 zLc|hi=L&~45aw`Y@3Cg-5R1`{;8PFa4|T-q1Dp)WTW&t(8+H8{ruGcl(JsHWDfq$L!nXDrrh+}GPq zNredARc^2mmXc7LA<@LKgMRvwXhn_Di-UVqc~J~6Sz_h4o!tZO2A+TFpofm#NX87| zKnDzhWqWo`qxPcyDJdV#`R;W1e)ETaNa^S+dDPd6_(^x)e-5B~uo2*5`?I#5#_&(u zgHx07y+B{aknoaVjvH?hQu0&yCt?HE4dkwQ=-g=mhsi;#Sw%lZBulFTRxhgxt~mD{ znP&^X>wfC*%Zq{I?N6XsjzWXocJe|<>Z_K$+v7*S<2U~BBmgc&mB`S6Qzq|lyhQ+$y83?H&q0M$^N%kR^ja?tO2$b*)WA>n4VIh094n>8= zxk)e8S8sr+wV1vS7;a~7zs!|li(FqjZVt(gF4Pr(l5f|tfjBT}QDUAP#a$Y-)Z9up zqT!DbCOCEKzgRcsmK%qeKEL7}!4ShJ1E&W~`moX)IUa)hX8M$-39HPRC}Yt%{x)5u zZP!_8R^`DvA9WxOnpM%M=+R=({XX2cH$ouSz2U6~C>rlO@|5LUPO||li(WMc><1;%gYTa4+53x{pwpQSOy0htsl6I|Aau^Az z@`JmGuvD8wt%1c?5hSuAAIaR!*xL>pMxw``FNPlWp>>2jlWczm)O`SvwKZv=!9oV} zb-&f8jz4phza20K)fQ3DIT^}pz{x=-XpK6IcuYRjPYpV~2G*S~K-92)yfJYFeh&A+ zf7xx~E#my*K||pA4!*op0sG=6_XI*`o%t}n1}-(|1MYffVZC-Im<0@8;|H1;8nfYx zkpyw~xIaZSJyjh3a_IM~lr(&J$7YVrT*Hf!&er8s>0y z{k8$8?Nziu{PDO8AZM(?oU+_@8GS0IGm~Gr-wrHz!_Ke0~`sU@J(>-Rhu&e$9mA%l~x5ucxaP;Twp5 zj$(A0zx<;+qwF6!+&pPyO$WT%i5{oFi)e$d8jV1(2WRL#05$&Ac6;!VF56u!E1;c} z&sk=7wt~FKEEP9!u80oIf`h-PpY6eAXhK=m5P|4t(Rl zXhN5EZZOjGJ<>{LIWO;R^0?xCPCYfYgEFaoUIF)g1;{VkN*c4ecz^epivmcRO50 z8IPpLgvk5PdTOTX49hc{>dqc@wODCo(CU*aD0u*8F-zA#=2128}pB`i= zLHoc}I=t)!R5eF5R~#m;@2l z679{yYM}!3=3ptQg=9a;`MZ<~{_&OlyG1P$Tgts0 zR!nDtSYmh%uaiZO@|6M5Y|6!k$R;5Lp-|5|sH(q4j*@`v@cW9YG#Pqm#^XOHA&Q*= zFAohOrF2GWV93lott1D@FYv|mFE9!tsqjO*2oWs=T5OQMJ+zasuN@3=pH~fBiTr=L z(yO68Hy2)Jg2SZkE+OXqEiscQz@-Yk4L|_+2sOnp1cRKV`Oss?vVY&zp1-mbyb?<$ zsGHUQn;EuG*v`YL_9F_7q_xdTo5Am~tP-gb{l@AWOdHS&*%f|xFnfxOxN62gu5R^V zzp8&*+HkzZ*PF24{qe-9|6uDd)2=Pf!S|kiSZ*t>wXx>K{k3dl`JN`J!nPCZVm!6l zS;max&AYF%Gr6$?O*suOrj@0}>D=o(*+s+XkF2K)G6SuGu{1G=xe|c` ztdJoT%Mh4*T$ad$jC7hS6n)$B$jh!LD){n%eJugED(S3{qytvr@prHDEu6coy&TQz zbKrC;&qX(o_R%%m)<~8&f(J(~;sLFeE)NIrXds4^e>$5bF|_~j_G~Ag-LzCcwMj4Z z7~-LqLFPv1%CxL1qqng+Fw3aAJ9P8pA0ap$xq^ zWB31ZapKK$&n6si>6Aqs7Tn(dr@b$arm}6{MrM_5CSjX0&mmLhAydda6Ooyc9TGBA zhKwb1$!wcKlzA>m*cxO=3K_~&rtiEx&-L`>|C=oD$3t)D3EwjxTTQiY&bmR}Ey#;c{r{$X#1@5tc^797Z&k@$UOp4`#-c+#OLtO{MU_+TC4C(zbO;{649){WJP5* zAI;+w^qljv{d1Qe>@}=d_1_-pHYzn?eqQ`R*7jwhfTe5xvDT{i-De&%b+<(4ay^~o z+nr&%7Cxp|C->KOJ@9BDS&0$w=!rWSud+BJ=+o%}*_(AOEHkNYEiaXV%*3e#olaTs zhWLO@pl(er^{!^q4(Nw`6*DL@BcvfK2v(0Kq}h~Ht)XQgM%&$2hu573bb3GF$L@YMMBT$g#~rNC#j z%5SFK-FuCyi+=0s42unts^6{ONa^@S9u=570VN%dpqIh3euYC$dlCaI`DYPH&9ft% z^=}F|YT3dTY8(Ap>z9IiY7HWmPu0xCx300rM;;pV8%P_ACQOY+GVn}5r4>mzXTdi5 zt&&cfXJ}{PjNVonDdbeuo^sEe{%efextCK22@u7fy){!z?2h_%=Y~4e{Fm)p&rM;E zA4s+{P@03BW1OHs(Hp;rUq$x;2hR6TErSTVW*CU-M=L>uPv4=K3xxt4cx<*WRIjs) zfs=Do(vV-mJ^*TeH+oLO2*(1g$hUK}(SlM#kq^LSQdsD4Qp+k(-q)?nw zu>KnnPc~%mWdCnwDgTKb{0KeWE!Vv9wnN|O-Bw8DhHcDo$f5V4Wu6C~D8UT3HtZvQ zCiSU4P%T)rel*gtS`hDoTgl`p0%}Ds1;-d{OGZDCb5veQLJQqUxKmAK{h9dcm3XJb z>*-?`Dy+X_a&$_1sOnq%Wt(zsY95OVodi_;?a{5IwC~Yd$R>nZ9dw zb}n~Ucd}3cR@@eb`-kga1N=&CIg^k;2?iK1n=yqC)08{-{cXqTNb>%$yNUyfnu!A? zO~3j~XwH1tqE;J+G_A372W-(=52gBVwbytaJLW?$XNQ;l?H3<%)G3YLQI_9D45W~f z>GEW4FDi}$ITkRd3*M!(;UCu- z48{080r()U-gWGs!i!u(Q6=XBV0%5eNfJF4@<|qS8bT?to7X_|*M7S=+fUn(1t&jP zv0l)f&O!qx2_J6wP2JT?a>bE9&0{K%gF2&#!?epi7)Lt)m@4x^P}=-Jxf}bITmI?2 z&oB*G#SjLk+BY>$uSyRR=Oc>eUkmx$9aK#dJ!FD=8Cp}#tjGgl)b8KpyJDpx#ojiis7}0zT40KU%nUTrrU-5R9Y1OPgfFa9j*F68uKu&=`uR~qL|9=S)w z2~;KpZZ7g|t*2AnW0KJL?FuqPzm=v1ey_C|6EmB~%YfIPH?I`yX3h4wR8xh7vmvEz zTUubroAZHl)sLmuNj|ID8yC|H5+>NQgtZigsR&GsN6UXh9^IgNTCyMI$inHCRwV_CYax{;iHk8d7_P z-16ft>h$~S(g{Q(VdVNK_RqJrA6Z{}C5g~gH+`zg!1WJTTY^p z+f5cRoqberQFud zaVu>+6n6k{tKs0q%QsYPXV7RSohea z(E4klF&?k8Tyjbdrt(!u>H`*_)SZfmS)IcQGL&a_+{Q{DZ3yi%*ahd;oPos@@6`Q9 zv4*n`Ju}1VsA=ZkVI<{bfF5|0jRV^_Gi?|jXI!;IsYnbXDPzJ!v%kCZ#X8XgpkQ!$ zPqk>P^{hM_b)*RP5q=OdOn#327zy!H)5o=_5jR4V@$*5tHxn z9+;eh=G96zY@m6r4gS>q9DFFxK0X1$XxNbG#YoP-DWKTac;@vzwkaH%dctJ|DpOP%<5w55l` z?+jZNa%OA<%7R_6>JDSuTlG)kbA;H)`2_Qjr_6gX+<~a`S+72=U`DQWrx+wqh=I}5 zibIpV#}x>D{NhMzl2KKtG}LFynBKUGq2<@h?>jcbmrXqe6I`xr)4n*Z)PIHMRE^c2 zQ_%|cG498=#kE-s_?8XX!o>C7W>07J8rSwcT_b!IS~84J ztlMvf8ZC43XqA(gwnNz2I2p4Md?-GDxw^f=aYUHheGyioBC z$M0xXTZiXfAah9v)wBkg&fXq4AC@@Z%aRmoD2SW^%G_AZ1svH8?2!0egfDgjHOSz(((73hF9j)hkZLD$i#i7+s<-eK+O6Rwur}8e^`D+Bt1BPtC{+HpQXwh4Y<_# zJ9!%gk=4eNV`43pbXbxjmGddj($gir{cJOXF0`d&ACM|A2vx+Wpw^6;QhGqO(6{6blM*A!33Hvdhx&=A7wc(0h|rr zcY}Dc{zu_ZPy7qkSUaB6BzDr>+;5gX-8nHBN^K} zrMD84PR}ePbkUPL)qx6QD)^V)Ra|vGe|9KIz_NdMXq*>DRFmoiDTT3=+PoaCQRwst zk$8cf+iAGt_hibk3Z}fq`1t_~j{-^+Ec>Ru5is%I2=jOayKEKfB6b<2^U9!zv-v7E zauHKaMR1I}1sg!tGAjl{m8oPLMihZCh>0e-1usOfE&t)IT`ySp1x9DQGqK01OC=m{ za;1|Oh&z|#RPZSU#kwRT3h2yL$Uo=jX#!`*#DT_X0nOo~H(4(y>mC3A9; zIhDR6Wxeq=BbE7Mq`tqYKu+J=Prn>GiQX)CNE5c$T9VEHh5ca`0%10EGRq5aKVzS5 z+9nKb8Qzq6gj29Wv3j?xNAceaon^dxO47*U)N+6O*F6}d<(?Nj#{6A5Y=Yd+f!s|L z)G#Y4-%?n^&Og8|5hh5~0|p)JfBYPIY7%f&kj5E7_wvw=7lwx(4FGMt|&>!bGaiRlXm%Ya4k<2>NpCCw^ z825-ZZ#;jIv1}b+J7s6uJF9cIB4yUsffH{eQjnp>rr!f)=|8Xgomc%aQ1iYTEX(1; zk|9%?)o0oH&*4>F|A8lkFDQQ)Aa+^?1q_w!yo^*hs;XQ)b;7 z1P}1oq%cAeS)pb+6zz;iY07Z$_~a1yk+?*$b$AeUn`X8SH+?u0nzD!qpzorqxoF-K zbL$Gm`#!zBsoY~+jdonG40l`fiDJT=FFuoD>gx=yIc}<4t7Pm^ycSGls>9pRv3T>f z96LdulY^HWwG}E0LZ7f6IC(lfql(3?qoWYCwS%X7W6UQ@pll7ErC98 zZt(*|ix*--Cv+&Xe)xS6{=g&gFKI-B8=8nb^a&Mw@m1D*g)`JzY2OGaYz&TBh@>Y5 zY%hY+DT61d7Rj-km&j2@KKz0MM#ZivzUN71=)`W5WAUJN)QT-$!tIrxPTpIPUqw_p zaCNOVGYHgX1Oi6PRY?U?6y92xQb3XBL5PJP3t!*9&B@cCQ-MeGkAx^)fN_!x@mbE) zfm{CiCn`NlPf0{5ThQv#nPw#|imH1?se{KoZN(FAONFibOu$u|?xnJT@l8^w1zg1; zUD5UKA!#N@b3r77gzY%wNfh0)F~&cUgE>(s=nOJ^oTO_GoutxlV(?IJ=4W{Zhf6(z zOPR%Oxw)d1FxW-_CPa~1056QJaK6bnrN#pTBuE_@}>vJat z=A(Enky-6of$@QHrS)W{drDLcOez20Q%d>)=JZqlcP0&V8uy%p3YCpL4CtO*f{@3$ zh{vzZPDwrNJc-DN2HX|3k5VYxi<8sq#?;kXZAG_ih648!m2k6mxUbBsmIxo%1JWB{ zq2j#0qPGIJHvRL1QwS{=Jx{nZ^U#msO(=>=)YHx^u!AC~^b==1n3WfabHdhaLFa;n0c zmqk6+hvR>F+Xs7oU;3!}vm}ZU8y-ZhfM~-0 z!Dp2LC*sFYPk#%fR)33`1@JTG^=)wKr=F~JN!)`#>}|;<9>i>U9&wK0$qhDwlqMIr z@YK=@SsDWf=RiD35MKDtudf939-K`s&I!~8hn|hbIZeBlSVsZQ4@i6lXJ8tr&@Mrq zS73L0H3N9J0zq%?u_}}<=Zam9+5_JJqk1=!n-B&SUH|@earJUfg5eD$GyGa%+uDEG zCg4-r*Bi6q9ir+%uhU>IQVCP`XPC90W}hYF(rVjiwfU|$Smpe+lm4(Ja}{b?2o3hg zEpuobTy%=S^cu0%y#Sur&Vbb40<{&$+rz2nnpR)zegSvsONZWLrD?Rn*5;K>Ur)(E zNTB;rN{GY9wA?&jjq$*?!cr1(qn6*oUDn1a<0*H+vtDrQO>DhV*ll{H;RK_oQZ?6l znwf1fuwn-gUC!62(tAkBDrmLU%zgrKSXK%n`1!3ck^kY#!-F7;f3RVDj@YoGBBWj5 z1Iy(|-)$P+o>B}%%A`;`Qq20y5(9nReL`IhdpB-XfrRV+s>ZTiK`(S)g+vM++!Xt4 zj)iGH?1Omp3q(_~*0LyOP%|X~9JfKcKDn4H{7}j>&M6-K7J}{K8Vgt8RhC`{pc`8O zYEx}M-)WhnK^Q7@Yn~ z<0iK?Z}-))Q=}^d-9S|2)V7eZOWaccYn!XO1-Ke&L(Fkxk?v%MGO)ck-=jKu0p6Vr zNTk;EGVDGVCwP*RBN-H6AJE=U;v~fPoQk+mYEz~sLpur z+5<8QtG!>2FZ#aZp?koh81a89J;eqDB~fBREwJq!t7(Hxw`4xDFA%`{v>ENoP_3JD zccqQ}RhB0#ff84w)H9!9Ck!YvCxK1TwweS~nzoDT-6&V=96)2aSKM?q=*v)sZ15b- z5(3oKhk?%;efwZ?iw%g!na2?o@ zi8nX*%i*#o$G5RQw%bDAZ+mG-yObrC6niwt@zmd*Hb=YNK}jHvGkmcRLl>=q0yoc=PXZM`A?GARIFpQ!?gC zU}2m8P-s<$Q?Uqm-k=^YMEgZaCSZB6V>rV$umsow+9o<`*aQUUId7mD4bg;yZ0y2? z%o0`?PEago|84CNPx<-Xa0-2r5{4{-dnwIA<2W4^d!IqJ>MG3#(G{Uh)~D5HUv>qN zK0%DkO*T~T_;jYIkUqGiFT-uHQh*~*m6KsY&c<_Dp?2qkzstez3xw#Ff^IYO8e67h zRg*5Y_g7?6`mWv^4m+gw)a$KCm-)o1y>Wf`wQ2)d8U@yjBIr@I6QzhC2<)CI)V7y} z@iw$@yz)Id*42@GGGR_>I=B9WX8S8^-1_+D8`_2hND+EN6bm{#~sp2&Prm@2N~9rmKPQ=HJRV3l}e zoZ3v_aVuw?T;N5LA{C{$ax9%98hG`1BlE(%4c5d1D@UI?3!i#&Gh!=AsgbN}Fgza} zeLv%O)WdIwS1w|mr_z9+@L!)+3w?pGK%Fsa+D~makFQ}_LT8H!kj2Mv;W4(!B7_biJzuQYiLGpF{m%{kUqx004*J6mDLX~$HE_9HqxOWEMB|en z)A3ihwI=!Zlu{zjqLxqjsH)hk-YN^q;Y(P1rZ_(kNSdd$r!RRLA=H3 zGGdG@1FZ-=#bBEJo@+1_;Yw}#dw2RCoV}VtZ3$u{aj!q|^g`5o(un(`XRU19i{|>EwTF!#rvIlUvX}($1=cUdmqVe8Ul)L)G&RFAFxX3LexzG@C4+wHkyCNn z?^7~Oc+BcpI{O7bH)K!1BiLJ;_lI9Vh0E0a(lr?ld~Pd!|a{kQXIZ_OWaK;UP$Mg_w!5=d!=2nQj&k-QPr=jPCFU*1=M z6CZa5*T+h4SEi#QR;6vAGfLnXmIj%8(FCQyb#I`kA`;2|WX@E!!TAKKC49R-Nc9t7qz=@nC_x39Z8-~=Rv`@M_MxFd7aC=N z6;om9>G3L18r|OaA5%n>uvPbZ8z1Xrq(dss7+$1;gNDn!C%@ycg~8CI1IX}VCa+lr zS+gd8e%^#_QZaYL5t)c;bwED!!mO~SP-ueh-HI*uOM%nGUrQ&HXE0B>+lV;Tg43SW$DksoQSewL8T4xFCu!vV@Q)7`G>2rN{_7C)IcAC<`X+M^DT02XP%^+%${r8+uG z=+Nd70G3}&LPz;3D?mXWGqdfmBJeqqo*sEIrZTDkoqZw|PbGHe+t4_K*+sC|z*a$@ zMh5Y2)`0#aXl|tK@d-0`*ALkDq^^S}SQQ3B(s{CNu=eF*u=WWnw|b`k`xcW8 zg2{5kD;cE02QOPC!p7YK4|i0b5bH$|52Qt;rcgU;>1a8{43u)!CcL^p@5r>2PFxo^ zV8E9~ta3Hq-IY7CW+*KwmCvs*Z1dK*?8N$1z`5N|3$3fqKmYpVzCZD~Drjpm==N5~ z_T=YZ$9YO{9rao*V$dbXUs-KjnN-xgFG=ed(}`pus&R3y2_^9pT~T6J23yBqkfyS+ zh+vP)9?TyHNf|_7Y4mXtWYJn_ElfQR@J9TUX&D&YPeTicuJyrhydH84PH^@L@L?ghblNBtVLz5CIsh1RM`nrHbaB#F=t zrTlE*`|}E1^dwcx`vZph_2z0?z6R?|?yaM3PLOnM#vMP=1U8=RGpPD~5w|&i2LL!t zqB_e*Fw7kC)Dr}(Wssgdr-ydiwR_jI)B#74pF=uM^XTPAw?$VG$(uq}+vkDOyRDZ` z?@mM_E22XX`xkar4yClCz?5slUU)X_>5ton%vBV~Y(`o*vK?)B;dpE>=-12<40V;j z@WWw&lq~~205yu*uJcD}VIutV!9vqm#QJZPu%O{k-LpklP(MzH;Y#eSBdkY35WHjA zcG(1OsF+O6^DzEB#>N~_nD7ww?ol8>Pq?#IAKF_A1EEjzkAXP%-!~AU-w(Dy2BQs@ zW?w+lo(@KGOo{L!tr(RUaU<*@t6iS$f^5}apD^3+jP7QKSSbVlpv0MN+YV^q4tQO7Xqv#MZ$r= z!$RCZZavMo7F0Dj`gai!t#pr?cd1k3o}>LUIL1OmYT@%cV-BPgqS!T;?Nq;?RH zQvVrO;h3uWLJ!SzvXMiq+Y~M~UpK0M zA4#?x9)K@)pF=duli5<83}H9?hk#D%u8wLPzJR`fC18~g{Dr(PpLJb&uD3kdUfBE! zr^iqhmKec6=hV@YoeUiAKfm-`rbq9_H`;tE}mt&{q(_oPM zl}T8NK-%y2?M=Sh$j^ax5;j37pQj_#DrkJg5+DU?n$)cj580{XA|z9`YP=1N$6;-0 zp@+%3f_4HqD7>#20%pjSFGhJ_Xsz1MIWO|R#F4-60pb-ObVW>q|65%0s&&f1>!L4D z@hJ-eyP&c3E_q^P`u%E3@gr-9Aq z0I=-8BuKnQ?QKKeZ;Vc?+);L_`u+SZYM@HaE&?_|hspCy-`?qo6YL_=%@k$-@$BjE zC}C3%A-fmW2m&H0gB*EZB!lf!F-FLeR<%I)wNtrb9yrmP&@^ivUV>D}ZV!UnM)8U= zFX@wLtJCFYNdq-?dw^-i%V+Dq!1?|6d&;_a z=><-W1cM0`+J_-e$Y-~oQ=No_KGNt;W;*oPyD_pB)VIX-LPWwm@fK(UoSLV7BMx?9 z)+$ymox}9dTL*xvAZfXaPiqJM1~4mx=QSDul{o{x^Qh-KeQii=fX;tSuV{AGQE$}7 z+?*FyeT6){Ko4T@mRe!sc@TlOX=rqpeNx_uBVYN&epDO6qcNL__s{kmapph27lb!1 z7_kS#Sp;eb?j;vct^To6D~Ok#!pzC#W*y?uEIo7xe>ukC$@Tw0bRN)GZUPaFQmGB(y!P`NW^#_GB zimvURC%u%;(S8Ddk(#TcXXY``#`NkkZTOT3m>(cazRjeUo*$$TW2ldTOBD~omSJ_L zmsK`vs{>U}?`%UM0Ej-hmMt6_Y@B>2m$QHBSq-KN!UT^Ws-wZCBTajZRy@- zur>oPTW3PEGD^iggWqU(D~}=i_gxsfpdXUTQH^|;p13{&a(^F`gz70#4(Fy}!WY7i zi9|5%u;)AhQxBvE!P1QM7-PyS)iczmB6cnfXIVLTV#GpF0=$#dHcw_bw<0OVf50BO z@puq$j=zw@BV~`)-(MfTZSb_RamN^j`h%D?U@<3bGZ2!WOWqFPEdM9G2!tu83L`&b zGtifz1?&U+LSSJ3nWb0?gw$^hRQ8G`bDzxVl~I|Ba{%Ivh-bKu)O>;nQP~O*4Zo3F z2~@e8qYzXY^D_f?XB-yz<`0Q-9bQ1uwbP${Lc?(#4y@rM>8!MkbnPAC*WZ9-=}l+r z%M;e00iGKDP+6PBi>7_^G&;QVbh$GMgR(+NoNLQ(qrMI=@c@igUOMx`kTVpsy1SYT@ZD6Fqz zwO?Sm8GJ~-%Xb~Di1+sz2Y0RDSD)<^kEh7i&o!}4kM!5Rm? z2$wy#dJDa63ufH4+;`8mdfYy_yA{0MN)GR4h&Qrr#axg7jv4ig-VBFLh5U7#*%2nW zPbfb~Z~fN((|hpcWhF4M=WbJ0cocptZIC<1JVC*A=B~s^jq1ESCC2F!QjSLG2GnuN z_;fSWL;M%h!S4(;OVYR-l!B*M4+zANH*^SVu6v zB{=E5#~z57A4iY1ZcjZ=#fAGs?s8byi`oHqBf8-bUf&X*2%Pp=;<{v4))tw#XJ2W! z&-(03r>v|pFEM*nPMtp%pt3B9S-&(Mi_z^S89)BET2(hPnU+{A(nndNeG0Grq;wZL z*6!_$x9rsQ_x3CjkfFWOf`J1aPAN^a)RjSzX4IXI%!a7 zeh~@pc$H2Uz2lRXW85pV3|1&TADJ$EMU(ZDKVwf~uqB`O9VzhtNbT#=cd=dc$WQdS zn?Pp;CE(I#%|D8G6eENu*Sp3qT~v7NW$Kf-K|ZzE>4p;7lvAU%#vhT2IHkrRsEPH8 zXsmK+4R@w`3~sA#{u^DU1!5RSfhqaC+$=5EBsb5-od8nnRF62p#D}pvq3Vkj&!&vx z-NEWumZ92*Q=ev*oZh~LFtnTECDp~ytSO1H%`ED=gw8w1Se|7BSYX_dQq%UMYHBx&uWNz2o zV9-_Lahv6YSZBrz3}XH@Qu#c+=6JawN#S@0{`g6*-cTT-qr?d~x-sxXrt9lQgu|S| zWM1A{#^HBdTL{+iXYk9ItQmd1&DoNT(cr){lzw#3Jd6=))N}~0?n8QK(y*iR@vPVE z=i`N-@@!b?^C|*QJ>^6rbqHX{0er74lxK`U7o)ENHJK7jzDmmqG%~J5cXXqE*Z{2- zw8{*0T|UVXJK?;lQZnz9_sqnxX&$WN$#2j*i$nVYo}=k5juA(J)0A#`R`u!yES;3$ z6vPmrgnkJST**kW%itbWhwrcluYD3GRih@W!9j(+B1T*AhW%Sm3mla*DdsLmSQT;R2ybA5g{+mKgh$*TdoOnP)lZ&TSJpGGc zCrPX(c9t25l~W)&MDEBr$ieagwst1YrA#C`nCnI?p|#p%AT*Jcc3u{R$VrP(cU#d4 zYXXwc{mg67{dptE7nlvB7unCczEQg0?bMukPkMBJW?vl;F!|pIcx~q40?p72Wc;|e z?3)iKV=4d*d?)D#p1RGx)D#4U!f>J{fk1$H7_|cBZkf5jCv%csp>zolA~A7ZCOR6) zco<2qR}4YW3joCmk3$LA_cltmuQWC>IT5P2imvw(?<1O{we=Oy=)3bk+eZN)A-wY* z7<+1{3T)>yprOq``otI-CX-h{0J%sq06W7O$it*DU8OOb!^1n)bwN$pSmMgJ-bQeB zW=F^|WfSmEh)l77a1g!QmwR$6s9=MSb(!}jHV#^*5G9t3#5e-3@rxmUu=MUawibd{ zc52a2hv)_{?k``52Fdj);BeLl^h;+jpa0XoqUPuh^2_jH-s$@!InM3?Wc;RXE~J?^ z5T88Fi#YAUWL*HguVjNe0P{sJ1muOgf-pXt)NSfRq?a>EZ7NLZEB~Ha-3|uy} zEj2&VJ3dA97}_4}U&)1|OFoiHd%oua`D-dX;q7 z+aN?FD4dOidElBp1No9q+0t7NU@_-FDuRUlI;0%P7xOV*5nv`~8h;690%-|`kd^l3 z)FvV6XA~!7O(ER@na&HKq}3*F0GCWYUfws2!r)f+`*pXRfyex8dG$r)0w@mr(N2vR zyq}HaG|Sly>8hU)OqMZ*`@6l#Q$|$qNI$VU_X&L(i=rA2 zd;)5xp+|CNh)M^h{66$F?gJsdGr-pe=64(g%5=Cd-@WAFd|b#IlFCX1P0DQ>)yd4Q zS45CE?C6;$8htP88Q{B*Ayy8H5gRLz^Ba4Ogkhu4=9ta3Ca0h(z@!+`0`eePXDJo) zegklQ&TS@J;bkc2^`(QRb-1$xV0<~u$t)aq*nJ^-r7=HE9a;OCy)|}(hX8@k5SP- zHxsdZ_O&Upv!LVu&R$tqTZTP+f+J6eV?e;`>d hA>;m!pLVi63K=(hN^+Z1XYt^_3+no6l`8h({|oq|a1sCj literal 181969 zcmeFYdHCa0-8VeW4GMz@$|i2$f--Xpw%H>B)3iz2G;NbMP13TNwN2VIP1-CCJ31~X zFe;$3$}$5Cg6y&gqxi7NrmVuSxS;GH4*N1ZC*zGg@AW>{^*n#P*Y*B$Usr#>G$$wL ze9t-GLpA5W5=yN2wL{MarFdTJ}_&u)RK$u z`qa})mf&yAX?5;aem^=%KRF!X2hJ>be75JZnHV;=ew@D;RszUkPGW&Z0K zRDhtp3iw`7Q7XWDz@;Jt{=x9x2#WXr)n6M}lm8kB-Mat=*i$VQ_kbzzjdvzd3a%-E z9fBdt!MD=a_3tU*s82R}tW~e25J3i=M zB=;`t4TGlgF!Vjpi76H!(1aEW=-ycV;Qf`n-?^jNTIl>Qv*nA7t#Iam6>nbud*kL0 zthqM$ua!&OJgg(*ZaiWkq^kD^3-Mnoo-d}>zxtR~>==L$uqiayThq}7q2_^Mod4Rs z?q0pArnPM;8WoU8s5@*F{;NB#!|Et%vIVzKGGlRCW6{j1=%iQ zJ(GoW&TdZnCXJZ$cv7_M5$L35UBL+!VG=c)xHW}}C|+=hu?}crG9_+6 zu_rVe6^q5v_6$yDxYD!;&_9-xumK4MJuel_c@g2t;dEhF^kF$MEE@$}M3o#o4f{A6 zMln0D^^n25?9^w?8e!&7?dHITtdtmaa4?mI0(zN=YhwkrP;Sm5te;s8UKS=|tzYwO ztlb{XsQ#qf6TLvSTA;HlPGNFD3UQGPn@PQuR;#p88x3kUE9z*0w--#Y<_L(`wL8Nq zVYYms0FR)tJg{Bxx=X8ZtLT6SIJ>b8~$83_%5 zCZJ%bix~4Lo)Qr)fP07cGqVu%<8BO%Dim4E?8T^*?~Le92g9;mpZDh7LcDMVuhZs7 z`I#2cF?e2aWbnTR?x&4Wyim=C5;>8ai*f!sCOB#8It`-9EWkv}q>;AALN<3p%q})2 z_BitsVwf{>$f2=4E%VbDHvtP#x?G9Wrfnw3l%&B9F}<=4J48BDz(c;8nWYM97k{yGWS`%7Gz$0*=L)9xWLR9JsNXf<|0m;Y&QhL~w7*yj< zj|Peg5J5UPjgLIu!5}oXYW}1HnmbYtsrCDvI@&=NA#OLSZn@Db_Y#Ldia{Bx>w#e# z)BqkjDnd^uTB#hn2Fzz|LMwLKxojxCDfmx!F`5%PW>R#DP!GbqzD3VEncL|WeFmE} z`6w}m?93s&44qg=Y*QfIPJ+agt8eK`eTV z;`&azg@paVD9mUG9}{B(_sZx3SOBW8E3&X~!$JcROXF-oXj<7IFb14?>~pm)%e&2i z8afT6ti#ZlANagiqDGZQsIZC`f~Ou|B;rXlYB@Lp1{^Dsng@AxFaX<)TP@sgGqT?) zW`nTpOafq@QnB8umIBs|WwlerYzqo8g|kBgup$$6p*G-BstgsBc@yqvL&j54s50Za zdO@e*#$v)VdbiF`2XdKFWtG*Waw7;Ub^tGGHQ(YQc)`{1(9u<*MTbPtgj=YejQo@Z z!;)0Bu*foMJZ%RIBKMI(GNiG&Jje=AC8F3w?X(x8`J_3HqC$C)RvdU-nhIlqCJF=9 zlxKFkOb|3W=NhIdj|!IGYF64f495+l1jv_}Mi&S~+>$V&qZ%QX3=GF6dQw_#>#>O} zAX1*`eI)4DMxeVSdBaX(m#h3dEzGLATTl`nF{X=!M8;ENrfSx3&b9@h%OM3Qb&g~d zLf{$IDx&j>f>>RoS6XyCHqhlvXUt9sFOA)461(gOuE6+Qj-@QuA&MRc22tmtB8dkL z*YhhziFe&b--4=gh6y7-=7+dhN|b)lW~<};2wI9+9FD_wt~GtSMzV}k0IG^gC#c|% zhUjxWs#Ho1na))q$L0EAC{k^;JOd`4Qplnfi)}X|20-OfoD`TgTo>Z z6^qD(L%OxG(#!Qw*z-%erWcE;6-^f|+f@BN$GWZlhy*g^F@nrclMaJ7P&cusvadTZ zhqaJi*UD`#LvgH;6FByxZX~ya;oOCm?#P*O_5@0 zGwqFWRELy>YX+p(PiO4{F`K2DRnK&HI-wC24aT^p`7LiY@8N0_FIu+P85R_?o`Ru9 zYL6c(Ov;6Ey`(9NQ5D8hKXOxsSGoDv^=YP8YIZCr5kY*7S19faz%*L zofu1$SwPx7S1u#E3Fc@Ib(}RYx<8y0FsY-#X?GR@ZO$MCY@(GV!Us5zlKCoCn~917 z`*o>1thBjqY0ix$rby^=kB}XC&gcCq4&OzZv23!IWKeX|3c>{#Yg#tqaM7UuhSc5~uPA+E-hmT$Vbm+IY^;b<$WY zN@A)5V_RrQR$%*p9LAyw6I;PC7ION9c;Jp&2`X14zfadXJ`fTrq9EKzl&+QAmZrs& zs`g|$>o+Q1gaUq69j@Yta!Z;P)Sw`XQ$p`SJRA8qL_`5xp4CKKt8fKc8Q0O&PH_qz zn2Od$@Ok+NcX z5}2dJjOP%YV3ZtTu@orr6dbiEH@R$HnH5=#i;7c(#UQy1%+#2oSJKN%N%v2i6TLA%Ia|00H_li7Ao~3JrNp_GE*C6 zlS&6;UWSCZDB&f(A5~LV10HBO>9^d05QSk?o~WG#>19+Y!ph}EK@MF$^`gJ??6Qg1S6wFMF`a~ZR zXv3j+rozKrcU}Y#E*5AN>KL=!w<2H@8`&j!QDq_^Isq#dQ&c|aw?I8pP%qlSq;=^+afCStA@AvtkF;5zEjEy3{9C?Ny;J0ObapK z^%#cMq8c;}FgR7{7=&+wFOko8c!{Q_i#}&?K@)2GrZ31kV_B+R4iHG3=a7ZcaJ=P( z`VjUCQPY@A`v)YAwL0YDsr!5(;}pi^`(9 zEHSNSW0s1zMZ<*0HcM$ZXWCF;R|2~{HQ8oMXmh?YpY;3r?xVI+NTdeDk|RCSTRpO_ zHAuZa8Zir^4qJ0d(`T|yw}%mqyGoxo6@O6bT3&$7J1AM{*1Dw(DhuOsjcklkDB>W` zZ;cSIMx-b_%R(xkfr=U1CNq3bBwN`Z#wY84ofj&aL!id5lSJ;0-FRd3{)& z*Dw&wC<_Kp`#9R|$W;dCO}8D4xRB*7wVuZ-=rpz`Rc^Sb43wTD)W{i&GaZp@2*cbM zjY=KP@tRyz8>>BiYH`MVk&Sgn*3+hnOy-STC`QS&S#l{U9QA5w(QEi^-&Nhxs33xH z4AqI}N)7IXv?R8ZLT(f&J&Fb)G8fu3iF#BMI3!Tjon~DdvDk`ICwvjZ(&l6y`$D*(HksH%7EDbcaq>i%V0-$)>=>Peltr zY_SUlWR*#;D@X`zvpMQj(@N1R%}}kG`3hz&konA1j8^ECM6;2M8pCoP!?3%fI^|N6 zaWco_Qf5Xhl$*v;EZqekiYp7TskKQF zgwAZMU$LtM+^Bli$O2nI8IH^XcB1Sg5oc=Iu4Ja9>-u;`<^E;6(M?7JxL=+kj5bE` zY89)dV`JLN7!HZcL)D3TC}T)2Iv(cRj_EYzVQL5~)lr2sP#NI9NGY~(v9EU13Effw zWhn>s%yu$n`@Rd}K2|ZxV@tUq64ZW~$W074nj1An(l;YL+DzwdmR1Y3Nnl{ZIyKXR zY1|?QAWoLMfepBAP?H8`CySV_l;mDpZDDd&Tc{j2?1~BqrgX?`F>1CKT}LW4B&P0^ zI(-t8V{%rg12e{Sm=Oe(nohkI=DdsX5zF>VF(#BkKu)=isnUq`3}lj)ODvr5K`ZWsGts8} zqN|MzJRv7KJgLWRxQmy_qyqq{FVK1w9cxy(Cp8MX!J$JOW*oQ$IFRa@Ucv0yjjlV= zI{kiCh`8burv!VxK>1OdqyP-7>Gq6} zaT!5D1s<22YMh5hs#s8mL8qxibzof88Uv&V=MS1?0fn2g)o6}qT8peFPRVpr(@VXv zDfN1Vu3E3OU91suo+b3$mI(!uaxk9*d0{#vUC#N$LU<_5YJN{`L?J)`a0%>KK+~QL zr=_+bc_EgCle!}mI+#|-0T#{$H3A|UAOMu5m5wwtCj>mwqDGCc;<{*8K@@^cxtxEe z2*-)I(;M;a{$PrmnKy{)Ls4F!2{UJ_-8Q!ffKF%H0zE93XsbSE?V>cG6WC=*Pqf7` zS1Wl{+X8+ILIn%Ht;;^+xA7TovreZPS4~DY)x?}ZJ_yAr7GKX?0)}08+An$F)KNi> zo4Q(nWfX)$Vt797^h8dVgLeWV6Fsw4BJWre_5^qoyOP&Zj7ij#?C<)^uqRI_*#il7c;)1#PU^ zXUJluW8pZeQ7~{~y3x!E+49`sd^IdN!U8J#ZdiegI&lBY$sE8MI#NrT2N(PH7=b;- zELFy0V8yzepMR??OVeVrlvRWY_piu3*6L8*<`hyCZB_umlQ0+~*&gCXHct2)dx^d#2aKm>4M;9Pyq%lnqigz6?!1CpvmnT`YL*dW zU?48kk;_98f;0{UoOBDBRO;~zU69iz+R!l|WUw(9j>cta1}wjtA0gImw27Hq5UCX0 zmF0!R%Jqy+DovIy`I(OaqA3@0CV0!Vv{9if4_$+cvfd2O>eX_g5AXp+whPk=1~LG3 zXvv+w<|;D^Lz+mNo-BG(w$|W? zk~fljMwRQ$%bY_Sm+Fzn(Qr^CtAta|O58bGWbPMaVD(`!_xFf*x(#cr5rU6=)su&zQ%W6>J)tDa3xqe`h+ z<27s2^G(hL8ko#8K1{VtwagG}8eX4`O%89*gUJxCR=sYGD|*FdIrrxh;H zXWD?$JDTYAB`PMhE{1xupfm9Cm{pl@T*QWhAT$stc)WScWF=Y)Wr zl>|x!0b|rs#VL6(RGn7zo(5sE6fc>A zjq%k&6Gsd;PI6x8^`&uj(wSSXpz2a)%>%XMWLjM&9jd!vLC|{^a*9xjA*6sBQ>ols zjF=kBXrs)lI2_JVbt`R5<%O1NS$~EU5u@dElI_(+tidonlCZc6$Pg+Wg=b8u(23?f zzc}%1faw|EWy)SD#buhNfZ?KCgPfA7)p6WTv&`8kRL^pt(NcsCH=WA49})tsoQ1`H z)hV(Xav>)0ac~js()M|6i8E65jpPM+UF7=v)kRP^vHD(%UAuQQo z49ccdUdVh$oyBf7@7U{uFz$So5mrCfi#5}2)%z8<#k;vzQHT=Jc4fEUYxaibs5MPn z?cUf0c?B+j=jmn_epqS>IauaQ1BMx-PPkQQ=9O6tcHG!3hmPgd<38bZ31n(ZS-VLa zJc^EKqSk650s}cs-R%v~2G<#?8ttdSwAIS>FVpICrBQi=4hw1lH_;9-Bur%_6uE2! za$LlGPPl?ROdVMiE7&~k)yDLw*UuU%MvTf@tx3TB{;U!+M6K?_49E^pViPamlafgQ zmvUC~Pzsv$5}N@z7O0gVdG5eNTQi%=eH!3NHyEp9=H3<63t^pXs}`wA5?{44I>4LU za2WJEy};lbi`u-wC$*ZP2n^4m3oXD*oNZbr-WXSXuStgbyxJ;<^CoXr+C#iJ(W)qK zl?SNA1i;fTSCvuR#6-D@x9j~DR+N-ZZ#bOvsbXVV3R(tU&%KtO#4d_(DwGInLgB11 zW$fIZ*9Vgv1JtpZ(&~>xk`=|ern(#e`2s#2qeDhh_=)4SRnzSk5J3PeI4_I2zdoNN z`oa@pc2aHOUPuGT1X}e*Tj0=k%*W>s7?$PO@ss%b{Ro2|`3H!P7AS{514XN4d#*@#lwZ7CeHQoRuL3apGb zdu>0Q+pGl#qXMWx=*zmm&Ye!zw;N56+@8z4T2+Z8&5bQuhpzSqs-Cv+MK@o$(s0M4sL-mK)nSbe+?uOGQ0hT(lklfC8Dq*=wM+)G zSA^NDRaH%>hAfm3Ix*2Uk|HE9!jRb;v|Fu4qoG(LSr&CJH}#yuXOzNP3&|=?bi^ws z(|J=+AkDG{AzNAGo*9c9%5af6{ixFk948btZ92&}sZ}rM0Emt{!!T;`mJ)Pxzk85o z^0?dM+P+r6+};#rIM|v2J7zN?E0#)~QmN7bUN;C>hN%fRrA4uvB5;c)3nblX1?7~* zoT@PrdiHc2wrDySkLM}8nR|BRd2_~@J)KIU{k`~otn_FbE6SYv#=(MD& zHIm{Y#g({jp!%p=@UeubHq6$P80R{tZjPpPI%_qMcHLEr7L!iuRSf`np-6Q#zv>Qq zc7e|NaOTazR$j0X0(qxsx7oGGBt)Ws8+i2^)N5qQJk_S^oawXxeab`(Wg2W}NlAP^ zQOi~Zsifi9%zW7FPr_-jEt^F($;fdYkF}=V1%i8R;1dLzW7Q)u(7RB=YBHa-x@dc* zO;Nn4s2sy(CaHhZ=zU}0+Y#&lp14DWQ!m;IU=2+m5@?k zc|FIO7u*?Kjf(J~j1Qy*S}7RKmbO4elkDaY45@L80$q&MRz>e&frT)=-Yk!SmWyoJ zG}I>Ga27;A+G!W_iQH)Ez{~EkX@3TzNVi+ZGiq4LwOeZ>K&}3a2WtgI4z$v#BX!^< z)nSedVyDn&dsA#ySSUdFN)!P|D9p8TFbYTg?cxlq<%V zBj&ZyoEVQ3cuFh7xG14Tz(b*p_G=i_D1ksqsM`~zk4ybZWLluILF&?8I$*gPgxFye z7Hcg`CH+?47oj?q#`QL@)_7gZ-T1nwd8j%A6Cu62QsQR`mh&C!!8NG>W%7XRRu`Gj zcf*mQ^?RJH4+;x|j__88sK`7BBQhZPAvuwm^g+rg;gA8@Fv|-Wu|U0+R;_kNI1}il zg1GQ1h9O|R79oJyW)lY#tc~sJyfGjqUbWj{HLgYsF%6F(nW$CfnT#+khDzxf)}7g% z67M@CUuyUuKxA+tsB=s8f~(D8xdW<1fN^5_EeY{63FIR|_6kg4Pg1KoS3F*6X^`24 zIJ^(UgzvG79B*eQQ_RCUsKC|ZLa0|A8CS2Kk8s)yWz9?URS`dWW-F7baxmcuibutvSLuNRQeq^i;p1>P>54S2#Poa=LYC&#c?2AHf*2!^F_s!M zqkzQfWE6;eh6iD1NM!;Q(%n(c)xKfy20G+*S*n7$Fu4e*X0X)af)M~Ya)q>$ULkij zIDttCJ*nr4ItKS0FRL{5h?bo!MiFzN%%a99FuMyU8X9F#_6mY%J}l_zB0}OJ5P2q5 z#-`$tL?$hoFo?8hWw$4mkb0M}vr*ml6=|A{xdh_awCQ^W9u2xP+MQQHaHi}*ngOD0 zWh#~1xE&x!K`xbms-kN8tkBgfGhNOiX9(;UF=Vx(!xZLOcQ(+~nOGeL0PPK;xdlOx z-0xIShNOBj6Pcuqik>N1Xv6^Bu7Cne$rV(bjxL-rK zSs|CYenBZhEu$V<}o3j$IC{bL8>Em8d zH`Kl~X-r|iCRk`~R!exsNO>Aem=565Jc$P7T($C`jEX2u8@ekYATpFGEs~w1bFIll zsWwyV1AbB`8-`Gv_4&>)YE7oLtMMIqVc@eGOBM$>mG~*aRsmqc*t%{+I&h^@t>GI< zx5c($lc}gq363B%OF#&D06f>&Xk?_^_aPKys>Wnvf|_Dgk|!XVw!pKj62t;G=z|KC zMZnTi6C{POG#F3&YD2YqYZ{6Jl7-dzxXf5}-K}&* zXuhx`k(lauk1=?OltTj?)D(5vbea``38I`DUFg7*iro&&vut8yDl~&@WJMKb7~CJx z3M@Gz1_|I?PUAqY#d=Vx<#x~=4U)=`3KgA2;+Tc(j#AL(Ce006fl=u#EZTMwQR$Y$ zfTFnepfSV@T&$>m+V@#b%KgJ(&ji(9lG_PTb!_zbYS_|80gROGMr7p^`g#Vmxy$%r320kEPiJc1DdlrLkMu6HJm zIs`D)LFyLNNkUg#K=slTD-8t#DK)aTTJ6pw!LI_6;C?jM#u$z_DmXiXviSrwW+|HE zK4n<4tGGjBnmB9bDky4%;At9GM_IDDP-WKRx~&kFkdn8+a};4RAW5Dg<@S(jw>c^X zQ!qUyK?d?fkWe+70k4>u8$cT~9krH`1nLVoP%fKmdR0*1iZHZ4H{u{xk|Y*&qM-Ic zKoXWQlks!SV-#mZK)M(uz_Yq%<5*A`iF3P|LcL-J0m#K>YB|GXJ7|W2X?G$lXPm+e zR6>HQtqccEdST{9G1S7oniB#5`l31mg$xS>bO{Jh6TnD>8CNk~DiV1ZAAG8kjSfM* z1qhxNK(&=s7D3$90$nM4Dv;)o(E4$)X)FX%G(eqyAP_MP>`XC|G5=4O9XZLwOTO=Nii##}zzl4T%Ut&3K|F z-FCMqgR&T_RDo+^Wt1P6>dEZ}JVgjC>&zRlY~pooh8eqva;CXpY-S?TM@$e0LWCuVuiKbGFx&Rva{e z{D1&y2g`kDt}bN32vK6!D$Uc)^Tg9}u2fjuZh{U1EHIPOOd=*2K&%X&*r++m%l@gN znYBSnQRZwwYyPZ(ZVqx`;Gu4EYzzrgfiMQSY=EQ#l{1r_>0GS{!jL%^<-3ME6VOhP z0#c}o4&>JDNXy*>hA+3s)_?)oW+0fQNGcXAosVLYv(yD0j!B|u4g?z+CYv(=jWo*{ z+G&Bw841E?jTFWO3>mj-I@uA>xfR!{4X?o{)g1H%Nt_=`2^ZbO4fE1|rnk8$B`t|A zS|er)rpCAVMj)asqgof;Q9J2Rv>rFA>y$%)ie-}VYHb0lb+u9|_R1y4%gsJ-u`0mn zF4zvL))SptL!5$?Iw;05Ne9a}iE8RFIV=g?Xp!p~zSI{GH|?}a?ucUOGF7c0RbdE1 zJtC-R6i4(l^~$wcj#W^!I3+`aO{|GsZHYimsR)fxJzq#R8iM~~nDc~UdJQ$jt2uiS z$t;Gn!UQUS$0aLiMbinWkm_Z?cVY#lpH?d#i);BoPvcINbl}FAk6q6W^7uvHHdMoI zS^22e#KZ-V>mngAasI0bs;76`68H`Z!g3oA_?M}*6dn{OfM3!iK$S2(!mAFrT)pMs zvoaA%4N!Vb<~?KZ2R;iSQL}g!kA?j7_)Zndv=%fkfkG}A8RqkX&k)9KJVMMI96%Yn z*-9d|9wP#3l>6lxBBbve(}&BKYWFA?-$Sc>`_aWZngXW<-aFRU%7m#xxkDD6zkc_f$KT!QDer{O?EAU<4!!o+f77)+_JO6QcIrpp z{KmhV{;gVoCXFHd3r-r%El`1-!L zANM}-+wbv#2Yw-*ve%pcUhFpyIciDo^(Vjcna_b_EZyq=U;WVA<*CQ6zwWq?7jHZ$dF)q<2QJZm`}5a6 zJKp86zn!G~+`9ebiw}74;6pEZ<;BPMA0Kq?{#!k1cg|TIp#N6ByhW;g^m_7~Tk;zW=vwb${-`g1GWpDdD|bKq0}ovO z^r-AHAe^+ncj!iyv-%$r*op z?0xh1ogXfF_Q5^x-1%_&J&SnbS5_YN<+o>*?LNA4$AOZm;Ox4brb z*8V(u{1pfI*Wdr<%TMp{`Wv&CzPZJ%VIc3?*?X%?&bV_`&;0PeEy|{?E;-`PGq17F z{dY^gZmay$Q7-U{-G9B!_rCTM^IP8mJNSj|&+nXf{NbD4cyfzd@40%PtyZr&`lhqC zGR31_8Si}QH9P*>3az|!OLhIur>@@NeY5{M7&F*s^Zgc|14FL-IJtFh!j>Ps+mUbo zVO{sazrV?EdD+>mPk-RDvkwTqu=JrFzrOFO4e#Pr?;YIk!hyh)-L%saZ@ow7lBGxF z=6Ji!_ebYjuszc}X60kcp1bV!y4g9vhO!4}bpLA2lyK z`1-7O(u(fK?rPj}{HLG4;Jh=!Gv9f8r;|Mpwk zUUcYdFFbISx8cOu&sUzjY2U+NxnFty^1JuD{Qe7-4G$dPKTq|)dJFmFX~ub{h1`v^ z@zbxL$NyA6Vc%DOa_6b|-SWi;I!A7L!1C^C)l&s3ito@g#9P}`gg9n?a#khzbSm-m1pk1e1|6S zo4v38)6xyvw?F-{BYrt~^xCV^m-Nx^e|Gfs?{0eQ)fd;l`|$bVIpgR4c5(K zg{R*8+mGyX$8qOH&pvR#%Rhhmz-v!__@-SB8GqwL+g5$v!EHZbKC}L9%zM~8 z^!Y1)e5HH;?=HUKO*eV`Cj7{wp1b*z{`|G`*Im8u>wo$N7Cj@q_38%yBI$y*d=9hi zK5snnql=OkAG_+_=00nl+j#OF=e+w(uygZGcYkf;_xC#R>H_wm4gUJ;^G%8$32x~D z9QVlMohy^a7PmaK{-v8gd6xlpb@G|*_Iv&7$-B=!wr6MU9Xr3VagQyay?&ix_uhEg zZtscd%H6Agmr8E9_rGO1=cNDme{s^DC!W3gU1uEnf;0R39hd(7&Qmv>cjghN{NA|m zqN^@rKePBBK+xnr%~oCctJRIW&)D~%>Qno_`^E{|ynO!h`*zrE_s){)XLnn5(ht!s zhdWl>d)MA+fBXFHfLPAgA99)b-Gh#N=as!*KKbXT1L|LW>YNk$Pv5f!-{%Rikyl)P z*H>@f@{jE+JFR{1U-iIW%EZ&hA9B{$w*1rlQK|8p3jqZW-}&7KkNNQGi+Y#e{MGqW ze>$df!6`Q`cK9NH2{_y%F8}RE_I+76;F7N&z0LK9|Km3wdfc56V^p9Jo3<^-&ppt^WpEF^5)mPhmn1rSY2Lr*mK*hel)n{(`z@~{`E(% zjkdn~oI{nnS5YUvbP=)fsnhF6Uw`sm2YmIn(naHkF2m+e3A-%&zQ63)`(b*~g`H7_(z@VSJYS**&e_v29*g{<&9{IjD*kU=*Ue(53xpY5q>5{K}`Jd@O zcm3+p4{UYc1)W>EUvIBD`|~G!?Vf`VeIDINeSO^xuRNMOe$CGw*rD~cKVQ6d$;mhF zy@@lI9lZRxHEUO}ZywnF)sEj6_xMuxpY1O6iwmClBfZN(PaJU{I=SHu@Y8qxtlbWJ z@r@_X{N)kvym^gq0yTmMcU^JL3Hx39>)}p6d1=!-_oCg!b64EkoIR*K#s2w>T@Frv z^TPG7J*HM0-L-pP^TZFAJ}K_sJ?rTc_TMx$Iwzr9-Xy(IKk3fL4u9>S>z==A!*k#? z!pA#LJ^#XWFYY}(etyg2SB@T3|Hz*7xU_Zs43JgFR=xbi#wkx+eAcn%vRfA$x+_jR z?^y6NaJAkz;+Kzv_3;tET7BTUW#+maANY9>K6T$iuX^jTKYx3-$%6+ar@wXif!Bn4 z{{uhb?NoWX{$S^*TKA5ReC;2#p@pae!Vo%|`6|>8PoA!C7w9`G(n&$vN2k(d*4u9>@ zM-NwTIP8r-u6g?d5a5M9*L`IjvUY|0?%Nwr*ycv(uI^`Bjg5a>wbMI??|s+TvL~Gf zFFyUk2hLl2>;P=iS@-|Ecke52y!GPxWT%&2SpV)3%12up*A-4(cg-88E}bs>#JZ;s zzTxS$r#|7-!i(6?Nax|$1S7pJbj-B zx4hvm8{U3n<3+U}eR1!%*X*}$#VKz-iEiobc*Q?Y`Q@jzw-@)dw!HnmE7qKK)vKNF z+%|gn6TjaE-(#O!b~)s*KVQ{)8!Y-!;>b7tw#zPeJ@mtuF8txiOY6&~%L`9>FYWrc zf8;8(`@8m@w?2Nx;ji{~xu<>ID-RrSQR~e8PTh6wvemaWzvV9b;qvp(U9BFrakulf zKl3W~Wqiw%kZ+&y^zC0+f7(Ab{bA>yEj#yuI2QItwjZ>*ZAHK13G_>k<>FGO;e0R&@312<$m{XTM zb(?s=ci#NPpI>}?I>)LCVt~lq@$s@s~<#)jQYwy8M+a&z>-P0b!zW3(o$9T7V z=FstTM)#EL-FIF)=&9U7&+b3-V^;!IP`v8?b5&CT ze!T91#hu%%e)`FcckjQyywl#B4t!?)itz;(a0hA|_PY7V{r6kBcIACQE1!1B-Rr(~ z-t&9ie?0m3k01KZD-RmCyzw9A!^cXm9k=47J={%~K7BP%8~eoS_8ZUt$ImF&z4pv+ zZ~MuUFWK$QH8%@qQCse^pY+rnqvJk_$G?HQU%K~^Jx}}T_%qKw_=^{pes6>K%hNA> z`Mj@xYTKhP0qAVo+xg#b_iwv&^w|KO?RD(OZh2pM?$`w$ytsz=NPZleBWr ze?~0bwB(_0ZoPwk|Mx$3`n}s+_!NBPcUJ7Ta?LaRZ4|lg+;e~Z!*%;FKk@J0;Xi#U zyLWBld)>?LdG*-j(MWl&aO6?^0bl&cr@x9U|Hl4TtbP7VS8i)v+tBuS@e}JVTk|}5 z{mFN|{=MuV@5~GK+Wr13E;@JJVQ(A|EHxiKzH|Q{@7wVwomE##jr(uBVyE*@S)p8T z%t;Tv{n`KY&~?Wi{M}Pl+`9bN=dQhI?<=<)e08t=R=x`C)6IwdF2FJbLnx9J#hMMH@tY{N1phZ@P+>mHZO;CD?YWyXp^@S0Hwh` z8}EQ0J!{jFldf7L{qalU#;cB!E@4Z%b|2#I-*MgsRj%4Ds}BCv-?v+R+$YfA-L>y) zkDPnnCjidd@Mg=a|MJC+-#%aZ^Y1QPd(vI6-}}=XE8VoBazXp2zue=TqCPxz3k-sR&>`r zaoSFobY8i}-078H?YHM8Pj>${+HloHj~@B%JIk*-@2v+m+}zgqRgkmQH)(*}Rr{DD z{ukx~O(XF{;)DNI06#k)Xy9X4+!Sm!=gWb-|7P1`mMp#LqyPBOtw#W)m zGP*d}@RfDWb^ETm`aYltyyMP){+*AZTYi7X!iFEl0EcWiX3K5#LtgpNt$+E?V{SV0 zkTU_!eE6Mycg-1x{qwe^-#-7{*4JM8=Jl`t<$JIGf!*zz=l9s@ZP7ZvvRC)0FW>+A zJ5S#8>JN-tj*mWj?V9?JuU*l5hCO@d`BA*F@3TL@{E; z%)O&cOMbfINaxUdE8b1V?sW0*PVNW)VSabTWj7ttx#bRko!{wiz@FJp+4!MbFTVcO z{>9k$gIKR#-g-8W>#`cv5Os=`oq;K7G&;Z~X0r z7dI{Gox>bAzUwq{>()8z#6w@a{J>|BCzrQQYZ`f(w zmCn64OV{5%I`go9e)q!H&wXaJY3(zuhd2FxwCus&@%`;AW>S97-%IPH3(h@nqq6&( z+pb=|{guFTxaP(CE;``B{eYd@>xFCgU%B?8w@*PwC%=5)re)^C@x2=$p>%ro$}athCNiThM zm3O#$+FoCNXQx}AINuHbCwp%l7UkCV4FiheV4xDBpx9Cd2udT0LBq^|Gzv%#Al;#| zZA1y_5Ez)DYmg8S0}Q$c5D@`slII-a6pSn(JEYj9;7= zDU2tZ+bFS#ggsgx9HYm3pGFfxDglZ(?)jl~=_xpgn#0uGj-Th~D{h6A&zxJBY}QYs zwodfd>t0sEH$ZdreQTTN{P6JOGha^P^RaHdp(ZP3sMiU(!}4zyPJkM7FQ)D{t@6?Off$E18+$f;Sth&q>=I>wl@2LeO9h5F0JBQ)9&Qs|6hr zB1AjQ^(PjVun9?1ZgyYf)h{k0v}C-7t9V@s3O?4t`E^E1#fL;=>69bIoE-N-WB7@A zNp)PqM(x;@APR+Qo_xpSmwx(LmI|DYVh{xW9lvuU7wYQ~k%zwXZ2H0R39~p5G0{-vaM0dAmABaZP-Tm2X32Gdca?=%c~Kv3O>U(*D-haGzajPA`le-1g7c{0lLIP8+vEMr1t zm=JXD`FC`i)Z@ralhsnomaMqV2c%iQi?jA@S0BrQR)r{MP93mcoSU>7BCF*=zx^^* zWtwV{e)VMLvA*xS)|VZD6J#kU{C#|oA ze$E73MELq!hG_|1`DVz6GeUrzu?@*LFqe@vvx%fpauspFtZ=m0t!(_*%OJjn-0SZ! zZH7-I+NV!PV{8-Z7g$;+UO{Q!3K&e-81so&6VDy;X9)X*oa+ql)f zL~Ts2ZMSP`5-kts@^D@!wRnES0<)*z6?0|ww&E8Nyz!OT&`?2>g0FQO_qnUY=)?9d zj*Dq<>5I%`_mxtJCv16sTz9uvFQ6!S2<}^Sf3xMxTXNv6@~{5HXezYweRCPMJ#y2v z(DRyOOcKOA2_2-b)$kRKS$J?Z*Y^7UTu|)FOinBK_}-7xqGWlgkdY16Y6X3EiDIN^ zBfU>U1KT8baRSDl^oA+E;K~^^>`e z6UsDDM6KCJ{{@xH*t7DAZO|k(VULm5S|VjMA>6qREsykUR9!vdwTHFdpe~8Hpzvt^KA~z zx{ROCL(2c2zJyO!uS94{-eY3fJwcoD(?vKjg-m)Bd+qZJJ zWp@Cd`84D#1MT`}49>J!aC{5LLdaU&5rIkEMw8zIlneZWN)mR){3=c?4IqbciwBUo zb%+KUPz^D1Kq+4tCDArFJ!(xB4o=avs}wq(!qUkc41Jn@-6*#KaX{sls;N@jMpwma zyoCFqRWo=81=?fjVVVoRERJdhKLB{P>w*nZm|D7@>Q~zqrMiDVKH}FIUvf@IoYpm3 z0s6rz(Lp{pK+v&OK0NQaA0?9Yf2KmVOx4P@jV*&7tc99uv2#in-v*q3F@UE$V=gM_ z%&1P0{evwz^!gl@2Q^>Lj}$Um_K>Ub+fy$+*((evN8otU*Dk^W@ z7wgpn=N5c6?!C+_O;kGeHKDW(Fq9!mCLfmgC|UHdA-&JmvtMbNH3-*8HU4GVm^6}F z>yO&F)N{8tjMxz_InVYyFN_J4)F|nhn(2O0Sk1`j@4`jhid})n2ix91-qVr4RpdJp z8*8A?Tu4&T1!$5bcp4IiFSA^52drKw=-*p(iM?*`2y)1Vw zBk441>!o-qE_~9ZrEe=53m|`Y(YEd#xyQ~l0ANTHEc@1 zgp=iKA^Bqqd?b@5k{UP;{5VS&%LIJc1GAW&z6?xU-K^)h@}OMnomvnOT|Jas%>eiI zQXdKIU413Sh@QbeC`C%+5@1NS7okuU5e(YA-e<>lE@|}xLprAwq1HFMb@MFUb_5=0 zZi*{hTSgQk@KfV^yt~#e1}!6~E_MahBh|$$WZ8%AkuL8aOP_=ba_i=IzEFfuY3f(` zNnc^ih~n>O|2nt&W;AsD0H-KkdT6+cX3?(4?1VL}rg7#gur}H2-?-K@T|OY~{Yd*D z2Hy3>N%@KGKKyJ35`{gE?mO37W3G7!N7>d@EUWM4qXUAC;7{3~T2RlzhXGFNVT%sN zhXXjq;M)OVx6dCy|NrREG=>;HM`^BU`r}1oGAm7tbf-%nr`Wf92W`D-*!Oltdo7uv zNKz>GR}aWud_6}=KUtlB{@cS7mH_^w zdzD1bUtFauZJ{f++^Trw{5h`sG_+Y?t+&t_kraV4vaMg$7o_O-I~`s&Nx ze76EFK0nV}IwzEaJzu_BbNO5bz0Je#Ikjf+kzDT35;Al~)Er#>d>Wq@=!O@tTspvn zhYj_*ngc#Y(Qfe(ke?oZu@UE!N~Z`G`fG?hDzDj)CTOSh0FYKEvt}^OpVt zokND;`U6Y{(EBNG`2X(v`MlUrfeNa>B?vKB{)QgRK>Q@Mbvyl1Osb=%AQTr?tEcM` z#D+3%qnQ22mOZ^y(}*^O>dyiZgAj`A?H8aOh{W}GdM)Q7>gkA5gelZvX^RjuDUIsd znvkM~lH&ZbfRt-f677$d4s;lKeS2dYZ+g*n)cGw!X^J`{v5A`VselDQ<#UM_*hwD? zNC|+4QqFX`*FScHraKK)rMZhh+EP9pFT4s3^)R4HnLySi4q1mRbUJr$ar+T_cPKUQ zOIEb!+y@s9`mJAVR5yY?Egc@s4Pe`wfk5U2rodV>x#j%ZGGT4;LJEjSg z7UAc&chJJDa|7f`(N4m=;n*HA$CUX+U_;G;yv;(?rfxbMtScS%9v;>UGe0RdT{35! zpsGsd^q8o11ffBJWOc}?H-1t}&Q5+1|C<*jBZ>1`)5&4I6d;U`?5mt?&$k;!jWN_8 zsLMCu6t%bU2v&3l)P|@Segg>HJXF<>|6s3mnRxU=vR3d#pKzn#i+T0sJxc@0=~Rh`=oQV}jGDrgRpgMd*J{%c?cR4yAt)8p{JMjW>a)Z0JEmk`bItAr0wCODukbQzVysFQr{akct`iy13Aa{>jSl&VbUzYo7oX84 zLwoPS$jWE)`Yq7BrSw_M269a!MdM0^(8rybziL+lMKoKCTmv9m-MzBcF6y3F^tmXp ztv}~x_j}F0s>lwFi+&tt7ELLqIz}-{ht2PD*xuvjA~FS+z;?_wsdntj1RU*AY1@BJjEuJUT6MeMoF zqsPq`PpOuiKU=7lAjk4UD`X+srI%d{$~m27O6!e1Z0(|e&*{>Wl_h82&P@#uaxll# zwKU+iD6y0-0O*^d8h0^`+`iXssEbbF&E0KI_(En!wPT9G(5k(ZnEMeo5-8B@-T>up zsn8nE63Nre-EhQB2!98A)?)TokK@mGY;Ay6w2wL{bp-V19F1}=^UZBw7H+66xOAd$ zNB}D&G&u?ce5TmQ%QvvW#hi4Y>r@C{f=1xOWLn{fElU}~Lz4k@V7yH-kACFfMFJVe z5mvqNsswYxg5s!yzMpWailDXMr9i=0lWilY(Asml3BR)YQ3y49x(Be7BOF-`*+jb^ zOE`K7`s(iqJl1osMs)Fk<66SejrP3{4ad(zZRhz}Fb)ZYR*q%XVaQ9`bvhdnc5@S9 zH#6%6#aHtjS2?P#BRBpszH2v$-i9#*|ckIg=Mq&qQ zd<&gMTlSOPb3wb64`i7lhLwk@$C~<0wXxf1bkaed&WN1WTT)`LY+6`9L*QYdG*BX_ z7qP=|9X=mZ6SL0wX!3E63coe6LyrS#ygzd&s|PH@iA&mOS2Y8 zrJ;tU|M=kpyZ{_1)Cx;g5(iO1yYd^h=ivAr|9rqunk!ct!W4xGclHuKnmI;}^^odW zIsD58tz7dSO7z4Tud^3l^Wl@_awen5tfa6YIvorRzcz)>aW`ShOJMA&ptufE1?XB5Y4`{NmCVdW&#BjB*L*dkSx?cJBuwM(;uho73EX zkUn{bP>G^D!%>AL#AES|#eWT;Q@I~T)^TCUo|p~ZP%)v4?|iV_xqmdQpj=6E)@a%g zV5IB#UlZ9pPe|s$VYd_j2UTimCSen)_m4*HnooHN5`m43Y{&VSHjnGKlmsR7#LVX1 zob23)8Gx*KX;bue{9wJ{i;O6``{WJ1)}o1YcCI%Zq|A@+5PGcLt$|(1tbC3klwY{U zys{Bp`WhUIV&k`oA{Um5tl1RexQ?CWzoA51!E(N5fVz((O6QM1N|)DT+RCzysbIF4 zxt+^}ebJ8h{{>gN7pj+BNsqZh5~(~9W^NLMJ^gr#y4QfY79qOC<3ugR?dMU;_LrH- z97O-nsyI0q%S=sE)5eiWVZjs{g$Cwts*^-$Q`s1@Q4jk|%_mI2_~Rk*yHY7}gnhX^ z1_k_kmX-!=NMtqAD8|!l@JjBt^%Xa&BFq5im9O{-aE%t=xE&_s;Dq@%7E1$0WP@H` z+MSV?gFfWY6A?9q@#N+RO#wKGUtN)3(zM^};tu@J@o22}TkaJeTE?D0C1kkR9P>YLe0&k=9fcpvu=5K&9)_)_^$Q8G*+_<;e z0ZDI#61lSLgRv>Yf-=`Vno#lq?$0lXa>nC*)hE6VZYx&^Ir&;iYH=cd383#M9?&IQ z$xF~@77@R;0zf(9IfUr42YO$AQj3+_G|2C)D>Ylb^X5zd0ABbe$2g8m1OOKJKUI>s z+6U^(o82jPeN`idgb&=w_S(V=EW5EnqC$kYB(na8u=ZEO;tzL1yZVvw$a{VHHaA!8 zTja1{@_QG>{TB%v$wVGU@{Q*yvw7}(R^EKYJG97>&1t%AlCZLt{Yxen+R`c3osz>Q zha%@MYJ2izBu$kuo_I^n?>8Z&lHK&$tjHj@`-K07Wg3mSz15awS}oU7GP(azsNwh} z2)Rq2g$}L>Dzo-O$ldc%XB`T;>rlvjeMs=aTFAYNLhjgifz#`kj;aL0@#f`#x{>iZ zNh^TIb@q*}=V!>-SfawsHpwFvm}DrR*uv>6auTA*4umUiBl&$pfmkK(UmCz3v!pes z`G!1;tl7t90ZN|AP{E`9x#dsxS(8H&fPZA&;N^wSEF-(Vn(Ym@8dO2s3E1&%kXm(Q z#0Xe2a8uuatRY{g{=(tEKFclkn5R~r=^To!gXuwmkX~VX?me2KEN%Jouc=^`iW{+#u3&!)~8y#D&ZPb3{>M&Fj12P5~thTFb zvpc(~Uqagol-1}~{hs-2GI3mtK z_dkAv%zkXOVf1H#E>ZJZ?*TY%(j$z}{jc_xE5|RN4?vgaCeJhXkLmm1XtQF^-$lyF zA-{Uopferz0m-8A8096xP+cobluYK;wf%5d*rqk)f`Db!ZXmDYJj^Q85 zCDH?%7EnSt$suGOXjtR;lsp%d@(RR8P4QQDPTvIJ*1Rc&ol(W?ICGR-6ZBAhBNn+J zg2{0(jF$9xruRwTCk1HGO#kp=CP23O(gED&TS)Scu5x?3{nA@X$fW3VbH+~>*3AHO ziHJ>Mk2(7@%hVf97E~ghR?vD+8#+qj&pE=S&}A@5W9MGG3|rtbw5s&(MwekP66S6@ z61snFT(P)M&Ap8KREPp!{Su!-Nf}{_iff;%vSY;Fa{DOB1 zpna%;bMn9+7$2#;z&T}|ceR}+v?`%SKWhq3O$(GS{gUc6@{MIhtZ*S3%L*Ka2b5ZK z%&^#mv+3V7-J=((J+d%HBr6zCnrvt4h8Oa3J|13euC?vR#=gf8eTzcPH~fyivJid$ z0ulV@QS@CDxp8ML`W{Eox2M(El3_uEOVfL(FWQR&6=*9b7H}QyETb!GSwObc62cRM zNi?khXj-Of=Q%e2XwM&KwKmZVbSVM+dZ|^WmkVF%0D*od8GI~Be zw`P5-=B%(k1Q@85O7j+WC2(HNd_iN))U_*8g(U;TtEr&3nQAe7qKS0L;c~tvVCL)Q zxoyV#4xoF1)c&Svq&nAk|LHp)RXj@g@FUW+`~Bmzfv_@RbHFRJpsa6Rl(s_uzUR$z zFCj6BH#I}(viE$fUwz)aUhrlq?Zyx~N2;sI5lpL5SY3in&J99HxAE8U(qat>_FL?~_Bhk$DHY$*k9{}lR6XVlHC;ET?dMiXn zdd~G{5~gyteD$VXr-MJ>YXH?cCkjzWd5X}3LMZZe8V`UbBXQtT&&MFUW%})YwJxvZ zF6m_?18+?nKElFUC+td=BW5%MWufSEl)jUBuN@C4u7&TFaJ||_ zA*5b^_rOZ5djI)9-jcI8Z@%3=)f;YI(A@w;w{Pt-00R_@^jA%fRq-9Te);jD4#zf; zK9Gjg<2uOJoyCszif8h>@&ee!Y10v$z9?aiT5GYFi>=C?Cj}UU< z4{z!HbU=KPMTs`|HAu&na2UUK0Pl|T)q~8Tl7eyX@@3NrIdaeDkrM%0ES1lo561dg z0)};3SKlX$pMW@5{JW-f{pbm1q~p}4fnamkQ2{ugj9Fgy#@O>4!^K@}WwzmOW1WW@ zu*$h$4=6B{SaF;`u^qSl zWU=wMW=EY##Apu@5>k7F#>F+?Okf~j?a!X|6`*A7w+WJQ`H{e`KV@l9y15`BN%fJ4 zuHFRHwMsL;?FSHv@zt@Kc+3URD-fkU2;@uHN3T zg>H*~zZNF(Oe$cLp1bU-uXVpXNl&c6T)rV1e_)AEJm9wC(J*nVhv0-400 zuO(w95R^??ay^Pzk2)e=TEZ3=kmkNTWnqCO+}+jGl&o<=BUK)ihE0%Ca|-0V`S_1- zy~xE2BZXS6RLi7o@)cb@?frbRz~GiW?wleTw+P)tJHM zuL+=d=w#0j`f=cT9A2UET?4{k2ix*SZ*)Y9Ii(4KxD059eL!M|@#`12e+=diZ@k8{ zivp-0a)kAziGjPxqV~nR8y+t~{(yW@BT_oZ-p+H!{#?_ktbqsfc#fqu)z&K}$Q+i$Ooet(TnrzSE*5BX$uiE@_`kA{~NB z)E1C#8UutLt{5utZo^g%Q^2krqMvYx)In*hb>I!s-#dWZRkskTM#om;=bD=W4{EJy z0pJUzz~QBUXlRd=XVG9M5Ekuyi1KMn*OwYD{y(zt!1a30UG!`ma0qqltN?qW;*TN( zU*6snY%vc9@5)^Npao=s!u||U`rmvw2fX9MmYE%N?68T$RP~hB?$!552yaEL}hb7gzLP!`#f8|0OOPw*$c#&LhPwY<=D(92{$bui6}4A*H=(N{7xJILkir! zxSqGGA1JK{+33?JGm{#0f5s3)`6WHmHlHgCnxa?~F#Tu*UnR*=KgIV^n|@8w5sxq~@;^ z4Qw%-aA1qqPPq6EIN_H9Dpk-CRzN2_pdexo&`p|Lon<1xpF5rDYm?ahiv30TIpDpw z$UPhX{cQoSnzZ-}uUffl{!-8+{Q9e*^hYxei~^qr9At9!$+zpH26AIlG_!AvNNLs5 zPmK0K8Q0E+2p|CIZ`77>ygq2hExls?MAqPok9Q+zko%9 zTheMiIv9Vb2&zP#Ml1ov%Y~K5IySj@9u#x17dL?ON_*ROO&mev^9Tbm|JaG6YtZp8 zCFmKyD2l8@RJp)Gi20vi+N!UAaX=+eiE|zprcM5`#$|FD(fQ0=gPW42qM9Am&NUBW4C9s#OhG7@BOu6yPfis4H~@m#%R@CF z9&AC}k7qGZkCtCceNf8^u{WLZCoWa15rGAgUIV1W6lhXLMuBHaL0~Sxf`X{bhFegH z?6D9(kb3VbaKFRAsXBVJ*CFY%+rrQC;ZT#POkYN}Fc}f>VLm57v_y1O3+N?HfOoX< zdScyC=#+cQznn&wAJ``TVP)fp-0iLjWAgWy|VAY*;y6K4VC}v&>O@9?lxq z4hWI=-kz?#vYw9R@=@;{&Vw@v&Kx5@;dCRag(t{59uiz@FCXmTs&{zBe~{%m?ySnReip@j z)|Sn_!9%aa(_~ zA3bqtI;}?(LJVNh3pdK?U7ipZna1e>fG%|n)~5X(s^s7}#+}xlU|D^Mp#+lRSoL-Z zL?|BE4*}(}!p_JGTq?BmS~!&%HT5-wN`4GEc(Nu_4D!kLgy> zv<&;XfQaGx_}9pzfK@Ops(1lZY64Pcm+8AaiTz78i$VsaG#a(?iq~E)EzTE~4BGh; zi=^YoC9hyFj0pOceNPOwv>FBFe2d)+H+7cDXSvWdiLt(|@5J+0TflXAjGt`-b^Y*) z^F1%h7wYqm9s5vcayR)vD<~kYw^b6y7l;LySPoe>rGzG5Omv*-x{DOJeM@}6r@Ixu zf3j~h>fEARELQ?g0;ls=ANKr90W!a6>14qoqP_mm*57%I0U?q#3iO<7FWJgKc2QC| zcpIHRIX#HYhov@7KtHgfhV?1t0ExsCD5Lq4A0R#+8}7gaVk#GlYuG8ni#{iVopcEa zi3XuzWv4MB+@Ir9_bw{Zp2j<>Ulo7H^nn19tZJus)zVSQp|h##*4pp##iCUfpSozXxzPm0UyBlNFw5)9nM`XcOf zS}q|f`KFJU7nWYo*S{erl34O0$f+GDr1o8nI5WARv;|lt+@zYOa7-WfkUBu7Y#D73 zvl%Dw=fvqhg6_w}X&*N(aV#o~&gaX|f)dcs=7ySN<>Oz<`v?iqr=C9ZAuKJOd^1c8 ze-K^Zj#$hP_t!+4=Vk6+gwuZZ^*5!4KZZhiQR}tPiIaVt8i9Rh8YReXYOz;@=sz%r z;4bqO&pxRa&b5YSz~}s}g8vh@;g}rF;d?Z#f9d@QmLVjH=ETMd<|5Ur$6AGb$Qy*c zmfW56=-s|0TP4`yO%ow)j4=6{7G-F>7%hUTSsnbPPM*G1MZtU#aR&aBh6NxUb)0`d zHTxL<G7|JD!U2<(A#2FaJogF@!E(w^2Ix-9xs*RPk56^c4^6o*XGUS#p7E3)EC*1~=Du z7jNnN&`0zCNh%x{_+8Ej~CyE@&)J)^8w0CWVNZ9U7<3XcUI_c%W8Q#mk#9Rseh?(1-=AaD#X-14`gqmc7f*79 zblE-?Z0<{sxZZvq*~8{5cw+?-`CTRYgHIC@XCVB&Oy?Qv*|x-TMmku@OKtK^@=(G! zXuUt;f66s9EN|H({E{HL*w_P!!wn97Dk$?tp8eFux-O~+m4MEwa&ZP|yQ?rzq@KN4 zOuex_N6{>6KIvGsb(R~h>peL43ha_!gpIV~6j_F0aDkrFJ)UPIa#ZsIZI)$woZ0zb zzD3AJ##aBCYb^msY=r_UGq6j`fk zg#!?Sp)WGsZbtyY&XvMk=q%Ydu)KVK`hn?We;&mht4?lk1mq@+BQGAggM5EBG^Obd z@}#@)htp;mEvf{a_N7jkT$@(Q`pI@idJ2eg3oIAi_g#&fmFQ}`h@=V6Gw zyi9L-2Z~a(^Qs8dWFWTnawSIRWnDZ2I^wAB8`?1VwiYF5!Hx59wMx}@sfVBITt|Gu zkh2%?ztg6wi)W9Qfb6rk*EB^S*oKX_MPVnVZdx}p!dqPamAWFYH24LKruAI!1< zHKSq_^m9seKaB*XdmX+(m74+X6Dmyq(2e0K=Jpr*%Q))u1imWd^x76yFDMhTJD_&u z?o-w_2@?^Lc9Pf9-(Lx@mI z0;jR%%vcxECY;Kmp>u7z!%1K6lJC~=Gu9)1X26pxMv03!iqmH0Sf4BQr-jJGF5MIO zyZ2%Tmsr>-Eu}RG2WCwwQwzp2)wHBNVF< zX#urS-kC4XZ*b=-Ek3}P;Au>dXLD*nnr~#^|ET=}id`gdGU1a(Tqm0}$S&dr%Tezz zFb`beRj!oyYJq%TW2VJ14X%3Or{HUno4?5jn7^BB+g13;^fYQn-f-f`bLf{^K(tDT z_L#aE1ZpaZG4f=0r02@^D4yx~E~81d*8tCGOIK)nS)IO*!t@(xv(-e4;g_u3G;*PM zYlVD$y?iH^{5s17;I z!!d&3Yd$irfael}yWi0iWRBrQ6K}4}$Eh?S)ve^V0&w0gs??+bI+i9ER;EFnI@N)w z;pQUfy+6-)s?fh<-sLu!nwJ7xO`1H6g}~VVRBY2FKMM;hdjQ3{d)a=|WM$umhFfXU z!iMi3wK#yuYiFCEV5l+qfiaBEdbLhO62@wn{Owo`==_ny;%{efR4Bt4niUy+v>OV0 z1|2vkk}60u(wvOxCfSY*5I?8zRn87v@KejO%RjH{&By@z8Iuk?UA*3mij& zOp`2{RsghiCF54c%!t_CP|I7<6gUq3kgUdeTY^+14@og~4Z$!!A_`J5Gtfc!2W!== zId&fY8cmSsx_9!p>s`8druO zMB6u3EDWzQ+>4+{)S?)DcoskXN6COj4Xr?>18`p*xo{hlvG9!D!tc-Iug9wRZWnVJ z;Sh_U(UcRF{0wu?TKUe|v9AVV7&rovWYOM4_Tugu#tw%q-7Z0XO z$4~ruEr?KQJ&U|GZAVnVy?mdq*sM*GUgwL~vd6S4Gblh-tf0gJQ?P`4e4MRs^1zHI zq2Wq7kqKI`fhcES*c9h5q&SXEgztU!)Wn_;Y4cA`wDHsK%azFWgzc^Vb49zOck5pz`re+Pi^5e70RX8e&ERfap1A}Jv_dI7wj zn(4*;yVDaeeK{7*RWNN}XlrBeQ;f;GGXz3wwuv&^$EUhPI-@23u-+nY6^BpuK!Hm^ z_5}L%C7|1#&Lb=qHkVfy0AMcxG{d8A#H$VeT4Fv9Ry7m8(Tp3 zb!XXr>=PeSe+Zm?j->d1?%!j<(5_wo`P2CK20sgjzJ13^xLgB&r4P|FlYibigG3H( z@bIJ;xKqghb6F{19@@j4ibdV79rQPp&UUS5yH!hZio5hgnDE9KhDg2Ragp6GO);%K zpwW2c++JTVU;xY!io$pwIYXd~g<5wA=$2eSjoKeCLlyE6pHo*&Digs7abJxi(gg5a z<5tN5!df&BAgVTq_Bt&}?=j-WaQI;YSRn*{U47i*01}_D<%@v*yjS+UwD~D*qO>kC_)A$n@ypG26<*u2--wV0h5i6~6MWK(^9Ezv#5qNP#d?SaAHtHX*BzX(lTUdGKF%T@vPDAh=H_gt|1YA2-Jy*&tI>-qKUL{ z4z|ZpvGbh>C&boHkDY~1mPO@9FO(O2HqHQ_=+InL1mZL07sW=wUXR`$QW^??iJK_*D~~F7>G*K z%tc{RUYlW3_;Nq-Ulmuq`ImP2=Gl)XQKMySe`Q+4IGA$=zImr+?M2dIri`iu1t>Dqf8g%gDqYT(RtssY7QJxs8zT?LmVx{{4 z)Us<#_@;fWi-R-WCW=RnJ0t<4LH-tR2OFvqcVEsY2MJv0E57AbG)&*d^qCG`!0&Z~ zc18i8Eo{~PBQ1F>fF}-ld4bSE? zEbl<*f@C0$phzf~m2ZH@1$C?S2;q6K^pb>!B(gqmHOjowM>Lk3(m=eB*Zo9FvZrJt z#*~L+7D?*~e3L__OHiL$0hE2O!`iipSr6wdU!BMkL>kbCBhfy~=;ry*_Q`-ab*mlV zD^tLG6}mJn#(FU#!z&Vhx)ERXiFq2F>xg^0urW~S?nSscro>x*ziAt0(7Rh~_dola zGKr~xJn=x`ozKesA^~;zdJ)Yo2~6>(h~f?(qYpttS)L7VUU7jQI0nK4@ZkCVk--vRPFjU`v zKgQc%&U=z~8vXFk{3h)WYg{qP!VcPt6q-+tM#moX2FEQF+e<)vJZ-daP9- z$j%H#Y9SFebOp=N73}_C@&o>SlNNsf(bvGCe}IzX;5-tiB9#$3fcV3MbqNo1A=z~= zenod&`nTG0_4bdzkd(?-BE}b1KU?|=5VpKmJkrpF;P3t@bejsWV^%ke|6N3W+0?NM ztiHl@4al|aQQ`$_6!aYx09YB0`W{C+Ko!|unN1!`uDO*NoDn0!wtC_I4Mt@3pZFX? z?;y1L*Z;fkphEM+W>pLDUl^Lz1^ho<&;PqMtbRSTb)WD;2k`&s@t;~JFc_M zw!R^x-Z8Ss%&n*z{aIX4-T(PBOylYnGpPz4FAx_G5$PPw6;B@xm8$BNh+ebQuPx!f z2R|PhBvwuoHe4$fSL=}91>Jx9({>b0ZwcQf{Vu-$`JcMbQw@{|@Bf`(df+k?GV2K& zuxs4$fBy!58+=!OT82h>M^GQF36B5y+88eQLqcMpZYCnR(7*8eE5C9F3#&Vu%l@xi z=hao-FSOy{7lIAAImvQ|0%PVE27KQSr6 z>be?k@cpB#{$G+I*DVnC$=2LB36;ga@Lm4=6|M+aT^XtJ>c4!kp?F>oCCtN^N&}vM z=O3MgD!>;Tp82n@jmC!o)Pt<&!e8V5oqzP7gM_x#e-6^h;rh=(T1ou>IY|G>NNWl8 zKN)G|Qb_+NBcU4L|39Uj&oR~+MC03Zm08iFDP=H7>*7!II_m+Gs)$S^Lql3-m;;d$ z#H*nN)4uAhOHWR^!|>TXqV`FTImMblVQsEu0+=WPys_89&P{9KR;sbu|^pcIo4908#rXl9W{G@TL*)8ITt2w%FcX# zBPBs+^d)Sci0xZ6su?KZo3XOK0+U0v$XeC=_~5I5;gjRzO5?8tSc2=r5!in1%^6w zQ_8a)+)(e2T|MWVc-i~2+b956t!Sn(C@qBWhr&-@yET3Lt?85X71!;%HGe;yaxFOh zmy(!Ckq(X2hYMfHTtxy<|FoinrQMdh+iA1D=Yd6fIR~c6)p^czZG_2jIiM%2vi)AM zonpczv5{KrQHX}+Tirt@*WeTSQBiMXJvu>TVZt~MgIvLNa5Hl7UJKG`du(`+skh1h zUCSTYI{&nK=Ay2j8tJf*eZYLP{)jZI`*fM{1#iAtCuMl*6dIs6@&ZWj3M&}7VCq(Q zSfmrkUoDtn*ggo?A{VyEjj-H=av5OR?~?Ne3^67=@g(y=q*Cbt>9fa%hp}iSH8-+x z|9mC8=@BJP$7>GM#i+r{M-2Xl7q_B$5NJZg$h~rlwEXuVCu4tXop-3O2xx2MA8>mG z8)yn7)h6Ugmsh*!jPxEZb#%hG-)rzdgM0ITM8Jd5YA5#aU37(ScW_Uoz&}FwR$3z; z)15!4xydm8_sj>g5_p^x+DPSYi%8*thWMd@wP?aOcSC@LnQp9`yC~ZSVNSVwkn21)Cg z-%A{fC@4p2v8qcJ;UacK?KX%`=y7z&X;qNhpD*9S{N>l=a`f^-`R>!E252<-D_HUf zJHFHcXp;LQ@(Ff#raxQS|F-b9>k0Ryd$6dK~4tdt-z1J)r${OtFqV^QNHUOw%4F08f5v>;5M{yUPnz;-XH8^!KR(&fTulmS=4Z)|#!Z>9@2nmL#+2 z+)kJPlnbhsj>&2GZkjOrzTHz8o`OhUI3ak3)azT~_h7MHYN@Li`{KeT^gy_d>h)Sw z=p++5{KWq0wxnHOr^=Pvb<7u!=1a33x{|i?1T%lNvXj9w$BVh1$uMD#3R$(c(7QG; z4{X}(?*WfzaD=DTN6*-Et3Fl)^`6+dIjcExfW(-?2kiNzaAaaqOZ@n=qu^Y zpL@}yP&amcMS;`kh>R2F!J)>i8ru<#Boupl+Zyy>Zq?)2>i z7N2=^5~e{Em?$e&{{n%pWlhYvB@1TZ&F)cEz3lP?Z-v;`$W%}N@LAjPaovKeqhDU_ z)O{9~%N>&t1EafC;fZpI$O+qNQsz%eQ{__C`yljc+Tnspl(@?+Ni4>mCol--1}COH zv#|K%RdyCGtiSRo=VJTiG+l7BX%4AYZ4E|cA{@XWtyFZ`BY z_()Y>9(;~ki2Q3`q)UTafamme!I@o-y$dr$-*qH^R3f)9w=j!iuU=84jQ|3?@S_HK zB;H(uOpY@*G{?{_jz=$_#+RvrE^ZNd0*yAubD!37eTEJrj~!entDN?5{$D)0+k)U(9P!IP+re&OBKX8Pd{+RrDD zWo=b|C|wJLApkG?kD0!Z)Amt(&Cxl{ET9&Y22!_nW+O68(1?U=*_5h{JY-`V=g`QE z^b0I4&8;oO_wuh#>C5s6LoDo64xH z&?^(%yTO)B!{ad|2YBvMO@xds3~aNHJ@sl|1MZrN8%K*;Hl@@ifE?d%fscQd+8gh$ z3-yfdw5!+PV$Ys=7c#fq@F)@z(oRpq2!xJFh^7ufn|D%5PfdF6J89sZERYnv zjZ7g*hs)T^<##cL8sogtM4GXUn?42cnqVmX65zDyEbds0_$84{zDzOx#L8yB#S-H( z=c#UTIX;QW6K%(2~El`IkJM`8*n0fv64t z!p6GC3J<0@+P>Y(9K>&98)fK@cBJWwIVnVh$?PC|2W4=dePQspOdiwCan`2PH^*JE zOHluE-viz>8U!Do5KCv>$h8(?{0H?r1RAwEW0<&`>~A7YdRy*i^`2*Fkeyi z*tZC~sw=0XWN?_mLqdATV4K*YZE^|AAgdUZeG7jYX{mH3`Ey}_d!dSfLA|OUrZb8A z#|xUUTQ_{%5}KLGJld2LkS2ZPEKl@S`+CYzul0{_M3ZyXcfzJR@-#M$ZkedJz?>yt z4^HO^9d)J8z^Q)F;FhPA>%4id;K)hwI1_wh)kF#!R(PK{7-03;)j2B;Bw7Z?B4SNSG_+^7toy{izgWJ z+!g|VQm`7sA*YdcqMSM=V@3YH#xlbmMbSvm z!`{jn=s+~VTHBthNBtk1y#-X3>GnRXub>htNUKOmH!316A|Tz3fOJVn8AvEfNhmF$ zARr-Kf}}_z0@5wgEdtWtzCAOeGjrzr{`1Xptx;!|zVGwgvG=vFc$mw8Z3p2VD&Fka z7G4Dp_UD4|>7scj*I@cmNT8}(@YOmM7V5F|Y*O==jXL}@=QLN^X_EFu1wKX^+`)5R zlyWEdM7$3=eM(N-pJo}^`eEIAYbc`OwOseXhtE{6T7gyhB}znfbcxB(&K|QO8v24a zNRQ8u>JY~=m5R8D&cG07*l=YE2y2tneE4;4#z$X&yu?7H74sPUP8R}Y_i)}@6 zqjP1(>e>e5sS8UxS(b39ipe~K5k&qQdqjZwORx0TUy4Rzy~URl0%jGW>s`31=4uI^ zDefem`*XpCIjUN?D%#78KS6FDT7e=c4H&Qb3f);N9*NY3R}wgu0YOH0=Aq_Ve`Nb) zMs{VD^6{&&b>g`t^w9g&voOY>MtRJn zGX09DZ_dA7gw;#{B`d+!E z9_|jdKp(f=6aI2lD-~Bo&s>Ai;xApv<(PMJX-AV2>F%G$j=!t+0YV)|0#ju(nKM$y zSUWNCtk@aQ?M#yo`O`48xZ7ts`wDHWKtN#6 zdFY_q+x#Q%WhL#?u15w6f5R^K8YG(n*%SX@ys7~+mngDTzXJkoFZm9cN1+(h6WG5< z%RfhH|H{(J@lom-c~W>hKIxCThfpD26Cl60ar;Y?yHqoGGLoD>IU&F(Ko8mc{9QM)7CBwV*C z1l|4)j=|3Vy<#8W!I|D}?}J3^^ZiA2I*+~ZJv(0$8!La5geTdHlr0d(gU6D{C52*u ztUw94qQNWew+yh3BTX9YW@KIlPCLO2I}hqsy|0HRdmbMMg-_{8-y&C4Rv9kfas!D< zw}+Jtq+akBd^;R`%i^S;4#*$$L^DAyll)vwnf+rH=v8+QeFw#`3sO0*VUt@ zp*OxuMV>3oVLX|1S$cmiIBfL>QVNKTN;}Gp*yq6GjKw-w{{-(ss`7KO#}*czRcG{* zF0K-h-^S}&1dg=qqD(;m9PuM*e*T^`+Cu4@QLhZrv*w2@hIcNMK`*|+=y+QAZgB<6 z7SMrxq3Y!9G3dsPf9@z1(mqQ zsNaW1uu<={Wqsq1g$E_c`lCtJoh(pYz4%C9!tkkJW5~T6*8@HlU={{Iv$Zoq{Jm%} zF;9MjeVRF185>2OMFm!?Hh~H`@SYpeR({{S*n@I}Uc3g)$nKcfsd`F-Bj_OZQI-k%{b|v$k=#}tfBQvS*)vJ;viddtm&DX6P^_8ArKSRvnLDs8i2&qy(jtzDiD0D>qQHWYh!&g9eVgT%FU*Mfo)B)BTZz`*|o+ zHj$m!G%}L|3qDH6G|$E9Z{U>)=Nh)%0~5>mk(XJFq7$+7LjMmWgO~S3rJ;4cq-rBM zk8E!sXGRTz4E zYjD{C92lZR=0ZrT;jy%vW#4&%2L;X-JaI@tY6%Y-(k z@Xq>;qIiH8q`!uXil`-baQk>l-Z?n*Dp4IUzq>AX9*4#x{LJJA66ub)cebFq(OFJjb56^05+K}!M8$D5j`%5fOkJ%`ryJ{ux0#V7GkrLUTLHq@YX?!Su}Z! z&uy^q3 z_ef2P9-1vjqA-+kIS|o6DNyRRRi8k!>OlTCR^NlX-BOzj&+nhQSBA#nX8I zN4F?Q%xB0r*UGhh@n(y@x%y3y(SOKQ&mQEF8DXbLC|2l-bJ+Li=A%t|u;(pi3nj2aKW2@=Nyu4%Sj*aelA zIT|m3e@RKft5p6cUX0}vYH-)~E6xFuV1#7zrH;M1CLA8*sKb~hm(g>FkMO=!x7A-v z6Zd^8K$v&B60Z24qqsF5442{4AITjRdplXrQqnLp|62Cb}Aq% zpNFE^>D?=q5kOJdVY1+xoI)@IlDUa$eOxBF7``_5mO`8UfxO!j%@iFuNzhglfMrGP z>=;}U9Fb{hI_0Db`+5Nc)MHXH>=wNBwRptBfIxnweG@5Eek8?!-3Z4L$()(0Wx!M1 zU<*M`IKaafZ#BgUA+*+Zcb^^8qE@CaMDYYL{)hVdI}_(`1Q$;Ntb2v=Hd*rpRP%Lk zUA@~q{GuqY;=#V&-jlVnp8KNeo)0;vEL|yecK6cujg70*d zH$QP&JNIpVZTW7dr5ALQ5QSg}RQ19Su>z%vKGA`Z9abgsqkf;T>S36$kma02(D+nA z*a8`skT5IPIM4MM!rpaO3qV#QD&{i)is7F4@KF$xKJ_X$a^jVf#WmbgX2qlpDyZjL z?tsd~840m2%Qw`gQ(ol|O|A?MBvMnUmotn#d84?>doo`#?RW}TpxBi(zSTz7tYRxC zG-4Q7Cw}>r1&$;eCTCo{O)*7n7dR-rhDfJUCKWD;Qcm{1*151Qn3@n<9f+h=B-5W% z)vmr^!zOe?5Z1*9$EkJlOdsFTXD)uZj;g7_tXfo78wu{_AR0;w>s7b&k!Mm=fG~ zsmw3a6RDl@({__<`JiUj*ezeL1YMcl`HS;v$Q23hb=>jSjpwfd_j#=CZ}0z43&Tgt z)5w|arDCL)QObOl(JR^{Lh2P)Mkw|0XKY+><(WMa5|19xF>reRppKRy#uH--J>Z-4 z6RH`SIj(LK7c3fS zaiQ7X*T1~agl*fA^MLJ$`{S)9mxzd*DC%>kZkf%}W>XtaSG$qUDG#s=QJdJ!k+vQCMCcsB#AirT#+ zh@)jQQ?JKXhrx9cyi=u+U6}`6=`bG%3Ki>%8E{aij~u-JOC$9A??tJPcu-~^+1tu%DWp$3 z?fmhm#C#u4@U6E_SoMMjSIY&|zA05og+;2`OH`fk&cqzh1$TERwF&@m=F=!im=u3V z*IbMfSZFo^?}C#K7m=eH08xqX<=M(R5(+Lq_SB2xKrDhWF5d? zzm!W3f{<)rT6y&|Q*Z){9?04qUK~@iSN2Yn;doO6VeHmOh*Is1$9T(~2|)a_P=kId z!sw(`u7b=aQcSIn^>u~Acw;8*Q!$lth83i6grM(%dn`2x=aU&kp`&QN(AC=qC|%`8 z=+yM2?1#(UE(LYqeM{G`D91a055@=|456#w7jU zyvUCIoY>(l2!03eKDES^VJS|U)Fl~n#CkcD&R?SXA`?N3)Jb9vmbjKeV1V>OP$IR2 z0rnGr`wFO)_PN9)V@&Mr?H48$krJ|1VJAbmWBYss#aYv0yVoECyB*C^lT^zGfJg1u zYW*ES$maTC8oV((nUzM_-p&D>&Uxp7pR)bm-}tZVfq(|{Xg=HD*Czk*Ze`?dMctZs zJ$_mI!Tmfza&$aPnO@I z1K=1s0Hj@nJz=-^sxc@dW5C=xfdtY)OxnQ98Tqt(E-mM~d!WW8LUuxqi`;oZ`1{q| zRaVazeB(cTjz|4OxfZZ=-#6V|a6A*U zdt>NrFJ+k~EWqdf_rRbE<$Ej?{21>8IIv-V-POD7_G&I*lmec=Pm*0vKo9+W)L=U9 z@YE|q%A8a>p0VWLjJj7d99>iX^FB9pY*$wYckZ#0jk+(&m~ zRE2v_ObkTg<5IxdXt*y@V05idw+lSJQL??d1J3IlkMZMI^P~b$K&J2 z3&f|9cPnUNT^cyPqwxzE$98{!1o7;5umA<#oLqwGQ~prdozgU$G_a z??VqOyieI(Q`R$QzEDW7_C-f18Zujlrm@1m{QUiYTb0x+NO>iAr$PFEGLjXrkM@tc z8s?A`Rc5Mmk%;6nNq!v0{=Pwemg7)*x|z^n50B9{x39_;GkzgVb?^j;4`b6 zHc{+(mz|mL6M4k7;Y}u8VUN1=pHuB${gJ`)7~FsjF(XzR2x=B9x(1(aMH8$;>Yh73 z`t4S4L!vKjXTMvt|LuhT{r67eoXS3sSslrFuCS%>)~BIUp*N2vIlE80|+=mpl zYFn;K^Zz`x`S3j13+by}Hf4i9{2OZ`YBL06os7qMR z{R^%ya)b&GrH~_T*0KbgcmMXAjksfGt@Yl1?BN!8D2ES&!5LuW8o~Yg+Ig|G!_AH35}m zYu+N~3Ok%@n@hCJXV3!w!1_KNCpbx}2K%=K9()nrrpX646SZF}j^Eeg@4LVRqhpf} ze^gDlc<)@)4GGw`E1I$Y`n`!J6Y-hWeWp~p1&4IW`P}EtP7!f`m=T%xGEe+tl{S)E35~f;l^3=%R6Lr%S!9<9XNy}?Fgq+Y5*q90 zB0f$ifWgPa!BM;t@HH#&U%t&sEj+jmYFF(yzgZwEl?@EVP}HkVvE2)BwwTS>N;!aa z_s1^fD|}zL@4jdWdP9+6|MCsJ)EWU=L!s;PbtIJ^Z+Kd_HrHze{F{|^#27=7QPEqI z5?E)l`<=Hg8?D#~GaY_eiXOf1zkKwf(O7VAky$~WsT&Myt`6;iX)DSVw}v88u7iAl zxF3V-|F~#*?S-3pMgL;XK^gR~-c7KjCyahke1{D*F}#pNYt@^ZG&|NN zNmT$-y1HR~@bI+;^c0wE5i{JyG`!gIz071MI^uhI1$YTHogSjo+!gO%zB17?tb5zb zk|_2EMZF>qB&(sfZ}xV9_ldGH=K!o(cVC1yJXbo5CCL(>BT&ebvhbaEEkh4hzxhd{ zV;&@ukSM_uRP>{w{1+F=12#LrknR9-tGAj1V-{rG3y;8hc>!pI!}Gw#;G(oo<#qTX zWd%)Ey^)=vH4a-2{jQ%;MPF760kfYP}DoMSx9a9%ME=5ukxG?DK-gPa*PiTv{HvQYDU5~l5 zHkaeRJw~;#2~0q3sQA5x1Yk~!!fytxym3i#p*Yn6a*x>QM|fvbDizkAR`m5)>cn0o zYe?hq{_&tg{^fRgz{UkR7RY~OU=UkLz#5}i}o`>fVx^gW@k8YTv1cDv-X=L z4bKTo2()|6W0bU_6WmOLzx6z#`LI>}!(*?<{dU;Csjmw8oeS`na~OU}gA*g{)`uWJ z@VoLW6-M*WlD8AlR@N}PTj)a$hhUn1v6kn|bo0%Sz!X(;**dj$0v`r+AuW>r%aiu- z)e(Rn*C6zw7YL67tNaNLK$5$(sMdoV!Fhqry?z@iVp+8Y=x@YM`1>bljA(3i>f2cR zvilBsbFDjH13{&k!vti{jroO0*!Wfol{NTz0PescUgY7kR^SAi|CG>A)Lx3C3 z0)Z~T!fbc^Lt*dkNDs3>*alfMt`QgoN7ePq!fB>h@|&-Lr#VzHr0fFk1^=OA^CTx! zEXaXBPY1XwHqbZustu#fp!jCyY9KV6(BoT?dD! zOIMz%YXn;hQE zuG)_5xed#Fx0R*KbNyK^C_u4ut6GZjABq}LYg{Hl$b14u^$lnWg0bv6khpFnb`7S>lS;nHvJ?i@KX+k4&X zclFJ}3v!SC@!>t20ikDGS>$H@rwXWDZUhB0!jS9J@E%MJGF+EGTbxjkR5*I#Ts`p= z(BqSk0nPHJ(s>^2hPx<=T^*RW&yAQxyAmajbw^~a&h>Vn@Nw7fc%aF_g!nqJiHmH@ zH)@fW&3Z|-5z3r0fia1k)oAh(-dm%^o@Z;x&|i;I#Soqi6ODQQMpRR|imNQV?)W36 zvm_Y*pIT-gW>`?%1%qs)|4_g!$%}T@5w|0rLq!L@On5Qwb>@Pnj0%0={A~k+mqN4F z(;8*6b^6Gc6(Rx5=_CUkC9fYW#35qPgmt_#48IvE1Yw<5k0zC$1o#o$Z*F#fX?fON zzWr4OvGTXHJ(^PBlb5!On`0t>im7>18Bi-O%e)GssP+ z_z{;uM<^qkB#;7+^pA)^Y7Y-sM$4!EvAutJRdjy_082WM^f<5st2!5at&+$~`0s5O zgFQ|)a?a`4>vU8dhe@X~42`lNgR~C(h@P6u@v_VCl7m%aH_?MTO- z6R`=9F}B?x24)zNtxSRYoC)5iy+9sZthR!gNFlh|S9^EgwE+0Zu^IU=(okE{Stn(}LUxA4J?=cqOeyjb}aEomB+5F82H+qV7YoLvtBq&y#2< zvB7=3FbkJNFZlc40K!~0j1S)|PWv=M);->ebQ@oX=|ff*BHw!3lqTd%wZP zKkWC)UR+c_f9uxRV12Vo{1u#4pCF6dOo!eYUm`v1?8-Gnn1=%XzVixjU%m%5H$PPDx6b^zEFq3^6#;()lUY2$*byFkT`RkXf zNEe0VQ)L5%Haf_gc3{t}InvN&!2Xdy+Sd@t(^t>?1ZHOd7@95$u45EvHn`{7tm;yG z#DX-^Qbo_sISV z^FNh?qr{4K)*oUnBGXAS+zzGSO`z(oxpsUE2?N$o4xB_$7#)~RBr9ry{BCf^5-G}B zVlJL-BYb*WZVYAet-(7eu>t|nh}Sj#KnDO~f7sT-cnEyRS*N}_RqUqG$Mgf3xD(cj zjw1LA9Iak>OB$5Oxm4w7t*zT9k5WV_Rnr9bJM=$xPV6iw;owmpYJ6m*S^F#E2;*e1 zEAXhH|NZOz{Gz}8>?$79VO}t!o`s3aTYuFn89+AXI5T0DCZB8<9{B7Ocz@zWrKZkA zF5XjP?0<7J1+HkWspl|u&POhdd(kYBsVq^O^Khli50&-%5i>uTx`y3(t`$NwN^wn2 zECQ+AzMHuxxf01Z*1*i%Si^CG~$=N`=@tuxQ0yeJSQd124u(dLy*cy+8qSWySD+!XAYuq0$ntk}K1C&OR+6{Vg4O{gD&xeP(3gri+1 ztJVTyrjZJTm3bgAQ3^OW_kjk;wqmF7&OF3dKB%i+dhTvb)ekqdn`Qh%!*dT0KdKCK zPD1AJV zsvU(nbY%ROFpXd-wZ)bbJhCgYm4rC z{b>H5W)Pk|9fu-#JfgCMHm4H1itUZocN9c+K4Fijz7J?LV!qL>rI-DYv`_J*C2nwA zg3fav5_?bXom7*8jEu0y3)tLue);s*RRJpsxFOht0-b(-sh>Z4OVCpRd;%DNf+4OI z)WW=!L|OpvBb}SxI{#4zz-q!_RU1F*a6^|Avj5imF}4D;_NQ+ZB<0hFLDAI@)8v7W zaG?6hIma|SWkhp}ot0N0MA=!d*eieyQfi;3mkGuF zQaAu(yR3H2P!4a4pKf*F{NVv@=jlWL^@GD#@C?Qx?%M=h#0D^)F67QzsH}*xqbv*ircA*TTP%tTWp%{{iR~+kVX~kPEtIgYdNhsTaYav&JbLL>VVdaGZN>Y);KpN zt?NAK%3Nf>KvZ~!R0!=F_#O7cJbUnznvFHI^1Ln!x>g^bd%`VRA9rulVjZO)4RD8- z7Xrl!c7&#%RR?!C#QGGXUdD>*_7u$>2y1?YAD*E5MKAkPc*#f)@w4N%o*GG9!Uidr zyLm=(r#Q~9i}pG)1;V%CmH8PA`NuB(v7p5W`5eCZz@uwbJK3=udg$n>Y}jKprK?nX z-yhiwmUOPo_fH0T&4D)~NJqQ%Zhl`fY=SCgZxb{?I&h*7cH{aoJF35RwTD~G@vX4h zw5+6bIp`J^wqS+jfmy01Fy+Lec)P_tDmnULIdJwj5ptbO4t^qv!#bK4klLrIm;S7M z{Ouo>jOezCLYt6bP&53WoQYmu5v`MB;Y+Rnh$0WBR#ixh4LrOeNYd^3Hr=r^II{<< z*tvV!wF%0!lI~BEP*5REZebQkb(%mj9N3Fs)B0R(d{vDMg(afmS}%Q!4Knslwl7Cm zXtA!lvM%|ReXceVut_PR?0A-fikIDwFtXMPpwkt?PCom~HcLQ8lEgPosQlBh(S8}> z9vp|0rLRK?TL6aYTH$Q&k7QJ}GJa3Z9i_VUg%B(<#S`cl6yk;F#SEzKE_s$_g7R>I zf7R)84GybrarUgFq#jEQX;0v3p&5)RB>p<9wLm7V1v1+X8gEaL#B^9k;|1=-@5Dlec?}mb*Qk&ocYm&l zKRm!DM_Cht4#KB^o~$2wms$K77iodtzkg33{m{!CP%?+%Zth4B#@mP01Oj4!!qs49 z_kkdd2)o{K2d3hmYdQ7H1xL9#FZ7I+tM{^yo!YA0#l>x>m7$IwUpZ7ud`e*WLr?|| z&&gk&Fo6#_l!%0RB(hk)uJNA-GeJGyezhaey2S`s<^o3)ZMZ{6Tu?Y{WK!zC8)KMGLi?pzHGlQi?C?qBv_KlY%TE$2&Dc>wx zoTe~G1c{&qcs!#s2{*4E$?&Y`)3j$j9qVt<^`~=_5S^RXPex+>>688}c!F~>AkEq>jq)esbX)-PBhp$b}DFSE?RX3s1xpF3p?66<-@!ZJ;e#D2GtQ zcM$1gfoMFn9MNqm#F}OhZ*3j(SY}z9L(1J#X70Gv*9wvDzJh5HYP#PF;~&di6j^ox zA;vW1*AM*jlX-}K#o#(ZxJjj+BXnf_7zatF?xJ6^`JsW z=Lz&4U)gBZRKJuR3tRxI}X_D?PJ>Wy%ejGrKw! zBv2{K4DJEk@%ZD!H*-+WCd7n_ojXCQS?T`>QuEl^hNzY=fq)mp4Ub z&+$aGC=KhEV~+>TFFbT6`n5-f&u9T7;P8XzZu~@Q{(QmEDvclu2=Gqs1+j!RkXCQ_ z@!!aWY!C>(@-|M1;SyZ~`+hB$rQ9D%G>8sN0n>`yJ3B~r50&c~tsL1)JUcB<=>4~3 z{AE2ic!#g$Mp%cp_%-9y)@N919&xwJ@F4LCQOlG4^{A*v37{0Itv&znEI`dcJ(egc}1VR9}1Xhvz%gx z!Bq6xc6D!-ERnMtA^Z(4;PB4I$g5l|zb@{Y3^*Mk2XB-9>4N+DxuUKZKrgk1;v`T- zkK%ODfCVVM$a{I0z7SFsBmz&NC4dpw|Tj+<6mH+Ec5}Wg>j)HGbmlpCa-8^cj(-A9XfCd#cgO>(6-?xYF0P6G_ zp5XGrvA0#-5sP92cAl$sXi`d7Xb zx(YD6Nqqz7`aT~*I%}wxeiW=q2@muD{ar(mXRx)OP%2W%BAOb=IE*&;O$7=pWCPUN zb8#|eY+ii&$gdaZ&!^{wJ4JT+(J`tU@V@-kON7%^I!=kSO-&7(FU=hB#Ud zkML-HU6ZDFbX=7OifC~}Bs9#={z!PxuZtf|*x1@#rr0J^j)e|^9{&@TKwt|tWqKPKsz`>O!>N=2}Y%sA&p8#^ow`?P0EP=2a2T zH@w~0b>-Qd?Y0EB*YI97YRXtyxbzRc`t=e74|F>Cww8q~t3;iT1fdIo;S>NO#m78= zkvn&6X%W zX1t8}7dzvuT+EG+Czvdss@$N&4XR%U;$Py8AHJUqK;vP(__ zFNJ53WmN?yCA(I|y`AT7v%6?>CvtQ;=8A$+W?;{KbD9z5v&=*7T?Ema7l)L>%RhkR zalCeIM~<%^(lWMtb&Z9X_Yu#}j?F!Gs3UYb7YArP%e>?dg z?oTbXry~qd!#`9~be4JPBhd8Y?#<{qaV=FfX6ufkvV*d z>P<6gkEdImob}j_XPf?dmem_W9m>=D(DLHuW6`iITgV)PF?(xRKo+3*?n$^|^lWCs z5UhX{SzGMY4{V^-?E?H#BTYElW}vtYlp#-Xu(f_B!T)+-jFKqU%Sg)2kX;5aZd&Ym zd2;vfV-8^M*Wr?J%n2WO3*o%;d9A`XBh*rr-;;7)JGEF|NfH32W#09lq(hkuVNz|s zr{OV&QhRYpSRylVPF+y-L`i!_K|&LO1>5kJ^s?EX^ns;N5s~}ubbNc;o_FcpVLtos z+0)T4%jIXaGmBGF!^|CQwQUtv-E4bKatIbS&CP8!{mun&PTIV7A8esuam%B@ z84S_L7gqr%8vOdD;c4Hrz0j|9#?PbX41p^+ZVYhRr%ms%Yv=p8cysRKy|?WOciz^3 z73bR}F9b@s55jJq13#W4mZgC4xKAaB@nKOz73ATn4{YrjUT=1RXy2s>on4;yW==XdpwELJWXoeIS-kz~vQUI;@#{(Wv$G&5@ko1= z+P4RNmu$t$TabIE*%~K=*vc-kKiK_H(!CcrsN8)GA_Lb@#z@)vu3D!h6z%GO!tGT; zN#i7`chCx|c_+^t)B}|X!bORgP`~lGucJ8b45dT~-y5BiUT004vmpqyc*e}rh)J^x zl)7ZsA-A`Mdmx^SMX=EDOSR^@zu%^P>V^O;x<}MxPz_&)D*+W#a8wZZ8-fEza zDArl6dLsSh5UWLegOry1VGKX!5*1%2gmSz2@Bv??+MA}>{_mJ%O}Ga}KkZysk*&TJ z9CawcZlS&b#fD*5VEO?K*{*1g3VkAG!tZMUa>a!wPv~X(Kr=J8BW5uI6XgY`io5&} z{I*v_B84Jc!Z;|mHH9giv|cIF?5%D#FC*rg{a7ue$+}IjJe~gJ6@VLroymDTEo8i8 zini47V^g>gOgL{9AM3kBcIxEy%k4>fnv370OWUbVl~!{2I34Z!Q_aPVY}1Ku6gD=_ zzDtBD?|Yp=7`o^&-@>lC%dTI3ci}SqPPl=z+~{*)yY=Z!Y}wR>E{v}B5PVd^-W*Yp zlVoOtLxsgSCucR|uXnPiEdBEt150ML8HJ{V)hIox*OJn zPH!~4K(MMhzQixAm&0EsWU%*z z@?LpHt8A|H^30IB3A4^s|D-cvq4~W}=6u;q8jjQN#xKshP3*;R-!%Pj@#cr9iz}s@ z-)ow82AbCInNHlwoOIFCa5ke$-&)$o>a6`(Rx_&C_2gm=P!g^te~WL9?JDfsKdO1J zDNgowL$kgW*?vNTUw+iz!yFGb**k6Ai_diN768r3JfBQkLbT~t=v@L^QGwhAn!)Z_Zcp69V~l^<9Rd_v@4Njh)2_Om{bOycL+d7b*Cr=+X{xk(U>N16;8^9tn$aXpA6(7_<09P>(gliY*kwV6+daK8oDE z05+em&k%;LJG?D2#Lk)*Vxm6Xh{Id8sjaVL$oiSmMXV(&^}JJcPWt>_-Y)$o%sH(; zy;t~vKHU3p>aXLUyH>gdUEAEtr}DVsI6STSp;@)17g|$jwnJc_6__WQ%4;Wd(PC(+|MnyJGEN5cJ*VBb?dj^Khqqb0Y|oSG1;9haFwn}X@qQRUYfip->6=?3CC5(=BXk;$Dy=vKA=)Sl6 zaM7D5#HX&_4`t__EEjg4u1AoO+L0w|=!22dW$oErw)m61^gmH%a7qw!$(QnT2pZPF6LYKPXVwjhf-NZJyW^`8+dV7a^e9*y| zO02nftsXtaH?r#vjMqMxkE&oT(Fh{@P~^h2z=u;`ZQGw&U}e3$WLRi5*cUlxlOdzA zmUpjfc(cy<#!L+$ZVuHsC+7~1{@jSa?@lRi4=m%WcDF}FtCzn)Ynh@skFY4MMk$FJ zx_LxHFB)+0e@xCzD<{TKJ6ve<%zwgIHbFoEvN(a=7y=%|3qGM+&4(V5%a?$60U!7A zsMqzkNn_$fTo(eo$#KoJ`Eoh|H=28VVTh~ocAQg}mUAtInI^z92j-^_gbW~A-ozlx zqq`a0cej}zzI*XVCFIFIY+T}OK)40u<6QmLnI%OG(54J8 z-nmN{m~(JfFGZfR`_RM0Rj5IowkGZCBRKV6s>m+-|7G|5=a-`4M3o{uaJx-zRW07v zzfUdQib5vI_{i|yRdnQ<$aJd#>S6=!qM@4rLM#UFuC#a>!UXL&la;R&zWXN_1;l1G zoV|Pgn9#RiR->!aE$HqP*msU}R_=lDJ@T)iHoKPB9;Tc~Zx36sDQDHX*ko$rDnC;R zGk7??7PPS~)e*gP&J9SkQlY54bm4J|@ORWBj7NAQp9xTzy_kqEX1C*0)O26kQ zb5Tj@vM!J-IeXprw)A!0x-Jvejj)vhj~VrwycP9RaGKpzipL{;Dcd##rO@PIyofYdeoo7_6JTCO65)$#1IY}49@|jdtT#!>=#o(ua?`kQaEsU)@HPjEaRRFi zZ->KGKIZckl_9JRHW{88WIe7pD+h;zLf%Ci*ZwO z$VGU6L^imYvZ|$p;#Jqg-JVJHuw4Ly-8@)s9lrH~m!i9Ic3CFwXEB|K*U#9Xmv(p0 z)V5${3@my*>~_bskyy4qth~1_&2e1u26AM(6`msQswsTI)+kyDz>^o~$fH%zl)%~^UP z89%=U+_AWbz?|mOSAhirjkbr!_kEM>;^Mi5SUr?0&|O{h)CQg&k}+f>@i~);=mc+# z1=PoHk&AJ`V7B3XRvOVRjtAEfrs}^`Ly!<+cqF6?7%LV4H`*T+n*i>_Vh1%YJ-h zVF|XI++SIH3BwXz+aW>J3hVBXCsZN(Yj3_Im#D4QcoIhg#O)@R>9j9Et;-#6&XY;M zeMk=P?}s1!j+8kDYZZXw4;!{zJT309qW9~QFOKC^2aSi7eA~Y8T@CIeqONXIHfp4- zSlM{MQ(G19MTJkty0^7hu_$i%z5LZVC}l*D68dpRgLkKW@x7F zjV8UWoCe;D3^%3M>*$h^M4xDba96d5KP%7MJK9&BKufqI4SZ8K53KrZ`($reEr8^Gw9O{0`NA zvg#COm1MqA5-%Qcv%_IrH41!RyyoGebx5KibT%{=T1nZQJfEeykCvxKmv4+foaXup zz7pANhDKK0mIz^N=t1t6Qax>;Khw$W&BeSDmUeFs68?M6PQZy6gH_svFchFRbq~{9X_fel=?0CPsQmU z$Dc9b{<|juXK*n%cUK)t<1-%3>=t{`z~{Txa4$LUzkQFcatR=yV;5Bd>80AwreOz9 zi^SL-rJ|_vjUyb8dQO|QeEMDyT&ZS+VKr2ygNGJ-)29RI-0<9vS`+dQxIupN6bv|vEKY3XYONcfo~AsYYuV+oaUfq zf~Z>wB~Rt~8%Wu;Llg2-+}jQ>*-1ayK^6T1dyO?8mG8AH`Hz-eI1fa*Y{N7+_BmG% zqFR%+`BmM8;iO?*%8{r#f`MCi#^Pl@F{YgG`|sE2DMD&Ik*E=&ljqEX@tA7N9(dq! zQ}m8C?4sVHgzbA=NG#=^G}vwhX%doP4zJN=x1Qyx(g1eFmzn!+{HkP?W^3@21on=p zVN{cOzWU~kKg)t0*V>tWnU}*}U5`~OC6nFFQ2fh>yX-v5B@Rz*9L8Dn3nMztC7+qHT@8lj!({8A6Xug4H>#}prAVg z|BI@M%Ivh(2d+j*+9zNA2YvAA50C}&bM{kI^ToKujYiV>5#{J)KlkTFgq60WYsnn$ z;dzp$Z`HI6pRMqi2MLEXjp@6#!wRc;xChmp&2=XTf2|oY2I!sFR&RBsat2%Br^s~4)nPm&k>i#z4 zD}QfF;de&dvFZsFJm`eU0;t7nw9(jM#eVeN@*xFqCCdX{L(o1Eo{_B``k|BGWD0L% zmIP5adXqV6Y@pbf-vN zA-mpnyweLO&(|gbzRf^)Ek7~nBEyW)+lMfmZQ@@`OlrOsF%kG=+k-{@Jx<+s&WLeo zhZEZ6e|>v3522dP86{sY8wsX85HSp8KLz6eE^n@r5`T!bP7fRvlZ~>;rl&5u!z;0U zPC-vDI;ohkDuLdB8IB zAz!W|bpG9NWl#}J(nuhH2-vof5R1&kXuL9q=KqLu3S8l_Yt@(PmtW+TRegh@zY{$Z zfZWrK*6l|LPka{I)CR=w_`Tl6>GNGmmaF3F#HiV+;%$M+Jh`5;ukf z=S0ng2X?bSp_S*x<|!r`kQ||T2$ig|orUyfECkZy^?U==!dX6;bO5@CiULr`X@b{e z43(etX24}?VV=0=Zr}NE3=wHz;DnmL`Grsb=vQ`5`0S zz7gs(?<-u`_RNG~IB!>dW)5j2##wj9xo*Xl6PTizL;*CClQE(#wtUkBAvAHD;Dk6< z`|gEg!+u-Yim4`n@QWY2I7_}Jh)h3vGgkR7b(&)Pt+jd84ws9&1n;KAnMuyG;Qg)8 z2UVDLD8V4iTDR`o%>mfp>|SU)ym0E_oZQCO@dIN#oZ_yGajpr^$h1E6=(G|vZ=9{z z*x(96Lpz>Wa;;%<)|eiA4r4F6G}5sFS})%ATTjkVU0_%FYZHt>CTdEorTrn4vCRwQ z!h!IoR-5d{TRW7Lxb^B7%>iMGIza*WOh-gcXf=49oj+veAp)kNh}}+e|Ld!R9$EhF zVQ~oT+b|Y<_s9tVyEhrT-}|AeIv5^?pYV`G@<_M)xenjDHQV9S4(j8rwuWl`F8Oz_ z_$RxHuw!zcIJFk`3EfGu=*+VzBnoQD``G)j{gc-53+25xoImHxI2%_w95-rf|Le&^ zZHmfYipKAYQ!wDPtLC7+xFgZUo~wc8O2{ivn(TOs6qYee5vu)swgX=S4%F)#Cy3ZZ ztf`TNmpz=Iqk{K2<&l8VnPSGhBz-*L8>-(0$v2BXcZIko&>)^_Z2xHS~M|{trgirJz z8tnobDt0%UO#Cl@c^I;c<~wa{mu&tExQEWs!x$J|7mdTSq}Rh{XjeWD|-4 zXsb%+=1%fj9}e*4G=VCY$Nl5!IuJteeheRx z$cr+ST(tHqPXnta=hwo$9CHAGZ1ya)>TBOybwSTRCV%m~wb|MJJ$H#*yT|P+B@WMz zIDY2V+QiYl5g{B6s+t(K_?Ok zk@Iu>-o}?|=Y2_BZ-!T*;4NFA6Lb|V8cO2R zzJhd^^PTPf`OpCB;nvZa;MCs;KfMxhuclX$wD6O($Yve&*#RxH*m0f!!|aq(46|%N znCL%{`)t(lORIeyCE1fpOK*K;lfE!0W%R%XoxyS)AYflRV=K>wORDw0-lfc;Bv)!wSsW9NnJ!;$OO!pYXaq8Ql_$xl*@;QgH zkgjjE^MmAwsz4`B-HjZbnk#=hEvfO)b>f{p=EQ_0PC>|~wE3i2CvMQ8i5&#jK8|7c zzin1ByTE`6Yg4z-I*OH&z?yH0$*}Si7cJi+6awomF;};7NS`kELFkMDcn?QgNovXR zn0q(gAhl>Ek5|S8)t-x7{GEl107>b*e1}4kR6ksH6N`~C=?e3p@A5iSFPsVHoa`$aI)7U+?6SYB~FXji~zkwAsXLE~)o|83BJ@pW* zxvmLiFS-RjXo#tE=Qh#_)9q_t5#biz?;+qkXLpai4@6_PZg7NP=$_6tOTFoP9RDFF zjA%H&qR<-0_l5P-l^DAWgH&aU>dBXGt_>5(HjTXgJ=)PqQU_6w*G9EN*uXuPFheD~HDY~t*?~5#lZX9_MD=SS zl6O#Xp>N54`Oo~DWs!1WqyEXhks{|kogT;e*7ZuK z_3SuC8rk`a+ziqUwuSD*bq~#%$G2wR#&xJd#3;DyVbn1+Hs*deYZ=$8x#XFF*k8~E zITTCOd-}?#(h*VO;T$ZqQHL=*^d53!Arb#Po0sE*r9NN|ew45Hl=aPSe}1ed+#IP& zcfJviD4#y9x{e|euOMQVX#OE0kNJwUmaK(wv8INTjrB2V-h0;0{{&{~NxBphm4 zGvGGz6;(ImR~IAwB7pi83D&0k$DOL^7=+I`H^BX~vbw1xUIAtGC;$P4KnGj-j=*13~K*gl`~s z2i(Q5UOlE}NjYJ<5b%mnp2VmP8Je?y+-z$PK~bQ#PghKDp8y@TL#*sp>eBsiS>PsE z8#a<2ayR;eD4)}F%s#)yH5nl{LKAQV+N{Z@{CAmy55}tyu)^^`EnIXO_sXGF8yva` ze?fKY0p17UlyNH1?(3_pDX?aDLWi~M3blh1j)@2+?{!4tSwm1Uov3+)E4~d>ISo0)7Xfxu+^`t!2|k~((6?65rR*lui_ePr2N(RSNIdohLp zNgT*NO>gq_t1&#V??ShqkR+L=rFPm9H=OmU0|$y_umQetNBDDMv;*3yg=~hH_7n>` z5|`nLq-gzUMDUXL0Bi)^1c-S04W&v0^Tx)xo&kbBKg1`LoCb1K(-d!!$!T# ze(o+&18LAAMAJ*`<0D`vJ>6ai!zjqp!>5&YVRD%%FGnNjLf?V9xcQYPGC9wIz8gTz zWfZk6VxN+6BZ_DRuo;(miB&+}PWQ={c*<;*nQrut3oeZ``5)qsdd-WcT&W<*;NL#- zF`!F3%Y$K*`!>1E@!kiA?J>nGsqv2zzm2>#7{l-Al=&kY3M?m6KM!e$A4NR^2VO%) z?DVjd1oPXGeF7Y@_QvPo7v}1g53$fv)>#z<~VRY!i~$ zu28QE-^*|3R-)7H-Hb>l>(6j*#;^2PGLXOxxh9EvXQf;=qyC-kBKb#FJiv3daAX#%-icu|Z>NXEj!2-}zJX;MF;G{p zR5t_!)T$Rr;F<8pSN~@^s4j@|Km3v3LmNxVo^)KuYy$hC-aU~70h8+2KRo@84sH%- z_I@&pyOL|YuI~;4I_!N`CU(4d>-Endy5Nl?KSaQGxde+NvKi5R4y*yoq$jOe$Ggey zWWZkwGdr?ss$@$}ob}y#lJr>i?e&ABy$6lyiy_vv{-(^|9=;{+cWExM?q>A6dV-LU zlSQ-eXNREG8uzOOf0)iQxuUYAf~xP8lwVtOjjO2ne&UT}^zbei7j_Vw>>3P4L6=BX z%{-!6k-gP^62nMlIc$Li)rE9|<|ejNU!3R|r?X3+zVO4E*>C3&CB+XF^N6g@Ybv?< zmoq8WX`9O|a6f>+@)TS&lmbRd*EH}Dqnz?he%+? z=0VU@Y!-viG^c%9SL(OT7WXwZ=bjDIIeaI~<)PG&3MxP0fPf@DiUu(3ZqY;*x^fqK zBOUD^YLy@bsF~ONam1mWvdL?-dEfd1NnocjQ6QqQ(Lc3Th1lUQMe#e2fL*nzkygk} z(2jZrNw%-Al6tFR346ZP;I6r9x|R0!p`;#o$=Y~-d75vMRA^3>Y9M&+U!d&IRNxlY zn&ng@%Q4~>+;SLo>J46{7x=@Xmk~E4&~>PqaL6(5v(lzDoV&+Qw@!N^?hO+&;R21b za0f(edK>OosRi0S$nn3nQpQr1O{uZ9oWby+#R!lo*x0*Y7r8bSlaONen(>9cAY~)I z96xGvj$6Zb{LrMn8^5E{Z|{6(Sm^VM9`h$PhwwA71)n9dX|cCIzL;k>eeUx0s;}CT zThHq6$4@7G8!zQJX>^-7A0hTm`s>vG+K#I?XZ#zaX9 zL@q5zo#erBpIRv-RO!?h-pCY2ngfu791%v800S~Z!gZOfR=})o1ag`=K@@m4I6|>h z4%A&{VW5x{Y@XAiu!%|(H3<`A$TJDK)qh@494?$2;27;1^a>ChrfDh_p0JI<@gBtf z0e^r?JN;9tJd^_0V?Nu&7xle9`=9lN%h`a32z_K6`#BsKp=;R}m)ES-Hf%(yny zDY<*3M(a=QlSVYM(ai`2jjsvm5rjQd@;}CU)&uL6UiUYE14tfd__s!oBYn-Yqdh$N9)L^k3vld3Lw4#mFUO8UhA_C&(`f&bRBXLE^po-dhemsgC`5PrwW%9oPw z;&!mn@MisNv!vEXP*>vYH#(m(%3F|DCnSd!I%}I|4{`o{wQ(v~7bxQp>fEJ1R)v5i zokl&y3<3q(ff~@z&z$_cW)f|82a7kZGaH&Ef?k+k^`D!yZb)W6j-Lx!%!=^8^)d3; zCq!I77`*@ZwbC>zE6(tfEWh2Sg(fv`c_#Z)lT;SR(j3evbaxidO5H-SH>YhozBivq zK$Bn8W4mPqW%-I17X}@G`yL;5g2gPF%1j5;-#3-1MhB23=O*-T#AeI!c^v{<#t5-?aA7JmEMc1i*Rb_)O`Ms?E$~>SpG~{T6MX!5&4_#{ zuUmiU8MTA$Gmmy3oue9P5%$N|T#;2@6NUk&+j83m&}k?G&ytt2b4&}_QG$2w2mWj{ z90SPcofnxtYTwWWqaB+xn|pwaGQRK&bWS{Y_q(*IH7u0B_zR*VP@onlsy+5E z;75BKMi6f|`PBY%)7r}VwPwN|*-z{A zq!Zv=L+=tJbF6MILDNK47)5b>+rrP3KGi~tG*#L)V-eF`UM7NikQsZz_|5RI z1UNF)mS52wi-CH@{wHN&TXq!eP5Gw$AS5^9dG4$S!b=KrBisAt3ZC5_5{7LCDY>-Q zL+(1ylr%2C=uKCRS*i`KaBeQ)y4P^*BLl87A;r&d+IcE)lc1AK5Am13?o&kR6{8-S z>m0Td)qVC+(X1qs3)#%0_e89em%?LYw>p<-Gar8hB&X=hg=+?Y0;TvgQ`)HTu_%3- zV{9ptUTFSa&h5kYn)L(*-2jFLPLQ7E9c5;`?jY>jA5WYFzl?-CEJ1|gLuX6L5`05M zTJ@rb3yeg!qv?d1f&?1@wzzzq5wG-uX#1iUU!cI76N&<@hO`56w5V$I2-R1h&m7C4Qd^PZ71@~cp=mE*nFMj!&%R8nN#C=(y& zrWR5fy)>SZu6v=?1o@W6Dh8V>dHf;hCuLn*$N3*-6Vov8H1qOxk=j*v9?QlfyXx{L z*?3cdLu7wPzdhl*h%JA5;AWR`>YPj&q z;*P6HZYcrY$5cMOW6GGh?J^Xa_5U5(cCglt$K4I+#Y9KKH|oHQQoNr!5&tue1Gd4xd#@huoRBWB|c+at1D=F;gU%G8X32?lTRJ8m1s zej?H3`(4OKBq-d*Mw__F0j_+Vs_1Nu0jE8t(TiJQku2As!!PI+#O*vYmWZbEn;qqj zo$An6! zRJiz}m#i{1U1bKyg^MoBZWP6*aa##RFIfb!butVA4JSn)+OwBZQvj3BsG*ME0LxW3 zIYNP4Ss(q)rcWl(2aG&1gH9KX*MHmiSog%Q_2XCIXw@roa+Pkep=V{Wd>L9Qqh%$c}LkqK-Hh6NnHugKOBp_c`S zjQHHLuhA@$4!qJJYpzeZ$v^s4@lwT|u*fl}FgchpY*;iKWQXtkFG~I=T)?t`)k)+J zocQXu$xSGcbDQaa@$k0KO;eD{W|LbZbJ%T|W&@97_$F21+sOn>2PR$4yV@R2hYVA3 zFHFJp?oAZ4l75^Y3XXu}p53O1WGAC$y~bXnTKt%c zW%kV21Lg@tu7joDG&~dWPQ9|pL-H{(PoEG+bZ4I?$}j($4H;udbRmEKP$}Vp=u?j2<9!-NHviMYV7T7m?0@DNUzYH)S;Qqi1yZ1 z2_T#ga}<)Euj?iG7@P*;1u610yQH^s(`o#-QMgAxI`BJ&>NY$(gIyQ99H2K-d@@Bv z(Eh~1lQ&fpmF|&Wjcd7dUw%98-DblyZZDm)%F%Tt^LjqC2Dq1!<~YiIe!ak64l+Uv zI$sz|ei}`NnN|xzMM-Y9Zz*2r^AXuR4(ikbttNPp&6hS<-Kd>9U(X9!s>_??-)=qy zj3r|No1|_Idb;F0bp@7YwdyDllr+p4C;KE`aUtvtL8l>~qWA)3H(9=yjVyk(ML#Wn z*GL5vgdI^tR?|a1&~pRSCLEJE2pf&}nk?Hg2`AK=XV%ODER%}HD7?v>a71>$4F%{D z>7`G0CM^_Z9B|T~*p^QkoNH*mk)*)6!C>^-@Wo}zlLjb}b~fh@%6V+JHNvB!nuYrT zsr;hy5553rrvI`W?ZLfUD5ZP&e zM8Wp*h;?iQjBoGT@#mOr(gLcm38I^QiFAZ>90k zD|=!u0M<&JVtULQCS^NKy*d(dqjhTR8oPd=#ys|{i_-DvXb0PkXFCfyWzbi%q0h$j z-Wqw+!C-wf)(FKzf$Re(H;vXnZ(|*9CO#__3YXpcWxv236nR8w0KbVRH>ncfNEsuM z0oW)SnVeP@PHN$EmEN4fEz=vVx)FJwI(qO_(>%Hhtxfb@oze_6p9c`F>m#GvNGJ;f zqK^@vc$sn{>})jgB&HrlW_pm!kaZT!S# zWy**I>PoXA>zK2z!jJWqL51FjNXSzz(OH^5vLw+{1>`yWyBL_Ufq5*IdSg5 zkf0N<)gD?Yo%4t%Q}U&@eNNqX&5BNN_a!6(rr1@pYFzREzM@tzeYr$y*h1Ggl9lY8ue|VkKVppWAE@|--8Ti$JzX>5VY*Dk|9Mzyxh}9GD zWHI|XGgZ7i{li2*<}T0rA8s%sg3}KSX-YhrQ2|6Q$1!N9`HeB?j4FeI&+hx~?yVDc z?i;mLUxqYX_gQtdKT80+p+fsv^dTGJ1YF$d*|ET>uZgxmbAj^gyrJc#Twf~_Wus+H z=ScO1;8(3h^vM=$hX{>`eyj;ey;TS;fjFS-iDO@ooqji7eK&>d7dr#WHu{Gveg=3d0`P;UC+)NGP>Vh zaC5zKHRQ(YFwkaT_PjJWcC-BCSLt>RCFO$GA8u@qCvKq&UiPdXxL5WM_1qqPO3j=$ z>nh_c@Jk27f*rU_6-SPDRzdl;BS;7W-$s92Pts6}Q}w(OqSq7_7s+o6^X4UI#(05J z0M#(v{8WpPEnz1Q=OoDTBz)jxVj4{}_l0{T`bs7RL|c<->uFQ44g=UfAyzkux5+|3 z1~iN7DtB`0>kxorWd&DqmE2YeoYl>bPBKLos zN0n~++;)$K9d1AY@(DhB2maq_?%$a-zdm<1Ve!y+DWw3T+Zf0~`UURDL_EdG8%a0M zl2P;K(4a(=tz|-tN~}Wpj1up!zYYtR$kgMCz_ojd|LWGU(5uUE8g7oZb5KVeDu37+ zW#DGm>q+_E=kK1@e!jqXPurl_{qra3zPWoa6#|&yeR($D)TMIvP8hTRo2{JBtv#rm z;8(Z~;fTvXl_LFxFjD4~>hr0mnqV?1nP?bvN}_7H@~~v)$;frR5Yv1HRufGQj8Sm0 zGp!VhW+4qReM+~DZL$Xqgdee-8#KcQ#liG+ak7ZxCS@u#&v?%7ZGuy0^|CeXWBIP2 z-iERxKRvotb_yk#E!a`U@TE<=^p$P)wpU5(7MM*?rKg=jPXM7FjR`HeQjC{j|H(!| z)-W*r9E(XFXazit0Go^Dc~tg$SkE&_vaC0@AV4gl(kdns*qH)E$q>jB%b=PhsS^W9 z>=O9rce;?}tut}DbtW0WJiPRmvcjgrTUqx;zW}3iTZK?*%X^|LzuGmqW4Pe>I~UQh zQRN4pTCJCyd{t}D-I=vi>FUllIL$lsT;&&Su~i7!mc$H_uWep8XF}8V@;4dLXb1b! zgg1@c9DBgzF^NDSF!K*C3iiK`E&^<%BJ`5T5#FaN_ zR+5!q??gnvo+A5*Wy6jUG0{L|70!5cGfdvg!k0Zab7JLOQ3{7KNa=0>)+-IPtZkTM z+IICUw3lGO!c5G((pDUCF@}r8i(BcsZVoFU)_ny=GTJ(BzaC9p5jD!of~Z`8oztyH zntYspXuL@bVn~K*72`P^#}k(w^F1|To9TJD2H#ckttgYkBJ#Pd27j8tM#w$|IZ-hDiVlzqrsfX2Ud}9l1h9) z<7P@7hPb|T=jIO72gZi9GG@9jG41cI#)V(L?wdv#JKz66LiU5*m@st4KUi;%NN;K9-Hq2j zBWR^k@Z!5i9r`!MNv4BUs;{8RH6dctT^(Jma)(M-w4>#@Flp0Xy}gErM4&%bbAWJ%mccCEGa8sNj-2O` z@Z39UUX7(PKjsJL7CCN1_N%tQ7g8glFAP|I6wc&oRc;ad8BEYV^sN1iagSZHfb8P6 z&4iNJ(&Iw%r#ED95uZ4BjUAPyek^=^i#f%3aEq~U#9mCqg~Q_)Z2o7&`{To?W(AJW$Y5=80#XRE3ysZN z-p4V8AXX+Lk7tZpu0|9sBfT#pB5;T#)5X3+^zuAQmYLz!FBPUvsKg&K(tTr{gT>km z7;rV`(?r_N$BRL|zldj>RGF(hr>Dj^k7d+E*9p544L`tbw4SUr-iAL3ahjW{3?pIyHg(6n@EHs^XSe{1Wp}7K)0wur7qXN@=`wT`}2s%yUitm3as?gjR zOzyhIt}rs5H&5@8B6iB9hY;V@v~D2cAduIBqx$?Z(4Gk%l(0;^>{M=7ssqBtJ8-+P zg$u@&bXTx;S!DZE6t0#GLqaIm+TxeNO4qly#&`RI;)n?@6)lUzBp0}Ony~r2XR46% zoKxzqPIna7dDi&-W?ILeXY2)5=@o?qn+jtXzM}NL*iwmInl|kjS!jGRQOStIi+WqE zvkczLC6I_GP+4&oIn*??k#T--e|KK+9qnj0SvqUNZRjZxojvaBO1uw=hB1h*P~)y3 zZlc4WrKP)xA2D@5r9l7G9SKMj%j%-hCgCm7{HADZ+j_jY&XM*rT<7o4iTGl}k^1BT z=5p0yiP+1Kjf;!i12t4Pm_*FRfQMNOF_X-Q=gP$AkgE~PcxD>Uzs{#Ql~@USp9m6L zfiOQy0_?<*&fYBuO)r<-8xOV~(5LV_m<>t!@4<^hd}>DHgheLw&Xj@2bCFPMM5;*K zV-M~@GpK(HA$io~6Rw~M)M8QCTmWJLN>)?-9)8^5R?g z5p5c7#7AzoV~9@z!fp2ENi>+XWH?yIRXU|A|M@dtp*8olJ!qMfT%zn4e`&uOZqob) zn-EyQfHSwwQ%H>9Tn=&xI%pga5ad3An|RHF*fD^(c)?ThO86gl^-QvYCt>GQsbve! z&-pbQeG*Tt*c4{qwk`uVu)M3`lK5|EjEdNdfXeIyZttGZM9;s9XliTUrZ$D)ErC~h zq%;QI2GOPNkMjN~X~dhhKngO(O2np%u9s}+u`S+q=akC5>di6eYTtkygMi@>p(Pwk zve+n1_Id&Atr|f$S02st3aWcxl*s79kCMW2gjVe559b-VAy5lInv>1>*pn?T5^LY6 zbH7Dh{a)nj!T&5;6)MSC=rKvFB4$W!(5_Q~Fwv)6wH+b4T4ws*NJm9?f_-6#W=%)G}nzmX*c zb<{cwi?tPADwj^?a;Z(cX%xR6dWeniI2&t-W|C>X@@>fn!q#Dg_gJcD;0`H4QY%2C z3t+QryQ>cIqIf~|8s8S(dl>?&yHlqDxcjjv?NHsI>#Y01UT_;4-H2YR7;)5ykw3h} z9g`!&oqeXeD{&nlqqO0mo{#THw{g+zdw}uX)pAB!?$$c(LjAFXg4M6Shp(Mv2h|-I zTMT$K)gfJXWE0b74cBxuH79?Xs|UPDBo)!M+gxCeI$`t~ES4BL#knzzR6Q?tK&Gaw z1UJuBo~L*5&=`SJ{OChgPL7@+;@4!qBj_I?;MXsWR0AlaW!AooOSsm^FlEaC70cjZ z0G41{{n;yxd(gu>G^r4o)8*_hupT_)Ufz7^xy{zaw;zry=pDC5r^9_q*RZrJ^Z|;g z95P7#i|5O79WPFnNcaQ7Nj-P7``3RcjRCykCm#xi5;fbfZZLDOrfL71vf&xen01j7!J)Ruj&8%WTWJXktUrN=pDR%bgF+M*ih;i~2GlUN zlfRcm9Tt&4r0|h43q|1jQb_%i1%|Ze#3||D{|4?p&a24ejO4kbU%GZQBT`GmRH#w}Mqp)k zDK4xkE0#v65B`aW|IY^&tUz-+U-WaX^Tp7a$Lq>B+1N0x>Go-hiFNQ38X@$o`rzd4 zbi-sow3b`#>A61sT6^U0oy!$(q%$?)-Fo1^w`qTF*j z+~SBEf@376u1*~*{Y>hAjRbz7p$c1+I}S_Kz;TvbOpHt9)h*4vqFT=K5Uq8Nh)q=K+!Q>aa#nY!N{|YCP>m!Iu5!@?U$*R!R{W)F@(0sjL zUC~Y}D0yszor$?2>4P=ozmIt|tg2Xg`qc&f|6ak)X)K;gHP_xMOS^xv=u9?n8g6># z`3Vgy%>$CT&2*%Y5VB6=Y)WT zPLmBEz|6o7oB%zIy1=>4So&yxBQfFbFM`Ip0-T#$BiMasv4Zf>9E53&eE41N*Z!Y1 z`$jRcGnyZE%W*YtQc;oT-IEgFg%`W0g#^6s*d58)x~kYKR?FpeFJrzm1~Nz6VXD(b zf34OZ7dk9T06&Jrd3|jX6kVUP2Bv&yBbYV!kGr{Zu%S-f8{si*$1?NFA!Vwd7k5Ok?C zX8P9&_`SZr_csYEl#L{#>H_R`6rIuhXuk^-3G=-hs?Yzk{#Iu~J!ss0Yr{BRf0z;% zC3xvY!=T^+`horu`106FugS)?=Ua(<}Y!}r_y z4e~jS9Pf~Se?Oo*SX5~g+Vy?2s=1k!Vz}SHus4n)?bnqZ7fk)^;%M@7exvQ>CtSyc zvL=t)7>wlNBs!X|d+7B^)6owaU+z)8%-|$eX#2h=Hs#Tc z;J(`qE}C>dpgvgSENm2dvt4lScf5@|Kwj9Pta>LMu<7H*sa@VuB&aA;l?Glf_6RPd zU;ZR7ZC~Fsw5XXS%Or^X7qbYCzG83rGABu{%5XbMKeJFH8y) z@B8mF8GdQXiK)!E^xP<4jXCzPqnTe23oFau=snk97W#L-8;-soWD!jsO?w(GHun2x9KA88LvMYz+!WQ*{Jnwx@buxBBZ3sT(ZkZ5YE0+(#`>Rek2QLI<4Ah-Nnr(3yrv1gH&?EcEzg=* zV3XW;Y5Cg=A@HV?ep6`DXuf;!cJ=b6IcoRd&cLM5hsLEt+50*!+5UbxMmb0`_-8n( zLrP#XPqwB7Rt%#cC&Q4>=Opiy9B6IQ)ApH@P|0IRJ)94?hk0gq63f^B%bxyZ)*FAb z&AseNnu7-ABd<5BQGVu|dlWyP_GsYQNUWx#PR+N z!(sGOzUt6QkLSIktbP2d#_7tFdi^?mN2f4Mvp(%A4|BgcTKlwje!KBamcTW@seaxA z>nd<9?u?Q4sbXCqlPtE2^}W5<*M210!oko(^z6%j3e_NDvz$Q9I;JCc67@L6`HftM z#Ex$xka^u4%h0Iu6fpc3X2aruC^jnU#O~weM!xEfoOK$^#kW7hb-$e=Mny^E{}Ey- zV2MO2+*opo9iL4b^lje0GJZ{Z-B8rw-kQT3)L%K>A1TC47DV#(Mz#Bv32+lETT{ev ze(uV(`OktjLLr^Z(B}CvQ*B4y*n7z|z5Vk!Wgeh(OE3^QY-dXX^+r|T03};RM<9S}i!%=)^ z#ENoJXE7M<;9!Vq=^IS?_cug-hXo&B#!|;nXel{_FZOy@{s^ylYuJd2r=C0RljQ$+ znASL072%MlManD&SR(g*wLlH=HDs6kpA_3aVaiUt!0(kGZ(q4V?_e$Z_I!+7Wk!YD zObLMjtJ(|wsDEGk5#|Wox%%;{t;RVPcI4SL-zKW|{6D5rk{qX+xD3sg9AGj9L%*P0 z-e$3^<3WMBkCtlLpO5h82X$lkyE(rOIZUsgW0C#2F2f(**Zn{1@&j+V)N}~q^C|j! zK2fo*ZOH`*#Fb4$Lu0C5A@~3NLL(Fw$l-Wyj6Aa=R~HQ||M^P$B0PSb-GBd6fr}#5 zUKBzCb|nj?n#OXGP-Rrct!1>dR0&P?=)d3U94!(cQVZWJ!iKq87ONq7kJ9ss!>@0r zj)OuRj}S9jd2o)c$cZ`A4SqMr2j7x1oLx%yE{rG=8wSo-gLn>?kCFTMB-mMy0 z3(}FQ5Ri7rKY7}Lx7bfjEpD=tl7Y4PY(f?&$r@+8C5+!OgHAk6{QI7d z2s$?N0%pjJBaXlz)K+8ALx5Z0Srq6#Qe^d3@)7r3HbmwLT&SCD^!G;^@&dpZ(d$(_ z|Bt=F;($j~@d!{prtw5EOs*-OzQP*H*uhd`d`a)~M*n&$7COXGfT*@WtX($H`R8`q zD}0Cbo6N(4jnQgt?)yC%1SsvG(X$1k&!7G(HYA90;^9|-zHI@(EeD$ZDqavW_YDd| zhV|QsLJKGm-HLf`KY41uACW~6kH2aj?r-!12AYk?VGZ}H6>S;Mq^BIdbt~};zqqG= zPu48BFw**gDS(M;`uS|Z=igBM@pmy|!B3d&J`WSysW(8<5*(?7C^hX@|^`tG}OHxdkgAEosSLi%@lywV*O&#W8DKBr09c$fQ+_x>v&u%yDpcZOS;y#bDQ6)0?iT)R7GRR6JwM3gP=oOdzm@GEB)eXpY}zhhfF8rcz3V(q$np+fGj zuk!nt1~Mo^^kpbdGd^cUF;d}q_xQ7mQo`IXjQ+e!BvH_ut3rBKVBNo>Y>9aI0A$9e zkPpJ#6|qKNuz)uJ%jGyM@?6BK{`U4t#*8l<{N}%39B8pX-^u|SMtaBKvfH0RP6)l2 z2aBrfLjsQ$3cLPYKSccE=l*@`v7qQU6t+qbr(82R5IuoHz~~Os^NUXrc|Q0cmRPAE z$Mb@Kn%C4T42L(_p$KZtco~rCpL~31H}+3CdQ|@-JSnSLRQ5r{^%56)iJ4G7nC6*B z87o$ir*Tf}{!T!Rp^|=4{ucaVEhS(++!oZuK6OrELMnYrq)G2{;dTfG- zGV+2}vj3!W3o&`VJWTAX1x(*m`kXQFEk(hF@_*KxbuGgeWGL?(ja6T2+_BCo&0jXF zmEawE_Pg=<_d;mS5s5a-2ZLY!eiTXrjwzNXg_Ddzdm-7X{Ofqt6#yN+g2M=Lof+)) zJ%C&bL9a({w*}1~#24127L*1r8~%p&z(c`6g0OLCZl-ZdX%UAAhBvGBp7(pscs?>s zWgp5>`TJx1@fl7Y?%y9onI#dg4%q(4ptQ%I>H+-#hrQM(sy_!aLsP>5894?phro@G zb$X2Xs(*jUY;n}6zjUehS`tc~)RwL)IYwkyaC6M>R$TpkvS5oqub~uaz}dk3hGyH| z)Oah6{B+klVD2-4fCCV}G&kq-91i1YA3xV;q&gmmATJQ?Ove#-fNzTf%!4l1IFL)O z1krQz^E@N{$Fap@bA}DRG*MFqUJG(<(ujeUDYV?ky}nL1PF@=>asv0;GNdB~avfXP zbTPNmPyDeaKX<=^FN(hH7*Ht!b{Pb@pNr9ST2W*Uh9d!-lSwpX$*z=nIfC)E0hZ>fE zS_7FYY%{$qmh|^Oq|IIYhvrb*{94%X<-TV%3CV?p9$|YIaQ|HWQB9Tv$#WU_=f#+EjrM6@fcmQ65rfKA@=>J)-(^y=i9Ny3s3avbK ze?j9z-rWipPQK@c$+-&;+kW4a3fc$=FqaYC%Hv9UEgsR?fE9ujvjq4?BbIpu;HM`J zp4zQuT4!vtmX~yJOSPmy3ah2`JO;x11$KoG$lWlW{aDlKBg{2hIRC(LAj^LY7$VD0 zWV{M=r<)Dxl<}YI7NuV*yx679qu&k^Bzw>}QyKo=9}(WDq!(ZT_d<5Pm6CU%yAd+1 z!-$O|Dv-f#Vuv+1Sy?*rP%1On& zI(Nk$Dj!62gn5}}k5g}~tnquSZ^swCKQ1GdaXe)THD1g#kvN<2E_+)5;kXZ$>Gz-` zRY_y+BW#b2?rJz(mfnbAFoG>KM%<@@l@Rd?k{8E~djjHa{R|H_n{X?y^_>{6u?}aH zaqo=je=rQq>g)48$z|`fW!`*A_q?BRq455tXNGS;W@GCWBR7V09=Bg#B-Kv*l>6oa zk{z)G;z7$mUT|;|w3G2xLx@!;ICaR*oNG8b^p*xikZCP~)m;Z;+PDsu)5w4_svl4G9AFzsyHTc#-@PGBG42E4HPT$Gz89pDw0Fb;vPY>gylFG7!T|o!VP+k>7f|Mw)8CK6;~)=Qr4cBV%JRQ%?lfXyzB*ywNW*`1 zFGl_&$$Xb}&C$Uy0h6RfC?pXHd)rrP4)zMQ8hi|3WMbj9Py$cr;2IP;8o_weI7BWO z`NaO|ul*OPXaSz>+H;%W9*&)-#oG-~v@+*6FOcvR0Ot)6I*&pOVHCmSw#r64p~3j? z%_~~;((+K@0~k&`9{CLE*u~0xizqa$6~}%FeW#I3|3k0mkig#=CKopa^23VlpeUBM z@9t&^==4XS$6*C;uJ!6w)3S{lNt|qfeR9l2C*A zSRf|4*#*z*+myU^xDQa z(l=U&wKz4wkj9)Xz2(*%g3n6Feh<;xHT|MJ{8~Xjl=%qFPwNnTEh;R*(x~)X%NM1^ z?hIY~(|9pdzbR;GVb? zB);xJ{#xT9^K2DVATX)!4i!cUSo~;MKqiw@50oI*#ce3lt^h#)!5i*U{7uFQT63yd z^5w2nthn}WHsNpWMgW!9gE8(F;yDRQPE!l6v&m4gR6)EN14BM5AVQN!6~b<~0y8o` zcmti!`A~f58)&oWh=5gMcTqH(*yaFH69dsq^_k{A@Ep>GoFO6XC#`iD76dNa>@rNv zDJK-Fdwsq3tGF~wrLzv@9rW8;om@o)=WC@|IkWLliKkybCVvHODURr|qy` zskk=372zh5?&2qdIFY=7=96m?LX%xW{k%_3BM=D0Ps;n;ODD3#u{@X#s*}nE3MfXS+$3GP4(;N1@ViLA;R7y{ zg1UQfFg!56(t5wTNiiAjbFYQ&Y&T3dcfH{z2u`IkX#Gr&HQ%V!eIPHp`!c)r3a_|n z>q?Hc)U8&QuW9w{9vqY|fDEN(Rc4Ec+UK73na>}b}eMBl)K>TSj(buJ7ewy*aV zPNJj&j*-Uw*jU;8yw#m5TzT5xZ~S8Y%dgKb^^nBdKUTmfYdjPgFK%)zG`3L#Qwy)g zqmMBkD*IxjcdtJ8{nq8_Qf6yVt4h2*KcHkH*qt27kDJb59E7A0b1bNdau(W|g+5UR zOb{Q(7*@tVFlE4&%pwbCO(*y+-9b!m^&GbBIM^V}rL(}nEup;Z<~GnrNcU`K0~gM2kcu$I_)>G>{vKWXPq7+-a<{ zBO&i_F|HKHR}hvM1H%wgqPTaohpZCZN4T|e%DK}JTeg(!EK<3hS9ja)(#yb(rY7ri zdAAQXUWggP2NUxC_`xW8iS)~-3P9dZY2boM+ikcF&a0oU(?Y||ySI=upM9V91$fN$ zf8GR*S*+Ev9&#HP=boeA;yt{snkbY&Dpy5ENK6S-rH3&1KUOb|MHuk_$NLX3Qhv^_ph^C1m=;iz90on<&DR%Sm%+$0}=n(cd)G{|4j-1;U85--j_oK?MuO5^a zWLcAyx*R^<@_NV^B#?FSp<7u6C(>W-K=Dwch4Am88E+7LSvZea89N zkMhw4M@m>Y%~sf3sEdDlb@D%x35oEW-Bmv^mwl#lsbw0@Ljk$-RN zOP;L8N6QS|)w4}J49+l%=;e8iSY$1Zv~Y*Tv{_Hi{jHd!`KUVn{I9X1P> z+duBApD`>p!*apvJe8dqF+q^YtSG;*_<@QNBNVgEt;oyQt$^l3crd$US-RYlKa*R) zg#^4oLf=rfns8(Nv!ROypFPxbrcRghXRk8;6(KKSku8wvb_DzH8)1E5rE2kS5B3rH zG0Q&o(&PC9iXgTD(uF=@I1yqPbPbXrmSA&xroh*ymT6r*7p(pH&5EJgt|Xay$DtiBV1`g=%{_j9;Ng z5&KwRsaoMR28r5~grn!0*RYEWOPaCkXQFb1_G2S9KZQ?e5M`DVl2mfyz3&m`xMVx}|~I8+KUs_)e-v0C`v;?*gIQd)>?JdQyUSXB_)t3k=F?cUdwsxpY# zip~Tf+P**5o@>Lz?WIEPQy0OIfqRZMHD&5j^Z-V-bWr#Kb(AbySwhtfypT0biqm(Q zlOCG-R6(NcdT6IZ8zw*0lQiEKK7gYrB}YhWbt2{wX{k7C@mV}ITd|?o9bD@d_|#kU zi+8r=Cb4%KrEr?48P@PAC!)+#2FMN<%55`dMYX<1ZJx-&ILgc$A|(Pem2T~8!uLBY zF3}qu8#gCm+!Y4%UL31Zw0{duJe3ofGFaQaXQX*fga)^lj19M0!j2n#sXJfRWku~! z+2nV<6gA|m)4AMd>tytAh7G`X_qv^!2%_#3xSSsz+UXhSi#!@XZQA?0= z?~Im*pjtyMR5@YpXYVC<@ctPf?u!|2F=7Rm2fk!_+`GhM{?S*1kJ5-D%f$F4a$UEQ zV_bh$ZMl(BTnDmn6T0U2e$T7lsM4yQym~>`?cMQb{2cLyxzh_=T~V9tVxkg~nbYc1 zVf{kSW@NLe>mz8co6$x+pjptIV>ha;Zc-s@C(gE;h;zeKZ5J8pxUEjUVpRN&FrJD8 zbK%ak$yA=mL|<7-*aNXCtrlkjS0!Mk6LyfaV6@(sCFD$)mA$^QPl6MZ&pbd@o_LO# zo4CDCJo|;kM|5I~ROkp%3+vgr;}Ut9dg6f(^maQ~aopMg@wIsfhQH1eYnk#Y^28&g zyPHvOoimHMGp(`hK7sQ)oycusJBAqETP0bNC;plt(WPNgQ3&1%mzSNrD2>o4z|Z-N zyuvcbYf6m&L^VKd*LbXFBMMswFN>^!e4i69iRZ`S01lM~L-PHA=+dOwj@X+@Y)Nal zmv<1`%5Mxig)Ga8pFT z+p$>tMUWrJoqr(|V!v}jxHTl=>><88a=~Q|(}^-L@x$abe=}pNieDw( z!WqxyPkCyWh_-kno$1Iq7RmP_KH(5j$LW2*6lMyWqzb&^EMJFv6Xhk`Ai6KNaaE4S zh?m7$ZYPj@!1B}+LswL>QnKdbW&T0w zosVr*eH)>=S&i?j)yn)@O=VKn&M7Cb3SJbWI$Dff)oD;WXcwgl>eQE(crv9Za;)D{ z5{t02uKUzx;8gOLQ;&Lu9OtDmFihBh`WRWPc|Qk9;P@^VmU3#QjD<(hjC&t-eDqT2 z@VNK+C@uS=K+j2-hWv@!T zEi^_HC{UvzahcUP(krGbDy23?gI}CD&L3ng())IQN2}hCS3B_aU7@pI__*pfxk|m% zu;DY{{e|j_K|#PqyxNqdfR#T=Bqqb3r?}GDl(BcXsLAJ0<^ms|a8AW>mB>iL24~g< z8Y&k5U3V>}ys`P&PjQ{PApvA$C`AiAJm&=>(-+YOV?NF^{5<}o9?PgiR`;Fk;Nv~g z-v+Y=#h4RPO=f~6>@f63+QQvldaqAEXu@STPTCu%VV<&|EeK|lkR$pQ81?lV#vRg7 z_hk_-$!PJBWxi00+v40k#utt~W-Q;aXfqOT=b-&ivokd>lv<7Od+%phYoR`e^Y@=% z*NMpxy$$t--Lu{IpSEFKMaaB&V%P?2vPld!7rz<>b zyEc8sbk|yWk?E!HI&CrY{j$}DA9QYU>8%>9%;tA3sp8gsnREzN_pupA+(VC9$0RI? zgsX0!#K{PDS3&s$17|6vasTmdgrH7fw4=gvJCIksVjU(btwpU3a693{9w8U8_x0 z$QGE*y+!bm=hpkCbZOJiI~h0wcG?l!9z5@szPR0O+=Cx_{z63i!-s}Z?7pLGM+5|R zUU%QI>N0eyE*HSDQSQ6g&m3T4+UZBL|mdtj;MGE75{d0NaN@us%4jU-b5ZB zS`OxyRrY6@nJcCAFA}y&lH4<#Dw)Epe^Ex;c1z2`MHYwByu5DfyktDNz{el2x=Wn% zSeY{qIP=;kusIm1e;)=GtRSvp=DlR+Wr4cmo8pwdZ5$lD(<3Qsk0WCg+l7#0fZP}+ z6jQnC+A-);+}7@q%mo3_|Hsx_hE=((-@}4*cb6cr=!QjiH%bapi}(wRhk7O`v`QlmSo?7cCaW zhsUa+sYt9tq*RIukh+LwH6zV9_ygY4zDQeJg;P^m9v8<(hsQu$E9i9~?++k?Z=_64 zGgWynuAbmZwss@~Lmc9cHwBNgPMqnj(;Vl)L(Uu{r~cy14w`Pd(=BF<*Qpk7ipK;m zSoAn)nstbqeI2Y9f}tZ68W32>I-|W5Q3?DP&cQ;4_wb$SAt52V`9LpfxbYeh_ko-y z-=8_2D|xZFvijwa7X=|X-mscfuc=g}8r2H!)JlUuG%TlGHyO`aF5YL3sd+=9kdWpi z280ePP%W~Im>FI?hrMcmRSr^^fAka)y%5)ZQV!2y`l=d=9z*KtjUu)-2)q9}$Tn^Y zzcUR@>tXoDS6=*|3*53|a=U+gxK;W;lY)1S~qqyVcFs3!FjE)-*sGq;8pR|xNBm_Is?CbIHe zNt}+=Ql4B6Z6FLX7{A680@077W)uPM<}3*Jy}CtB&gC9FT}2ZXu&<<4;yo76dRPsr zJG=uFDXlNl)Kh;xI13*xO;H=7mYzQ{M6Z2OpbNYf>j`P+7;Ih90Sm^_5~U4uCD%bT z!o<_P4(Do_Y115&3tN`as7>FH(Nk749OlLEw><8(-16?(7hzebli02@F*4dIKq|14 z)7F_^FR0Re)<9o%7l=4XC6SEk0JG9)U&dkPK&8e`0F$!MX`1T=gd*Wbvo)WG9<#Z) z)7a709rzNr8md|TzOQ0P(P#mzP=*yEMXiQqk~Ed*wjX6()|%g(;6?6nT+uKj8<_w3 z(Q`@vgnbaVNyYgrAWNL8y%bw55yODUh@*svH%PtBu_IDM8}*5};X&vteHascNVrYI zg}n$?ek=>&^@OF77R=D^^?q@tCje~DVbCN=@ZkTB-6L&LLEkGD9cViR%6n&T-y#o& z;Ki#W6^58U&hjRAaDN*%Q%JL*=?(~Hf>Pu;1h;uphDfhO9|1dyaug|oSf!y@s64=p zj5Lnsmoa_A4D7yXwKHS>>l#Pn>ePV7mQte=-g}UNF%UYX_1I;!IaTlu*`f>iVgMT! z*&0(aX-~a*yb_kTSGOb=KYS&G=_G&nvcodw``hF=Gm*h^`W&rH>k^yhd`s+)I=h39 zl=A48>u3|G~=iFcXPFu)s=!gOekF%J)V@?Eu@*DdeGEwC_Q$1x5Z*eXl z@WW(Cm}!wCo9(y7z5`F;!pt~~Ci@`6yzswr-EXCQ>w`~AfXZrN-u~SZTZl;;HdI4T z+&C}(OVz809%|n!K}ce@sk#&y2rlvibm!=F z($^L3VOEiGsbVXh-j*vi?P_ENpmh@uS>e6+wp9aS64Zu{gckj3U~{yk(>Q3&?V(!> zDc-xtUm$anhykNOGf6I!#6>1oLXQS8%*B9@W7i4C;|O)JCE?Vjr@{!>{Hxxj&hRtqFlngxAss~N3i zMxN1c+(bDb_iUqFel~niI0&Sjt0vW@66^XFH6ME;h(P{O6W$B{G?FSiUeAa!00QSX zJ^-llovZYVm@EfNJh|XKBX}CX7AB*=r#Ba>u@QX_T(NSaGH zJ<;-s!f^!j!w*H1p%u7?S0gzN(v9@l5c)qFH&i{Dd3^P0bJBmwAYLdR6R@gn|y7%cz;y` z#PATm+p+B1jKljF2H?i|c8jGnw!zWAzuJP^o-=1(o0`iIa8XDaTj%fk^@16(?+N!l zq};!Mo3ZOi05+*@+_ushweu4YH+=`aDCh&unr+b<)+XnM7uKv*%Z$^t}pMlZ3};9Ze>P>msCIgrY+R#bKZ6MbkUAb~H&0h52%F{1$0 zH$AlkZ0$=SG`0o&lCctH)6>&A!Kz9CH+Fvxe>2;3#&sAa-vrQoh4yFy zD@GYsKQRI8uY9<-k9E$x*qsg;w7-nfy@$!<#LV$BPhhH=n!H1Wi?zuYS&N%pVo} z&(8o^KF1KYpU;uHpgam&k&>iuRlVnD1{sY$EN3#8>D%x&jS$MG>+ZV)Ci3=eysqmV zRlmq`zlXhDi_N-Jns+ufuQ4>CxF*L*tg2n3$#|n`Y8|Br(8A)J09uxWgoGr^KwN1C zc2qZD1UWx7EcO-NA#umh; z3Rq?ZE1rY?b6+iIx4i6+$G{{m9q}NbG=A9RYiR@4VDpxA@Tm26i}R3l#Q;?(aPPi2 zI05oy#C>rv90VE#2+e16WM-BM?ETOYxP0woM+h@%V@!;F5!<~)k75Me?ahGNHp}KaFp=(TOM_~h_i1Bu*mYGND2w55Ix5dI@@|aGb5&?WJyzqtE)}OY%xf6T9^{= zctRcN>{Ris1j%i|5s?57KV&lN%b(l@bZ6}9PW#gwHOFl!u7eB=42&>8iA|Jli71^U zc3__j3rpk>E$V$Xm<&(m;O+o#`oVtVCszNCbGwh@^| zTa<BS>%Kq)F1d#7x zThwTo%GYkU_m@Ej6P(PiRx4|e2C-ceft*YGcg{6x$ISsnmx1-h#Ryp=89{X;w0+zK zxgcXJC>57L7`y;`m&k8ENqz16Lj$0=RVln2|LF7b{1|=I4>4v7uRvZwM z_XP6G-q(;~!06V+ssmR9A0OXm1C#%Iz^`b##U{XAU|-D=h-q(0n`DUkeclz<8pSDt z_D(3cbgozqEdVY%r-Wx3Nk)uk9+p#OQN(#OngrH>g29u#6v_OaIs10X?_sJGwP}f~ zST(F1Sa7+(&C%3?liamSx8AGo=O+$Bbo2vg9=mLBGLaO0PUkmVI*$CHc=-4X0cl51 zuOvIqwC3<(X1?Mi9)$Q~Aw@iE8Q!35Lc}0%zcgrcXsW`s$j=`Uu)vt_OX=WpDXq;g zgFqY(Mn6pN1b-?*NH*<`2O9iuOpI!f8k4h+JUY#m*qmIPcDK}mb)jY~e;&M~q`w4J zKGC)oymM24@*~HAA#M-O-C!>Xrg*He}=*OHv8#@aw5}#KYqvQgUuPe z=nZo7NsRru;QS+5U$kj1SQ4O}aq{gwls0El?bqNWRk+6o%`-Ce3=KtJ4xT?C_e8V4 zdCs4MkB7GmnBYf_se$7;;(B)xzEHQyS7lfVemDUXtCUYiPYIH$= z6tYJYA_+ug#E}T4Y|MaGB1L)RpOFr8#GA1pl1i?$@({rg zOB*(|z@eBHVr-VDbx#^I)Be(E!xKl>grlL#AETnL=K_s3ti=l6yLP)Dow`tQZQkxk z6+OirPsN`!h8w{_nr+oUy-#5}P6=(h+)bj_d8F^B?k%J61WdW=%HP@%J4$4QhuYJVaO4Wd} z|F)=2{aI3aI81;$l5wD%2HML0?xg;Lc&OmIL;@(zLBH#Nfn}n*=OkU&sm5CEmG&mbhWBWu zZf4qlelS=J3vOFPl8~ee;N5e`mY;V5>);*Ex79Bkf!xz2pAjc=3-Z02Te_Tkmmh>l z9<%LK9#nRttE;=Kz1ajNes6*pT0VzKPvX@60v;Dn#ZsL343crqk2jL-A1#5CjAQm% zON-Hs!cSZ_>--!F`1%l`z!1+FG<);MlJVzVice*?C0C;%$|ip;V8RK4ZQsiF6EUg+ zyvQ_Q#Sr3bmFz=`9FTh2U837xP_11<8N@d8Jt&SR43FoB05Sbt4~Qzi3eS0w8MkM? zh5$EYt?uSK$0R%?EiG-CM+q4CvVlX<+Ff=-MKgpU?vs9;Yk5e&-S>OC@!4ew>7k9!h z8RyS2b)muxegkx% zj>rl7!!SHVLFha3gJ5^8*c2q?&tDtd%7T^iSttYzEfVgx19{6=jww@Ux<%Rk8s(Gw zQo}<;e%%Mx0TW~at%;E~eL`tN@3=ss;>L!PkcG=rs_xSMWhEKOs zNn!zkF@Rp;A}MB!)MlXp|F=)-thS2_&*ujo^$gdpA1;-N`%)=&SLs-*bKLgBP$pTQR>BOp27K{0eKCC^2 zYs!JuGg%!2-~t0;+r-u^d<{??bP2RkWqjsLMY4Sst1RMf!k@HLHgKt0cq-DT@f1@Uj~oV-0dwck{<)Fgd*vD?l?aV$^O3GBP;TXAukC{ zck+z)1NRk>fK=Z^QFk1tHrNDqI0v~NE<`oV>(?FqAUrHoTuBq0dNas5eeC`$J!Xu{ zNZ18sgzZOg+En@4dqm2go9LwR2?_a+70LgA(QlECjk{AzcG=|H!@ww6L>XzaSAZQf z+FC!&?3S|(1OyAB6T8llOE*V=*EGDFokEa$tD%vH!G87mj!uwdMct@Xh#- zVU#!>j-bHd5fU;kc;)^R1gB{fz{1c?LV%Pr6?JMqW^L<7@P>m&iwSU#uPK~I`)9be zAFn6MeJ9u?RPG;v%2E45w`4-8Za{2pE7)a`rk|n z?_`S%a5^A37Baa%6MfhPe%_ovCEo zN1%3*{x(Q)2y9MS!$RVUBs1*12yVlV4u4y78 zWPL03P60(XYUqI6%r$F}zDi=*cc`)!q2?I=TK26p_o1Af-mfwNUFU3?09l6u*f5eH)j> ziojN;@}|5&)2z6D$x|-!f0F|u9ZEhoF3JrkCj;=VFV&JxX)Vt3M7g=SDTVtqs0`3R zJw2dU6V{9=fld>l!}UIqGm%zTV#q_Us;?6W!$oHfqN2N`ol07S6n{n9;OF=O3WDWC z0oQO5l=DRv{2phdZ8yov43ti`EQo)9PXu)K8PolD^hdV+KKwNVM!xsbN!|0ET)4{s9xQSZXExcD92B__t2Lsq(t%*Lwu#eP0F z3!KbHe^=@?%H;de3FFFEY+~f8`x^)Qc_dZ!_ly=1!NJQ73WS`jwzgur#9!!Ds4fp` zv9&b<>wZc}b$69MVI>kNwtQ5gY@TAeUbXPqyYVhtI`TT$a(1@&YTmoNYHo2!lIw?P zv{xd1##hJ2-c5=k2;0$q+=6(=wVa7civ%CXIXwoniYn+b=}Y_v(Cp%ciHzRv>RkSj z$-C2XJ5fGvBggV_m6>SvoXevvj8SC#q-`uaC+dmt>_sNm718sE6xb0{*l>B0$TA`& zl9SvC(E94qGwt%XnwX^-_44mrW)rziHs|>0vUG}CiSWWsjP=Udi7hzTLy zJs3RO%-y4K863TEIMVjB(#o~cD?|$u*A+^G8M(69#JH~iU8zwYlV!actz5gVXzH3K zY3sSXd?6G}xf+%lGea|nJ=6Fv>ah;z-A8?U7=MGCOqg#fYG9H&H`3;0i^n$~38cBC z_S8VnEFf1Wwle3p4M&kZwSxCCO&?_nE9uF7>V zkB!g6-(-3Y@9YbeICW7(4FjB!yFmbc$7z(6FcmDaxOi>FiUEYvCqjw&&9nhK7D!&2*6_?74Tb|H( zG(5Z$4fn1iV1Hmw9eIoBvKtpC@rPr==YOjYUEdyi%4@W8$#R zNNzzranZXeBN2yZ$%-jh^2SM>tN3wNgzN{`g$u2oSEF0Eol6g2^5=%L)#nR+d8_k% zFR#4HOY7|)7B3PVl zBo@k*)jSDK%wzIe8TC@R1eDMlHKjS**lZuuVY`nJl!N9b?eFi_(O6B@n!3Ym5#SxY zTP+L`ap#jI#3F}#V$8T0p1tJL3(FSq(fi@lbiYr!bRCKlt@vMDM_8+tjb?kL+scEN z3N<(ENcis#d*w~8E$AQU0ANHuKBIpcc@b)72yHXA3saHFNbKniX}J9btUpSU^S|L# z`LeYI?P$=1AztBlk_o^&dj;LGvb0q5pcWW*aH70hDX-3FbKk5_jWb~e+R`M=b3z$e zA72%9#D#%SMg)_eWMt$`sg$N7?>!Wfo%1^|7Q9na#>6-KCp3Z1o1QXKFm(vE)<62r zv=AnX6e^X+L~gJE>d9}!q95n%-WHU1E+OK4>X~OA!rnXqpQNB*+0g-DQd&PkPF6IG2(+H1g|++YWVv#m;( zEtUQGM#4-0)yBtftG6M}_|n*qldS&|m=3rG!6YD4B)e~VUq#Z>6-j@ZGiciDH2%i^oE^x0J}J3b|{ zlriM0zQV4b+FXV)qF26MLlXkkgtVy1SNprLEr+pj(LYC5O_+7-uuvl-*~=@`gmrFw zi78NAb+!MKi9+L^J#7{|(-|sQ@8F|U0R0^OKH}YD>;#!8)!a1>!E}9quN~`U5xG8j zajzBJxlcoBcT>?-5Q9N?X+D(o6;2ngdE`=H_({||zHs|%Qd#Anq$0bIXfDSnw#;rH^J*Z>RitE(_>I2o5ahzv4Ny() z60w65A|A*}C<9^<$!D+q74CfW^hqr|PI6rqn>->HBr$~xZ2IjtV0^9z^=14aYY z(m=y4rJ_^vNiq*^4W`bKhCp8eOkm5q6C!bI3mzskDXn1{j31 zho7kadh)8ucgQ^GQz=f-CLI+WK~{-nIZ>R7IXQXw;bB*Fk6eFvY*+OBH{*R93JlORb|Jwe7jY-cj&I;F%&zu}ip)D`p@&E}Wg{{{^3;%4kCi9W!mbU{gpuM!D39*RC#`NCHBGI zRKDqfp3&}W_ac=G0Y+)*5UcXhXy7J1$2q3QI;&Op|_0Qx)s>^*{spG98I_6YSN>oDT*3&}8O6Umn zg;_&l2gxyW0{&mWH;sh9ivH6v=2On4@(ON<;o3>SEdZNGe9M>=Z?qI}kpDNFnf!u-XzRLh=mk7AgTAPK^4Ka&^iCI_c@gcGj?^pN(@r%R{U6%vH0Zbw7Pd z%}NPtn%6H-`B<#${{6OdzF2Q_j@JA8%92Ul6nr^ z*2*8JznDtBG6GxyFHT3k!I7S~w=e&`6JkigVXdg{;((9As--(gM$T8E0Q%RxzqkvO zflWC!|DYveNN{wmWF%)HE8!<#@fuOqFG5(cMxB9bj5NWf*`|f)$xnc8IBS>HATyRi z`1U<=`?x+}?g0-doEr3wEJW{!n=fn1W0GDdh;}0d7~ZcEUhitRlzJ*!RQ{e;ET!wR z1i0A=U9fSs zMC{OS@XSISJ6`m8PL$#sQYB^OaA6-3j$&1s@1-b?!2I10C)&w*U%|-DfsXsUyc~rX z^m%bz$^YCRyQF7*uT|1{m6JX~?zd${+pn6he!Q`D9k(5VQ<0HDxE}6Ww#oj@LVt)R zc9B&O`1f01<4ngM0F)8$A_2Hoj0#m3_%{(nV~7^y)qj2IXnR;y;S0RS6UrwJ=AZ&D zRdI1~omrBDnEi!DzMSXkB|gRM8vrTqRFbZodLepMKePhO+pDday-oL61oo0sy?7yB zFaB^|EZPako+q{d$8SyQDuB>O?vOmD3`pR;=fsMzZU!S2UY zIyW1DXmIxm*bw@si;FIeO07K*_`OUCDnt=R zS5lby=*Zt=3GtXr5aTRK<7JTy6|XQw*$&rAe|p5=xc;<8)r!1QC_OKRxxfb=-cR3B zHX~8`Rpname@gZD4|aXYAY0#9r{bfReHiIFP3BBD368DY*8)Z&kX3)HTY)td29$_{ zi8FvXO5Iw!R2x8;+;&|6p3}>ZcZHCVI>BL1sy`onEnEy4@Xp-V6%ve<;o+3Lc`5Sg zrzw0Yk)cs6n%T_ffASqW1)vwOagbGqg9NSdrhXL=6x1w4PR874+kV|e=HTo5Xyi&W zhZF#VtS00-Bz%=qU0uE8B6`!Sx(aNLO?Qxx0l->!6dx#jWcR+Sp!MGF@ou`k$y~Ef zNrj$zW@>mAI_YqgQ{j{cv&dp2M+gg!X^_AAc!A#~zQ9FoY|GGjPtd}kn~&cEl3TX- z)r#u8nLd5$!yTzCRZ&+JP3pt-oM@*hUTo*jl0D3k5!1B{($cpd)KxK+F8GWZpxBez zzHzC-bL_OuxSx=P*=c{a;gg4bEV7*6RtRo%N7hFrfT=R?NZ=#4vCq^I{Wv6`%OjsD=T)Oe2tgdKX$f|iHNd|40|QIn>@)6tfLbRNuyRPHEY4W}7rMQsR*TZ31vGQ4 z(3tWz^fSvmtioW^rLNjAkD+h>&Vc+~RD^y2;3*M6SP6Do4=*ii6LPh-W(2J03lww! z&Ldm;Wy?_#7ObS4zY3(~@uK_$aNb-6wjx^E*~z?qop}40UIxj2y5H*F2!1e%kMw6I zQV4aqE+ohQmZG4j?z95?ol-RR`BYi1%cc^vKkYdn)NmME9kiiHZ?Am2MLm7sKY#$R zlj9>WuPo??M^=2|4By^FMtcGH`W+QNq|c(}QZ^{Bf#>fv(zbH?3Y(>l=Io)|N(>CGy9M&pFG<6S zMOZFsa)gI9hL{S}V?`O&}X5Mb_+1n}TMJy9D*7Z;5CQR~L`i<#hc zQ9*07uP_;t)-z<}<6#)9FAcHv`eJT;!?P&k0%KJaU$8&wO+u(X(C&c4)QqUQ|{o^8anJQOX9*$;Mm7Q!vXuXA{#kFMMX zQ{xg|*zO5trIRU7Z$2~Kem7Su8W5Z9_@&F%bIOgMtisK;-K^FR zM4dlkXhN-YkK@sc<1X^(=pGp*+0@Xzvy1os0{Z#gl=ls+$y-0<-mt~aZ#M>@tf`oO zG)x>^WiXT%Ms|=sr<8$U!uG_0s$yJ6k4zRoB)Mh5ZIPp@=pAjp$n z^dmyfw(>0(h0@U3Ra7a7e>auiG$xqWTNB8k77iQ?O*L4<7oG!cT zQ!+VfMq%9lJ)6I(se8coLKkTZ{_DQA^*cwP7%xAV4!9c1mK|&Iuw-Hk^g1!A+v-PV zCd+4!lECmylXd$xf}_U{4D$b)NFyQf-!xDCm~L$QP7ek{x@pJe+o9WUmb81>{=ny z!HxuS6^syjMq|?NF;=R7YPo+aVT9igYz1m*ZP$f(cV!CfmjpX(pbUb^wws@P&%eCc z!ms?8Sqw&6f4v^k1Ct}boRAF#=Ngz?pD_)7ebtdonAF-eMEmYku{N;zf8 zT|spF0?C1*l&a!h-bH#DwO<2FJFQcvWn>XQV313kK0frQDzx`UqkS=~K}qMc5z{cq z!(lsjJNRXc{cj}uJ3IlOk(~fJqsxkx?2gA*n4nRV@$Mc>(T#Z`snnLJJ|nu5_)kUf zUmrgpLP87B_6WH`P&N`ChwcooPDPSwix; zQcTREQ@o4ITSrA11ffr#TGx9QZDrcOhM9aHRLS{HP*i1s?Quel^XnIuwn0qEcU~z$ zvhbLwSBkJ9rW_pMYeyU$rLV~iLhq5K0mg+w4e{S^~lNkfaw>IR-NBnIi_# ztftnvdpg>LvzaQ~UP6`#!#1341jNYNHq7%0^c`HbBtkPY*6LGQ3Mg2lf~T~Q8bu27 z$GYK4)kZ994(*(&x7|r1#lk-JCq5T%vG~}UQnsZV$#<7(EXT})c4Wwz=N6^+1ITrV z+>oO*%1k<)=#!b97z^neJ+DjfWn*>KXFdl1`YtuDY#7mSpX8vb5@z8<(x1ZC;rR$V zs;3t}G7>PiHQ3p(YSKSAB)eE`6&?{mJhm|wy8JqY?ti2YqiCEG8J{RvGq=g| z^N9==2E{^gVtud;$qdL77XN((e_jyKN2cZgwmJkq1MKbXWp#ClRkHYlYF!W7A9t;* zm;6L+fTNM*m@bfiglED)RO*iFfUd#;yt$eNEFR(KPGI;}D2nj8)@L{3LrZ%^MkZrM zh5(N}t(W=@!5MX6NLM!v4+nNcWu?MP^9>W;j`mKI9i}L}NGhg87s*ccMBA`gLR~)x zIDJ;a43%OWD_%an{M7LW-`qH;v-6sv#3#Z@$#&q9 ze|?)&WhfO~tF$kNC~c&_EhLvB`a`YmleF3W{L+w2E^+sYD%K_w#@dnR2y0lEwv(|S z-h0OuC^l0I%HGDAobQvWoahY&Z`n@Qt)_5l){(j$goTBUyEawLi4L}SP-b~LNgnLW zgCDzU=D=nEqq_OpOqalUpUC9$po2T?`Pf%28@(Eos|6RrQ94yElUMaJvbT`LhkpTx ze?D@n5prTa+0gmpXUPSl^!EqeNJ8O=n!Udy@K8wqXONOG0^Sjft|(&Qpd4Q9_~gXO zP@~&gPy)SUNj>qFsmXG~kw~4^*ITt}6Pxahz=*-O6B89=!YF%{rr|A~_>TDa+rRpP zSlBQx17X3N{Q>k$iY%q~X8QBT{PYWTFk`(5;X+PuCzRg))gMWKZo$Y}2H`_O0yZUO zc`)VXdk0xkTEZ|WO%t5EFvm8xdF`C0hr$83Ol_rW@@J^P$ofgnh>c9~3|b>#9g}$r z9MB49*NsOOo`y0h z94xSBTM9*@T#>!i!%8g{P@4RbuleMY&c)cy8_dZC`dzEzpX+QxQ2UY_CJsP!1a;8f z;Jy?k5WiVhFAgf>2g23c0+VS}f_4r!7$uhrcEitNCerX9$_=}Bb*m~oPE7CyKZe{l z3H|KqQjqUEeycG0@qff7G>!npx&nwPv*t{2(Tl~opH?EU*g*4X;O(}GrYFPrKQf4f z5diM|KAgx^4wN^n2F=k+O~FKMZu;0OirCxWYk+KwNdH8?%~2j~f2A3imaCEL!$JKTedCdaAf zR>V|Xd4aVUUoyJ4dFcklP1hMIXcoo`83hFdhG%DIx40)~M*}Y>wWe`#miv4BeP+2g zxHtO;L(^gV)*?WdrMnHW!&o4zT6#j{YrKf7Ha_9Tp@rl==xRyCxUS6J5w17<6tDU0%=ctURalt`c zKJAqlP$dYSG3A|%&Cjb7pD%46D{5KL|7y4X1Lpm~Rez_fS`{GgJg^rGZ+L3r$7b>e z5iWTkHty{j`CS`>`Rw38*79<79`A~A=>)tqwb~oJ_^7Xry4PbdlmO_n`U^9}0+Lgf z3j?sYmWTUNiWc;WZA?5koGX$6H}So_K!Gvwgr?fB}3t(59x_{p{%1&oh&0y^wu!xqZsyFSj_aX+)X zayNRute_kc5m?zIRJX&OoQXbct0Z`aK2qZ_Ryndk!vLG#L8K@=`l-)6DB{S)t)t^g z?~SqbyP&OchMHmV;f{B*sCCt?QBxctrk*Q22YU$SP~C3~9#9R(X2etW@m%w^N5pqXIM{0#k zIX+n8zW@TGL|jX@mdN0yo&2Vh(f=A0u0ta0cHH2Vnc@)K@2HtWuFRHtxk`DAxhlZ> zBKA9)#{Y#Sfmqqa34ndWjbxc zezbsk7Vtb=#E;^{%na1?tNqIt=AYeN)U3Q(Ne64AjkK2GP`!#&Dc5ZffW)eZxhFM=;e!I6<+|5^njGy1Z%)$#^=SQKwu+Y^GcUMSY@d{Sl z$WBz5FKZK zaOd}>+V99yaIJaWx~+X?HT$G!cv>ZPWL3+V|1RxuMn@$K^vTdVjL z$;mHHkB!$|p+?`kgOr)HmIHv733Sj-FK{h7)SYq_`2KoixEW$QPY*ByTZ1ND9ex4w zXOVPZbmHc}A8kN{;xZM+C2}_%Ye+8XjikF=M0cdR5LEDe^8ct>ez#&3KtN5S1U631 zjEx12GHD{cdk;t$1tM;g6|i{ zg3`u{Y5ZonHE}+yB9r4yI(#ZA(^3SE!sg_pVjvxHu03S&H1$=nr!-GQgfZbrs)C|D z;2C;>(({2qKLHEY7im~C+6?63v)#Gl6c80uu0pR5C8?TA+S3svEXHM_!2Bpo0j<-o zsMjxjS;)WwVD|cTJ591MW7Sq~Pw=I+C20xr<0H%T^#Mxd@UkK5WMY|Brj|od5tVsh zAl$}IM#_{XkAxI^X84)&n{+*9Ev7G8OnS<6)i4$12B>#kF~>^Thb+>48tG(xSjb|M zBI5k6jIB^zMT6B3M`QBuAIx+I8w7Ngd~nqTm)btw@9A)@2}DK->(mX$r0N`5ldQB! z66`Nnbl!Y~=r?d6$Ar8a`3B{h7iP`LMMgF=ldE^fCfywD3`*zCbpTeUm_w*O=7}Ny zDLrVET4!b=77Tr0RnnD_d!*!e+YzN){}B(TBJa0R(2{v!456Q8(RUr5#uo>h#;u)1 za2OF6{y%a0_i;Lk0b$n{!^F*vkA##|-Dwl;t^18xlc8qFCCeM5H;n{xs@kxr>46&u zDw%=x1#s$!nAC^oR(L9zkuzy&a!PVy65dTt3mgJRYBn8(9p;i27WCF{-l&g_29mN8 z+Nl-1dJQ+U+Id{jWF{U^8>&y#3Brp{Tk?LzA3sn%Lk0WI(SZkZ1*_U2dW*Rnla)7J zndM+%!Ft8RW^dbn>_97z)54lD!^&#A_m@T#m#_f~p43O3)Ay*EU3F?{QhZ<7v(_lv z#7|y(2@cPe&Ue-g>nb%yr|s^o7{|z@qmKZcUZvi9BVL*j6ZP^F0#p+kYAizRT)<5r zw?Ft%bC(#xyQ_ScAC3RGqwg>oet4P zRhz@2$L1WaGF9e%QY1BT2l`JxW;VitK6Ykn528fWAbjev@ z<-5*u5h%i>G8(PU+3B^17Q~D}TbPz$jh{@Vn1k`-Hk=&xYt^_Z<1fXs{Lzjl$HI~M z0s=-rF0H92o-Cr1nw(;?s0=TnyU409MkEM(KH}(TEgv4CuIR0w!6-@Er%~)7Q zBpfSAQ3*Y<$k%?L?}8XO)_T;rRI;MlB2X(!m~`TblCIhocKmm4U6kt8eo)rgsM?ZHbUnPcANHhb_0Jjk}BvUwBnL}CXjXd=9VTz?Aj1h zSkTI2^v* z1M$l_DQR2p2g#*!dQ(}z%}uR$W+=Pngnqwb?5p^#ewM z%H<-8$Cb4$2g821ip=uxd!!7z!8YPKH0Yon+SKYsI74G#u&`H!%_+o2?;BiHRHWK# zo$!K!f}BQLrax6J5hH9faLfOaOW-5(S0bs|#(TjEg9YTu@qYVWFh-YiG@_HMg5f?tq>4#)&`*YskAU zGyJKH`F2mSy71Vh33R`umfP+MmwmHvem|ICH z)EW)%w&ZMX?IbxB+PE?t)%`rI`?=TA=-Nq6dY+6xO#Q;PBiN|8F{KkWt`n9^QH}0p zYv#w&jPLWzdkVE2D5Ui->0t5VL)=vmq?ELoSuwi9FifF@doD!zbE!^5d;7ulh42Io zQ9QiVdATs^7Z(-0+^wVIa6mcFY|cf^KoAwDtzse*#_>pjiyLGax!8J$={;UUbz}n2 zdIk-_p-n>E0|3bZ%udhyHm1NIGz40{OI4{{cJ1)ew`Ea#^?a|Zk5AET9+{2k3;H}+1>8({Zl)kWwrLX>mql5H=bK2eb0jU zvI03h(ZNP|60@%C3)TN>SOH$a4uCzm$S4IkXKZ*gKn!h9LU+urueI~n#DPSg@x_vnc?x-$k0vm z*Mejvc{vuluj?!ZU)xz8c18t^zxEGI!ICB_I(16@Zm(^|XF8ZAtz^qWO+$l7>xt?T zz4CU63vHE*mX;*+0mS>G3~Iaq;bb@={G#PfO|udasSzc}h*Gv~S!ZI>gz6U?bMZ(< zh^Xx?G!F#elVhQ%*wBa#hEHU>wvsL7gOVsDH@e_HTn(^HfX+Ln;o%$w=8xO#lY5+9 zSM$uGGYc_DRm3CaRa2V%kkjUm1K~9~Sf(}9-?XPa5*kw{B9R1QF9f31hw-A_`@Kql zYJ!x6RDEeWTybEaZhAB@Yao4P_FLzhZ(OvrO|kEcg*jlkyPV_A#2RhbGr=%t5o^3q`JIn5-C_ICKacy1P>m zr5g?{l82J+5(T6s4qYOhN=bkF;5g&F^S;0DpXc%#Wq6*oSKRAfYp=C_E}l!XmGC9) zStj6RjXIt&GNAUQL9+RtW9t))h#G=~M;EtEIDq&j#z(vRYMCKgB|F{X1h-_R+uPyM z(UjO9G)$uJvB#%>b^j1Zd(~a<^J;j>RL*EBQ=wQ!JKe>?0bj=w{4Q3;sm$*jj-=}PIvAV z1Z6VT#hAOYpUJpB2&O-RSL2w@GCciKJBql<_4AMniVIXqbbi1(OrDQyN`{Vy^6`hD zJ}ZTslbiA|xt2btd-YkOWK=%1WX&{0LN|dVewHgaC<}T|R&!A3U1k}fdWo(WMD-?| zknq`T!|g3aFGH)k$km0Og|_b*9pQPj)fOTSmIp?=bv9Gp)kG>eDAJ#(_@lVFlihBW z8YwdCdGk`Lt0cT}|4d<5!~AdraW}V-B9Mn{OXD31{*14PL$16E8V5mC;O_hAs-Lz) zt%~NO+o^G-Aw3vz?>dlth`IqiY2by(9R3enA28XIaHc)GGU7&JI9P6WKxi`TKFj|J$DvrtQY`p~!f@l~5x%8(0FCm*G44PM8028n^C( zfMm?Pq-K0Cf?Om#{p<_rn4Wr2u@qIHQQOrL%SaOM0fyIKN@M5=z|8YRuchnp%sQ`X z%S{jCI>?F_X5{a}dS9;9@yDvGWzLw0;rJEz$c^D(&-L}76B3~YyWM{Q{B6dM*N^jN zIAFs>_HWv5>3+Powl-{-;}*JIJN-^loSKJD@{tnlfB`d)T5ZU;!?7`q4<9~+*3@e} zxK^U7I;U*T0AKj>l-HfZ15xM?_C6y4ZDyUQvHEIHdvp{tQ#XGkRN86-@gOPlu_=n_nAe~*a!4HGZ0LvYQd(e7+^#Ztmli1i=5$z{ZY>`I24QNZ_Wx1P;4JWLbhnr%O)+}Z9 zbq_g3s2-{0GS0Wz@l)06u=1rUI89iYZEuJ>dkYn-Lf*8lifgOhB#)s(by6UEtX`qy zE-9NUnI@`^>?l_;%~d9lkd(N~L3ed;Ciu{;0mttae>kl7Rn}V#Xx6AwsDhDN!LcUG zRabUSh_uoD6}+*rsZd#7o4KhlvK5{3tHmtZb1>m)rh7Q5#id2K83L25LoJw8ZW7Rj zmkd|43#dyh7c6Ch)xUN*zbqK0JsCsfq;xW49vXP8+xM&q`iB)*)to4h(&f6Vx=yjS zY@r-%^MY&UMSQC%5#6^fKU0bjr`3pOsg6>g^xU>e5+Y0Y{z}l3%4s?lSY!0nDca`G zGkHi@10m%wQkQtb6N;(e^5S-Dkwj-4aF9f+%X)U)Mur(!IezxvN{@2fFdrt=d1XD1%`r zl=^MV4>@(~t_>aSzT)2z&OF@ypc}IOZn00TCv9Hb#ifJ@hQa4M^P(+?Wz6#tktgGK zrG#poq=5`7612$P@~fsdPaJ8{0W8pc*)P?Hk2D} zByWo-jG}$M6miBrJ9{(h!Ti|l7u$|g4JgWg_dud6fa|!r#%*D@@xy*Y$d_`mShsCF z>pmZq*NrV&*#`0Y`Z%V@qf>YBrc(~(aEi7}7$-YDy;R&N8E!xj$d6L$?NEt(d-GiR z2Doi0?JmwxC?YPsPL0>?8aD#=T!nmE5qeBc(|$Et#<)ohaq;x}TY*MSBnupA=uqYm zS%c+$IHOLZ3vQf}Ql5;0Bd9g5BVbq@;#Q>eaOz{Uc6r<0^Gs zAXU#Fbn)v{$lgxvs(C6WlfZ#pj`k=Wcj?s3+CLvqRtrG}LKXN&6!c1Sf`QK60`|*v zq=SQkuY#9u$mJDZotcdBn{9@LeqSY<`|&l`z{X1QtLL_Xy*T=oei?c-F|mQ3!CmEX z-@iHGC)6n*1RGp3OYmRJk|ekP^jJ|!`wAZ-bV+G?^xH(O)Xpoy2;w(p4R}iJzXk;T zUV;Osa2-hpqZI2j1{VpqJaaW?2$z)16r{)8a$cW?-NwS} zvLwtc8>goRY`V8s+|)*f=iX<_=9yVb6m>i==C<_fpu&7`A8=r8(sMuT=f>FYZ_Gx# z@IHA5sBLDj+)MQuOAyhO!;!(kfc6}^SWrCovS#52^F$YR(}U>Q@Lz==)CFK*M|3ce zTY{{{CL^!Mb^gSO#j&>G9y@ktDDbI*#=+{U?RC*Qp?Jpa>Erk@3{df$5YlJDp4jX` z2h>XgtW&i$c=+ChxaB4_k+4<&kJtH9S_EvhcM5WgY9ie+C#tfLrip?*2=8ur8R0k&naSd^k%bx}&t9Goj4IN-R_1&Q#D+qA6GcUQ&-XeeAvTJ+cFdq;uVMlwfq&CrFA(;R}R*j>GtynHxp^;(4?jH z4ms=j=f6~T#%QTzfkHVx~u%|QjLsk!%Asu3Jd1m4Yt ziZq(EVvXL5U9x`c>A-q}`1x131(ZT0Tp&lWgH-rL^CmG#_#FeAR}Y}hNXfNC5{(`2 zJQr)iA8!Tl?(Xwv6Hth;@*1gIavkl->3ZcLv6eH{(bp(pS$gT zktn~U_9v6-i%!=7rlKx|r}6n;cpRH=G}vG1r8>D~1)46$$MwKMXUv=eb%Uen?Z_Hi zDibLw8WCa2)z#G}ZzlU6U=c)yMPIo)jUq1UGNjq!*|S)nuH>*qzE)QLxy+1!ygR=Jw+pZ&AG6AwD~sZe!NA^*q>oY*zV2oq6|s zgEeuXdKbZd{j7nC&aKvTc`tygh?>?NzfGXq? zVd7J@`<^cQ8k)-D)Peihe29`m{(W&t#zV@XK%94iXI#p7j5n8AFTc~wwfE({mcsl`5& zUU@ZfVcO%8-f{YZqfl$=^}eNU224vL5UW1?{`|2()Ua?6 zri0lnQ))V)`6{{h{0({kbdEJ($7E;wG8TKj9i@ra8o|>iba#K%Rs;!Z0+_sw85QS; z-R?{zl6Om5slG4uwBJtLXm{%iz6m5+mRD6?(Izf929(dr(nuO`N7>=FCx(u-amRY8)qtVyKly_WM5MtpUc*#pl$*JD=d_oXugPf z3zy+{8-N7%pm+2jl1fX9+f)s?{$O=Xv`=a~wc?V(hkQD%GX0cRsz6i5Yc`xFU-z(5 zi&u9#@7rezhp|+Tiz`7shn~KR3UzWUmQ9S@Rh<`Mys=YLg|c53oPCs|l~t4r86&vR zZ-}D!6JcD7#4Vx^m>V0=QZ#vvf_9C1j?nDs^K+k#O}68Zq+#^lMBp zQKqa6mjHvb3cY+Z7&3&XXb$9JOnVDcTO;lCI;e)^S5`u50|UFdJ}GUcJhG_U;&-N_ zlgYsz7ggirLgi2~E-ZKq%a?Td+DYFr-xmF-4jvDKLvv(cSgEj0_Ik{2xf-ht4fX6Y z%BrdgioE!uOdV8h&YOv)YMfS{u^e^cyU}-?^t6IpHY(N?*^VqtJ2Bw3J0z9Y$rwD9 zq73mVRb^yD;^knOOlrldQ?U$QoOk_@GO<%YpCG%lH{WOpoxvBU;p4dh-+O)e7sVKL zkByeRVO@Rub~VjeC>R>8rM4?%cM3`qsV{%@ACFw(og|&FN$SD_&_t_LlK6jOV!*e2l%5FP@A0h!POQL7GX9GIntQ$EZ?T}frD^O#>9%pK~joQ zoP6SMh>7ns8;1yU`ZR1cZ1OM_%8Fg8z?{yt4ex#9&68awn`Z7-_Uf3yyFgfeEssbv z3MxAa!WNk>$Rl1(x{}sFs!`Ay$gc?vs@AH zR0bZ=S|pT-HU4aWl(@{`c}_)@MRePnZwu|_Ju9ER-&6F&0Nu^uIpi-wK`oY!wWhH3MyDV-5qfsH+D$tehSZ5FkuWE8TEA_=Z9L)T2ka_!Sc0C;O`RGpmfY8 zkBv+`WmTfA2Jep=!1G|E;SiGw2&Aj3S=@h;<7S0HkqQ5IZd09FNj%Hw^0xejm)|Cy zrss9#Jz9H`n%mN45!ifIr6w-E(yf0Sy_B8vJ?!P>_qAl;To>PG4={S(6gqVSX)(`G zFnBB$z734=Sd+B~eBOs$V@4P<@wtQ*KZ@zDz4{NMLfV*@M$7UQXtUd?Jux@8xwUTU z_j@!WO%ByQ-k z3ng1pM>?*BAN3fui4y>KbeHX&ia^o8n8+S}(dhAA5q;Z~IdS=l03-bo^+x+2p|}4f zBtcQ6kPa`Fec?U*iezVJ5J7_gep0shA#|GiM~lnasAcbP$zq?OK@AMB@$u9%ZbBW%d=!tfV`m%Q+md{3j-iF)&9t&XG>J8-1!Y$$X!=seFCM z8JWJSt7gmtHA*@1H`LnYwpInzK>iBHe!G$TEGm=BO%EphwT?ti3W=#t4!jS|=TDEm z^Ah)({j`tk(SG&t2m*4lEQ|%7%l~wR@o7fDLR|aINc|NLHhvLD)MP6)yPk%yp&HKZ zS4=>J{}fQmGKQD1s0-NT2gk!h^sSgd6w+B?n@sXIGMPjVf zfw%}3D*5-ck$gx9DmQo@8}&v>yUJ`BQKaU_Y>Z$=gGPh?W9N;oUWkWDj>S?RWO7-g zL_ww1azlgR;lOTsO0lS>T6~3ZNNh6G;&Od}kqKqFsVoCS^!S?Vhiju%@h$ccTW0|kSJcpGv!LSY&?jCJ;_=u}4<~r1O={5^Kt}{j_3G=`;M}{dn9L!Hw|YbG=w)daRUDP66>pxwElX!%bpip<6!g?hdD0t_YHNX##>Iev{D0Vq!uZ!=ipY z%gqTwm@Vj?gF{6-8X9Wx(OF;jsgQGsK^VyOUDc+#?vhiW-CLp4sTOD`hpz+ zE0P^8afRHUtRLMkA69ir5l~O!Rm8?AhewT9TSYI}`bIe}&{b}C#c+D0?7D4pJ$8)cN&eb{Z}$j1W?l(D2UWEg^S3cLu)D=no{O_B=KR zUnfA8W>-Tm!5OTHecXwXLCyOo&uT`xMZwY4kzZAPOoaE9I6a2=8?bY~D+ z+S&0W>a=BNC%Pk@U0qpXK{~A*<+$17eGU^`fUl{lA~}lNO0eFg8%Gq!_3Dt3F^MFn zlVh%Pn|g%`*IU5|=@f>+ZPNz%=ilxj-_q@ksBZ!A0=w@eOgb;Wlu_xmFrwr53Dv51 zV~O`fP%tT$mxO-ld!rbxPa%@MPyg)(lF@-1AR#1p0}86cbtYl_@yt;H&$IndEOD)C zYl~4dJ?cyp6En<}l+^sJe(cOsR=2BC@7BjhVp&n_~b8Flc`srd{eNp|L zx`kyzuSr6>Z)9|P#~NI-oJ)v9c~sXmRZ20g^%7@Y$MtVgqXO`X3z4jewBV+D1BFWq z{_I5LCr_!4yM}{?1xpYkYIaty7f_UI8@x8^Cu z;S`POe;)NMlP}!*Efc8`GOlbxZkS?rGGSTw#fUc@MtFO`~ZkKzuA=H@5 zKZ3ioS(`wHv1C!)R9v#oGriQVw~GBQtG%(Ji41r=Dx0R?3|E^kwCh$fiL$~mfrHXT zEn6{TjQlqJLev%wz0-pzdT6yGT(`DXDp#;UfLdli617i4ebQ^IgIXpX!(~0ihk=P{S%djfpo@_) zHaQ_T`q%@)pK8GY8Br^WCM5Fo#pb($>WY1XdcEAl$G)@*YFc3U9ZI2DtGvm;P%H|0 z@+AFaCy6LINvD;4*Q?&^(vwkrHVh2udRI#?>DS7Zmc%2&S*B@TgO)iR zqL*6Lpg1>#gjDXccQ_1@=R}I`VxBNFdIFB7p)&6yY0f66V@lyCwMupsXJ&D+oeP{D zSR6F-w-dPxoo>wlR1aZvIyiiF`z{R}q3Hyde8}t1U}f^n8*}cySWoV*BU{PItDgP&Ge20zt);Azoppb-DqO4x_D;jHpu)GgfN*@KQQ6=Pw5pbzvmN3L z+M!g9-bPzk5`P}f5)s<%d8+bE`0^zv?+r8_-)d#Y*Sz`CA9+sCuv7~su!CVN4812D zad$bwYuAFQEITbhjrgWESBvSeQLM$_PMg0n?P|I$|&@nuG z7>NRN6`TzHu7ict7B7f%C3Z*%g#1=s^okjGPjYS_F;kZP!tqp)dYTy;bYw(XDJnL3 z9Xk@D`Xnq2+tPMaJXhrnPqOesZQa42x_b-7pGG1O8^-01;*lf!(}gOqJT3lC^xlw; zFTTX9#!H-9^$oz4R_c%bAo7AD?|4~+*kR7^UPm~@?rCJ1@cEc! zZb!@SajV4@!^QGY+Mx6b|6Dyan3PYAL4hCsk)bb$Hj)1~Vf_@FTOH8W88m2wNO9@v zYEnWZHDjdvG1$l}_}C9cGdHLGB0_ZkI2$qb3~70KjE{20rD~OU)6$&f!dQG? z-@(IRa3d_4l_Bnw7r!6n&$mmFMY=fjPIB;i?C70+i=17Jjq=DBQ!jk;<_~9QXU4oD zh>LTj#d5#;NvdntBS#Zp|Hnl2j8VilpOEod{6G|8PnU}MkBl&mmA0+tcKjpoJu|xo zz;M>PG0M%`cVdi4Y=|}9a;w=fOEB1MCiMLmhvk2hTGXWuMbo8fBSOdoLM_1dNOOo@ zQSI5YjMK9-Ob7YCyzR1J?8T+U{H!LuIECCK61MnD&()tN!uohF6zT9_#kIAXQW2C8 zANSfaY;4u~XZ{o0jp}{qRHy4ul|W`*b$=M_&VDN<_5)V6((#GtpLy{w@mvoO4P;dH z+9(pIMM&vx_jc^Vsa`1A;nh@-p*}m;jv%OLi`6;OmV-$e#_a333z-w$tDA%vWZI-9A0 zz)p0Vks^dk-17P{h~syN-8kr)Z~JQ(IS4 zIFsm-?A@|<$^2r4HV%%Pd+%|+_xGvo&op{heHH&*FL&hpC2>#5M%n}&H-pylia!IL z+#uBDP|fXZ_?OgLFp)ZSSCqtnF)}-wfO@yp_C}7^RU`%oH9>qqmJY)2_C51>1PI{qYU9<)e&$VEwv>p!rPZQ|18q1s z);#m$6a>!urH_y)mGR{UzDey?!fnK)!7q*_0jc!K%BT6RBR$5BI`R9 zYHCVvrWyp}hDQqqS5=3;d>n*Bz+L`a+_-PooxyK9)0=Pn_;I4byS^(|PHBOAG;bQc z)6h_7QsY>L6SZu~1cpaw#IEpCX!KyOGzjFw!1xk$++<8u9n( z{`!+2DTtQ>x_(xZJgf6T#I-i5@vORVFz;r(=ZJFbTBQ42=8v^Vq~sP4H)l&&#>W|x zAO0c5)~IR?wB9_L%K_Sa@_hma{L9TjcDrA10Y-z}pmy92CZu*Op>M2Jd={KTjvp>R z#C7N_r}*o4|7{O`q)0!?B6{$g>Ve@jKZ|yioV2twW&H;Lj$F*WY@Y$kYh1#}&Yq~V zOz1K+1e;SshU25}ef%i>R&pPyJANpzQC5n-&+26o3M$88@dNPi7@Qo((aFFG$Lx?a z`!MeM1pnVJ&~gK~Nl7rNTd-ZO^({K`dmmxT%EraTye+d|P;K_A)sn|31Kjn%fY0G# zB`L_jC$f$HvX+*o;G~ykh(RRKQ}hsU^iOt*0aXfR^)z>SoqvO>YuA;)@uGLWTzT7D z(FX%|<1<7W7iaEiQ!Mi~)5+|cVPztUCZK~z5Zg@+2LU#y9L-WxakDw{9t&k5|CdP| z(?66n3RfpfE~q`LPb~j0I!Q%{{Lr2tO4l6z2S|_BtD~$}OyPNu$93;SS)&JDfR}riQ)Q(ora|y;Ei?nj0&s zBWC=ip??`Q$eDbQHUL3hURqlL2)#;*Qt9hUT&+5{QbHoa<39vyazP%bW4q;Y2Wgc) zf-+1@ao{p>^o|`QHwXR+y|ahi#p?fW2C2+93ZDTAtZ;73fhFkLFR$_&PdaxUsd_i5 zEv+ljzzA?*c&B`F#n;o_xLZ`dS3f*=#6m4=wO?ZO2Fi-S%py``D1j?)%``G%;X;g+ zqwmPOF|)`AzgltC*Yo_N8U;3M6!EFb;Q360VfLs(kpJKC#jWJhIw*cx2R)i>h4?6i zX9$Fu>))mUB0IMgv6zx&T07dRJjxpPgPn^(QW`CN)ytC?1a(L|s}j2G>TE4ZomF zg|QOwg(1yMgfebqWI|md?@I>tW<-ceTgs!sqh;C8pU<|sE!iHnP9xM{C@@NQ@v1$i zM(52qJpqcV;eYw5xkg|xQ}r(3vA$Z+sGD5?j&i?F&!k)CzrP?dyw>9Jl9-mFQRLZG~^P76aqf)Ve!>bI|-_yOA>8~trw0@zIc3i;_}QFdCZbO)^W2&Xn$WX?FG|(}S)0L3|%-@6*zm+W9-P$s(MRf0-BG z@}_r$&sX`rDb&BQ@ur;O#{ZOI)21v;6WUwff7Me z^-|BRU%zAL;bru`fsEed@J5!;gaw0%?jdpb=h|+0tjxQQ|9a8>xT!Z zCl5BuF4ok8C+Z-i0KC7r%_-<&z*JCBgrZrB70JyF9H;BFgkO)5y45xO4GlkLW+vJB z4m9W|Rce9FfKdd(;^O>_@nBb_b>%ZWT|m80mNm-p{foP&8G8@8|F2h-X@q5HsGIem zcm7$5`8@+cL0eYvLmAIUgBBGjdpDi}25kXmdb83fs83N=<+Q?l*(Teg7FbY(?wwgO zjcSzfmCeaGyF#?_hoF4>O%set%;*9v>ezU`H;okBr;prO&!;vehVE!)SIn>H5Rr2G zFSkKSheU)pAggIi6MMs3&Yg`F4l82pjgR}22mgo1_jhCy^$SHAul2>g-8ulG4q|)% zz9=Fr6u`iAD%M{zM!#Wq>5M#(P$9Sa;Qv-!KU1K%MmVzl9`|mC9pbzTG;SV^WMQt4 z0?hE?ZX3qm?rRHRWe|*!hrO3G({547I%KS7)}u=C_GcCSH%9{O+pQSbpbADOKYvyZ z-8c~9>_P;S!>$R7X2laMPE(H!88uZ1Lvw~GEy#~8&6V1K)38K50T@NVn~}^M)c7$HKo80rVS@;(k`I&^tk$IW8f+<1>j_j6ktVuvljk= zHhl#;S;b(#rrIl`K!RG9mhc5k5n*IxR8|u83pO-zcIqR4l)w^WXn584tZ$zJD>8MR zc<%g{06~Qc=}u^nC!UrzHtE$XLU~&|$2g5oy#2qh3e*E3K!9%usSEO++UTXp;8Cd= zn=aF%mVFR!!n$!w$KM8&J`2HOVwCYhO~8khV~+s(-~pqu{j-cBD_ihIkq}{}_ivD^C`#+82=jWsZf|mn~ zjH2MTPbBf2CMg*EEqYoAV(Nkt_3WYioMLPM#;%g2%_stVg4oW@EUVKx!N!4*-^@A# zm)IVnf|`l7lhb8{??JQ{6_pj~G6{WuWwpBMu|C1{zX92<&OVQtk>a&5`GFUX+&8yE z{t6{P{luQkEhgwASgNNCdsjL{&PyrX=KSw+3FHJI6*2+5avB=6x3|oCmbJNqN*!vF z6VI%b^#aBz(%C69W_s%ZLgDdO(;V<*}u_}*a&K(t%Yz&;N zyu3@qT2U#zw7fM@`Q39*X`IJqc($aj=YL~4%<}5hB%jA-%;I;SyL)b3vWmYfMwl8X z1ttlM;hvx0=uhO-WAzp>!Du~cf^qvEuk~Q`Zoj&rS3?IY^Phg_76`p1?(UE{2e6_~ z+ANPTCK|BQ6dD^Rb9}t92UwA~w^%5U9_$Qxv?_i*R=HKy$yO19nVq;~6;9s_ zY3c6ok-5ENr55GU7@W#g2Qi|N(EIqsAP9|LmkaI->Wt*)TX3LqIEGS8{zBs?Y(96v zowVc0Y*P3C9fj*X9XstG$CZvJZEk4~Q2h>JKpoB8Jm1jBs3=MxwGTBJ6}1fYZMG56 z@QhgyFBOQXIWK6;!mTH>z?Q$L)m5!3r+h*oH-RTe{CQCOECUIBv|W590?T&4tAZLa zURHMg_=^sc-stwwRV4mHMdc{b<^LPJT<5-weo9D(=p{$l z$w?==B!<(kN+8;j3*Z&d|5aNQIuR6PDifxqs+O}^Tgw<0Jox5g2w*&ZxG^vn{!+06 ze397Mw-H^oLv)Sy;~)Pwwi{0Xx5~{Rw?Od-Fn`fsYkhBwCmh+~{dR)sBxdI3pSQtE z?Z)%t^@&=?Ts%s_yo?NL+WYrcCM-)vbX}*jBO@bY=GsGVznz%Sl8}^ygMlm%_pid!EeS!!F+jG->z;;gU1vju?DGn?xd-duXSd*%`+`RK1=Xh#a z*wp(JZ1-3Lr!%7Hd#rMHe%M^ySG$kU-UoY5QXhu*^(mYk_4^_$OB!?JlX>z1nslk3 zzO$Pt5mIQWR;)9=Ft)I;0G31+#Kztd<_iV(8(u#tqLkD(bi}>JD3DZrq8o_dgS5~5(;W-$F&w# zhjQ05Ls-j}2q`GMyX>dIUiafoTVKmYmz9CLVRyJ?wi^%Ah$A`A!0cReP}4>1I(D;E zccyIH@p+^yj2A~u?tsg901K3Z!~_j$G@^|CF$e0be) z1?qd$t?$%^%d4^61SXPCG`N=|$MjNA4S}^rfkbFfx?9d*H%mZ(-9wDe39GP z0(-;-R|SdoJOSHNSVFdto9?59FSPeG;tb|DBXa%?AM9*ObqW_itdM)J+i4@62-1xK zZq@q z=+*^QN{b3Sbky~?wBB;sf4Kt=?%6}6V<(~Z{9zzbteu-Jo50A<{`ok9K+(z=uphnM zD$?GKjHwFTurhdon)K_}X?!~ET(L+?@pS%Af-VOQ#&F@eK}CJGH9*D&5K~w|d*Uxj z$p0<_65Dml_-$+mk(x&l-_nL>tHqT*3{3UT-TM{mfuR6yZpwW*6>$)eBXsmN=J7|UIeX}QIcZr1vZAGIdQ z;*P~w4&HUJ+SB9F=Bg$uGzFlz5sLgBR;fS6`+X1-GlN`2=$zWDF19$J+p0Z`tms*y zxozWqJTcFS6X*Pc@{c*@IgAt4P5VVe3hdg?TrfK2GORKtR?(m*huhTw)+RIa^Yb0m z*Ut7d>O@FIezfB6HEw%vzfcKXrilQJ--Z=N?F_P}dn{jD zU89iD)mxh~H*fB_G5{Nb2!6=*M`>|O zB31xi{8WL`d%Q;G-2d9eh zh{%TXu24C*srt2zA)>C%&H-dRVM}gFgJ~ZkghY89m*jxyt;hC<=RY*5de7xwxuqSI z)HGEqDYl^D)+jCU!iHgbW#?SmPuNgzQJ`Hdw}dW=LHIAVZ1Z%swlX6tu}vr zAX41pV=o`c9yf6SrFr@k&KrR9qAfV#flb?v35lA(<6uSi6i2}R%;r@vf4xet?&AC; z!nS&B2pt4bFWAGRqtr^Q9%qO+=dvq)q&HZ{tyN_;&QL$z=viHP5^ru&Aj|o3s~3a^ zZ*PZQ4_An@z;?rKA-2`D_94pn#fk4l|Ab6Mu1S@cklmbLB}Go@CMYqzZR!iz1*x@v zD}b-hfN*DGyap7+1mVfCpjC#`Kncvd*Tkp~6_I3xv@HIKT z*79?mK!?=6XVn&7`at>k^i0K{vby_I1yCe6ngb?-SBJDY-aivpkU* zlG|q?y0dNp5>k-#&(Zl76}k<-3LaMixasybtH`e5{ljw z9{Kb0b5&}xte}`lw|rpIK5RPwEQBqB=KXT->}KDeQqszLE4BFJhtat2kt}HZLtN-K zy#KF>QC|WY6czg&<7@9axJE_hbcl@Y-wJo_M@CEI;Y`8o=@KuZ#}fy2|HHx-%J{~3 zxp9@|M!qvphfPcUp@j$$pDvZ{+GR?no33=dswVYo@Pcst2_aF$@Nia3ON)w&C9olF zucW0_)G`VImzAUC^y>ExIl;;K*AYTfBi;d^J!!`0#JWhQwoJ;RTxhMy`$Pddveq%I z51M+}xP9w7kO`>pBas8$$pKIZoVXnpW zGGesWDfJMf!AjNBE|cH7UuyYnOwOKHQF`wwIlH(}roT;3PY-zhyy!ifZc$Yg;@B<& zq%t~h&x_fYk@?+oVDW|csAZt#LW|3m5)kDcjI|N2fW=tfJ%;Th9^ubS*VZ1pP4hzl z8NKY<%mj$uqj4ynzIj-fvTo{2W2o8KkYYEWaP%}ino4@o+%G#GFZl$wNF-m*`m*|J zCt#A~7T;~z(s3amx;^^Bs_YYu5$KJ-kxF)wXwyur^emyt(1;Hz)~F5aSQ|aold)Y_RYR2PB&+f z=u#gy|H8+`$4G$Shcx`Ez{P%_oKjE+o~i{M2d1n51RP6*34(*cUIW6^? zZZDfE1#)4pn*F4D#z>*lownoci*wt8ez0ugyPFw&mWbRCwd_+2eL-Gcr=c52D=G{> z2CGD?g3WXM{1YD58H_(|LHBQ40RF+)w7VbKH(g0h`w=@5my8Dxlg|WUQ*FqC^1l0~ zmbNyyeVQpGA<@;-hwukIwBN#PJ7Fmx?RwesItX7D0>K7rmHhjK=%rk$^fVgmI^`l> z|IIbIMO+qCMxKG9p1DSPfPqr5!}iyef27t|&k>T}&MLgmIDJb3T~cL{&e(+n(N?svX8JJc@0lk_X}e73m@_IrFQ;_pXy%~Pc= z$j|>gR%*l&P*cMPZaW=zemf+j%Mkn33($O_tFGssy?-o<(FwezX<4xj@;cS^m%tzD zp+OHiD9h2H%e3^C$6r5TU%xJBAhOu1k<~Qy92@Gb^d;pFzmuTt1tldSdgS-Pa-c_#9wE2^(9IV=SY2}BFS-F%rN{3Nf^+EE z4hB1&8>qM~Vj<2TZ-2 zWoeU3juBc5wMF~8X zFk92nI>|16T0qhrV|DccmvgVm5-r;09+>x5+q$9?e|DdO`K&O5kZxPG4aCf)3Jst9 zX=`8Vzxu&`vr*&$Y!TFetYr_71DdIq33;!rkE3!2-HW~Si=%YJX!A}W8@b4=*Ezu7 zY9&p_@cju8o{CFAprY5kh)F;FFriS^*f{NB{SfrL2%9iBpDwZ$dCq{g31t3%Uqqxi zrri{7t?Ru%!qLjWNk!DMHZw&`tzBUj#lgW*SS%|m%k6XOcF6oC*JG7I)Wqf6ZIJg> z#zbIYC$-GwwmG!VHJxk??e>e5w6{w#>6o>fw@)_Kg3hEq?mIW0@JoOQKLyCf!UPo9 z*|&}&BuhKBQ}H>__Oi#1Ke^e1oi-LHoN^=$p*GT+UJ|Zt6Xm!zEPOb>PoGr8B)<<9 za%ELoavN^zg_&Co?^N+D?(K};*Ap@QEtLJ1>ins>XCx1sRitHPl%1U`oi}L{bTR=# zW}>5$TwGlASj|q@1N_b>RRT_fw;(`klsH!+ZMAMSC%I5jzBLl$9G-Px^LtT-vb}vN zF^}hBoO+>*#_ZXaYtimiCQ)!-kf6W=A-s!u7|mKUhvvONHah@tLeUXG=5$uZ?Pl;o z*i(p$OBJ0$id(>2P}8iQ@hAXm&?E}Bk-4?Q!#BlX0!puw(cKq-A=W+QUN@f@%$6-; zG~_ht0lRL33hgF|6b0{=>za=yS#vg9MuWa6ww3SQY}MFpiJ+UB!?j4Mnab<326Gkk zPHNhsmVw?>(CqZFL&e`Jl2XQIVG)_)H2CFsl^tQqE1BjVz&N@<+jhem<0FxMsuS<6 zfn8J|~m2lp@orwReyK z;^_2fx3cwAuQ2GKPhfim@M4vEXML_sG%C{@PDSAUDl(Gt*v@!O?DinSZJUmAOnQ@? z2i>=@BO3v5N07kMZA?yj>bL5;tqZ*BP+vgMi8gGpib?Y{+E3 z9eHS*#;;x&*&ep;NTuhQd9)l3%l*gm!wku-NEu3 z3jecK=I>ANaPp4u$ws-_6RYLERCqyw%G0NjUltaMP~x%p0L``*%gd{+B7C+tq~=_t zTkoQ&O(iKVZnia5i>OLuQZKHkD%m?ctS-Jl(uvklVvy{CKaJ?GchqA6JsM7^ zWm7tje0Iq|i@fLHeR;qlw6?Z(99AA=#erIxbiw?B(Opr*GA4C%jfQqvIfUK4EIcu~ zlYwC{mO=T?K7TT@?6#onFtTjlQ!z#cdyFo*k;?TFS3rzxBYvEn#3`%1&C8(^Iw{b1 z@7=rg;Qz4jzg}*J5jb&BdRF;=?7d}Nl}Uod!?#f<`?%zYdy;x7GY3EM%46xF7BQu)_T8vvT?sZ zP%BAO>n;>p$r2iG%X*Rebto-@usJs^{bJU>9=#XtYygM1PKR?mav^}%-ejpUSqC?Ya| zYwL3AkQ0RiD_Mv(IcyxJu6A@PRDXbu((^;<^l+`r}CUZ~ti+ zA*3b^RC=*wGXnZf!jE~$79$r1e^lfv)Q`D0C+TH!oesSaK8v~wdUbj?_?0jt?2i)h z?|M(Sa&v6?-_wZU699{d*urROT4pyIUJawl zLDI`w{fS=mZ+2Ylm9rVEg0&_kVSx!!g4-J!^ORFfulll*?OQ=$h(Twbo#^c zSL6AQw}7JrY)t05<6ulQ*x6aJ3JwmvL&ccY)`+9U!uCR=!u|n{#19-2M<5tb`WW5T zmOy(sZLzR^Jdxp=$j|I&gIk|APGW|>xs|GkUg zG-MeSt#W|i1uS$6yB%EG-w{;mGz<$Bav;h)}EQL5h^$umI+~1*q{%Z2h=N^*~0qP+=fQU@9)~hl! zJ6j==QGRlgvI>w8XRZUo!YVvW{5phMDB=YEnRtZr$`25?z7!d42Pa$q;U}YL)r8FE zQeL50j_BL;p0xvCRJd*x?|E1*!kFnFw6}$?uiqgHNaT@C5a>q4rJ_j#0sOfA=$LJ3 zl0ED)-F96}Wv|mwC@JD-n?~mnMb=1RwMvOaSAQP7MAWY8{NKUm{`LI$rZFBb5J_Pz zEb#Vi&A6nz=h-@1Kj^jjC58qm)b;zx?|8VQ$SQlYK!6oBNqYGPb$Qz4^X94T!d9j)}J0 zfM~0ymN9U>WU6M3ahH#;V{JfJN7OucrFKK*gQC28@cgf~>92n3zZ|nuEXRY^)ymgE z*cV}1LLk$d^98Sj$QZTfe0FyozfWEyo+!FcG&z}YgSMckh>I|h9WR;(3aCYdYtxee za4HiZV~f8{c3Uwt2-1EG)0iTD9dDv#SJ2DD1Lbio7#2TrM=;)1ynI>1=*_Hz(AkR$ zWo5ls+X9qHWo4=+wW30Vd3THwpKOV37SYJwzT%%4)~ydJtqMdlQN1oS$>o|f=+zj~ zfwsd=9v#{ns3#MysgxYrpTdpxyAA1Ner3e{b$kACp@5M~9v#z2xARwhw9I^bhUZob zBVLl>D&2~cvaM7=*0XY!9Gu3qw1g{^*-Os{5rb09roRI-353AU?jgIpjvA zWu%Pluqk2dZ;X3OOLY^I3`a$UQU*@dAB_7@k*Or1J_@X(;GVhYH4B7`0u4;s{&F?=p8O%*VN(Ci{}mvL zVhdDu)zz&GD>ahM!H&h&dQQ8o2w9VKxRKG3T)=_EDu6-E(aX;oa2laBY{&CnZ#su4 zsSf5@_VM23i#`#bxwq#52vb%QZ=VnA>!KSKV*y?fl3juI;SJ0w#quM|a3I%3E#j(x z#}|Cn)=#$fY`@N9FvrK1pw{>BgOls_?7LKlpY3WtRg7@p#pN zug_ecE%Rh$IBThht8C0IL%5SahEWox$F{#%$ZFbnM%fbh)qxN0_4M4}@hDAnrR(fXBK?zb&7@t}IA{HUlHGm`EeSQ=zNX>GA1oCBf7QM0FF&!N0Lgph; zeGk{D6kWXS0y3hJ_D(c`q?J;SW&|DIBY620l$8ruEE(zeeQJ0e($T|lL=ExF0@Z{q zO4Ij74zCc}b*Oy|C`*`c9ZYhVz9Ez+pG>3S)97ZKtEy(!PmSo5hZvcay_@h*WW9ZR zbDGmzexs8=?(d*@k}67X}Z*xa+@BD z=CHx!^092Zy!@=xFP{HMw*K=e|FaGF} zzPq%wg;^eFKgweZ0o*z1=qM(Jd+I>l2ZM!eWG>?XPhxbZU{)pW1YX{{5486j7=SI` zJBdl6#&yPL%vcvf1MwV#n(N%gdA?Tq&}OAAE;4cvkIhKbqil?}7OuEp@WcL$`Jgej zn0K!-WRUl8WZe<0#Aywws* z5JltYYsFCmw>?R3#>u8>qn~UpAYk1V#a#7hTA?W(W&VFzcp4$chg1NN-+l9`-c4S9 z6i6Yc&4M@#YsoWGg~PQy*>~AJI^4NY;$A`tXqf=3YFa)rZ6Re&+Y21pRw=IYFTpIR z-hc4mIVot7DaODstgiNEkAk(o&O9Uul2e6pyD-%q(WQbcg9_VA0^JA@tQ_o12(hqa zK0m8}>z>p5<|r+K2+TV%m~XOAJY z@>meK4;va3q+|IhhHb3$uu91SV|QjN9K_BP@0ChsSH%&%h*vPyr+5zxLO_5jDR9cX z?CR{g=22V&Tg61}2|mrC2paRC@m!`sV<|nxPv)Tp3HewV>;lW~lQuQUy?VY{9@(~A z`_6|+XV`Unji((H6>M}8g%k?CuOUA(v-Th2b*FR1-!xn`?DsQn+`JiUfZAnde)aOD z`U|3hp8vy)fK+Ii5UXOn$ISIwL;d_JMNa6K@4E%e7*sdl05FajZ~bI)@;iiQtEG(fC%HE2Sh*;#F~w(~+vAYD=A;ms z{6H&{vAYYgwGVs}1(+Y}R{6Q+4N4<%Rcq}T3H)UbOj?A?Tnm-w=UuX5mHPJ{$fFYM zQ-mp#IA!mr1=N2_=Lin&kJT!K4JQeKv~^UYrqJJ_dH-TT8lD~Nt#qEVSRK#5YTyk$ z;$Vdsd(~K7xiY1s665sU&HAKGbo9FCj{b#-3iX~WKo7I&FJ*@C`iu(V_b%mK`wEQ$ zfLpGpO4(EZ(4euf0*-={Q^_{@RqOrnT9l$Pw2wk7m;ToM1VQzM{8wqrBe>q%K&64@ z1p<0`aj#;3uv17M*Cc-6Alq_RSKS4AW6|U0Z7i$oy@Z3&~7`q*~hW%4S=9Iz{B& zMUwJyROb7Ki?gVl?>5VK&*uCH68|z2|6))PAl|)0K~A}lx>|?6xU<|B^XvpgQ!~nG zUIU?$x}x)O&jatW8Y9N4_;$6vu+@*?gR;uNCK4jXI0p*si*-8zE6<2t(-@8bK@Q~h zr~AionToW3r~$wi+12ZJ$w%sqNTqNTnPH=OeTyCh0+AvlYGJC;Ypll3&)j@OAHwI* zc}XRbfj}ARlc+CvF7x?= zsqe24{O}?K3W7WWrAt%P{3X%`mhP2~j!sZOUN~iIYo(wRRZydmAi7H(8mzmYDd|&J zY7rK&I%G@(d1OK%;9cbxaB+|;@ImAEgXvZK)`^;(omf!mM4Zohbxe81)Nv|98zZhn zlTu~(s%P}q*u)DLRw;1f>QyKPtZWg`>paHA2m1_=v5sF_JA0tsdEl_^jwU^MXOjIs zmgsdn`@P0v{fw1c+#6d3`OITmYP6_Gr1;EG&HY2FK}&^3(htrn0I_?+dCkATmh}|D z2XY$}Q|$OI(?ia>>!|d$4xGyv`?`pB&ayiHL~0bhEI>eDo)8EnX14 z!+eW90HBc>Y^K7RqdI=Pjg@Y#&T`PzYRdGIK4PmOVv^}^Uv5&YPX;D{n1Fe5@)flR z%$PCBAvA#q83)5WtuLdnumsF>svG?_EEnT#*SjW%x-JuyiwzQ#mBE_WJmK+(U}6%8 z_QPLf&YZP2ReLQHdM)iWP>HY!{ba=Y%+k;F0rT-~!Qr&j)zODd7D3o=+wkeRr3phc zrh>y_{hq7VDr6^UOZ!K~GuLi}vOY9_XFTIYc79Q~%J0#P6HuwR^BxM%W4&Wu0Ia@w zow@kVhDZjniI|uQHfapAJdA7zxoP>W`RU^4N?g@;x`%S=a6#O)9D-8}64g{+4tzv@{;-feJ>ihjQ z95@Dsm{VM{9(eow>~RK7Z2xo6-q$(xGOu|>E5o|cvJXi_hH+zKN)(v#3D~D9#48j^ zLkSZ3Ia^76>D$`#x@a>1e*@h~`#<()(#wXSzBinth>1mK*XjqJBIq~wV+aqAz+*!L z8jOgk(Q#%Xjt_-BG#d#{QCy`BbZDq?s6J$!yO0>U($wh2iDg^vpP{~E_n*^ zjgzm(?8;G5?usJL--<{FaF(iwG8fQ=!+7lxLeDcl={V4c=AA5nlr;u!9pS6V=5o9C z506sgd+MJ5B6;o?Nw!Cq(f5X$`G=Z|lLZld42mTw+50hA%f7AHOvMC#+at?Fe&rDx zEfvR0{AdX?5(LrIJX+6@$jswdv;O#mpJm)R>7P?se2Ac zt}dKf^-OJ#Ws7(IA`0)44gIT##b0lC-$`)S2oW|*0gb%Ay60!NcAxGGh=E3IDHpxv zd;s*d)IL7`a$_i|yGm-z>R02eCnMS4zqBNygcPr`-`M%|+<#nHL<9=eMYpqRIhR%I z+R}zq1-C{L^L;qa zoiSnnPc>aoK%e6u+KhHVRY0_L7%%~6+Su47&8KTdUp+ciuhW2=4YEWO8+Q*o%}xn< z$}n?^<@8@o?P*+G+!{LdL8pc*HzMM&-DJEqIC0sw7n|d?*DMf;z&fLcZ|=X5q7hRV zE;m&4@IbU|&R12ZOYPVUXMR4Uvm>Z`G{^ljX}oexkklnVn#_>hx@oxk3Ts%Ex#zhG z9kDHE)`MjiLDw-eJD{)7dXf;DD{SH5;58{`O9PPeZxrC32T9TiK+_t{gS$a6CrY%s8WqhJv)pSIJ^rpJYP&qno4(YpEdQ1CLa_Hsiku3fu z>hc#0^=BhyGzv1F(&4FMt}3cFBiS@Ls*BnNAln|p0`LS{6Dk`gg zkad0m%D~6lI?{9NiD4=a&dkFF3&~=;D>jDIj7g41b{;bD@omLuF_&1fQr)=WjIA@s zSzN?bBGBJgeafX67$TJU@DemDufJHeq34>G7~2;sFd8XA(F#73*Rw>AqQvPuB!tB(m|WyuJyVU zim}4cGi>MNel9_@2HbZ_GXq_%9PhKFj|YoQhCz>7{9 zg#9}@j;TdUOW|S&*Yf@$CRL{r)4plEm(!Zn1LeW1g|jC0Pbj{+-HxstMH$6x7H^b3 zCA#=+LDcTnLz1luL)%1ct#_Er@MKS0+pgVQwAOT`2M(!bZfILP;a^=9MSh-TY!;H; zLNC%$a%Xm5sZeWPUS1^{lNl8yCyhBIHUkGFU(+07(0 z4K=E_HTJY#DomV3Ig!${THEze?g7F@_?E=#;{LQ)k>Li)#oFM5omfSdY?vs3QUtf! zRB~85mB?yQWiE4?&7D;>Tktwuw$kygC%Ba=ir7l%8_v#3POf^2V>#H&2t$=-z84aB zVm4i|mOkbFSG)b^-F_Ug#=QW3Wx7mOM#h8VAk*_(QQhJ5n~$|DatP|bcMywzmAv!# zOMr!k$8Bh}7;o!l-111TkY?djt1fI%zkX(4;b6i~?f(vr2Xu-M(L9Z>hEvhcovG_5CF zSNA;*&T+Txw*)J>r-6hcvt@bPf{@gstg)5(v6#27^HXn@)Iln5l<2TD- zhlS+T3&$&4&--wah`1oyMuu6QKq4X0Z1@>SM zON0yuriuJBvx_;ab-Lw+ddMur7(s~E722S|6BxsPQ(gO0F2RmX@)=uu>*@}=qy!QO zF72mYTj*f}{ru3KTGg>c0ma>2jToHhLTY=j6gw2U4)kXfo=y@*XJuRY0A*aoJk5-w!H(SBh&(n@l zpiK;2sho|fu?Xu8yQ$@2n@?8ovW3@iQt+%r(uw#oL5Z*pYRcS~vOzn=BZuDN{VkaGw0=$hzFzWD1~Gl#%}wixK%jrq*{R9J+Cda6bdpD;ySI0$xb!uYadBdNdouII z-qY30myd*K()>F-JTeDhIa2sC7Bd85eE=ta;R114Y3oQ|hH0Uer9mM^jMfaVh1Q(e zVriUpLPg~tTG;0UKfz&+umZ9keEQep$s#>l~}=tE}$q+Hmv_ru}vT9 z&2^wAm}kUv=P6UBBp1_D!8}R9yt>1dy`_D7?b-;BMq@;v)B=%z|LhK$^I8q1t{Ms2G0ex4})OAZ&#$AOJ?=9lGw0m$UfR5POZa0ZO!9LYLf-Zux z0iodXENOAH#=ubSRI^Ohz@P}OJ*h=RcxuBf=@Q%=76ZEWMn|R;ENwc^dg|sWz!Ur@ zlSDs{%V|w6+GV z#~8%6eu+r&(9qSwSuG|A=WEmUV$6)QvJ5B6`f_T8J^C}m&h~A!`zqns@aZuh!k9<< z8CSzIbcXuS(6+WJi!CeL+9Mx|?v&*k)li1VB73C8gg@iWojVT@z&4lSgJL&lYzuS#3Sr^~UTqmW` zfXfEX?0NxewId5bQy&k$OWhZ*R;7 zrm$Mq8$^vK*iCoa4v`!O?(UeZ!Z!_YzrJi{F7GNbS`vUX^3$H554YsDty0>tK&$b$ zzjAL(iL`suha%wT7p7Q}dQ)cj#soAcVN*0DXOg3I# zzAGXnDX)LZbT>~b9?A+_$|(+cc?`Hi^E3$`|+N$kUZnXQ%GmOQg7VZxg;6U55(nq`N6*YrOj8>r( zf4wXJ;yn7kybTuib@*dD%O0w`DswmxCN_>$mvLTF`*g7CDrKr--$B4NkVg#HiY0@s z)qeGha9xGnx6LQk)zLJ7WdotVyY}3A{xl?8Ly!6DYz?U~3}dh!#yH=PGJ4zxe| zJvzX(=e>jFK6N0l@Rht{L`jV7VEID$+$y%8mQ-Y7#3U{Aj{h>>BWT;JSL8s=G%X^c z)j1Tao!i+psSTTUL`Q9HNfW3YM7NEyn5p=4lSr49ck~TpXU>=dHky%xE%ow5q{m0=W0C?jXFe7!3;!JvCbw?1H1ybp4KjKdqajv1|K? z_L=ENZXD+;Sv^%tiuCo9LFQr_f49uc60mb%`LABRW?{J<-7>0|RD4tXbD!@i@!CU~ z1kz+VE!$mlK3lJ9DSaPzPAy9r?^^T0L2E^6e_GFxk)$1I5>&HE)#w`CXQ7|+d#r%@ zJ#$?heR^PMD7R5IY~g9$j@WW;0c^2)JgdNS6(MzRa&&aDd|@GC_N%e`MH-C->q6$m zp?e_88u$!ab4EsIB`w)l9Ly=0+HK`@6>#7+Mut%dF_bvnxXx@!0C|}#v!*bp8;uw5 zBN}_p75w>3Yc`E=roXq(yYg;XT<}O{sj|wj)nwO!`9q{3*YTS5V zMnRVfU>6AYnVzv}>(+Wxq*f~}y#OLSqZy@H3xFDrOr}Aann$;@kz3BX=CMXzSn{N! zD=SxIX9sEkzds>~X1QB2*(D-&9p?iWrIMv(cutj$e79ImRIDM) zSSyxzf3NiMp%*(7vjgh2wAO8Fz&h~stmc4fEowlcg?V^z@zGf;uZR)(2Kiq{D^+m! z0PSIV>Y)_Vz4IwRCTQn98Ri5W?kaE+qg|7b{Y@O4lkGkGt9Lai&$r(^Z$J_U920ME zZ>x)^ld>47VI{h0Y}YgeIaO1x^N_Q!Lv!<#Cfzq~LrQewI$6FqeHE>@lVcM!E5zlp zn8DIIkxJ%*mD#toD?Fn2rg>f23htRIReQ_A zP-wP`b#+SK7G9+p1_GHFcAd<0cuAC<@%^7e@hDvb+1AGM(x6L&f!91kEl9g<^9n2i z0STavkp2dG?Nv&9@0hGbPEEB-TQzVyRg=^P{7H1UJ+YKmDTE-O@V$M5IpcNWe0&0E zWR~<*kVL}ckqt>gUA#}zE>MwIZKyDFa?U_o(yJGQoMx&{;A;+vP5ao2WFCBCJk2IL zbGmhS1PAmkXF^FW<{v-Nvd~Q=xPF~@W(Jj$`A`fnP9$6l{G4V4-*Tf>7|}{G@w?_< zS!jLHZ}%*GSxB_tV7;Q?P|Ti3j&OWA7B-%6!~X^qg_TtVC%Ge~fZSEArMXt#i_A9z1$v22<4p;_^Cy`f6dCe1mJ;~R$WhF$)kVeB%Rm9?Ja z_MnbTme1q}l7Lte65D)Zc+qyt+ND@i^e%>^BL_F&p$S>+2`V&O#A{)okp|h#mO)d7 zb+EU%@;29*JdN$;zM4={c2fV%hJXtmfLi)^pfg_OD@WCpFUm>gHh+@D{7Ze|_rrD% zFe3TSn}Vb(hkjk&sg}@rT~&$vWZ;Y+eeY(qpYRTU77JB+W#=nt%2Lx28(r#@qu~PX zG;pRoJfRwznL;Jz$b#Y?c!G!st{0EQ0&lbqq&`R}nM9w~X=>*dDQ{RzMhc#>V3Um5 zd{5Rc;w(oZEW!t*RROT~wj^bS7K~uEnI#(k=oWW9l%C}D6by7?*+MqHGowsD@88da z979FQ6VJ?cK=ks8po}Gh&p|qj#f!526)C)_ZvYhqS7>Jm-_l~(7}|klf@ z=XYJHb7sb9L)kqgifq{}rvtEOe98`VKXxpK`B$7#ahN}}Sv)VmV75sfZCBKp%-EOj zJfo6kX_#@dge#GzM7gEfDq2%mRer=LuQXY8G4!*7En8(C!uo+uHGgJsXX_6Rv-=9>pHyW2eOTDc1U!ywf@qHZzP=0y$WK`VWCi{@qgr=7)*!-l$1W>LJb#nqs%AnWIsyO-oDs+>wBj-nxgaO6{;s2(rquns)1I^Oe2vc;e0^WS#p)e~FPVB$`vy({c|x zm6gMpZ+53dcO`{;c+x{;s@|5&6|U@HLv@=wLPy30MjK-H#ks#)2uRL|7gF5_I>hU@ zT*!b6+7uB#-qv8JRC?#CL@N9|#}iy!+u?9qn0t0cLm2HH-FnFT7ylD>?E z8_4Y8jM;6KKAu7qEyXoQ1iN;c(Jrxn42)^I^>Wtocs@QqpXI{o%?27*!RQwAs}#&2 zjaJ3%)#5qiCjReN;h#K=YdWAp&t(xvXu$Rm2GK=dbzS;c&=^<-Vw$@=+~jVX>V&o^ zc@i^iv(&j6*ljc_;>nQ@1C3~IUb}*sK}~K!uLdGE231(2cWBl@&cWhHnTYL%r#C)c z6Lqq+s(TQagq*<`_`rFrtTcsP3tm}#&@eDa0eT%tR`57+l!CZsTV)K`O7ml&v&%AJ8uWe29kOr=89Bf9bpUWo6rUQ zDw#tH>nUV@?9OL~X-ybQAx0ySl5^k`&>g|2ORG#52M3=gK$d?Nofi6!2g+?Eo=QO&dtb1Ij>hA|>adbJ#l!j(u zenI1jLCW`ynKp^1bsin<$%J@Sbz4ImVFqfw@ni|x@4h4;zA=jxRjTT)%tPemwVh@Z*x70M z%H5o&Lda>n>EZj`Dt*2iyTo}_%5M>iS$HR~rC@sidFDOH@nLxx=a+d$%zjYcqvgRx zOPTw=8X6jLSjY6#AnHGf0R4S&Uh*B_tWv#YHlm1R8+DxgEG@S6ePh^tGna#$JlCp= znsB97>pqDeoa!11b4l*Ob5VYrzH$h_#{;27He)o(^lgbR#3=NW+at`Yi6r0E0x19UAmTRBLRk*ZL^$7H!oSHJUuGu|hiHM~-ydX@DQ8aRe@ zRF-a?+h(is`ugkrgKaxYkajOb^?-SD@9_7HDsOK!YuH%|Qu(*fHir-IEQ`I)L~V;g z%Vtpp&KXv-wwk#{0q=GR6@*<4>L58#P{Dk+?J@>8C}6i9v|95cWMOA^7-wa3R`|Kh z`Aa~gup$4_H`JdQYv?XrNGUap70lNd}11y*Pxz>0q?*&l1uuBgkX zP-3}sgKE0c{{A?CUW&OWO|oi5^$(*uOL@(5vX}*!@kRIQ{%-eK8N8 zBi>p!`-EX28%>|1?K`pxkl58z#V2$;tB>Wo##6)+QX?}6L1!I|Wh8CQs`&Ku47Zut z=-H^de~I1yCcLL}0WqPBF&^Bk3Bx+cf=)6LUWe|>g6K7O5$Fa;nu820>p1<(=}%!0U|CVWz4G-zZZ{Hb_Oa_sf2ucv6w+iI%Q zb!YO^`A7Nb$99Z-i^5fug|#Qn>c|%I^cLy$-}8TGY+=7@9m zu*U9}+22>gm5J*kx98g_!V3ED%xjEW>8I2w9AX@IuST(wpJS#z*XB9(!YlBiwYx_Z zYVf{%Y%uidEx1*T%Xn*STSj=gJJipWO7G8<#um@O&Dw`z8u=?_AX~w8-)E_9j02 z-0{Jy6kx$6v%v-8Gb=)2Q0oy@xWZgj<=>LGuB{yHm7~J4+_q}9S7+fo(r%ZpGmru2 zX>9LWd%XIRnno}@pEYD2W%ohD{y+v~p`sKNrs4%u$NO@o#SjYa03I|v*;r-r;fC#S zg*qBm(BJ-w_^#kjqOaTT0uvEsVs0GW)uoaw>?9)#!r|>f!@-oGtGFuAc>om2>_L$X zq*zX-x+yaVwwuu67AWV67anvyd-o?>|&GACrGdEbV-{-&VV zOxbLGk9dH{$NSi=(Z^4p|1uNc_3G{RYJuqJM)0Ii0ZBjz_F{}`P|sS8nS{W(@3l=` z$t%3=ZBj|MM9#8{nolxWV-0i?MEi0So0^C@bt&V!xO)bz`FyxH zU7i9!ug24}fw+-bbuBvSG9g81V)a8Bf3tyNOt}bu5Qx zEvlC9q1>CdQw~eDAhfiW zD3;x`hnSP98xUsI>k_?C*f(-VSg)in8yP2U8)^41KyGpWV z?@nFTW^(sqm|g6;)Aw~#3zoPTWWtOy4l&DA;h677fzFgxBu}ZAOaaXV>I{VTx0x-D ze3UN+^08A7j9_hg=yl7jfC80@eegUB*&bWQ#y=15_qgs~eg=^QUhB0pJ*d~fbb;ER zMOSj)8jr>1dQXPO@;gF4fIH6a)gT-!)UwB+HdH&Bm; z9<#h0du;e%3sKS1;zUJaHN42qERUHdU$#!i9xC{y1fbVzEA+?pIhnmay{Vb)X3C+H zj^`;MPpVh*?e$+^BHF$5?sqHz6V&xk&)?CJqN_Ecyi$5Ro6((>bs7}iI(T@>L|GMs z0P(@Ti~0j6bI*78ji~VOG+y+cj3mE$H}_u1pP_?)H)Jkpu*zfaC3Rl2T{@RrjFgw~ znYk{uv)&;*f=4QZ$&P^vQHtkki018%_E*2Oo{Jd!g+KB3vxXOhHVf^NlE;Pe!_>mI z{Z0Pe#1V>xHCD3$=iOHpZS|#6zU#zDn>1e6g8l(UP;BN7rGe}fo3vMW!QnVu)yDP+ zVz4;`rClt=%F2?2WFZO(al4~^`ERbDKNbBzgyBmBWNMcf16x5fySX_x>Q5rml>)mqHpi0C!IBLuuL+;8_v6~jm*w3_mmplM zs*|IZ>y#AjBJ_rDGd2Bd#di~Qr>yN_tgNO0SJ%=CrO?+~n)yaj5%9EYDxIL*t_8&F z8vs4{=@+2mA7XS~oA75|SsoB+?Pi~CNO`X>OEdt*zQ@Z zk>;L7+|3+LOp>)^16pc~FIbs@W^2I$<7$r3XzqlBBn1?+5cnnh0N{sA%QJn#`?MjRat@HdR^ zqT&94l(|N6?o8H-9kP5dexQd4CLLIK=1gb6elpGc;{n&fka4?Q@AKFdqqhPgKDv2^ zFf%rgA)4JcQZv}EJaRy|wCX|`R3VX3DQQK7Z*5q{?6t>3NwW~HXf{5mnWbeyY;2Bu zUyil8ahf@(rhznD5(6`HTRiq(8pQm)tA2t20s#;r>So;P&f-*Cr0`)gmB-BP?AGTL zvExjyJ}a!X-Y%J-e2me(_QzRMg; zcFI>yt}{kb(tsoszvENyr9L4NhF?AKarf|?F1w^J8z?$9ra12Wo9zrSr~rKm7u!?4tJAr-1E0@fWE48S=#*^mDGW@5{s=p99p>lv}aztLVaZ*X=xw zh{)tuI(EwvVJ#aoJH1;IBdcts12_4d215=#mR+&7M|Cz6&+P>4lMiP%bYAy+haMto zdiEC#yYYp0Qd`L2cNi)SYYk>CJV(8khJ_F671un>6cf60KrY@aCx`Ve52PgTv$k;> zkQ#u#PF>ZcateLgBoJQhVs_dVVDgWL}H);nW@OAWtxF;qiChR%s*OeksScTStPJFx+ z9}&hP;m~g}7%AN#6~oTXUZn;{M&_s>5yQNMF`Qb*$RGh5HMbSLHa`{q=~Gjg<46)Kz9uDa0$ zlT+L7`8x3a)k0g5R(`wOPCwJ_S_pgR!SKxhCn?KQl)Bv)qVVL=NF-7vuCwkZw{S54 zo`rn*rW>6V5OBt#*gl?}_w*HLL%t{sNX`INJgc31iU}@DaWO8=k8M>#X@@Y;_+t=I5}+9W@5oq%7F zI{_*NL|m=TmwjK}`2-uU_S(gCC5zi@&jKlb%~(VX-|tQv^zydx1F z>Pa&J`pf#5hsT8n4vtVI-S`M@Oe414#HU`Ak8d61_?Eu3@Xdaf&i}f*iT#jRX1uKP zAwdY@o)J&%1eEV|{&AZB(^n0d05S(!lDsCRQ_Pda^Pwdci=h;(n;!@Abu9O@{z(t)?>wbH zes&(P@`K4vojlzP{WQ1sW!Ur6GXqg?ossTTEfZ;fzl&m-MgA?0j+s+a;WVmT*N~zx zD8t0zLA$uSMhO}PXx4DoLU;xOT*}7qcymh1P@AWDe^TrI_hY{E1|;@QQ#)4$H{_GM zdF;D@g*-?l^{f?!Xl54hS(DdobhVa7XIR=z7Y`b0tqatp!7aM2%q)>B+O;|tceH3X z+(a|*^ou`3-2($A0$~%|WIz%ry}dP|fyXq3*ls^$c(5;{@%nWu!)jO>z}~tImxj~C z5w>`EOjSC|gS>2%=U%A-3SGv_2c^==?_HSgD07>XVhIaTiu^f~M)ww+d4_L9k~^2L zJ@NJC_nz)b_Q*oYSMTrjV*sE7(7cmUB`^=>S7H(pr$O(GZ319o@3qcV!o~3N)qNE88jA)ZWTHfBa?K zDdp179jG`rkYZsRkF$SxPRY_2Xe$A7@4{Jd=M;J$?N@=U&7RK}0rC`qCtpv*`?uI2 zQ4zCq>h3#B>g%C2I@d_8J3!r}4>Z65zKg<4SM=aw*7{JCxaS=8PYwP($koI1r12ov zd7kwn4wnUb%N^K{fSDhe7{Ft=%f$9_2^3?PM6F|@lGt_+G(4+$pjkT$&|NF5C=Fe7 zf0Zx=!uhd0Q|7e4zYbJAjRC})Dh|c#>+7%o(TnTfUt-4|{jdCOX^Q;kuctK}xF$0|f9|gM4_6 z_LKTm@%;SUV|6AV$W5QxEjwMDNJWYLM|YF|@D{$Ofxc$Un^UUgmn(1tXD{9y=+dt) z%|R)6>gx2r4o@2gMQRm=2mx{p55rW)?>-dUn~znV6u#1cK%-I%F%ehtwW~Cp0ObyV z%{3s9CkQP!pP#CgNE-EmTRgG!L5nXvS0y2E)-(YQ*urJ$qic$n#w;reDFiOj+uf9(?87wZ3T=>9UOE5{rUKT^@LpE|R@ef->O z2hzW6q5rT*MBox4t4kh-0SlVF^s)CIFk5Ia zCB^N&aYrkY`z2hQ6(FjziaLC$J{Hy!2=*JkLR!b*m@MLf@gm!s`z#1`M#%kLjeCADkk=` zMjZIbr-4%z^Xcx1vH!zo-XGiD3KP}tpS32JB>%}t`033>=Wu-5SBCnW{>x(j(;Ug! zAD=59f{)(+htC`vyO$!{oBwEo`CpIn6}{tKpL)XiXXt~!ZTc%(;4}YQp8qY+|4z^U zPS5|0+yCw!a4*RH|8n(^|&MBGu7Ct>#-0RN~&rPSs>L_cE{^%p$Hl2yzAe@|lK0r!=zVZBF$WY3j|xiHOnRFqZpl%KRq0Krb~+_z z{MusD2t#ClApHIX+f3xh&rN&Y-rE;{lCoK>ZV>8Ir)gDr zjVSE$oydy1unFr}v0sHjUgr|%)ysr|%lWQaFL!Yh);__-;ViwJ=eq`xxYedU=Nw$PcrZ|}KMOH{f~;aWy* zZEkd^uDWd~(aG@>8B$RH&gE7jJa#{g$>&cUyPpklglDRYO+_;HhT`P$e_sUmIfWU^GND(o-bXN01goC%lyumg#*RKIvqz+wAfnnf<&`Nrtm<5v+>@fx^ zmF9FC`+evx%xeHeB4w1w){@TEe?j&LM`qtu$=O!x^$8Y!R?}^u+i(vSK z4&nGsq^7~`7^ZU3ECnP&FG+riAqt*pj-a`NYq7(tt-b$!EuPtFHr+~i%nb%hMO|{( zl)e|Y=$vsp*vR9-iajC!?Kio?PiGHrE#^Kq;lEa#D?UTI5CRAY7sc;mUT$i9(*DgM zHzEcPO(b|OclE~)##y+AsT5aebH$tSe}qA!!oJ}!hZo}Sj<>VCJsVpa&p8Aen7wKm z6fs_{+jc~`pYHnLPWcL=jpz5ld?bKO?;(`l-iu|R1pC=Lq!etd*O%^mVfX_b{{A6w zww12oiGFP5hnKG{hA@cupu&`+)Tac0dq28xLK#TYtzpaCr`zlp19OqwBA61Y=->X`N3k@>AReRW@+i8pVLPbWhH?`R_2q=5}nA-5|-?^P+^~*PVKf?$S-)Vofmo2;Iwfs_~!VJiiy` ziO;M!<$}L%PImA3ExZg2mwsn)J>ulLUTFA4Sa62B8M7Bx-CeACD~J~6XId=LhW}m0 z_|7jN?EK}Lx$tpkBqe=c?NM!R8dO-*D)lbT@Bj+rq75BWjJi|AhASLQzNfI=-~PVY zr@A;9c+pI%&wdqZH7|M}8b^4htGCKf^S7MidHlY$m|XlwchMyc1p zJP_@r*E9t-S-cv$D5&lK_< zD!cRhLJxqT{1JQm;g9c|rRiY6#yrp3)BYY1k|L^q%uEx>I2Tzc+?5J?vbG13HXv> z;F5zCk<#YkU>x{dTF{Tr3F!K>?QPzc<1aI?**x=GIQW?n65XW|mP1~%1=U~o!G@ouNvD(X_t z6=GjLJ@1wM;^5k4@cx@7H}~T}&ywhv7)BERI|@`Q!`sIVDvxFD1<6x)J1t6$-ulI1 z>}{za|Bt=*3~O>-+J*&Xp`c=+s7SF>MLq6pG^4L$T4 z6%~-)O9-GyZz3f^AbBS$Ywf+(yPxOVzrXj72Wq%;-B+18=bUq{x#8p#u;cWX74tjL z{F=2D4D62&NpSwkWkY6}tA$*2en;LBd@$*!8?V^LfYFfkrhh;B@#XbvD+NE|?hMX8 zs}_L!eWNj#cYNeIH>grlFmIoN`*~46t;`QOy!%4+K!HKs6)^*;9j60j`Cu)a-T34% zE;Mz6qy8ox<{q4=JwO@Y0;_STP^; zHaKe|3CFf|eD(tST_9fieydXa-BN2iLMK zb`jK8B76%E5w%(RU$!!e@&4$Uqihrhp4k`X zxXg3@1`D-;xs6Kpfnr@EmVB#%QKQc%Y>MbwVBXUhXUfs(ZFeYMJGV1~RJ&g@%Yy&ih=r0C_NbUwM2k<8K6d$BB5 ztMBz9VaKb0;W1z;3lr-P=SQX;JaYpM#LP%wr<2p;#+j9%&cem>2Kx{3!7IHjC^$NE zso$9I=c0X@3|z2%KfOdtSvRYHUAGVI1h1Ly_GtVx{~wzQPgkX<0L2A(++;1^1`ZKf zaQe6PR5qpH6*reDO4 zXF7E1oasev_O3v8GLOD_XDDh!cs!ysGl33Ts&J_-)OU+G&)>1^$0%w*H6&}ngUfKs z0SoqrVl{NDK;F0Y^an+2nEwn+`CR@lQ>~<|X*i24+t=ECw#9^nxH1%v-e4sO^c{du-(kHb( znM}8X`r6g2wmd)jTA>&7`vi{w!UYl$ORf}F>Zu`bF3gxb8aFYlBSGh|Jh!>xUUeig z3#t|1{bnYhLtX4>=_q@j^m=>nbfZ2Avt$F+gtNv&9GmSNQ<>>;x1r&7&G)dp$yyH5 zH^*qa^6;$4y}ZNb*tKYECTi_9s(lUW7b)+9v2ScqD2#<}kL<2r_iw)C*zf{vh@TXG zPKyj*beXt1XJ1k(ZD?X*4y{@TDjc&qoh9;U%?+lo)gQ5h>ILz6caTDRcvL@>jyG!#7sF;U zJRI5HV*7C3KHgq0V0(1+>Rk1wb=$S?a4CbM_<|#3V88_?Q$mcXIQRMTlE_$cLqmhY zYV*e&4CXsO78@yuSsH9{HU}lfr{?DF)j3=&;VkPCG!UGKnDbbKZc=$m6<4lZJF+TO z*WyZ$!e(YRxaRb&u0FCRTlK98tFz`UVy6yrnbB^~`u^T-c$U`*0*ta#%^V#;H?K1v zPY%@OBMi?>)^z1 z((4E}%(sXvS2)frL!(Rm1=m*hp##Q2dqet7f}kaZIJpH^oULmB!Ag7i*+>!d@PiuU zTA2+6e*GFrtKKICHA7|nt&H?6XB~3Mv-SzP2bD^-9+8TApX$;NIF5d<^@}YioN2CH zs6k>0?%0Wkd)+?!usA@cBniK74CHSNEu#jeV(yl#9(b!>Pf9N_{_>L82l4uIE@|(I z`FpbrToL$n%UqguAU=(&3m8GG(0kmU9Rzu#vjD}d2eFqZHT>6j*9L*0xmJ4 zg4(GQXLU|H)|LlrgQO^IBQkppoec3qdBztpp zv!JzdOL-&Hx$E((Q|8GXozAX3y{7DOvf%f zOt;^7EFz&NVI@KGYWB8pQs{UWUMoUxqccM3o#fJJmOO_&yx9ekk=2D^nOS=s)vlJn z?Cfm8>Kg*O6)6zE&b;%Xe{5y#m2Qn9;#!)eXQD;irTUwdO82mE(*N-|X!8oGx^RWB z%WPqL@}7_n_n*&Jm2k$o2R#CO*a2NgrjF_IR}r8~kzpGenSLYIPQJ=X!6`%3q~$0D zjU8Ezfz8d)c~!VcX)q+9_`$5T`N2hR#)SwKAix8 zuF@IaQwNT^Tl*Nw3H@0M9O4N`=73Gx6eUnTcX-D~-Yemdtwv^-i-}pSn)4AH3+oP4 zS8tk(*vO^2#In@lXA8`b&<*C*W_p$geLtreqIA)OVo zoxc@0o5eZ~XSBHXbrlsy`A5v-h2Pp2;R3vC<{DRFl1bl(q7YG-kd~Z7m+2WO&0y{0 z2CN49TSa}bOA^>o^&gle3kWn?#0|pUXKP<*T0e|WvJThA&YD!-GrGr%^NZ99Y0%+o zxh27zWp=kYt~O1!h(PDA=g!~1hbQZ{F;n5Jqfs-p)au3JHg$)>rD=10V$@QbKNGJZ z(_;2DZ$vz1BnU--JGd}i5?Wbi z9eOa~Z*CGcG`nIxQHl5}7!-Ap%d;5 z>y=odgvskwJwvANv&QN8OEFM7XJ0$e#J|yx$IoS(EL^u*5g}+DIdbHvKvs)Mo$1>v z?tw@jiL96hh}jwsd@{7>fX%d;$2v6bVrm8#P`Z!V(w?!#P}cW;s_f+-# zlUmz>HE+h9=-k9?-u^lD#Y346OQnjTH{ZGp#eKEd2`)7Cr#pU~OkGxFLgPCLr<@gd zrOK98=2c9q1hmSV$kT1@n>dObuDn;M zV=zJ!ZYCoW1<$^6WVJHZ($vGz7hY%J&eqBEP&)5!uCc!*S7vT0hImSdd86068%YhHOE*;5_Xo7d76HoE^LZ__Jg zJ#w9Gva9})?h2FWl=YTdmO|*TT|t5V0byG>-;9Fu2S%?iKpg0GRRCbEic|6s^|sY8 zW)4b>#XODK79v6~+ox{T9#%4IOT2lXJ_X7#qVQFHMW&sOwC0^v+6lGQhcT8o(K8o> z^0g!0?qS^%bEAc%hL5XDYb!Ev`QC6Qc8d6iX!PFBw0A|(+@frWh#Q4;`pKrEInNR5 zOT^6^s`cK-MRiRaD(%Mn556iOzbZKwgx_Wte+KNGM~O`UVtanHWP7vKeA(M0m5GMr zXNNaAat<~O2jPOc-zoRZ_F3>$O&W`R%>EKV^Kvly#rExnqvAmtc%Jn`bH>4e&2LP3 z=A=G)%ZaiDibR)m$)C3h*gMguA}$fn|4PJ$?v2(;^E-+5&Z`3i<|c=%m*sUva@_7Y z;1Mzp&bahtv#Ht=7@`_y$A0Xk@otB!?5E$cQr?W=H z^7|M2T<@z1>~TDcpIkAUh(M0LO&c%p?0aKd%pKcQCvR@Ws^ZzS>OS&@YQoX{bEa3= zltsK#i`JN!JGNl4ATwpqSWUTnfmJl83mEC4jvTGP7uv{-?x@(;t4nv84p~mK6MWMU zhgr2E&#vFeH!ZP{q!pzPs_@dry=L8DYhA>)uf1KUyZNTYo}PQ4*QF@Y+hBXVxumxt zMuV%WYHMronpG^@UY4V*Kc3$it~1%4wyx(#R2FO}Rl_-8svIw9WpvuS z*UJq-mlMyy%VPAgI1#kZi|l@rV}vD52hXNhxQ8DWtZ5rC#5Do{yR<5NVeMn$k@!Tci z#wUnR$*)Z;Hlw+E^F|MxbpKM_F*{oz7wC{R?KBlT%sw@cj0_&>o2>d%<9R?H7%lnT z!ar%k(^y$a>+}7~%%Zyc`K77B<3OX=no)HFjBEh@L4oNZT65+Dw!9wNOh>c24&n#N zZ%XSPO}&295IJp`Z>)yycZlqnO)Ef(H#{ogULS0Wq-oA}Yf)_u!tsP^6T#^$-Ali7 z)Pke^-t)KU|^Vm+BwUT3!`C zeA3(|uwRj^*(PXUaEG=qZ~Od#_-i(N>+j33t$pefUwsdHr0winsI(x}d`F$0?8*$~ zu4glMA@Htypao^`|XQVn1p%DgEaLRTWi*|*1SR7_}9EB*&93-guKIh zUdEz|`nQuc`K1g-y@H#DNY44uXD%>jpF#dEXYq=GJ37MEIvW}&(wlODkY}_i>c<*q z9YZJY-Nd+Scq&-7obS4Q>SD$hhLBAE$liGYH=@}y?erUL1cTy=m~;2!4PVUTD{-MW zrKd>xRIjzV>#BT8E&9LkkTbj^R&zX+c@)AvEGH-$;42&jc^RfeXp9(>R9R1>#?Fyz zlPJwLMIEQR$|?yme5%DK5W?3S4Qq$>%ei`v5`(oFOuN$5Ph6A@Z+2a#tyiCtO^kAZ zu-AX@tu>DNDdg->xuP|1hJC=^5bpOWZ*F8KIz2I4%Hj-{x1=LnD&_mM;C6em6<0IR zhSo_yopdL;VN0y=13Bn@nZ36Khe$VNHXSsdDI61Kb9Nv$U#iQ=4@a9m;K~>)mJiUo ze3ow0)$5}=wV|5;y5otw`nvsfs%mv5Au5bv>FZBN$5<*fm?~fu%0zYax~16aek_ja z;;!#0W@Ecxb9b<|b8)g_Nzi)8pBtSI_u*l39mHh@4YruypookAefFsJnUvi68K2ps$rvqzox@Z zHF6hxgdUhV*I%EVKZQa9xXQEmLAw$uKM`i($%k)^Cr$UE6Y$W)zAOfu6Qi^*n0xmXH zrOy9n#({==-}2+M4fdxjU(16rl{JZGRVoP4pS!E`@W-sAV4Y$Zp@;aE4jG93X&@H80+@Qi-8rJA_+O!m5 zbO=SDPq32c0yCq+e0gf8j-jePTk9TR<817aobH29PWn5w*Ue*BgQV9VXnHiTlD37h zx44FlCzbB+Dqq`f*p5iLADNYtmg~5ucwn&XFU#%cm>!uD#;=%oFWWOIF#q)azPh&VyWvZxU%1 z>fgT;1|CB>1P8s)1?IViO%JCbq>rP3+{3i`k3TI#$7|!N>3p;? znkO-HH_B6)p9gwhvO2H4)_>GLP-?xPr|I|rk4?LX`OMK}LKlm~P+=ToQ0oiFRwne5 zTH`BBmIvI@k8sj|9}>Og$)`*x>Ho3usoD~aqGk*nqp#gGACbc-YaF9TuOE6_khJ*6 zSH9nXjB_6lcwXl)KU?&9c^}w0Eq4%6FC_N3L2@?oyy?q8cBuj5);LREjqGz$cT^qo zv`%2RMe>{uyc zb^4fo*+bUGj)2I}owoY5g{EjRLaalN*Q? z`M1dqzC1fzaxN?(hshI{gcfcgUUj-(IRQPO!Zqm!r9IaBa&;?@`=$CD*0DLqh*%DE zu@w%WKGJ2R9pI$53v$RMmBhBk4b}EcZtHIr8@5pJ-EA8%!6F|Za=AZ>yphYG*BT_N z+RZA&bTmL?r_hz~XRx&D9F2xHd;_6G;%rqb9Zv7%n(}_%Vdwr056ESs^Rr)Yy=Sz} z-K4^Rsq8myir7!U9D=URnfJq$sqzZYVc|J53j2v@|5TJ6^xMl-~lYD1@r=nInm`fjvQo(A@HPKB6@)@NjiY$|z1L zMVLr?b&!&f_fM1E#}JhvA0BCbroEP(M&)eva)%`UAw=M1rT|80>=w~v?h~H5O&fX~ zTCRN`Gd-43p$?R0sE%f@88lrT#F!anw%tLW$k?VGvB9)s39U%!FPlrJR+Tut6L?u? zfy=b@7?I$CQZQ0}7tthn%`d-ph8eul~geHIK@& zF@#96C9dRZPS(B%^!rmpc0^?c^wBOKQ`-~bng)@)J+7^Gc=A@IlcmW~d=FRuHf_;~ zD|PGwvg7esb!v~e%O&G7nE_9HgwE!tce7$(4SjbW|G9?lw>|ix-xfT$IlmxG(%@B> zs27lB{y6NMNu6$oO|m2|>`_~j4{*LC_ecG^FO*|QmI|!dktA?o%@0fMR6&J-7P?&s zLbq!4t%XAC>=|Qtsa%>eB{UU=bHQ>68nmwui7Hc8Pi5t1*`R(+{t)($11B3VF=3=K zrIl>>2*Wlp$9@y*hROgnKR)RHnNXLN+d13t7*^TH_~QYo*;}kdVnZ&qb6SbpH+`aY z6f|=0xRyS?no6Tsf%4MN)02t@(igWd-JNv;@y=UgQIk_GI?@3hN5jNPABqAV$>PVi z&q2tEbUNF`kLmG`%mP`(oc?9~!u7Xx>w78lb5{E)LVIk$7?jhehEy)LP&vQBRNv*+ zNw2wwU9zuB9--jX3bz)NPn)9CM)D%Uu2m*oqQb!W8W3)k99<qS3!COC~Rdj|x$gK9W zbDX*q&;4$hcs3fF2Sav1rSp_#K2M-Fy!V}9TG)picUp}K6D49kfH7(ud}VspVS&*) z<9^P3vB>Q`AvCVm(aN5Dp@foq>l@Q~vLCB0c~IZKj$_Jg$Q5;R7|yJaR3zoRS=GF~ z!23JdR*#09Z?;{b@K4`qu`7j`z>VE^r6fq^_3FWed%@TPy+9j22w>*NTnpp*AnAxw zJ)_1{um0?6Sl)T{&uA-r#o@?55Nf;#^efBZ8oZBH)hDyeS-z*+wEH%!v71h;7ijIb^?30JNF7h>zBYw3|22;{Ek+nZQ4RqnJ0oSysIIT z+?~xxt5?t|=`&Xpyw3Q@80;aFR#T`Wv5vv$b1t8Y)rTY+__7Eo==Y|VN?8MoYp}(W zad4+_Y0fC6o&24Ajn6`xu8W;FWy(?JCl7Kqt{$B#`-0$HLY>fO>aK8Jh--4V6yDIY zk?x?%7qj2X0WJ3A)CJ}}FRgwqO{NA1z1lD1_`GV2u2~5H>+hv$ktSLYe~bp>k3Isr z*XiA^Gb!ie<>0@+{yJbPY1D@3X(E{6GV#vW*OyO)y3`II5$WEh9YQDpC+%HRx(7F* zId7@9K6-kBr6rZvTlCmaPUG11Vv48Zcqv!2r3HvV1>1W67Egpof!FIVG`{%@+Hi(U zQ%)C+%+*Eq)r{{EHFDXB*rz@EPwH5u+?H+l2hR&JajN0M9&N6ddsIOtsRuHnBZ8z- z#p2uz010?9zc%JQW7{(kQH#F2=#o_1zI%TCwsmY1B#EEP7yoG8v~sQlH@G$>pwBe^ zT+FIs>a<#;Odu?v=tMgluIS4PRC?K?8gJ01ooVx@iY-@o7N*Fdzt&P#6EZX^{K414 z`3{F7nKoC4Q79IdY}G_>Xn@_rpN?|(x=G{97~?MnrkQY3R@C;(B}hnx;Zz{W(`jWA z*~E%`E0`CXGUT_8-)C+yP}ES)bqKxR(6b2_PnN?&(oKb_^*k6`ruUSUrK#^Kxy>|v zzUzj%WyP03;Qyo0B4%6>Wy6n%FkYER^Cw0^Cqm3teDnXPOLFYk^^)e64`0}{!M(jf zitcu(_(+0&U+IwrVa2|mh!#<5g}>8xMnnwOjCch{ObW$38(C6VZ;s%qY)Pc{^k`QUW)(IIg{azliC$BH&t!fN5QYGtHVe7 zC2HyBLHoihq}Ke5QoN^#^G%vD=l)GYml9iKw zdT@hEh^;n4&|vmUfIyJzAehadSQKduK10kY9kL_Oa3|n&a~(W4TRBq5^@e+05ZnB*3CN2LDp=7RT_JrM2b)lkZ<9dXpkd9$2i`SC z-5b!-vFmB;TKDLF?iP+ooWL?`03q_Y1$F_mMudK$vIL2RYJy&qYZr^A14CM(z#t>yv4H80kEY)wLJ#}r;;8kP{^(}c6S3R0RS6}FaK_7i z+Xn@*`3ZB{h#5j2H%)^#03pz6c^ha~*7WcH?Qt0?HbK!Eh;qu_xk7((DFJ}pTfO68 z6S!2rcr>mTb>0Y2ANanYOSQ}ARQOrl=>fL~muP*L3puF`2ZFGHPY3p+5m&NpCt{rk zMuTPM^=@BLoQU|;rk_89{ED7VnNj&%nj9?cR;rS%S3Ph<#O$j)GsrATvn*0ZUMc;2 zH{SEN%k9Rl`0%pDzjGxep1Td26N}}^_80y)3v&G|nql{(jdm3Pc)RX;)+dZt6O!dC zcScO&JyvZI6KKsmcI~tM+YqX~4;&zfIAj7q(=>3BEh6_OO{g?^!=7+Ls_51jS0F&B z@=u1SjYU6ts;P^CdreJi7+-}pfSVa-zYXc##M2DqD`Ojo)Ei-^&gYhWp>rP#(;Ot8 zaLbt1p6SWaP2E#0(S0XXNa^{Z{h9Jw*hd}&_Q2eZaa6Dy?uMwW=))g2Gr)8pRVK)j z$-y5bC94IN6EyD$??HW#@8@+%TMaKjzhUY+`hh-V>Ib6#R>=|c$qR<{A(9jP^a6ZY zAt9wz%uV1=>~iugY^WQ+*Js1tNi}?I=ziOW4?At(BmOIpvRSA-XU#oi;(v}*)7Z1X zi=UVjej?3lI{B#1d}+Qpb^g@ZvJvWNh-8Q_=H;rsx&PWiYmx6N(;L)1XK~ipK=lX> z7d?Hxw$~gR2Ak_E^N%)$$t35mOE-VfE2F>Yl@bcQ;=3lMv>KGdg~y&|JBbVBfslpc z#D(zcfM}`TMTD|1pfpFrFg@-dMds*VBKwGfyO{@9UI3>8Nc#BObNtT4xzfsg?Px^S zpu%3n5gcT|DQMcMu38Q^*=2yIFL&%=k_LP zBpkgf!}6)l88lm>ulKb=<7T_W1a-ffd%4zVGpXwj%w#I07mr!ur*nN0ekzmrc$eQlFwwI(F zKVLc{)3e>)>h~fRu;d}Og*{?}`%JM@y26<|GQ2MUoLBCxWWO?%*j-H+ni;xIcZ!nr z5=VV|OFMrKwt&I#!=+}c-U^*Ix10-1f6U=Z^Rk#Tu$MF^Ek@pWopnj2)1#wtwM1SH zJTf+p@Z#GH{j`>4l*04Ch2a{4MisH%HH47k+3e4CZC4PIl2tEL>Ag{G)_vP8V0tsr zUgPd{g&Z+QOEW#h*tfz~Y5R#R8D2)u6`sOVtel;0bWCnJG606>-?_T&%$6BtEbELH zbCaD!9K02w!BoGY;3X+=huEgTP#&(19!#YTT(?i<9Ot^_smyc=b~&pl!$7vSaOHf( zOtx7!dR|h`V+G-?VtRJP#FIUHTEyDWoTOHvrFG$)*QIV&J3u^vVfrB!H_;&P2R0t{Ru}Ig)~Vvr$X}VZ-mn)?>Xovagh=$o9M=vO@$;JN?z`|O@G!UYLu&tK?hr-; z`5uqPhD2Xs&tlwE6&Fb&!<_wbAX3z%AXbe$bEhp$wIUK?jP^KG3p=<=uJ6=~?B~Ia zmt8;6UK{u9;F*dZ*LC_iEd?rXN`Q6l$$(RahaYP4^Ko`wiNB1D6+8=YE!cr-wQNM3vB_Rbol&I5eU&K)%)r_mX&!G>} zdkARF**B?#q%t}lA1sc4CKg}eYs8MvJr}kOv2S9WA!I5M0m=K=%AuPDzVg@1;xqjo zkP^`bbP29hX_JmC`_$%Gm@)!ZSZ3&SxouugukmVS(k9bcpFZNp@u-a6Dbri)qQYC@ z>eiLJTs>{^Qh8WXh5Mw~gEr36dPvRZXyoX;_`npdwhy7O;F!mhO45HT6^ms#e%;|Y zT0YG~v2<2_^5(*`$oqe)$ zQZ#7bkt!AD+&b^W)Nnt591cu*=UEVFbwR1++ig>@<(=#oM!k68B zR!}qX8p<~#Co@;gXWxp7D+1GDJMDEn+srZZkBrsjBP&1)uU(_!LJZvAd2NAP>RXrO zBrC~mduE%OgH6LyPl?04TST&--v@std!}UdT?$O+)QzqyFcm}0GEbd|C9P*=si*PW zLw|YQvNrQ$IbZ$Q4TN}SJe!-$v`%}iba83bET(ag=ycN;?aKWlRfc}qU7mI%F*?m?;%vUXyIj!<4XBthUJE5rn-ze%cv_ z;Y@dNj~i_hr#%E^^*`QXLg4+TA01yWyiQq(A?qEBk;hr7gcfS_y3^~PA0C}=aGYH~ z{)C#azL8AsnNSpvO>@tn2!U5t2Rq$y5Z7DaalVTS3=TJ2sx5V18z$;KBleP2hSMyK z^IAlR6L$)m$wa#c7ZLRv-E}*In5GGT&<6i5DfXe*n$K}EK@?jf%Xyay(ci95&AmgO z3FB$of0UYPSH|~Oy&dWdw|#dXKF}7fhIAA@$Z5fsJI|Qt&A=AuS(>73UBCNW{$;B8|~h)Z)dRQK-rx~ zYh&}C%OrJ?7v6_<)YHkwdK~wZ&D}NGYAZ03OqcSUEHFaTu)HvS^VFH8`8nfL4Cf@q zP~;m{IY|Yt$QMURH4mD^O`gdf_sV~mcEvbc{TUJwB(m(xWD@JBA(U0Hn|i0=6;ERC zj(oiki%t$>lmvhIVV5t$g_u)Kx!EQfB`$U|`Ha5-D@b~kV6;Y0!U8D)&d#s?o&)sg z4@aQBKuF+QlW=Ppv!@w8Dg3EXV|ZY>8Y1IX^z}XbEP2)XX~7ZOw9|b0rKxu^(oi96 zp7x$D<%&TGO=N6~l)u;TTs>UH*uA`Lcki9EEj$xX-jG?i_~N;{dNv!*#25L{v*Q{n(+ad>XRHo}3cBOueUIK&rb6xt^e@K2Ovu+;e9s8>20S(VITY^0)CODvU&jh?=b!KZ;AUNKr13*(bonUqv@atbXKkqf;CGcC(3fL zto^h~l;I|kPzoNcyjTC>qT)^NYrgC+_9Pj#y z2l2_Oa!%B|ACt=F&?dJEbQdn;R`Q@p9H<7%d$B*h&}XTo?-kxUHCxa6_l5pBktrv> z^&qXwNBYK_qepXV2t)3b(}vD?N6m|sJ1y9N)4zo|w&eq0j;Ie(hB9BdAWi63I#%GK zkQ2AkpR8SI>~*-{UqAPAR+Av{W2^GldOf)&YkB7n26l_kGdC&0Yl~0Ar&rvgJTGD$ zd$fB}ud`$!vNXIngkb{WsrUYLJHP($ilFux6ZY8)&9udV8aWp&Y8jQIRq(FF5@$>o zI3*k`Zy<(;yibOzSLEL>FW^iD$(PWl#*e=<760;BSn~gS3A@)fsQ92?7_>3mnz_HN z^#ARzvP$r}Mz3B6{;7)G`eoUB`*#|+e_@kw>hq-9Zt?!<{t}0&+qh!$*KCemw?wUn zs&>wl*^W}e_f?>%`g(GZIS<#qi+Zd(NQ_4q(9uiPQ3^nQPUI7f5gGDYFe3Bz2ex>f zMv8_mQL5*i!(AvP7|yXCu9*)x1N#b8g96Hatpz_%H02lnjmH1C*YWcUL@!77TH50(`WwSm+;jyMOZZiCVx zw=AM7L{T{aaKuGqV!)*R`exOAl=V!$;mIeQYq3>Lv+s%~_=O6)Y`?8}`g54#r}mX> z>j$)zZQLByQg$m@Nz{J4Npc9X5`|2>8hv1IM$s?BxYbUlk3R|hRfz?AgiZ$@XlzXR z<4!-%)|ZFm0y*n2rp54&tz&nM(}D^EqG=?gsACsFxoUN>X7X0%?Ni7~ryRD2-`=MA zMT7nSz2Us>!e*hFnX(N0@4f&EJ+&cJk6G;2)VEAl3j8#xTX0_ySqhREh_*}Y#y-VF zG2GZHOxd^dF^spVi5mVW!yvZ4ol_U=)YPW}_N~|YWxinQzP|F5kzEA=W`C^nkSUPq z1$$UUn#=I1Q+%-b4S8vMi=eX^O@@WVnT0X@m!w??mZjje0e(uivSh4J4PKf;zY z2MtO7MaSs~YJ(%deCD5tb2&bL5p?+_{K%4%Me)KWK_U;@?v@%k?5*`Bo zUV>_ZVnptp{%R)(sDFwO<_rGVbHottsVf+3e2s&Mbv|5tCcAJJiawsIqXWgRo7qbn z*6)kH=!mY=#1)x_ve~?$a_YKuS$k=``DZ>|@7&WxieVLyXo?W5{hF{kT_Gk31YEXx zZ>|O`oMh!9ZT*n@f|LYd(0&dWs3K@cje|Vx)F1(8E#n;j5SWqys7IKT91T3T1~#HU z&TX2TRm>`eLK2r)4_i@!lgf#jl^!Hsa>#kuWA$4tLuKdMbXMN%lY=*&x|;RJ)N$t0 zlx(>vAIcf|94is@&)YGm86mN@zA`gWk{!|oX_x!+iVUtpDClp-*&_3fnNv-5)|b^P zfBy-klU*IP?@Nat;UIfHDcP8LAd1?m*u2+?;n)i2O$NnkIZwVf(CK)K#mLz4a#zR{ z`!skyyJI<*MuCVd=><{f%?J83b67ITs(U66JA{AC^ELI`t?XME!>jH}47cH%6QYi)^^t6h9{t@g~f{uy{wPsFHz3P3}K@Rz(A1haP!EO0LX)ZbtQlyPH#K#zUZzVl( z=gLGIqQestVoK5zv>Zg}5bV)X?j>0#ZQs(cl=`}Gvm7nktFuxwzh`(G zbs`fa7}LxQhNND+Q^8j{i_v^Qt7qPaedfr79e@}!3QuK4%{E!t%Ad9xMtI; z?#O8rzINvNY2beXB|a(z9_ioCAbFRPaVLKN0AiWB7nj)!zK=Cl5^WdQb(gqGy(8*g zorz=mZD=`7z|M}%cG=zkwlYluJCy0jH_@e#c9aI@Mmc{%=KzYXA0@Z(I&7r_Xg zs2u3r7Fl|Xrd)mP`Y0SLCrhuS%YYwGP+@>F9e3S?<7qP|DzdD4v-_BO!EraPeQ8b? zkD%QaVFu<)>H+4?vOk)Bo6OEUoj9r@hJQsT(De* zGZ6RAK-i?E2yp9|ID7HQ-q%#>iOO?5EPPraXP$-+8&+?8Z+vm?^*m~2EMW3n^t=?Z z*lcW`12N{*o}~D~2=W9p{mbNnS#`xy&`QkP6!FuvZ=6sj36;Sw;y+K(bA1o4A&}s; z?o{4rexW&a;isIc$vV!J?YArR4+2+{B-|Ur{SU8lav#Wwr>J@b>y93@2PKGG-@%)b zpY_xfccCg{&(YN100mX20uQ3LZEe!)es-dtrrGt(RdMhaPTky}!ueUX)tL?~Z&Mzv zT52f-LvGLi=jKN(~BE$2_s0Q)+XQhy(q$VVA- z8Pt~9iFC#Qx}60wUt0L>Wjh|g{U(i0^N2vzH*ZjoanB!}YTQOi|L0}#yH`0yEQ*fc zIe5;e320sN!&j}`kXliXhJq3LChjtgQY&4;OV~mJ22HUNV#e;*5ZBZie*nrW^Wf93 zd047I7m6j@d)Cz3PNly7__Y$Cn(hY?>q{VT5D!-TqSAEr_g;{_4Up#L{rmp_(EI8g zsel=^G_E17&y=NSJ6(iW!7(o$ayYBtTol9iT!;U)tMb3+CYwnc_RNxv9UA#d`$pbA#(#ktKMI*}Ndp)V#-iJ)NR*EdS$cz? zXT|4_;-+QafipZ!Y5sa>yAt4)>!c)$ykuOM4m}4Ilp$VFoGcz+foVfonWwH;{)xV z^C1#!Du+4nd*gh~hMg1>t8-)bKTy`~{otq68|0YSz61g~5xi|Ahxnw9Z)ClhmWs3^w?Q7YCuXTEaz)DG(( z+YQklQ<USaTZc-|KsN>LU=SXuv73)oSDQKqU@=hm;RlS z={3XN?}9@V6%qLHmg-qxN#tM8U++9z$APM9j+2s@LO|eaX*p12+vq&iaq6}<|J0sK z#rZLi3=y#&lANEu%uu->U#Le>Rht4@Ol7kgVlR|FN>QX z^;p#0sf_q=zU9K`?r2e$mQP7rS^!HOdH?GI)mg{g51{Io;ut;YHB z$im+kV{1S_KRw(5gC#CthuK|5yvodf@P<$#x<{n7iFyp|r}2goRpnCZen2VN z_dobs#lyOm(9km*Di7&<&3d`yRvvm(f76 zm#OuIN2xGHQ-3xnpevUJ1|3u|+9t7MItSbkX2~~^a#@hN?Ag3>xplIF77xv6VmQ;j2|f{0eiczF+GsIbQ=TjKow*=zaEgU_XxM86B4`aa}U*)l-`jMeLEA zv*}=iMGb?x_+N*WYnHO8rGs_>6irlY(mN8}W*uwAnXb)vrPGl9u!5*zwow4R@> zE_7O%Mh?et^Er-q(GCD&r*Kwj0-Enx%>v6Gv>zwfJ^o|Q;P)ex^v`(S$Pi%r9GAr} zC8nLH2@6^VfIT%JL0o_R*P+C^jyrCRLI-@2f6qhvlE19b@1OQve#60ugFs^r#9o-k zdoOa0cQ_B)`mHPs4_Bw5$aB`H0KW8TBR$r5fX2kgWW>*&h7hd8~e199>M$Q>H-;}cJpz*oV z;S$KTd@%fuT9c)J&LJ~&w(8rvdJKfW#ha_R)=g9eKVNaKPQDBfeO3|xaP_}p4cNLs z396FA<+zZ37sfRg*1C5wS@A+pD`H#hcYeqBQ|KO00@ zX`krLZl$2ljw*1@xXN>_ zf>8MWp*U^>;z_)%$L31!JV`W6(C+J%nYP5o$g%eaZ#ocf)2oo%SPrWf6CiRg0tH-! zMj%CmfIRtkrBchHNawHy>})e#x>wV9Ttx>^eyo0t8#@bZ_254P(ML5A37OL6)5k z@u|!&D`-1CdI0E-&cAigPqPKtTSaft9gxEE1KcQ?BMUt)8LoDBHpf>KXJuDHO=s_Y z56ED@D0vBVgd-s>b8qZY`9vIRW?8BLZw5~uK`{W<$Ea< zP`N~D%;A5a^%Tx;pa((%PlrE3$rAOr#f8OtWN}hZ^^v@K3v$dS*I{>6OBmw8;ukG5Tp!x=U z-PPQSuhBgKiSzbzAm(B3X(UhySv~}vY+CpX+Aiz?*PS$?MjnqA`e3Q;s8S{5-ey5o z5KxJp7i2P9LWjB1|FNHwJ{ikXP;AlPp+3gn)5fCKHLo5o+%>OvLc^0UdMRSMs!(zZ zkfs439gNXzfeV|rfYtAxZZo=oNt*+w>R?XMxJ&I;!?8(yTi;k}wFDzO|5iWtqGL9^ zZSGu%4(UCso9YFZZ+9tzD@%wnKyfS1!q{0s34xI?)Q_uE>G1>i{Md{^C*NnO2C3Yt zK;XPP^&mUYt9K==ZdrD5)g-PJA4C`lHJ3`$zT#H<=wVt*A3`Cnf-Zb{8lm>0*>(39ox7~R zZKkRVMCnXJ<)ih#m;FDI^a&xmVkps1i^M`%at{ll>;9`PdTS?R3M`X%m&x#!CH@B& zy!CY{JGwsEeSQZm3bX`)@*B1o_8{=zo@i~@3dktbwvY9V3&;Py-hW&EeO#BQmnK?E zU!1sHaaRjCsci5?g28(HirpP{AUWvCxOJj;J@l_37Ey*6N45I*%*;QA>Z1eK^w4NP ziInqRT8@YL%~2waXpNi-ocP>edFM}oqs*f!;u=sZa}WyhcTF_E{hfG_wF1FnW1#C- zzQ2$5@7a!oZ8QVL<|Y6v>@M2?a6>|c_Z;A_62OrapA2tGt-SI8gFU|jpQ;Se&b*yU z_w8xF$d<|Yh61cmcHn>emTg{AjC~lRfMV0mk6=F{Y_6l#MZq9vX%~*O&%fy2T63?v zFzYm<^&0={1F3qGzJt{(5x{PAke1@fec;xOn0VClK`u8`oDW2D4v^DFxwlr2^E?bx zUYP0V&aI(uq1yjptAtQYWdDk>_5bjhzduIy0cGPD^IX`s_0|7zC;#;yoRu&-%uMsp z|Nh>8KGmxY)|kFo-G=kO8J!axGo#+<>VIICe{8?Mo|?FyQZ z-2V|P{KJ6$^;CJd#*gp3+FP%`!odIir+&%>*1FcK{|ue~dV|0J^h61u#)CBP?SCeF z{u;!8{0YMgqpKX6g$uy{<7fWGtmUFGg2S$z{#D6^i|Te<9ibcaVOrn(Y5ONR-|D|JQ@WRY6Tja02Dl_jLaW z3&=~BnD?HQn9fMH7^-sJJ63-p*g*#F?kTbysuH)!fLs9u(~Xzl&JO z_kpo@z-<5q%K-rFWi^cJ0}V$ugaPv?;>wH(Bu?w=AHBp+Ze>`J8xYgkFKKDjp-4*{ zS+`UDB{m?Z-4FlD>aTVfGJ}*zyk>2j6$iI)fjoZ*`jc4I9kqWhQ3I)cWS(C2phz|3 z^8s8&6k87u`R-w5_8*<#{B5@qMkpw3gbRku+Y-Ep1u|8W{Jj;9=4#)b|A~d*y57UR zRR5!ull7v5kQk3p`OXutGLOeaiCUUblElC$R~l48$ge`hj+nn4hDq>4pLd+<_+YsT zna^`H1Kvmb(Xy+MfB6~7?X3m??gZQ#t?LnP>i{}K?$FdCd5YK|tZhqdfP@%sU8BT8 zTXW?`Z=COt!FJlcMFzoAJ&0qSLVxD%WhsDX@89kGzr!jz^}8T9&?q!kao!C9n17KQ zU)y6kmx+G55SoX5?p5N{hVIG{HrxMAfUp7r1mn^%KL!pf2pH^S)VMH!q$8y`OSZ10 z^?@t4v=d`~U9t7=-}o=%sb};0twF%=(gl^-DqPac>wIG#Wg_p{G)vh(Ialasb{fz( zLh)EXz`8j~IKi}@R0sKhxp1VFtql7`hYUP$Z$4r1qg!mpZi+wWJRALYam`;KhVoOr z{$1Gr8o=(Aj%?`@P^t1IJE(-H4I|48Vc$IfJ#-&iL^ z4Ps3Wvo*?)78xk=fBrjVZEVr2KWVpuI`)|!3O$9>T!st)X=CXo4mc3}V&EaccWk2+ z&JAQdlnR?l;B#{z8(^xE_0Aa>N&A`Anch~z**z##0qiyFYIi~j{9dL{D=d-(K;r`^*Q5GU@qY%QWT?#-pt(5TgiABILAxYKA~YP`*$7*@08D z8OcEyiiGw}D2WWpy&|X_Lc(UW9Q_z5Xjz0}n_;!Cx(8A-pG}BBbBmMF_OVU_re|X) z%xuw};+I(J$dcq4*@;cy#&A&1MPd5vaMHj8;WzM5i00HLM?2OZFVhvKkI1)gmFlHv z1WE(p{sNGCREP?cjd(wqNF+STZFfm_oaqs@8Z5)>Y4A23Q}FHU%2ZRaG!nBM_?m0f z?9-yT5DQw5_k$_pQ$8$uHhHGizz_^jDke-IkICb{_<?W-+A|>269|MNWO<5k_w_uLy-w3WeVge);gsJ3IAV{aW9HdNy_<}BA}A{g3Ud}0;{U1a%;TY6 z+dnSlNh2*9DU#`Ql3iq|#X1;ccDEq#p5=DwqI>#XUHk!dG8CywB(Qu@)WiRI( zRF)P}Nj%qG^m<;upQrQt^|&=jdTM1 z8nz`R_wVdC&H9bYx-n^!^!FvXtPGi;b?y;^pDhs=clZ+QLW>quu9u=bnbohQMAZHB zY&}bAru+r-lmsvW5gKUrb&}W`GH2xTaArvR75q4zLcdZBhNIcfk55&v4;Stpy0Xm( zHMbJ(@52+wmHV({ilbrTeLU4{Z!tud@eN7x2fg7nulCG>K;8RTkZR6S@(Ep{8136# z?lnTKf$oOglX{|lbTNg#Pv^^11ynBQ$B6??oSxeR-9w`gPuvyg&YwiRRw2?=^#GbC z+>3H{w2nORLeg#JG)PmhJk?SzNE|zEFNfrF)Xtdf24Qf7VIz4x4?M+Ff`wQv_c7Ga zI&QBM5HM0)QO)q}sqhKGUQq@{VThP-NoGj@F{YCh1DX~@XzkezR-#Vsi}sC2(+0HN zrc&LEb80h-;?5$ntrI&r`E*y0nW>o2OSy`viCF}Dd!qFZuJkB#3=&51p zGwK%6RJ)T^HVKWcv$-*+4&r1P?RlqMMWeU2`t@NOvz_Do5u& zJ=AjQh9^7{Q4VqI8MA6gSjhLCKCH5~i38W(vDJdQvC1g=qt;nr6s^(mhSX)Z8i=(D z0%@`R&2a2`!1?2=1xU-uUyZ4wbyqHOr8Li>{%uSii7F%>w_6|kY`#qz^`UWr^so*P zHSMCMun=;DWQQ6=<1wUj%j+%YwC#R>S!b0W*5u4Q8H$bMROG97C^8IbIGa}5ej{qT ztdJ;y{9^yT3ak5K8Wfgd$#e>ppBym?l!*e%sNIyMTB2=T6kuL=+wuO{s-(87WG}s% z>=zkAMU+8BY|yA+zpLRoHhcb7Tayem;$4ZZH9rrz8r(3P+rpFu8&C+f1Q zDIU9hKqz-pXPLFR0;vqQO*1$=sV(#{K~7lvk#eu<+vMar^iIgBTOXFq2#WI1{LsZm3LxoLM?}YUb++n5H(0lp)C_GRPPuK0GG^#v3K?F7yib%Q37NzzrTpH5>9B@4 z6#5quh$&NX%t`PI1&#N1u@YS7?+nraNFWxWL$O=uC)zAtWc!;FI9y#INjW7-VX?3B zp8Uo>AnYzicR$zCX1ywcyL&Pq~1&E7P`@&_YJ+mSNZC*BxqY}4)&p}mi0KxCFvqpcMs+yXjd zEIVeie~Bh=OMZp-kBL~;$+Ak?KEXe+FRXKp(IQ!ZgwFY}#^)rMejU!(H(V{zLGDa6bf~>b_+w2OcOZdSrEf$T`CD%Ad z7$;^Thk0v*n1InX673>Ny|67`;F{L-lw*;Gf{!UFqd9SMu_7xcmUCJ(>z&25T9+u+ zW=rKi%GA;taBOe^jo*9Ysfeb7SP@9r2~#oeRA{k2I1RJ`Y$%cWf%ORef|2INVHn&Q ziA}rVz=|4~z8}DlDOi((5CNQRy@$wEu|@=w-aPs^UIwl!N~mgtHq3u=(@+rW1T(7s z+`FJaE_Puf)9?~2mnhzo{-o^mfY~nw6$2_w=N*mI#5eq(Z!J6-n?tV_!*O;{TL?5=+Z*Ql{SPOiv0wn3~A>dG3yXBT+$1eiT8qZm3@z23Lq>3@L}sm} zn^1>f)+dIMg`qlL+n~xGc7W=k%s#lwWxQ6^yLSVfNt=qnVcUdpDfE-MXrvl&nI^Ps zL+8gZVxsraCtF$l<(#mO<6~0EZYzbAINnu*)C)BUaABR<0gRSG9=@Peu>buZ!tKVt zQSkvxXrNU-99^AVY<*K);M02xQ!e8@*Ik9)1kK%{d>DhlCKpFN!0rwaOA^k%RF9hK z;IZzqvHuvE#T%s!iLV4L^2~oN`_M09nIySo9HrxoX25Thk-H#0>@}T=& zY*_A9I_?mNYv3gFldp!PRO@{;d_zI}CNjZLC$V#t+KY(fo-V+d`NZk|$>`f>p{##6 zJRJ4yfj8dp(Fz}k`gFY`PxsKl+-U<*q}K!NxCd^fyC}Zd4VzK$Y53OH#Ox7BOY^3~fyt?@F_2+T?l4?QFzvuyP;?@bF zvyc^CvCN@H+l)hJy8_7K`=X~{9;BF@QJacC_>ek)i#Znw-`Y!hQ+`%^_?NL^wi!@} z@yBXZ-CBMX*a0J|K+@?#cb@b&@<||BqT|{;zt5gr+5m`*r7s zG6DJFf*{61#q}QGOISXYR6A2w(^l?fdmP1`xach;+L?EZ7|EI3h}6@h*=%>mB!@6M z-y_Lg1#sAiC^$t0jdnh*u>iY%s(QeY3`09WFN52Qp`Et2>o%;PnA8d7;8ClO(`d2+ zoI8#88SeHtYm~%{hdQy`Z^I0eQD}7rk1));AQ^OmP#BWoRRfAn2U3Y#4()Rz1Q^9fIs3GB3& zw5X-upFV{|jYalcES1!`)EPM!Owu)~_MyV4&-Xq*jbVj543?56JQe2mUqYohvpAbu z1#r!(^uU&V3FlV=vEZaxl!L3oJ23 z@Y?0h4FVsh&u`Cgh2o@uPmi9HY!d?Y{WEL_nYXd^1DU&FvLdA-Ee+|4A^ShYgx`V2B&WQs9xNG`l)A!U z`dae=!FFImPoGQSz5I&Hxfh&VAuxMu!eZ!66euYTAT@#QN zrU3O+6l5Eu%Ti|~DS{pn%kuAD;kI`;UJvA>^5f60&G?+wDJOpQYgn#S3O__{*&JU8 zl&oOe8CYOnM^>oL!yWEz5`~ap_5#0yZIfjkPXo4q{n^aJgr}RLF58~%e#qvaj$j?C z04$5YsVb`Z*HceN#-`o-Z&&g4)(PV(8oYr-Nw`ks_GFwM7IS}C1prX;Jq_89 z$WD1T=`8aP*vl$Ivq}cI8^^qi{_2vj>nJ%`yGyVi;(nO&jd}850Oo40XMTR+y4YQ~ z@UzHYwwrF?cD{-iEnp<<&)nSydG5U}JjIPk@^4O?ftw-&rL&lL+-3j^UsdAOpbF=q z1BgFlqroVpcKa|y^B9Ner!Am>=yL<0iZ21@IXlr342ieLUY-^_lk93Z;zmU23}3(I zw@o|-|InGcyLrVm8%r3T(yM|W zH>C7=TnheuFcEv|34z1{e!O?&p^O;!tsiYpe+!5o%_g$jf8LKYZCmEAK$-#^NtaQb zesZdd=_K^+abDj74nYkz!aeKKZHoq!A)`gI1K#ZczRl?^}m z{_HHYrK8PYjU3aI<2NoIT^GJ!p8MYT`bakZ^iUv)dcS3ZDk zq!ateChB#VF%c@CzPZPs=%MG7pi1k@9E8dq82Fbm|L8Ax<;Vy~D0o&j4lTUPfB6g? z+THo8z0)fRD%WyQQjbpTXz5O39|jLw;6R1$Umz*6;9zV3tt+u3-0BB!Od{NY$DuP< z{nO>UaTf$BPa!+sNW|O0cJ+a9R0>@sE8tdfb=Gu&Embi{7R$%}ydL#MZ8 z;^ys&s8uvp2)yNm!i1efmrax?$zCGh%ii$?o( zs2%x-FZrL#Oh6CaUP35c@&EWgSvx@dlD=@WUSVFp`PrxXabPUrozWWHo;-Um2iML8 OfA;B_=rXkro&Glv$Gi0a diff --git a/planning/behavior_path_lane_change_module/images/lane_change-lane_expansion-with.png b/planning/behavior_path_lane_change_module/images/lane_change-lane_expansion-with.png new file mode 100644 index 0000000000000000000000000000000000000000..1793eb8f6e691e11446cc50ab2f91e78c027cd03 GIT binary patch literal 25187 zcmZ_0bzIa<-#@B?(w)-X-QA6pfaHRtba#VvBOu+<-Cfe{(ji?-ch~uHJ@<7#zu$SC z^AE8*?9R@7X69W(n6jcY5TNeWMw2izj^Zx1pJ%>`vLg+qyYaF`1aQEv$WWo zigALyH*ZMZ$V!N+x#=Bdyw^+^xf$qe(DW-JX_zn9{L1aZJzqZWH}4-h&*;)PXH&UM zNE04VR0JEI5ajpr!n?BF$k5d4C+D`~?pEP?_@FoXsPts}V z@_!!=>^h-1J>E9)Qi>Osm^%q%a7Os=3yO(IB#r(bzrjAfeYY>E5w0e(sM~d8>)Vw; zF)b0E&^4zaJNT7V{l8t2F?*LP2>K`wMLSiKq2J-vy*Ut5ZMmzc%i~KVBqVhEEI6Dy z5O_SnY%Bb2JiX{kIo@J}Wr$&4gt)XcOepMop_P|yYuTWGdmboqPMIA9p?m-9Q^;JU zp25`4*zLDDCgag$v^xY$zsyXc&%b2OboOGK5a8j(;tLdfE%}8@1xQHV=uKpj((vF~ zFEs?^Ct^8lk22-bi%N;(Vf|-RVx8d3C|g$UV2pm&vLhd^qD1sZEgY!UnW^C7;y${7 zXL3ONP0h{g&);F-#O|IRZVs21E+&L|9Bx@|R>xg1YreU~lU&Q>{clevDY8|ZBq0f1 z_eeU`X6s_pmHNcjoBg8t`ocAhNlc*MceUTnHu?~}9Xtcu_`$k**hX4B3y142HlfY=~NE$T-eytQ@g;RAlBL2 z9WUBr4P>Lq&b=53r4qGb4v(cG0h3lY znYE>*W#jSg!fkCIURYQ-FgUm$;bb6&Sc}1A=m%vD5xTY(5+YBpEKwCa79EM>&Zw|8 z_131efcH6c;Y50O;z-gND+ToT5X5yBTI&9R+%mm(JWGwrfS$mWB2c>*!*PQA|Iw|K z*KR=$<>wdYjb>6gS=iaXCne$Z$KVgpfWt1DtKlG78MqjPgy zeeSm0WDm7mUbe}o0=s*5 z9QkOmaTk?%TUTX#?%H~Z=Ua(wrw@&C_8ZSEL;T-UAK2YHguL$qlbH1#(xhVu{F|G3 z2?z+|I4!@_t1B0Qr+T3Bq@tnAKc(-i`QdR|T1+wMUqHa*br#?NNsTn@`uYwfCd~ho zItlc%&AV!JP+tU&^aPQhrVQ_=tno|+ItmXeh4j!3O1ZCn!-@8CYB2{a%ID94XPfr7 ze@KDRfDsQtnJXy?K_SYvPUAA0E&Eu&$74oliV4og(rcFa&zcv>C1v?*gWRUy*;f%Y z4rifSCZSPn*!T5IKD>6lO%#}mi-6DA7Cc?tQBz!;$1yG$WkGS#a!|CxIC$+p9DFq?Y|}A*QUB%;w)NjfyFY^LHw6U_`9T~<>6l*jO`Ij zb^4a*^rk?j_Wm64v=6wpQ~1HWHHHB_Y*vdt&@SXHdEy5jSlBrHjsk<4JbJKn<~~V( z@dojXY6n@jMsI@0mPu@r6_Fh|id5gXa`BSO??jrdjv=ph1R0#n@-{h65N?;cik_x9 z;t7H%h$2!N`h?TI<=8_x>NX#Te_(`J-w5Mmxa|L=4Gphep~r@Hq%$`lI7dyR-%f9n zxfJMN5?)k)aTdQ@q&b3~q*x}I@;S)g_qz$*n~RtDq7g$~1Q?f5@gux~M{PGZXeY;+ z-`yD(D)pbuu|Wy2s|_X~AK$V5r{wytP=9R>!xJI79^OxnaZ@xp6dRN3{DyX`$hd!6 z8JAoj^Y8z5)(Dy32zhHyn=fVs<>ppS>y@YpD^|&(D&YjZd$>ME zVs~^@94z#1O#e3C`{a33<$mx57k|K~&=n07wzo;!@ISyt#DT2Jd5%>%^tgQB%xrlQ zQ;z~Xle;Ms*wKmZ&J2ft{w`y_F+tx`Jg12ao0Uwb)e4=j-nuvUU@-;hFeO{Rpx#ktwvD!dkFo8g>cXbh0+$%Vg`%#y;I%&ivYvBDw}1# zYac>B2k5)=?T9N~EHIX(vBUR&0a!U~tjI?Tb_AaZMGMLn>}IQheWVAT!UzcsetG`D z+w>T+7F}YGDx8R69erP1EQ`=3oCZ5srFvx|tgwoMZ`|32cei0o=dsn?mU96zZ#8nH zG_a-N!TDDB3%RJED10?l%fjC_@a)IJUO(I2nf2TI>e&w#E)q#HE2xz+zy9%iJD5R@ zQlOaDpIIS`LDjXoN^Ch-84?#4_a$EBjtmV{Ek(usFO>Wf{$^V{W#(Wgv*K{!@-7qP z`4W_AW2(l+*i8>Zth?lo-Uol~nGor-aj9M|iL)Hv*F^Pmln|;^@nr<1P~zs%J&M=; zNh7Rc<$K}A!JO@Uodw4iu=suM|Ovpzfx70z46PUoK&q9EPBHx@4D%>EdnvY8B{(t{<#E+3FHx}T3O zlv#Y4%5)oHHVYYhE<#}9sGKe8b0Y-g69|+tt8#-b$Q=ucmZWGZ_0k25-dD!9Iam-< zZ`{FL)3o?#lH#7ZR@yCN9vD7 zC&9v%0ecyK*@NrW@HGKXRNVCik3o8aTedD$5@+kWhjYl6b;*+N4PM!d!VL<|G!aaT$hk%+p1SSF;R4M_tONGYZ9t)f zvO2OlKfY0{(VzxCiLC6!W&zWBV#>)13`wB@*X7B~2P3KLuZ|mpdI@7Hn_TYOO#c!N zv9%L2U`Qzk-VFKA`OXc9d(cDw!$ic^=FmbDAwQrhC7qsHim5r_{)2~ZTVZ?UoDvzd z(D7$02R0-lz8YCZTodx0RtuAol4{o3kv7;a1;ZB+h(0VqVQtB_V+LZ5&L*<1HlA(wvUDO>7(%V{w?y(qO1r)R0=kn`{A zBh8io5Hg?BHKmpHVYS5=UUEuG_s9ss=0Mc87c|3QR$)-nV4u_Sq*9dm@x$$a?> zszUn(klqxm_ro<(M@NTUyDzc6xcHr)<>JuFpFhe+%knlV_u%)D$o!I$pL(OsVK+Pi!X{P- zI{_gYE^cTlP#fMzQ{H%pChCOzH0SjC`;*ky8HWpvC8WxuCKSAF^vnN;N8@ z0oYunarBMy{~I)4U>niHYgFn*)t72?8;IFXSLg`|f#N;?T}ZJ0ouL3wz52_{PNm?| zC2wm>!0(gZE>_1e)zbsD*&l6Ui{aivGg?GL@k1tECC5(BD}2Leu|Qu1vU(|P{o{?Q z4|74o|BFD}X}UKR>Fvi$=1C2vOu?!i@#Tm-&l7845@S15{&#L(Nf;&wjgPX*ehOeJ zRd25LXTCo*+5ee)sm5o-I`_yB_QYn^YkL#)F=nSC>d$5^VKq+hdDjd3z#R5`d{848}DZdPGn*}eUhF(9Z9Nm zd+fz%bs_#86fw7UG0VKds}n}3qnJlfWcmfodWl1{IyWdgFP=yy4juODZAS>T%SE5i ze`}5;4)qU13wl_NVeo&4odo&^+gmh{tovoJ%l|eULPZ598VAcE{!5Yn|C*ipIwGvo zI>l|QuOqLz5?uuvGEZG&zt5SEQPX>2&HOFOGq}4kK!A$;TeJgZ`$4$_#_&Zjmd(WC z@@S5j_A!9G1I9P3>*d;8iS4(_|M6~tBDvHe(dBI(`mr0{GQBr9q-bF)Us;v^JJ_i2 zWD`XUdeq2Te(bM>E&mJL14SlDNpk7;A`>;~{<8^*z)~2z1Dc(#QP%C%&661|Vus#k z{`pB!aot1Sv1zHfQ6pRS9{?3d4gB%?0Ew(lEVZTFFC`3TxPD;fU#a?Efbs#%Js>NK znCy4_P_-=WXOi#H$io^%e#7b|*;WfRG8uf%39MevOawVYzglHI9Kz3DyX7w-B_g3g zh9CRORMF-s;g9TtFnD`&^Lqxr%i8VP=IOUr?n!{Zp@ z&7-A8fZ{L$YdR1hGC9V@pX0_NAom#Lq}Kl&(m#k^r_Od1J+W^%_W+zH{mO8d^x9wn zP~`;q^OjOBLBxZQ@RwX7oyr2Ch7oWUpkib9=N=5M_h@$75F*I)dwOzM&PJ9hn1M}x z2&&h`GP@H$t#%HSYOI`IUrU*p(U5WPM9@d}I_QUEGWcBpOHH@GIXjEflEeSyFr$eG zW5h0uP;AYXiX`{Imgq_Uk82RbY-V zI1V%NR5+G9!`0bx_BjzVDH;{d!S#S6rnMfd% zbavKks)5myNNohrB^KE09CsD3TVih_1f8M;Wv;f3_I- z-W(Hp-0TNc>UVUx&oV%E=n}JeLBqKtQ&Sk8E+_rfMgy^e(#Q!+pwzxF`|)%DD~Q)5 zj}Z%d|E9OKb#r&`o|#E}uL&q!;2IP8Yo9QP9Ci;w2I{+^0Kd=*W7bHxxv+Gtj?LNn zh-5w!csvfPK>*n3mIVFSqgF`vvz)8Q0s0RyG!F~MqTc{yttPKMbSB*fLyiUlT6-^x@SfP#CU22u~wHOvn6k-zL_MkE3BKDqs;2jSceSNudxOw?y8ns;2YUzaxHp0yp~lYHDlu&&MRo#A|w; zuD$(mc@SbTQSC>_rPa;js(0pO z4yF9c8rK>zP{CJAXw)Yk*t}l+#tt+tcrL|M&KfP;fu_u@j2`7W&_ z)xDweKAX$=vBVN0uJC)PukZc0iFDDBXhLv_vn3!!N+8_)7!>flW>|W<9KvYxc}fjp zhGV6}44|CQT>l+Z&lLl`)Li>brB#uz{3Hheh0*|BGO8dD*Sb2A8c z5wm7#cMSi!fJn$GR8SApqP;HORKe9a@{hvezbYppF=yMC_DKJ7e@sh2NJXxcDUi(J z?obyy(`dWOvb6BA)%8g1q{Ex_>zYXU7uHGdt$dHWjrRxvV`*H~sKe$~WmszHh9f^2 zL{sa`S=|Ovw+7>&?k;wBQSsquXLQ*m^S2m30&=9Mw-ul;0;*^EA!UyJ(Y|_Qb**?Q z@-n#28>Rg4kq`%KI1b(O=CHdaUtY^e)A^u3K)$((=j^PzrQT92*<>sgi_>z>R8%g9 z4}NO7#Xa6}hUR2!ejb-n?x%4u6&2NBGA%}@B7?f1N{)VKu4NL_e6y!(-7%OfP>EPL zKrEoccGbb><2ICsfcNlqEXsv*!(y6e4l7dZ~uv zcoNt4#qNaJTmxeWYU9a#PW?bQ(fnmLv5*xm0tYp9p;^H8wOPsv%fjSPFJ<&j-|Tf zuSe{yHME4&6IY$Dbf1t?rO|L;H7=JIPimtXTK?4KS{j=<`pH7Q`3Sa8QGfoUELif| z`~EUa&~Xcd4*+G)h&tM>;*{exKbBv8gK)KV&D)K-n-7=p2qnQt_%$IioCDFl$Z#n~ zOAR?%7ds55nDkF-NMtcaGIlJU1@EBVtsNXh0Q+?9O`L#XogbL2Ti) z$(_UBW=9y%{X({;>=AStm-By?MH2vtuy8CKlqlY!gOF9J&OhWt;c4LMcLDO86#__J@iWz+Ar3GU`Ms=F6>b;Q9Q)YJV!DL+2e3g%2|NN5U zd7DL!GEo%5Q9hSUQiIV2|*J=|VSh5t&9Hn#?P%pdu-f9cd7?J%z&5dXvPUbOqhlqs4I@T>(dTMNl z2BLOl97vfeG!V8S7%nb@P>`~joEs}<>Nj}tR+>gylcGuF9_);z;d1-5&E`g2!`IeV zuiF(YC$qLSi7tuZpZvICQr#KF74qUa-ySKPDX&vGIn=6EF0}XLu$hr9_1q!@Fy{{( z|2+(;-@8%V*yW3HYlIl!#5M8QIwWQ47TuHOo+^VL7UxBd>k_lpOZ`L{u}~&>tnoDV z5ZA0MF7K8vp4ybyU}wWQhn4T6{j)zCSCpABwabhx;2j+u8T6~k6yupmC2&5rxQyXh zEwp_!8i*3lXmPHu$p~C$`1UP%#ypy;oZr$pMwbFQP~;HKO0N--u;p4Rl>@F86y0(y z>D1>VupKQSCz1ha@jW4;{xzXr^(KELAYz3||MnPqjq>n@l(L3+ zh8zi;a^rMPOKj~%n<#)m_qy%-TMz>ZDSwGW25Kn2|DQjVMVb`&z%h-Of%uWtW!TE8 zZa<=(pWEQ>9d(<>UXaxS64Ac`KxZtRHhaizn5xk|6e z`HAg(hZ%MWjvZX8YLwo7g~%Iqv6gt__^AOuz%prq)DbB9k~!S#_-~}vEl#Wrm4ETo z!TIA2DXK@PYcE6|T1a;Hx1`W8@3T$#<>wWhHt0Hio_=2wuQXz;l9MU7cu9Ur?|5^k z5PtfQHpkSrZ*sAAaDm4g840%RveUfABQTE+#M$JU*s6Ge4TZ>Q=N>#R)Zz+ya3DXw zgo`YqlQU5QV_~f$nj@x70DyQVa_Spc|5fp>u`4F+S?)f?(R)_Dpx-=YfN!0 zW^21L(lo$%;^bDsc0~Cj>b+&=*Yk~@?Dt63qMO)9ae^Ue963gO%MX!L49Ta z#eclg5*%^UcK75GHKyE=`%!99$;e;&1mBpwcQnW{d$GfUIZ-l+YRQy8@_i5;;cmIa z=FZXS?Yj5zQs(BIN}HM%j}qbc*2W6MmGiMbGZW$Y7X8Vzc&Gf~J&kxVpr>tqE z)rj0G*#&WdiFp* zd!HM%iiH0$#x3$n}k~rl*^qP&ak&hRGv;E$zp!eS#;m?0c_9uD@ zu7)_YyJ8%;5EzNK>kEi44+q&l{=h%Sd9>e}SG@@_`&^3{QBjIB@pVgN1eag(cNB87 z#&umW2552qdj3f0i;WPfmcmnsB&%7k=5*0A>df#?7#O+meJL*@uc;<8!9piO;;2Qo zDF~tN`0IPYrwXdGxVd$LK)l#pA^F` z(e*yL5R2}`qRQC4E6KH-o2_RklW9`siIXe+fCVmTSN{cZ@ZB0-A*Ew(6A<~m)5{}( zBKU6>U|V`nBOA4I=k5}Xp(M!=?EG}j`>E<-EM=kfAGu#&9=p%SkR^Yw|dIuLR|nV%&iFuT=YV9I|q#EX%&hgST0a>qCb5;3I6rt|2Jh9JmQWwjea zrQxF!1nzI28#XN`;7ZOF#*h*;=yYE2lzge|xj9^If1d~AY6QNT-R0bsqy4eJ_cW0u zbY9X|_F=&&aSBUkDFHAWqn8)PW!bTF)E{2lSInwKDg^G(q^R8jp(Q;U21{pK3@ESt zt`3FMAAqj2j;~P|tNw!E@uEjDFyv|~dg_9&p`A=u0h_&k(S?*Xl!>ncvJ-{xb?V%D zeFSdQ7cNI`FCceFHy!QTwWUROlJ;NI}GvXDd{8SFR*uv367+|c@VoID+bhn4g4^+{$J%0XBccMkwE>^3^ zyD99f?)z#0ZD&w?^HNuM05G>lyTVNeD#gr5K(Dkk;SQo0SX?5Hw{bxvJ}H|K?A#=C z&OI1ET7oR(!5j`mN7=X4RZ|1oWyZQJ{;bOh_uY2=CZUDL{ zs~M9SC@YfsK+MKSp79jecWE6anPOiXK|j&kI0VDz*sML z*BW!EYe(T{MpAj#O5-$$h=>xadhH@Fp#6>9tDLz@(%kJHr&|s|o{)YEopm4=H9;sO zdO0^~lmC>sHdILG>6suIBVU!$Bc#YH`)|hNwM@2>gk`4W(lXFgK;XsHz z{rH<-`m}}5Pe~}{OlnOmS@gK7zJ_?7HBW!KziT!)(Rv``hJ|zH5Wu|b$dVUQx) z!p!4g#>{2A7)T`OnX7&<3wE%EKuPF@J6q13uMavA3UchN0%0Qmi8OAvr+dye*{{tl z8{o}>TTJwK8Id0ilF4CwPY1;lfyjiJb8SoJ8AVBn0n~;IWQjxoXreqb`l(cx$zpdbjXNDm>i5{o z6o%E~IH6_)Kt~J?Z_kQAtu7q=6`yrV1Mu3|gzg1>a~eXGrc(n}7Y%j@+-5 zHG!W;RY;ag&l_d>?vgS|55CQ7XB;?D#6ysbPQooece>gEt*w-g8 zFmMeJ9^5vLk>w;N5_s7=Z9Z3#L`FubWQ)9oKp?MrWkf|n@n^|B${Bf-8Ni6o4h)Bh z>O~D>;M+=pPRgoej>rSnNKF@cjxzwK&=Nh_c0-f!uxKPzmDm=;E3`!n+m z&h*sFa~6|Ws~v^YJF}|}V;2vFDR6KJ$u2h3q;l(1j=SSI`Y+D_D=x0C?ETS;&FZnW z)2}CpUQDrnd39C44`VOv06`7MWE@@}^Wqq%qGI7-Gh`*iu(e2ven|oJDo^5&7~F27 z{IU7i>_YLHm!}(jr(;2MlTW18g+=%)i=Wr@WX7@{Zgf8QVztut(fMGu4^ZMxStY*&K3B?X zFI|>0eY&`#OwUNyyp3+CHn7jrUTO0|;@8muG`ebyi5i_ov$@zcQmKcVqn`W-9NtlR zvLrp~W3@r3;?zISgk4D!Sy~LG*yzm(+|s#W&os>PO8Ue>pFSxAvQ`4E26DZ{%*IVo zhEAhR_jrHs#TiXf>6fELZ8#>2q#fLhndC7Nd>}R@%GIOW312<^4=E4D0F+_--&EYR zu(6Oy*|c|W-@fJXxTJBhS_)>+s>!yWDk#!x=i5~-_Gll3I(vM%InDKAJWmgNxq0(4 zrMB0tNc7Xo{i242biE)7Cg>0m8M(jR^TzJ-)F7SD86NQB4483dE*?Q{0pU#XhqUuO z;=UAWshqas8#2wY+3q`ga07c&_6Iu(fUE`wxEqH-WR>LZ-84880|OzpQ!_I`fOjXC zK-Z@ya_@U?X99?usSvUW!;Hmx`@QpRTuB^v!o8Sldve=_qcm<&dbK@H^c{+g!6mKi zucGO~uE_5dJ~a_@WYrN8p9}riwVxSI#I+K{Ox$nSeH5boM|TgT0C)iD9`*MItlWqe zvELErr7lPF-6)ouy3IVo;bJlih=_GQU#UzPFb&C1{s6k=ZD+TrsM&G>l6IY$zX0&@ z_uv>?AmT?)=aeB{=91gDa2Q`rZHN@y;>tM`>&Q+|*L%`mqym!Lw8F*6LVh9+%bN^^dP}v#pXBhs&+5JdXDqo=t<6 z+`Wr8(O2^OomOl(i1R{(_LeUpah%`taZLz9gK#cG6(Y7SO_+g5 zqf$T+j!FNXd{aP$Ygi!z9Tw?sSG=c6tCO<90U3o`@IJr7!E}(C@Gv*75M94=2vY z_}VVi-!GIY1sj-#-n6b{gZ3tX+gNUZlGI3EpOvY2m3!vm5`EzOg=PHCMc9o;1I51` zhc+IdI3yLkw$OfUQGSMQ>5Ji?WnF)omMYISGufY;>hhC>c}{qVy9!ccHY?Qzk~MYe zQwDUJXAYn!eN&t2lFZ{raP~Z4< zi3r@B8|Ijp83)n<#+pJJR~&z{rK4B$?~#05(K8py=w^m5uZk8A93TXwZ<2kXeB+-y z&d}z1LR6w&naME0@Q8;O9vd4w$c|w9x5F`{ozA~Ra)uZDfom?Vk)D;7t>ppJTgHso1qDylXe+r3lUtJ`m zqTOJ@@|3yw#J0rvJ}~aoeKSh3)a4OuGvJEcH>>IFD6y;?W6i%`@se1!#LXHaS=#^+ zG*hdidQtQBp~Npa&{$;5Jf!gn)A!*<%+zL@AP!XLosd`KQW2T&-9e3sAUK#Dexe-CrN!ue5uHuoo&B z0sA1$=Q^5TO`SZ=vmX{H;Z)3X9m_hXMA*T@JN2g<3#wlCw`iiGZ_TEvmuyFla<6T4 zTSM8l>BOkTr39RPVYB8cmD^pQdbjn~!W$0k&|oNvjFrt#yLnwsKr7}E$9j-O2}4UL!xdXT*^rV1ujl2_OJ z^obD&HsR~sWId77f86C&*n-(kmL0G5`8o;JQy2QyM&R5CB?CyKn#!NI7N|y~LTs%= z_>fZjJ&^m7`m;`hOU5s57t6d}@*Q6c8@>xZ^ZF>{LGBZep39i-nev3UAE$-E6%Ez^ z(fXO7n{)`5Y^>y8Z#jFq8X89qE_1&y3y2UJoe&UQ=kewnB$vu9Db1(!49RS2-2~9& z?ah{KEKOc+X(w&Q_2-WyuY0gXl;)@K^ZIr{x3k39xJ=Ls+SOxhyjr;-!(xwzM~b~<(Y!YFt1-L&oBA16o4 z&2TGi=l$!BH@7duf=wZSKxTIz3{#RgG`8NC2jgO};3eGv{__V{nptS=bi*r&QM28O z>F=_xN|B5`53?Tem=QYOJr-7k@n%owkP#OkRBnwX;*i6*1Wi58Bn#PNKCV7=w@HCU zwOZmNKPD_sRDSJN<=*@-1VZGbmDP5XDNunk2YwCuXY$>xb3{ytYSVJP2fe) z>-6vs@Zn?zn{PgE4#Rsj-%*)4WCbvuV$sKL(#?Gi!wdw)I%JC+c> zdt4P~E`6&=EZm!O{PT#xfFCToS$8tqAQTG7uX_gIHb#P-CbM+$>W>Ji`s1ntYpZz= zXM0AlazD$vyx_6v`WwIm=F@dZHmgm5emnk~$5kjYjSGi!pCb}`)?@pLApR)WPt$lj zcjRK+=bXV*Hpp!v-7q9+LeSvzFWkezQGsRa{y*0Cm+EXv zwIe_Cy1X|EzLHuF9&-~?25BMH7>y=q5jdzJO`#2>#9Oc3U9$Rq2ot`_Xd5q)To!n^ znSaZp&>#vkvZ4tQc+Zavk~sTpGUM}Q#+yie=}W!m#bQ2CFGOD6dgLK-tR6_X70&Sf zp-fT4vdwF@q_H~}@;v;!r0OMVxYkDBz3%c(DxP<)Eaw*%e*^ihr~9k#CXF`W(?30% zGo>2yowmeGptevL6rw7eNWGX_=0}+oc6IR8KS+E*Ctq8}Nd-5y7vl;1UFv_3xaMf$ ze{nb=dY}sz*Wne}x;o%4mj}&}b90ZTaw2^Au<&Qm0=DMk&Lq!!HOZuYe8Z-$*%lbY z8vNfj8=tV_IES~lnKzcDnZ=b>-&{(%9#i>U~J62~kI_sjAJ zGs&rgFKuEXQ`n657MH==`7q)m_XSOxXs5zT8YkCge{%&7sm3Jilu7s+i-LS+8z3vL zG&G2uE)x1pR*Nwkl*4O>#d)~1jTnGz``zn3ykx1qmQxhb->A-CyUkVxqK3k`C}P0< zhH!-k@^<?PuKlv(BcHGrC)T;kxLyruc;Ue}N16sB);=Ga4OTIWS!rcmE|2oq9RrW7%DqX#d@=3qzuOo$U>(lyD4vE-`;@|?_-6)gt|LT?JS3B$xVe$wO>!faAt+8 zPltd8eacMNkLD@&aa~8xku2(MuTQm~`xyq8T=(7!3lk&mgMYSfm+;13W)%2j67~)H z|9osFLI+SQDXJ z0i8iz03YW~Dg|h`*=i2dWI@!u<$;k5EN~;IhPxCX=7;N(TcV!>k7%G}4R-+5=PsBnZj8k90ew&lsxS^J*CDQwH1nAb1?pb#*{euuk1% z*(^~nwY#6Dbvok5d!^=WCmNv@z73TF*HQEfn_`_7dr9=}PN{W=e)rgnEN#9xnDi=m zAP>Z8nwA~L)lo6O;qkH3JB>XsLWOo%#j9|*A!utnVbD7_mBb#_K+B$VT6xd5O>Zxw zt^&EQ!77n(S2)Y8fxyEdZzN&q!J)@e*f1^oV$rt9SaDd)23IcCJ2QS^OzCl{)aJwg zrby6VAXrGY1gf6@xce-Kw_Trwlt9(m>5U*+dXHr=;|Z&a&0Bl(%V26&m+;D;=yKYZ z&S148M{K<;x!z51Np3}C9|KO7PIUlzb8c`+2E}ee97Pv>TunwdKDpq2FfD~U3yzAH zapOkDYAS|^ZdlCk-eWDRoX2k8#TaLoCwic-mf8&r9ah0kjZ%H1s$!u|)Ac)LC#C>B z9&*1x5I&~)XSd4ApW$%9^3N}jITp zxgNDch40h($N$(hGD?4zb>>8JQ~+6{%swTA{K1tKMRK9l5kqFM^THdS9-MD8s;1RX z(Gs3SH=w6Wm%u#RRfap^m`V;0Hu+pcLx;)Q6?s?s=a=Mz*=FTpG}lFB+uBx6ey;g= z>4QK?L;2xe?pdvcYE1inctgT&c|kK(t~>^*`%5LM-Eo&Ta(Pr5i@#)?MNT>ShpUr` zfYI?4p;=v-(Zj#hP~5gFy-jDEapVIN7x@YFfT+f2Wo`AE_n43Rh{2fi@-6rePPhNl z1FP$?E)WRH^^756-6`yIdI6NOs;|#pb+ve*9~71>4i73(LAH9G5>IrJ_6NnnT$Nhk zz#$*kLqiRmokJ^?c-t2SXZsm6Uq4IaK^C32*doa39$c*Zy$Zt!eyTCDy0-*hT7-D& zb;l(|<1fSrCSEFAX_iB`3H;5QnQ9Sl91JNqPXmHiPhhA~*Hpg&n~JtuzwiqJTcsy+9 z^?X2>OZ#Dosj#7p@W<#Y8EQ+RV^=O zTJ@>t!w10M>dvXX$qj6zO;~XqG{bK0P4Xd8R!qr_{dy>9MxkBb7@mG`Y;&`ahM`Jo zJ9{3)jz)m%cSqk~k-l4kQ{>Sy9hI`*&Kkyqe&`LebedoHF7aNTYm)Ap32;@T?c1js zQSe5-a=RjMv22x-?XYAqy1<<)+ml|v>yG!FOTkfZc~_<0+5{-8CR{T#G&tS!t(h`Q z|5?H^GGDb`9uYa_@PGV;7faamzem5Dm5mOMR0^!7W1)kDg0*#efO~9A^cv?uaK-RY_!2JT106jnj2tS%t6T4HS4g)s;d3!ZWRdikh1XJ5_VVA>1BvIUbc5ek~ zzA`$tR$26f1(YOb?17}0)9f0 zxb`Au5M+PR5mlyWx@0xE#|raHZV0TqcY@^H#9^i}H}2&d4Q%nny2>Ug{8p5s zk&!3C{WEB5q1o=9M=^^h@VjSYPt7g~;C7-ZIK6-G)fJGqMAoW6^a(yI4kt497W zd4^8TOA<(pAp}8k+j_+$pBv%heMBxB8@5^S&aA-=2=|D1gy#G~lOK>9ckNQdehGL# zzM;4^>*!T8L@x+GQ1jI-S|L_&GRI}#elS7@4eLl1VSv<7+^Zn9BD}UZ~-I zm>5~^0?}6js@%InP{qd=MZ?qujO2qR4+#0PHed$&FU=#6r}H}}5O0;}`>}2V z0xx)GwS*F}W_#@~sbr3^U0!;#(N+m6=!!wxuMLNqNjQA;NqbG;BmNi0Njax-EiN3L z*;W<|N%!5GpYg@CZ*^6{#@yQ~VDa$ZUmd?i?uM*%ts6CK?~A9LC$6)2^1cX%QB3{* zpxI)>?MV*o**$kl6XXhz#S&zvtIK+H&@{|OF>GAcjDWL3UY#4F@`k6C(}+d@oK;>cJ5#B$!{Jn{^8 ze#RUK%hRly3P9f$GnkwoXLojdE}x*U&yse|EzOoi3;f4qHH*~YF6%|$_P8dl*vq5g z1>wOBz4t|W`+xa=k|EK;4nc-GuhA4?mq_tQL61ujz+%m#JRO*h2}B2NS!)RlyeyB)~uLOd}noUnbZGKOHqbI6P<-0?ZmREA&1g@L`jMeii%!W4i zqtA6?Dv5&Z39*WB#}Qvnwsb#gJ4@>y({mk%m?v6*mFXljTAA9Fi_KgVp$mPp1Zra1 z-EU4-dY!rTf61nCEf!P^yG->I+id?PU?OK;;@2leJf1;DN~`P7M%(02lvHq8LOvR5 z*4|QaYIj8d>CE=8#LoeSE=@$h8(&}LXw|)QtZKtJc8I9w`mwySOwBiGgu|B`D(Z!) z`3zxaOyF~U2--DV3=r?0vOk8O=3w*#@&@NkKTfsT2Hx%}68Ck)bLWLJ3F{M2m+InT zd}ELpaRIrT5NsbJHm3cSy-yVYC8#OTZ_~ULED$R-ct9kIYRK>)0o`AAIx)z|{B82^ zm$cX!ZAsq#I&tStT_LdXmtjMG!}m}mgWIl*4?BS!nU2RPDBX{ z+c=V85}OGfPb6{odg~Q`jCl3D-}(F?yZdFAjo#_$iMlKFd!JCY30i5D=H7v+dg~r| zh7|6M-8VsDj5>2sHN5-4T_lc`BZiV1oJ0Yd13RBR zx+4+`5#V!Khwr?f!d4aoZlbM>xwuGOU^8m6l-Qi7CQIOiAzVy0--_}rn6svFx%NXd z=(9jckFSQvu5W+=;MzQy#2IuL4e|(u52~?XY@xCGH1xMo#%ke{M4Vwha7nQyq)ipb z6T!f}-4wWEv75(LR@C?;$y;c7)8L$Zz>|5=xX)?f&l;ccf{}1iU-NK&rwUx(!&V}0 zt)>q1(Tc&7f5*8$OD>!iBV3y%#@BQ2{2PpbLWYC#>7!AUw9QSG$;rp-SPrwl@UFI? zzN?X4clqx?VnJ$0Pl1R%F#hkJzvYZ4i^a4};PDZ@Lx;TdNQZ^{WB}ZNY@Vis$~(dB zb+8L2$9Rd3RIHz4rbWc=gg`92tDfdH!62{7<>@R%iy7xyLH!6%B~3w%-7IFAHd|U_ zclJzvNg-Yl{LOsid-puErO3^Yn^TM4bF5Os-l%%K!7RT`NFS!wl@gyieM}DVd`^2IC@}4w%RF@=Oz+G}L*sCo$zHr+q z_?BQzujbgYGnVY<-O9b$^WZvYlN_&#oZxsqEr{5q4h(&sB^Gf1}swkl7wQ ztdmTE_0Tt-47C1{LJIv%PLeAxq4D{VMR}5ao8hS}5|5t{AQhpGb3eXA!X0-pPNfzH ztfxunIV_jq6cN5qXH!mIRsw#|fyQJ)%a2zf8?X{Cp|LlCn@=*AuS)nmDLT{(=08t7 zPwU3JyxNQWuf5|R0C^BXy{#|BVb<*e!iZHKV|WSb3q0yN$#984&gAV_CMQCV8 z4{I3t3XFGvB>(sUuqu3@)QW-h>pwBZ)ew`piYg*L%=U-NFjW`~VCNMALV-Kul7O`V zZUD7Pv@2<(clBRT&6LBbmFCsrnDayTX*rx(DQ+J5wg^UjFn1UI)aqjCZkgNkDgLRh zadAHG$qmMfR*d9T>hDWT|C@9O3!Lu2KP`}?R8>t*OEda^s`~1vD8H~euJ2}nzc zph%}MbR*K;(lK;Mcc;?bt@IGmAuXwN3?)bmjoyQP>$~@|-o+oR;jHtXc%F0iv-h5> zNMffwZ}Eug7z!Sv{Zw`sz3*S@+R1V4Oy~Tp1fs3QX=vWQk zhQ|YjzLS7s^~>`v^5T;kdpcyKrg6&>;cBlP#TzqY;qJI4@M=Ms;!MPQFZMyo=*CP+ z@RJ@7at_{s3{U{^pih2~h!c?1mbyWi)z0T;`x%dp3c(4OqnX0qBqOOD(l6M@In^za z0CNCnRz7ff^8it1@EW}o4JhpE{5J=v;+_sQ*P{Y=lb=W%ULN8a5@}9KhUwU}Ih8fi z#c8mNxz!Gc4%GCeqfq%PQN;I`e0515%xH`KxS44sshRT}5K3HYqqC%Sl6E3-dAGbb zxI#OJG0K?M?x}-(=Tpvf^p3lOQnp&1*|@Oc7|7eGf$5UkgDG^2?d=aDrWjBtfB=!P zdAwGAZ!hr$-4D8e66eKYKL-EjA7+SIKzJ4P6WaS$7KBePO{d=qrKBswEL{fy{~>LH z^pk4fcVX1k6|hsfWq+nly3hjMRfF!mi)kgPdUbxPnbp3twH6!E805HrZN6;YHomIr z19?cic;!`or{c!};JZ@QHd<;@aX4-^zvl<{yC)WcALHhZ-^0Vy%oVSmy%v}XI?S@- z3Xl7lcU-D6^l;jO1I~4z-V>!e%MLHF4-7=Pq%rX#dqWlZYrU9T{?bVQ;bAN2U!IkO(5o=(Pjr+zwDra|Fcv2O#>TXk8kBM0EC(G(|PkL+z zHZJbQMl8VeLdJj48)%N@NNIVHT|^xe>W@kU2C3vZYVdLBMUf}jT_Twah=(s06j+qL zXHc*jfC|`4Ic0B-UrV<&a%3EZ6S2JM1`u$Gg9qdzX?cE#kc8-`n8jzhDrw{MF4{Y2 zhB>?wBk9CrQL{mAtR>+>$TIevZ&-S)}=^$w?Q6Yop%EV6L1uLF-%2dqSxTec&|mZ7|kdE zsL90ibX46ephVCz@R0!_j<}H+l8>+N@#V3pUb7=|4Xj$2k)iP&uQ0k;We?StPmw@kG3!N%~pROnWWc(u8q9;$nAyu{5@B&mV zsw53mRPcbJw3hGSnTfruUKUykpC4YD$fCd+@8s+QoV z&#}jWI!@h0zC>Es#eVd&R<8t1Hr&I7)HvMwoR=9Pkm<#(iS`<9oET$YLE3gD3hqT2J`CZue;5s{fIbJF)Wp- zwpwwsTY50Hn`~@Db92Qy8a>MDCuU~gb33ah0vB-yjpS2Q7z+(spyZIXnm%$82$5mIj7gSvojDmGv-Q|EzD`c`R)Ebzo~ zDKeziYFVS=Hw*RiYU_;h9W_e|&yk%{DuK?#et$IPtas!j=P?6Gu|egA4a~)(I-&ie z-`75t2wp?&L-QJwCW=kn8#ZLuOxi0kz8bVl+^X@05uK-1seHWXqkAoHDp_;H2Ymr< zrDiL~65gCc_MGDdx9B*>mZA@65<9~>N1Y?cSw370n~TR8D_=x2yC zV2KjgEg9MM?OXD9T4k~-ErtLsAQvPF+ZujHqV$a!o1i}6(IC+Mp{2V$M$*5tojk}x zwK8l!TgRj!emg07^rp#<0=u5NS=rkma5{}PX(wayv}+DFUpnxQuoW|XU2!qmVn67XS=pvltyjVV=cutwe6uY z&=L~vwLRj%qEo7w#u8a*0&i4gw~Z8qwNhPEf6+}1-$R-1(B7J&-1&di-tM?;+W@HmzW^9I?bO2HK6xg z;i)$G>gnl(jc;>joQOln4kkas&8oLnR54d2HhI3y5;v7yKk}(!Mt##r*XjVOf$9$J zy`B@4&DPJ#-b~ERNoRQ>;sxF9&jB^9HLyE?0S45K4^2%?lbN*%0Kd%039`)WB@A>h zluuQkZ|3bR7U8%ZE>l(Q8yg#6o*mPBkI4{qc%EV?=ZK((2n}TeQ8Gz55VvuTrQj?B zdX{GNwMr}WU6qR3%5sNq6tGEH>%KZAdkH0r{J>-8RH7r}*x;a(W%xwcUcjK;XY5b4 ztpN^CP}>*yC|mPQ@VlAn_52|3#=5!P`u%;Yi%IWIC%VZZWhAr+ z_go@ag`BsZI-DZn(F0k4kf&?X&Q^X8Z)bwyaT1$Pa@(uF2b#ZrP|Qm}JltK%Zhyic z_gI4s`9VNA2?6)FM-kPn|794j{;KoAUQi5k8c^T)wN-R#S!$<@5P8di?ODAosMux7 zJNF0eiZnRX&zu%q>c5}oL@E4kq*_d>DX6W;k1tWu6s^$sH|vc{(lxozmPp&kle{TH zTMUz%{*=kut>LV=p7g!`Q_Cc!Y08%`$42v`(BAP+Q;YiStnPTdja=<2`+n;X0`@ue zXwnnkuzn8$e~(rZL__?+bCSuFgHUw=B2APtW15=es3@GVZ2q7}RDvhV8VoRXmy*E^ z*Y!==OhNBd^f92|!>6SDnvKc|^`F!WqrBG29oqcAmd)`Gtgq?>!_Q zy;f^`TcIJ@evL@rvQ(-nH-2%o{h!<6k0E1Of~uQ11dgpAubs5~DBoP@!P6iL!{ndN$% zlDJcHAIuB;F!S-(wI4a@BX{VI$Rbt%v?nzyVZz>KtVF^{G9#b&rm2InKDsP^C*LQ3 zIY{dGd)UQKB;j0Hv_AD$4JBT2C#V_yl}eI?_c)kD`R?@o>WV3*m@8{k_4`=;ty>;e zqUQxS790zB+K6Aj_4yPk6#slC)(?qF4R5d;&W{pz@pD*lEIqc|vfQ}(w9h?C3xFCe zC=1T(Bhqn|CTC;H&PzPyr6oF`khqb7x*l<%>3ctlw1@=-^-lamxGOl4!<*%5*2Vlq z9;yoo3DvqGtRKVm)6SQ zZBD@wwh!FV`25b8pX;~w@*8PrXmE~Yk!Jg?iT->PMoRG(ol&78b>6FG$4~MyOh|uI zJKyDQn|_AfdLa#OeA0 zV!HVKVr2DK?fTwD9`nftiv>Mf?W4dX%_q`}vZgYp{=x07$F~c?MJhF|{15|G0NtS5 zE*EoYO04xA{(QW8K8@?sQFI^ZL>}*=qU+p-|oYX&Kw^{QKl(m0=4Of}-hL`FnZ{XkU{<-UpEZbZsc2 z0Lyy|at*t}$yb{^sH+DTk^~uA-056=(}jx5u{q2j?}m*knrq$fWmL+pE=u=@Smh0w z?xHAOm$*peIROogmmyP(^^n zpbxV_J{n+HMV}BW6jToSoFBropPS$%HL*Q6c#f_-UJ~bF6DG)8Q!gFS7+t$39K2HO zNEhO2uiw@?bmB_E9rP28X>3}Jsg-#y5=I%DB=rSIt)htKLaC29pWVpC15s4#tPz7%Lh1vxCMnb{32MI|-Oo_0Q>sCK zLf1t&78(W&Zhn=_OLWbioa)n8*9dXbjUdCDW z!kO{q%b`We2X=e6f6mDxrvL%v+>0ggPm(KqW3q)X?84-B2U(TGrMEz!1;N1xKn@Nn zkKIPR%eQFB?fS>Z&UdWdh1ofTxu!lq78b^6<9@0tl3W5Y7F?t&Fxx!|JY+(%k}L%n z5h%h7#_IdfWCn|60_Y=>OQ1y+h)2U^%)9N7I6~ zd)+X8WGEX{`M*?2ahhZN@XJS=6Y?=c$Q@r+Q18SEazacJ{$H;W>;PC_3_xp=>XPmM zQZD~C8Sw#J;~+wOCh7nC*?6D(yS|7ii*N*H0HC~!@p?an1j~CBpqNG`v*7*W;d`RK zr2$xtpaB(NULn67gm)PywoD+Usx`qMd2i_h>Xk~_d;uE+vB#?XpN*}ZnOW3|gY8qF zS^X%)rjAvF^AyXc#g5|@5f#ncoq9T;9)$@JaKa$$0sSvA4D1WwODjSF&g&C zN-UMFf}aFE78cYr(H9Z8+<&w=T0f+x-d;~;HHv*p`oEGZPS4858QWkTE9H)pF2A{udW@&swZI|A0K-_qXp^p zZ&zNUFo>aCBp?;-i*%c5_GI`&TI~T*69yCVX|}`-3<|6j5T;6EQg&-jQbF4vPGP$o zpEE3IZYE=rms7E<%N_B92U>A(a9mzqT7^3A&$7RI^{UJ0@{i=8j=ZjJMxqF~bKO&N z*6{H^2-rOqmylT7-7PDlXj_V{cY()eWyNe4KYb=I-y>h=)T}XGSSHMtfP@{7gw4k! zw(C3=&Mk!<5YK{<$?yBv;*<7}nuSI2qT0cb)7}@F#5a2C!9kd~>+5|{WW4s2FjoOa zk(ihmxlH?ISVRONlZlQN*_l^+q?l}uX@9h;uDiXx{UbWdPYboicV4hIrvg-`A&#UK zcQ?2E_5#$Oc6L_Q*5WQMT&!$ts&C&GIgdi>H~FuRH|ji&O<-gc6`q3X*{T{Ep`#X` zB7dK{A8co zW`Jd_MiofcIUE_Jz!A>kDEX!)cw}UybcV#l#C(Pt7z_1n!1qH(N9S9knTjLlQ-u%y zbp{4<6J|Fx4l9jgO14@}ht*Sz3ET<73)i=Y*RDR_CvvloeN77%m3$OxG)?0zuWoJ% zYHRTt8X9Eeellh&r=>-U>HYO#B zKdUsf_VyFJckqTsMiMd;^F6=Uv>Dxnc_fsu~az_Zd5pv%R(~y?EiayaQ z{U~_0cQq+#!iP@ZvxG%Iy`=2eIrw;|rF}j3)ldK`Gdp`<&Rli-{#?BKzWNxpyx}Jd zAav09p6yF-EXs{HG|9@!+Pz)*3<8ldS*SNpmsB2O{GQlAUei&J)R}1mgSXTp-|vig ze|ls&QcZMhDB+-BLQvwmN#)RB7qA!hc1oz~E7UZ6Yl!7nYdJ3Ln=(H=X(XQ}r0G2D z*72v~T1+h1PRgUX*lKR~O^MO6S--sMv5bPu`eWL^tDqSdjamN!nXZkD94+?tlx8fG zzkp5~IL+*Gm!&&&s7|FMCI&{kFOyFMhl#hEkRsknVFvszlpkBW_SJdJV{Tq%*AbAMmslNm>tkka zPTL}w_q*hz%TI_&Zcc2O^ZWgqiv0mS(xYXVP|OwGz1Dnnd;*fLrKRvW6}?~y3%U*;*QH#CPVa_$0pTEEV3#1V$mio2g4?uAR#?3SZ8D$`#(H)+)6_2mcJ( z3{6HVvXMDHUBe{=<6pFItP@9xgB{;BNH4bg*z+iv>oLv!-);Qm!$$ABAO=2`_Ee$r z)nhCx*}^{u6SS^dV`9T9ThJE?el!kIfBU)m8!V)y_r(WJ9|$I#%^?BP*S6cZ1_ z{}lH#Lki408mv+qe>u7M?1TWzY|r93`p{EuF=y>YJ=D*jdNMkPlqCSj z5U4~K-INBXXEY=fH^5bcECq~v!AXP5lsi2QsR5jdKmR!_o8QHvhPCIedmnJRyOL8e zfNQiO#~uTsvy2vTieXcnkYbD>2d#PV^(dCJO9}ea7S%Al)pm9`ch|_ zPdnm1X2|5eM@fEOjYqKabi%f?Sjj%;)jI-(r%63Sr*!mJOiD&JZagRtF$#-|>FSjs zm6#T9-Vkn9e2JQwDQ)v1XV+lsX!E1u=H{-|sls}M9Z(V`ePs36UnygBEj_!jk!MDU z;ock;7!rCY)P&`9iata}#=^!{HB=vN*4NWh&jHbRzQKj5L%{po4W&ITEv?wy4&>zJ z*($4d_EIPNo&8C9%I~ZP{wKD8t|AjmK*Xra-z4O92cnpnS*%}`GKa||`UG6|O%}{I zxpVwjS~~vU3=+1$*7-LceMc!icc1!;t(^2 zV$qvQ0*(Yu_CEWjf`cFYW|o!}c75O^#?jZmrlXjYx?L%8pH&!g1CWa3Q5iJIsn8&; zg@Yu^2|Z!7((E!X@46+UI5}RZ+D#(ZS!FvK-rf!7IPK5Ie{uHS#7{Y5{2o*9Th=hh zvjuNyi9ZE&x}_AyzJY;_$rp#UdR7yQ|Lyq>R6Yz`NhZso^ zVk!+tF>i9Qnp;~|Uj*R_*ts`iG7iXY?*F)YzXAE3c6l=LKDVJ=aZ4#Cczu2E0d*Gd z_E%5xI*xu?+dXK?$V^ht_WE96>VDNuJ+A(lJ%i&m<=_1phEx<~6YzKMg6->%h5^RK z29M?x|6lg~`+IjC1l;@6%l#AZ8YG#=XoEgze^cb&yra_EjB(%EzsCp<>qlz!YY!6Y ozh~Zm4HYDcrM2U9_zB#So(1*d80=dNB7q-SNhL_NxKZH$0h+JfdH?_b literal 0 HcmV?d00001 diff --git a/planning/behavior_path_lane_change_module/images/lane_change-lane_expansion-without.png b/planning/behavior_path_lane_change_module/images/lane_change-lane_expansion-without.png new file mode 100644 index 0000000000000000000000000000000000000000..6b440d862c7ac0da840adca71414b3667ce5f2d9 GIT binary patch literal 25525 zcmZs@by!s0`adisNF&`iG)Om+(%m5;QqtYs-Q7KefOMyHcX!8-(kcA5=bZ03&wE|( zKgz}I*|TP?d)@0(n=nOr2^2&E#5Zr=ph!uID!+LHtqc5|hwv8o_m3RnH{d@g2W5%R zZz{%#AaCA~y^#_XR(1V)q6@DRz4r7!H3jf?=0x$t@oDq9L&X*Uf%los#xd_g(q4y4qm80z z(uynXOXYo|kPsOeIywRZEG#rMl;1A}(C_Wr&qg1n)rL%;6`U!pasTfn-+x^xiRd@j zc=sD(!6@9)d;8z_{e3Yu86i-hGtlN0>phsBK^Vsi>EHMK_Z!i{GAB@e|M~e}_w0o7 z+m+HtwiJps_|-Vk*_9~EE}C5aYXCQG@SA?=KgI=#5*n7)ST`4%C$cor(IFz?cMl|9 zY20~kc5wak$kE{?V|&QbesDE1z@!XDAYeCrQ_HBUSglOCJDx>&|M)Jn{b^+2Ju%|{ zhV%OXMCRwH23ND+JA%tpWj8~0vRn=0cC{~NrmMRaQMOD+)(PXE#RnQp7?;7Z1U4VU*v#C^9U z#@kR~xW9|>pF3tEfF)Zx_A4TtjvK#qJwKSPxAB}16XpK+L7Q{h7lCVcHi{1m2e)-~ zphx=TbUe?{+uQqVaFAvW;b1t6kWxBXRD_&-c6vb~nrLIKu(ZzQd|iJ(5}(`to>@Ga zDB5rBCXT~GU9AOu;h!^vOCAe?xZ~u%Ev993B_WC=mxuv*+@9P&-q1fkKW{SIfjrOG z`vhN~6MTI=A1>i8E-sLdC;B~y&NLhir#m4bk_ru$OUkM%C1^EiC#5=th$kl}iUr^0 zvLooC_Kl`XvBR;Z{AzX44wD&6hflY){!tq*2C&K$x(7Dm-RtWZUXQmyeUo{zMUrdj zXZyi}gOcp#vj{(BWfePgc!H-E7H|*7vwHaT^a29|H)o0!1mSEfEk7nuIypJH35wR$ z)zvTcNg-7 z!F!GOWT`epfk(Ye9i=ZETckp#*_)?>RM1=0)Rd;ol2p*kpz$Cyj$En9cFSl01noLD z06&t#0MpDMq5UP#rqi2__Ul50u1KeV*XBMu7V!$_^PU6d|EGdYK*0JeyMWMl238E8 z#up%NNO-;?hGBWf_jDvHB=LaFxoSeA{VKX{9lT}LOv^|#`Xruz7#i+!o zj%m)Opa%iFynk#@A1-LRxC-ecI(?zn7g?~5j_#MCd~xuA*`<+csSf^#M!BR~uDf}P zpZ^^(wVeN5R{$QLE3>$^w#?DdOS=a%8;4k{^XcZvHfU*#MlyxMwNLDS#m|hOxiTjH zdxUGTx{F`eN;%9?ty~l1?afi1%E36EiN#2ThXQA$`!hy4HAp5I2quWjrVmL@&w-N6fm zd_OiyNdB*zBegPn^p?HDDZU>jetvkYuFUCpggxI+7TLqL;%h7kxvYD)gOI+|=i@Qa zT5YVi+oo}%RLm3?h(+KiTVtGwNzsHw{Hv+{-N&(bP>2_KqOhp zxObV>VYh^-yp2yJu(F*X%WvpjBq%vlgSR*IJ~s_-eAw>@ozh z=04HN(da5GzF+vio}Cl?Yo}Nk@B3+RgvME}tuVu))?FV>gthA*DrB+Y`tAhnR;7kf z7n_Cdy|0?h)@atci;-UICM?d|M97d0e0ggbJIK9O`G)2A5%F<_C}ILPoB^Qi)YY18r=;ZPdHp3=wO$Z2{b!L@%OH! zg=)bp0-pDwZEp5G4v%=6$jowYI%}ru^~<de$&94C zn>_Dlp&v}h#0L;7ftPz-&{N&Hfr`EJ^g%?jhyJa9legqcO7_W zvLD0MR&V_*qXNT7LSOAPpv2eKfe8-YV>AlI>A$HmEci4#cbRXY_sR2xD28AA`_6pU zK#AEb(p2SmQHdjlTX~61uxp)GTT2ei_IL6~LKVYm5mW^h2m4Js zPp}+O?mLf5Q6)<4o;A(_?w82*gc&>A)f^>X>xn8h+<$Rr@zfE`l_tuOPGb`jNAc8} z7~Y+&c`pAxZnOz?y^B63P(FfJb1<3e#{nNJxVQD`{HJKi$UoTLJo4jllKTG6RgrZq zAr|n)09GMiQTV5k6t3>VvLie6`KiQ@_hR>7L7XejBqF}&0xv!wrz0^!!_EaFcC(U+ z&Zo;gdiHRRe!o)(rA~PcDqSoDoB3*5pAPpP0oPIO82AO}6492Djm8gKH2Eq*sCM;_ zYb^GXT*!n*{SCx?_9QM$HVHmoYwWdMWor$#Q!}%g?e~1`R`O)Aj2#LuYK))0c2Vgj zGTOtT;X4Gt!XRd8!uH5u<+`{Yt(HiCo2Q0iXfBHY3{y+dn>@ozNaC-}~f;ZwA) zj-$a*1n$X{Wn&6{1xZ1#5*R zpHKSJ_rj)gqhwz`4WTUgEMi%1I1oi4TjV>9yggj0WoV_FiE>=)@FHw?zy8Ipq2c(b zM}z}a<$S88-ib=W8>n0;{i96-4x)_DY8UX|-b?X82-djnC;VsVXc>?$QnFP~>5T_Z zQG}!huEVF^Hh~mh$A|ShL+ps#ry;MnT) zdc*9@UvuV*8AEZAj*X@5zx>E(w&ZT3kt~1FloM0NTv+Oh7ta^1CqUi3a@81<@8Oe z@P}i6$R_rXC+iF*I6BnWPYAfHaL=>vV|~VlD;_G|JDl0+ythSk zWYVpnfvXSN~L+s-{uz;3(ojm5Fn_IbRd_@`<)T@-cx{n}QC) z#d;w0%tG!_hz5E5y#=HGQzwk0OvB;3n>m2=`e?2e>JP)>{aU3;Kq z_jg!1C>A-glxwyUCKNGr)jq-hR=7PGif2?#rs2*`tU}zA7GcoquEPi~#x0iB8>gmV z%F!9|yBGPWYx|lf$XjPNN{uB2_Y^lR2Bzov#AV5Yp!`77lq0XEJSouU%8>O51AqcA zZqrH2i5OV2J|~AtjM-Tn+MMjxvk3ii86bu1-Ukk_<-0i6&xq371pmb@U{t@57#JR7 z*sNQ6RYlAObuWFMx=$_*9C&tua@f zuRqmE9KJ8+emyOvrPI~x^xjkP$7S5;PYlDc%rH=)&`m_m_we!1xwsGu+YVw`u|oFO zYwJpVmu;KP9vN_wK(0HqBqe->Iv#Ov^xaewHXMu5HxEXRrK?CV<7(ziERKl7DMMqG z^8Zd_fP`!W`AUOj5~1G1RlZgXh>WWLm!fo{LM2J2(6};4E>y0#=Trap8$RnI0BxjH z^@sn>@x1<)KU@{DAc=0P(@u>b3k!=TvyVW7)mpgL<6{*bFIJ&UN^p8QL5<18%LvAw z%RMCcO?Y_ttJILTc70RR!JsnQC3E{If2coyo|)(S_dTkuadFu#XC-T*K;-R4CA~ra z#V60enk+&h|MW@Z-p_Kl2+hkNtpc%iDMAvi4TT@EL>MnH6sW`wWM zw?zFX0X2`DobyAX`r*~VgzM8S!(S*pppet_i^I5vNvFxSrqTQH`rU%3XO-s?>uQS= zQo+yi$wocFq|mK;i-pNb1=1!S6tRH@6ctuAPsabvoUf2ChGd*$Rww>D4-biJ$Vv)! z`Tf1CfF1YR7)o4Roat-{hE`f?u4l9TYF=d}(|FdW5RZ-ygm>?tFtT#Ys;jHXjAe9n zb=Tzp?4Dcr6QvZ+%*ZHEtKPi2^tJ#8lQ5!KA$xNcGSlPMB)Y2FT9K%9 z4mIVb620^UsWNpMWl{KXXZ~Dmts8qW!GNG9jsKPlwBKliP&oM5;%s=a%8qb@i zYaaVkGYgC264pN-)7M%Y0s4n#d$-=6b4sUn7ZMcY_rCIMy*>iw*6hW3XCVJuw#JVm zg;k3Gt?I9hFkg!4pmH8zV`on5<-gn)Xd?oN^K)V^&kr-1j#+{(s7gvorZWvzE#>H0 zw#di`LaL7JqobqW){D`?v1ws@*QIbh{y|gG5sc(vm8o=jWS}=XT2Xek1-7R!eNGnL z&<~h&`i{9i2ol#OP3hC;t015toA->?q0p(*M65PDKz*r!&iM+n(P89x73B4gePD$C z_kQ@jiu%F-J)eNy?>8FhOQxIVb`yB|&x;9QVIjlpGL*>ws1h0Umv=9K zwEkR7i z9Q*wi3FaU48<;6|*kSB(Dqv{3eER>?OVZ$>09Y}h^-ks=*AMn0AWSEP;WD+$75Ct{ zIT&><*g&kL`Uze~7HsbEa;h!g&;JLw3qAh*!jF~0MGd)u>gv0X)LR&lHX9uuXlM|C zy>EN5E%ukw9;XO`EtQi$4kmo!GM_IEYPmVu+VFW5yFFRLEZ?e~WV*i&k>ygck=Jkg z*SrmW`#XXz9E#dB6&*Hu`-A%!$9C^O1S{=rw%3PBfo)z9ZEjcjpZmgTl);kexRS5L zi%L+p12H69V;Nk7apdsB$qYyt)rLxi=4ubW{T=^AC!rhuYs`M5A%9oXW{fql57<^) zJt3NHwjUUEn%=;Oh&Ue4qa@L5h*zvO$1!L(ARD`wM?C;?!S>Ehnj`V$ZGTI>MVjXF z(n^7DtMjUrdjey-|I+(rPbn{CG^Cyg+%5!E)c#_H95RK`6fI`fVXrSW%utL53{i2G1`#ilJU&*lrWSg6=y!|-)9HOc@^fWN)axJ}&Z!`?>@d7!MI~LFkRmFs28PzZ_7pR4NB{eKn z@zfdhqG8}szaaUM9e$A-c}b+v?b-LZ^GQI zO}~EqB2&s#w;v%PAP5(Rf!{XNAzJ0<%T+2jZ|QfWjc4@n@i|#<#soT@aM$M`#h+Rn zRMcV-Si;$SZZDy0L{BgLUt!_NnVHc$Iyz*3E!SB^L=%6id8CwFAgvxXcn|F-2>o|4 zLXBlRrLdG4CU%tL?_`IL-?mWFP@bQOw>0Gk;Xmm=@%^}A-i`9m%xFpdZL_)e( zSNVqAD1zAI`aJH=^izZ2{_2ECgeIP2>8Xw{6>9NujDmuKB+EV(i$@XA=;c8>Iy$C$%9vr^S`#fFb*#s^2VC9pgR%5sVU36ou$SJSWdpT}CJ|fKi zn1QTME|X;%Opy%@^6#AUCO-+vGu&|s+3h(E84E5yXCXYKt_nWgQ;Q;t6 zeq}9LS>%CQ3^yVkYs6tyX~{Q**B50Kc_HbcGd0E|w)@v+j>qf7S-dX6fMN-9VTv1N zGa0X1Q^?`#8cAVFyMK>SAkL_%+&`Q|PrbwkvNV~<6vi|(9J-qfn#ksdp>+@~mr?dq zzu2B!Sddt8KD{RkP84_U^u7t7Q#}uW|8j9O*NV38H5F^$`XAa2riJ!*ETnDo@jf6G z$>|<5MwCvZfhwj|dEZOHpv5;h0fYyw)}#S(XVjI6Irpm#0y9 zgqiBJ+rwd=oJ{`E7OXp6){DPkJs({v8m zQ9w+bERn*b0`HcRbFD=kFYu^GZLf#pFoX}Ql`;prySoo&Fp<7ySE;J!3wS+;uD84E z1JYbrkwggk`ar+Gj=#-D+txj6IQ+H8W8&!txcK>CEJiI0kiqU*Ay2G@s&qkfTurlm zAELUFgm#Q@8o?NNm9FC7q}41OXuW2L=Q$e>+OLFFjl==#`}=sjmYVtR63p2x2hrJ? zS^b~Nzx;sSy**vQGqj3IDpR)`O-a1n>VbD;VKcs&K*wCs5Kydq;8UCVUw#Ey1QZ6cXem|@nKt%S~5wBidLuAWXxcJ9Am_q z-<_GIkh>D?e1n{oF8m#CmLs3b?MM0;aQ5D4Qp8#t_@nYF$sZr*!h|1s9p1)!wO`xa z!}cZ4zG-DJU0jeEvoJD7@3O12gpDTA>t)X|D6>24j}Dbm$5BgvGGK9}X(cXX2Xz_2 zY$-NNtJR%-he8>HR<_3ex8CK)E+Q0L!5(mXet3VQLMrQ&i9l~*QFlK1p$iP@6Ax%(-G68MjNHSyJPwmFZk!~F9GD&hvIc29KSZPJ4100ne{f45WX>^*H zi<+Ax?G?UbO*?rGC}#>dA>N{*mgG6+Cxi~p(yDN~dJjz(dZsJQiBp71E&z;bi`gvR zXj-hf8{k_tpJuGPVFgyn>Xo*2mCrAK{OAI7$U^C)ct?85qpZCxsGWJ;sTLJ9sk_j> zQmmgK5|oAnVVgI0BpiMFw3h+UcAnlFS;NGW>vp)D{Td!d9G@wwE(P5jcCvyX!YzYp z+$Oh{;{t+Xb85=+Ws#p-qE9u4c?K;9Vh&~r!=rQ}oUU&G${1QWl2UAbRR|9Oi7b?V zjT+0~)XxuqiOk?kGWvueg686ahu0{PG0so9M$Y*DFBXvaHnU85IPZb}@<8o1y+^^- z0f-Ql#ZBY^pjaYEi^l;fJa{6D3vI4cL*WJ)m@y1Lt-5be`Gy9Xkob5>cD7i?jaC=^ z^;WI}6+%8E$cF6^RTCgn4B%E>{Pm9I3YQ$RJCKYH4@piM)@xb%v zbG!QC$V6N^RFvqWREWwA`{CgNP?oTj?7V^jh*I&IOvM&kfpjoY``Bc#H!M12RA^mu z4bpXtpX%v>0gfs01?#o=a`#+5c;OasMQM{fSu8KCfY)Q_@*WZy;~9+o!B9k)ib&(|0TTVUUMJv1+ zzBG1pZMh0t|Hr%hLTwlNzyh^n7Rd!7P)8&sKa4Z=!PCEhqS|lMCD*THJ zC|213TvUh)$*;rSr33ds0R{AZua_U%uTFT=@7&7KvLZ&?8>8G2?vY=dzJN}%&K;hB zgRSf5vBqSlHofJF59*xxZ14cP$H`jrJDdW`sTL6ptdHOTVg40gd6@~_27IMBj4I+e zv_>19zMxNC&u%I6Z%e+cyy3i^N!^?}ScXG1+<%@^B++wA4hPdyu6%Eng>9x=+bK{o7DZxwBcOA`FtwpP!U}%8 z;Pak&lgq)|w>PE%avt(|o`t2B$-pU73;&w_6%O(qEMtxslJgEsod^ecwCGUp6=lPR z9tMZV^Mr(Sh;?Pcw?CM>UFhlb{p}=8e1bDRD4j=r`;V)GZhZ*5IlMvZCr>?kj zwfc2G1(OQU5d27zQ^KuepFqCvkqBR6P@^^p@d5_W&MC>fhT<4$8?pqv(c$Gcl3iw+ zk{M4jzq1OLe^JLA;XD!J@9BT$xzQ-g#7VYU4awwj$cr&!BkHh4>kIc0JQ2yE&-TUz z(+2-Hlbo%XuT7LmCW?3G1VO9tEX zr;~{w@dhge@GjK`Gv01oW5*i5LRm1Us-$Gt?;Azqokvp}!`EUl%inHKb`X~sPNGMp zr{_8}3Jg|0=!u~Vw|JkgKktakL_5Z@3ga*T?2i;)X|Q6OgY@Atef`!_Mo)eGoB$08 z8eJle{=Y1M$3=_>Y+oQOG$h)W6|!7yjDkrIV%(Jn&;Jm!ay(j=kZ&Ooyf$_U)l$qQ z4P7K^y+$u|9JxGy&JhR+EQsinhyC z*%Ukg>7!Q2ww3>ZxHrHHl546KENpiQ^CpOCnyP};RD5gRPlH$jUjcTO%U zUPN&Y>F#A~^LX&FmnCxR>AaO-_@j8g=R`+V28*?k9+j@m*Unu{+AoUyUN2i-A9J*3 zrx{C>Wm8HU0J<`B_GeMP7=kqUCq%T|Dj zM+9u1sc&n`oZo7;n~liVgF@{27H;Tqcm1xvQ{CjL)N!x!rI1_9TiT|v2V-WxS5hGn zwCM;e9KwQu;Evj>FL9;;GI0bnB!+Y;#Q4~yKy-+8vB8XTUp^;tX5mk@$$+?}W;24! z{HZAInmxj`PozN67|Wa&OL~SUQv$VQinO+jPI=_7jN%36r7qN-V6+3=Jo~HV29z^4 z6NB(tw&i+@6uLJ)jnmjbOo7RTE``l)7)!NGT`qoYH$KzUCdQKhPM?2BcbXpn&i3Hr zc>q96b_$+Q%gfrggBKINf+NgbmAjX{|2(nb7rp;X%OTvN{8~_ zfJfi9vY~1B={?X5?N%35pQbWd{j*C#bVaY&Hf-9)eYnhkny?EuQ&QelBF2k<z7BN9QegelkmCvDv^ul zel1AGV>W0@)Sli=-<8Cj>#FJ~RbnVLuiu|50a4@~+wp($5t?_mZ61)0N&Pnw) zfl5IWlao^=05FOEjyrz>!V|eoH1-nHK4D~S2&ntpGph5! zM+oL-W|S={B=hB8YTjI5y+(OURMdU^QkyRv@OF|>(RW~BYRa!D8Ryc%REXTio3Wpv z3`)|cFq6;DKSDi)K_mJYk%}V+JfCg(SFuR`_%#x$$5OFXzk7S5)1i}SqZ#>NB4;4* z9p-yAXfhpfZLRK&3A7RQ@>o7Wv8R~;M>se*{jN5*(D3Nss3;UV$#Q%*$hKHhYiq=E zM5hBxcr`5a520Vn`P3lt4gK3~l-xVNwL`yW`15U!PbyQ|{q1706_Kr+Y2B=+nReWs zwrHGItD!G2Z*zeFL70KnArvUd0AP1IL}?WTDO7(xF*2f7>a}+RTo*$Yc4Pq;jg-Ip zDHU&bJOeif340qp2CG!3*`D$!V`wf2i6{r0+2Y$z$$AfY#jY(Wp-~_IeM*RkMdKS^ zC~ene!eC{EMW>1G{qpixD3d-u>hA7_zCl5z=(C^VuKe1*jmHeKPIk5))T=UW`MI(5 z$D+#WSY0-g{heGoyOhzuT$u)o!J(o&vowX~+-<8Au6_%kD!aP7=bKDqA8vFC0$7WD z=%n4_?yvlHxa2-4T=Fo3FfqLS6(q}1YQ21JTBAv49U zm-j3*==?e91g~E!W$_QO7!U!s;BU;z&Hmu~bP|Vl18gnW8&bGjBuA*Kt~?ovj4_lC znhy17==ln5DeRCb+dQhgZ!gei5>p97Iw_3<^FqK7{u zZ^JODCmmu@N{<&(jEes?bLa?Q?7x}>c8!lzXCFr`wBGh2gG6tE=EXK1w=G$zdRa2f zWExh)N~87GNwdTAHWjYM?+D!c$Gr$52KzrrAC*4a6JgWp&MItm2jvx2Fyi0*{%uR; z19qPpX|r6a`74dUkdtFE(CHTDgFUqyEW3*2GA8THR3ZsD5Uan`{f2bXN;N<aL@wY90ZhEL~4QmP0AN&Ni$%8%0SPBRV(KzxBy9qk@=7u|5qSMP@kH!#m; zCH+)UO<&)Vo%O&|jSNRgGWLyOnB|j(j|^A-2&-{-FHtIZTe?u<*B?cAWx_rlMacCH z$kJT6VvWoJ3YJu0M1LW_cs&7D$<3^0~e5@9!_SR}!4~+zFB@Ys zU%|F}LkZLv5Rma-WlpEfkydINxcrYI377JS_18{R-aP3}aszpa=vnzSR%6?tj03?+dr{#A=R3G_{cN*8gs#IoKzDq$nix=9P<=4lzqkZYoa%9&nc8`P>_3FbwE; z3=bqNKmp-4TCW-GC8)B3&cT*9kQI%~9~x@c`eC61IZVsAoX@#<&A8YE%}M_L*<0hM8Rg$r+Z{62q=uzO6j0KmxiCNEmG`u` zyWcm8GtBI{(dZt*ux?8Mt4KU$V%T?iC zK0pr72{1T+A2Sl)~P7_a*Bn;Gu404HZEW6%ZKB|JebzTA6|dn-nU~*15S}1 z;1q2tdqk7vOrl`RN8 zgsTC_Pt;$ud8rmUXS*|jY3g4A3L$q8pa{9=Gxh(Spnv_!S7@_R*jH*Hg3IpR%iE9Y z_a3L@|GxO&xzWGbTyGR;(w*%%%5AIb#=+QBy_teTvHuyCe-ox;7|@jT5QJ&U+n|4# zZUCPZ2ZmlJu6fP$KOfRp=nbIj7!dw<0Dq&y_b7ndbVDeFBl1iD%Z^m`!Q%Y`ddUg$ z+|$$VEq(#7mr=3u*VJT6B>VlrE?NwlGQqukWy>7Fesa2xw=roIsiFV+-1`JzPaP|K zT@$plCV;#0^EQeaUQndE{OdPA2O%{92s|4eK7h4bhJiRC?nC|qaISPusGfXL$D!8i z@U*|gexXBTIbSaxVg~}cia)*Kh}Iksv4_=Uncv2(Ue-$kfh2v^%1fK{$V%zrEcXVn zjO5dAEZ>^w8Y$gQXYms*j&5W=X0=`xKRvGSN?K2VIdD4d(ZEI)(jF9r6Dmh~!v~%3 zk7o`P^qX$J@ipyJXTPJ}eC_1`>@ir^?fH!eUl1gpAk-T$qJZQkx7#-C0wx%F7hnuR z7u$Vt4l1>hWpL8y^bNbx>B-bA<6>|Bw6p6NY z&v|+yMhfnJ2mG7Zpl8CO59GSL^4IMixIiAYr$8cR66l+CRtu>Aa`trIIgG|>VZDFv z4;*JN=L<{_4OA-a+ml>_@gOAJ;N)Z+z(Sysit~7V;Xhk#4*277XD@uj>vZ((J``h; zUYk=+D&;aeox|ttU!+W-UCd6cd%%>{7s*q>z3D_T^z)}_1evZ+&rFVM^som7d0d5F zJ!tspS>r|~u-?2KvB?1fb-6#30fIcL?NBYC#SNY;)x1XMO*CrT57^oTLS6oY z8PqWpY$cZCt)U2>VKEY2{&19QBDj5heJooA)gy_t0R$Wt`9Kz;M7J2V%zoHTOYn#r zIJ`bJ*bD^U95^i(nYGkkJnDu+s-Qk86qsS96lkQ_RCZ@FTdx? zr+=FAt7c_B<}Y zoX4_C)p|urWi&F{Y+X(zF4`fIHf_wZWQ~Y?jBlrR+M1T@;K8PI+Z-AaL%QwoY{DIx z5$Q}te1CPLJ^$@txzP3MmID!YT3`0@hG6hY!%>R55q{mrHAcGrrpkUx>!Vh+@6+^X z<&cNuQr1so91O-ie%A3W-X;FrBQ4;zfsoqbt*}>2tXalT>mq(;&q#@{}! z0p}2Mbn#Ul@SCZKn3}-+$PJC98ya67FF2EyeGKQWw2n1v%IZc+o$Z7zku5zJ&Y+jjjXa6q278234eBchCU?{b$O>lxZ=tMr=WT4daE8Xl$9Q zcQq|yaxxcV+1V-#)ryyeh1-4`c(9{h=yg57HLJidf2!JqFqPc`rj-Q~$RSfTO=Lh- zI<+dcnZ84()oines>o{YIiu>nvO3hZ)ak%BcD!*_7)=+%Y-AGn#^umz{jXU^R9Zw!p1$G7tXltfzkjoc+{a)plhbnS@yAb-C>k?- z?R1L@rn=cY*?e1zs(Uf}`tA|sc#OhXapQyR=Qd}XzQeqE*}$;hs0}AE95S4jq`2W8 zhqFtVRZewX>3xKXKMagB1zg^fTYkKcNt>p0O8a%c-r3_3m@ToqB1gd42TKV5(s+`l z(l3(cNZI&(n5E*5bX~*(P(seHR4W`&Y6*J5?x6D&n$$Fx-q5ZB=BkOihv99aA%^B5 z3x3XuMMOC{hLhDDxR?hvyNBHyQ4iiiFYyUuRYwY+5Y-AzY=R?#A%QYl{utWRw8-Dh zWV-nJ*nueV=w#D3yw7kS-=gjRvWJ(D*p>QR*s{OVQ!xNY84k#*ULqpVH-K=3hyF`C zt+P{bK<44;VQXd}MsZ>C+nkh~Zq^XqpGmVWSn%-**WY;GxuN0IuftYQ?xKOA;X{!8 z*{{h-MJipTxVY!{8W7i;NY0fHdRw-kVi@EM3QnvTYc$p zMVYnVPYKL9$v^dI(7(EkT5LBHw0>ImFB?!*S6Z$=^G%kMV>Vx9_D;J!^e<|a(p!ku~Tn;s7s@|ip@B8Bwz;0UScgikSI zEHqKtgxilxpIk4F;6_J3ZTiKKR>E=AR7SW-@U`H_9*X7N`{$*Q0VD$sX@tdkX(+WC z0A?vb62#&fI*B9T`{VO=KCWg`%U+fHh5Kx!;UKAskJ@q4KsqJiZs*g~HiLG1>eG6I zbINl(Wf{(;jP`A7JG_hj+4j=mOo5>D$&JCbEF%F(7pDOJ_j8zzvUZgt<1Oj>NW=TB z4?$uwDiMO@l;z?9!)?y)Eyih%82Zl6wtEu+{yBO2Wsj>HSDR#xq~H3@O{(+z_O9{; zm9fI!(0&;@^*dR5)vr%P{a9x`mHc$ETn{H>whljD*i@VV(iL2WS=NG6)k5laJNH}T zZhHz`MZIgDu{+zwSO01jL&Wcfha3Gh$!Gnio{4IyBAg0!3k4Z1co0LFl+8Z#S<4;O zT(uJJ7{l<(srE@TksKk{!9*B(P;iL-3Ahw|EMY;l0>cUu57IT7sb_0csuKFpF*NLgBgA;#YvWNt2*xkO<@R)Z7BuU}_0j@XR9;%xnWFMd{FncVwD zq00LK=ivZMh8d?TVB-WGZ?M_`C7GvWt;_3dI2U)qTm5PYjoWgfr6#oyGcW5FLoL=4 ztcB8Ba13S7HlRQ_Gj=qk~3=K3jEH^ArQ1xacPu-K= z%ZB2ve0p8s%uUv8!YFV84l;~TMrIis2n3k6hIk!R&pw$h1sYlM2@4_$;~HShc8YyWr!gnUE9Scn*9B z$OY_OaAXf6H@57vAj&-b&ADq;Q^6TtX|__2U8Zn0!?(wxA=)AyLz=xwDGk=2hjzKo z?C4|M_ceji6tKZAb7f(fDp9WVgr2@3=QC!qeSITH^vNl3t`>mu2CoewL`>8xY@#hd z9qekU2tbuJg(!E^(*hS~&_>H8)sszQ<6{pYCYHy=%Xs+d%-2akXFpJrt#D#WkiR(a z35tY!l$f;!AFlmmI>+4;hs~B;sBSM#;DeOVL8Ji`xdW_zqKf!)sG}0;^_tUZ5!wLD z8BbLL_Jq~3Go^Br+M3A|+Ns>_7dgoP&pP+Zp-gs&z{@)PIlEP~1SoC5z-XFmvUnuX zJ1Z+IsXugIMN2jADs)*~UOW$vk7YW1dP6a|9geUnUM7OU{*OMh7_=sUlhkdo!ue6R zgXrdHE`hHINEtOb9COYytWiCXECpd^_U9ReDQk9oe>YCjF?ysk_EwF#>-+oGN}3{Z zp6?XEV_p*Ah*emu%Dls`;KgL&g2%11J&7jU2cp5ZV#?xvzv?aK{_Fu@!~`qA5z^~~ zHAg#)9(x>Na9&sc{v4wZm#S~u^YI$v>O151Q)s3l@~WmxD-hDA{gQN?954cg5a}>k zbTMU9D=)-r3GwDu=^yiE@_S0X*qLe~%wGN&8RF}!P*UWfRc=VITx3YmBkx>ocfFaF zLv<|X^zi#Mo+;Qj{Jt4c0<~H+hOzyjHbP^(;NVw9ykv^JKC$RP@8DYhHFS|H>kO*y z)K3RA9!NfS$L{T$W?>&(VB?nzYsFfmAmrwI#Hm)4Eif8RBnQZr%IAFYQ-Nn1TnJu` z*kuKaV1;{_ZiaSD&NKe9^QjRp&6nQ-J;PHpw)5njCBuJRMrk%NXBnpOfic z58y4y+2zhkj+L6J2JJAFsg|aHqc3ZjI9qQ`IH^sazACxI)#qIW1SMWy#$Z`uXwepA z!nrO$i<3{wU6lN()nU?_n{obCr+K%)4|8aU#_4TwK!HJS(EFlZa}kEYS4 z(Y&tqtPy*-ocHakeWKhTZ;h2l8`s_r0~Gq&))=k3m+!8)7~{hl%G6UItwL%++%s;R zIdtW@l^J9_r8UyR;pmj|g)>T`n>3Owu2b8d+i~(c92Og)FyoMj$KA9YJmXJ9YjPfd z*}Yp2b(P}2Jvoj^bXZo7N4NaBs}bu{;wnS7<(rSdDa!aV=RK(-rP>*K4Ex&X!P1x89 zm*4ao9bWm}=T6a1DF(7;yGX5hLyf&$0UU&PUPwq~ex_?}46o756#3E=zW(!JSY>5D zYW=08QwmR+Qyb2^;YqvKgIIp#bF=g6FSK{kmW9{q9@q&wPG79{)oM0>L&+&sk?+hc zAHl!4T2i+Bu-nNbb=pe-!`UUnpT+svVRo2Pbi+68* z>FBBX`u;BqU?HqYSYH}qhH8Dd+JSV&f8FQ1wJ+Q7PNXIxQ6zkgJl}0^nG&^bqgkKH z{G}|1CN}%_W!kOm{#Vb9_5!o5k)FE5@oeb`wWn8wp1vA`_N^t6k&V$L!YyY)ZrcPl z%yt4II7PZevXI@{q<5n7s~P|O>a|oN(T#*O?vjMnG8iKJTOsQc6t9~sbzIVGsFG8T zQs)r=U#LvygHhCj0?|dtEtiMU)3tuQ)pG#wx z*)B(>&sj(<$Ab~xe*ond=Vj+$*Ivxu4kmLDwp>FH{-itYLTG9FgF{a);Vd-!GB(+h zrMgZY*p}2}FXXYX>jY;|{rr7}p`emjWrouz4)r!H!d;KOEmD$CIk~`UG7jQ6yAU{brU;=k%LXQf3=T zobS;bxiDP^8|QN<1C;^)@5-oqi{Jh?m7^iKNG(CeGkvq&htxEY+9iApgby@mW0FC= z5V4jb`80pbftVfNMy}bpIm(}p6S0g^Frg8w4A9rmjTx3b7ZPdBarx?CTctYlbzT*@ zfJD{dPepj4IX|e#BIVeCCrhN+OvMH|3H){?7p`*2qN7R+D`T?xJ?txf&ej1zHj9Pw zu2Qu!+s#d3Q&Uq(R$br&nExc<{-Fg&Oyen%uzp#N8?8zO>wM8f`TXO3;V!K#YrtA} z|3&~He|N&0unaQ^2_ZuAH}A6BJ*Yj*nR!&EBOHI~HKNk1mjfy`?n%PvWM7s? zK}y=FbG@fI(OuH=ZES4J3GQCs=TY;OazLySoKPPOmEZswlDe$xKJtkoi5Sbm}Y|Fr@=5Hqaf)Z7P1u?_t2>$&Q<>ATP%} zE>Yyqq}LW6w7h(NA4NO&<G3M{Ab3($n!b@?@RyJL+X~a@l1p0+a$YT^Bf1I<2DI1)hqQlfJqAV3I~dA zOuR3{crVtV{Iy0C=yOl3erfgxdRfZLl(;^S(}0Sz`8F12YG%Lr@KM(!jjPDD6kcYh zSIaOWke$mES*Y2R5yk$@v%Yj75pqnq)t6~0#X@~DdD8#p)0={xR1F+Q*Sibg(oX)g zCnZd#VC*H#E6UC&cb}AB(XIY2f;<1wPP;@dhznnc^HL*?%xXGmBnKj(nx?~MsWQUP z65QYSR|j>#pt@Exevn4hr=tCu=}V=SV_DuqEzE5Tw zr|%q|w$l#U0;f8%N|jGYX=nRw#+;*G_WdZ^aCk~VHFqN6v=4s#G>E1^DZkr5$m5vr z5JZ*blN~{-nodI9D3jHk5n&w$95p|adZOv|si~}n9L(l? zqY0*CRqebp-OT`jOw@eGUOFKPP~qFLd1b1zTV{Pc8M%!9NOCllj<4?#xQI z4E05#%_mbt2@N6T2&4DJyxY;UHy>zpiU~30f?AM;4@6*oCptc>q_}H)5Hr>4ZRvCK zHHj)VR`PG~&edA~GU7)<6o=4Ft?hA=P)4L~zCDgWFi`y@H6N6;Bt&zIzaZtM+9^q- z##Y)j1ucD5l%O75X8}~sUW$HSMKvxThJfa6)5RWm`KahM9&?5KKVSGgpvlPY&bNET z;oz_sH9nfY^X1yRf4pP+sim_qUL-f$WQj?qUQRK$-Lbvxj{XP@#<7d{Mg^5hw}h`M zf7o5hM9DR}lWp>PMghtS!80vOkIxa&{Yv18?NZIYSJUJ_*UO$UJ5uUxxj0!vKU=c7 zYV*#?Z=I8>2}*(FgCfmUWw0a1UN;@aZQPbUCfLml;JyA8X1``pzLUbIY0Gpc8bN}N zOjp?Id^`w{Q)?S=7B*z`_kw)+pe zIjVprMJf`Dl!VkdB$-|VX3C~;McGD3rvl;eoQTa33sbh-Fm2p@u*-`?pev+JlX(;0`x7s$wPGH02+O1=%ZWZ&kXkvA&0nZbsRfNAbhO=(A{}eV zxxjti@x@Y3eZEALT0%}(7zh&8y_lHt9$CmS0O7RQy=WaD6JKvoMR%8se8Hnn-=7|> z{gCooyE`~>ALeIY-^G2A2@?7*c|E`pdo?VqtPFREncauKd>*2%A!lU`bYRr@>Ync- zOYyXweW1nZhP@*7!+9hC#O=3V z@6&i(I5W5`yNkR^ZMW|VG}8$ua#{d3k_JTQlNcVU`jSG*MC2C}nE-00{u@!qOpX3` z@WZuuouaq_r`=*WVPvV)(2n~>GaQ&SDViTY$30_o72Xdie$CYl_p>; znBV>M6>)=^1F1JKgs+q<47E9sxDz&rJtd^mYy^|Sq#fw{8rA?flqF0x1H)D9Y@Cwq zEupnU9LhykN)(`zmA?FkS8N&}6K07X@-m~f#^dE+%aiLSr?UWE7&2Cga^!ZkvfayH z7dM-8-$(TLUk}n819TwnWRah$Hi5S58NkL@GARiNli3v_Dx-s}A~l@C)I?3;FnuKJ*V6 z+NR{oVLfF}v9%QVSoekMxzy?8n$T^N#nv&Q5FF5l;cPMSxn`xs7_%aV8a3;C{Z!;j z8OvIyRc;x#dEesCC0|d@&sO(gY8g>6F4~0Zv^0xjsp3^4URSil;yFMogU@kXf}+tS z@|$<|Of{pHET?pBNRkv;7T@$q@(jw;m|%i@sI+(QyeW&{wvk6ViAw7qj>_Pz3ylKT zs+Nx}7FFRUD&&x=K7XdR*lN8_GR+p1PkqVYREH-yx>E))FghYE_FWPl0U5neuE-9} z;cNs*OEV+6)W=U%z*9dL{D$hZGaL|ELI3INM_mJs%_AKKy*9j^-#LJE45NXKaiWQ< zCmsCb=9#f>t1EIWiGZku79KEeeR{ma$M5$i3(UQ(N!NFA^gQsY!$<7;5WzTLxy>U8 zXi-d}Q;*PJ-X|c?6;qayf}@m63C_tOrqd`777alhkbyz3j(*1p5HeQwE>1xyDJdrW zH%AL_d^$SZimoE<8OW3?Qn+*pOk||SM3uK8YBk@WGT5yV0rEbPp|yU-i>nxDE`7Ii zOhphYNZ$KdI<->3i#S}83YNS6fkLm-C)!XW==8Lu^YP*=v2R_@o1b2GGl7u5Tev*m&)CxQXFJ0gzb$>Y3CpFVuKdCH#~!bo>|UK0>$ zQM-pl$9;YQc~5UW*Oyl!07k8;rjF%g3JDM;_{pF+LXlj#x@y3n(}Go^m~G?+qE=O9 zw-|j@$gtGpOT=Zn*!558${&lIjIYSWMY-A0RHG!ErR<4WQko|>`xxNI@e(U+moQT8 zKgWDF>}6mjgBB4H0VKTMc2X;HZ-)b767s!)Fo?OjcjxXnc;NtO>**RrE0By1v`uGC zsG~5F{$P-om#5Weg;eizcNWQ5rjUrJbd7pytU3GVyVu$Il-%KpD^0v-0#;qZ)pK?n z&-zau{ku5l{aOdGnCsEl=k~SfptIEs{e;3uUm2^pbfgl8_2CbPH_JgC?XX?TW-8F* z68m`BCTiXu7~1q|wP=ae#YY7BZjBv>^&iX8_pB!Bi5Ott?!?}Z%n#L>i1Q~{(MG4T z?-2xc2s{i4ku?&>6R5-|I5H>Pi=NpG77lgKq1cHn*LyLSNfyfCt8N{b6h=zt8bgMb%q{K{-k4}t5RLPblLrRqOW$ROJP}PVfyHP%@78EkGJFGZD0Ms zr}kow4@R|=yp1P4g>v!mf~Y8g$`zj6E~n7D6r~Ks^hGWd&~nH7g@{T>-ky08jCj*ktemzQCEIHOLeWo5H zdG#IS$h_Q?!LWyjj1=%q1BwSlN|D%1)c#~}<4s}Yx;@i_?#ERs?9G;N!G_ zo)=i-h-#J_5b&UB$_cz3A?~0c3AI-lD*3%%MORoMp^AyeKGByhhC3%{)qvY%{Hs_! zL0VJxTbxeZbu9x70(w@4q`H0A0em??b#4ABY}aU3&>qgNQ##g*`lH{bfm~3o1+gHq zda4*Hj6~6KwgwOS#Cg>LJYAF96~b?QUTSI(Z54U5=|Hx0c}C?}R>r%=O$g2hAZLe! zNBX@CH~T{KI~<%y_)FtH#f^&<9@I8+eUz8~V6r<(ff zR@s(4o?fLPAwvItY*^YfFBPW!vXGO^(3vD!y}?YL-EJ%pyPAxbw?Cae)uacT7zb8S zQIYWcdizbSb08ZP0}48w@b25O$4|ciQ8-M-%nXX% z)NT3hb7xW8buFnkurNkl;euMbb-_ys&a81*?|7jkjg?4U&+>ccu+y+a;+k>I6*7^7 z%pf01N6;=01kkkOU@lVJ*Dvo9xxZexLyx=6?O=GK9QIW6es4jpHLk%mW3-nFn(8=aqnH~Y$*s9AWegDw#|_q}oVlri0JqUPa24s^GS zR)7%O{FSL#v?HU-fTjckY!EdOIo-@^_H8#} zzPtAcC`xQnx4%Q@pNmz~=@;<09>%Zy)QsWl>-*BC6pBpp+X>kZ`%1Mi(x`=h`&ZZT zYd&FG7({G_sO6>mS}*D{$ucCGqps+M8D-&$SD`3`0e{-z&Wbh_ob7Y`!CW<>s$z-i zZyxGmyvZ1V(aSmwEO-H%V$A-jL_j4d#(@kHeyFN|U+4JbSgG5JrTk%x&`kAa%XN#YRMdkxAK*AqDlS#=;_e9N=gdl3i!Eo!jh5``*@+O6xZfd-;BK90s z1*}({o*Rg+^odV}_8g_p0>?3vLS!i7O$sD!{&ZJ^PjS1WSGY`HHrU}dWhazIPyrU4 zWqCda_-hWo zx}@VnmYRethr{ixhz8jn*52f2CK~NFtYwKdv1r)jx>+Zl-B%K)kvpY&SNaOZ%3r1H z#0!Bq&F_0pQ#|6j*2E$JlEwcJf-QaTo2#0a#FB=hGn#`VPa3E3!n|noNBH{jK(mfh z9&iJFx?Zj)Kli69(u0*(Jt6y3d78y<>7~=#<5g~M&x~V)3N~w;$r2Q}zgbVo9;?VB z?+qR{!9T!22Y1D9gs~V7HoXbsdcz7G5ETPpeSDvgU?0af=ayUDjWt->SNi0Xk&7&V z63FV}UBfBT>GzUY2fsH~SmcT1=1gjpO6Zcv1R|YgM6Pu-eST#G6IW9Ha3FB)bkm~X?Ek2lbipev5^bSpvinB#lQLh67r&fBKSFeSwEioR z1T@yt1Hi*{I{BgV`k1S9kS_N1?G5zcRww9>u2|RP7{2NlK6)gJ=orm=*%GYj`RqBO z;3W75x2=rJ{;eZqA(fui?ohK2#0(vO6BD3jXA2m%7ARH6MXJvTq|A3wn7 z{dD$g55p`4_P;N(cARo>S9o^#M+{qOg`p6Y{GqYzX`n)x!uFXsQ=qYOU%}7_LrGy9 z>^e^782^9z2uYcLVuQlbfklJs)9pTadw5Xx$DKm4jaV}{Fh`~wU`6gTB8&6YN{8W) zr#9*4-WsTy#;blHwMI@(?rbVme?8K;&%oBQn=!L0Rp;8Bsl>@KFt(9P&-2c7IO216 z60Pc_RAkd zyr3^iITQSFe~$t$I#+W(+_=(X!n#)68~7QMYE@A#rPPa%*O^9a#(&pz`3(%s=$AKm zE%&N+wTwP=qxdcJ^Yiw%qwm`~!MM7*y0r#tqQlXVV#31ypa+Vq0kg?-^5>sb9ho`K zt_}gQv8annODERhRWM(xt5LpeZIe+`!+C0IQj`>uQc=N*g*7=A${~>sy*!Okny%3z z^oU;A4*%flgP9s~W@c29!{z8)bn;qOM&ym3(G3eGpP;9K)OPmeq*Kbl;e$d_(y9@N z$Xerohz1oE)!oYr9Gdv6_2A&Zkez^ICO)vLs*3K?!^6XHdpI3FlM@+}T3%FI8h&wc zkv)6J3X=agjBjFYUQkwt9;vE&CaT6>ok74cW&Zx}_Sn_)&#UkvPr;*r?%s&zR{s<+ zJp2(mg_V_cGRbI%phN){fu~nOg4=%e)r)$S;rGz)p$S!(FQK8Z*jcuVO##XUl7=c4 zG;d*p2m%tEQ1DsB<(GK)_!eMzB6|Z}z%%PhR|iKwOnuTH+Y1U_+Z-KPfNdmcaB_ zCr&(@87T{kQna_ahQ@m9xnqCQQpm;5*y3VkF{RWS7{kr}c>9}EB`EotnT70y@v#6G z@bn^=^FV(_ut56#_44=3% zf59W7gl2Yt)8eNLh;SkakXs+(YALVy1q9HsunHxAQJCD_J$%PQ^9N2hZ({KB=9lm* zDeR9H>t3$_<^Pb+pWUCLxkx9nKgC4iG8+wT|FW>P5*=?_Su2Yh`&3@{_OH3lrHq18S>=2K3 zF@h?jHW6DfK7Kmi=7D-drJ6``vJzWg&-!R{wg1q8?9rJx=+-l?QPoqa-7xuer=8re za~e&%KwV8OI9gjf4Tm@ekaY&5c%Fmm<+b0P4a!}dooC&Kb!ck*3z)z&V-my$emu^N zAC9uOS1UOu1{h*;b%-zP4c63CwuA5J^tusiPoDM2Uq%5rg0xk?ZM5G^B0*!!7Kesd z5**P9cwnTzV?7fUf4gpkc^mZ-3Ua&1(F}Gy0qw)yE;R1Pn%CSe`$+@?1VX;vshO-# zr$LAy85tRAznyI2C42o~Cd=IbMM33m@W6r{Ig_AXJI~zG`vQk_zZHM{i30TJ@rotv zot3{)UpVNMSSl<94n83?DkA8ds9LDF*howxC1d+wU`#Wwf>ek^TU%SYtv&b8%yht# zkK$X9z@FiB9*`aWZ=p|fN3Tu-p)0lOpn1OdmJ2?QCKl9)rnX7Y+L;1FL+jBnNbFSz z#=HA6s0}DDy9HRI*I1(z!1vVCzQh9k>+AMUOdnMIEyd1>=TM7hpW}=}{4q+0qAM-6%K)}7jWL6g8;cN#HAd(tPA_c@``ja3a%}N6nh8=Qp-aEjT z+W5=L#--%MAYf8CHwTm3y{5=C9pV(G*Q^?ELmnN#q@Lsy9vk_!%_$taVYtCVD;yv~ z+cnBT)0)lYBLp>f%6oEZ2wA%Vl#N=k94?V-N))mqk|xz|@9r%3ADLr_RNv`!^4_@E zx>w0Wg}mI8GjrGIR6DxdTa1AEL9)a7W=tT|qmz)tdd&#FC>!}{e|yWBDQ^?OC?YxJ zaIr1_HSPa#*3+x2DHS618-f1BMXQ18a2u*g25H#)bHs5(KbOrLH8a5|1X_FQBY8Tnwf^3nry2JZ#J*F zjSZvg@oa#d!k3N)|K;!B#Z>iYrlt)46Xw>zoxQ5>3pl2X|K&h~-E}r$D0%2mG(`?p zH7zCo%c!^f@6Zjo5-99QeSJ6KujLC_s9wE#E%)*t0mpN%H8nNc@ZLrCiT8-o<8zG&XW#TTd=|Uj}g?ulNIw;tdNp0I7SMG9&lM@NjTrBNvdxSv-gFxOsS7 z%9z(mno8jxu8+j7<{I$+Y$no4L%x2^&C7$jy1Hs|*nkBzwnAj`@>uZRo?f2?#5Oh( z^d_{UW@l#~iN?Lj0W$eAkPwrKA3>4}^YaU1)ANY<^5FXw3pI6h?DC2Vhat0|%*=P8 z$nT1w(}JsZ3i8<%jR!eQoNbNGimg`0O@|EaiK=NUEuqc+u6mHJ|3qZaBh>2AGa1_X zrM+&aFA)G@ZVhg1-$dgDBwJeIaoJ{pPUGTB1PRNjJ4ViwwJb~+!w@u zV+a7!&$Rz#yq68tP71^nr2aMl9lszKAY=XWlfN&4k9mp!$PqWr1L1$)0HAHJ`AcGZ zxoIfG%fPN|-~u!2l>htv+^$@#T5X%tvx^^oPze)p8%C|qrojJjypoYn5U&c&d C Date: Mon, 1 Apr 2024 18:53:48 +0900 Subject: [PATCH 05/29] feat(perception_online_evaluator): unify debug markers instead of separating for each object (#6681) * feat(perception_online_evaluator): unify debug markers instead of separating for each object Signed-off-by: kosuke55 * fix for Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 --- .../utils/marker_utils.hpp | 6 +- .../src/perception_online_evaluator_node.cpp | 94 ++++++++++++------- .../src/utils/marker_utils.cpp | 11 ++- 3 files changed, 68 insertions(+), 43 deletions(-) diff --git a/evaluator/perception_online_evaluator/include/perception_online_evaluator/utils/marker_utils.hpp b/evaluator/perception_online_evaluator/include/perception_online_evaluator/utils/marker_utils.hpp index 3ac4c1db9efbd..0831d580248d3 100644 --- a/evaluator/perception_online_evaluator/include/perception_online_evaluator/utils/marker_utils.hpp +++ b/evaluator/perception_online_evaluator/include/perception_online_evaluator/utils/marker_utils.hpp @@ -63,8 +63,8 @@ MarkerArray createPoseMarkerArray( const float & b); MarkerArray createPosesMarkerArray( - const std::vector poses, std::string && ns, const float & r, const float & g, - const float & b, const float & x_scale = 0.5, const float & y_scale = 0.2, + const std::vector poses, std::string && ns, const int32_t & first_id, const float & r, + const float & g, const float & b, const float & x_scale = 0.5, const float & y_scale = 0.2, const float & z_scale = 0.2); std_msgs::msg::ColorRGBA createColorFromString(const std::string & str); @@ -75,7 +75,7 @@ MarkerArray createObjectPolygonMarkerArray( MarkerArray createDeviationLines( const std::vector poses1, const std::vector poses2, const std::string & ns, - const float r, const float g, const float b); + const int32_t & first_id, const float r, const float g, const float b); } // namespace marker_utils diff --git a/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp b/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp index 8820ad16fd8d5..f3a08bf42797a 100644 --- a/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp +++ b/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp @@ -132,50 +132,74 @@ void PerceptionOnlineEvaluatorNode::publishDebugMarker() tier4_autoware_utils::appendMarkerArray(added, &marker); }; - const auto history_path_map = metrics_calculator_.getHistoryPathMap(); const auto & p = parameters_->debug_marker_parameters; - for (const auto & [uuid, history_path] : history_path_map) { - { - const auto c = createColorFromString(uuid + "_raw"); - if (p.show_history_path) { - add(createPointsMarkerArray(history_path.first, "history_path_" + uuid, 0, c.r, c.g, c.b)); + // visualize history path + { + const auto history_path_map = metrics_calculator_.getHistoryPathMap(); + int32_t history_path_first_id = 0; + int32_t smoothed_history_path_first_id = 0; + size_t i = 0; + for (const auto & [uuid, history_path] : history_path_map) { + { + const auto c = createColorFromString(uuid + "_raw"); + if (p.show_history_path) { + add(createPointsMarkerArray(history_path.first, "history_path", i, c.r, c.g, c.b)); + } + if (p.show_history_path_arrows) { + add(createPosesMarkerArray( + history_path.first, "history_path_arrows", history_path_first_id, c.r, c.g, c.b, 0.1, + 0.05, 0.05)); + history_path_first_id += history_path.first.size(); + } } - if (p.show_history_path_arrows) { - add(createPosesMarkerArray( - history_path.first, "history_path_arrows_" + uuid, c.r, c.g, c.b, 0.1, 0.05, 0.05)); + { + const auto c = createColorFromString(uuid); + if (p.show_smoothed_history_path) { + add(createPointsMarkerArray( + history_path.second, "smoothed_history_path", i, c.r, c.g, c.b)); + } + if (p.show_smoothed_history_path_arrows) { + add(createPosesMarkerArray( + history_path.second, "smoothed_history_path_arrows", smoothed_history_path_first_id, + c.r, c.g, c.b, 0.1, 0.05, 0.05)); + smoothed_history_path_first_id += history_path.second.size(); + } } + i++; } - { + } + + // visualize predicted path of past objects + { + int32_t predicted_path_first_id = 0; + int32_t history_path_first_id = 0; + int32_t deviation_lines_first_id = 0; + size_t i = 0; + const auto object_data_map = metrics_calculator_.getDebugObjectData(); + for (const auto & [uuid, object_data] : object_data_map) { const auto c = createColorFromString(uuid); - if (p.show_smoothed_history_path) { - add(createPointsMarkerArray( - history_path.second, "smoothed_history_path_" + uuid, 0, c.r, c.g, c.b)); + const auto predicted_path = object_data.getPredictedPath(); + const auto history_path = object_data.getHistoryPath(); + if (p.show_predicted_path) { + add(createPosesMarkerArray( + predicted_path, "predicted_path", predicted_path_first_id, 0, 0, 1)); + predicted_path_first_id += predicted_path.size(); } - if (p.show_smoothed_history_path_arrows) { + if (p.show_predicted_path_gt) { add(createPosesMarkerArray( - history_path.second, "smoothed_history_path_arrows_" + uuid, c.r, c.g, c.b, 0.1, 0.05, - 0.05)); + history_path, "predicted_path_gt", history_path_first_id, 1, 0, 0)); + history_path_first_id += history_path.size(); } - } - } - const auto object_data_map = metrics_calculator_.getDebugObjectData(); - for (const auto & [uuid, object_data] : object_data_map) { - const auto c = createColorFromString(uuid); - const auto predicted_path = object_data.getPredictedPath(); - const auto history_path = object_data.getHistoryPath(); - if (p.show_predicted_path) { - add(createPosesMarkerArray(predicted_path, "predicted_path_" + uuid, 0, 0, 1)); - } - if (p.show_predicted_path_gt) { - add(createPosesMarkerArray(history_path, "predicted_path_gt_" + uuid, 1, 0, 0)); - } - if (p.show_deviation_lines) { - add(createDeviationLines(predicted_path, history_path, "deviation_lines_" + uuid, 1, 1, 1)); - } - if (p.show_object_polygon) { - add(createObjectPolygonMarkerArray( - object_data.object, "object_polygon_" + uuid, 0, c.r, c.g, c.b)); + if (p.show_deviation_lines) { + add(createDeviationLines( + predicted_path, history_path, "deviation_lines", deviation_lines_first_id, 1, 1, 1)); + deviation_lines_first_id += predicted_path.size(); + } + if (p.show_object_polygon) { + add(createObjectPolygonMarkerArray(object_data.object, "object_polygon", i, c.r, c.g, c.b)); + } + i++; } } diff --git a/evaluator/perception_online_evaluator/src/utils/marker_utils.cpp b/evaluator/perception_online_evaluator/src/utils/marker_utils.cpp index 75af92e83dcd8..a29e1a468e983 100644 --- a/evaluator/perception_online_evaluator/src/utils/marker_utils.cpp +++ b/evaluator/perception_online_evaluator/src/utils/marker_utils.cpp @@ -111,14 +111,14 @@ MarkerArray createPointsMarkerArray( MarkerArray createDeviationLines( const std::vector poses1, const std::vector poses2, const std::string & ns, - const float r, const float g, const float b) + const int32_t & first_id, const float r, const float g, const float b) { MarkerArray msg; const size_t max_idx = std::min(poses1.size(), poses2.size()); for (size_t i = 0; i < max_idx; ++i) { auto marker = createDefaultMarker( - "map", rclcpp::Clock{RCL_ROS_TIME}.now(), ns, i, Marker::LINE_STRIP, + "map", rclcpp::Clock{RCL_ROS_TIME}.now(), ns, first_id + i, Marker::LINE_STRIP, createMarkerScale(0.005, 0.0, 0.0), createMarkerColor(r, g, b, 0.5)); marker.points.push_back(poses1.at(i).position); marker.points.push_back(poses2.at(i).position); @@ -144,14 +144,15 @@ MarkerArray createPoseMarkerArray( } MarkerArray createPosesMarkerArray( - const std::vector poses, std::string && ns, const float & r, const float & g, - const float & b, const float & x_scale, const float & y_scale, const float & z_scale) + const std::vector poses, std::string && ns, const int32_t & first_id, const float & r, + const float & g, const float & b, const float & x_scale, const float & y_scale, + const float & z_scale) { MarkerArray msg; for (size_t i = 0; i < poses.size(); ++i) { Marker marker = createDefaultMarker( - "map", rclcpp::Clock{RCL_ROS_TIME}.now(), ns, i, Marker::ARROW, + "map", rclcpp::Clock{RCL_ROS_TIME}.now(), ns, first_id + i, Marker::ARROW, createMarkerScale(x_scale, y_scale, z_scale), createMarkerColor(r, g, b, 0.5)); marker.pose = poses.at(i); msg.markers.push_back(marker); From d9264277833ae2474c5db41ccc43db262dd1ae1d Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Mon, 1 Apr 2024 18:54:27 +0900 Subject: [PATCH 06/29] feat(perception_online_evaluator): extract moving object for deviation check (#6682) fix test Signed-off-by: kosuke55 --- .../perception_online_evaluator.defaults.yaml | 2 +- .../src/metrics_calculator.cpp | 90 +++++++++++++++---- .../test_perception_online_evaluator_node.cpp | 65 +++++++++----- 3 files changed, 114 insertions(+), 43 deletions(-) diff --git a/evaluator/perception_online_evaluator/param/perception_online_evaluator.defaults.yaml b/evaluator/perception_online_evaluator/param/perception_online_evaluator.defaults.yaml index 976b10a2c73f9..46ea68c991090 100644 --- a/evaluator/perception_online_evaluator/param/perception_online_evaluator.defaults.yaml +++ b/evaluator/perception_online_evaluator/param/perception_online_evaluator.defaults.yaml @@ -11,7 +11,7 @@ prediction_time_horizons: [1.0, 2.0, 3.0, 5.0] - stopped_velocity_threshold: 0.3 + stopped_velocity_threshold: 1.0 target_object: car: diff --git a/evaluator/perception_online_evaluator/src/metrics_calculator.cpp b/evaluator/perception_online_evaluator/src/metrics_calculator.cpp index 60e02c8f24c39..20d8c6d570489 100644 --- a/evaluator/perception_online_evaluator/src/metrics_calculator.cpp +++ b/evaluator/perception_online_evaluator/src/metrics_calculator.cpp @@ -37,20 +37,25 @@ std::optional MetricsCalculator::calculate(const Metric & metric) return {}; } const auto target_stamp_objects = getObjectsByStamp(target_stamp); - const auto class_objects_map = separateObjectsByClass(target_stamp_objects); - // filter stopped objects + // extract moving objects + const auto moving_objects = filterObjectsByVelocity( + target_stamp_objects, parameters_->stopped_velocity_threshold, + /*remove_above_threshold=*/false); + const auto class_moving_objects_map = separateObjectsByClass(moving_objects); + + // extract stopped objects const auto stopped_objects = filterObjectsByVelocity(target_stamp_objects, parameters_->stopped_velocity_threshold); const auto class_stopped_objects_map = separateObjectsByClass(stopped_objects); switch (metric) { case Metric::lateral_deviation: - return calcLateralDeviationMetrics(class_objects_map); + return calcLateralDeviationMetrics(class_moving_objects_map); case Metric::yaw_deviation: - return calcYawDeviationMetrics(class_objects_map); + return calcYawDeviationMetrics(class_moving_objects_map); case Metric::predicted_path_deviation: - return calcPredictedPathDeviationMetrics(class_objects_map); + return calcPredictedPathDeviationMetrics(class_moving_objects_map); case Metric::yaw_rate: return calcYawRateMetrics(class_stopped_objects_map); default: @@ -372,7 +377,7 @@ MetricStatMap MetricsCalculator::calcYawRateMetrics(const ClassObjectsMap & clas } const auto [previous_stamp, previous_object] = previous_object_with_stamp_opt.value(); - const auto time_diff = (stamp - previous_stamp).seconds(); + const double time_diff = (stamp - previous_stamp).seconds(); if (time_diff < 0.01) { continue; } @@ -443,7 +448,34 @@ void MetricsCalculator::updateHistoryPath() for (const auto & [uuid, stamp_and_objects] : object_map_) { std::vector history_path; - for (const auto & [stamp, object] : stamp_and_objects) { + for (auto it = stamp_and_objects.begin(); it != stamp_and_objects.end(); ++it) { + const auto & [stamp, object] = *it; + + // skip if the object is stopped + // calculate velocity from previous object + if (it != stamp_and_objects.begin()) { + const auto & [prev_stamp, prev_object] = *std::prev(it); + const double time_diff = (stamp - prev_stamp).seconds(); + if (time_diff < 0.01) { + continue; + } + const auto current_pose = object.kinematics.initial_pose_with_covariance.pose; + const auto prev_pose = prev_object.kinematics.initial_pose_with_covariance.pose; + const auto velocity = + tier4_autoware_utils::calcDistance2d(current_pose.position, prev_pose.position) / + time_diff; + if (velocity < parameters_->stopped_velocity_threshold) { + continue; + } + } + if ( + std::hypot( + object.kinematics.initial_twist_with_covariance.twist.linear.x, + object.kinematics.initial_twist_with_covariance.twist.linear.y) < + parameters_->stopped_velocity_threshold) { + continue; + } + history_path.push_back(object.kinematics.initial_pose_with_covariance.pose); } @@ -507,27 +539,49 @@ std::vector MetricsCalculator::averageFilterPath( average_pose.position = path.at(i).position; } + // skip if the points are too close + if ( + filtered_path.size() > 0 && + calcDistance2d(filtered_path.back().position, average_pose.position) < 0.5) { + continue; + } + + // skip if the difference between the current orientation and the azimuth angle is large + if (i > 0) { + const double azimuth = calcAzimuthAngle(path.at(i - 1).position, path.at(i).position); + const double yaw = tf2::getYaw(path.at(i).orientation); + if (tier4_autoware_utils::normalizeRadian(yaw - azimuth) > M_PI_2) { + continue; + } + } + // Placeholder for orientation to ensure structure integrity average_pose.orientation = path.at(i).orientation; filtered_path.push_back(average_pose); } - // Calculate yaw and convert to quaternion after averaging positions - for (size_t i = 0; i < filtered_path.size(); ++i) { - Pose & p = filtered_path[i]; - - // if the current pose is too close to the previous one, use the previous orientation - if (i > 0) { - const Pose & p_prev = filtered_path[i - 1]; - if (calcDistance2d(p_prev.position, p.position) < 0.1) { - p.orientation = p_prev.orientation; + // delete pose if the difference between the azimuth angle of the previous and next poses is large + if (filtered_path.size() > 2) { + auto it = filtered_path.begin() + 2; + while (it != filtered_path.end()) { + const double azimuth_to_prev = calcAzimuthAngle((it - 2)->position, (it - 1)->position); + const double azimuth_to_current = calcAzimuthAngle((it - 1)->position, it->position); + if ( + std::abs(tier4_autoware_utils::normalizeRadian(azimuth_to_prev - azimuth_to_current)) > + M_PI_2) { + it = filtered_path.erase(it); continue; } + ++it; } + } + // Calculate yaw and convert to quaternion after averaging positions + for (size_t i = 0; i < filtered_path.size(); ++i) { + Pose & p = filtered_path[i]; if (i < filtered_path.size() - 1) { - const double yaw = calcAzimuthAngle(p.position, filtered_path[i + 1].position); - filtered_path[i].orientation = createQuaternionFromYaw(yaw); + const double azimuth_to_next = calcAzimuthAngle(p.position, filtered_path[i + 1].position); + filtered_path[i].orientation = createQuaternionFromYaw(azimuth_to_next); } else if (filtered_path.size() > 1) { // For the last point, use the orientation of the second-to-last point p.orientation = filtered_path[i - 1].orientation; diff --git a/evaluator/perception_online_evaluator/test/test_perception_online_evaluator_node.cpp b/evaluator/perception_online_evaluator/test/test_perception_online_evaluator_node.cpp index 2975a1b4d6df8..dabd17b9db46a 100644 --- a/evaluator/perception_online_evaluator/test/test_perception_online_evaluator_node.cpp +++ b/evaluator/perception_online_evaluator/test/test_perception_online_evaluator_node.cpp @@ -115,7 +115,7 @@ class EvalTest : public ::testing::Test PredictedObject makePredictedObject( const std::vector> & predicted_path, - const uint8_t label = ObjectClassification::CAR) + const uint8_t label = ObjectClassification::CAR, const double velocity = 2.0) { PredictedObject object; object.object_id = uuid_; @@ -133,6 +133,10 @@ class EvalTest : public ::testing::Test object.kinematics.initial_pose_with_covariance.pose.orientation.z = 0.0; object.kinematics.initial_pose_with_covariance.pose.orientation.w = 1.0; + object.kinematics.initial_twist_with_covariance.twist.linear.x = velocity; + object.kinematics.initial_twist_with_covariance.twist.linear.y = 0.0; + object.kinematics.initial_twist_with_covariance.twist.linear.z = 0.0; + autoware_auto_perception_msgs::msg::PredictedPath path; for (size_t i = 0; i < predicted_path.size(); ++i) { geometry_msgs::msg::Pose pose; @@ -155,34 +159,35 @@ class EvalTest : public ::testing::Test PredictedObjects makePredictedObjects( const std::vector> & predicted_path, - const uint8_t label = ObjectClassification::CAR) + const uint8_t label = ObjectClassification::CAR, const double velocity = 2.0) { PredictedObjects objects; - objects.objects.push_back(makePredictedObject(predicted_path, label)); + objects.objects.push_back(makePredictedObject(predicted_path, label, velocity)); objects.header.stamp = rclcpp::Time(0); return objects; } PredictedObjects makeStraightPredictedObjects( - const double time, const uint8_t label = ObjectClassification::CAR) + const double time, const uint8_t label = ObjectClassification::CAR, const double velocity = 2.0) { std::vector> predicted_path; for (size_t i = 0; i <= time_horizon_ / time_step_; i++) { - predicted_path.push_back({velocity_ * (time + i * time_step_), 0.0}); + predicted_path.push_back({velocity * (time + i * time_step_), 0.0}); } - auto objects = makePredictedObjects(predicted_path, label); + auto objects = makePredictedObjects(predicted_path, label, velocity); objects.header.stamp = rclcpp::Time(0) + rclcpp::Duration::from_seconds(time); return objects; } PredictedObjects makeDeviatedStraightPredictedObjects( - const double time, const double deviation, const uint8_t label = ObjectClassification::CAR) + const double time, const double deviation, const uint8_t label = ObjectClassification::CAR, + const double velocity = 2.0) { std::vector> predicted_path; for (size_t i = 0; i <= time_horizon_ / time_step_; i++) { - predicted_path.push_back({velocity_ * (time + i * time_step_), deviation}); + predicted_path.push_back({velocity * (time + i * time_step_), deviation}); } - auto objects = makePredictedObjects(predicted_path, label); + auto objects = makePredictedObjects(predicted_path, label, velocity); objects.header.stamp = rclcpp::Time(0) + rclcpp::Duration::from_seconds(time); return objects; } @@ -249,7 +254,6 @@ class EvalTest : public ::testing::Test double time_delay_ = 5.0; double time_step_ = 0.5; double time_horizon_ = 10.0; - double velocity_ = 2.0; unique_identifier_msgs::msg::UUID uuid_; }; @@ -589,11 +593,12 @@ TEST_F(EvalTest, testYawRate_0) setTargetMetric("yaw_rate_CAR"); for (double time = 0; time <= time_delay_; time += time_step_) { - const auto objects = makeStraightPredictedObjects(time); + const auto objects = makeStraightPredictedObjects(time, ObjectClassification::CAR, 0.0); publishObjects(objects); } - const auto last_objects = makeStraightPredictedObjects(time_delay_ + time_step_); + const auto last_objects = + makeStraightPredictedObjects(time_delay_ + time_step_, ObjectClassification::CAR, 0.0); EXPECT_NEAR(publishObjectsAndGetMetric(last_objects), 0.0, epsilon); } @@ -605,12 +610,14 @@ TEST_F(EvalTest, testYawRate_01) const double yaw_rate = 0.1; for (double time = 0; time <= time_delay_; time += time_step_) { - const auto objects = rotateObjects(makeStraightPredictedObjects(time), yaw_rate * time); + const auto objects = rotateObjects( + makeStraightPredictedObjects(time, ObjectClassification::CAR, 0.0), yaw_rate * time); publishObjects(objects); } for (double time = time_delay_ + time_step_; time < time_delay_ * 2; time += time_step_) { - const auto objects = rotateObjects(makeStraightPredictedObjects(time), yaw_rate * time); + const auto objects = rotateObjects( + makeStraightPredictedObjects(time, ObjectClassification::CAR, 0.0), yaw_rate * time); EXPECT_NEAR(publishObjectsAndGetMetric(objects), yaw_rate, epsilon); } } @@ -623,12 +630,14 @@ TEST_F(EvalTest, testYawRate_minus_01) const double yaw_rate = 0.1; for (double time = 0; time <= time_delay_; time += time_step_) { - const auto objects = rotateObjects(makeStraightPredictedObjects(time), -yaw_rate * time); + const auto objects = rotateObjects( + makeStraightPredictedObjects(time, ObjectClassification::CAR, 0.0), -yaw_rate * time); publishObjects(objects); } for (double time = time_delay_ + time_step_; time < time_delay_ * 2; time += time_step_) { - const auto objects = rotateObjects(makeStraightPredictedObjects(time), -yaw_rate * time); + const auto objects = rotateObjects( + makeStraightPredictedObjects(time, ObjectClassification::CAR, 0.0), -yaw_rate * time); EXPECT_NEAR(publishObjectsAndGetMetric(objects), yaw_rate, epsilon); } } @@ -641,12 +650,14 @@ TEST_F(EvalTest, testYawRate_1) const double yaw_rate = 1.0; for (double time = 0; time <= time_delay_; time += time_step_) { - const auto objects = rotateObjects(makeStraightPredictedObjects(time), yaw_rate * time); + const auto objects = rotateObjects( + makeStraightPredictedObjects(time, ObjectClassification::CAR, 0.0), yaw_rate * time); publishObjects(objects); } for (double time = time_delay_ + time_step_; time < time_delay_ * 2; time += time_step_) { - const auto objects = rotateObjects(makeStraightPredictedObjects(time), yaw_rate * time); + const auto objects = rotateObjects( + makeStraightPredictedObjects(time, ObjectClassification::CAR, 0.0), yaw_rate * time); EXPECT_NEAR(publishObjectsAndGetMetric(objects), yaw_rate, epsilon); } } @@ -659,12 +670,14 @@ TEST_F(EvalTest, testYawRate_minus_1) const double yaw_rate = 1.0; for (double time = 0; time <= time_delay_; time += time_step_) { - const auto objects = rotateObjects(makeStraightPredictedObjects(time), -yaw_rate * time); + const auto objects = rotateObjects( + makeStraightPredictedObjects(time, ObjectClassification::CAR, 0.0), -yaw_rate * time); publishObjects(objects); } for (double time = time_delay_ + time_step_; time < time_delay_ * 2; time += time_step_) { - const auto objects = rotateObjects(makeStraightPredictedObjects(time), -yaw_rate * time); + const auto objects = rotateObjects( + makeStraightPredictedObjects(time, ObjectClassification::CAR, 0.0), -yaw_rate * time); EXPECT_NEAR(publishObjectsAndGetMetric(objects), yaw_rate, epsilon); } } @@ -677,12 +690,14 @@ TEST_F(EvalTest, testYawRate_5) const double yaw_rate = 5.0; for (double time = 0; time <= time_delay_; time += time_step_) { - const auto objects = rotateObjects(makeStraightPredictedObjects(time), yaw_rate * time); + const auto objects = rotateObjects( + makeStraightPredictedObjects(time, ObjectClassification::CAR, 0.0), yaw_rate * time); publishObjects(objects); } for (double time = time_delay_ + time_step_; time < time_delay_ * 2; time += time_step_) { - const auto objects = rotateObjects(makeStraightPredictedObjects(time), yaw_rate * time); + const auto objects = rotateObjects( + makeStraightPredictedObjects(time, ObjectClassification::CAR, 0.0), yaw_rate * time); EXPECT_NEAR(publishObjectsAndGetMetric(objects), yaw_rate, epsilon); } } @@ -695,12 +710,14 @@ TEST_F(EvalTest, testYawRate_minus_5) const double yaw_rate = 5.0; for (double time = 0; time <= time_delay_; time += time_step_) { - const auto objects = rotateObjects(makeStraightPredictedObjects(time), -yaw_rate * time); + const auto objects = rotateObjects( + makeStraightPredictedObjects(time, ObjectClassification::CAR, 0.0), -yaw_rate * time); publishObjects(objects); } for (double time = time_delay_ + time_step_; time < time_delay_ * 2; time += time_step_) { - const auto objects = rotateObjects(makeStraightPredictedObjects(time), -yaw_rate * time); + const auto objects = rotateObjects( + makeStraightPredictedObjects(time, ObjectClassification::CAR, 0.0), -yaw_rate * time); EXPECT_NEAR(publishObjectsAndGetMetric(objects), yaw_rate, epsilon); } } From 2fd07d1c6f8c5e61756ceb6bab4e205848420f8e Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Mon, 1 Apr 2024 22:40:00 +0900 Subject: [PATCH 07/29] feat(start_planner): add validation check to prevent over cropped paths (#6721) * add validation check to prevent over cropped paths Signed-off-by: Daniel Sanchez * use constexpr for magic number Signed-off-by: Daniel Sanchez * make the threshold a param Signed-off-by: Daniel Sanchez --------- Signed-off-by: Daniel Sanchez --- .../config/start_planner.param.yaml | 1 + .../data_structs.hpp | 1 + .../src/manager.cpp | 4 ++++ .../src/shift_pull_out.cpp | 20 +++++++++++++++++++ 4 files changed, 26 insertions(+) diff --git a/planning/behavior_path_start_planner_module/config/start_planner.param.yaml b/planning/behavior_path_start_planner_module/config/start_planner.param.yaml index b17db7f907471..46469de68149e 100644 --- a/planning/behavior_path_start_planner_module/config/start_planner.param.yaml +++ b/planning/behavior_path_start_planner_module/config/start_planner.param.yaml @@ -27,6 +27,7 @@ shift_collision_check_distance_from_end: -10.0 minimum_shift_pull_out_distance: 0.0 deceleration_interval: 15.0 + maximum_longitudinal_deviation: 1.0 # Note, should be the same or less than planning validator's "longitudinal_distance_deviation" lateral_jerk: 0.5 lateral_acceleration_sampling_num: 3 minimum_lateral_acc: 0.15 diff --git a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/data_structs.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/data_structs.hpp index 1e32237ffd870..0e85c1d0e76b3 100644 --- a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/data_structs.hpp +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/data_structs.hpp @@ -84,6 +84,7 @@ struct StartPlannerParameters double minimum_lateral_acc{0.0}; double maximum_curvature{0.0}; // maximum curvature considered in the path generation double deceleration_interval{0.0}; + double maximum_longitudinal_deviation{0.0}; // geometric pull out bool enable_geometric_pull_out{false}; double geometric_collision_check_distance_from_end; diff --git a/planning/behavior_path_start_planner_module/src/manager.cpp b/planning/behavior_path_start_planner_module/src/manager.cpp index 050d591128a15..794577d7cc7aa 100644 --- a/planning/behavior_path_start_planner_module/src/manager.cpp +++ b/planning/behavior_path_start_planner_module/src/manager.cpp @@ -88,6 +88,8 @@ void StartPlannerModuleManager::init(rclcpp::Node * node) p.minimum_lateral_acc = node->declare_parameter(ns + "minimum_lateral_acc"); p.maximum_curvature = node->declare_parameter(ns + "maximum_curvature"); p.deceleration_interval = node->declare_parameter(ns + "deceleration_interval"); + p.maximum_longitudinal_deviation = + node->declare_parameter(ns + "maximum_longitudinal_deviation"); // geometric pull out p.enable_geometric_pull_out = node->declare_parameter(ns + "enable_geometric_pull_out"); p.geometric_collision_check_distance_from_end = @@ -424,6 +426,8 @@ void StartPlannerModuleManager::updateModuleParams( updateParam(parameters, ns + "minimum_lateral_acc", p->minimum_lateral_acc); updateParam(parameters, ns + "maximum_curvature", p->maximum_curvature); updateParam(parameters, ns + "deceleration_interval", p->deceleration_interval); + updateParam( + parameters, ns + "maximum_longitudinal_deviation", p->maximum_longitudinal_deviation); updateParam(parameters, ns + "enable_geometric_pull_out", p->enable_geometric_pull_out); updateParam(parameters, ns + "divide_pull_out_path", p->divide_pull_out_path); updateParam( diff --git a/planning/behavior_path_start_planner_module/src/shift_pull_out.cpp b/planning/behavior_path_start_planner_module/src/shift_pull_out.cpp index c6a56139e63d2..592f57ed97dcf 100644 --- a/planning/behavior_path_start_planner_module/src/shift_pull_out.cpp +++ b/planning/behavior_path_start_planner_module/src/shift_pull_out.cpp @@ -111,6 +111,26 @@ std::optional ShiftPullOut::plan(const Pose & start_pose, const Pos const auto cropped_path = lane_departure_checker_->cropPointsOutsideOfLanes( lanelet_map_ptr, shift_path, start_segment_idx); if (cropped_path.points.empty()) continue; + + // check that the path is not cropped in excess and there is not excessive longitudinal + // deviation between the first 2 points + auto validate_cropped_path = [&](const auto & cropped_path) -> bool { + if (cropped_path.points.size() < 2) return false; + const double max_long_offset = parameters_.maximum_longitudinal_deviation; + const size_t start_segment_idx_after_crop = + motion_utils::findFirstNearestIndexWithSoftConstraints(cropped_path.points, start_pose); + + // if the start segment id after crop is not 0, then the cropping is not excessive + if (start_segment_idx_after_crop != 0) return true; + + const auto long_offset_to_closest_point = motion_utils::calcLongitudinalOffsetToSegment( + cropped_path.points, start_segment_idx_after_crop, start_pose.position); + const auto long_offset_to_next_point = motion_utils::calcLongitudinalOffsetToSegment( + cropped_path.points, start_segment_idx_after_crop + 1, start_pose.position); + return std::abs(long_offset_to_closest_point - long_offset_to_next_point) < max_long_offset; + }; + + if (!validate_cropped_path(cropped_path)) continue; shift_path.points = cropped_path.points; shift_path.header = planner_data_->route_handler->getRouteHeader(); From 5f9444de3d89f6a1cf1a6ca4517b8c8f90841432 Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Mon, 1 Apr 2024 22:40:19 +0900 Subject: [PATCH 08/29] feat(obstacle_avoidance_planner): sanitize reference points (#6704) * feat(obstacle_avoidance_planner): sanitize reference points Signed-off-by: Daniel Sanchez * bugfix, first point was excluded Signed-off-by: Daniel Sanchez --------- Signed-off-by: Daniel Sanchez --- .../utils/trajectory_utils.hpp | 2 ++ .../src/mpt_optimizer.cpp | 4 ++++ .../src/utils/trajectory_utils.cpp | 18 ++++++++++++++++++ 3 files changed, 24 insertions(+) diff --git a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/utils/trajectory_utils.hpp b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/utils/trajectory_utils.hpp index fb49a7fa446be..d119acf09b6ea 100644 --- a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/utils/trajectory_utils.hpp +++ b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/utils/trajectory_utils.hpp @@ -129,6 +129,8 @@ ReferencePoint convertToReferencePoint(const TrajectoryPoint & traj_point); std::vector convertToReferencePoints( const std::vector & traj_points); +std::vector sanitizePoints(const std::vector & points); + void compensateLastPose( const PathPoint & last_path_point, std::vector & traj_points, const double delta_dist_threshold, const double delta_yaw_threshold); diff --git a/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp b/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp index 7057a2885fd52..94dc62b1335d4 100644 --- a/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp +++ b/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp @@ -567,6 +567,9 @@ std::vector MPTOptimizer::calcReferencePoints( ref_points = motion_utils::cropPoints( ref_points, p.ego_pose.position, ego_seg_idx, forward_traj_length + tmp_margin, backward_traj_length + tmp_margin); + + // remove repeated points + ref_points = trajectory_utils::sanitizePoints(ref_points); SplineInterpolationPoints2d ref_points_spline(ref_points); ego_seg_idx = trajectory_utils::findEgoSegmentIndex(ref_points, p.ego_pose, ego_nearest_param_); @@ -586,6 +589,7 @@ std::vector MPTOptimizer::calcReferencePoints( // NOTE: This must be after backward cropping. // New start point may be added and resampled. Spline calculation is required. updateFixedPoint(ref_points); + ref_points = trajectory_utils::sanitizePoints(ref_points); ref_points_spline = SplineInterpolationPoints2d(ref_points); // 6. update bounds diff --git a/planning/obstacle_avoidance_planner/src/utils/trajectory_utils.cpp b/planning/obstacle_avoidance_planner/src/utils/trajectory_utils.cpp index 453d55bd7f770..651b11b28e8bc 100644 --- a/planning/obstacle_avoidance_planner/src/utils/trajectory_utils.cpp +++ b/planning/obstacle_avoidance_planner/src/utils/trajectory_utils.cpp @@ -79,6 +79,24 @@ std::vector convertToReferencePoints( return ref_points; } +std::vector sanitizePoints(const std::vector & points) +{ + std::vector output; + for (size_t i = 0; i < points.size(); i++) { + if (i > 0) { + const auto & current_pos = points.at(i).pose.position; + const auto & prev_pos = points.at(i - 1).pose.position; + if ( + std::fabs(current_pos.x - prev_pos.x) < 1e-6 && + std::fabs(current_pos.y - prev_pos.y) < 1e-6) { + continue; + } + } + output.push_back(points.at(i)); + } + return output; +} + void compensateLastPose( const PathPoint & last_path_point, std::vector & traj_points, const double delta_dist_threshold, const double delta_yaw_threshold) From 3da976cd489361eba898febd10343404350ddfa9 Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Tue, 2 Apr 2024 09:54:15 +0900 Subject: [PATCH 09/29] fix(pose_initializer): added "user_defined_initial_pose" to dummy localization (#6723) Added "used_defined_initial_pose" to dummy localization Signed-off-by: Shintaro Sakoda --- launch/tier4_simulator_launch/launch/simulator.launch.xml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/launch/tier4_simulator_launch/launch/simulator.launch.xml b/launch/tier4_simulator_launch/launch/simulator.launch.xml index 4af7b3abaa2e6..76fb66e4ebfdf 100644 --- a/launch/tier4_simulator_launch/launch/simulator.launch.xml +++ b/launch/tier4_simulator_launch/launch/simulator.launch.xml @@ -127,6 +127,8 @@ + + From faeee272b5aab8ab9e841c1b44aab730560aff8a Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 2 Apr 2024 15:15:31 +0900 Subject: [PATCH 10/29] feat(static_centerline_optimizer): static centerline optimizer with GUI (#6717) feat: add GUI for static centerline optimizer Signed-off-by: Takayuki Murooka --- .../static_centerline_optimizer_node.hpp | 18 ++ .../static_centerline_optimizer.launch.xml | 1 + .../scripts/centerline_updater_helper.py | 198 ++++++++++++++++++ .../scripts/tmp/run.sh | 2 +- .../src/static_centerline_optimizer_node.cpp | 67 ++++++ 5 files changed, 285 insertions(+), 1 deletion(-) create mode 100755 planning/static_centerline_optimizer/scripts/centerline_updater_helper.py diff --git a/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp b/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp index fa7043de42f5c..f25a6771aa0cb 100644 --- a/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp +++ b/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp @@ -22,6 +22,9 @@ #include "static_centerline_optimizer/type_alias.hpp" #include "vehicle_info_util/vehicle_info_util.hpp" +#include "std_msgs/msg/bool.hpp" +#include "std_msgs/msg/int32.hpp" + #include #include #include @@ -67,13 +70,28 @@ class StaticCenterlineOptimizerNode : public rclcpp::Node HADMapBin::ConstSharedPtr map_bin_ptr_{nullptr}; std::shared_ptr route_handler_ptr_{nullptr}; + int traj_start_index_{0}; + int traj_end_index_{0}; + struct MetaDataToSaveMap + { + std::vector optimized_traj_points{}; + std::vector route_lane_ids{}; + }; + std::optional meta_data_to_save_map_{std::nullopt}; + // publisher rclcpp::Publisher::SharedPtr pub_map_bin_{nullptr}; rclcpp::Publisher::SharedPtr pub_raw_path_with_lane_id_{nullptr}; rclcpp::Publisher::SharedPtr pub_raw_path_{nullptr}; rclcpp::Publisher::SharedPtr pub_debug_unsafe_footprints_{nullptr}; + rclcpp::Publisher::SharedPtr pub_whole_optimized_centerline_{nullptr}; rclcpp::Publisher::SharedPtr pub_optimized_centerline_{nullptr}; + // subscriber + rclcpp::Subscription::SharedPtr sub_traj_start_index_; + rclcpp::Subscription::SharedPtr sub_traj_end_index_; + rclcpp::Subscription::SharedPtr sub_save_map_; + // service rclcpp::Service::SharedPtr srv_load_map_; rclcpp::Service::SharedPtr srv_plan_route_; diff --git a/planning/static_centerline_optimizer/launch/static_centerline_optimizer.launch.xml b/planning/static_centerline_optimizer/launch/static_centerline_optimizer.launch.xml index 37a9abc47bfeb..2e163e2eb93eb 100644 --- a/planning/static_centerline_optimizer/launch/static_centerline_optimizer.launch.xml +++ b/planning/static_centerline_optimizer/launch/static_centerline_optimizer.launch.xml @@ -56,6 +56,7 @@ + diff --git a/planning/static_centerline_optimizer/scripts/centerline_updater_helper.py b/planning/static_centerline_optimizer/scripts/centerline_updater_helper.py new file mode 100755 index 0000000000000..00a646406f14f --- /dev/null +++ b/planning/static_centerline_optimizer/scripts/centerline_updater_helper.py @@ -0,0 +1,198 @@ +#!/bin/env python3 + +# Copyright 2024 TIER IV, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + + +import sys +import time + +from PyQt5 import QtCore +from PyQt5.QtWidgets import QApplication +from PyQt5.QtWidgets import QGridLayout +from PyQt5.QtWidgets import QMainWindow +from PyQt5.QtWidgets import QPushButton +from PyQt5.QtWidgets import QSizePolicy +from PyQt5.QtWidgets import QSlider +from PyQt5.QtWidgets import QWidget +from autoware_auto_planning_msgs.msg import Trajectory +import rclpy +from rclpy.node import Node +from rclpy.qos import QoSDurabilityPolicy +from rclpy.qos import QoSProfile +from std_msgs.msg import Bool +from std_msgs.msg import Int32 + + +class CenterlineUpdaterWidget(QMainWindow): + def __init__(self): + super(self.__class__, self).__init__() + self.setupUI() + + def setupUI(self): + self.setObjectName("MainWindow") + self.resize(480, 120) + self.setWindowFlags(QtCore.Qt.WindowStaysOnTopHint) + + central_widget = QWidget(self) + central_widget.setObjectName("central_widget") + + self.grid_layout = QGridLayout(central_widget) + self.grid_layout.setContentsMargins(10, 10, 10, 10) + self.grid_layout.setObjectName("grid_layout") + + # button to update the trajectory's start and end index + self.update_button = QPushButton("update slider") + self.update_button.setSizePolicy(QSizePolicy.Expanding, QSizePolicy.Expanding) + self.update_button.clicked.connect(self.onUpdateButton) + + # button to reset the trajectory's start and end index + self.reset_button = QPushButton("reset") + self.reset_button.setSizePolicy(QSizePolicy.Expanding, QSizePolicy.Expanding) + self.reset_button.clicked.connect(self.onResetButton) + + # button to save map + self.save_map_button = QPushButton("save map") + self.save_map_button.setSizePolicy(QSizePolicy.Expanding, QSizePolicy.Expanding) + + # slide of the trajectory's start and end index + self.traj_start_index_slider = QSlider(QtCore.Qt.Horizontal) + self.traj_end_index_slider = QSlider(QtCore.Qt.Horizontal) + self.min_traj_start_index = 0 + self.max_traj_end_index = None + + # set layout + self.grid_layout.addWidget(self.update_button, 1, 0, 1, -1) + self.grid_layout.addWidget(self.reset_button, 2, 0, 1, -1) + self.grid_layout.addWidget(self.save_map_button, 3, 0, 1, -1) + self.grid_layout.addWidget(self.traj_start_index_slider, 4, 0, 1, -1) + self.grid_layout.addWidget(self.traj_end_index_slider, 5, 0, 1, -1) + self.setCentralWidget(central_widget) + + def initWithEndIndex(self, max_traj_end_index): + self.max_traj_end_index = max_traj_end_index + + # initialize slider + self.displayed_min_traj_start_index = self.min_traj_start_index + self.displayed_max_traj_end_index = self.max_traj_end_index + self.initializeSlider() + + def initializeSlider(self, move_value_to_end=True): + self.traj_start_index_slider.setMinimum(0) + self.traj_end_index_slider.setMinimum(0) + self.traj_start_index_slider.setMaximum( + self.displayed_max_traj_end_index - self.displayed_min_traj_start_index + ) + self.traj_end_index_slider.setMaximum( + self.displayed_max_traj_end_index - self.displayed_min_traj_start_index + ) + + if move_value_to_end: + self.traj_start_index_slider.setValue(0) + self.traj_end_index_slider.setValue(self.traj_end_index_slider.maximum()) + + def onResetButton(self, event): + current_traj_start_index = self.displayed_min_traj_start_index + current_traj_end_index = self.displayed_max_traj_end_index + + self.displayed_min_traj_start_index = self.min_traj_start_index + self.displayed_max_traj_end_index = self.max_traj_end_index + + self.initializeSlider(False) + self.traj_start_index_slider.setValue(current_traj_start_index) + if ( + current_traj_start_index == self.min_traj_start_index + and current_traj_end_index == self.max_traj_end_index + ): + self.traj_end_index_slider.setValue(self.displayed_max_traj_end_index) + else: + self.traj_end_index_slider.setValue( + current_traj_start_index + self.traj_end_index_slider.value() + ) + + def onUpdateButton(self, event): + current_traj_start_index = self.getCurrentStartIndex() + current_traj_end_index = self.getCurrentEndIndex() + + self.displayed_min_traj_start_index = current_traj_start_index + self.displayed_max_traj_end_index = current_traj_end_index + + self.initializeSlider() + + def getCurrentStartIndex(self): + return self.displayed_min_traj_start_index + self.traj_start_index_slider.value() + + def getCurrentEndIndex(self): + return self.displayed_min_traj_start_index + self.traj_end_index_slider.value() + + +class CenterlineUpdaterHelper(Node): + def __init__(self): + super().__init__("centerline_updater_helper") + # Qt + self.widget = CenterlineUpdaterWidget() + self.widget.show() + self.widget.save_map_button.clicked.connect(self.onSaveMapButtonPushed) + self.widget.traj_start_index_slider.valueChanged.connect(self.onStartIndexChanged) + self.widget.traj_end_index_slider.valueChanged.connect(self.onEndIndexChanged) + + # ROS + self.pub_save_map = self.create_publisher(Bool, "~/save_map", 1) + self.pub_traj_start_index = self.create_publisher(Int32, "~/traj_start_index", 1) + self.pub_traj_end_index = self.create_publisher(Int32, "~/traj_end_index", 1) + + transient_local_qos = QoSProfile(depth=1, durability=QoSDurabilityPolicy.TRANSIENT_LOCAL) + self.sub_whole_centerline = self.create_subscription( + Trajectory, + "/static_centerline_optimizer/output_whole_centerline", + self.onWholeCenterline, + transient_local_qos, + ) + + while self.widget.max_traj_end_index is None: + rclpy.spin_once(self, timeout_sec=0.01) + time.sleep(0.1) + + def onWholeCenterline(self, whole_centerline): + self.widget.initWithEndIndex(len(whole_centerline.points) - 1) + + def onSaveMapButtonPushed(self, event): + msg = Bool() + msg.data = True + self.pub_save_map.publish(msg) + + def onStartIndexChanged(self, event): + msg = Int32() + msg.data = self.widget.getCurrentStartIndex() + self.pub_traj_start_index.publish(msg) + + def onEndIndexChanged(self, event): + msg = Int32() + msg.data = self.widget.getCurrentEndIndex() + self.pub_traj_end_index.publish(msg) + + +def main(args=None): + app = QApplication(sys.argv) + + rclpy.init(args=args) + node = CenterlineUpdaterHelper() + + while True: + app.processEvents() + rclpy.spin_once(node, timeout_sec=0.01) + + +if __name__ == "__main__": + main() diff --git a/planning/static_centerline_optimizer/scripts/tmp/run.sh b/planning/static_centerline_optimizer/scripts/tmp/run.sh index 07857a9d923a1..9e475b9d8759b 100755 --- a/planning/static_centerline_optimizer/scripts/tmp/run.sh +++ b/planning/static_centerline_optimizer/scripts/tmp/run.sh @@ -1,3 +1,3 @@ #!/bin/bash -ros2 launch static_centerline_optimizer static_centerline_optimizer.launch.xml run_background:=false lanelet2_input_file_path:="$HOME/AutonomousDrivingScenarios/map/sample_map/lanelet2_map.osm" start_lanelet_id:=125 end_lanelet_id:=132 vehicle_model:=lexus +ros2 launch static_centerline_optimizer static_centerline_optimizer.launch.xml run_background:=false lanelet2_input_file_path:="$HOME/autoware_map/sample_map/lanelet2_map.osm" start_lanelet_id:=125 end_lanelet_id:=132 vehicle_model:=lexus diff --git a/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp b/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp index d98341ecb2e23..844352f577432 100644 --- a/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp +++ b/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp @@ -26,11 +26,14 @@ #include "static_centerline_optimizer/type_alias.hpp" #include "static_centerline_optimizer/utils.hpp" #include "tier4_autoware_utils/geometry/geometry.hpp" +#include "tier4_autoware_utils/ros/parameter.hpp" #include #include #include +#include "std_msgs/msg/bool.hpp" +#include "std_msgs/msg/int32.hpp" #include #include @@ -41,6 +44,7 @@ #include #include +#include #include #include #include @@ -202,6 +206,14 @@ std::vector check_lanelet_connection( return unconnected_lane_ids; } + +std_msgs::msg::Header createHeader(const rclcpp::Time & now) +{ + std_msgs::msg::Header header; + header.frame_id = "map"; + header.stamp = now; + return header; +} } // namespace StaticCenterlineOptimizerNode::StaticCenterlineOptimizerNode( @@ -213,6 +225,8 @@ StaticCenterlineOptimizerNode::StaticCenterlineOptimizerNode( pub_raw_path_with_lane_id_ = create_publisher("input_centerline", create_transient_local_qos()); pub_raw_path_ = create_publisher("debug/raw_centerline", create_transient_local_qos()); + pub_whole_optimized_centerline_ = + create_publisher("output_whole_centerline", create_transient_local_qos()); pub_optimized_centerline_ = create_publisher("output_centerline", create_transient_local_qos()); @@ -220,6 +234,53 @@ StaticCenterlineOptimizerNode::StaticCenterlineOptimizerNode( pub_debug_unsafe_footprints_ = create_publisher("debug/unsafe_footprints", create_transient_local_qos()); + // subscribers + sub_traj_start_index_ = create_subscription( + "/centerline_updater_helper/traj_start_index", rclcpp::QoS{1}, + [this](const std_msgs::msg::Int32 & msg) { + if (!meta_data_to_save_map_ || traj_end_index_ + 1 < msg.data) { + return; + } + traj_start_index_ = msg.data; + + const auto & d = meta_data_to_save_map_; + const auto selected_optimized_traj_points = std::vector( + d->optimized_traj_points.begin() + traj_start_index_, + d->optimized_traj_points.begin() + traj_end_index_ + 1); + + pub_optimized_centerline_->publish(motion_utils::convertToTrajectory( + selected_optimized_traj_points, createHeader(this->now()))); + }); + sub_traj_end_index_ = create_subscription( + "/centerline_updater_helper/traj_end_index", rclcpp::QoS{1}, + [this](const std_msgs::msg::Int32 & msg) { + if (!meta_data_to_save_map_ || msg.data + 1 < traj_start_index_) { + return; + } + traj_end_index_ = msg.data; + + const auto & d = meta_data_to_save_map_; + const auto selected_optimized_traj_points = std::vector( + d->optimized_traj_points.begin() + traj_start_index_, + d->optimized_traj_points.begin() + traj_end_index_ + 1); + + pub_optimized_centerline_->publish(motion_utils::convertToTrajectory( + selected_optimized_traj_points, createHeader(this->now()))); + }); + sub_save_map_ = create_subscription( + "/centerline_updater_helper/save_map", rclcpp::QoS{1}, [this](const std_msgs::msg::Bool & msg) { + const auto lanelet2_output_file_path = + tier4_autoware_utils::getOrDeclareParameter( + *this, "lanelet2_output_file_path"); + if (!meta_data_to_save_map_ || msg.data) { + const auto & d = meta_data_to_save_map_; + const auto selected_optimized_traj_points = std::vector( + d->optimized_traj_points.begin() + traj_start_index_, + d->optimized_traj_points.begin() + traj_end_index_ + 1); + save_map(lanelet2_output_file_path, d->route_lane_ids, selected_optimized_traj_points); + } + }); + // services callback_group_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); srv_load_map_ = create_service( @@ -258,7 +319,11 @@ void StaticCenterlineOptimizerNode::run() load_map(lanelet2_input_file_path); const auto route_lane_ids = plan_route(start_lanelet_id, end_lanelet_id); const auto optimized_traj_points = plan_path(route_lane_ids); + traj_start_index_ = 0; + traj_end_index_ = optimized_traj_points.size() - 1; save_map(lanelet2_output_file_path, route_lane_ids, optimized_traj_points); + + meta_data_to_save_map_ = MetaDataToSaveMap{optimized_traj_points, route_lane_ids}; } void StaticCenterlineOptimizerNode::load_map(const std::string & lanelet2_input_file_path) @@ -450,6 +515,8 @@ std::vector StaticCenterlineOptimizerNode::plan_path( // smooth trajectory and road collision avoidance const auto optimized_traj_points = optimize_trajectory(raw_path); + pub_whole_optimized_centerline_->publish( + motion_utils::convertToTrajectory(optimized_traj_points, raw_path.header)); pub_optimized_centerline_->publish( motion_utils::convertToTrajectory(optimized_traj_points, raw_path.header)); RCLCPP_INFO( From a8de91fbb22e01c0e20e9789cba0231dd79b77cd Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Tue, 2 Apr 2024 16:57:41 +0900 Subject: [PATCH 11/29] feat(multi_object_tracker): debug timer to work with reduced replay rate recomputation (#6706) * fix: mot debug timer, full set of timings Signed-off-by: Taekjin LEE * fix: reduce timers, rename topics Signed-off-by: Taekjin LEE * fix: separate debugger Signed-off-by: Taekjin LEE * chore: fix comments Signed-off-by: Taekjin LEE * fix: fix stamp initialization, remove unused function Signed-off-by: Taekjin LEE --------- Signed-off-by: Taekjin LEE --- .../multi_object_tracker/CMakeLists.txt | 1 + .../include/multi_object_tracker/debugger.hpp | 68 +++++++++ .../multi_object_tracker_core.hpp | 42 +----- .../multi_object_tracker/src/debugger.cpp | 138 ++++++++++++++++++ .../src/multi_object_tracker_core.cpp | 111 +------------- 5 files changed, 210 insertions(+), 150 deletions(-) create mode 100644 perception/multi_object_tracker/include/multi_object_tracker/debugger.hpp create mode 100644 perception/multi_object_tracker/src/debugger.cpp diff --git a/perception/multi_object_tracker/CMakeLists.txt b/perception/multi_object_tracker/CMakeLists.txt index fe90be8c583c2..8d835fec20a9b 100644 --- a/perception/multi_object_tracker/CMakeLists.txt +++ b/perception/multi_object_tracker/CMakeLists.txt @@ -22,6 +22,7 @@ include_directories( # Generate exe file set(MULTI_OBJECT_TRACKER_SRC src/multi_object_tracker_core.cpp + src/debugger.cpp src/data_association/data_association.cpp src/data_association/mu_successive_shortest_path/mu_successive_shortest_path_wrapper.cpp src/tracker/motion_model/motion_model_base.cpp diff --git a/perception/multi_object_tracker/include/multi_object_tracker/debugger.hpp b/perception/multi_object_tracker/include/multi_object_tracker/debugger.hpp new file mode 100644 index 0000000000000..ca1b20d26c25d --- /dev/null +++ b/perception/multi_object_tracker/include/multi_object_tracker/debugger.hpp @@ -0,0 +1,68 @@ +// Copyright 2024 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// + +#ifndef MULTI_OBJECT_TRACKER__DEBUGGER_HPP_ +#define MULTI_OBJECT_TRACKER__DEBUGGER_HPP_ + +#include +#include +#include +#include +#include + +#include +#include +#include + +#include + +/** + * @brief Debugger class for multi object tracker + * @details This class is used to publish debug information of multi object tracker + */ +class TrackerDebugger +{ +public: + explicit TrackerDebugger(rclcpp::Node & node); + void publishTentativeObjects( + const autoware_auto_perception_msgs::msg::TrackedObjects & tentative_objects) const; + void startMeasurementTime( + const rclcpp::Time & now, const rclcpp::Time & measurement_header_stamp); + void endPublishTime(const rclcpp::Time & now, const rclcpp::Time & object_time); + void setupDiagnostics(); + void checkDelay(diagnostic_updater::DiagnosticStatusWrapper & stat); + struct DEBUG_SETTINGS + { + bool publish_processing_time; + bool publish_tentative_objects; + double diagnostics_warn_delay; + double diagnostics_error_delay; + } debug_settings_; + double pipeline_latency_ms_ = 0.0; + diagnostic_updater::Updater diagnostic_updater_; + +private: + void loadParameters(); + rclcpp::Node & node_; + rclcpp::Publisher::SharedPtr + debug_tentative_objects_pub_; + std::unique_ptr processing_time_publisher_; + rclcpp::Time last_input_stamp_; + rclcpp::Time stamp_process_start_; + rclcpp::Time stamp_publish_output_; +}; + +#endif // MULTI_OBJECT_TRACKER__DEBUGGER_HPP_ diff --git a/perception/multi_object_tracker/include/multi_object_tracker/multi_object_tracker_core.hpp b/perception/multi_object_tracker/include/multi_object_tracker/multi_object_tracker_core.hpp index ca59f994a3b0e..94cc7185bd518 100644 --- a/perception/multi_object_tracker/include/multi_object_tracker/multi_object_tracker_core.hpp +++ b/perception/multi_object_tracker/include/multi_object_tracker/multi_object_tracker_core.hpp @@ -20,12 +20,10 @@ #define MULTI_OBJECT_TRACKER__MULTI_OBJECT_TRACKER_CORE_HPP_ #include "multi_object_tracker/data_association/data_association.hpp" +#include "multi_object_tracker/debugger.hpp" #include "multi_object_tracker/tracker/model/tracker_base.hpp" #include -#include -#include -#include #include #include @@ -41,9 +39,6 @@ #include #endif -#include -#include - #include #include @@ -53,41 +48,6 @@ #include #include -/** - * @brief Debugger class for multi object tracker - * @details This class is used to publish debug information of multi object tracker - */ -class TrackerDebugger -{ -public: - explicit TrackerDebugger(rclcpp::Node & node); - void publishProcessingTime(); - void publishTentativeObjects( - const autoware_auto_perception_msgs::msg::TrackedObjects & tentative_objects) const; - void startStopWatch(); - void startMeasurementTime(const rclcpp::Time & measurement_header_stamp); - void setupDiagnostics(); - void checkDelay(diagnostic_updater::DiagnosticStatusWrapper & stat); - struct DEBUG_SETTINGS - { - bool publish_processing_time; - bool publish_tentative_objects; - double diagnostics_warn_delay; - double diagnostics_error_delay; - } debug_settings_; - double elapsed_time_from_sensor_input_ = 0.0; - diagnostic_updater::Updater diagnostic_updater_; - -private: - void loadParameters(); - rclcpp::Node & node_; - rclcpp::Publisher::SharedPtr - debug_tentative_objects_pub_; - std::unique_ptr> stop_watch_ptr_; - std::unique_ptr processing_time_publisher_; - rclcpp::Time last_input_stamp_; -}; - class MultiObjectTracker : public rclcpp::Node { public: diff --git a/perception/multi_object_tracker/src/debugger.cpp b/perception/multi_object_tracker/src/debugger.cpp new file mode 100644 index 0000000000000..e3fc58dd5d692 --- /dev/null +++ b/perception/multi_object_tracker/src/debugger.cpp @@ -0,0 +1,138 @@ +// Copyright 2024 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// + +#include "multi_object_tracker/debugger.hpp" + +#include + +TrackerDebugger::TrackerDebugger(rclcpp::Node & node) +: diagnostic_updater_(&node), + node_(node), + last_input_stamp_(node.now()), + stamp_process_start_(node.now()), + stamp_publish_output_(node.now()) +{ + // declare debug parameters to decide whether to publish debug topics + loadParameters(); + // initialize debug publishers + if (debug_settings_.publish_processing_time) { + processing_time_publisher_ = + std::make_unique(&node_, "multi_object_tracker"); + } + + if (debug_settings_.publish_tentative_objects) { + debug_tentative_objects_pub_ = + node_.create_publisher( + "debug/tentative_objects", rclcpp::QoS{1}); + } + + // initialize stop watch and diagnostics + setupDiagnostics(); +} + +void TrackerDebugger::setupDiagnostics() +{ + diagnostic_updater_.setHardwareID(node_.get_name()); + diagnostic_updater_.add( + "Perception delay check from original header stamp", this, &TrackerDebugger::checkDelay); + diagnostic_updater_.setPeriod(0.1); +} + +void TrackerDebugger::loadParameters() +{ + try { + debug_settings_.publish_processing_time = + node_.declare_parameter("publish_processing_time"); + debug_settings_.publish_tentative_objects = + node_.declare_parameter("publish_tentative_objects"); + debug_settings_.diagnostics_warn_delay = + node_.declare_parameter("diagnostics_warn_delay"); + debug_settings_.diagnostics_error_delay = + node_.declare_parameter("diagnostics_error_delay"); + } catch (const std::exception & e) { + RCLCPP_WARN(node_.get_logger(), "Failed to declare parameter: %s", e.what()); + debug_settings_.publish_processing_time = false; + debug_settings_.publish_tentative_objects = false; + debug_settings_.diagnostics_warn_delay = 0.5; + debug_settings_.diagnostics_error_delay = 1.0; + } +} + +void TrackerDebugger::checkDelay(diagnostic_updater::DiagnosticStatusWrapper & stat) +{ + const double delay = pipeline_latency_ms_; // [s] + + if (delay == 0.0) { + stat.summary(diagnostic_msgs::msg::DiagnosticStatus::OK, "Detection delay is not calculated."); + } else if (delay < debug_settings_.diagnostics_warn_delay) { + stat.summary(diagnostic_msgs::msg::DiagnosticStatus::OK, "Detection delay is acceptable"); + } else if (delay < debug_settings_.diagnostics_error_delay) { + stat.summary( + diagnostic_msgs::msg::DiagnosticStatus::WARN, "Detection delay is over warn threshold."); + } else { + stat.summary( + diagnostic_msgs::msg::DiagnosticStatus::ERROR, "Detection delay is over error threshold."); + } + + stat.add("Detection delay", delay); +} + +void TrackerDebugger::publishTentativeObjects( + const autoware_auto_perception_msgs::msg::TrackedObjects & tentative_objects) const +{ + if (debug_settings_.publish_tentative_objects) { + debug_tentative_objects_pub_->publish(tentative_objects); + } +} + +void TrackerDebugger::startMeasurementTime( + const rclcpp::Time & now, const rclcpp::Time & measurement_header_stamp) +{ + last_input_stamp_ = measurement_header_stamp; + stamp_process_start_ = now; + if (debug_settings_.publish_processing_time) { + double input_latency_ms = (now - last_input_stamp_).seconds() * 1e3; + processing_time_publisher_->publish( + "debug/input_latency_ms", input_latency_ms); + } +} + +void TrackerDebugger::endPublishTime(const rclcpp::Time & now, const rclcpp::Time & object_time) +{ + const auto current_time = now; + // pipeline latency: time from sensor measurement to publish + pipeline_latency_ms_ = (current_time - last_input_stamp_).seconds() * 1e3; + if (debug_settings_.publish_processing_time) { + // processing time: time between input and publish + double processing_time_ms = (current_time - stamp_process_start_).seconds() * 1e3; + // cycle time: time between two consecutive publish + double cyclic_time_ms = (current_time - stamp_publish_output_).seconds() * 1e3; + // measurement to tracked-object time: time from the sensor measurement to the publishing object + // time If there is not latency compensation, this value is zero + double measurement_to_object_ms = (object_time - last_input_stamp_).seconds() * 1e3; + + // starting from the measurement time + processing_time_publisher_->publish( + "debug/pipeline_latency_ms", pipeline_latency_ms_); + processing_time_publisher_->publish( + "debug/cyclic_time_ms", cyclic_time_ms); + processing_time_publisher_->publish( + "debug/processing_time_ms", processing_time_ms); + processing_time_publisher_->publish( + "debug/meas_to_tracked_object_ms", measurement_to_object_ms); + } + stamp_publish_output_ = current_time; +} diff --git a/perception/multi_object_tracker/src/multi_object_tracker_core.cpp b/perception/multi_object_tracker/src/multi_object_tracker_core.cpp index fa609ed9ff9c7..b8e19d4ca2df4 100644 --- a/perception/multi_object_tracker/src/multi_object_tracker_core.cpp +++ b/perception/multi_object_tracker/src/multi_object_tracker_core.cpp @@ -66,113 +66,6 @@ boost::optional getTransformAnonymous( } // namespace -TrackerDebugger::TrackerDebugger(rclcpp::Node & node) -: diagnostic_updater_(&node), node_(node), last_input_stamp_(node.now()) -{ - // declare debug parameters to decide whether to publish debug topics - loadParameters(); - // initialize debug publishers - stop_watch_ptr_ = std::make_unique>(); - if (debug_settings_.publish_processing_time) { - processing_time_publisher_ = - std::make_unique(&node_, "multi_object_tracker"); - } - - if (debug_settings_.publish_tentative_objects) { - debug_tentative_objects_pub_ = - node_.create_publisher( - "debug/tentative_objects", rclcpp::QoS{1}); - } - - // initialize stop watch and diagnostics - startStopWatch(); - setupDiagnostics(); -} - -void TrackerDebugger::setupDiagnostics() -{ - diagnostic_updater_.setHardwareID(node_.get_name()); - diagnostic_updater_.add( - "Perception delay check from original header stamp", this, &TrackerDebugger::checkDelay); - diagnostic_updater_.setPeriod(0.1); -} - -void TrackerDebugger::loadParameters() -{ - try { - debug_settings_.publish_processing_time = - node_.declare_parameter("publish_processing_time"); - debug_settings_.publish_tentative_objects = - node_.declare_parameter("publish_tentative_objects"); - debug_settings_.diagnostics_warn_delay = - node_.declare_parameter("diagnostics_warn_delay"); - debug_settings_.diagnostics_error_delay = - node_.declare_parameter("diagnostics_error_delay"); - } catch (const std::exception & e) { - RCLCPP_WARN(node_.get_logger(), "Failed to declare parameter: %s", e.what()); - debug_settings_.publish_processing_time = false; - debug_settings_.publish_tentative_objects = false; - debug_settings_.diagnostics_warn_delay = 0.5; - debug_settings_.diagnostics_error_delay = 1.0; - } -} - -void TrackerDebugger::checkDelay(diagnostic_updater::DiagnosticStatusWrapper & stat) -{ - const double delay = elapsed_time_from_sensor_input_; // [s] - - if (delay == 0.0) { - stat.summary(diagnostic_msgs::msg::DiagnosticStatus::OK, "Detection delay is not calculated."); - } else if (delay < debug_settings_.diagnostics_warn_delay) { - stat.summary(diagnostic_msgs::msg::DiagnosticStatus::OK, "Detection delay is acceptable"); - } else if (delay < debug_settings_.diagnostics_error_delay) { - stat.summary( - diagnostic_msgs::msg::DiagnosticStatus::WARN, "Detection delay is over warn threshold."); - } else { - stat.summary( - diagnostic_msgs::msg::DiagnosticStatus::ERROR, "Detection delay is over error threshold."); - } - - stat.add("Detection delay", delay); -} - -void TrackerDebugger::publishProcessingTime() -{ - const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true); - const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); - const auto current_time = node_.now(); - elapsed_time_from_sensor_input_ = (current_time - last_input_stamp_).seconds(); - if (debug_settings_.publish_processing_time) { - processing_time_publisher_->publish( - "debug/cyclic_time_ms", cyclic_time_ms); - processing_time_publisher_->publish( - "debug/processing_time_ms", processing_time_ms); - processing_time_publisher_->publish( - "debug/pipeline_latency_ms", elapsed_time_from_sensor_input_ * 1e3); - } -} - -void TrackerDebugger::publishTentativeObjects( - const autoware_auto_perception_msgs::msg::TrackedObjects & tentative_objects) const -{ - if (debug_settings_.publish_tentative_objects) { - debug_tentative_objects_pub_->publish(tentative_objects); - } -} - -void TrackerDebugger::startStopWatch() -{ - stop_watch_ptr_->tic("cyclic_time"); - stop_watch_ptr_->tic("processing_time"); -} - -void TrackerDebugger::startMeasurementTime(const rclcpp::Time & measurement_header_stamp) -{ - last_input_stamp_ = measurement_header_stamp; - // start measuring processing time - stop_watch_ptr_->toc("processing_time", true); -} - MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options) : rclcpp::Node("multi_object_tracker", node_options), tf_buffer_(this->get_clock()), @@ -243,7 +136,7 @@ void MultiObjectTracker::onMeasurement( const autoware_auto_perception_msgs::msg::DetectedObjects::ConstSharedPtr input_objects_msg) { /* keep the latest input stamp and check transform*/ - debugger_->startMeasurementTime(rclcpp::Time(input_objects_msg->header.stamp)); + debugger_->startMeasurementTime(this->now(), rclcpp::Time(input_objects_msg->header.stamp)); const auto self_transform = getTransformAnonymous( tf_buffer_, "base_link", world_frame_id_, input_objects_msg->header.stamp); if (!self_transform) { @@ -472,7 +365,7 @@ void MultiObjectTracker::publish(const rclcpp::Time & time) const published_time_publisher_->publish_if_subscribed(tracked_objects_pub_, output_msg.header.stamp); // Debugger Publish if enabled - debugger_->publishProcessingTime(); + debugger_->endPublishTime(this->now(), time); debugger_->publishTentativeObjects(tentative_objects_msg); } From ac1cd436eb8b41628dc5470ccbca0bdc36a410ac Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Tue, 2 Apr 2024 18:30:45 +0900 Subject: [PATCH 12/29] fix(object_recognition_utils): check polygon area on iou calculation (#6701) * feat(object_recognition_utils): check input polygon on IoU calculations Signed-off-by: Taekjin LEE * fix: MIN_AREA close to the epsilon of float 1e-6 Signed-off-by: Taekjin LEE --------- Signed-off-by: Taekjin LEE --- .../object_recognition_utils/matching.hpp | 20 ++++++++++++++----- 1 file changed, 15 insertions(+), 5 deletions(-) diff --git a/common/object_recognition_utils/include/object_recognition_utils/matching.hpp b/common/object_recognition_utils/include/object_recognition_utils/matching.hpp index 5e8b6a3d49890..e9b924023f62e 100644 --- a/common/object_recognition_utils/include/object_recognition_utils/matching.hpp +++ b/common/object_recognition_utils/include/object_recognition_utils/matching.hpp @@ -29,6 +29,8 @@ namespace object_recognition_utils { using tier4_autoware_utils::Polygon2d; +// minimum area to avoid division by zero +static const double MIN_AREA = 1e-6; inline double getConvexShapeArea(const Polygon2d & source_polygon, const Polygon2d & target_polygon) { @@ -66,10 +68,12 @@ template double get2dIoU(const T1 source_object, const T2 target_object, const double min_union_area = 0.01) { const auto source_polygon = tier4_autoware_utils::toPolygon2d(source_object); + if (boost::geometry::area(source_polygon) < MIN_AREA) return 0.0; const auto target_polygon = tier4_autoware_utils::toPolygon2d(target_object); + if (boost::geometry::area(target_polygon) < MIN_AREA) return 0.0; const double intersection_area = getIntersectionArea(source_polygon, target_polygon); - if (intersection_area == 0.0) return 0.0; + if (intersection_area < MIN_AREA) return 0.0; const double union_area = getUnionArea(source_polygon, target_polygon); const double iou = @@ -81,7 +85,9 @@ template double get2dGeneralizedIoU(const T1 & source_object, const T2 & target_object) { const auto source_polygon = tier4_autoware_utils::toPolygon2d(source_object); + if (boost::geometry::area(source_polygon) < MIN_AREA) return 0.0; const auto target_polygon = tier4_autoware_utils::toPolygon2d(target_object); + if (boost::geometry::area(target_polygon) < MIN_AREA) return 0.0; const double intersection_area = getIntersectionArea(source_polygon, target_polygon); const double union_area = getUnionArea(source_polygon, target_polygon); @@ -95,11 +101,13 @@ template double get2dPrecision(const T1 source_object, const T2 target_object) { const auto source_polygon = tier4_autoware_utils::toPolygon2d(source_object); + const double source_area = boost::geometry::area(source_polygon); + if (source_area < MIN_AREA) return 0.0; const auto target_polygon = tier4_autoware_utils::toPolygon2d(target_object); + if (boost::geometry::area(target_polygon) < MIN_AREA) return 0.0; const double intersection_area = getIntersectionArea(source_polygon, target_polygon); - if (intersection_area == 0.0) return 0.0; - const double source_area = boost::geometry::area(source_polygon); + if (intersection_area < MIN_AREA) return 0.0; return std::min(1.0, intersection_area / source_area); } @@ -108,11 +116,13 @@ template double get2dRecall(const T1 source_object, const T2 target_object) { const auto source_polygon = tier4_autoware_utils::toPolygon2d(source_object); + if (boost::geometry::area(source_polygon) < MIN_AREA) return 0.0; const auto target_polygon = tier4_autoware_utils::toPolygon2d(target_object); + const double target_area = boost::geometry::area(target_polygon); + if (target_area < MIN_AREA) return 0.0; const double intersection_area = getIntersectionArea(source_polygon, target_polygon); - if (intersection_area == 0.0) return 0.0; - const double target_area = boost::geometry::area(target_polygon); + if (intersection_area < MIN_AREA) return 0.0; return std::min(1.0, intersection_area / target_area); } From 0bd9a99bbea00d4f95c281bbd8846ad66e6bb988 Mon Sep 17 00:00:00 2001 From: beyzanurkaya <32412808+beyzanurkaya@users.noreply.github.com> Date: Tue, 2 Apr 2024 15:27:51 +0300 Subject: [PATCH 13/29] fix(predicted_path_checker): check if trajectory size (#6730) check trajectory size Signed-off-by: beyza Co-authored-by: beyza --- .../predicted_path_checker_node.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/control/predicted_path_checker/src/predicted_path_checker_node/predicted_path_checker_node.cpp b/control/predicted_path_checker/src/predicted_path_checker_node/predicted_path_checker_node.cpp index 0cf2548d69746..bba069442bee7 100644 --- a/control/predicted_path_checker/src/predicted_path_checker_node/predicted_path_checker_node.cpp +++ b/control/predicted_path_checker/src/predicted_path_checker_node/predicted_path_checker_node.cpp @@ -537,6 +537,10 @@ void PredictedPathCheckerNode::filterObstacles( const Pose & ego_pose, const TrajectoryPoints & traj, const double dist_threshold, const bool use_prediction, PredictedObjects & filtered_objects) { + if (traj.size() < 2) { + RCLCPP_ERROR(rclcpp::get_logger("predicted_path_checker"), "Trajectory size is less than 2."); + return; + } filtered_objects.header.frame_id = object_ptr_.get()->header.frame_id; filtered_objects.header.stamp = this->now(); From faf4abd049fe8d53494f5396941e885ea669163e Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 3 Apr 2024 00:57:07 +0900 Subject: [PATCH 14/29] fix(static_centerline_optimizer): fix latlon values of generated LL2 map (#6727) * fix(static_centerline_optimizer): fix lat/lon value of generated LL2 map Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../static_centerline_optimizer_node.hpp | 3 +++ planning/static_centerline_optimizer/package.xml | 2 ++ .../src/static_centerline_optimizer_node.cpp | 11 ++++++++--- 3 files changed, 13 insertions(+), 3 deletions(-) diff --git a/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp b/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp index f25a6771aa0cb..3e6aafd3a9954 100644 --- a/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp +++ b/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp @@ -22,6 +22,8 @@ #include "static_centerline_optimizer/type_alias.hpp" #include "vehicle_info_util/vehicle_info_util.hpp" +#include + #include "std_msgs/msg/bool.hpp" #include "std_msgs/msg/int32.hpp" @@ -69,6 +71,7 @@ class StaticCenterlineOptimizerNode : public rclcpp::Node lanelet::LaneletMapPtr original_map_ptr_{nullptr}; HADMapBin::ConstSharedPtr map_bin_ptr_{nullptr}; std::shared_ptr route_handler_ptr_{nullptr}; + std::unique_ptr map_projector_{nullptr}; int traj_start_index_{0}; int traj_end_index_{0}; diff --git a/planning/static_centerline_optimizer/package.xml b/planning/static_centerline_optimizer/package.xml index 363c88bebf0ea..eef133581622f 100644 --- a/planning/static_centerline_optimizer/package.xml +++ b/planning/static_centerline_optimizer/package.xml @@ -19,11 +19,13 @@ autoware_auto_perception_msgs autoware_auto_planning_msgs behavior_path_planner_common + geography_utils geometry_msgs global_parameter_loader interpolation lanelet2_extension map_loader + map_projection_loader mission_planner motion_utils obstacle_avoidance_planner diff --git a/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp b/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp index 844352f577432..ea7e1c302fd68 100644 --- a/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp +++ b/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp @@ -18,6 +18,7 @@ #include "lanelet2_extension/utility/query.hpp" #include "lanelet2_extension/utility/utilities.hpp" #include "map_loader/lanelet2_map_loader_node.hpp" +#include "map_projection_loader/load_info_from_lanelet2_map.hpp" #include "motion_utils/resample/resample.hpp" #include "motion_utils/trajectory/conversion.hpp" #include "obstacle_avoidance_planner/node.hpp" @@ -28,6 +29,7 @@ #include "tier4_autoware_utils/geometry/geometry.hpp" #include "tier4_autoware_utils/ros/parameter.hpp" +#include #include #include #include @@ -331,14 +333,17 @@ void StaticCenterlineOptimizerNode::load_map(const std::string & lanelet2_input_ // load map by the map_loader package map_bin_ptr_ = [&]() -> HADMapBin::ConstSharedPtr { // load map - tier4_map_msgs::msg::MapProjectorInfo map_projector_info; - map_projector_info.projector_type = tier4_map_msgs::msg::MapProjectorInfo::MGRS; + const auto map_projector_info = load_info_from_lanelet2_map(lanelet2_input_file_path); const auto map_ptr = Lanelet2MapLoaderNode::load_map(lanelet2_input_file_path, map_projector_info); if (!map_ptr) { return nullptr; } + // NOTE: generate map projector for lanelet::write(). + // Without this, lat/lon of the generated LL2 map will be wrong. + map_projector_ = geography_utils::get_lanelet2_projector(map_projector_info); + // NOTE: The original map is stored here since the various ids in the lanelet map will change // after lanelet::utils::overwriteLaneletCenterline, and saving map will fail. original_map_ptr_ = @@ -750,7 +755,7 @@ void StaticCenterlineOptimizerNode::save_map( RCLCPP_INFO(get_logger(), "Updated centerline in map."); // save map with modified center line - lanelet::write(lanelet2_output_file_path, *original_map_ptr_); + lanelet::write(lanelet2_output_file_path, *original_map_ptr_, *map_projector_); RCLCPP_INFO(get_logger(), "Saved map."); } } // namespace static_centerline_optimizer From 5d14585cc28bc9eb01c300c30e250b79942e3b60 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Wed, 3 Apr 2024 11:46:54 +0900 Subject: [PATCH 15/29] fix(lane_change): check prepare phase in intersection (#6561) * fix(lane_change): check prepare phase in intersection Signed-off-by: Muhammad Zulfaqar Azmi * Add new parameter, also create function Signed-off-by: Muhammad Zulfaqar Azmi * Rename parameters Signed-off-by: Muhammad Zulfaqar Azmi * fix spell check * fix config file Signed-off-by: Zulfaqar Azmi * call the function check_prepare_phase only once Signed-off-by: Muhammad Zulfaqar Azmi * add parameter description in README Signed-off-by: Muhammad Zulfaqar Azmi * minor refactoring Signed-off-by: Muhammad Zulfaqar Azmi * Doxygen description Signed-off-by: Muhammad Zulfaqar Azmi --------- Signed-off-by: Muhammad Zulfaqar Azmi Signed-off-by: Zulfaqar Azmi --- .../README.md | 15 ++++--- .../config/lane_change.param.yaml | 4 +- .../scene.hpp | 2 + .../utils/data_structs.hpp | 3 +- .../utils/utils.hpp | 39 ++++++++++++++++- .../src/manager.cpp | 6 ++- .../src/scene.cpp | 43 ++++++++++++++++--- .../src/utils/utils.cpp | 35 +++++++++++++-- 8 files changed, 127 insertions(+), 20 deletions(-) diff --git a/planning/behavior_path_lane_change_module/README.md b/planning/behavior_path_lane_change_module/README.md index 874d542b445d3..17cdc58f5ad47 100644 --- a/planning/behavior_path_lane_change_module/README.md +++ b/planning/behavior_path_lane_change_module/README.md @@ -551,13 +551,14 @@ The following parameters are configurable in [lane_change.param.yaml](https://gi #### Additional parameters -| Name | Unit | Type | Description | Default value | -| :----------------------------------------- | ----- | ------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------- | -| `enable_collision_check_at_prepare_phase` | [-] | boolean | Perform collision check starting from prepare phase. If `false`, collision check only evaluated for lane changing phase. | false | -| `prepare_phase_ignore_target_speed_thresh` | [m/s] | double | Ignore collision check in prepare phase of object speed that is lesser that the configured value. `enable_collision_check_at_prepare_phase` must be `true` | 0.1 | -| `check_objects_on_current_lanes` | [-] | boolean | If true, the lane change module check objects on current lanes when performing collision assessment. | false | -| `check_objects_on_other_lanes` | [-] | boolean | If true, the lane change module include objects on other lanes. when performing collision assessment | false | -| `use_all_predicted_path` | [-] | boolean | If false, use only the predicted path that has the maximum confidence. | true | +| Name | Unit | Type | Description | Default value | +| :------------------------------------------------------- | ----- | ------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------- | +| `enable_collision_check_for_prepare_phase.general_lanes` | [-] | boolean | Perform collision check starting from the prepare phase for situations not explicitly covered by other settings (e.g., intersections). If `false`, collision check only evaluated for lane changing phase. | false | +| `enable_collision_check_for_prepare_phase.intersection` | [-] | boolean | Perform collision check starting from prepare phase when ego is in intersection. If `false`, collision check only evaluated for lane changing phase. | false | +| `prepare_phase_ignore_target_speed_thresh` | [m/s] | double | Ignore collision check in prepare phase of object speed that is lesser that the configured value. `enable_collision_check_at_prepare_phase` must be `true` | 0.1 | +| `check_objects_on_current_lanes` | [-] | boolean | If true, the lane change module check objects on current lanes when performing collision assessment. | false | +| `check_objects_on_other_lanes` | [-] | boolean | If true, the lane change module include objects on other lanes. when performing collision assessment | false | +| `use_all_predicted_path` | [-] | boolean | If false, use only the predicted path that has the maximum confidence. | true | #### safety constraints during lane change path is computed diff --git a/planning/behavior_path_lane_change_module/config/lane_change.param.yaml b/planning/behavior_path_lane_change_module/config/lane_change.param.yaml index 74c6ad0893b23..039e8a31ed10f 100644 --- a/planning/behavior_path_lane_change_module/config/lane_change.param.yaml +++ b/planning/behavior_path_lane_change_module/config/lane_change.param.yaml @@ -89,7 +89,9 @@ stop_time: 3.0 # [s] # collision check - enable_prepare_segment_collision_check: true + enable_collision_check_for_prepare_phase: + general_lanes: false + intersection: true prepare_segment_ignore_object_velocity_thresh: 0.1 # [m/s] check_objects_on_current_lanes: true check_objects_on_other_lanes: true diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/scene.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/scene.hpp index 3b8d2ad6e9931..0eec0ce75f622 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/scene.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/scene.hpp @@ -174,6 +174,8 @@ class NormalLaneChange : public LaneChangeBase bool isVehicleStuck(const lanelet::ConstLanelets & current_lanes) const; + bool check_prepare_phase() const; + double calcMaximumLaneChangeLength( const lanelet::ConstLanelet & current_terminal_lanelet, const double max_acc) const; diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/data_structs.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/data_structs.hpp index e48f687a89035..0d77135fda242 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/data_structs.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/data_structs.hpp @@ -112,7 +112,8 @@ struct LaneChangeParameters double max_longitudinal_acc{1.0}; // collision check - bool enable_prepare_segment_collision_check{true}; + bool enable_collision_check_for_prepare_phase_in_general_lanes{false}; + bool enable_collision_check_for_prepare_phase_in_intersection{true}; double prepare_segment_ignore_object_velocity_thresh{0.1}; bool check_objects_on_current_lanes{true}; bool check_objects_on_other_lanes{true}; diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp index 35cc02e867557..ff5d7bc0773fa 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp @@ -23,6 +23,7 @@ #include "rclcpp/logger.hpp" #include +#include #include #include @@ -31,6 +32,7 @@ #include +#include #include #include @@ -185,7 +187,7 @@ std::optional createPolygon( ExtendedPredictedObject transform( const PredictedObject & object, const BehaviorPathPlannerParameters & common_parameters, - const LaneChangeParameters & lane_change_parameters); + const LaneChangeParameters & lane_change_parameters, const bool check_at_prepare_phase); bool isCollidedPolygonsInLanelet( const std::vector & collided_polygons, const lanelet::ConstLanelets & lanes); @@ -220,6 +222,41 @@ lanelet::ConstLanelets generateExpandedLanelets( * @return rclcpp::Logger The logger instance configured for the specified lane change type. */ rclcpp::Logger getLogger(const std::string & type); + +/** + * @brief Computes the current footprint of the ego vehicle based on its pose and size. + * + * This function calculates the 2D polygon representing the current footprint of the ego vehicle. + * The footprint is determined by the vehicle's pose and its dimensions, including the distance + * from the base to the front and rear ends of the vehicle, as well as its width. + * + * @param ego_pose The current pose of the ego vehicle. + * @param ego_info The structural information of the ego vehicle, such as its maximum longitudinal + * offset, rear overhang, and width. + * + * @return Polygon2d A polygon representing the current 2D footprint of the ego vehicle. + */ +Polygon2d getEgoCurrentFootprint( + const Pose & ego_pose, const vehicle_info_util::VehicleInfo & ego_info); + +/** + * @brief Checks if the given polygon is within an intersection area. + * + * This function evaluates whether a specified polygon is located within the bounds of an + * intersection. It identifies the intersection area by checking the attributes of the provided + * lanelet. If the lanelet has an attribute indicating it is part of an intersection, the function + * then checks if the polygon is fully contained within this area. + * + * @param route_handler a shared pointer to the route_handler + * @param lanelet A lanelet to check against the + * intersection area. + * @param polygon The polygon to check for containment within the intersection area. + * + * @return bool True if the polygon is within the intersection area, false otherwise. + */ +bool isWithinIntersection( + const std::shared_ptr & route_handler, const lanelet::ConstLanelet & lanelet, + const Polygon2d & polygon); } // namespace behavior_path_planner::utils::lane_change namespace behavior_path_planner::utils::lane_change::debug diff --git a/planning/behavior_path_lane_change_module/src/manager.cpp b/planning/behavior_path_lane_change_module/src/manager.cpp index 9f1c3c13bfadc..7045544df50aa 100644 --- a/planning/behavior_path_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_lane_change_module/src/manager.cpp @@ -68,8 +68,10 @@ void LaneChangeModuleManager::initParams(rclcpp::Node * node) p.max_longitudinal_acc = getOrDeclareParameter(*node, parameter("max_longitudinal_acc")); // collision check - p.enable_prepare_segment_collision_check = - getOrDeclareParameter(*node, parameter("enable_prepare_segment_collision_check")); + p.enable_collision_check_for_prepare_phase_in_general_lanes = getOrDeclareParameter( + *node, parameter("enable_collision_check_for_prepare_phase.general_lanes")); + p.enable_collision_check_for_prepare_phase_in_intersection = getOrDeclareParameter( + *node, parameter("enable_collision_check_for_prepare_phase.intersection")); p.prepare_segment_ignore_object_velocity_thresh = getOrDeclareParameter( *node, parameter("prepare_segment_ignore_object_velocity_thresh")); p.check_objects_on_current_lanes = diff --git a/planning/behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_lane_change_module/src/scene.cpp index 08034d43feb43..a6d21aede64b6 100644 --- a/planning/behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_lane_change_module/src/scene.cpp @@ -889,23 +889,27 @@ LaneChangeTargetObjects NormalLaneChange::getTargetObjects( target_objects.other_lane.reserve(target_obj_index.other_lane.size()); // objects in current lane + const auto is_check_prepare_phase = check_prepare_phase(); for (const auto & obj_idx : target_obj_index.current_lane) { const auto extended_object = utils::lane_change::transform( - objects.objects.at(obj_idx), common_parameters, *lane_change_parameters_); + objects.objects.at(obj_idx), common_parameters, *lane_change_parameters_, + is_check_prepare_phase); target_objects.current_lane.push_back(extended_object); } // objects in target lane for (const auto & obj_idx : target_obj_index.target_lane) { const auto extended_object = utils::lane_change::transform( - objects.objects.at(obj_idx), common_parameters, *lane_change_parameters_); + objects.objects.at(obj_idx), common_parameters, *lane_change_parameters_, + is_check_prepare_phase); target_objects.target_lane.push_back(extended_object); } // objects in other lane for (const auto & obj_idx : target_obj_index.other_lane) { const auto extended_object = utils::lane_change::transform( - objects.objects.at(obj_idx), common_parameters, *lane_change_parameters_); + objects.objects.at(obj_idx), common_parameters, *lane_change_parameters_, + is_check_prepare_phase); target_objects.other_lane.push_back(extended_object); } @@ -969,8 +973,8 @@ LaneChangeTargetObjectIndices NormalLaneChange::filterObject( const auto obj_velocity_norm = std::hypot( object.kinematics.initial_twist_with_covariance.twist.linear.x, object.kinematics.initial_twist_with_covariance.twist.linear.y); - const auto extended_object = - utils::lane_change::transform(object, common_parameters, *lane_change_parameters_); + const auto extended_object = utils::lane_change::transform( + object, common_parameters, *lane_change_parameters_, check_prepare_phase()); const auto obj_polygon = tier4_autoware_utils::toPolygon2d(object); @@ -2113,4 +2117,33 @@ void NormalLaneChange::updateStopTime() stop_watch_.tic("stop_time"); } +bool NormalLaneChange::check_prepare_phase() const +{ + const auto & route_handler = getRouteHandler(); + const auto & vehicle_info = getCommonParam().vehicle_info; + + const auto check_in_general_lanes = + lane_change_parameters_->enable_collision_check_for_prepare_phase_in_general_lanes; + + lanelet::ConstLanelet current_lane; + if (!route_handler->getClosestLaneletWithinRoute(getEgoPose(), ¤t_lane)) { + RCLCPP_DEBUG( + logger_, "Unable to get current lane. Default to %s.", + (check_in_general_lanes ? "true" : "false")); + return check_in_general_lanes; + } + + const auto ego_footprint = utils::lane_change::getEgoCurrentFootprint(getEgoPose(), vehicle_info); + + const auto check_in_intersection = std::invoke([&]() { + if (!lane_change_parameters_->enable_collision_check_for_prepare_phase_in_intersection) { + return false; + } + + return utils::lane_change::isWithinIntersection(route_handler, current_lane, ego_footprint); + }); + + return check_in_intersection || check_in_general_lanes; +} + } // namespace behavior_path_planner diff --git a/planning/behavior_path_lane_change_module/src/utils/utils.cpp b/planning/behavior_path_lane_change_module/src/utils/utils.cpp index bae733610905b..f112ab103b167 100644 --- a/planning/behavior_path_lane_change_module/src/utils/utils.cpp +++ b/planning/behavior_path_lane_change_module/src/utils/utils.cpp @@ -31,7 +31,11 @@ #include #include #include +#include #include +#include + +#include #include #include @@ -1086,7 +1090,7 @@ std::optional createPolygon( ExtendedPredictedObject transform( const PredictedObject & object, [[maybe_unused]] const BehaviorPathPlannerParameters & common_parameters, - const LaneChangeParameters & lane_change_parameters) + const LaneChangeParameters & lane_change_parameters, const bool check_at_prepare_phase) { ExtendedPredictedObject extended_object; extended_object.uuid = object.object_id; @@ -1096,8 +1100,6 @@ ExtendedPredictedObject transform( extended_object.shape = object.shape; const auto & time_resolution = lane_change_parameters.prediction_time_resolution; - const auto & check_at_prepare_phase = - lane_change_parameters.enable_prepare_segment_collision_check; const auto & prepare_duration = lane_change_parameters.lane_change_prepare_duration; const auto & velocity_threshold = lane_change_parameters.prepare_segment_ignore_object_velocity_thresh; @@ -1155,6 +1157,32 @@ rclcpp::Logger getLogger(const std::string & type) { return rclcpp::get_logger("lane_change").get_child(type); } + +Polygon2d getEgoCurrentFootprint( + const Pose & ego_pose, const vehicle_info_util::VehicleInfo & ego_info) +{ + const auto base_to_front = ego_info.max_longitudinal_offset_m; + const auto base_to_rear = ego_info.rear_overhang_m; + const auto width = ego_info.vehicle_width_m; + + return tier4_autoware_utils::toFootprint(ego_pose, base_to_front, base_to_rear, width); +} + +bool isWithinIntersection( + const std::shared_ptr & route_handler, const lanelet::ConstLanelet & lanelet, + const Polygon2d & polygon) +{ + const std::string id = lanelet.attributeOr("intersection_area", "else"); + if (id == "else") { + return false; + } + + const auto lanelet_polygon = + route_handler->getLaneletMapPtr()->polygonLayer.get(std::atoi(id.c_str())); + + return boost::geometry::within( + polygon, utils::toPolygon2d(lanelet::utils::to2D(lanelet_polygon.basicPolygon()))); +} } // namespace behavior_path_planner::utils::lane_change namespace behavior_path_planner::utils::lane_change::debug @@ -1194,4 +1222,5 @@ geometry_msgs::msg::Polygon createExecutionArea( return polygon; } + } // namespace behavior_path_planner::utils::lane_change::debug From 16c4713c9276c63d38b0d9e8cab2981b35af17d2 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Wed, 3 Apr 2024 12:33:41 +0900 Subject: [PATCH 16/29] fix(lane_change): fix terminal path not working in some case (#6722) Signed-off-by: Zulfaqar Azmi --- planning/behavior_path_lane_change_module/src/utils/utils.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_lane_change_module/src/utils/utils.cpp b/planning/behavior_path_lane_change_module/src/utils/utils.cpp index f112ab103b167..0b4893f94e071 100644 --- a/planning/behavior_path_lane_change_module/src/utils/utils.cpp +++ b/planning/behavior_path_lane_change_module/src/utils/utils.cpp @@ -439,7 +439,8 @@ PathWithLaneId getReferencePathFromTargetLane( .get_child("getReferencePathFromTargetLane"), "start: %f, end: %f", s_start, s_end); - if (s_end - s_start < lane_changing_length) { + constexpr double epsilon = 1e-4; + if (s_end - s_start + epsilon < lane_changing_length) { return PathWithLaneId(); } From 0d0069d81684aafc025bccd480e7d98b1ddca85b Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 3 Apr 2024 13:06:05 +0900 Subject: [PATCH 17/29] chore(goal_planner): delete unnecessary comments (#6729) chore(goal_planner): delete comments Signed-off-by: kosuke55 --- .../src/goal_planner_module.cpp | 28 ------------------- 1 file changed, 28 deletions(-) diff --git a/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp index 7310e93dda4bb..a890cfc21ed13 100644 --- a/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -1640,34 +1640,6 @@ TurnSignalInfo GoalPlannerModule::calcTurnSignalInfo() ignore_signal_ = update_ignore_signal(closest_lanelet.id(), is_ignore); return new_signal; - // // calc TurnIndicatorsCommand - // { - // const double distance_to_end = - // calcSignedArcLength(full_path.points, current_pose.position, end_pose.position); - // const bool is_before_end_pose = distance_to_end >= 0.0; - // if (is_before_end_pose) { - // if (left_side_parking_) { - // turn_signal.turn_signal.command = TurnIndicatorsCommand::ENABLE_LEFT; - // } else { - // turn_signal.turn_signal.command = TurnIndicatorsCommand::ENABLE_RIGHT; - // } - // } else { - // turn_signal.turn_signal.command = TurnIndicatorsCommand::NO_COMMAND; - // } - // } - - // // calc desired/required start/end point - // { - // // ego decelerates so that current pose is the point `turn_light_on_threshold_time` seconds - // // before starting pull_over - // turn_signal.desired_start_point = - // last_approval_data_ && hasDecidedPath() ? last_approval_data_->pose : current_pose; - // turn_signal.desired_end_point = end_pose; - // turn_signal.required_start_point = start_pose; - // turn_signal.required_end_point = end_pose; - // } - - // return turn_signal; } bool GoalPlannerModule::checkOccupancyGridCollision(const PathWithLaneId & path) const From fcf05297fd4c4a4a02d65f3d3233684cd3ae781c Mon Sep 17 00:00:00 2001 From: cyn-liu <104069308+cyn-liu@users.noreply.github.com> Date: Wed, 3 Apr 2024 15:44:15 +0800 Subject: [PATCH 18/29] feat(global_parameter_loader): add gtest to global parameter loader (#5021) * add remote * feat(global_parameter_loader): add gtest of global-parameter-loader Signed-off-by: Cynthia Liu * style(pre-commit): autofix --------- Signed-off-by: Cynthia Liu Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> --- build_depends.repos | 5 +++ common/global_parameter_loader/CMakeLists.txt | 5 +++ common/global_parameter_loader/package.xml | 4 +- .../test/test_global_params_launch.cpp | 44 +++++++++++++++++++ 4 files changed, 57 insertions(+), 1 deletion(-) create mode 100644 common/global_parameter_loader/test/test_global_params_launch.cpp diff --git a/build_depends.repos b/build_depends.repos index f7b3f12484015..5a12a67dbd346 100644 --- a/build_depends.repos +++ b/build_depends.repos @@ -41,3 +41,8 @@ repositories: type: git url: https://github.com/MORAI-Autonomous/MORAI-ROS2_morai_msgs.git version: main + #vehicle + vehicle/sample_vehicle_launch: + type: git + url: https://github.com/autowarefoundation/sample_vehicle_launch.git + version: main diff --git a/common/global_parameter_loader/CMakeLists.txt b/common/global_parameter_loader/CMakeLists.txt index e67ae1a5c06fc..eaca44c515452 100644 --- a/common/global_parameter_loader/CMakeLists.txt +++ b/common/global_parameter_loader/CMakeLists.txt @@ -4,6 +4,11 @@ project(global_parameter_loader) find_package(autoware_cmake REQUIRED) autoware_package() +if(BUILD_TESTING) + file(GLOB_RECURSE test_files test/*.cpp) + ament_add_ros_isolated_gtest(test_global_params_launch ${test_files}) +endif() + ament_auto_package( INSTALL_TO_SHARE launch diff --git a/common/global_parameter_loader/package.xml b/common/global_parameter_loader/package.xml index 4c2568b9aec98..78d08e4038250 100644 --- a/common/global_parameter_loader/package.xml +++ b/common/global_parameter_loader/package.xml @@ -10,8 +10,10 @@ ament_cmake_auto autoware_cmake - vehicle_info_util + sample_vehicle_description + vehicle_info_util + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/common/global_parameter_loader/test/test_global_params_launch.cpp b/common/global_parameter_loader/test/test_global_params_launch.cpp new file mode 100644 index 0000000000000..2b33a695253ff --- /dev/null +++ b/common/global_parameter_loader/test/test_global_params_launch.cpp @@ -0,0 +1,44 @@ +// Copyright 2023 The Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +#include +#include +#include + +TEST(TestLaunchFile, test_launch_file) +{ + // Define the path of Python launch file + std::string global_params_launch_path = "global_params.launch.py"; + + // Define the parameters you want to pass to the launch file + std::string use_sim_time_param = "false"; + std::string vehicle_model_param = "sample_vehicle"; + // Construct the command to run the Python launch script with parameters + std::string command = "ros2 launch global_parameter_loader " + global_params_launch_path + + " use_sim_time:=" + use_sim_time_param + + " vehicle_model:=" + vehicle_model_param; + + // Use the system() function to execute the command + int result = std::system(command.c_str()); + // Check the result of running the launch file + EXPECT_EQ(result, 0); +} + +int main(int argc, char * argv[]) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} From 45f77be092f2c17692e1cfeabce33619f6327cb8 Mon Sep 17 00:00:00 2001 From: Berkay Karaman Date: Wed, 3 Apr 2024 13:38:14 +0300 Subject: [PATCH 19/29] feat(time_synchronizer_nodelet): set input_offsets zero if it was not defined (#6664) Signed-off-by: Berkay Karaman --- .../src/time_synchronizer/time_synchronizer_nodelet.cpp | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/sensing/pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_nodelet.cpp b/sensing/pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_nodelet.cpp index 7aae6c937f4a9..12b034043894e 100644 --- a/sensing/pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_nodelet.cpp @@ -83,7 +83,12 @@ PointCloudDataSynchronizerComponent::PointCloudDataSynchronizerComponent( timeout_sec_ = static_cast(declare_parameter("timeout_sec", 0.1)); input_offset_ = declare_parameter("input_offset", std::vector{}); - if (!input_offset_.empty() && input_topics_.size() != input_offset_.size()) { + + // If input_offset_ is not defined, set all offsets to 0 + if (input_offset_.empty()) { + input_offset_.resize(input_topics_.size(), 0.0); + RCLCPP_INFO(get_logger(), "Input offset is not defined. Set all offsets to 0.0."); + } else if (input_topics_.size() != input_offset_.size()) { RCLCPP_ERROR(get_logger(), "The number of topics does not match the number of offsets."); return; } From 21c4eb00989e1a85b40434a83b48ee240f7c875a Mon Sep 17 00:00:00 2001 From: oguzkaganozt Date: Wed, 3 Apr 2024 14:14:29 +0300 Subject: [PATCH 20/29] refactor(object_range_splitter): rework parameters (#6705) * rework parameters Signed-off-by: oguzkaganozt * . Signed-off-by: oguzkaganozt * . Signed-off-by: oguzkaganozt * style(pre-commit): autofix --------- Signed-off-by: oguzkaganozt Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- perception/object_range_splitter/README.md | 4 +-- .../schema/object_range_splitter.schema.json | 33 +++++++++++++++++++ 2 files changed, 34 insertions(+), 3 deletions(-) create mode 100644 perception/object_range_splitter/schema/object_range_splitter.schema.json diff --git a/perception/object_range_splitter/README.md b/perception/object_range_splitter/README.md index 89d266a666219..19c571962c0dc 100644 --- a/perception/object_range_splitter/README.md +++ b/perception/object_range_splitter/README.md @@ -43,9 +43,7 @@ Example: ## Parameters -| Name | Type | Description | -| ------------- | ----- | ---------------------------------------------------- | -| `split_range` | float | the distance boundary to divide detected objects [m] | +{{ json_to_markdown("perception/object_range_splitter/schema/object_range_splitter.schema.json") }} ## Assumptions / Known limits diff --git a/perception/object_range_splitter/schema/object_range_splitter.schema.json b/perception/object_range_splitter/schema/object_range_splitter.schema.json new file mode 100644 index 0000000000000..ed5ba3a96c18b --- /dev/null +++ b/perception/object_range_splitter/schema/object_range_splitter.schema.json @@ -0,0 +1,33 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for object_range_splitter", + "type": "object", + "definitions": { + "object_range_splitter": { + "type": "object", + "properties": { + "split_range": { + "type": "number", + "description": "object_range_splitter is a package to divide detected objects into two messages by the distance from the origin", + "default": "30.0" + } + }, + "required": ["split_range"], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/object_range_splitter" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} From 951b90231597a745be855145a2d61a64b1ef7145 Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Wed, 3 Apr 2024 21:00:30 +0900 Subject: [PATCH 21/29] feat(tier4_autoware_utils, obstacle_cruise): change to read topic by polling (#6702) change to read topic by polling Signed-off-by: Yuki Takagi --- .../ros/polling_subscriber.hpp | 65 +++++++++++++++++++ .../include/obstacle_cruise_planner/node.hpp | 15 ++--- planning/obstacle_cruise_planner/src/node.cpp | 45 ++++++------- 3 files changed, 93 insertions(+), 32 deletions(-) create mode 100644 common/tier4_autoware_utils/include/tier4_autoware_utils/ros/polling_subscriber.hpp diff --git a/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/polling_subscriber.hpp b/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/polling_subscriber.hpp new file mode 100644 index 0000000000000..f4d230e15dcf1 --- /dev/null +++ b/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/polling_subscriber.hpp @@ -0,0 +1,65 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef TIER4_AUTOWARE_UTILS__ROS__POLLING_SUBSCRIBER_HPP_ +#define TIER4_AUTOWARE_UTILS__ROS__POLLING_SUBSCRIBER_HPP_ + +#include + +#include + +namespace tier4_autoware_utils +{ + +template +class InterProcessPollingSubscriber +{ +private: + typename rclcpp::Subscription::SharedPtr subscriber_; + std::optional data_; + +public: + explicit InterProcessPollingSubscriber(rclcpp::Node * node, const std::string & topic_name) + { + auto noexec_callback_group = + node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive, false); + auto noexec_subscription_options = rclcpp::SubscriptionOptions(); + noexec_subscription_options.callback_group = noexec_callback_group; + + subscriber_ = node->create_subscription( + topic_name, rclcpp::QoS{1}, [node](const typename T::ConstSharedPtr msg) { assert(false); }, + noexec_subscription_options); + }; + bool updateLatestData() + { + rclcpp::MessageInfo message_info; + T tmp; + // The queue size (QoS) must be 1 to get the last message data. + if (subscriber_->take(tmp, message_info)) { + data_ = tmp; + } + return data_.has_value(); + }; + const T & getData() const + { + if (!data_.has_value()) { + throw std::runtime_error("Bad_optional_access in class InterProcessPollingSubscriber"); + } + return data_.value(); + }; +}; + +} // namespace tier4_autoware_utils + +#endif // TIER4_AUTOWARE_UTILS__ROS__POLLING_SUBSCRIBER_HPP_ diff --git a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp index d1a9d0ff56b52..c368265ea0f66 100644 --- a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp +++ b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp @@ -21,6 +21,7 @@ #include "obstacle_cruise_planner/type_alias.hpp" #include "signal_processing/lowpass_filter_1d.hpp" #include "tier4_autoware_utils/ros/logger_level_configure.hpp" +#include "tier4_autoware_utils/ros/polling_subscriber.hpp" #include "tier4_autoware_utils/system/stop_watch.hpp" #include @@ -138,14 +139,12 @@ class ObstacleCruisePlannerNode : public rclcpp::Node // subscriber rclcpp::Subscription::SharedPtr traj_sub_; - rclcpp::Subscription::SharedPtr objects_sub_; - rclcpp::Subscription::SharedPtr odom_sub_; - rclcpp::Subscription::SharedPtr acc_sub_; - - // data for callback functions - PredictedObjects::ConstSharedPtr objects_ptr_{nullptr}; - Odometry::ConstSharedPtr ego_odom_ptr_{nullptr}; - AccelWithCovarianceStamped::ConstSharedPtr ego_accel_ptr_{nullptr}; + tier4_autoware_utils::InterProcessPollingSubscriber ego_odom_sub_{ + this, "~/input/odometry"}; + tier4_autoware_utils::InterProcessPollingSubscriber objects_sub_{ + this, "~/input/objects"}; + tier4_autoware_utils::InterProcessPollingSubscriber acc_sub_{ + this, "~/input/acceleration"}; // Vehicle Parameters VehicleInfo vehicle_info_; diff --git a/planning/obstacle_cruise_planner/src/node.cpp b/planning/obstacle_cruise_planner/src/node.cpp index 2d1b70d1745f9..a069b4b6f9395 100644 --- a/planning/obstacle_cruise_planner/src/node.cpp +++ b/planning/obstacle_cruise_planner/src/node.cpp @@ -357,15 +357,6 @@ ObstacleCruisePlannerNode::ObstacleCruisePlannerNode(const rclcpp::NodeOptions & traj_sub_ = create_subscription( "~/input/trajectory", rclcpp::QoS{1}, std::bind(&ObstacleCruisePlannerNode::onTrajectory, this, _1)); - objects_sub_ = create_subscription( - "~/input/objects", rclcpp::QoS{1}, - [this](const PredictedObjects::ConstSharedPtr msg) { objects_ptr_ = msg; }); - odom_sub_ = create_subscription( - "~/input/odometry", rclcpp::QoS{1}, - [this](const Odometry::ConstSharedPtr msg) { ego_odom_ptr_ = msg; }); - acc_sub_ = create_subscription( - "~/input/acceleration", rclcpp::QoS{1}, - [this](const AccelWithCovarianceStamped::ConstSharedPtr msg) { ego_accel_ptr_ = msg; }); // publisher trajectory_pub_ = create_publisher("~/output/trajectory", 1); @@ -493,10 +484,15 @@ rcl_interfaces::msg::SetParametersResult ObstacleCruisePlannerNode::onParam( void ObstacleCruisePlannerNode::onTrajectory(const Trajectory::ConstSharedPtr msg) { - const auto traj_points = motion_utils::convertToTrajectoryPointArray(*msg); + if ( + !ego_odom_sub_.updateLatestData() || !objects_sub_.updateLatestData() || + !acc_sub_.updateLatestData()) { + return; + } + const auto traj_points = motion_utils::convertToTrajectoryPointArray(*msg); // check if subscribed variables are ready - if (traj_points.empty() || !ego_odom_ptr_ || !ego_accel_ptr_ || !objects_ptr_) { + if (traj_points.empty()) { return; } @@ -609,11 +605,11 @@ std::vector ObstacleCruisePlannerNode::convertToObstacles( { stop_watch_.tic(__func__); - const auto obj_stamp = rclcpp::Time(objects_ptr_->header.stamp); + const auto obj_stamp = rclcpp::Time(objects_sub_.getData().header.stamp); const auto & p = behavior_determination_param_; std::vector target_obstacles; - for (const auto & predicted_object : objects_ptr_->objects) { + for (const auto & predicted_object : objects_sub_.getData().objects) { const auto & object_id = tier4_autoware_utils::toHexString(predicted_object.object_id).substr(0, 4); const auto & current_obstacle_pose = @@ -631,7 +627,8 @@ std::vector ObstacleCruisePlannerNode::convertToObstacles( } // 2. Check if the obstacle is in front of the ego. - const size_t ego_idx = ego_nearest_param_.findIndex(traj_points, ego_odom_ptr_->pose.pose); + const size_t ego_idx = + ego_nearest_param_.findIndex(traj_points, ego_odom_sub_.getData().pose.pose); const auto ego_to_obstacle_distance = calcDistanceToFrontVehicle(traj_points, ego_idx, current_obstacle_pose.pose.position); if (!ego_to_obstacle_distance) { @@ -727,7 +724,7 @@ ObstacleCruisePlannerNode::determineEgoBehaviorAgainstObstacles( // calculated decimated trajectory points and trajectory polygon const auto decimated_traj_points = decimateTrajectoryPoints(traj_points); const auto decimated_traj_polys = - createOneStepPolygons(decimated_traj_points, vehicle_info_, ego_odom_ptr_->pose.pose); + createOneStepPolygons(decimated_traj_points, vehicle_info_, ego_odom_sub_.getData().pose.pose); debug_data_ptr_->detection_polygons = decimated_traj_polys; // determine ego's behavior from stop, cruise and slow down @@ -785,7 +782,7 @@ ObstacleCruisePlannerNode::determineEgoBehaviorAgainstObstacles( slow_down_condition_counter_.removeCounterUnlessUpdated(); // Check target obstacles' consistency - checkConsistency(objects_ptr_->header.stamp, *objects_ptr_, stop_obstacles); + checkConsistency(objects_sub_.getData().header.stamp, objects_sub_.getData(), stop_obstacles); // update previous obstacles prev_stop_obstacles_ = stop_obstacles; @@ -807,7 +804,7 @@ std::vector ObstacleCruisePlannerNode::decimateTrajectoryPoints // trim trajectory const size_t ego_seg_idx = - ego_nearest_param_.findSegmentIndex(traj_points, ego_odom_ptr_->pose.pose); + ego_nearest_param_.findSegmentIndex(traj_points, ego_odom_sub_.getData().pose.pose); const size_t traj_start_point_idx = ego_seg_idx; const auto trimmed_traj_points = std::vector(traj_points.begin() + traj_start_point_idx, traj_points.end()); @@ -1191,7 +1188,7 @@ std::optional ObstacleCruisePlannerNode::createStopObstacle( // calculate collision points with trajectory with lateral stop margin const auto traj_polys_with_lat_margin = createOneStepPolygons( - traj_points, vehicle_info_, ego_odom_ptr_->pose.pose, p.max_lat_margin_for_stop); + traj_points, vehicle_info_, ego_odom_sub_.getData().pose.pose, p.max_lat_margin_for_stop); const auto collision_point = polygon_utils::getCollisionPoint( traj_points, traj_polys_with_lat_margin, obstacle, is_driving_forward_, vehicle_info_); @@ -1261,7 +1258,7 @@ std::optional ObstacleCruisePlannerNode::createSlowDownObstacl // calculate collision points with trajectory with lateral stop margin // NOTE: For additional margin, hysteresis is not divided by two. const auto traj_polys_with_lat_margin = createOneStepPolygons( - traj_points, vehicle_info_, ego_odom_ptr_->pose.pose, + traj_points, vehicle_info_, ego_odom_sub_.getData().pose.pose, p.max_lat_margin_for_slow_down + p.lat_hysteresis_margin_for_slow_down); std::vector front_collision_polygons; @@ -1424,8 +1421,8 @@ double ObstacleCruisePlannerNode::calcCollisionTimeMargin( const std::vector & collision_points, const std::vector & traj_points, const bool is_driving_forward) const { - const auto & ego_pose = ego_odom_ptr_->pose.pose; - const double ego_vel = ego_odom_ptr_->twist.twist.linear.x; + const auto & ego_pose = ego_odom_sub_.getData().pose.pose; + const double ego_vel = ego_odom_sub_.getData().twist.twist.linear.x; const double time_to_reach_collision_point = [&]() { const double abs_ego_offset = is_driving_forward @@ -1457,9 +1454,9 @@ PlannerData ObstacleCruisePlannerNode::createPlannerData( PlannerData planner_data; planner_data.current_time = now(); planner_data.traj_points = traj_points; - planner_data.ego_pose = ego_odom_ptr_->pose.pose; - planner_data.ego_vel = ego_odom_ptr_->twist.twist.linear.x; - planner_data.ego_acc = ego_accel_ptr_->accel.accel.linear.x; + planner_data.ego_pose = ego_odom_sub_.getData().pose.pose; + planner_data.ego_vel = ego_odom_sub_.getData().twist.twist.linear.x; + planner_data.ego_acc = acc_sub_.getData().accel.accel.linear.x; planner_data.is_driving_forward = is_driving_forward_; return planner_data; } From 47e7215c1d9dabd51a0ddd3a9ed5069b834d5e5d Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Thu, 4 Apr 2024 11:36:28 +0900 Subject: [PATCH 22/29] docs(perception_online_evaluator): add description about yaw rate evaluation (#6737) Signed-off-by: kyoichi-sugahara --- evaluator/perception_online_evaluator/README.md | 1 + 1 file changed, 1 insertion(+) diff --git a/evaluator/perception_online_evaluator/README.md b/evaluator/perception_online_evaluator/README.md index c0e2a516cf948..7c2179239221e 100644 --- a/evaluator/perception_online_evaluator/README.md +++ b/evaluator/perception_online_evaluator/README.md @@ -11,6 +11,7 @@ This module allows for the evaluation of how accurately perception results are g - Calculates lateral deviation between the predicted path and the actual traveled trajectory. - Calculates lateral deviation between the smoothed traveled trajectory and the perceived position to evaluate the stability of lateral position recognition. - Calculates yaw deviation between the smoothed traveled trajectory and the perceived position to evaluate the stability of yaw recognition. +- Calculates yaw rate based on the yaw of the object received in the previous cycle to evaluate the stability of the yaw rate recognition. ## Inputs / Outputs From c4546e20a39b16007370ce46d20ccda2c4eee2ae Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Thu, 4 Apr 2024 16:13:42 +0900 Subject: [PATCH 23/29] fix(hazard_status_converter): check current operation mode (#6733) * fix: hazard status converter Signed-off-by: Takagi, Isamu * fix: topic name and modes Signed-off-by: Takagi, Isamu * fix check target mode Signed-off-by: Takagi, Isamu * fix message type Signed-off-by: Takagi, Isamu * Revert "fix check target mode" This reverts commit 8b190b7b99490503a52b155cad9f593c1c97e553. --------- Signed-off-by: Takagi, Isamu --- system/hazard_status_converter/package.xml | 1 + .../hazard_status_converter/src/converter.cpp | 73 +++++++++++++++---- .../hazard_status_converter/src/converter.hpp | 11 +++ 3 files changed, 69 insertions(+), 16 deletions(-) diff --git a/system/hazard_status_converter/package.xml b/system/hazard_status_converter/package.xml index 9ae7a384927b9..082aa85cba97a 100644 --- a/system/hazard_status_converter/package.xml +++ b/system/hazard_status_converter/package.xml @@ -10,6 +10,7 @@ ament_cmake_auto autoware_cmake + autoware_adapi_v1_msgs autoware_auto_system_msgs diagnostic_msgs rclcpp diff --git a/system/hazard_status_converter/src/converter.cpp b/system/hazard_status_converter/src/converter.cpp index e1da4f463f06d..58282306491dd 100644 --- a/system/hazard_status_converter/src/converter.cpp +++ b/system/hazard_status_converter/src/converter.cpp @@ -32,10 +32,10 @@ enum class HazardLevel { NF, SF, LF, SPF }; struct TempNode { const DiagnosticNode & node; - bool is_auto_tree; + bool is_root_tree; }; -HazardLevel get_hazard_level(const TempNode & node, DiagnosticLevel auto_mode_level) +HazardLevel get_hazard_level(const TempNode & node, DiagnosticLevel root_mode_level) { // Convert the level according to the table below. // The Level other than auto mode is considered OK. @@ -49,7 +49,7 @@ HazardLevel get_hazard_level(const TempNode & node, DiagnosticLevel auto_mode_le // | STALE | SF | LF | SPF | SPF | // |-------|-------------------------------| - const auto root_level = node.is_auto_tree ? auto_mode_level : DiagnosticStatus::OK; + const auto root_level = node.is_root_tree ? root_mode_level : DiagnosticStatus::OK; const auto node_level = node.node.status.level; if (node_level == DiagnosticStatus::OK) { @@ -67,20 +67,21 @@ HazardLevel get_hazard_level(const TempNode & node, DiagnosticLevel auto_mode_le return HazardLevel::SPF; } -void set_auto_tree(std::vector & nodes, int index) +void set_root_tree(std::vector & nodes, int index) { TempNode & node = nodes[index]; - if (node.is_auto_tree) { + if (node.is_root_tree) { return; } - node.is_auto_tree = true; + node.is_root_tree = true; for (const auto & link : node.node.links) { - set_auto_tree(nodes, link.index); + set_root_tree(nodes, link.index); } } -HazardStatusStamped convert_hazard_diagnostics(const DiagnosticGraph & graph) +HazardStatusStamped convert_hazard_diagnostics( + const DiagnosticGraph & graph, const std::string & root, bool ignore) { // Create temporary tree for conversion. std::vector nodes; @@ -90,19 +91,21 @@ HazardStatusStamped convert_hazard_diagnostics(const DiagnosticGraph & graph) } // Mark nodes included in the auto mode tree. - DiagnosticLevel auto_mode_level = DiagnosticStatus::STALE; - for (size_t index = 0; index < nodes.size(); ++index) { - const auto & status = nodes[index].node.status; - if (status.name == "/autoware/modes/autonomous") { - set_auto_tree(nodes, index); - auto_mode_level = status.level; + DiagnosticLevel root_mode_level = DiagnosticStatus::STALE; + if (!root.empty() && !ignore) { + for (size_t index = 0; index < nodes.size(); ++index) { + const auto & status = nodes[index].node.status; + if (status.name == root) { + set_root_tree(nodes, index); + root_mode_level = status.level; + } } } // Calculate hazard level from node level and root level. HazardStatusStamped hazard; for (const auto & node : nodes) { - switch (get_hazard_level(node, auto_mode_level)) { + switch (get_hazard_level(node, root_mode_level)) { case HazardLevel::NF: hazard.status.diag_no_fault.push_back(node.node.status); break; @@ -131,6 +134,22 @@ Converter::Converter(const rclcpp::NodeOptions & options) : Node("converter", op sub_graph_ = create_subscription( "~/diagnostics_graph", rclcpp::QoS(3), std::bind(&Converter::on_graph, this, std::placeholders::_1)); + sub_state_ = create_subscription( + "/autoware/state", rclcpp::QoS(1), + std::bind(&Converter::on_state, this, std::placeholders::_1)); + sub_mode_ = create_subscription( + "/system/operation_mode/state", rclcpp::QoS(1).transient_local(), + std::bind(&Converter::on_mode, this, std::placeholders::_1)); +} + +void Converter::on_state(const AutowareState::ConstSharedPtr msg) +{ + state_ = msg; +} + +void Converter::on_mode(const OperationMode::ConstSharedPtr msg) +{ + mode_ = msg; } void Converter::on_graph(const DiagnosticGraph::ConstSharedPtr msg) @@ -148,7 +167,29 @@ void Converter::on_graph(const DiagnosticGraph::ConstSharedPtr msg) return HazardStatus::NO_FAULT; }; - HazardStatusStamped hazard = convert_hazard_diagnostics(*msg); + const auto is_ignore = [this]() { + if (mode_ && state_) { + if (mode_->mode == OperationMode::AUTONOMOUS || mode_->mode == OperationMode::STOP) { + if (state_->state == AutowareState::WAITING_FOR_ROUTE) return true; + if (state_->state == AutowareState::PLANNING) return true; + } + if (state_->state == AutowareState::INITIALIZING) return true; + if (state_->state == AutowareState::FINALIZING) return true; + } + return false; + }; + + const auto get_root = [this]() { + if (mode_) { + if (mode_->mode == OperationMode::STOP) return "/autoware/modes/stop"; + if (mode_->mode == OperationMode::AUTONOMOUS) return "/autoware/modes/autonomous"; + if (mode_->mode == OperationMode::LOCAL) return "/autoware/modes/local"; + if (mode_->mode == OperationMode::REMOTE) return "/autoware/modes/remote"; + } + return ""; + }; + + HazardStatusStamped hazard = convert_hazard_diagnostics(*msg, get_root(), is_ignore()); hazard.stamp = msg->stamp; hazard.status.level = get_system_level(hazard.status); hazard.status.emergency = hazard.status.level == HazardStatus::SINGLE_POINT_FAULT; diff --git a/system/hazard_status_converter/src/converter.hpp b/system/hazard_status_converter/src/converter.hpp index 90c6f6e42bf85..04e84cfb3c0c4 100644 --- a/system/hazard_status_converter/src/converter.hpp +++ b/system/hazard_status_converter/src/converter.hpp @@ -17,6 +17,8 @@ #include +#include +#include #include #include @@ -33,11 +35,20 @@ class Converter : public rclcpp::Node explicit Converter(const rclcpp::NodeOptions & options); private: + using AutowareState = autoware_auto_system_msgs::msg::AutowareState; + using OperationMode = autoware_adapi_v1_msgs::msg::OperationModeState; using DiagnosticGraph = tier4_system_msgs::msg::DiagnosticGraph; using HazardStatusStamped = autoware_auto_system_msgs::msg::HazardStatusStamped; + rclcpp::Subscription::SharedPtr sub_state_; + rclcpp::Subscription::SharedPtr sub_mode_; rclcpp::Subscription::SharedPtr sub_graph_; rclcpp::Publisher::SharedPtr pub_hazard_; + void on_state(const AutowareState::ConstSharedPtr msg); + void on_mode(const OperationMode::ConstSharedPtr msg); void on_graph(const DiagnosticGraph::ConstSharedPtr msg); + + AutowareState::ConstSharedPtr state_; + OperationMode::ConstSharedPtr mode_; }; } // namespace hazard_status_converter From 718bd0b822b7921d060d54595b05c0a3267f4783 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Thu, 4 Apr 2024 22:52:42 +0900 Subject: [PATCH 24/29] fix(lane_change): limit prepare and lane changing length (#6734) Signed-off-by: Zulfaqar Azmi --- .../utils/utils.hpp | 17 +++++++++++++++++ .../src/scene.cpp | 11 +++++------ .../src/utils/utils.cpp | 10 ++++++++++ 3 files changed, 32 insertions(+), 6 deletions(-) diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp index ff5d7bc0773fa..7c8cfdb926a6b 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp @@ -257,6 +257,23 @@ Polygon2d getEgoCurrentFootprint( bool isWithinIntersection( const std::shared_ptr & route_handler, const lanelet::ConstLanelet & lanelet, const Polygon2d & polygon); + +/** + * @brief Calculates the distance required during a lane change operation. + * + * Used for computing prepare or lane change length based on current and maximum velocity, + * acceleration, and duration, returning the lesser of accelerated distance or distance at max + * velocity. + * + * @param velocity The current velocity of the vehicle in meters per second (m/s). + * @param maximum_velocity The maximum velocity the vehicle can reach in meters per second (m/s). + * @param acceleration The acceleration of the vehicle in meters per second squared (m/s^2). + * @param duration The duration of the lane change in seconds (s). + * @return The calculated minimum distance in meters (m). + */ +double calcPhaseLength( + const double velocity, const double maximum_velocity, const double acceleration, + const double time); } // namespace behavior_path_planner::utils::lane_change namespace behavior_path_planner::utils::lane_change::debug diff --git a/planning/behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_lane_change_module/src/scene.cpp index a6d21aede64b6..bc9a366e62b34 100644 --- a/planning/behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_lane_change_module/src/scene.cpp @@ -1293,9 +1293,8 @@ bool NormalLaneChange::getLaneChangePaths( (prepare_duration < 1e-3) ? 0.0 : ((prepare_velocity - current_velocity) / prepare_duration); - const double prepare_length = - current_velocity * prepare_duration + - 0.5 * longitudinal_acc_on_prepare * std::pow(prepare_duration, 2); + const auto prepare_length = utils::lane_change::calcPhaseLength( + current_velocity, getCommonParam().max_vel, longitudinal_acc_on_prepare, prepare_duration); auto prepare_segment = getPrepareSegment(current_lanes, backward_path_length, prepare_length); @@ -1347,9 +1346,9 @@ bool NormalLaneChange::getLaneChangePaths( utils::lane_change::calcLaneChangingAcceleration( initial_lane_changing_velocity, max_path_velocity, lane_changing_time, sampled_longitudinal_acc); - const auto lane_changing_length = - initial_lane_changing_velocity * lane_changing_time + - 0.5 * longitudinal_acc_on_lane_changing * lane_changing_time * lane_changing_time; + const auto lane_changing_length = utils::lane_change::calcPhaseLength( + initial_lane_changing_velocity, getCommonParam().max_vel, + longitudinal_acc_on_lane_changing, lane_changing_time); const auto terminal_lane_changing_velocity = std::min( initial_lane_changing_velocity + longitudinal_acc_on_lane_changing * lane_changing_time, getCommonParam().max_vel); diff --git a/planning/behavior_path_lane_change_module/src/utils/utils.cpp b/planning/behavior_path_lane_change_module/src/utils/utils.cpp index 0b4893f94e071..15db6b0055756 100644 --- a/planning/behavior_path_lane_change_module/src/utils/utils.cpp +++ b/planning/behavior_path_lane_change_module/src/utils/utils.cpp @@ -1184,6 +1184,16 @@ bool isWithinIntersection( return boost::geometry::within( polygon, utils::toPolygon2d(lanelet::utils::to2D(lanelet_polygon.basicPolygon()))); } + +double calcPhaseLength( + const double velocity, const double maximum_velocity, const double acceleration, + const double duration) +{ + const auto length_with_acceleration = + velocity * duration + 0.5 * acceleration * std::pow(duration, 2); + const auto length_with_max_velocity = maximum_velocity * duration; + return std::min(length_with_acceleration, length_with_max_velocity); +} } // namespace behavior_path_planner::utils::lane_change namespace behavior_path_planner::utils::lane_change::debug From 5d0922dfe3cecb32082ff9ad01d933b006373b30 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 4 Apr 2024 23:23:04 +0900 Subject: [PATCH 25/29] feat(perception_online_evaluator): ignore reversal of orientation from yaw_rate calculation (#6748) Signed-off-by: kosuke55 --- .../src/metrics_calculator.cpp | 13 +++++++++---- .../src/perception_online_evaluator_node.cpp | 1 + 2 files changed, 10 insertions(+), 4 deletions(-) diff --git a/evaluator/perception_online_evaluator/src/metrics_calculator.cpp b/evaluator/perception_online_evaluator/src/metrics_calculator.cpp index 20d8c6d570489..4b882bb8b2e68 100644 --- a/evaluator/perception_online_evaluator/src/metrics_calculator.cpp +++ b/evaluator/perception_online_evaluator/src/metrics_calculator.cpp @@ -381,12 +381,17 @@ MetricStatMap MetricsCalculator::calcYawRateMetrics(const ClassObjectsMap & clas if (time_diff < 0.01) { continue; } - const auto current_yaw = + const double current_yaw = tf2::getYaw(object.kinematics.initial_pose_with_covariance.pose.orientation); - const auto previous_yaw = + const double previous_yaw = tf2::getYaw(previous_object.kinematics.initial_pose_with_covariance.pose.orientation); - const auto yaw_rate = - std::abs(tier4_autoware_utils::normalizeRadian(current_yaw - previous_yaw) / time_diff); + const double yaw_diff = + std::abs(tier4_autoware_utils::normalizeRadian(current_yaw - previous_yaw)); + // if yaw_diff is close to PI, reversal of orientation is likely occurring, so ignore it + if (std::abs(M_PI - yaw_diff) < 0.1) { + continue; + } + const auto yaw_rate = yaw_diff / time_diff; stat.add(yaw_rate); } metric_stat_map["yaw_rate_" + convertLabelToString(label)] = stat; diff --git a/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp b/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp index f3a08bf42797a..ceb304894ad8c 100644 --- a/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp +++ b/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp @@ -214,6 +214,7 @@ rcl_interfaces::msg::SetParametersResult PerceptionOnlineEvaluatorNode::onParame auto & p = parameters_; updateParam(parameters, "smoothing_window_size", p->smoothing_window_size); + updateParam(parameters, "stopped_velocity_threshold", p->stopped_velocity_threshold); // update metrics { From a6b29aa839e8c15350d9e1dffe2e4a3d6a16e6bd Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Fri, 5 Apr 2024 10:22:46 +0900 Subject: [PATCH 26/29] feat(obstacle_pointcloud_based_validator_node): skip validation when obstacle pointcloud is empty (#6684) * feat: skip validation when obstacle pointcloud is empty Signed-off-by: yoshiri * fix: remove mistakenly unremoved line Signed-off-by: yoshiri --------- Signed-off-by: yoshiri --- .../src/obstacle_pointcloud_based_validator.cpp | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp b/perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp index e39de639a6121..db2e6ec3a7901 100644 --- a/perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp +++ b/perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp @@ -327,15 +327,19 @@ void ObstaclePointCloudBasedValidator::onObjectsAndObstaclePointCloud( // objects_pub_->publish(*input_objects); return; } + bool validation_is_ready = true; if (!validator_->setKdtreeInputCloud(input_obstacle_pointcloud)) { - RCLCPP_WARN_THROTTLE(this->get_logger(), *this->get_clock(), 5, "cannot receive pointcloud"); - return; + RCLCPP_WARN_THROTTLE( + this->get_logger(), *this->get_clock(), 5, + "obstacle pointcloud is empty! Can not validate objects."); + validation_is_ready = false; } for (size_t i = 0; i < transformed_objects.objects.size(); ++i) { const auto & transformed_object = transformed_objects.objects.at(i); const auto & object = input_objects->objects.at(i); - const auto validated = validator_->validate_object(transformed_object); + const auto validated = + validation_is_ready ? validator_->validate_object(transformed_object) : false; if (debugger_) { debugger_->addNeighborPointcloud(validator_->getDebugNeighborPointCloud()); debugger_->addPointcloudWithinPolygon(validator_->getDebugPointCloudWithinObject()); From c0f09e1700143f83e72330d63a3b39c0d94e7741 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Fri, 5 Apr 2024 10:49:31 +0900 Subject: [PATCH 27/29] feat(lane_change): check prepare phase in turn direction lanes (#6726) * feat(lane_change): check prepare phase in turn direction lanes Signed-off-by: Muhammad Zulfaqar Azmi * Doxygen comment Signed-off-by: Muhammad Zulfaqar Azmi * Add config Signed-off-by: Muhammad Zulfaqar Azmi * fix comments by the reviewer Signed-off-by: Muhammad Zulfaqar Azmi --------- Signed-off-by: Muhammad Zulfaqar Azmi --- .../behavior_path_lane_change_module/README.md | 3 ++- .../config/lane_change.param.yaml | 1 + .../utils/data_structs.hpp | 1 + .../utils/utils.hpp | 15 +++++++++++++++ .../src/manager.cpp | 2 ++ .../src/scene.cpp | 10 +++++++++- .../src/utils/utils.cpp | 13 +++++++++++++ 7 files changed, 43 insertions(+), 2 deletions(-) diff --git a/planning/behavior_path_lane_change_module/README.md b/planning/behavior_path_lane_change_module/README.md index 17cdc58f5ad47..62f35a053958a 100644 --- a/planning/behavior_path_lane_change_module/README.md +++ b/planning/behavior_path_lane_change_module/README.md @@ -554,7 +554,8 @@ The following parameters are configurable in [lane_change.param.yaml](https://gi | Name | Unit | Type | Description | Default value | | :------------------------------------------------------- | ----- | ------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------- | | `enable_collision_check_for_prepare_phase.general_lanes` | [-] | boolean | Perform collision check starting from the prepare phase for situations not explicitly covered by other settings (e.g., intersections). If `false`, collision check only evaluated for lane changing phase. | false | -| `enable_collision_check_for_prepare_phase.intersection` | [-] | boolean | Perform collision check starting from prepare phase when ego is in intersection. If `false`, collision check only evaluated for lane changing phase. | false | +| `enable_collision_check_for_prepare_phase.intersection` | [-] | boolean | Perform collision check starting from prepare phase when ego is in intersection. If `false`, collision check only evaluated for lane changing phase. | true | +| `enable_collision_check_for_prepare_phase.turns` | [-] | boolean | Perform collision check starting from prepare phase when ego is in lanelet with turn direction tags. If `false`, collision check only evaluated for lane changing phase. | true | | `prepare_phase_ignore_target_speed_thresh` | [m/s] | double | Ignore collision check in prepare phase of object speed that is lesser that the configured value. `enable_collision_check_at_prepare_phase` must be `true` | 0.1 | | `check_objects_on_current_lanes` | [-] | boolean | If true, the lane change module check objects on current lanes when performing collision assessment. | false | | `check_objects_on_other_lanes` | [-] | boolean | If true, the lane change module include objects on other lanes. when performing collision assessment | false | diff --git a/planning/behavior_path_lane_change_module/config/lane_change.param.yaml b/planning/behavior_path_lane_change_module/config/lane_change.param.yaml index 039e8a31ed10f..1ab33514c5f24 100644 --- a/planning/behavior_path_lane_change_module/config/lane_change.param.yaml +++ b/planning/behavior_path_lane_change_module/config/lane_change.param.yaml @@ -92,6 +92,7 @@ enable_collision_check_for_prepare_phase: general_lanes: false intersection: true + turns: true prepare_segment_ignore_object_velocity_thresh: 0.1 # [m/s] check_objects_on_current_lanes: true check_objects_on_other_lanes: true diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/data_structs.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/data_structs.hpp index 0d77135fda242..fdaa15ff9bef9 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/data_structs.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/data_structs.hpp @@ -114,6 +114,7 @@ struct LaneChangeParameters // collision check bool enable_collision_check_for_prepare_phase_in_general_lanes{false}; bool enable_collision_check_for_prepare_phase_in_intersection{true}; + bool enable_collision_check_for_prepare_phase_in_turns{true}; double prepare_segment_ignore_object_velocity_thresh{0.1}; bool check_objects_on_current_lanes{true}; bool check_objects_on_other_lanes{true}; diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp index 7c8cfdb926a6b..76331bd98eb9c 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp @@ -258,6 +258,21 @@ bool isWithinIntersection( const std::shared_ptr & route_handler, const lanelet::ConstLanelet & lanelet, const Polygon2d & polygon); +/** + * @brief Determines if a polygon is within lanes designated for turning. + * + * Checks if a polygon overlaps with lanelets tagged for turning directions (excluding 'straight'). + * It evaluates the lanelet's 'turn_direction' attribute and determines overlap with the lanelet's + * area. + * + * @param lanelet Lanelet representing the road segment whose turn direction is to be evaluated. + * @param polygon The polygon to be checked for its presence within turn direction lanes. + * + * @return bool True if the polygon is within a lane designated for turning, false if it is within a + * straight lane or no turn direction is specified. + */ +bool isWithinTurnDirectionLanes(const lanelet::ConstLanelet & lanelet, const Polygon2d & polygon); + /** * @brief Calculates the distance required during a lane change operation. * diff --git a/planning/behavior_path_lane_change_module/src/manager.cpp b/planning/behavior_path_lane_change_module/src/manager.cpp index 7045544df50aa..81d4b86afa094 100644 --- a/planning/behavior_path_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_lane_change_module/src/manager.cpp @@ -72,6 +72,8 @@ void LaneChangeModuleManager::initParams(rclcpp::Node * node) *node, parameter("enable_collision_check_for_prepare_phase.general_lanes")); p.enable_collision_check_for_prepare_phase_in_intersection = getOrDeclareParameter( *node, parameter("enable_collision_check_for_prepare_phase.intersection")); + p.enable_collision_check_for_prepare_phase_in_turns = + getOrDeclareParameter(*node, parameter("enable_collision_check_for_prepare_phase.turns")); p.prepare_segment_ignore_object_velocity_thresh = getOrDeclareParameter( *node, parameter("prepare_segment_ignore_object_velocity_thresh")); p.check_objects_on_current_lanes = diff --git a/planning/behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_lane_change_module/src/scene.cpp index bc9a366e62b34..3a4a44ef33edb 100644 --- a/planning/behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_lane_change_module/src/scene.cpp @@ -2142,7 +2142,15 @@ bool NormalLaneChange::check_prepare_phase() const return utils::lane_change::isWithinIntersection(route_handler, current_lane, ego_footprint); }); - return check_in_intersection || check_in_general_lanes; + const auto check_in_turns = std::invoke([&]() { + if (!lane_change_parameters_->enable_collision_check_for_prepare_phase_in_turns) { + return false; + } + + return utils::lane_change::isWithinTurnDirectionLanes(current_lane, ego_footprint); + }); + + return check_in_intersection || check_in_turns || check_in_general_lanes; } } // namespace behavior_path_planner diff --git a/planning/behavior_path_lane_change_module/src/utils/utils.cpp b/planning/behavior_path_lane_change_module/src/utils/utils.cpp index 15db6b0055756..97fcc841a546e 100644 --- a/planning/behavior_path_lane_change_module/src/utils/utils.cpp +++ b/planning/behavior_path_lane_change_module/src/utils/utils.cpp @@ -37,6 +37,8 @@ #include +#include + #include #include #include @@ -1185,6 +1187,17 @@ bool isWithinIntersection( polygon, utils::toPolygon2d(lanelet::utils::to2D(lanelet_polygon.basicPolygon()))); } +bool isWithinTurnDirectionLanes(const lanelet::ConstLanelet & lanelet, const Polygon2d & polygon) +{ + const std::string turn_direction = lanelet.attributeOr("turn_direction", "else"); + if (turn_direction == "else" || turn_direction == "straight") { + return false; + } + + return !boost::geometry::disjoint( + polygon, utils::toPolygon2d(lanelet::utils::to2D(lanelet.polygon2d().basicPolygon()))); +} + double calcPhaseLength( const double velocity, const double maximum_velocity, const double acceleration, const double duration) From 392a83c1c9d72369c656a56b4a5e074e64340fcb Mon Sep 17 00:00:00 2001 From: anhnv3991 Date: Fri, 5 Apr 2024 08:46:51 +0700 Subject: [PATCH 28/29] Keep timeout only Signed-off-by: anhnv3991 --- .../ndt_scan_matcher/map_update_module.hpp | 7 -- .../src/map_update_module.cpp | 74 +------------------ .../differential_map_loader_module.cpp | 18 ----- 3 files changed, 3 insertions(+), 96 deletions(-) diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp index 4e80042709ec6..2eb14b6004282 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp @@ -60,13 +60,6 @@ class MapUpdateModule [[nodiscard]] bool should_update_map(const geometry_msgs::msg::Point & position); void publish_partial_pcd_map(); - // Looking for PCDs in the vicinity of the specified location - void query_pcds( - double px, double py, double radius, std::unordered_set & maps_to_add, - std::unordered_set & maps_to_remove); - // Compute distance between an origin and a pcd segment - double dist(double px, double py, int idx, int idy); - rclcpp::Publisher::SharedPtr loaded_pcd_pub_; rclcpp::Client::SharedPtr diff --git a/localization/ndt_scan_matcher/src/map_update_module.cpp b/localization/ndt_scan_matcher/src/map_update_module.cpp index 9fbf9e412b229..8034c1f8be18a 100644 --- a/localization/ndt_scan_matcher/src/map_update_module.cpp +++ b/localization/ndt_scan_matcher/src/map_update_module.cpp @@ -146,13 +146,8 @@ bool MapUpdateModule::update_ndt(const geometry_msgs::msg::Point & position, Ndt request, [](rclcpp::Client::SharedFuture) {})}; - // While waiting for the requested pcds, look for indices of the candidate pcds - std::unordered_set pcds_to_remove, pcds_to_add; - - query_pcds(position.x, position.y, param_.map_radius, pcds_to_add, pcds_to_remove); - - // Wait for maximum 20 milliseconds - std::chrono::milliseconds timeout(20); + // Wait for maximum 10 milliseconds + std::chrono::milliseconds timeout(10); auto start = std::chrono::system_clock::now(); std::future_status status = result.wait_for(std::chrono::seconds(0)); @@ -177,20 +172,7 @@ bool MapUpdateModule::update_ndt(const geometry_msgs::msg::Point & position, Ndt auto & maps_to_add = result.get()->new_pointcloud_with_ids; auto & map_ids_to_remove = result.get()->ids_to_remove; - // Check if there are any maps in the pcds_to_add not coming - for (auto & name : pcds_to_add) { - if (maps_to_add.find(name) == maps_to_add.end()) { - RCLCPP_ERROR_STREAM_THROTTLE(logger_, *clock_, 1000, "File %s not coming.", name.c_str()); - } - } - - for (auto & name : pcds_to_remove) { - if (map_ids_to_remove.find(name) == map_ids_to_remove.end()) { - RCLCPP_ERROR_STREAM_THROTTLE( - logger_, *clock_, 1000, "File %s should be removed but it was not.", name.c_str()); - } - } - + // Check RCLCPP_INFO( logger_, "Update map (Add: %lu, Remove: %lu)", maps_to_add.size(), map_ids_to_remove.size()); if (maps_to_add.empty() && map_ids_to_remove.empty()) { @@ -233,53 +215,3 @@ void MapUpdateModule::publish_partial_pcd_map() loaded_pcd_pub_->publish(map_msg); } - -void MapUpdateModuble::query_pcds( - double px, double py, double radius, std::unordered_set & maps_to_add, - std::unordered_set & maps_to_remove) -{ - int lower_x = static_cast(floor((px - radius) / pcd_res_x_)); - int lower_y = static_cast(floor((py - radius) / pcd_res_y_)); - int upper_x = static_cast(floor((px + radius) / pcd_res_x_)); - int upper_y = static_cast(floor((py + radius) / pcd_res_y_)); - double rel_px = px - pcd_lower_x_, rel_py = py - pcd_lower_y_; - std::unordered_set nn_pcds; - - for (int idx = lower_x; idx < upper_x; ++idx) { - for (int idy = lower_y; idy < upper_y; ++idy) { - // Skip if the pcd file is not within the query radius - if (dist(rel_px, rel_py, idx, idy) > radius) { - continue; - } - - // Generate name of the PCD file - std::string name = pcd_tag_ + "_" + std::to_string(x) + "_" + std::to_string(y) + ".pcd"; - - if (cur_pcds_.find(name) == cur_pcds_.end()) { - maps_to_add.insert(name); - } else { - nn_pcds.insert(name); - } - } - } - - // Compare with @cur_pcds_ to find out which pcds to remove - for (auto & name : cur_pcds_) { - if (nn_pcds.find(name) == nn_pcds.end()) { - map_ids_to_remove.insert(name); - } - } -} - -double MapUpdateModule::dist(double px, double py, int idx, int idy) -{ - double lx = idx * pcd_res_x_; - double ly = idy * pcd_res_y_; - double ux = lx + pcd_res_x_; - double uy = ly + pcd_res_y_; - - double dx = (px < lx) ? lx - px : ((px >= ux) ? px - ux : 0); - double dy = (py < ly) ? ly - py : ((py >= uy) ? py - uy : 0); - - return std::hypot(dx, dy); -} diff --git a/map/map_loader/src/pointcloud_map_loader/differential_map_loader_module.cpp b/map/map_loader/src/pointcloud_map_loader/differential_map_loader_module.cpp index 3b270b0084ccf..a8d380fd81b86 100644 --- a/map/map_loader/src/pointcloud_map_loader/differential_map_loader_module.cpp +++ b/map/map_loader/src/pointcloud_map_loader/differential_map_loader_module.cpp @@ -29,12 +29,6 @@ void DifferentialMapLoaderModule::differentialAreaLoad( const autoware_map_msgs::msg::AreaInfo & area, const std::vector & cached_ids, GetDifferentialPointCloudMap::Response::SharedPtr & response) const { - // For debug - std::ofstream test("/home/anh/Work/autoware/test.txt", std::ios::app); - - test << __FILE__ << "::" << __LINE__ << "::" << __func__ << std::endl; - // End - // iterate over all the available pcd map grids std::vector should_remove(static_cast(cached_ids.size()), true); for (const auto & ele : all_pcd_file_metadata_dict_) { @@ -73,12 +67,6 @@ bool DifferentialMapLoaderModule::onServiceGetDifferentialPointCloudMap( GetDifferentialPointCloudMap::Request::SharedPtr req, GetDifferentialPointCloudMap::Response::SharedPtr res) { - // For debug - std::ofstream test("/home/anh/Work/autoware/test.txt", std::ios::app); - - test << __FILE__ << "::" << __LINE__ << "::" << __func__ << std::endl; - // End - auto area = req->area; std::vector cached_ids = req->cached_ids; differentialAreaLoad(area, cached_ids, res); @@ -90,12 +78,6 @@ autoware_map_msgs::msg::PointCloudMapCellWithID DifferentialMapLoaderModule::loadPointCloudMapCellWithID( const std::string & path, const std::string & map_id) const { - // For debug - std::ofstream test("/home/anh/Work/autoware/test.txt", std::ios::app); - - test << __FILE__ << "::" << __LINE__ << "::" << __func__ << std::endl; - // End - sensor_msgs::msg::PointCloud2 pcd; if (pcl::io::loadPCDFile(path, pcd) == -1) { RCLCPP_ERROR_STREAM(logger_, "PCD load failed: " << path); From 1a852f2353cdda87a6df32650a4f15d245e7ccbf Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Fri, 5 Apr 2024 01:54:19 +0000 Subject: [PATCH 29/29] style(pre-commit): autofix --- localization/ndt_scan_matcher/src/map_update_module.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/localization/ndt_scan_matcher/src/map_update_module.cpp b/localization/ndt_scan_matcher/src/map_update_module.cpp index 8034c1f8be18a..47aab3e62e79b 100644 --- a/localization/ndt_scan_matcher/src/map_update_module.cpp +++ b/localization/ndt_scan_matcher/src/map_update_module.cpp @@ -172,7 +172,7 @@ bool MapUpdateModule::update_ndt(const geometry_msgs::msg::Point & position, Ndt auto & maps_to_add = result.get()->new_pointcloud_with_ids; auto & map_ids_to_remove = result.get()->ids_to_remove; - // Check + // Check RCLCPP_INFO( logger_, "Update map (Add: %lu, Remove: %lu)", maps_to_add.size(), map_ids_to_remove.size()); if (maps_to_add.empty() && map_ids_to_remove.empty()) {