From 315681c25b72423781ce5bc49a01772c474d0385 Mon Sep 17 00:00:00 2001 From: sophtsang Date: Thu, 16 Oct 2025 22:47:16 +0000 Subject: [PATCH 01/28] added cev_msgs include --- .vscode/c_cpp_properties.json | 24 ++++++++++++++++++++++++ CMakeLists.txt | 4 +++- package.xml | 1 + 3 files changed, 28 insertions(+), 1 deletion(-) create mode 100644 .vscode/c_cpp_properties.json diff --git a/.vscode/c_cpp_properties.json b/.vscode/c_cpp_properties.json new file mode 100644 index 0000000..ccf510a --- /dev/null +++ b/.vscode/c_cpp_properties.json @@ -0,0 +1,24 @@ +{ + "configurations": [ + { + "browse": { + "databaseFilename": "${default}", + "limitSymbolsToIncludedHeaders": false + }, + "includePath": [ + "/opt/ros/humble/include/**", + "/root/ws/src/ackermann_kf/go2_driver/include/**", + "/usr/include/**", + "${workspaceFolder}/**", + "/usr/include/opencv4", + "/root/ws/src/cev_msgs/**" + ], + "name": "ROS", + "intelliSenseMode": "gcc-x64", + "compilerPath": "/usr/bin/gcc", + "cStandard": "gnu11", + "cppStandard": "c++14" + } + ], + "version": 4 +} \ No newline at end of file diff --git a/CMakeLists.txt b/CMakeLists.txt index 03f571e..4b16117 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -11,6 +11,7 @@ find_package(rclcpp REQUIRED) find_package(sensor_msgs REQUIRED) find_package(std_msgs REQUIRED) find_package(geometry_msgs REQUIRED) +find_package(cev_msgs REQUIRED) find_package(rosidl_default_generators REQUIRED) find_package(OpenCV REQUIRED) find_package(tf2 REQUIRED) @@ -21,7 +22,7 @@ find_package(visualization_msgs REQUIRED) rosidl_generate_interfaces(${PROJECT_NAME} "msg/Obstacle.msg" "msg/ObstacleArray.msg" - DEPENDENCIES std_msgs geometry_msgs + DEPENDENCIES std_msgs geometry_msgs cev_msgs ) add_executable(obstacle_node src/obstacle_node.cpp) @@ -29,6 +30,7 @@ add_executable(obstacle_node src/obstacle_node.cpp) ament_target_dependencies( obstacle_node rclcpp + cev_msgs sensor_msgs std_msgs geometry_msgs diff --git a/package.xml b/package.xml index b4a48b6..413d47c 100644 --- a/package.xml +++ b/package.xml @@ -13,6 +13,7 @@ sensor_msgs std_msgs geometry_msgs + cev_msgs rosidl_default_generators rosidl_default_runtime From ba9cba0cd3d42001c45288822726ead1135f916a Mon Sep 17 00:00:00 2001 From: sophtsang Date: Fri, 17 Oct 2025 05:22:45 +0000 Subject: [PATCH 02/28] BEV and OBB conversions now work with live cluster outputs from /rslidar_obstacle msg --- src/obstacle_node.cpp | 21 +++++++++++++++++---- 1 file changed, 17 insertions(+), 4 deletions(-) diff --git a/src/obstacle_node.cpp b/src/obstacle_node.cpp index 44bcdeb..fa2cf23 100644 --- a/src/obstacle_node.cpp +++ b/src/obstacle_node.cpp @@ -2,6 +2,7 @@ #include #include #include +#include "cev_msgs/msg/obstacles.hpp" #include "obstacle/msg/obstacle_array.hpp" #include @@ -27,6 +28,10 @@ class ObstacleNode : public rclcpp::Node { ObstacleNode() : Node("obstacle_node") { + obs_sub_ = this->create_subscription( + "/rslidar_obstacles", 10, + std::bind(&ObstacleNode::obstaclesCallback, this, std::placeholders::_1)); + pc_sub_ = this->create_subscription( "input_points", 10, std::bind(&ObstacleNode::pcCallback, this, std::placeholders::_1)); @@ -38,6 +43,17 @@ class ObstacleNode : public rclcpp::Node { } private: + void obstaclesCallback(const cev_msgs::msg::Obstacles::SharedPtr msg) + { + RCLCPP_INFO(this->get_logger(), "Received Obstacles message with %zu clouds", msg->obstacles.size()); + for (size_t i = 0; i < msg->obstacles.size(); ++i) + { + const auto &cloud = msg->obstacles[i]; + auto cloud_ptr = std::make_shared(cloud); + pcCallback(cloud_ptr); + } + } + void pcCallback(const sensor_msgs::msg::PointCloud2::SharedPtr msg) { // check required fields bool has_x=false, has_y=false, has_z=false, has_id=false; @@ -53,7 +69,6 @@ class ObstacleNode : public rclcpp::Node { return; } - sensor_msgs::PointCloud2ConstIterator iter_x(*msg, "x"); sensor_msgs::PointCloud2ConstIterator iter_y(*msg, "y"); sensor_msgs::PointCloud2ConstIterator iter_z(*msg, "z"); @@ -75,8 +90,6 @@ class ObstacleNode : public rclcpp::Node { "Received PointCloud2: points=%zu clusters=%zu", total_points, clusters.size()); - - // z-axis filtering const float z_min_allowed = 0.0f; const float z_max_allowed = 2.5f; @@ -215,9 +228,9 @@ class ObstacleNode : public rclcpp::Node { } marker_pub_->publish(markers); - } + rclcpp::Subscription::SharedPtr obs_sub_; rclcpp::Subscription::SharedPtr pc_sub_; rclcpp::Publisher::SharedPtr obs_pub_; rclcpp::Publisher::SharedPtr marker_pub_; From 9cd11ab5ceab07c4888fb98b6c41902d8c47fe3e Mon Sep 17 00:00:00 2001 From: sophtsang Date: Thu, 23 Oct 2025 19:33:00 +0000 Subject: [PATCH 03/28] Merged elements of PointCloud2 array into one PointCloud2 pc, while keeping cluster ids per point. Added #include pcl. --- CMakeLists.txt | 10 ++++++++ package.xml | 2 ++ src/obstacle_node.cpp | 56 ++++++++++++++++++++++++++++--------------- 3 files changed, 49 insertions(+), 19 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 4b16117..a2bc3cc 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -12,6 +12,9 @@ find_package(sensor_msgs REQUIRED) find_package(std_msgs REQUIRED) find_package(geometry_msgs REQUIRED) find_package(cev_msgs REQUIRED) +find_package(PCL REQUIRED) +find_package(pcl_conversions REQUIRED) +find_package(pcl_ros REQUIRED) find_package(rosidl_default_generators REQUIRED) find_package(OpenCV REQUIRED) find_package(tf2 REQUIRED) @@ -33,6 +36,8 @@ ament_target_dependencies( cev_msgs sensor_msgs std_msgs + pcl_conversions + pcl_ros geometry_msgs tf2 tf2_geometry_msgs @@ -40,8 +45,13 @@ ament_target_dependencies( ) +include_directories( + ${PCL_INCLUDE_DIRS} +) + target_link_libraries(obstacle_node ${OpenCV_LIBS} + ${PCL_LIBRARIES} ) ament_export_dependencies(rosidl_default_runtime) diff --git a/package.xml b/package.xml index 413d47c..02db6a4 100644 --- a/package.xml +++ b/package.xml @@ -14,6 +14,8 @@ std_msgs geometry_msgs cev_msgs + pcl_conversions + pcl_ros rosidl_default_generators rosidl_default_runtime diff --git a/src/obstacle_node.cpp b/src/obstacle_node.cpp index fa2cf23..5cdfea3 100644 --- a/src/obstacle_node.cpp +++ b/src/obstacle_node.cpp @@ -2,6 +2,10 @@ #include #include #include +#include +#include +#include +#include #include "cev_msgs/msg/obstacles.hpp" #include "obstacle/msg/obstacle_array.hpp" @@ -46,12 +50,18 @@ class ObstacleNode : public rclcpp::Node { void obstaclesCallback(const cev_msgs::msg::Obstacles::SharedPtr msg) { RCLCPP_INFO(this->get_logger(), "Received Obstacles message with %zu clouds", msg->obstacles.size()); - for (size_t i = 0; i < msg->obstacles.size(); ++i) + + sensor_msgs::msg::PointCloud2 merged_cloud = msg->obstacles[0]; + + for (size_t i = 1; i < msg->obstacles.size(); ++i) { const auto &cloud = msg->obstacles[i]; - auto cloud_ptr = std::make_shared(cloud); - pcCallback(cloud_ptr); + + pcl::concatenatePointCloud(merged_cloud, cloud, merged_cloud); } + + auto cloud_ptr = std::make_shared(merged_cloud); + pcCallback(cloud_ptr); } void pcCallback(const sensor_msgs::msg::PointCloud2::SharedPtr msg) { @@ -86,9 +96,9 @@ class ObstacleNode : public rclcpp::Node { ++total_points; } - RCLCPP_INFO(this->get_logger(), - "Received PointCloud2: points=%zu clusters=%zu", - total_points, clusters.size()); + // RCLCPP_INFO(this->get_logger(), + // "Received PointCloud2: points=%zu clusters=%zu", + // total_points, clusters.size()); // z-axis filtering const float z_min_allowed = 0.0f; @@ -114,18 +124,19 @@ class ObstacleNode : public rclcpp::Node { if (!kept.empty()) { filtered_clusters[cid] = kept; - RCLCPP_INFO(this->get_logger(), - "Cluster %d kept: %zu points (orig %zu, z_range=[%.2f, %.2f])", - cid, kept.size(), pts.size(), z_min, z_max); - } else { - RCLCPP_INFO(this->get_logger(), - "Cluster %d discarded (all points outside z range [%.2f, %.2f], orig z_range=[%.2f, %.2f])", - cid, z_min_allowed, z_max_allowed, z_min, z_max); - } + // RCLCPP_INFO(this->get_logger(), + // "Cluster %d kept: %zu points (orig %zu, z_range=[%.2f, %.2f])", + // cid, kept.size(), pts.size(), z_min, z_max); + } + // else { + // RCLCPP_INFO(this->get_logger(), + // "Cluster %d discarded (all points outside z range [%.2f, %.2f], orig z_range=[%.2f, %.2f])", + // cid, z_min_allowed, z_max_allowed, z_min, z_max); + // } } - RCLCPP_INFO(this->get_logger(), - "After filtering: %zu clusters remain", filtered_clusters.size()); + // RCLCPP_INFO(this->get_logger(), + // "After filtering: %zu clusters remain", filtered_clusters.size()); // === BEV projection + OBB === ObstacleArray out; @@ -188,9 +199,9 @@ class ObstacleNode : public rclcpp::Node { out.obstacles.push_back(ob); - RCLCPP_INFO(this->get_logger(), - "Cluster %d -> obstacle center=(%.2f,%.2f), L=%.2f W=%.2f yaw=%.2f rad", - cid, cx, cy, length, width, yaw); + // RCLCPP_INFO(this->get_logger(), + // "Cluster %d -> obstacle center=(%.2f,%.2f), L=%.2f W=%.2f yaw=%.2f rad", + // cid, cx, cy, length, width, yaw); } // === publish ObstacleArray === @@ -202,6 +213,7 @@ class ObstacleNode : public rclcpp::Node { for (const auto &ob : out.obstacles) { visualization_msgs::msg::Marker m; m.header = out.header; + m.header.frame_id = "rslidar"; m.ns = "obstacle"; m.id = id_counter++; m.type = visualization_msgs::msg::Marker::CUBE; @@ -226,6 +238,10 @@ class ObstacleNode : public rclcpp::Node { markers.markers.push_back(m); } + + RCLCPP_INFO(rclcpp::get_logger("MarkerPrinter"), + "Visualizing %d clouds", (int) markers.markers.size()); + marker_pub_->publish(markers); } @@ -236,6 +252,8 @@ class ObstacleNode : public rclcpp::Node { rclcpp::Publisher::SharedPtr marker_pub_; }; +#include "visualization_msgs/msg/marker_array.hpp" + int main(int argc, char ** argv) { rclcpp::init(argc, argv); auto node = std::make_shared(); From 4b1f96eda74767809ac0ffe0509729a1fe5ed925 Mon Sep 17 00:00:00 2001 From: sophtsang Date: Sat, 1 Nov 2025 18:54:11 +0000 Subject: [PATCH 04/28] intro to rasterization --- README.md | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/README.md b/README.md index 8e151a5..2ca716d 100644 --- a/README.md +++ b/README.md @@ -1 +1,13 @@ # Obstacle_node +Hi all, I'm going to start yapping again. + +## Rasterization +A raster is a digital image made up of a rectangular grid of pixels. We can say that an occupancy grid is essentially a raster, where obstacles will be represented as filled in pixels. + +Given a 3D point cloud, we will its 2D counterpart by projection to birds-eye view (BEV), and then rasterize this 2D point cloud to get its representation on an occupancy grid. + + + + +# Important Links +[Rasterize a point cloud](https://r-lidar.github.io/lasR/reference/rasterize.html) \ No newline at end of file From 0ee140468edfba2075bf428bee020a7a95052c6b Mon Sep 17 00:00:00 2001 From: sophtsang Date: Wed, 5 Nov 2025 18:10:34 +0000 Subject: [PATCH 05/28] new script for occupancy grid conversions --- src/obstacle_node.cpp | 2 +- src/occupany_grid.cpp | 166 ++++++++++++++++++++++++++++++++++++++++++ 2 files changed, 167 insertions(+), 1 deletion(-) create mode 100644 src/occupany_grid.cpp diff --git a/src/obstacle_node.cpp b/src/obstacle_node.cpp index 5cdfea3..83261a4 100644 --- a/src/obstacle_node.cpp +++ b/src/obstacle_node.cpp @@ -230,7 +230,7 @@ class ObstacleNode : public rclcpp::Node { // z at the middle of the box m.pose.position.z = (ob.z_min + ob.z_max) / 2.0; - // color(all red now) + // color(convert cluster id to different color) m.color.r = 1.0; m.color.g = 0.0; m.color.b = 0.0; diff --git a/src/occupany_grid.cpp b/src/occupany_grid.cpp new file mode 100644 index 0000000..9e4d056 --- /dev/null +++ b/src/occupany_grid.cpp @@ -0,0 +1,166 @@ +// src/occupancy_grid.cpp +#include +#include +#include +#include +#include +#include +#include +#include "cev_msgs/msg/obstacles.hpp" +#include "obstacle/msg/obstacle_array.hpp" + +#include +#include +#include +#include +#include +#include +#include + +using obstacle::msg::ObstacleArray; + +struct PointXYZCluster { + float x; + float y; + float z; + int32_t cluster_id; +}; + +class OccupancyGrid : public rclcpp::Node { +public: + OccupancyGrid() + : Node("occupancy_grid") + { + obs_sub_ = this->create_subscription( + "/rslidar_obstacles", 10, + std::bind(&OccupancyGrid::obstaclesCallback, this, std::placeholders::_1)); + + pc_sub_ = this->create_subscription( + "input_points", 10, + std::bind(&OccupancyGrid::pcCallback, this, std::placeholders::_1)); + + bev_pub_ = this->create_publisher("bev_obstacles", 10); + + RCLCPP_INFO(this->get_logger(), "OccupancyGrid started - waiting for PointCloud2 on 'input_points'"); + } + +private: + void obstaclesCallback(const cev_msgs::msg::Obstacles::SharedPtr msg) + { + RCLCPP_INFO(this->get_logger(), "Received Obstacles message with %zu clouds", msg->obstacles.size()); + + sensor_msgs::msg::PointCloud2 merged_cloud = msg->obstacles[0]; + + for (size_t i = 1; i < msg->obstacles.size(); ++i) + { + const auto &cloud = msg->obstacles[i]; + + pcl::concatenatePointCloud(merged_cloud, cloud, merged_cloud); + } + + auto cloud_ptr = std::make_shared(merged_cloud); + pcCallback(cloud_ptr); + } + + void pcCallback(const sensor_msgs::msg::PointCloud2::SharedPtr msg) { + // check required fields + bool has_x=false, has_y=false, has_z=false, has_id=false; + for (const auto &f : msg->fields) { + if (f.name == "x") has_x = true; + if (f.name == "y") has_y = true; + if (f.name == "z") has_z = true; + if (f.name == "id" || f.name == "cluster_id") has_id = true; + } + if (!(has_x && has_y && has_z && has_id)) { + RCLCPP_ERROR(this->get_logger(), + "PointCloud2 missing required fields (need x,y,z and id/cluster_id). Skipping this message."); + return; + } + + sensor_msgs::PointCloud2ConstIterator iter_x(*msg, "x"); + sensor_msgs::PointCloud2ConstIterator iter_y(*msg, "y"); + sensor_msgs::PointCloud2ConstIterator iter_z(*msg, "z"); + sensor_msgs::PointCloud2ConstIterator iter_id(*msg, "id"); + + std::unordered_map> clusters; + size_t total_points = 0; + for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z, ++iter_id) { + PointXYZCluster p; + p.x = *iter_x; + p.y = *iter_y; + p.z = *iter_z; + p.cluster_id = *iter_id; + clusters[p.cluster_id].push_back(p); + ++total_points; + } + + // z-axis filtering + const float z_min_allowed = 0.0f; + const float z_max_allowed = 2.5f; + + std::unordered_map> filtered_clusters; + + for (const auto &kv : clusters) { + int cid = kv.first; + const auto &pts = kv.second; + + std::vector kept; + float z_min = std::numeric_limits::max(); + float z_max = std::numeric_limits::lowest(); + + for (const auto &p : pts) { + z_min = std::min(z_min, p.z); + z_max = std::max(z_max, p.z); + if (p.z >= z_min_allowed && p.z <= z_max_allowed) { + kept.push_back(p); + } + } + + if (!kept.empty()) { + filtered_clusters[cid] = kept; + } + + } + + // === BEV projection + OBB === + ObstacleArray out; + out.header = msg->header; + + for (const auto &kv : filtered_clusters) { + int cid = kv.first; + const auto &pts = kv.second; + + if (pts.size() < 3) { + RCLCPP_WARN(this->get_logger(), + "Cluster %d has only %zu points, skipping OBB", + cid, pts.size()); + continue; + } + + std::vector cv_points; + cv_points.reserve(pts.size()); + float z_min = std::numeric_limits::max(); + float z_max = std::numeric_limits::lowest(); + for (const auto &p : pts) { + cv_points.emplace_back(p.x, p.y); + z_min = std::min(z_min, p.z); + z_max = std::max(z_max, p.z); + } + } + + // === publish ObstacleArray === + obs_pub_->publish(out); + } + + rclcpp::Subscription::SharedPtr obs_sub_; + rclcpp::Subscription::SharedPtr pc_sub_; + rclcpp::Publisher::SharedPtr bev_pub_; +}; + +int main(int argc, char ** argv) { + rclcpp::init(argc, argv); + auto node = std::make_shared(); + rclcpp::spin(node); + rclcpp::shutdown(); + return 0; +} From 5045a94f9c5776fe758aca1582059b4ca0e0fd7a Mon Sep 17 00:00:00 2001 From: sophtsang Date: Wed, 5 Nov 2025 18:14:26 +0000 Subject: [PATCH 06/28] added required stuff for occupancy_grid in CmakeLists.txt --- CMakeLists.txt | 24 +++++++++++++++++++++++- 1 file changed, 23 insertions(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index a2bc3cc..8c71775 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -29,6 +29,7 @@ rosidl_generate_interfaces(${PROJECT_NAME} ) add_executable(obstacle_node src/obstacle_node.cpp) +add_executable(occupancy_grid src/occupancy_grid.cpp) ament_target_dependencies( obstacle_node @@ -44,6 +45,19 @@ ament_target_dependencies( visualization_msgs ) +ament_target_dependencies( + occupancy_grid + rclcpp + cev_msgs + sensor_msgs + std_msgs + pcl_conversions + pcl_ros + geometry_msgs + tf2 + tf2_geometry_msgs + visualization_msgs +) include_directories( ${PCL_INCLUDE_DIRS} @@ -54,14 +68,22 @@ target_link_libraries(obstacle_node ${PCL_LIBRARIES} ) -ament_export_dependencies(rosidl_default_runtime) +target_link_libraries(occupancy_grid + ${OpenCV_LIBS} + ${PCL_LIBRARIES} +) +ament_export_dependencies(rosidl_default_runtime) rosidl_target_interfaces(obstacle_node ${PROJECT_NAME} "rosidl_typesupport_cpp") + rosidl_target_interfaces(occupancy_grid + ${PROJECT_NAME} "rosidl_typesupport_cpp") + install(TARGETS obstacle_node + occupancy_grid DESTINATION lib/${PROJECT_NAME}) From 4288ea5bb6495fb9fe925b671e54c624aa2db945 Mon Sep 17 00:00:00 2001 From: sophtsang Date: Wed, 5 Nov 2025 15:33:39 -0500 Subject: [PATCH 07/28] test --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 2ca716d..4099048 100644 --- a/README.md +++ b/README.md @@ -1,5 +1,5 @@ # Obstacle_node -Hi all, I'm going to start yapping again. +Hi all, I'm going to start yapping again! ## Rasterization A raster is a digital image made up of a rectangular grid of pixels. We can say that an occupancy grid is essentially a raster, where obstacles will be represented as filled in pixels. From 97c266394fc557792cc450814c4fd222100015e0 Mon Sep 17 00:00:00 2001 From: sophtsang Date: Thu, 6 Nov 2025 00:12:17 +0000 Subject: [PATCH 08/28] pub bev points to bev_points --- src/occupancy_grid.cpp | 211 +++++++++++++++++++++++++++++++++++++++++ 1 file changed, 211 insertions(+) create mode 100644 src/occupancy_grid.cpp diff --git a/src/occupancy_grid.cpp b/src/occupancy_grid.cpp new file mode 100644 index 0000000..e0eb3b7 --- /dev/null +++ b/src/occupancy_grid.cpp @@ -0,0 +1,211 @@ +// src/occupancy_grid.cpp +#include +#include +#include +#include +#include +#include +#include +#include "cev_msgs/msg/obstacles.hpp" +#include "obstacle/msg/obstacle_array.hpp" + +#include +#include +#include +#include +#include +#include +#include + +using obstacle::msg::ObstacleArray; + +struct PointXYZCluster { + float x; + float y; + float z; + int32_t cluster_id; +}; + +class OccupancyGrid : public rclcpp::Node { +public: + OccupancyGrid() + : Node("occupancy_grid") + { + obs_sub_ = this->create_subscription( + "/rslidar_obstacles", 10, + std::bind(&OccupancyGrid::obstaclesCallback, this, std::placeholders::_1)); + + pc_sub_ = this->create_subscription( + "input_points", 10, + std::bind(&OccupancyGrid::pcCallback, this, std::placeholders::_1)); + + bev_pub_ = this->create_publisher("/bev_obstacles", 10); + + RCLCPP_INFO(this->get_logger(), "OccupancyGrid started - waiting for PointCloud2 on 'input_points'"); + } + +private: + void obstaclesCallback(const cev_msgs::msg::Obstacles::SharedPtr msg) + { + // RCLCPP_INFO(this->get_logger(), "Received Obstacles message with %zu clouds", msg->obstacles.size()); + + sensor_msgs::msg::PointCloud2 merged_cloud = msg->obstacles[0]; + + for (size_t i = 1; i < msg->obstacles.size(); ++i) + { + const auto &cloud = msg->obstacles[i]; + + pcl::concatenatePointCloud(merged_cloud, cloud, merged_cloud); + } + + auto cloud_ptr = std::make_shared(merged_cloud); + pcCallback(cloud_ptr); + } + + void pcCallback(const sensor_msgs::msg::PointCloud2::SharedPtr msg) { + // check required fields + bool has_x=false, has_y=false, has_z=false, has_id=false; + for (const auto &f : msg->fields) { + if (f.name == "x") has_x = true; + if (f.name == "y") has_y = true; + if (f.name == "z") has_z = true; + if (f.name == "id" || f.name == "cluster_id") has_id = true; + } + if (!(has_x && has_y && has_z && has_id)) { + RCLCPP_ERROR(this->get_logger(), + "PointCloud2 missing required fields (need x,y,z and id/cluster_id). Skipping this message."); + return; + } + + sensor_msgs::PointCloud2ConstIterator iter_x(*msg, "x"); + sensor_msgs::PointCloud2ConstIterator iter_y(*msg, "y"); + sensor_msgs::PointCloud2ConstIterator iter_z(*msg, "z"); + sensor_msgs::PointCloud2ConstIterator iter_id(*msg, "id"); + + std::unordered_map> clusters; + size_t total_points = 0; + for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z, ++iter_id) { + PointXYZCluster p; + p.x = *iter_x; + p.y = *iter_y; + p.z = *iter_z; + p.cluster_id = *iter_id; + clusters[p.cluster_id].push_back(p); + ++total_points; + } + + // z-axis filtering + const float z_min_allowed = 0.0f; + const float z_max_allowed = 2.5f; + + std::unordered_map> filtered_clusters; + size_t total_kept_points = 0; + + for (const auto &kv : clusters) { + int cid = kv.first; + const auto &pts = kv.second; + + std::vector kept; + float z_min = std::numeric_limits::max(); + float z_max = std::numeric_limits::lowest(); + + for (const auto &p : pts) { + z_min = std::min(z_min, p.z); + z_max = std::max(z_max, p.z); + if (p.z >= z_min_allowed && p.z <= z_max_allowed) { + kept.push_back(p); + } + } + + if (!kept.empty()) { + filtered_clusters[cid] = kept; + total_kept_points += filtered_clusters[cid].size(); + } + } + + // === BEV projection + OBB === + ObstacleArray out; + out.header = msg->header; + + sensor_msgs::msg::PointCloud2 bev_points; + bev_points.header = out.header; + bev_points.header.frame_id = "rslidar"; + bev_points.height = 1; + + sensor_msgs::PointCloud2Modifier modifier(bev_points); + modifier.setPointCloud2FieldsByString(2, "xyz", "rgb"); + modifier.resize(total_kept_points); + + sensor_msgs::PointCloud2Iterator out_x(bev_points, "x"); + sensor_msgs::PointCloud2Iterator out_y(bev_points, "y"); + sensor_msgs::PointCloud2Iterator out_z(bev_points, "z"); + sensor_msgs::PointCloud2Iterator out_r(bev_points, "r"); + sensor_msgs::PointCloud2Iterator out_g(bev_points, "g"); + sensor_msgs::PointCloud2Iterator out_b(bev_points, "b"); + + for (const auto &kv : filtered_clusters) { + int cid = kv.first; + const auto &pts = kv.second; + uint8_t r = static_cast((kv.first * 53) % 255); + uint8_t g = static_cast((kv.first * 97) % 255); + uint8_t b = static_cast((kv.first * 193) % 255); + + if (pts.size() < 3) { + RCLCPP_WARN(this->get_logger(), + "Cluster %d has only %zu points, skipping OBB", + cid, pts.size()); + continue; + } + + std::vector cv_points; + cv_points.reserve(pts.size()); + float z_min = std::numeric_limits::max(); + float z_max = std::numeric_limits::lowest(); + for (const auto &p : pts) { + cv_points.emplace_back(p.x, p.y); + z_min = std::min(z_min, p.z); + z_max = std::max(z_max, p.z); + std_msgs::msg::ColorRGBA color = getColorFromId(cid); + + *out_x = p.x; + *out_y = p.y; + *out_z = 0.0f; + *out_r = color.r * 255; + *out_g = color.g * 255; + *out_b = color.b * 255; + ++out_x; ++out_y; ++out_z; + ++out_r; ++out_g; ++out_b; + } + } + + bev_points.width = static_cast(bev_points.data.size() / bev_points.point_step); + bev_points.row_step = bev_points.point_step * bev_points.width; + + RCLCPP_INFO(this->get_logger(), "Publishing /bev_points of %zu points", bev_points.data.size()); + bev_pub_->publish(bev_points); + } + + std_msgs::msg::ColorRGBA getColorFromId(int cluster_id) + { + std_msgs::msg::ColorRGBA color; + uint32_t hash = static_cast(cluster_id * 2654435761 % 4294967296); // Knuth's multiplicative hash + color.r = ((hash & 0xFF0000) >> 16) / 255.0f; + color.g = ((hash & 0x00FF00) >> 8) / 255.0f; + color.b = (hash & 0x0000FF) / 255.0f; + color.a = 0.5f; + + return color; + } + + rclcpp::Subscription::SharedPtr obs_sub_; + rclcpp::Subscription::SharedPtr pc_sub_; + rclcpp::Publisher::SharedPtr bev_pub_; +}; + +int main(int argc, char ** argv) { + rclcpp::init(argc, argv); + auto node = std::make_shared(); + rclcpp::spin(node); + rclcpp::shutdown(); + return 0; +} From d4862c371c6420ffa72d7382034fc2e39f683211 Mon Sep 17 00:00:00 2001 From: sophtsang Date: Thu, 6 Nov 2025 21:29:31 +0000 Subject: [PATCH 09/28] please work --- CMakeLists.txt | 2 + package.xml | 1 + src/occupancy_grid.cpp | 305 +++++++++++++++++++++++++++++++++++++---- 3 files changed, 284 insertions(+), 24 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 8c71775..6b24500 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -17,6 +17,7 @@ find_package(pcl_conversions REQUIRED) find_package(pcl_ros REQUIRED) find_package(rosidl_default_generators REQUIRED) find_package(OpenCV REQUIRED) +find_package(slam_toolbox REQUIRED) find_package(tf2 REQUIRED) find_package(tf2_geometry_msgs REQUIRED) find_package(visualization_msgs REQUIRED) @@ -54,6 +55,7 @@ ament_target_dependencies( pcl_conversions pcl_ros geometry_msgs + slam_toolbox tf2 tf2_geometry_msgs visualization_msgs diff --git a/package.xml b/package.xml index 02db6a4..d289af3 100644 --- a/package.xml +++ b/package.xml @@ -14,6 +14,7 @@ std_msgs geometry_msgs cev_msgs + slam_toolbox pcl_conversions pcl_ros diff --git a/src/occupancy_grid.cpp b/src/occupancy_grid.cpp index e0eb3b7..faa02a3 100644 --- a/src/occupancy_grid.cpp +++ b/src/occupancy_grid.cpp @@ -6,8 +6,9 @@ #include #include #include -#include "cev_msgs/msg/obstacles.hpp" -#include "obstacle/msg/obstacle_array.hpp" +#include +#include +#include #include #include @@ -19,6 +20,10 @@ using obstacle::msg::ObstacleArray; +constexpr double deg2rad(double deg) { + return deg * M_PI / 180.0; +}; + struct PointXYZCluster { float x; float y; @@ -26,22 +31,41 @@ struct PointXYZCluster { int32_t cluster_id; }; -class OccupancyGrid : public rclcpp::Node { + struct BinInfo { + BinInfo() = default; + BinInfo(const double _range, const double _wx, const double _wy) + : range(_range), wx(_wx), wy(_wy) + { + } + double range; + double wx; + double wy; +}; + +enum class CellState { + OCCUPIED, + UNKNOWN, + FREE +}; + +class OccupancyGridNode : public rclcpp::Node { public: - OccupancyGrid() + OccupancyGridNode() : Node("occupancy_grid") { obs_sub_ = this->create_subscription( "/rslidar_obstacles", 10, - std::bind(&OccupancyGrid::obstaclesCallback, this, std::placeholders::_1)); + std::bind(&OccupancyGridNode::obstaclesCallback, this, std::placeholders::_1)); pc_sub_ = this->create_subscription( "input_points", 10, - std::bind(&OccupancyGrid::pcCallback, this, std::placeholders::_1)); + std::bind(&OccupancyGridNode::pcCallback, this, std::placeholders::_1)); bev_pub_ = this->create_publisher("/bev_obstacles", 10); - RCLCPP_INFO(this->get_logger(), "OccupancyGrid started - waiting for PointCloud2 on 'input_points'"); + grid_pub_ = this->create_publisher("/occupancy_grid", 10); + + RCLCPP_INFO(this->get_logger(), "OccupancyGridNode started - waiting for PointCloud2 on 'input_points'"); } private: @@ -59,6 +83,7 @@ class OccupancyGrid : public rclcpp::Node { } auto cloud_ptr = std::make_shared(merged_cloud); + pcCallback(cloud_ptr); } @@ -82,6 +107,11 @@ class OccupancyGrid : public rclcpp::Node { sensor_msgs::PointCloud2ConstIterator iter_z(*msg, "z"); sensor_msgs::PointCloud2ConstIterator iter_id(*msg, "id"); + float min_x = std::numeric_limits::max(); + float min_y = std::numeric_limits::max(); + float max_x = std::numeric_limits::lowest(); + float max_y = std::numeric_limits::lowest(); + std::unordered_map> clusters; size_t total_points = 0; for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z, ++iter_id) { @@ -91,9 +121,41 @@ class OccupancyGrid : public rclcpp::Node { p.z = *iter_z; p.cluster_id = *iter_id; clusters[p.cluster_id].push_back(p); + + min_x = std::min(min_x, p.x); + min_y = std::min(min_y, p.y); + max_x = std::max(max_x, p.x); + max_y = std::max(max_y, p.y); + ++total_points; } + const float padding = 1.0f; + min_x -= padding; + min_y -= padding; + max_x += padding; + max_y += padding; + + float cell_size = 0.2f; + float angle_increment = deg2rad(0.4); + // 26 fov has horizontal angle: 0.4° + int width = static_cast((max_x - min_x) / cell_size); + int height = static_cast((max_y - min_y) / cell_size); + + grid_msg_.header.frame_id = "rslidar"; + grid_msg_.info.resolution = cell_size; + grid_msg_.info.width = width; + grid_msg_.info.height = height; + grid_msg_.info.origin.position.x = min_x; + grid_msg_.info.origin.position.y = min_y; + grid_msg_.info.origin.position.z = 0.0; + grid_msg_.info.origin.orientation.x = 0.0; + grid_msg_.info.origin.orientation.y = 0.0; + grid_msg_.info.origin.orientation.z = 0.0; + grid_msg_.info.origin.orientation.w = 1.0; + + grid_msg_.data.assign(width * height, static_cast(CellState::UNKNOWN)); + // z-axis filtering const float z_min_allowed = 0.0f; const float z_max_allowed = 2.5f; @@ -146,9 +208,6 @@ class OccupancyGrid : public rclcpp::Node { for (const auto &kv : filtered_clusters) { int cid = kv.first; const auto &pts = kv.second; - uint8_t r = static_cast((kv.first * 53) % 255); - uint8_t g = static_cast((kv.first * 97) % 255); - uint8_t b = static_cast((kv.first * 193) % 255); if (pts.size() < 3) { RCLCPP_WARN(this->get_logger(), @@ -162,29 +221,225 @@ class OccupancyGrid : public rclcpp::Node { float z_min = std::numeric_limits::max(); float z_max = std::numeric_limits::lowest(); for (const auto &p : pts) { - cv_points.emplace_back(p.x, p.y); - z_min = std::min(z_min, p.z); - z_max = std::max(z_max, p.z); - std_msgs::msg::ColorRGBA color = getColorFromId(cid); - - *out_x = p.x; - *out_y = p.y; - *out_z = 0.0f; - *out_r = color.r * 255; - *out_g = color.g * 255; - *out_b = color.b * 255; - ++out_x; ++out_y; ++out_z; - ++out_r; ++out_g; ++out_b; + cv_points.emplace_back(p.x, p.y); + z_min = std::min(z_min, p.z); + z_max = std::max(z_max, p.z); + std_msgs::msg::ColorRGBA color = getColorFromId(cid); + + *out_x = p.x; + *out_y = p.y; + *out_z = 0.0f; + *out_r = color.r * 255; + *out_g = color.g * 255; + *out_b = color.b * 255; + ++out_x; ++out_y; ++out_z; + ++out_r; ++out_g; ++out_b; } } bev_points.width = static_cast(bev_points.data.size() / bev_points.point_step); bev_points.row_step = bev_points.point_step * bev_points.width; + // bev_points done -> get occupancy grid: + sensor_msgs::msg::PointCloud2 map_scan = worldScanToMap(*msg); + Obstacle2OccupancyGrid(*msg, map_scan, angle_increment); + RCLCPP_INFO(this->get_logger(), "Publishing /bev_points of %zu points", bev_points.data.size()); bev_pub_->publish(bev_points); + grid_pub_->publish(grid_msg_); + } + + // need ground segmentor before obstacle seg + void Obstacle2OccupancyGrid( + sensor_msgs::msg::PointCloud2 &world_scan, + sensor_msgs::msg::PointCloud2 &map_scan, + float angle_increment + ) { + // add step that transforms point cloud + std::vector> obstacle_angle_bins; + std::vector grid_points_(grid_msg_.info.width * grid_msg_.info.height, 50); + // 360 degrees + constexpr double min_angle = deg2rad(-180.0); + constexpr double max_angle = deg2rad(180.0); + const size_t angle_bin_size = ((max_angle - min_angle) / angle_increment) + size_t(1); + obstacle_angle_bins.resize(angle_bin_size); + + // add obstacle points to their corresponding angle bins -> 1 bin per ray + for (sensor_msgs::PointCloud2ConstIterator iter_x(world_scan, "x"), iter_y(world_scan, "y"), + iter_wx(map_scan, "x"), iter_wy(map_scan, "y"); + iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_wx, ++iter_wy) + { + const double angle = atan2(*iter_y, *iter_x); + int angle_bin_idx = (angle - min_angle) / angle_increment; + obstacle_angle_bins.at(angle_bin_idx) + .push_back(BinInfo(std::hypot(*iter_y, *iter_x), *iter_wx, *iter_wy)); + } + + // double ox = std::floor(grid_msg_.info.origin.position.x / grid_msg_.info.resolution); + // double oy = std::floor(grid_msg_.info.origin.position.y / grid_msg_.info.resolution); + // // sort by distance + // for (auto & obstacle_angle_bin : obstacle_angle_bins) { + // std::sort(obstacle_angle_bin.begin(), obstacle_angle_bin.end(), + // [](auto a, auto b) { return a.range < b.range; }); + // } + + // // initialize cells to the final point with freespace + // for (size_t bin_idx = 0; bin_idx < obstacle_angle_bins.size(); ++bin_idx) { + // // iterate through all angle_bins, find the farthest point of each bin -> last element + // auto & obstacle_angle_bin = obstacle_angle_bins.at(bin_idx); + + // BinInfo end_distance; + // if (obstacle_angle_bin.empty()) { + // continue; + // } else { + // end_distance = obstacle_angle_bin.back(); // furthest away point + // } + // // from origin to farthest point are all FREE initially + // rayTrace(ox, oy, end_distance.wx, end_distance.wy, CellState::FREE); + + // // later implement method that takes into account blindspot behind obstacles -> UNKNOWN + + // // fill in obstacle points as OCCUPIED + // fillOccupied(obstacle_angle_bins, 0.0); + // } + } + + void setCellValue(double x, double y, CellState state) { + int xi = static_cast(x); + int yi = static_cast(y); + if (xi < 0 || yi < 0 || + xi >= static_cast(grid_msg_.info.width) || + yi >= static_cast(grid_msg_.info.height)) + return; // skip out-of-bounds + + size_t index = yi * grid_msg_.info.width + xi; + switch (state) { + case CellState::OCCUPIED: grid_msg_.data[index] = 97; break; + case CellState::UNKNOWN: grid_msg_.data[index] = 50; break; + case CellState::FREE: grid_msg_.data[index] = 3; break; + } } + void fillOccupied(std::vector> obstacle_angle_bins, double distance_margin) { + for (size_t bin_idx = 0; bin_idx < obstacle_angle_bins.size(); ++bin_idx) { + auto & obstacle_angle_bin = obstacle_angle_bins.at(bin_idx); + for (size_t dist_idx = 0; dist_idx < obstacle_angle_bin.size(); ++dist_idx) { + const auto & source = obstacle_angle_bin.at(dist_idx); + setCellValue(source.wx, source.wy, CellState::OCCUPIED); + + if (dist_idx + 1 == obstacle_angle_bin.size()) { + continue; + } + + auto next_dist = std::abs( + obstacle_angle_bin.at(dist_idx + 1).range - + obstacle_angle_bin.at(dist_idx).range); + // the distance_margin should be + // obstacle height |\ + // | \ -> angle is vertical fov + // ---- + //obstacle dist from og intersect w/ ground + if (next_dist <= distance_margin) { + const auto & source = obstacle_angle_bin.at(dist_idx); + const auto & target = obstacle_angle_bin.at(dist_idx + 1); + rayTrace(source.wx, source.wy, target.wx, target.wy, CellState::OCCUPIED); + continue; + } + } + } + } + + // function to convert world (PointCloud2) coordinates to map coordinates + bool worldToMap(float wx, float wy, unsigned int &mx, unsigned int &my) { + mx = static_cast(std::floor(fabs((wx - (grid_msg_.info.origin.position.x)) / grid_msg_.info.resolution))); + my = static_cast(std::floor(fabs((wy - (grid_msg_.info.origin.position.y)) / grid_msg_.info.resolution))); + if (mx < grid_msg_.info.width && my < grid_msg_.info.height) { + return true; + } + return false; + } + + sensor_msgs::msg::PointCloud2 worldScanToMap(sensor_msgs::msg::PointCloud2 &world_scan) { + sensor_msgs::msg::PointCloud2 map_scan; + map_scan.header = world_scan.header; + map_scan.height = 1; + map_scan.is_dense = false; + map_scan.is_bigendian = false; + + size_t n_points = world_scan.width * world_scan.height; + + std::string id_field; + for (const auto &f : world_scan.fields) { + if (f.name == "id" || f.name == "cluster_id") { + id_field = f.name; + break; + } + } + + sensor_msgs::PointCloud2Modifier modifier(map_scan); + modifier.setPointCloud2Fields( + 4, + "x", 1, sensor_msgs::msg::PointField::FLOAT32, + "y", 1, sensor_msgs::msg::PointField::FLOAT32, + "z", 1, sensor_msgs::msg::PointField::FLOAT32, + "id", 1, sensor_msgs::msg::PointField::UINT32 + ); + + modifier.resize(n_points); + map_scan.width = n_points; + map_scan.row_step = map_scan.point_step * map_scan.width; + + sensor_msgs::PointCloud2ConstIterator iter_x(world_scan, "x"); + sensor_msgs::PointCloud2ConstIterator iter_y(world_scan, "y"); + sensor_msgs::PointCloud2ConstIterator iter_z(world_scan, "z"); + sensor_msgs::PointCloud2ConstIterator iter_id(world_scan, id_field); + + sensor_msgs::PointCloud2Iterator mx(map_scan, "x"); + sensor_msgs::PointCloud2Iterator my(map_scan, "y"); + sensor_msgs::PointCloud2Iterator mz(map_scan, "z"); + sensor_msgs::PointCloud2Iterator mid(map_scan, "id"); + + // Iterate through all points + for (size_t i = 0; i < n_points; ++i, ++iter_x, ++iter_y, ++iter_z, ++iter_id, ++mx, ++my, ++mz, ++mid) + { + float wx = *iter_x; + float wy = *iter_y; + + if (!std::isfinite(wx) || !std::isfinite(wy)) continue; + if (grid_msg_.info.resolution <= 0.0) continue; + + *mx = std::floor(fabs((wx - (grid_msg_.info.origin.position.x)) / grid_msg_.info.resolution)); + *my = std::floor(fabs((wy - (grid_msg_.info.origin.position.y)) / grid_msg_.info.resolution)); + *mz = 0.0; + *mid = *iter_id; + } + + return map_scan; + } + + // implement Bresenham's line algo for ray tracing + void rayTrace(double ox, double oy, double tx, double ty, CellState state) { + // ray defined by (ox, oy) + (tx - ox, ty - oy) * t; + int x = static_cast(ox); + int y = static_cast(oy); + int x_end = static_cast(tx); + int y_end = static_cast(ty); + + int dx = std::abs(x_end - x); + int dy = std::abs(y_end - y); + int sx = (x < x_end) ? 1 : -1; + int sy = (y < y_end) ? 1 : -1; + int err = dx - dy; + + while (true) { + setCellValue(x, y, state); + if (x == x_end && y == y_end) break; + int e2 = 2 * err; + if (e2 > -dy) { err -= dy; x += sx; } + if (e2 < dx) { err += dx; y += sy; } + } + } + std_msgs::msg::ColorRGBA getColorFromId(int cluster_id) { std_msgs::msg::ColorRGBA color; @@ -200,11 +455,13 @@ class OccupancyGrid : public rclcpp::Node { rclcpp::Subscription::SharedPtr obs_sub_; rclcpp::Subscription::SharedPtr pc_sub_; rclcpp::Publisher::SharedPtr bev_pub_; + rclcpp::Publisher::SharedPtr grid_pub_; + nav_msgs::msg::OccupancyGrid grid_msg_; }; int main(int argc, char ** argv) { rclcpp::init(argc, argv); - auto node = std::make_shared(); + auto node = std::make_shared(); rclcpp::spin(node); rclcpp::shutdown(); return 0; From 268cda536c11083ecd19b6ac2d18174466346fb6 Mon Sep 17 00:00:00 2001 From: sophtsang Date: Fri, 7 Nov 2025 04:01:24 +0000 Subject: [PATCH 10/28] successfully implemented occupancy grid w/ obstacle point clouds --- CMakeLists.txt | 8 +-- package.xml | 2 +- src/occupancy_grid.cpp | 138 ++++++++++++++++++----------------------- 3 files changed, 65 insertions(+), 83 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 6b24500..aa16036 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -10,6 +10,7 @@ find_package(ament_cmake REQUIRED) find_package(rclcpp REQUIRED) find_package(sensor_msgs REQUIRED) find_package(std_msgs REQUIRED) +find_package(nav_msgs REQUIRED) find_package(geometry_msgs REQUIRED) find_package(cev_msgs REQUIRED) find_package(PCL REQUIRED) @@ -17,7 +18,6 @@ find_package(pcl_conversions REQUIRED) find_package(pcl_ros REQUIRED) find_package(rosidl_default_generators REQUIRED) find_package(OpenCV REQUIRED) -find_package(slam_toolbox REQUIRED) find_package(tf2 REQUIRED) find_package(tf2_geometry_msgs REQUIRED) find_package(visualization_msgs REQUIRED) @@ -26,7 +26,7 @@ find_package(visualization_msgs REQUIRED) rosidl_generate_interfaces(${PROJECT_NAME} "msg/Obstacle.msg" "msg/ObstacleArray.msg" - DEPENDENCIES std_msgs geometry_msgs cev_msgs + DEPENDENCIES std_msgs geometry_msgs cev_msgs nav_msgs ) add_executable(obstacle_node src/obstacle_node.cpp) @@ -51,11 +51,11 @@ ament_target_dependencies( rclcpp cev_msgs sensor_msgs - std_msgs + std_msgs + nav_msgs pcl_conversions pcl_ros geometry_msgs - slam_toolbox tf2 tf2_geometry_msgs visualization_msgs diff --git a/package.xml b/package.xml index d289af3..23472df 100644 --- a/package.xml +++ b/package.xml @@ -12,9 +12,9 @@ rclcpp sensor_msgs std_msgs + nav_msgs geometry_msgs cev_msgs - slam_toolbox pcl_conversions pcl_ros diff --git a/src/occupancy_grid.cpp b/src/occupancy_grid.cpp index faa02a3..06e5245 100644 --- a/src/occupancy_grid.cpp +++ b/src/occupancy_grid.cpp @@ -71,8 +71,6 @@ class OccupancyGridNode : public rclcpp::Node { private: void obstaclesCallback(const cev_msgs::msg::Obstacles::SharedPtr msg) { - // RCLCPP_INFO(this->get_logger(), "Received Obstacles message with %zu clouds", msg->obstacles.size()); - sensor_msgs::msg::PointCloud2 merged_cloud = msg->obstacles[0]; for (size_t i = 1; i < msg->obstacles.size(); ++i) @@ -241,10 +239,25 @@ class OccupancyGridNode : public rclcpp::Node { bev_points.row_step = bev_points.point_step * bev_points.width; // bev_points done -> get occupancy grid: - sensor_msgs::msg::PointCloud2 map_scan = worldScanToMap(*msg); - Obstacle2OccupancyGrid(*msg, map_scan, angle_increment); + sensor_msgs::msg::PointCloud2 map_scan; + map_scan.header = out.header; + map_scan.header.frame_id = "rslidar"; + map_scan.height = 1; + + sensor_msgs::PointCloud2Modifier map_modifier(map_scan); + map_modifier.setPointCloud2Fields( + 4, + "x", 1, sensor_msgs::msg::PointField::FLOAT32, + "y", 1, sensor_msgs::msg::PointField::FLOAT32, + "z", 1, sensor_msgs::msg::PointField::FLOAT32, + "id", 1, sensor_msgs::msg::PointField::UINT32 + ); + + map_modifier.resize(total_kept_points); + + worldScanToMap(filtered_clusters, map_scan); + Obstacle2OccupancyGrid(bev_points, map_scan, angle_increment); - RCLCPP_INFO(this->get_logger(), "Publishing /bev_points of %zu points", bev_points.data.size()); bev_pub_->publish(bev_points); grid_pub_->publish(grid_msg_); } @@ -265,6 +278,8 @@ class OccupancyGridNode : public rclcpp::Node { obstacle_angle_bins.resize(angle_bin_size); // add obstacle points to their corresponding angle bins -> 1 bin per ray + RCLCPP_INFO(this->get_logger(), "world_scan %zu and map_scan %zu", world_scan.data.size(), map_scan.data.size()); + for (sensor_msgs::PointCloud2ConstIterator iter_x(world_scan, "x"), iter_y(world_scan, "y"), iter_wx(map_scan, "x"), iter_wy(map_scan, "y"); iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_wx, ++iter_wy) @@ -275,33 +290,33 @@ class OccupancyGridNode : public rclcpp::Node { .push_back(BinInfo(std::hypot(*iter_y, *iter_x), *iter_wx, *iter_wy)); } - // double ox = std::floor(grid_msg_.info.origin.position.x / grid_msg_.info.resolution); - // double oy = std::floor(grid_msg_.info.origin.position.y / grid_msg_.info.resolution); - // // sort by distance - // for (auto & obstacle_angle_bin : obstacle_angle_bins) { - // std::sort(obstacle_angle_bin.begin(), obstacle_angle_bin.end(), - // [](auto a, auto b) { return a.range < b.range; }); - // } - - // // initialize cells to the final point with freespace - // for (size_t bin_idx = 0; bin_idx < obstacle_angle_bins.size(); ++bin_idx) { - // // iterate through all angle_bins, find the farthest point of each bin -> last element - // auto & obstacle_angle_bin = obstacle_angle_bins.at(bin_idx); - - // BinInfo end_distance; - // if (obstacle_angle_bin.empty()) { - // continue; - // } else { - // end_distance = obstacle_angle_bin.back(); // furthest away point - // } - // // from origin to farthest point are all FREE initially - // rayTrace(ox, oy, end_distance.wx, end_distance.wy, CellState::FREE); - - // // later implement method that takes into account blindspot behind obstacles -> UNKNOWN + double ox = std::floor(grid_msg_.info.origin.position.x / grid_msg_.info.resolution); + double oy = std::floor(grid_msg_.info.origin.position.y / grid_msg_.info.resolution); + // sort by distance + for (auto & obstacle_angle_bin : obstacle_angle_bins) { + std::sort(obstacle_angle_bin.begin(), obstacle_angle_bin.end(), + [](auto a, auto b) { return a.range < b.range; }); + } + + // initialize cells to the final point with freespace + for (size_t bin_idx = 0; bin_idx < obstacle_angle_bins.size(); ++bin_idx) { + // iterate through all angle_bins, find the farthest point of each bin -> last element + auto & obstacle_angle_bin = obstacle_angle_bins.at(bin_idx); + + BinInfo end_distance; + if (obstacle_angle_bin.empty()) { + continue; + } else { + end_distance = obstacle_angle_bin.back(); // furthest away point + } + // from origin to farthest point are all FREE initially + rayTrace(ox, oy, end_distance.wx, end_distance.wy, CellState::FREE); + + // later implement method that takes into account blindspot behind obstacles -> UNKNOWN - // // fill in obstacle points as OCCUPIED - // fillOccupied(obstacle_angle_bins, 0.0); - // } + // fill in obstacle points as OCCUPIED + fillOccupied(obstacle_angle_bins, 0.0); + } } void setCellValue(double x, double y, CellState state) { @@ -359,62 +374,29 @@ class OccupancyGridNode : public rclcpp::Node { return false; } - sensor_msgs::msg::PointCloud2 worldScanToMap(sensor_msgs::msg::PointCloud2 &world_scan) { - sensor_msgs::msg::PointCloud2 map_scan; - map_scan.header = world_scan.header; - map_scan.height = 1; - map_scan.is_dense = false; - map_scan.is_bigendian = false; - - size_t n_points = world_scan.width * world_scan.height; - - std::string id_field; - for (const auto &f : world_scan.fields) { - if (f.name == "id" || f.name == "cluster_id") { - id_field = f.name; - break; - } - } - - sensor_msgs::PointCloud2Modifier modifier(map_scan); - modifier.setPointCloud2Fields( - 4, - "x", 1, sensor_msgs::msg::PointField::FLOAT32, - "y", 1, sensor_msgs::msg::PointField::FLOAT32, - "z", 1, sensor_msgs::msg::PointField::FLOAT32, - "id", 1, sensor_msgs::msg::PointField::UINT32 - ); - - modifier.resize(n_points); - map_scan.width = n_points; - map_scan.row_step = map_scan.point_step * map_scan.width; - - sensor_msgs::PointCloud2ConstIterator iter_x(world_scan, "x"); - sensor_msgs::PointCloud2ConstIterator iter_y(world_scan, "y"); - sensor_msgs::PointCloud2ConstIterator iter_z(world_scan, "z"); - sensor_msgs::PointCloud2ConstIterator iter_id(world_scan, id_field); - + void worldScanToMap(std::unordered_map> &world_scan, sensor_msgs::msg::PointCloud2 &map_scan) { sensor_msgs::PointCloud2Iterator mx(map_scan, "x"); sensor_msgs::PointCloud2Iterator my(map_scan, "y"); sensor_msgs::PointCloud2Iterator mz(map_scan, "z"); sensor_msgs::PointCloud2Iterator mid(map_scan, "id"); - // Iterate through all points - for (size_t i = 0; i < n_points; ++i, ++iter_x, ++iter_y, ++iter_z, ++iter_id, ++mx, ++my, ++mz, ++mid) - { - float wx = *iter_x; - float wy = *iter_y; + for (const auto &kv : world_scan) { + int cid = kv.first; + const auto &pts = kv.second; - if (!std::isfinite(wx) || !std::isfinite(wy)) continue; - if (grid_msg_.info.resolution <= 0.0) continue; - - *mx = std::floor(fabs((wx - (grid_msg_.info.origin.position.x)) / grid_msg_.info.resolution)); - *my = std::floor(fabs((wy - (grid_msg_.info.origin.position.y)) / grid_msg_.info.resolution)); + for (const auto &p : pts) { + *mx = std::floor(fabs((p.x - (grid_msg_.info.origin.position.x)) / grid_msg_.info.resolution)); + *my = std::floor(fabs((p.y - (grid_msg_.info.origin.position.y)) / grid_msg_.info.resolution)); *mz = 0.0; - *mid = *iter_id; + *mid = cid; + + ++mx; ++my; ++mz; ++mid; + } } - return map_scan; + map_scan.width = static_cast(map_scan.data.size() / map_scan.point_step); + map_scan.row_step = map_scan.point_step * map_scan.width; + } // implement Bresenham's line algo for ray tracing From de5c14a4e1a5d8a476a1d7cabf2d6aa124a46cbd Mon Sep 17 00:00:00 2001 From: sophtsang Date: Fri, 7 Nov 2025 04:05:54 +0000 Subject: [PATCH 11/28] added some occupancy grid pics to readme --- README.md | 9 +++------ 1 file changed, 3 insertions(+), 6 deletions(-) diff --git a/README.md b/README.md index 4099048..17969df 100644 --- a/README.md +++ b/README.md @@ -1,13 +1,10 @@ # Obstacle_node Hi all, I'm going to start yapping again! -## Rasterization -A raster is a digital image made up of a rectangular grid of pixels. We can say that an occupancy grid is essentially a raster, where obstacles will be represented as filled in pixels. - -Given a 3D point cloud, we will its 2D counterpart by projection to birds-eye view (BEV), and then rasterize this 2D point cloud to get its representation on an occupancy grid. - - +## Angle Bins and Ray Tracing Via Bresenham's Line Algo +![Occupancy Grid 1](demos/occ.png) +![Occupancy Grid 2](demos/occupancygrid.png) # Important Links [Rasterize a point cloud](https://r-lidar.github.io/lasR/reference/rasterize.html) \ No newline at end of file From 52f647f3361fcaeb51ccaad52f435712c2f80186 Mon Sep 17 00:00:00 2001 From: sophtsang Date: Thu, 6 Nov 2025 23:08:48 -0500 Subject: [PATCH 12/28] demo imgs --- demos/occ.png | Bin 0 -> 118583 bytes demos/occupancygrid.png | Bin 0 -> 76486 bytes 2 files changed, 0 insertions(+), 0 deletions(-) create mode 100644 demos/occ.png create mode 100644 demos/occupancygrid.png diff --git a/demos/occ.png b/demos/occ.png new file mode 100644 index 0000000000000000000000000000000000000000..d80a33f4f1993bf68a6d93cbdc4270ed61dbd127 GIT binary patch literal 118583 zcmeFZd0did8#e5$O;6icGi_Qnm0DWb;!>{7*kod8qq(FZHdbnijtinFV$)PMrDlpw z5;~P=ih!k};)1P?nHwskh|Xk1NJ0ikqR4yQQ1d)Y&inoK{rB?wRbp`8*K#h$d7Q^} zpFil~y68Wv|D&g;x5#b(UN1ep|6J13`z-#8&%tj7KYhFe{PR(qm+Nm^u0xct8KA{fFc9^wyk%{(O}6eB!vCo|^2o_uE5>L9h6@3REc0= zb`nQLMq^5Pg<#z8U)xr@vKPO9qo>CpE-L=- zyA2_qZ2tRQ%O6knK+B_jZQEgU>Erir^e$ffe_zx4e@g=F;s03)?Icss}a z_8;l#1^Y}Y6f1%x)R1R(r|c@pFWS zEf0o=gIi#C;qnXP$ibG4)&@`&Hm94|Y(O%^U5{7lS+ScXQQK(=Wz73xBJ%s~Xrs0oQ_F z`~jVKX5TB6tsDPTPcMxDR&>Mqr;MVvsbgV#@6Y-zSJx+9ll7#h^ZER03Zd=T<%DW)ma zln0AphD}o!q>Lyqg%eeW2N!8Sd?am-?FcM`nV{Y+(zbnbY(?ZRqpex36QiwNO@#+c zNCn4!&|WR9>+^R;0p6!&4_xsmofmEjetsp9lp;v4#NrYJ^?*qZScRd!o*}IETicE; zg*NEjYu`i7HS$hkFt+x%ue87QU!vK=_a8YCYDZdIOagBsvs5ZoH6^FXAYuLbr&2|S zdg`sI=f>!p*~IVct{h;~e4)wq!=jpw^zY&#R%ox#X?p72g~9vaV;VE~^B}!B{#KK; zfRre(mRhm56FW|PpV9whWW>^gr?sY)%l>r~>_ZRzkj%GA&qDtcL?{^g_{rltt`sAv z)o{guu93;Q?|`m8i33A8$7nmoE+>yE z2O=$5GyaV;Z$iS~dC6AYeg4}5gOfGOy&wn|E{`)^zkWEW61_rTYlj^JlsNQc+ls;#Yky;`$y zY2WMY)IKOswCpcFpGhz~6)!oP^s%tWVLQG_O?ZH}pxOUWO=0i#oL@{dM$nxnJ9+Cn z-Pcl6M(?`#eUp;o>(0KAPnuBc!`5b@hHfK#Kz(MzNLYT4Nd7`;gZ58?GJxVoOse z4b4SF-xNAVHu0uCYpdb1&>Yu>k}NIqxp-d3^{RG~ zJeIIMz&hJ-XJ=C(o5hxW)w;kOuHQi#VKYT}4N=JCdzP+y?=L~bxa{5QpzQWrzrK^4 zU04LeHfv+cwGMO5M(we9zqHWXclo3;CiR8O$i!J?r;ikp%CPB8hfbJu+>ORl>5cxpKhb34n*Ud&%nn1>^wtXo;s4t@Gn?D7(a{3w)ccfy)nZjqho!f=zb=R=he{A5bkG+ z5^Qc-g39_tGxL|k_n{KJP0Q8}-o0tG*Y=^k6E4IdMG-RbnxFOH!AN5Gk(rGAhmkgc zVHLi1BjLmYCMzP_ZStm5XWmZiN}Wj@R2d3W{I)iEqP4*?_@++2xIz-fV=pCu&8(~k zA-|XA0^Mcb-uus^6A$m*+xQyEGD~u`tq=drYqezsJ*k6Aq>MAip}004a4DHoFC_*- zbpcph{)c%W?Nph2Y~x=l=`TI)^di$trxb38v6@j>y zDL(dK=+i&0Z60+SPpn95`4t!D*rRp_FvA+*4Py|neMj%c3d-!F zc3e4T?Q4!(JZSUo_L}X~{0znIe;Ux@8YsGce-*y(NGZFz9i4>ng5pGk07W7N zOK!yw-Yxm><~k0tL1W`C*2WnegF>VDXpzV+PV|EF&R}6W zfl5;)RsJ6;&Y`;HQ6gaXv8Yc=I&9oQq$JhM%zW4xS#wLH zQP2PUbKQ8rg$=ID)g#+FPgL#NwJR*Lo{dEj`d+z+(Q9|dZp<{??Ume=)AnpAd2s|> zLH7_Rx+B64thj7HJcR9^vF=9|s7vxrmTT=V(nu|Ow_D(!ci_JAngwh2_yX#i*NChK z_b`r(*TdiZ)^TD1${TKy^VD+hQ?==S$F(?7R<}Vff zSA$`7dELw+%fLvt_2D$DiAq#RRdHMHQZw!blBC*)EohAc=nT9f|D%(|HE<(sk&kg^ z>T~35c#7sP$R#WrCG8XM#yENP{yhf#|gE-FX=c`vI7h|alJ0Xp z2VtQ3fZn|mI>x6p-4ppp_3gSDWxgg^41ugcW(}_le_H&kEdksELVv{UGS0WknQD~w zGL$(lRSOq)y;;Y$g?sh>zZ2=^;-MCHwVX1Y4Z0FfO#!n zG9vd+dB34TUSZCsgMAMRQ|h9GGu#?kb8&`4|BQ{B#FaPdzeJ&3@PByKs{^IIr!_t$ z)&%7Uu=39^)9ff|f~P zVbDsO)nFApGEyI(s9L~~IgvB^VG>v1C)rv*34Z%8d8(Ta0gIYHO$$?bcSX~g!>reF z01^JBKs_({2>5$-#EnJccIRw{n=6tFV?~5VYobXdqD@q8{Hz_wF(U1fPt7r0^Mno| zWwfBzuQkhA&UiafI=tKuFBz*-Ci}JGTqVx=PIh~9+BQwxXKM{ zP+}19z^gKRj*D=fHQ!KJRv&lESxj6l%I-|&Jv>R4l6d~q_-3LO*LIWs1&Y1lt0Ity zMAd^8vv=-_>>#|s-3Nd|xSx4__^Eoi8A?=w9$Z@+Dcm(U7SULLL~!zXXU>FXMlF+b zBuhJhbh6UZp3c+)x-x-&q@ETx+4dbhgf=HHmj!FYqUuXiO0*6p5cW zgZ~nl@|V$lu)onHCno$v)xc*wO`39KC)uir#<(cWmGtsDbnxVVt3v(h>FIDk0F|_( z&6+(Y0%ZqXB{c`DQluu0>WAjI#c8U>z^%69J8UzyLj#PWl}vClN`-YMXaSkXoW5kw zLJI@->1PXyX2{qi>zFrh4*p00&Hnl$xBI;T5S2!O^3{Z=F`H7Anpk; z&T1a@h5+|HOjnMp`mJE?`Sf()M)=_dk=r^1mHkT#$c;nHdij&cdeOB*V(e;OV!lu9 zcoO@afqbF6=$asK{+uLr%i8AYTZtkbe#fwKvgo1_ehf7+>e;jvXHdNZ6nyOYaakdb z0H^*C;#e-YiHa-IuC*>bpam9HvoEsNUSLh#Xnk5BL9F4XNXFiZiA5JB%~NeMlq_;n zTUz+#qXqF#`qBhWt|%U}=tjBL0~h{FeVB&2&0-ZLtQmu1BPiS7dP|Gctvsg{`ugfF zqauJQ0--py!abL0@x;b>n3I8rQ>bs*+{2{E1 zbzV{c7hQs8u0^_aRaxLNFbMRtN210UgNHucz?PSMjBK_}@=`T1k?%1&YDp?gUesMX z5XtB^%V{h2fiRAT#LruUzSErkg+qB_qKQqWnw9*-x8Tul#MQqA+SU#qyi%ILar6X{ z^Lb`1+e*xo+OF{{6{nz{zw-}6osvsSX1(l*v}p)F4X+f6Vs>0H9ApbNYq8I^6FLD! z+XuP$=yuM$-uw5Mc_u~{$%Y|*9dTw&OVAk|xx=MQ#%3FogT~x``ev^01{8cT*k@xs z^-~~OI?^{(lv=F#MtiT87rNDxCRN@9?9Phhb zDyE17&@)rZ3?p>$;NN`HpVP(6nC5$IgNBuZ*hfvn&9u0%(GEgTD0iZ?wYI;;!?-r6 zY-qwawv`0JVWF&!HptOL(=;7s#YsDzg#eHSh7qGSjaKAzV!T1JU7#($ZL)Qev=;a+ z+*1(tq~^|VaB@~Z>$&|k?&Gwn;c}IB25(9DrM|nYyiw_ z-|hJ@@2}#xF-Y|E<>aQ2`p!p8dTo4TeJs5yzA=Qd0NRN?&L3K#-Wijew$BW@AII%n zs9{_O;>3PDo8|ou)IcBGTFvygSNUg3!2P@J?Ox(yUE| zTR|VE=A-eV4N8KEM@dFUp3^%vChcg|hx78^?uLr|8Sa*PAZHV?;Ql?xW2(2;j-iQ8 zMig4D8AoGDbG8T4IPBtkCBE6)5|0W~wl5Y+*){#)N-gd2%m1#zsMhcTixv>;hO2M%lhA& zXc@bfJlHbXpv}6Xz4tp_NNGmGMsAJO;p%Z|-y}|Rvn{%Wnil-7US$23C45&TFHPdU z>|0`i05EKTEm=7SG)~JPm>49Wermo&yI`eXUFP%f-NuI;ox^`B4iJKWGcim+L3A0) zU|dFcw!3=Ts#*(o7wTeY?J9K#5Q?8L77;eyPk8KYE0p#yG?w3DHpgCHBE!~JMCkEM zR98iV{#jOcYEYV$S!pnbtuH2+2*`_qZ?d1Y(J~g8lS*aNB`9;M#vixY%&`S6k5Jeh z!3Epug`)_@Erg_d;rMLv`QH(Nw0G%te2yXMo%S_l`3^Vk1p|y~pgTOW5z6JKoq=j&jxU1mu9_9cn=cDO>tdQ-D>8ddi z)gIp)gC6UwJy}0WeU_O_LiYwBGBs&(E>1M922d@e)vu2Tpxln#`m-r3lQOnz} z#}8BThUp8ep=qXlqw8mXb8dQoKToiSXj1e|fHtore82a8bfXA=pyA27df~--QJG~u z_pnfejces|6Q|i+hv%HF1bZ=K6b|)6?1WRyO;n9PR(i~lG9LFF#pQ z!a56@1WWzkKR-QUCqbjOoW(W?RWP2-#4An7=JMl*X5Zp#kLxEapvKDXfNPvy@^FFV zZEWM~Ov|F=j%|lF<532x{UC<9FWX$Z{Yq>OS#d*KDpVroaJVNYJz3AUPRIg>mwGl% z^C#{%jHs?|^g8?f(x)fd;T5lxsmsZ2RP@#+XQGpY_uF1#CvH$H@WnUikCU?0ZD21o1 zwOLV@(bRfn_d58tSA+gktEAfzAyv?mYpt-cRtt+Fm+OR=|GIJIW-Zy1p7`_y26SD7=7O>t`LkjP zs5pA&tv!;6%z-F(N_wv2V($VEVgoH!l*egzZ0-XPA-bLm*0%Yq&9ML7-{K-l(G7*B zj+&zV&uu!^uHoeM47S48Im$&W#%m_9v!pjK$+aCh`}0X#27S4?yB=P%TC@$oUJxgQ z*c4;OF6Kg1Bd(293KORgI2{E0Vd?YCrgFagEqgnLssS|@b99zn6Fm0N*}wGImC_qQ zkEO6~iZ7&tYWoakC}vWSzhUF0+ecx&dJQy6c@THhtA5miN;Jnb5}F@2Md3QUHEbl} zEIXoeO>(%Vv#Zdo}8S-x_`n4MAWmN7v+`F(V$=%h~$*@WXYVYYQ7PP zRx8Uj31s1g4|B0zU^s9z$Rfl9_hsMre(u2SF3P!<*It{;6<}G7CQ$x?;F?{A__&E4GjPkqwo|934DqhbKXWwWbK- z*0q+%oY2|By+eb-q_gW4Sjdsnj_RO$t>CLtKhx=Lup#dCojMs~B*Q&=njc3$CDHV` zQJ|NKb#sceFA~nwI%djY5>Jm1$H(^2U}g9ICH!sSX?mq?pdC9{LtsCvp>4h>ocMB; zXcM7<2DX#3gJI2|#OC7=C~foUxUSV|HoEd#0M@_zB&`_`s=k_(w9-UpC$v>u+E%U~ zEEvJJYO17t#4p~=VOMA-x?qmFN-vna@xr7z{Kf%;aVmCEsiH(1tX|&LnTY0_X*E!U zX0*T}egmava?Gaqg%4$t-4%(cWNu=9qA)!PMC8vo|}`+`IpZJCuy zOGu>j^tah(f?xy_#&eTD37pR!C8g%y=x}(^d6*bS|4y7Z&9OqFx&85m&yApg;CIn3Z(K%$rLok<&d<0eE;ke7Q}E&&%n)3l0U0mmSXjNE(%X)$ zZ@Wb8Rs_(-N>M(5GfBW|)J6a3e!rvfPhTooVPpL}NjBi7=`mE2=18J?Pr|&uoX##e z$gw`Vp$Q}Y1{(jxIi-hzW%T$5&0~Pu1|6oZBtGMLiB|$nZR0;_U8=ZVM&;e6*HX3N zr^SB`*VS{+Fq^4fxeKodk&-0+qJhK;7QG*j)ScvO4l^O%{8vdo-y_U z9;|mk0|PChSi}>Y%;BJ((|kcWM?%zVSywDP1B#FA5_keCvbkA&7}*tzL_-D~JQq?) zyEA6KXbIzR!JmVSj31EP!cH7lLj!!NgS5KdQJ}#CYwKRkrl;49_4O}MfoQdW-Z04H zxi{$Pt=!&*1)zb%h(|o@jL2Gd=xuNEb-Ko#!ur^z}!FWl$ngqjtDTkFYZwy-fVvpGjkKw!+C3xtaEU z;=1Y8(M7R>^2_$2WON)LZM^KnL!lH&3(!Bi^(!&K&1he^wdbiO6z)PHS%-%L`D{xqEN6{Z@RH5EKXaT96WP z{g54``FzlS@bAvG@-4gkJ>`D4**8}3ui&Km@v`*vUAra^+@F#-Pb(jvYo1ow7AdC3 zX2P!voo52o?RP~!fxaK>>qTB>jHoxyFOIy<&fQgaX$U_r7rOrovo+De370;uwSY4o zC`RW8MZdEuAKice@WJwU_&Unc@6GLvaKkf#f&1Nu3f2{vT<|?#La^$wQmMLd6Zv3I z%f0<9Wn4FUG}N0y2eMuCo|p&~A%RQx59~$t{xvpR7?JESdZ;$4AeTmI9-BNK$u;OsTamxbP=;YfpPnpV-Ow5+9KS=9E%t-j-}T#IqcCm zZGFR@$m49)LcKh=PKE`3+!C>%a2Svl)TdFrXP^m-iIOhHFsq-geQ#oxPemx}`+7{(o1SwIq&1a=UZD z{{j>FlXY5uxx#C1>c&5NvBGFr-6H@~>x}Ngm$0Qi;l=$^X2K+llX3=Rj2ffqa|=`` zw=X{$Ocj&aU7k-q?Z>A2&D{M?4OV1pBP|3`1&3W0K1n637l$=8v+Yn>l$=63mCdY= zZ4DGg4B^HiI$FG^x$!8S( zZd^1ke(OkS2~o! zT=M^wy^(c%_pZrTcSR-7*cjZiQqVxV<2M8viqX5LMvNuDX$p0py&r!gvsA>1Ms1rc z)~}~Ey}Ep6Hc*oE)2uXN$rf3ugSx_nD@QOb$lt2$l^kFi}-y zJ7Ngb6U}22XJ#42;dkETI(bGi*j)`n@*Y0~hd$mkoSQtD(Ae&aRgp)<0jzSayzY>& z4oYrMoIWVG+O+AB_1=22T}j&#}dkA808ro zhPWG^!xVkQF;&gnlooQ4U+e30o1R`yzj(jrkWgxgPG1n-KpXj*1vH52djm!4+ZIQYU`3`jfkFX7tPBgZRm@zXj1L|m3|SZ1i`i=AN5EyYg>uW}2YogF zUrX*+vF|t8!O{6-n2qDE$;aQRv(5gJ)e4+>0sSd@<29<8I`M5#F1AKt5qtLz#n~ju zKB*mPc-_oMfRvs!m+h+ggESHMAsX0kcIss0$HEbQL-=1f6biQ5mm9N%VzI@Wi+)_0 zn=1A#4DaSd&8>Qn=0TD@?Q77^OAjxb*{cR&uUe=F|kQ!tEJ>4nRf zBmRWflP$*;mNF!IY%JY4$j{97@M6YczI4(RFWI_)J~CsE+0vM|=aETyU>6j6q?h+A zp60Ljy|kyGp*hyO8k9mSe9Od1VGTi|%z00a;cyRYsDY*!2bcek(PcW?tDQ3)cj9sP zX5^i&MYigsr`IK{-7e_a(@Rv(uc-*k`@P58;CZJ}zKY#%fDP8aR&wZ$b*}?H-b}n1 z(B;F{l-w9ZK8-T;71fJ8dKTWtm41pVpLS382=Mr zZ3{!UooZ+2-cJDPN1!7NjY>9KzkYG2$yMJ3k0St;fZP<2*c7>R|6ld7&aMScMmB`L z-^YEa0{k+Jg-p#)>;(b|vd9jDBb0<32;g3bGkzpycmdQlQ}sQgnlNL`)w<-hb)wOzM2wKyrCMu!(HS$Shj zI?8Of0O3EvGT9B-y|QNB^5J|l_(?;vG8dxo!IDNRAR}dsvOo@*x7Pm%D|y0w0bP_! z6Aj6KP~xrvVxzK6i7i}NThi6bMi0c#nvmrKsr3;R@u(UN8+(K#OF@B}2?}e{4>01z zfT*#3WY{_ovCu~+3XfQx}Yg_u_wi^UCn$+L~V`atpjCN3qlA9`F^`cdSn^Z&Xh$3A7nxC2V z11} zdB6G&id8UM{@;;`d}BrVoHIUuAiBEu2?ar7AO2ql1NbIHo>^P9SN`6?NnDxLDgCoIVJBwZ!s#GpMOZd$T)$qN zGJps1Bg=@yitixxLb}2$1Y!%|AAqR=WrJbQ`t#L7=I=`oMWv!nlT6 ztl@E{(+U8I`MI1k@Z4#KZ5H)Kc(RB>i|S1hWs0tsJuJ`7Y@){~j4{nH!RA_Mh)A?M zArmUa)1H4AU2B-t89t>)pPAgVzJimUKf^`0T}O@NUj{+)kdV4-}EG@hUMUf-P1MckFkK*%Eqiax==WSGy zqc(xc-T4gJ2tpJP?Sv7L6+a>rzc`>3n{gbrrW8i&kQ0CF!6`M6J_B)(uoeq^%u;4l zKlMP9Z9p0M=mbo4dW?XkVf=I^ThL2=~$`sE`)%7kow zc`CA&#tV=u>BU`lm}3@!*fo(Q*QoSnu8%lH?idA%GV~(Uv(#AvFhl08Uk2+79u8U2 zN=AuRBz&(7*94b~I!EG<;zZ~3OL~&LoM;}g9y%?zv z`3p@(0o5rM4u;kAYNEnjh^{4cb}`4IF2v6=5JKf2Bs#F$w%DQt55EC+3vn92a90*| zA}~Yc))^Ex1;ZkNgP` zZK`i$L~7=1Y_HqAYZ<&~)swrT|4DL6Z;b>o0A#Y`rLQa8d7_|6c@4Gwh`#9Vf zgL7XsW`Zef+gU9?%yfd$ZJ`KqErTs@OE6c>xN-e>QgZ9_ut4*gi-X2z?ZnM8Ya~d6 zl&BO@Icp1=3&p@~`#y+;3lDlP4asRX>O&_NE$buXOrl6p~9IKOHWG?YI1l?IPkdTn`rate^|pRrK}a2LAp1)e;#Hzp;A zAz)n^8YCRQ_>HT$j`)xl4-S~v`t+jvH#ZFrF$pC~GEmbU!gy0pYSQf4y*f(;adVN4 z1Ca@L9@aI1wAsO{kxriCNivoUrAA+MkRJY09;*B059Uyo6^Q-LEc0 za!2Hxwm7n49f}}3yfgn?puDkIVTux}wCrcGPJGcwVpmp+f@0i`D1LQ+I@tbVoLPkm zEH3*F)qAFR;kOuJ9H%esgiztd{d|k7a?Oi|3ZyU;(a)aFu~B9Z&r?8|=81_8e+Ma! zTH?Gs$5uyPHVcszk z96uwr#bVTI@=bTxm(GR44{-h z!v!j&1$4jTH`@%B9y$9Bf{S)a?S=H9gBql_WEesKrF}j3G+j*tYCK|zJW1>>Ov!?C z<+8sZN7nC31+qQ7PzjLZ_{$N5SkwnBuYk?I^!%w@_YxojBBWjVbSWo`M#HvB?jQf)?TGu{zKV z2aUU}{Xjl8VZDZ1EN%qyF>Mu7Isb!*{CmyNq0Huf^3N4Y?ATar9TOb1iIKg>mP9Kh zus1~F2*daygV50F+caAX7duo1;pn0vG(>hX2}4RKzQ%H`?_Ew^T+<{G#_S&Cl;_x= z)si-41{j`{vxZeR801G{i?&infHKem2)Q(UxyX-oSTu;KuapC^@3oAM+wa6<7|7DE zIuPwv>&J{A&j&f*+wE`@l$lS%t*Yh1=`VaORkJ5~D?i7N&^`HvrHbEa7^8V`7!-wofD!APoj8F;STX~dl0suH*RJSj7 zeG@?@4(&D)IS4xaj4{K2|2t_v%$%rkZ1&(M5oJCaFI%N++EDM!9AL7=C_^!TVis1u zA)7=$?YOeV>d*SvBEeXlY?X-JZyMDWd;p^BwsY ztq&iEG!XzEL;d-PQ*weSh6GL$X*GPZkei|{enRDAO(KW&1CK4O@A@pVff@Q}XIvd~ z>LevTNHk_ksukDyM6CA9VaEvG`R2jzbYedgGdL!;86g!6>odg`N2}SnR)hELL?z)Q zkSvH}Hi!G`e91B_ubh~V?jKo>mex_B{0v-Qlb`kOFKymHbh=OgKv@c@L`n-ljs~Im zOlhr#KAuA;P-#OBUxjXsrZA+pqu}$eqY#(@V?dV_M$iLZs->dY&buPoLx#uM@_5{m zaVJdE@Np!Ps|?|yXM3l{u_+_$35*Z6i7Y?5jNr6FPe7TbMJg-G>}k{zsqJQJkvV3F zJc6yTvH33yF>P3UKC@w<6v*tEp@yxLeCEU4#!JPfKua zNz6hx0=u7=bkn|>dffDq@A(^qoX};i-jHw=I{$etl|b`U)DziLCB$pAt|2tgYWg${ zje=uPmhnAY`lxU^t z2hpzOYyor*``YvqPy=T1Wz4s42W-BAR0J6v&z$azk-HA_KG$=}NzJcOc|=S*aee@8T%?2TDbupI647g$22?UqJbqcB4{8xq|J$XTa1=RJYwgoNR* z0gNLe0ni+c5S#}2u!f>xPE|8PDc}$5CaY(H33CKV`D9K>VZdLiv^r09Qb2CYDs||r9ORolE4#&1S z_r=_^lc`d+8P*pa$ALp!6TTN4h$S%!YnlmsG^l1MY4aKk57h3A)_%7xs2zXt^gkI= zz3$(w9^9}b3%>#624Pcx@g;`*t-uMe7p9#iIjMjP%E1_Ve7qU;Y`FB->3+B{1te^$ zWC+bxfMa_CV7A!}POFNBx{8_BoXHe4&`~oy%B!Qwu4N{JL#;`NV|^PbZ~vdm^{^0`CvZ@^=h?KhfQ!D5044~lZnLTv0cXX8`3Hn9@#2dc4> z_~yg(W)R%%+5k*~dJ%tp2jiNKW~VN%LD*{$l(%VZYB(R9U%^1_PfKM;P~8^K%7ifx~M>KB!S9K=~9$tJpR4r|pzt)q_IpjDFk$wxBO>Fko8 z;*5?39s9ErsekqHb3d%A)?a*s@G7aNM(CBUXTb#C8p-vnv2w zTE5iXIi)>$h0@bG9uLmC3`NgG>kCNqw(h0-c#q(L!emm5Njr}A$Iia48<6vW!*K?j zYZAd}`DWFY@<4M`SD>cGqvr(H_8n|>^u_V%KrzudGWpgHScg{t1Wf!bbz(k5QU*VW z^|sG52He4+^Vcz{=)#o&`Jh=z@NFaeJbgJ@G@ZD2uVK^E0-$)9Et=`95Bc%JvVFv7 zB~)3H$CCp>>}rvno8VOc>M^@^glWG#Z*7rztwjZBrJdL{=5%3@c8WR5I~iyS6lh+Q zwU}OjHbZ~tO|c2LA9)v6xIR#U4hGkP)lG?zY3&=UEh+kSq#)Hy+$a(c%6jgBv5f7) zKIj(&71fEvyL$dg3@&`sTk_F($BC+n&#Utxka%{3D$?*#=(B?lubfFax{TBo}HZYVa=Z#Og$6EeQ*#U1X)2KyIq+(@@*MKmd))0;cmYC&S%`U7D~mJ$L% z!6usu-UX60j0=P2jcaQfesqwY+&}iBCLZW_c)n4p<}qKG2!bS{Z*-a$P?7v{;Mk6~ zlcEIKuMtmQe$6fBZ-h=G8gwI+hSt{prOnOxAKA1WWSu5D-Rs4lCQ~h4NRnoWL@Dt@0glRn&5l{=dvbzq5naAp4oxQ;%z4-ufY3MA9O`nEwH6u&& z0$Fq>fvv2EY3R;sUA7#W=Q`k_*~u_MtfnJ7L7IvN`JEHM+b* z*^euURIa{hfCp>#ltcj7JBLJq0 z)KuQ5rA5f(;J1?QOi5ST&+mjn(0Ky4=kfg=I5BV_4wJQoLA6Iqv7 zH3n1?8`MwzRs^x8FyeI0!==uoGQ7jf+Yk0eo_(YWptGme64`PeyAhx&$UqNOF2*?; zUGx-(K0U|{6U%)WDyE1=*G##F0Ks3DC4z1b9*6^VBwC*6G9sF&^I}7iXbg4bI|7MUQNl(G!vfjSlDnY!&D?2Sg8^K#0Gb;sEB2ZX>IvDd84iKRW z=mQ>Pw_TTmI1ynA%4!KyWC8df2uM}2(YGsNFl$`H`84@DSE1c!7F!fmDHUBO#3?>7 z!Bz;y(AY7whE(GnCxAWCxUBtB+k4LR12d zWs?zdubDodtoGu4Y-YRn09?#9FNY2%!r~pnF_=Y-@o%oHBYn z{{ciaI)N5Z%p1U>fImWBr(3Vb*yZ#tq^}$PRx+x zXbg)>iEkF3xGAcNC*=lV0$AfyAZUC&NOSeCmF?^fSd%ZCt@UAg#6p(#_FRc%3N(V! zOg@0!Eqfrm&Hj`P;tN#3Nt9E_19g6qG+rU22ZxZ)MXVBe?KTl2z68^hoIrBvORVjz?F_%GKE{b8jMY9 zzBX{X(01hwnWXKirbV`Gb*7z%~M>1ATIgYQ_>Uee1_Tqs(%A^`~VKqh1AXk2h81gZjx137#?LSeU@JpPldA6)&hq2IW{nI4?&>i4+*MhQQ|3PIb}&ZgJ#`v;ty4%km>_0=!oP=8bEcG4@{(uS+V9>xSAnf~cdrt*D_u|l@C1=ax zNrx>(&r_*>!j$L&=EffI__Uk_bk?kQ{+31y@LZqfH@2*0F+p!$7O5UCSU&7mPM3&a zLTp*G6R|T8GsLvYSdvGU)O2Fes>m{qE08{sMHLbyk!G>kYMfpTUrJ5&Wh?s2#N6*! zAPi%MXG#T>oMaY^>sAH`W3whPJ0_n4vPfFrU+V9nw5@%mQ6Z5{u#2j}61N=y2H-;_ ztbo^A123A+P;Uj8rZC_@FhxcPbHg5IFP&{{*Hl3L*nrg@2 zevRD(;~qv9&4WOaP_*irQGF4dEZPVuT~Y(XFNYDnDwyyA`1#hM<*9@0Iv`+weVjGkVgJ0Nmf3aa4;DVJSGWDlph z0O=NWO%00icR&;3vH$_TYQ+u?r0Xd8wK9k->QkNgf{h+d;Fq*g19_6JLxfjTKXW_j z(&x@9Kj4m+X9uDi|7^tMQ!4XObJSc*Ms-@W@Q?oVZ2uWY#$I z2!kDSk13O1?9O6$l?=&m)0p92FS9pDne*mJ)os_YYqsP0xj-O&ri9+BDCMB}?HmkH z%CM8Ve6alYa?lUepn9BQ)X#%Zv`&{Ubp?g9`mRJWGscG^maufWvUV$A$DaS;*c?qR zTVLTPw2Nb{I?Wbr^aC?8@%ip0rrC*=X(p_KEkqH&3MjSfGRI5p_0131p(4UYrU}hX zp1jP4s1#JzIWKg?rSU_`0WW6IAjdQ3TgtH>5{YzX7N(rF+AJFg6^xYmd@Q`OQ!4tc z$-UqAH*sbn5u2xYp_(zom!Eu9bwu!#}!)1QA(vVj(!9eFVjFZorO9 zEKM+YRjI|{L{h}z^Cjd_ktmrJPpVK#tD{oLfEZZN?#uLDmB;SNV~EJGg{oOm5+8Dt z_)D`+@Gl+XPHg`cSlxqXJu*f3)3EZ@ietCmBA8>JvSH%JT9U-4;qB8K`hpHWJ2er| zQ0@dkfyChPBmv13GgB`IQ+pDmgBDJ_nXF~0jL0NCy)7eaFhki1TQ%9-JoW9l(bCj6 z<1r7O)6>t*&SWRP>@qs-c6S@wF#QzqD{RXofdE%i1NEAs=i2|K<4LGk)S| zMmTp}ak#C^4`lhag=A6WVMX$eEBCWExCYc7?te@N$VUxvQ&;Mqx{PG7CPTWcILUV+LcvF*3gGY__ZI}& zdoFG0jv+KRE8Mwm;C#2tfwLLsWEmgjU&5|=R2i>|92nTW)ZX4+FbD{dcI%L z3VxPdO_+G#+SL@gqka>3s@(0@y912<3U}|kaQgI4!C+OF)3U08D#75DomFQ*k0|h} zyMg2W!81Ohh3>X=Envj`n zLws=O&bK08#|WTJNAz2kffi#+!i44Cze9ocA+<^BuCG4QdwC3M8wI=uoFMuy`G0}i zk(Uz9IqucDW{$_h%I~i^do7+s7?w1PdOQ3jenPb1q;hr$I_$FCY7NW6GO@$KQAS`* zfdg1^!czRC0rZ@=vFFY^Jq__wo@&rOP7xv1f6fRbsuoDCfK%5ZOexsKgB*H}J&nzD z$#(LDcNtN7(Ny1vYEevuA7cHVot=%&DqKIZY^jU6Yv!vhjUITU@gdG;geAEs!{_eP z?^mpWFm9<}+qlTD>0P zEVVCfCayFI|IynRz82o}1|5Cz<#xAMKdi0RSb8{Jg&l3k1Y>Icz=EdySuQb_o#E%N%B-{^+el@W zA2ve>=+#kNY}t@fbJQhx+He+G@qP}##R4=DVp?CO%JiG0$OrExBn2!L#g6Dt6{01-4)T*ea1kSK!q8? zmwj*UvsBoQ#}?l8H7+iZL{DSxX(D?1;@0Q_&}`p~X#GEYy?a~|X8S+>e72r#cHFFW zu*?pqGc`MSC{1zIN+Pl}&mmK16Yjo*+EHmZ?)y8={n` z%seHCWQfT5cVj(!_TB5XpRd=L>z{UCT=#W&zu(t&7b`S8#eNuUn|Tqhjw2-#5B7>! zh|h<>HP9sJ^{=M$|8r=V8~bNUqZ5p`fKx;`%1GrLvzOGvE8N(1r(H3f$1L0?pwwi=5&;REyzrEx3b3hJpZYPmdTSgkq;CJHE}yX8NJ3MnZQiSM%d zzS70EBON;FX>)H@L3DCihZQKU>&hiNoodJWIdeF!nvM!!Nmb%3P%(Xbaizf_@_$E) zwKq05=DAjmx(<68&|9t&y&JxwH?|z0Rx(Vcm`(xs0rUp|p1-;Nd(%MLj=l%zrLEP9 zT>9?<#ZKYkx3SDj4>jUT`rpW^=NWhgHzdw}AvU^JnJ9K@= z?%q?@D=R-^$u^w9~h{MiP0rUDp*;Qt{WU9b)=jT%GFBY zI{aXZ{#Q0S#3jKhGjYwuRYO&0yU6zqRq@_U6CLt@KRZ)wr(BG;ApmE~&hkaB!XWq!U>k5_5o zkt)nVL)UsuTVTVhi{H2z|1a;tHY6L5|AT&nwb+>d#TM>+YaT!Ten7SapbLX(!}85s z$vr#lTv3DUt7(H;6PE`myf`K&Qj_s-x59Xr+KP7E*(<{<8+1Ew{`&2<-}b4V-M%0? zI)o2By9<|mS1NouD|dME!s6h+*}7(>%gwbiTSQ;djXLi>d4#rcAE9$M%r$3aeWE-S z#;dy4VGWPwhbn!5Uvv{I`J`o_L7aA@5arjG8tx;( zl!Y3N^vl>^*Agt6?dNlg;OL`v>%F<`sJ0bED$yo05x25wru8W^S2^Bzi}0?ONc|M5vLSpnnJx5A@I7~Om8{I1 zEuESC20nL&YuR`!;?rv=Zrtm0H@y$Ir^~=mB0gG$N3ZG4U(_;$l`n7E5SFtX|(e55>aQIa+Bw|-4B#+GKzQK;y zz{UFz6#_BbUGz+?>YlvH{hB-7m>tJ{%RQ7@Xqips>xpS1JK9XwMZg|Z zy+c%SSaCxtB6YQOQIh4Zu5cq){-hQ04Pn@%+OCU;afJ{BxPRWBb$$tWVv+{ud z@y~5@$kUgT5}gp+!K5?+BXVw}pg8E5FgNGT9S2gM+})MhUXpz{I-^(+njA55(YM}} z6R!!fTk*-mT=j6Pf)lQEVWc0nc&l0hr&vS*S0W)j164~Fws<6r?w~Tf{vdM!Q3v0@j=y2ErPNVlHnU?=C zL*aeqoJJnoKv@0}2|s0S7kc2+>xK5oCk_;xKx!u*UvRA;N3%}T6fD0=n=el zFC7G4VZf?RzX(iyv&GGt^qCplG&5HQhBV|a;-b`~L9(mMz(Os%i|Cb?=e?!_QNW+y zLyLJFRi>vaS{W#X_U=n;Sx1FYQ1q|ttiOmu7LWf!(IVINvlZp}Y0{GgkZy<&+-Ste zq#JZ08#47vg!h*ne&Dr(%d_I>>sMuyk>Mtd!*zn8uU2euAbE;alAw>KI4viK#ZL0P zINMl3pJLXpUli{f_M*I68A--t{3MxCYCIUMU`x7hoK?;Y5vfA`A9)a10b~Ep6_87t z8^u3f;&s`;J?bdrvM&>oBks6UO{ZQvb`A)cq#&>C9U&8(38dfD(;Rxb0l zC%M(sE5QFCaiW$LB3{_#%*9N}K0z29rKlsS`1$^j4iMfjxai@ssXGYv4es%GYEB>Zswi#t%BYa<- zu8Qj0yl~KBtQ*drI*2aQXwUU3#D$Zu8iPs82i8y$Q!mO=c%JS|kzDy}<6SEjcPy)h zua+I(Rq^vcw#YiIs=CRz|-0{5zm!ftxy~!5N z-xSa=4vsx;#hUjM5kopB=IEn8jP<9|nPma*BZS53hB!at9a#*fTSRX~PZzh}EFN?5 zb)XuPCK+TXv0K{BOBzCd*l76dGp6|_6UaO;D$LuOzat027w9naTf~f z4trA|(V9%}UvC(r0>`F5E+JuSRREEc*BscwR?YdFdX-gGg~6zuom)4UP9BMmF(ZaZ zXs+C6Vp=L^T|+21Kba}+sW6H!{(tX>XKK$-@|rAyLO>{atg9zzL`#KipPXOfdpG&` zLez}%p`$~LNJZNn%UgYZq&4E86!=$)jE6}aZrldSVR6o7%D&X&#JM*k*4_8^KCfU6 zi<4m+MpvIdB-ZW{r^NUaGxKKUbnk6-W4}jyddMANc{|u$&bqAXV#H*WhL&rcL~83R z@%vaHAh>n=NLXvyMcOWcC2Zhv*h5IvXzSbF#_5owmN0`1USthZza8~HMl6y?U~KQ) zu*^6SEiSARPEQZ!}{jvF8 z#@JK-=}#y#Kg4@MkXwqCv#(fYuSO3ttu!Q##+iB_((dv|?=~l)}lsaPAiLS?>g2IT#cLElsbXWQyyq481D2F6PQ;sLOXCUs3 zl;rAf)di|tIPt{2ivt!&!?5T`UtBM}9D1i+>adtZ+AE*|Gdd%p?rHH? zGJeq(FZM2)hhID1fZDbKvet|eyS_JRn{Tw)A)$?_SB{#42nr7sk~Rn1#ma)7z=?^% zr-g@Z<;_mEwWb^wjy9CVYi#7cWPTEBzT2H!=0jT5>9)&Hiitf;um+S>wWKWGnhZbc}?7q~YUX z8nl3eAkHl;dzzdOupGXnF8RW{@4RMP*dQLBjf*REe9;pgvHBZqPKfSaV1Pga970h$ zgc_hj>xTJiGAY$yJmZUV%>>Ev#nb-z@gZyeup0hZ!(!>#$wKEs&_OCPWNIOgy9GAD zB_ChNTIG>AaW8D(#2?2H5qIx6n(&SGh&|vK36cRm@ASjajd_~2%?omq`$_47EXlGq zT=k=Ku%|-Sm3Y0@opp`s6QL1q79n$m-uaY)-vvsNX3%evWv_Jid+Bkp@84IXrzNN_ zdD4E2i4+5)wh9uM=?hV?M+FR{I6SE=b?6T&7~vS8-MeleG&MO; z_}5u(;8aHW6i?0(@duF;wE@4I{mzGkq_*m3o*i_QMf&q-ujT-26~$H#>xXJ}E& z{d%p#1(m5D4y2%j@bf-b=hprz9L+45!-rw;xlVFemd) zvvqd;gx$e79AyllIrNRn${AHFs+7S`6#}<4`oN2$&4e2( z7ro)nj}JHLO-1$P=7OX_aC7RmL)I1n5P(RnO^{Jw}gSG`#-5sBg7GJ-9bZevu0OS0e&$rI9@8`LFdyEi8(>$OUs} z2Z~Vf#q%x`c}Y}`Lvvc$WP(FIia3|C-QY(|oE{0+SPXA8wGzHw?IqRsb9XdO+6wgM zFrJ)K#XiZP2l_k`VWuzIec?!gnAwW3B+tu_q0G|e1=@j!udpWpFHmDCtDN=6;A ztmE$H)^1neHVlW52`W8`^oc3-mis1NGq_QxuLO4#l}j^nv67m1NqUKgQVD_epb%S- zfq~f&^vlPmh_x3Y7NTOgDMOM_>lJfu5-2EHC24-Eoiz`pmhgrek~PSGGqYsraSK94 zXZNz(gCx)3v&8-yKC`oMdqWn8GT7CaFZgKI;A{|!yPy^q$y5@*Z$650^AY7mm2vM5 zsvCB&hKyGE8UBy4rUe-2-5UTRc@gI_Z(X5GBy*gtVZj#-A79Z$#;?we_x(J+ce{@S z)Id^@sM+D834FU#(p%8Eqdd#4~BXJw~dv=9Hfh?ej0HP+;hG+{iCUjRos)rxo1sVk-JD+T$4|E zMb+xAL6xURp6rhw^BO7LpIZ9_EiWi8-T=Syj9r)eAiuuIo0r<}FT@T_$1WsW7D&7) zjQ%)u{v9WqI<5lr%8c^MkS@B^KlxrTl$KVMClrzC+_-pKo}+@}Q->r3j5Cdc;{QrC z`Kv<3_$U8zUmPNNQxUk0=bkLux&rdCdI?XYewO#N2db0rom{?`K1Ll}b9r#?KSme) z2ADe8H+;1Are#LS^}ZPSkKR_9mRYUSAdQ<5zl(0C;*3zm017;pvoK#`-qvjDP3v#9{UJ+!BDB??VS$SYT2CYicfP22E}bD$SOrG9Tq4!(w7vOaQ2ldCvIT1mrg@V z!-GmJs&yz%uM>dwnM@}PO8b*(GPI8xPG?HIbJIk|bHA|shZ62*mfaUq|7%&iOttTE zHYHI;`h<8C6Y|72diNJLF8|)@(zLZsKbR_cr`$iIF1>oaZ{pP{ghcXcFGoGLalliDq8K;Njwq}FSN&oI&rvs zClg6fv~auwtzibG1<_|aI;w4VBgtx#7ot(xz#Op0-kX>QDH&*Dr02y=eSN2!*aBFt zdXPPkx`?Hn|M(wV<8EqX`%#kTVwi2qA5TBvB-j@v(UW( zHTuz8n{753CI$tTuxn7w=`e29yM|=h{I%#=`9sU=!B5{T0!bmf^Nc}A7i0UST6Y>c z&z2<>o=qURx7At$NCcC?REG%a`r_E5j&)o|KTL?UKLF9hy3pAqJA-y-MQIin=zhED zs-f~rqXYcq=Wejk7k=pOKsdfzEJ}@VGm#oosYxSJKfd+l>ZXBXhdU6^-w>EbA%r+w zNnBH?ukzAt2Tn#KlTmh;_|}>Ih%JhFJ1}G=Tst#&t-98!(#ev=-Q~UI8#^1m%q2<7 zr}+}8uU=)V>#9vn-MlF)HPX_mcYZlv+5cZ+uT$GHjVMVQuvCauseTvl_NPdp08|{A z9F{K|Z=`1wJ9}4ztYah_!O+9x>Lhd;-mZbWhbAStRjTzq0Ya(Aqqz59KPY3b9{$Y{ zT^BO5uS@EHm9Q>Ebr(Um!-9io{c&vNPykkxcTQTAS~#dA1!EY4n(n^-#kBIvz7+=4 z-oMzz`0K8^#Xwq^OFp02o3#-F%fkqFtbqIrpCGyhfr%CZ7gQmX1)l{~DS?xE_LR{l zraq-jt?)_PMf`}_Qw%RFN#dx}uxa83Y1s%P|; z{MrhYeLx%`D!S-VngycohNFi~Vi)${@U)W-hz1U)H& z=UIKO*MwTsH<<%l6^i{jOc=|qy!&>u?YR!3W9NXSpHTjQz{umie(-c22rmwY32kFo zckAW(0sW}wGeZC=k9s=MR=?;@)-8i)ytamh?kw5rT~?x=exec9u1_{rGxfR_Le1Sk zHQRfWLbN5O|1##DQ;Z$EF1Vqu39|&;KlD)o9*LF6;}-)ATbm$gvLGx@r5}GV!oBb} zqkgFV68-xQZ-?t|Sn2?ZzpM-jb%43*#~(KloLF7Vhvv8p6) z;Gl1Ps_3^I&9JXuAu7IQqSSra)|A?t-h1i}^I|F+s!lQ(%n8;RBT7&NKnGUnk}AGE zS5%JN$YX}X?gNAwmA6p4(^kY!D<}xDhPkHffh4Kb;py8VZ(3dg46fZ&6`d|01u1Lb z=RN|6zFQrWprpX)@(2fI3TP8c249wc0 zIHOTdw!Afb`9G5Uy`6m*A2ECpSb1jWoED`?VLPp`bj=Xg&rIo z7N7)AWXZf|#Df5k21W9nia@ixjN){^KECD{0xr+EgY7F693N73nI5svNCd%O|y zh$mAhy93enQ}DF!4_LWm(CoqWMi)EZ{nKo$iW%*g>M-vv?#5PFqK3JPJH-5aVt3Dk zd%>snY)8`Jfj(6QnyteIPtXFzBx9`{Bqn(`U(c2|EAF`X<#?Ax8x1QY9<|TlHyT!X*u&J#&;^iJW~I#9HKu1e$2^qOo2*T= zh`O?PQT|j&!+164L_={EW6&gMxP6 zxzS$1wWmqZU<)I22Fe;{7JDQ!7_7xrJoxqcg3sT3;h&$!!8QWW-1%Q-b~pzmOt+C(rMSAlXH?B}*GQ zkJ0HVl~bxN>&e`xdi{lVDF&-iKDtvJry6Av&YnGD=Jm>0H`H$>wMKUMu#ea)nw&uS z=Q}~qDtmdcT0V){Z?yupuqk&DDcD)oBcfPlbmJ@`-^UGaGId(D=_{)pZQTXTB|aL} zgoQ2?#sl&4GGvM(Qs2JBJ7=umU5_@jjCmxB_w7YwvNmCJR+N4-(*Q>}Puof)I4Oo! z-qbzMdJ(4=K8*hHe5^1Jb8KcGyl{KPF#iHMSVr|iE148G1qU&sYZE&(#7#F|uxa3) zig}-!|2P9u^T9u@_Wqaure=D<+jB5nh(E^)mfAgU@xA4bDmY7pJTz{#yUx-@@vV=~ zM)B}b0cB%UyeN%PFF%cRu2e0Fq?`=Swan=*RK~)1F`?$BQV)H*H=GEbj^etXOijFt zD){2Ry?+eo{VUP~dU-yg5MNnYMUp&&G+GUK8Y8oJs3Fht$KW3y<<>}5T-CkDI%xBO zI>RB#zJzY}f~2o+Ub`j@6!Krsf+Tsxn5f;iYuxHn1jiAJvb%;(FnA zR7Lr{_3B%>Zdmc@5elaoOWVOM!nUXbD$eW5{A;JkrFGz+p4d`wwGWsNrxh6)dYgaq z^Mr|A7tr++7p0oV@(IlT5>-f6;j5W?VvQTSH2ja%k9z~H!jP&l>ojLG za1DX`d;8`$xooT~^``U#4!=k1mN;$ETZbu#niS<2N-M3JC~De?2-Ux^fDvcdnw11EV(qyRfZ>b_na9f79};V2 zzusEc@d_W&rgYexP2Ec?t&;m9gxctg7|>d$JYx#VZS;szv~ae!^qO^Kp@+HNY1kTk zC3fqWZCx`2=|J{+W@Gx(+`GrCloKuemjK%R5-a$VcYk&sv^N!a!AUu5Q;vU*mt~YO zn?>(=^HrdGq<|GKVmUpBQrxNlO+WqZz8(r@+#bu%vKUSa1yBQX(%LXQ{O)1p9Y~Yv zC^vvOr-v@oLZ)gcDG%Pt-zU8u+(ZnKiqXs95ZI~%-*f4|;bux&+ac?ff#{H#hP^d4 z3A|q#ZdP3Qth{gnY+Q}Iw*Psh4j~s=S{6|bXb0=*JRl_-fAynVR0Muow$QEbCh8^?-+5Vxhn+bnmYF%`gx7Y`s?U} zsDM|S^6Fb(g4aL$a|%4gTtvC<+}X2B0SyF&rc@8G;C-46F7QJx{rH@2f-g0z;dFmo zKY?D-uF)`J27988;6#xE2RA}+Ze8aiKeX~C&flHDdseha`2BU{V$t0_4T}MOm_VtP2UcvnUFa_@?0*GyX$_l~0N!iHqx zSs^(UL$gVsr4u9RC8o!uu8W-MJrv0^RkbRe0-5?P8Rt)|ok5^-Kj~&2=B+Qo^!DB7 zk}N4%(Rg|XmsM{i!#F{;`l!9LH>oP+-J<4)l@bpSP1=z?w5}S``BV_H8HZ2B;sL9;Y#HcSS8Q}X zMs$u_4kavHBLtceTgQD_;5=uOoT<+z>f502uLujRf^=m<<^ORU!{6jO*q-Y-Me>Xem-8Q~l>Q`7v%OF* z`*Bn4nt{sWAwBLeFJ5`ugjYxoI?brVhznL>zA)JP7D3GLSngTGc~*|~p$3)Hwt4%U zXdjM^Pq9_hwnqh4B0lS6K(PlwKyeE&3Xy#KonJIK(j>dwZI;9$L&cUzW7$fH) z;ys{tiec(=U0}pe{m|C`!!$?7KeGG}eqP=JIRIbpo;v3h#syDmPqQd)$urqksR?~f zGlzd0)bFv8KYJpqKm%ZbQCDCY7X0I++J0nz2hq(J&6d%g&i`6=@O7g%?|^o?=S!x2 z5FcFJZBfVVX8E-W^YhX;1!_TSZ3z?U`)ig$Bf24N3}!)B!>22k8&=}SOWt}wu?tW5 zuM@mYi7O=eq$NI-<XVbsIOpZRcM zKHQA@VUZ6-n5a_;iNYCLy`Cdx77&K(7dOSc`Q#t%SoNJd{JA_Mxz%*mi1`w{wgp9v z#rG~vS6`x~4!u-8^jGM^2kJ3n?Kl}bT>jmTf&jwoB;KDm_Zq&_W)pN?nmsdTp{FR} z#H3Iq>!}`dMQ33cD}}(01^}e*-A|Y^?t34rQrdd7gryo#$?ryVjnbyzw0KP?_4#TL zwwX?fVY{xk)B5m_CaBeiJNJ0}-n;N!&s~IIjjuAx96Sd0KtQ+#i5dzh0{!vAC5JCN zfLz>An9 zeZo1}U30m?pkOHy7tFv$II37&O1l~-$%xkYL1Zk%Aq^eOL&t#mtRCgf4^l6f^Lr*28n^#F^t1VKF z-algjF7kUNS84w7vhS+uAj+R(^e>8u)Xsp_(?!ZrH)O`QdLH_Ulu4vy zTf0cNxS+QNh;=NS$jB}ioV7U^)4xX6RvMsM!|*M=u46<;_eNIYiy>1FEp(4S%pEX2 z(rN0InJWbK@gn_vWi-@R?nd(i5~AS9(F0)WdyV`1Uhvs>bn-7zup-iQ3IIef$H8+@ z2~Bwzz-egpFG8(D=RlA2hhJGcHLH&>{q02zs1~B5i|CU5-cZo2yc)G2L2%la-w>%N zO|!x8t98BoIBz1rF$dWX%DR~$fgu%5{{E!mOVpDE%Q8hW;VVMJMNWD^@jUBHq^@o{ zgf*=_B@qt{I1f}5RbMz+GP7@1(dSMGUPxNc;wNFmBJ+3()Cfc`7CHaV!0V!KzSpOP7{dTa^lJPVYNaL89!|G0s#qdN}z0$-fLX;Q^Sx6UpoPquPP z>nGc&CH^W6t&?by2N?TlmTKXBE>gXcn-qJT8inTqj@t?MGZ3xL2VY2y~hh(`XkaC;bVOc$gMRD^Gv?t8$G*heTgHsJG_ z6DII2?z8Qyyoj91mYzHaZsv9+&~BP)!j*d~7*TyMbaH zy)5~dyY~rk_28YK2Jc)s<0peAQT%$8;ezJx;5bp}5CoAU#MtG(Fg*2Y6J9^ z5X-D&d^(|Bw$mQ@4N zqji72hqW~}D6Zq{xQ>HJJw8FA6qN0F-}0oP!S=Aaxfc&aPItWbC^SHgdn9VhNTQL! z{mu2{+2*U6L~2*TA=9Z#ACIUb)f^7Bq;u<=;A3QqNvwujh-oisTgkBcp?<7qPYCO( z>W>%qv)44ve7ZU36XKCf@1=?iD(Q?Fe66CrIEmvBP!i|n)HR?(5L5YB#5}P_!x3KS#2e*XR~(+ z>>Sqh=2-jn>fFDCk%4w-_Pwzbh!9x?kPXG@j4oxh>>ucr^T^bXraoCzB~t(}@irm= z4vy%xrEn+P=2LX3U9BG>uIczzLkCiQ??Ot{p5x~?ZpLYh2A3{AOkz7kuh{{qHy=^=a#LjKJi zm-xi}f^riFIlpFK%fyg^pEvkGPy_W)eco zJyhE=kpY`Z#*TLwpK}+Ak4Di!Y6_OH93R2mOcSzu)BF`LRCgv)wdB!Jy`R1O8^f zjK&#JO7+W4GcY}#5n)}%BJg85$0$NP9Bp@-pXUO}E~!#_xU3^CEdwgsLA(HqE~XY| z2?mwp+{$nOKUl4RT-iC)7;5IV#2(J8mD^>^9e?*G`st(njV{z}!6{_|aaF22YS{W- z>$8a))kztJ0l7%7_<*tlaUV6TZJmUF-2RZlT|iuk$9)^oQdxnwyXX2PvtsboT~R+f>xKhI+Mn z5Gj~Xi=pfJ66!D^8fUcGk-u&`TQuSaL2E4o$Tp1HZwM>|_4sShB()ghf7KG+8Fst( zo07phm-&gG^d{-nR}L!C>BoYHfPi}DA){LHEAbn&`&&SECk}xdK68I&t1# zGNtvr<3@+OkF(3*1O17Aw{>=Fw|B0qh>zIfL^`Y{N${-}GkNdxTHB_qjWiQ~-J~rfev_Ey`C{ zVo&Q4DJEy=d}U<3sGyQNqtL3beHA^Oi{f9;y;ltrtN-h0AO8J;IjFC`ykEA+0fWMA z*n)T!(h)>F)9bUE@&e7C`V3vVm)Z{~&(Gq8hPkP?l{jqgPw|p2zhvB7*h6Q7gHZ*G zYV8)*?JeJXjWg#57 zyU`&C2W&Zl%m?2mP3mFe<2&B4lOPF$LveM zYbK|^-CEc=-x<0ZAGZt&IP%`y&#atMOdjSIWW7joJrn{E6k&4z3{85T2Cu2vDlLmn zJt@}29UD??Z6(6cc%|0$bw}JEo3<* zLD}+eqCcVm(V`VlqAEAKZH8CfEdEbxhu}7u`fC1eOh`a4Nq7YO9T%*lPTb(9>kmUBbGpJEcLNnZ#SDbWKDm zL2(F}3NKlWS_(DH^(-5=PwBQZdI<*rufS=JA ztigsY`Kd}ZY<*)O^@567aV5UUGCNe;2vQ+IF63^94X^^wtkb&QE-RDVR21+N*_@tr zknEKK&YR3%Y=V2} z+Dh04SZ9&<@=VK&0sLsMG(G;2XnwrS2Fr*^dtO&jmM}!UTd*wQmv`}A`-_qg3MG^1 z*sv2@)S2rRS|D~|i#^(?gDyYPWe&C=aZ)QvOhTSTgh_NCLu#l?VIw~H;Per9>R zbTDxVJkqP_L^S;ns9A-zI0FtO3H}&Ic^a5(9lVH%4HINN&RTB^Vuu5ah!)TB$^&hD9(DtxWxt+j%3RkvTj+-d8@Q{$<7ExvZ+^ZBDT@F z593ojOb{xElF>~peri{(z@h>FD#d69`d_zdE!yRSlD;CwHH>l7^2HFg`4$YwGAI|P zZGhIzW8sD8)DwnP^VVC%8=vu3b&Qp4r}hi)Fhm4VammhcaPlfem{CM3I9Vlk4_WsC zGESThX?fPK=vfJ40KGo|ia!(H2oqWt_V@K+Th%u#zZjSYYLRCLP6kDXe@~~6ru&Fc zLBzAZ%)xb>b(!8<>YnjVRYCYhUm_MMGrNdX0lwt!&(lGvgHNCS2#IRGnr)}ffvR$N zzg#Q?r8oq@%y{Jb5bKiNFh{@WJ*d9jlL+zp<4!c-LfgUnv*L@3ij?F=HQra5s@K+w z`zOcyZ#e=Bfq9*WjK%SkJevk1ef~qjKg}Cdl#xFd)K)k=`9%hzMId5Z1-;DV!ug|d zI}XO}IK(ho1#5rFF3` z)?80<&^DUoE%jkuN$lWy(?gj+a!!0xf7AhxIl5L>^X=_nnt>R?LBJ&=Ypk9tJ3HGx zJ@#;EYb=?M$vMLoInzY7Y=v1!NM@a=7LHDCX2FUs^dwZx`qWuG>#n3nyYEH|z%jYt zn3chpX|-R^tqdfKKBxwr+Yg+7K4<|rD8st(en`CU7xBIu;+=2?Y~^InQFodRs!DlU zfqT|%QO8%bSZC-T7T|-4bN$@evoPNMVu$5-JVJ)EJV|?a35$fmI@bjput?rGlsXr+5KnJ!AKk!@ode~Ecu=7;%)_VWlDWV7Am=c z#JTB!D=Dfszgrh?Riruh>ISciIYFcER=Rf{tw4B!i#KHVNkk@@jR%^nQ!7Qn6}xmBb$?%-9Mejq%Tx zI%jfWQ9iW;rjsQ8yn;>p?4ei&Y{dd2P|wEtMak&m^hIk~XOk?=$i>&z>KONdD1msi zi}UFX0YJ`;fp*&A&_`1jgP@q`qHX3CMF2Z@z~j7@8>M{j4$O|M^CI@Ur=GfhuS#M@ zS)OY3b)pjxFF#FQh_~0F`Te}O+cA3F>%W>Eg)n(h=g=Doe zxnLQsy|XiHdUVihOIL5-EZJ>1o-6f{e7GEK-&ZBs`?7{`?${osRv{Lr8Cxk&)IZD{ z{LtO0lgve3Xm8oNTS7#POg_8?{Q|#vCA6%1N#&j#VywW49rYPo*CbOYks>gn9A_HU zclZ#ThaV{c6AyT0GCqJeW@ zhF0DSAYqhs4U5Q5_jM-YI@?dh~;CC=fV_ZPaM8Pm}Z!Wi|^FZa5+S+A%qr3g=c zC*><=$@H>Or{uJLVCn_enTB8HNbQlv7y2UST2!4p|wm{w;e86)S5|L0-H z#hdgY@5k9=$%Eq zHP22G2CXyH`r5Ny&&542;%sg24|Vvcv={51orHg0_uWbO(uxkoXwEmdJyRoTJ*%L~ zt0^UPgy8ZL--L^pCnu1gSeA6&RglSh1r^J1%4Zqjlp=q&^eiCN+XiTrqjfgOjg{=t z3L2*2G?HuJL>n7QfKNDED)q*g$}rQ1{2kHxP|;4-=>$_~<6y`#p^Nm%{l`tlIYuc^ z6@1A|Kpd+!7q=sPe>2CR1t`C1k2XKUquN~NnwXwbvoab@EwKWlH^(0sHayF3gc#S)yWSuQ$y2;5Y)ZT_4c<_zdzO4Oz zMh3-Wgdg~n=53exDqiG!MY=d=&FGl8(Uc~$2SM8P^vkULJE{@{a$^kwR%n~qm5)T) z`sCJyyb2DV3?c08$FGk&1N5NEkonLC;6qNJ5weoH_cakPyrNQv0X)XYC=Z{ZDUA;} zBo4h5y*9?!zx;d{XmhQUa!+6iytg?mk}CGM8Fp;O4q{2YjSFIHa-*V2&&+g1+gQ~N z6-3MU>L#!&-=I@}mU zO#H*MPIiQ|tS6YYlgcaFH(LvJ%q5d;8%XD0I>#gz+<4D8t!xhB-pCXT;>~k3=v_AJ zD@SvM7Nx}^EJ7%&kp5Q}ZuAK5--ZqT^x0U;Be~}T zb19Q(w~0STGnQ%`*b5IH8)jeQ9Z26Jb1PN@56>um*aF04I>6#bOodfJeh*XuV;f^> z*GSVO>|@x2w#_RQU0v9n)ZppFdpKsON6}iwhWk{jUisrz;1J>H)hH{GSR_ce2K1^XVrzL zujA$CiZnp&CewGzj!k+kl-s(DI4ZQZj3++CxnDk3Y7QNm zMJD?jGnV*Xkkci{Bwdus86GJmsxx`Xw3u%gj5%STm@P%sSk;0xE25oun$JI*`1Qin zF>awFTh=w;u5e|`?2W|)Atat+)TzBO`v*eshvR62Q8Pj_vw^Zj{L>NKHk!93NYc)tIj62&xdaRo2hssP&kgmgwaoGox!$DM zNb18}lXeYKEU%LnL*hJ`ngCbf%PgU;LS%~PEcED!kf|5r&Eo8M^Y3e$Dq!FaT8XKjJQt#%)5 zQPzfJZsA(akc9aV%4O6mQqTes>19FyuIQx^m;43nLt3-wI)8qA=+u5Yt*God+G3p@ z{O)|;*nT*vW^8{1ENM~CP((gFdHduQ=dlvcTKC}s9_w&32nqwoa&K6gwZ7DHW6s^> z>h$z^yK*bvN~_yu@UNPT^YZ%j1v25WEsCk&655=7PsilE8^tqPU>?AgxTaM)$AO{t zC#KEg92aP){i|N|BrpJ$Pi9JHV{8J`12W*vI28`d>F1MGn;YCQc`U zcaMartuG%E;~xg5jd!Q?K8SmVX4LEY2xWImxRL4XJvdGBbw;PT46Csx{|*}C20fz_ zZDdBi1%{4cecy=zoEtF}jOSL3 zR_TXMtNm}vlCgz_7;$mO{YP=!P8_CcR=oO{dq5_B*Z%YT@YzMBOs-Oy@b0_Wjja|K zaY)JWXzn4m_%=;#R}EJ9P&!$e#s!Ome2qOy+v%ptQ+;3$i3aRs`PYE6mJs)xEbTSvWvXZ^v+5Y%c7G}QH}hon)E6{`a|M{_VAmIU2Desz z?DxtwOmgIAmvT`62x`jFKjwu5Ut(=oGZ@Ee%^WGM(p3_4lH#p8M^b%cy6QqqG-u0@ ztv9I6a@2ZyRseiy9at+7%C*$m!PRr!MW{39x~D7ikGn#-LBv`;h4A1p*Ulza)==Z4 z2}P-lA*;EvysTuWcZZ9A2)IOicH98KVk^ji=TJ$4p|@}~3-3aOI*&TheI#v^Bh`~^ z6>NmCM>MZ1?MDHfKelW~8G(O9mktc#>H80q(7%F78o}F06KX4QJiYo2zQe`p81b4Tswh-9v&F&hsQb(xp#VRe~vRyjlpp{i9iH@Z^U_o09?rH%caMoGMLg znMv@OC_6)wBg>I=x?9|$CcD9IYHurQ@@>=qN7%c^C4Kh)v>rDWq4cr(*^rr`uNZWF+;i2WoeNmcN#jz zS;n4eh-Q%C9B47XHtT>hsRKqDOGvNo*xz(BeJyg*I=V&I23h~eA77*~n-7zKUxD64 zV9~LAxz5t)fIY)!X=y}v_fA^1RB8Faf+N}Mr7Cf+uvJ@}9s1nt<9TT}_m?87qiqP~ zh;A3n0A-XTJ}kB0g{EZ-u0=kD3N2S_&=7jrWQieW&tuk0B`tGy0s#ODpM)3pGEaD% z1n_EIK(AJJHDl1bm9XDw!F0APhJhGdiz6H%kNt5sc`rGMX&TR&_RBOuhfe-(gFmqD z_Sg@~xlTYmR1kQMwE;Jnt(}a~-63BD;%iRo7ScS0C3TPP4q?-`&_Lbh6O{!Dz*fop z?I6B3PBuvaVsYIhjO*-LXrb!{$Jmp&)o*2Gd`_o3BE|ZL3K3jG!6OZ~{8M-O16wVf zbaGR`>d<=k!Pd*r@Os8mLG zznm@(@o_r4?aV5~Lkhzybl*!=#IB(@_bOFfY@)K-w2r(T@M!XGi&qgU%4tz1bFQk< zjC}OW({ykdTK)j{>svPEEWR_gGn2$Qz-(Q2t#yE(PbiYPbb6t_Qm#Sjmk!_Tw9+IR zK>yXBPi$I@>&-D0Rf43ApuMRY>y$ZT1qaPz)tiE=oL>SBg0vB4%J^Vl{)v-&{M)tR z9zP%YjNnbr;)*KroLk@i2k#rgDa)dzkv88qy1^vY_gJisV{vdW=8li3pKkd&samT6 zv~Z2W9p>iRdTxS=RKoVH-)2xRAFj&_%%z9i@R&M$KkkOd7kGdZI`qqQ19GO(O4d|Y z)pp*iDgR45v0UOQ(f2J?CxQkfw_qq`p1H_(w>>Tq<2~y0QgOrN7ekC1sPHQ+!Y6t+ zaDnA7kSHrJj!e7|P2#lh_cbqqJ5yyx&Jh!ihu=Oz^PrVEY+-V2EL_A7IT$GvMDZh{ z)j)qmJ{cFPV5JD}t<)B-Zf&BocdgBXBJtcAf)qOuw()_4+8x!}E?0C!DPetnn)(c` zpjW<5QS@h%0dr^#CZ_sC+pc)2f}^P6IT{2m!QB5qAOV1h=jfYd^1`j=Xnv{q$%!T` z4la0|RRU-+k}EU-4o4&@mSB2pGuOooLy3mDruRF0CN{zN&Fw z?StR~8TJZ)D{M7oR^h_&L<1#dq=jOvCce#lN~)fC&kAyLowmv5%FqkF3z`JTsG~k` zBm;K5e6ZRzvRi8!qAtG-tkK-c>K;&hVFPuZ)qj|p*G*}=c3s>Gg-8O2ypz)kFmphhgnU1K@ zsFNQUhz~~+)@(MH?8F=5Tt|1iS0F{{aujAclH!Ed>X^GiY_IXnF2)=d)md`3lOtYN zJGgEcmbG?;BMIC{?0?p5-tXtc_84+Gknv*PX4d81QAUl6Hf3AV)-?#5lgaXtYz3**zZQ?JX;kXpI4WZulJN`Mk6XSClL%YC0}= zccT>ddl~?8xf0EW>x;n<*1Fn#j(Cus7PylzepTW(NFmx+N4trcma_ z(|%yn==&NUxXmVndgVZgSqq}Me32C;hEr<5aq|^fxp9x}wt(fiTyeK28Bp>de4*La z#RRf#C=%Jr2JN;>Yv^7fKu_9Olt*KR>de(}&Hw%91ALhT7?Uqepi+^$JKi4zdH#nl3tso(OD zAkJE4(r+av4$!`44^sb9L4%&%w0OtgwwDmZ>^PNVnEgJs*^RXV!1`u?Tf1;2LMW-`;v>_bSA5P>D?+0bY+`!bd z)A8y*uvv@U;U9jQ^j-E1^sdV=u3(z}SlMjgRP^Aly!wW7QvygJDsmD4#xAULdSPyRS&X=5Gx>)1WnOY;#FdU$~tQSWQTUrxE3sFc7asU!5__Y*yF05A^i0I zb3Omqks(}GCY@a2s}=7%ic<&TVB*7jN$hLIAkq5nZ<4$DmtZRI;MQaoPcc#ix`RCm zE`*m$zXLD|vuq}>(ED**+?(es1D(ELi09us?%TkR4dE6PXXQ&Lp+fF&lvc4sOR#}! z6I)4U?b1E!I3QQSjQ$BgDP*+j4CXr(r~QmFo%;^;O}%sqcw59$BIc~?Am3Ke2n zY`5Z-mdW*K3}kEn)DZpcq_q<^9sVemU2$!_DSWh2`y0C^9d5vQ4YBc-K7%oj_^`D( zKF7MxwJc6RNyrU(+UN}9=v=;HU{c}X<|@zI3j%3<9=O;@b&iadsdkzwdyzLcGiwf- z$_k8g>mSeLs|Dpuy5nJ0%chcSH4inK)Y@RDqf*vCdQJ6`2*jBi#X2=`Dv9N+9O&VX8B^oGW6*AVsm zqr6$MI)k9&qSbe&=;$oFOzLK(K;|Osk$8W>UrgLXR*& z6rbj>`7;4--D$hxQf`cABPDljKRpCn%|B$BiITKbV*_KL?H*80PWnVt(t5Eb`zjH&0?&~x0WYLK0K ztP(PRD3S+owq6l`aWQSnkaI5H&vw>XyHYiu*-rG@SPYzXcMqoZ# z#Kj3i@DKAJ6GHhqieLojgk}bcRulIpnEXbqSeCkeSsFnTQ|hEjQ>4R#_+- znxBySqL*@D@A~L}dt6mn7`m|hhv;r3QdIF21)7GuwQ<#;ja`E=5YZO`sf(_>` zYUnx>vA^vd*DIP?;6eHKpP#c|p^m}7_w!*lm2+37PMpM!6CMuy6LqkAj8xmptOmPx zROH(t5uentKt)#4l=vZ3^hu4me_Og{-P@cu0#eeJDp7ywB=IA6@-eAV{pkEd&CY31 zmdzGgc8`JiXNP+YAkw``BF^wVtvGo^GdR_)$sxE(c6n<&ySmkF{DBB%W>L0 zg~ogm=2qvV?`n=^duvc!_g^WLT2f>0gysUFk+g<*poJ7hTwL8dW${$G?V-&!8fh5d zDVq5x(?&B5C$K(;xuitHf2frKpBhe3<-IxH-xLw~wi4;@RYTA?Cx|Oi8hxczhioDm zu6d(S#;DP)@GM*V0h~bB^JRdt zSoZ-_>*hO|d((Ds0g$pvKm4QZfowE3^-6;@ng#z7fgI3Q8K=PHoS&=#OxP5B(CGuY z2PJ|BMsD!QTwH;03AZlU{IGMgumBAPvF~!v^I8v4A`FlB>*Td86fFYp+t~x-9Abvm zfnKoakgh^^Hfw6N&wj5i-8S2~vd{&2Bu-O&f6fXyRMVoFD$abKv(6Vk5l( zH~bfYZN7mkGfuI=>;|m%rdO`;1RH^MPj54!-7OTX$J&#a2Xh+|z1pLeFT`-mlpda* zQ6{^=wI$KSJrg9|o)MiblH71ay4M#BqpD!c>coV?&5>Ba11UAod4*iHE{fy4Sl*CH znFwsSIg0w8Y%5l`eUIktA&H$M*O%;U1zX$)RTmD@X5tloV&R!;W4qSIm*+}mx~!E= zK56e#1vq8W*LZJkByVp@Qc6ICOJFhI2)dfns}DP43{K>CkLy%`j! zhp1kb>^0Hg*lbiZ6nR`cJUWjN40R^pG=4 zQ!?NGB-lHPnkH^_qnO$-8U@_@gr=4ve8_r)9vIH#{C=>2-P>K>2Mk?kV-w2PU{>iU zaKUYSTQ}{EBgE&cnUbLg%?l-qD6a$cZ#tOsPjx>yNFKW*w}e4yaF^Mfo3hmHiKt=8 zs2CnE(RsC8KB+2^yo|i+yv80FYyN5(`?wip0seS2$hgT7Lx-*hNzdN5-0uypot(s; z?usZLc}0D*py+L;X>0X_Ec}a?cC#Hceje=x6oRpg@~kM z9S6+)4Cz?UtAGA0tuJ=h`c!4-u;bD&*YBxAijqV5rP|91>|p^++AHEc-#4t>oJw`X zYpFzN9_ZG|Ij|=V!k$Rk$5xeg0>7lmEZJ+-ps-h6Sqqk0053|P@+z%QeT`1Zv}O6Z#-Kap@>ToO+YXLtL*%?~j}K@>s0=A2I8ov z3*GmUm!JKUND8=D$;&a_B^*5}Y~pk75bBIWLvIK*z8ujP6y%psh zmfTpdS+s_!pGPyQYo!*&tAE;W&+W2=JE+mBqB6FRt+`Ggs6mTqWos3Qt74N`vR1_< z_S8{rr}qA{w@_P{rjg)s1njh5iRte~;}@a0#Q|>L3b?!c?y!?W8<_U*fjTXxH!0nVC#|3Dj@PIaSvWfN64tYT(J0>=XncsDd-!n0OvBcrBT@gFJTA zV&$CS%vp~kwT9)p0B4Bm9&R(cH@A)71xVJMpb*2%>M1HUyGg(;5Upbn`xlYi44uBV zSG{c)N9pHmc8-sN%bm6&<`w&$tbA#<@xb_wWc7_hebYxA%-aoiwl2eA7iW29U%SXR z#u)k>SJX6CIk(I2Fe+GqZZgs#Dpeui$(6E#O3_lexLsQU#eELBd{f@d4KvR0V1w>c z%NrG(sXZPY#q~wJd3SKU#I636J5d5hwypRen17(}5 z-1(w(r^{L{Y2;_HJc+lPU2mcP9tMnHY2$l?!(0lKTFqPre4}vhepv*Xi0LUAtem_6 zP;=}1%W(>NJpz4+rrL_;(M1pU8uC!d%k+g!1^OUy-j!$)uQR)L`Wk32KnXdAu_-c+ z*|y8|xWCqJbb~m{7TJToh?RK%67-Vl9vLzuvB5A80ynFMTdF|eOG1~^-UjO5p*#v) z_j|ZHcEALUJNtffd>^X?@tc=RKIS|7)YI%ngPqMc5ODwa*lYIjhQJuU)qi>_rFx*U z8P)ore_UC528sX3kvT}Zhk}u?LR*IZ?{fT-&J#PrYY3OuxlkE2?y&{~U%ILwf2Vt8 zIV`yT&kckAYw>Exil+Lh1Rya?D8lEv3{PB1EC2^SYDcG45nI-5mx=JQ1VU~HtzhV( zOdQP>P2{}rSS1Gz-Zw(ym&Pq%kJ(X%cwuB0kXD(oPv;d-blIG(#Jc1QGQn$;O>yY%f=-1^L{;7|GFA8qU3E3Ksg^zQ>w5|F_;i zZ(n>qsjznpmn){1UN6nD#blSAfJm1YGndW-vV2y3-HUtRGuX=?HN(P3nHoc41O{MR z`yz8&l*H_+CkMlI)NntCQq)aNP?hu=!YFRSmHFg!Wr)WrKOY}lvEfJ~zekJ?0IPS#tXhTBRgNC$xjW_es_@R^|KB|Ecu!j;^N4mCwDtpksNL_sy zV}Qgqx3Sd9ONv7E^mUX~ntkW9_u#_&Eyg3V)d=&GeQFoG(X0$;jj;lo`Ws?zzlJhD z&>N@Pg$UIhZ>uXsq8vUgCJW6X!6Nc)rmOy`xcwl})6-iL=IXgFP`fwZUHZmp#naWV zO;ZLMu^HDFgSYqZQoRf>3Q;PPOzuyGZ46f2?H&>G zZOn!Ol{H8oQjcVERFdya>x|N}f(X{rRXq6f-+%tIu++VNBfv7t0fGaNl(BoUcN?+M ze`r@0bW>>Tt0rik;M%s&R0I=kKH~U$oK{ur9I_~i$wdSb9dgbE6B}l?-rW2LQ=E!* zjU@C00>jDdB8*6bxg(?Zi$tNy_rZ)zNBp{xa24epe6U_6&?HqC#_ge94|H;2NEHdU zqq+efORa09VO$BQ$l)E1%6_zJV8`i7y6yO?Hn^%(4 z+KE$t1;$!q`)V20$w=Jnpt6!2{$_o~;bgG(s?8UY@D)eHO<9p{?XM5E@!46>SWJcP zzq&^#vp7s@m(+b=Zu=A&gO;K7bEV?XU**utJpSqiblx*W^Vj*}8mg85x*uDTGCR3y zxh_kDQA@lv7c*lMWv`p5P0vajA77W0f%Lo(sypx*7G}z#WxdkqIScJjbshTPR5_Cu zN|eAHJE%x~W^ftI&0B<39{aW+9VV^lQmecp9i&senLxMyYT&MG-eK30O<-A}HR}al zDj$xaO8fcJ@nc{BQi3?J8NyuxS1i%lkpZPuh(m7Ww`_K6wacK_IrgyT{fJBbHj_Nn zeCbwUD5sK32zzNLtU70D11aBrk`9tacMEdg`Js6jj?#pjlRT_(x(!bDxBSU27RSn8 zPb{HqFx+Yh6=1U0@B_Jqc?78aaeUXRni>zKdrgQg_NTAHtw<*}`q|-gYEhF#{Yj7?UMya*Dd;4i~H8Dn*CA37o>Q>s6x0bp~^YDqzGRLgS;z$0VmHuRcj7$TnxAgSC9xlQd7`Y3&a{!sF zKpYHz`%{1hF23p_Qaelh7?d)phECsA>~tZaD5t#OYkjK_@t9e*(H@R((Xik}G~&TP z$(f+OiXoeDCX+b2SUDh-JnTGV5a=p#cEk2WLm1N0qo=wLtD+xuO}e=i&U*Y*z{OX8 z+)sScur6K!sJf4=fTkMp_mc;|e?(t@{)&%HTZ>ttnlM9Ipku~H%xYU7zY?2du7{)_ zlxnl)kt{z~8Zo#03UJiMr*-|v=){xS>r52M)urv8uL|s#>spL6*piD?s?rp_b5ECo zA&>pLdc~q7Z}J=7jw|u1jj`VklXV&g2cFu|>mn z&*F|60F z%;&esPw21@BzM-txkcYsTAV4*_gM3r3E$JeXP>+4*5_CGR=M4WE_NUK?Rvf<-J9E< zO8t}Sttk&!o0yMBElKa5=@R~QVS#?myan?C>^Q0mbJ1w6*-{Xvye)M*kI2n_(lLj& zfL&Y+9@L+L1x7D{y-KbjcpJ<-h~wn*&&~T0uLLHI-23wAE$6Q)ULT|#ih&92H^QiH z2rIY)(2iN6mwn`uDWZ?H!qb?^j#?2AB)$GU;sLx2J2fvm6(FuC>sczd}*eM_BWR_T7FUG}kcm z!d5ur4G(}aCWK2%n*vg0+u_ScLNpCpk$Feq$|Yl;t_xt7dER*gY~F)iT;2HI-@%w! z_0E!5ae7)zoTQ=24%IQ;9<>4Y)j#a1B`R6r;<`HJyb2goa@jJ5B3QuG-pE%zdn45NjA}o%P>};OZhF;XW^DsXuJr=P)Q-irP%0yRGHTofJ6ZLItjhh=Ys> zdr}RXt?fA-Gd?%{(rt{t!d-uKQvPgv{j0Rhuddk*L(90^+dPb=GIMVSg#A0D0~+9d zXk-|!w^7Z{o_(7}*-u+fzoQj(%^6$D9RXdu*0-t1G<8^Tj&Mv^c0vL`YwfsiSCYxm zOtfe86m?Z6e>#;Nl0&TW;As`-1enXnX=qa)>;fOI$u?U0m69h1?ZB^R_?GH@dBu3r z-uA5}3|3K5(4O@{8V_Z956)FKFEF3kgDp(`y0LE84Q6sCJgm1OR8G$h6|hNda;;{H zec?0lJ$l#mSit2*&OuyE`)>6QXr=`#@H#b0P7_ODg z->H>7PFDILcQNr_L<%Qz=}jP>1(BkcL%?8X|PQ>pw?u(ld1&#yxe%z8BQQ zR*6iI2T=4K?yk?nTvxg%xkb?cUkW^_F8lC=w*0~cRvLBwd+;g^Zhh6Xg!b&gN$ke- zCgUP%T{`t=Z=3U0lx=K~y~Ink?@?{^RHch9a^C*_Zp=-1mD{W!=2p7~rtonDHnbL{$DAM6O;t{DjCC;7o#kIOoH)cZJPn#KIJv;qb(llm7je zM*?mPWZP8)%Wzx;bflR@alax4AxE2x2>gVn%}omdu&(*OGPnXvsjW`x?2!!ygHZFQ z#0V(W=?_-D8LDc^d4pGC8<%+~gt_^pp-V^)L!<~IhDHrqsJBLdHD&Dr4&X0|h) z8?i?B3-!}jAh3PitI27{K~48jt_j$|hPg0GctB@ZY#GyRE)n ziXsGak5KOTnIEFudU=Qq)F-oDA)3t$^P^a^YhI;!ETC1r5*^{mw{vi`P?^^Gi) zDvjM#ZbeJ&xcMNIE7!WhJlgWD2Kx`0_owlSUa5wWJH(QP3ihsOuF-&;v^=k%4=knDf1sIyl$Lmd+4YdOa39c^l zpPHJZ?>Dij+tb(D%<+Y|UJD=KSv_A~X%C`?)&A=UO$Iw^JQ@$*_hI)E!NrS)#*Q?m zR}-HA#Jldo1)y6p6_*fbZ3^D8SY;)cUwt5->;pzrCRqp>s8#K7bIv(Q<`@g`kHO8| z%Gq6L897`Un&FyP+wEp!(KCVU;AHL3K0>*eMzdx}Wx49=ONI8>o;^M+k%OKf)h@K$ zUd_@xRLWws&FkI&?NRu_H$-oRvgl1X*7X;Uj9j{2q)*5{qU3jl2qKjQR++0w;>FKW`PO=IX3JgqCYfGav>B z_T8FO^}zC$D}-`+9%BSop`s3m_PC`^^ujv{{88DzB>I;EO$Xq`hIY$ii~K~kcdduV zGZ$1|%puP1n*8Wbn+)64Tz>96`Z-i+?jQ;h0++JNhXkhbFj(1=@rrxxANRvYa=e~n zWjD80qg`f^iJMc>=G5zmj$K+87PU;+Y8Ft(t7tL3a*^g>-*oe6qM+I~aE|7}O%akQD=5arJ+Ozg?&gMuidgijCTI59>U2+(EEmo;1S@ z?rIzCTkrbur6iSZAZv!jE9E{y^C4Ck_x#V+Nco&DB!MuDei5b2(|TEg)qpV+o!|U# z)KnKDsi*fcOk=1S%*%$smf+vyzd-zI@VYU={$C+36Em>}PBSpgwvlVbMm^XaROBmL zuvGaK9`)@uun6rQaUY+Cxtk3^N@BfLd2-8wMVj3v3RRw|_U`Z|k7X+!?lE*i$WQrf ztmM39slW(mJa{E*Y%^_M!re<;;!dqr4rNfBX{ZS{`E&n#-7^ln6)ZJaA@!~|wrR^o zP{G^D3ea?E;Ly_If+4N(Vl{JZczX=gZyWK%iRu@nQaZv43=t(Y>}_-D}gj z&!sHzZ#Yd^pzSNa6TcieWAf-J`F$NoC9y$Y04%l%v~1lGg=}d?=JIQHY5`NUFG#br zf@zjAFpk2kNGv(Q(bW!d6lf z@Ca>zjjc&|G%zy=r77&=CVZFjb7tL?x4W=t$mYN)@LF=%@J$KPbD?U{)-WZG$yA6c zg>dQZ%X`K3{J(u)^&F1_8x=))7npG7L;Td&AL!5NCci&riqcA_s(pLdqb6vx{oADT zD%Mc4`*r3aO_xm)>KfhMs#K5^17mriJd=}GpNqFUUmgq+hwQ>1zze#os`e~lTCxWw z1IDC7hE7kc9j=v2Mmh3~?laFOn)fUnxIq~o6<;3t_O#=?24nX8~*hF zrhmxv1v1#n<-(9@Ku5o8x$mGClrH7>J@VlrTyIjLf-Io0dK|=d$YU7N&ggOVCxLIY zNehtq=;Ji{p)3s~=0M7gq$#PG6ZgIhL(XyM#(|@u$9s9X$u;Zvk<4W4XPeEXi zC|1)<(AK@jK6?dP(cwvLRPLjG`Vo|E;?%ydmyujeBX?k4q>JZN8tgi3UeIKi&%qAj zMpobL;fc&c+Q;f3bui})`t*fxyVaQmr_`3mM<>d-$L}Hrr)Y6O$G9&)4%5yUof8Us z!MAVh-TZhJBcI-L1C1^@K0R=E&Zt#8QSDu~Pg%9!RoaP+6n9?-O*{x8-c|Ck2ScYa ztE8dV>9kq*epM&0Z<2C-WF+;Z#3304H^!Loo#?_puELL+OVD0EF?gek9nq<$d@@XU zJwSqrS81kd6bmb>8+oLbZ#05{L9deX`^=o6L;?7+p?M9dYh4n>p?0d6txx|GudRVwVu+YcA!lmOtHv8t+m611ee+MdxBkf62TCu z?Sl2QK4I%9`gR)?L2axOm2Y#u0Sc_(Ia?#%KnTE_7eBx>A$8NGs=`8b=eW(YoVZ`_ z((Y^W#vgZ&qE;qz>LyL#FT&zrEn-iS3Ovy~t*38qNwl35lH;arep=TMDX>a+v_%x*>;1!Su-g5XPl_G!jpmPygQ}vp>fJu18>LD(e5&oAv8905 z2mi%I7|Ios=P%V6oUvT3Fd(15AcxMo;)H5yga3W{p7Jc>F#(<%_@Z-+SvpD5$v)3# z;V8?+otHl9Q?!A(al($;Gu-`G*8mPMiE?*WigKQj@FjEVpMHYmf__~0Bfms?*MvzD z7+#utSBF@D71(^X|GI7n2h45q!a>Z{D<&y1clT4T1g@$1!(fGlG)TZ}-QAo=ODxb{ ze}eto4R`U}((xNWqCw`5uXXLTevi|?}m#}aamf-rRu&AY}D??rZ` z&P?=cJvS>SUie3btE-LLpV5|-Pr5=65MN}NOwEN z;rjf!VZ*cyTrL0O=hO9h-4HlIy*ieU)*FsI4)&^6Dc|}-?!p80v#pOOUh@tHt+BsX zIP-Df3+)TtU7i(l%%v?)2Rm2dnE6uUAaTApc`roKRPJAlSqz;Cm-yP$-3FeRI;LJU zUy>2L*nKI*B)%@Gp8R9xegiC$3FaUFDx12FEU!*Jn3-0QQ>f0Urj!ShJ2s6u4^ISEYob)@Yi0_S z7+FJa9fgc(FEd0qaiQ8SWO0`c|jyp7`pmKCCMZ<@`ZNW}Py6@Ym(FCOVJ$wJ+}LicUdAUrgXnAWhtSN+~yq zHqu27YAGDGQLYjv@4;l2DzEw6BeRPw%~@s($%@*d)7nhZ6C7Qondj!Mf3fWjC>`cI zNm>$&)jicF=uS-{P@+_qlHaBxR3l~(XM#xa3L8w6Dd#85X%@$tASmL=0R&f-bC)F?wzv+vtev-ADuB(&AhMLof{(9(Pq9VQlgkv@v$486^bU5 zZ}Qnv8*^$*GNTTSQK#^ck$^4|lGi8j#J>Zb&kg}$Dggdud|QX6o%U-otQeUoJBjAX0KZ854KoLd)1 za(o_$oUJOpdX1NO+qw@Mrmgj#GvmA0NyqDsRY5Co#7Bk-u7XePA5bP`{^L!5I_Hn_ z;fuY|;b2JXcBiw|TDdh5lQh~tZt?y6*Oj5O>!s7z*^D2dY@M@oyB7~^f9xAvQXBb& zBtazdUz^-RhA!lW{C1`>i81&yyR-h1)hfi1J#-lieDbOR<*H8bJIcf43}C5hWAFv_IFJ#37qGz4b^pE zznsiwnmSfCa|&I#xm6qlBCYqG0H{*K(_ML>NQDM-O$}TRmZwB#Wi%(UTHJcXr%OYc z7Ad~}uuMaEO_R^B)J+zmQsDR1Z-mw{Ohj5QK`|6BqBNMAP&gG!K5KyprvfGej1m2? z>Zl7(4q{>;sk#O>%tT6$X$!o@Y!)TAQ7CC4-%$|q!KCg4tQ@G-|eEQaNDt>xYs zs^9bW0JIzVhgpIlW&zUScdJS+E`gyaesqbAB`H^4x}iejbR7bfVbi40l_T#-3vkGf$C zzht>^zZ7Q(G;5hW1oEF z&FU5Bl2{OO)U zF}FV{ag^1$7pKM!^ffvELKhSl1#nM}$-PZ8Os)y4%5x`;!4UC4%P4?7W(i)~86))| zFZ=%WU*2@1NN(28fn+;k@N~}6OCz1@HNAouW3|H&UZPFf(LU;DzW|T&^BY37dzE51 z5v0*{D&l}rrt~Yi)^csJe|>Xye2ODXG=WtEW_i@KwKlhyd$fXEtwR1f3B<9SP?x zNqgQ7tvny$l2-U-AFo|4=K8Tuc8iWaLX7m;L~fgq@YB64={q`=&cmt<^H|P7z`!1r zf6mN7@8^r@DrDRZ6idSeseZ~8;5<-visuh#sfaUXZT|ufFBpxszfGGFj=XtkQ=Wwzkcu^`+Hsk^N&*4UsqZaBorr<%(7_{d zm>HAW<6kUd_mUciNqmL-VE{H4Cw;C`*E0mA{uoHi8*cmQhgH^y$5R~fVlB7sE6>`S z>6T@YK@VDP?^tO8pQM;6s$d}|_MYwfx6}NY&H3_u)f{?MKNX@2T05?^5?4MG&r(Y+ z&8|n4YJNrpCS&r|4BEsQ=s$?>65~}UMbpajW7mo?C?u3vYmK;b?NwHRxb1D*DjrZ!5eXJ4aq?COm&03rZW@1mo>_zoeLUs zscBocRH*2?P7#e4b^LpU&+vrbw0x<`%sB)^zRy8-{tqPJV{W_N^WtvqxPq~RvP_)1 z3t&H@&;vpS;P$&H0qwYc1VnP53sqk;2D<@4Fn6UNB4tW!-q$Ky<5JCgZR$9X1jW6A z&pgs0`)~ieyI@@c*hVJCOXn=DjXK3GIX9gcIswgd2KQ7M@C@5uzaXidi6DEG{a(C$ zn(zEDQvU1?WcrN=TCS{Yu+5VHt~FZvDa4Mz_WH#%{MaL}o0lpO&UmGpDvGF_Btc5? z^Tzsblor>l+H;zJ|9df6k#(!i_KTb*BkomHz*W_1tznp%+gm95AD#aHTm+sa#^}BN zU4TROKn~}HEn03F&yja8SULI(xKe4xnCnU#uF8)2Bw(M{(7`n>t-KURFYG$(V-yMJ zS{ukyd>sFD={1yM+hf$^zyz8xyi{OR3$&~G7LKAeALv)c9;ygcz3$OZH`{ix? zQ85)_4Cg!}#TzlEj@->RUVJHEwe6yMp2^q`qEKB_a3od>q&&BI zO!EGRdh*lQLeC1c-eU#yIZH4DT>ryLmaJh#?gKc}8!L_Df?*9aU3U))G5zk8&O zEI@{U13fEnNyl6U!=KV%%Cu zGr8KbpmB1%{KP?A%MNpBQwxx-3Dm~w|u4ybArfW}}%^p8Q(n0P#wnlh^3goXHppFql1?&l zp^Y?Jv|Z3`OnS||6o&E+CRRn>!cS$J+@YE!El;JxK`Tct+JA-99FHB9D%Nt}uLTS! znAGN$wZoUnhWx8?WbTm7v0;_FACQw*gT=7=f%9UdCa{k-&pxCxR#~>)V9+e%@fiar z$%y2~XZHq_`SRq(d)c$~>P(`SH)qWfGP%Ly(~MS#PXc$kFF)I|?7KlHORP_Itwv8h zmxO~Kjb;A48kurMrMjF{>AUO1j=ttm5Smx zMdFOo+c)nCqIO)XY`dPft8<|C41;=l>)(b7;~w{?;x=M?NJCyOa`kbAr+m7KW^Aw> zXTQi`2T3Mexsq?N3+MrrP*5d@4n@5tw!QW>n(;i6H5xFytt(1}El_S_0g=N2C=K|D z(Efh_g&$R=dOw@D9SVcA@8QXcl%wS#!4sYJ_Ept0d09_^xRJA&;uH;eQ1N{rv87dt zp17p3FPG}CakyX&ILLi`tgOO&SF54R$&E#LAy@z7+qICM%aoHBhD ze5vwfY=9)QSQf?&3@b_c*9OMuLE)&=5CJUsL#qL-`JhOOc=}Ex05t9IKc8SwJy$y8 zHM_LjoVEcnNls5|DY|K!|HCF-C-0ZWPy+BmASbw9rn}yCsYtg*S_t-LHezoC*!9;A zIb)w&Ie=@rR;@{L25uG<(wF(;P=V7KlihE%<5$}}wp@83a5Lb4*RZWnhao(LwkeHf zN0(L)=iHyM6%>HsVk*bUsL7}E(EA*X>GYV{+=WTF2T@1KW3L-htf!@Idvf#*e`QIZ z^TWGrUN!E0L+bNVhS9jeAkYv@3l--o8KKlegiw;+MH zx8Lg#pZx@H@EbC%OJ{vT8%W2v&fi*K(!eTTYkhKuF@nx@L#BV99@HI(ZmZ+{b+w}J zUOydEo)rQwSXteGxI3JWjk{EE+D$rw?-rLup9~enK(Z82BF*R$5bSS&xQox+j6XHMKf@{ue zitgKhrTVA#0!^RXY+Q;hg^MFwzfqbLeta z)E45JWtwqD%DX@`t*-8lNj!1rIPMyv=6!`F8R0WVPFZZ|8l{QiQZC>Xqpurw#H-Yt zd^~=AV9>IR3ei1J^1X8>@4R^zdbi6fs9%!Q*Nxmb9^AQzqZ%UqkfXK>be&SGpU)%S zjPWs^1x_C@PcMprNWS|qM2O^bJ4o_UaeDa@KsoS_HJy;i`9FR>kskDRyu>x+naU>1 ze*n;S=2i?su52PZ>0B&V+-M>112sU|0VbpT-Vw?szxzf9vEG3`evI$@+e&J;m}6dS zB2GU6^v05wU&M$7kJeej!yU;@eC(ntFN;^^wED!#lOffmxaRt{8vkR+GZA~PciP)= zLQAeYdQqHg%_WYhQ`VHidCJ$>hkT5hSkpG1OK5K<)6?G-%E^&m)%R7xU{Y>CkUB~EEVjs@a{8}?S&OxF(%sjh(sS)h8@ zoL|l?Eni34hJ-#o2s5;0_w)8MH#0+c5nl`rG{Yv79KMw5{GA+(R!;RQ&>bgTI?kI$ zg3)D_<$$T`I;SPxPjn*NB*qZ)zPx0b8C`?PFM&6fr|~j$vaXQ8jG~}3qbx_;6hE*+ z=9MFp3XQGO5r)d~jhr}Fm->;MXFDQQFIC~-8FgftI`82kPRxXjQ_mR(DB!=CWZNbq za|^`^IsIs!xtcfx>Eg^zT7d-QQI5~viT)un|74X49WC(F(GGn+XHxsj9Q>u3wSqPi7g4=Tm76Upd%U_oiTmO1<)jS0ItA{7R0 z7LlhuR>WuA?*vFF?h7hOQe3wwkQvIZACRW*fel$#d!~&a=b+EFreH&Gr||3F;HjsX zT~+(ttS`EVYt1;*bHGGYqnx*w%pt5nTmhBfNJCy-Mvx#rXoqd-x%aPc*H#9?`NA)& z=bZ6XCKg$aOOMA*R^}%4p>JIB_3azOTB_n}$A7&c_;%E;uQmB{+4zKaqWvi zQ^NA48T_bXv9rAhKxX))3nA$YfOZhk{&eWGSGeAe#I@(gbYUv%MU@~GOj`@P18kar zV!U$BO@A2UI%VWD(ir@5CM=g zNS8IX*@U<(Gd>9Hr|!M6 z7mFUsFGU;#`CY_1+8tmgKx0butT0~X1fS?IS7ey0J(VXvb4s?d!aiJd_eNF);?-$m z2NTOWvlM_dVZ#Xwn^H^pI{N2HR-F2dAh1xOSjOWo6Slq4-8f$e>>Ej|dq=|R&zq1#IDZy7 zk(0Km#N-^yZE~~tu+W%6%LSFj+m;zP(c)|o6tC@r(M3navz=A$FgR@A>3Y0BlNa?x zAoHMn_N}D+QICBh<(W=k<_>eEr22h@oe^5HEp_+jM!b59*FZ(2zRX#-F+>ZFUPSyx zh2irHI3Uv4cYVA^la)r{I+qr=RP=FkSE#AUbGN-%Lm>#cAx z$j4;QFO(PGTpCMLLkZo4~kFfUuYx-*6$E~g9t*8{MfP!FA983qu5E5H(03rec zCX6VQ8G*9I03oGT!Gc6($rjlw$cXHuRUt~)BaxYE3;_Z}2q7dP$^Qgx?eF{gUVpBu z>E!@FpL3pZKlgJ#=cF6_*|FGZ^-!i_<@wXQNR`VVOng(6?zZOepis6~_D*rGMq0;% z3-bcyUdaV;iNx?%gS9WfKOGz0L~}&5Nlo)Uqk*Jx=Cn{0vA%5J2-KbbhgADp<+b7G z3u#AShD}ejkM@8&RxHDMpSjuJ`t2enS0fc1V=cW-@Y=fQVb5S#=V0kTj|UjBl^%m_ zW214W*vjT4>!fl6h?n!1?t;1d6AQtnheK!uWm&!fos{HbHoeS%S$}Y?&%Cuw_cvw8 z&eG&Bbu6X!*!&~_ux<1-3x5)(if9$TVMDL7rNs}IJSX%NI}O@99&n*7tfTNv=~(aO z2h&nS7HjbSrrO%0{WH%DzUPNtKhQNJ5e@<5qgC>JoUov*cW)i`sWdNWoYk53IW5 zh|2&d$@a>fEuL@u8ky)laV$CZ_#eo&&uSL$O z!fdxPVr6bQ^@|OUz%h9LCl{NUf3VxXvh9;)$=m6GEuTY}UVKfEo))wB>d-2eNxq}5o@aEId%T8;oY2@TgSIUobt+G%_8cAQAFPyU(p z6ak(9^CdqeTmlg_^s*-xWp2?CkxSr!ds*u3-v(rH zLj5(5u8*9333^NNL+dv)J+{sEwR!j==;zE3+k3X8wk}^Wom-oReT$CusJ-ok&9T`PrytaQNmbs7;QcDP3Un zu}pda$3cT{8Uk#%#NseKl!23JS`&QrC@O?0KNag;FH-&2{UYnrMgLO(2t3+GqXYC` z*3-?p@6IP%>3lzQ5Zkf+{9Rk632-3#`Ks1=!-L4nx3nk+-u>q^ z2bbo|Q(z`X?zPa`%^@WDOZ0ZIJdy(ad-?)t>H)_lfKx*rm-RJOvhzDxVzET`UsvQ9X1083AGY(8iJ0dNahr8m;3~4 zrYz*~{lKk@MCl!=b$N0Oy%={Rahh5*P_6x84g!zpIXL(j+^yFSPNhSunC!qYv7}`k zn?uE{!wvy;mwuNv5B4&il@Qw#Pww2;K(GU&0F}V>=FD&(kEJ})>y#R)X7jt*VB`H$ zncm}|yUQ$N$F|N8t$TH`62FOU=*C@SuRTr)V&5p9ji~C$IRRUBU3qo zq&{~!^cx~5f5Dvu2W)0D2cBMrz7shmx2V3;6sjswMX3`qzxXWClY@tJC6Mx39ymf$ zs&C+CSvCP!j`^Rmr45>Xnz8!n8i|3IZMGPEs9x1ZFsB~W`+#nLu=T5@vda+Tp&%E2 z)WSADSI8S_N_tQ@=8B$Ni#~d*bD+8N-j6`L)&9Nj$=EP>pIp}c%v|Gd%D}0O3YBv3 zyg6&cwQ{-FQRi)R6E$RZTdRs>OMZM-sF46y_tl0C_0-WJKP)34qA0K|inoQ5cFuK6 z^MRqZ*M|3CoS&v`&pKfdH)i<{3fmtSs;W{3;K{Ln{oA*Ao=z9#h(a_b{s|C3Dm#R~8q{(dm_ z4bsV?Sbcm(#xBbNFsT;fx7Un(xpSC|P(`?J(lIiB`1t<9^7EY! zr=t*E^Rg?d4nhyuuSK>yM1Rd;fUJc%BHYZFQ=X1Xs|Jp2fI z>x4HZkT~$Ou~-`0D%)i^vN)&vW=F?yLH=yyk#eq3(mP2z3%fpfD~Da(QepM%K=H}1 zl(kwLqi*aPyZpTl*FNq>d_jEF(coup+m35(J)hmb`;M+ge)#cZZMk3f|8&GUp{u(z z*6y3b)>=ot?QZ*ma^#DyU(R?cor4eB_wJSXkKW9In>8}ZzCS$C33rU3L9a^+N3s4q zV;?qi2qlcB%sS4chxR~h&7$($G^pvp2n@WKOSp1>iyOg$-FzTkZDlIa5@zjq~$E!Y~O{TE0c+`OxE2Cf9U_bnkgv>gNc$ zB&~SyO~cLtHv?{pM*o_?;G|8)a_`zgUeJ8Hm{LXSgX@w@VBdB>_D#3jG=Q6jzVDFe zdc?8=I@z9nqa;2}VhG(+Q(-TuAPV*NslWX$9XdK%O|HiV*;NX-_eORLQ2IlyDWK5){xI;+rmG$i}|rHv04;;^X5(nOOoS z*op4h*Ei+#vBCj8lif8eqfSwB^CcG=TxDx2&Sb~AxEYscIdQwKod5J1_hdyzBPvW3 zNqgA3eDoov2MYUOc)9g@F=F*r@s5l$sTK}Rh;(f%A&S|?D2|U`{c99^#^QzTWksPm=rNt^L0U(aT3SOCevPS3rQ7hchf}+++MA zTDFkhX+Ps&3sI=4_{yaGlu4O(nwZHJ+Jar+RwK)U`6dOM3+13|KR5ZQlkLmw*KHvw zI}T;0U2)6J+wHpyMKtrxvEhsU-M1Xu4qWfPrG2{?NzDvi(7dB+`r6bskTx?z*|kIb1?5fs%M;49ezbv08p;M(xZnH$7g3?n3o}{GHbGu1)PUtnO3iwankTA6Fd^()B^U2HGxp6%Oj3X=* z7(I`JNb2vJ#B4}Q|5q*c$M1I1<+!3vhVQk3soQwT>o??~{vuG8`p0bRS6B}=4YaTc zz#t|Ui_Y%5zVn=IZsX!wRyT*q%0n;Td0l0S3)ZnN@^?f=;g@xw121=$Rs&KCEeCFx?vrkon0whSr=07}334v$(0QN>*1?JM^T@Sp~fYiShArIFYY~#oD{O z+x=jxbDF4?)LuzDby7iIo*45!ec$!eA6kC;2CrS1Msikgw1%135SQ8|XOa9WqPWC` zY^+=4)nquMC0lq{i`#3;2}6nwRX~ys%NC-{9yYMPCkLo5=-e(1M{KOqUp7_YnJRHj z=n%QVqqD-~W`ZppLa?TCbTjkm8~%7ZA~X#Dv{u?Wo22Jyb{wnd9H|F>V77b_Tur@X zRJ&u;QLHUnRI*?;0T&OFvPeN@le)=ioy=DoXEM5l>et(1_-k%yMHdVzP>t6PRLyrM zc^LaRIkh|S@lv<3c!62blUzqerP(^DN~jo-^e2&n_&*_q<*&BSEGqNj z74_V~W+)wxs@GK)+*^XQVP<*>Uc<~k z`*|*Cc8AuPIR#1H@GOX=%g(*36r`6(4WJiO7Us za(2_SE-8x6P1!V%d~j3!|@5L-g#A)$nxed`6n5t-kIJv{n*|Db}Ncfbf*zc)2@NhZuKOA2Q z?+|{$_R9T_8R-A-wPA@adv!qG>H3lfR^9@`i`+T?eM=qlWhA<-!h_ z@mw8FO;m66bE>z(yCcBs67X#>W%!>;@GtE4Rw03xO`DcqopybRyxP+qqU}I?;M+v2 z)glFr^CSl)f1ZSsX>E&pbp^i5@RpLe7`~}S?Ct1dQFSI z(Y~3_%;)$TR|-sD@}SG;Eql&xSiycSu%Z*9$d7|!>%-P=IP7n`vFKre-RQTTQRCx5 zg2ldegxK_A8q4C)%k(^7r}5Q*KfpL1?tw32b0NpePRqxfwbPun>oC?6ElP`ze?1w~ z^qM~9zlZcVYuHr91nb`z(%^0lfMcI|z-u+7~}@_?VFY$+5)=XR1(Np^wk$Y|7f z!9s9nt)Kng01(FOxjLJln?B^4{T_9xG(y!RPhqSN^_P&QWRkRDPHjCTe6aLib{2d9 z8#~UicAUeino;0{u(GnS;RlTVlHBOZ@u84~CZ-E{Jx<`NoMQC@K)|dy8-QKxDql0Y zR2A9Yw>y5L-=4bi`Qgm7HLSYDQT$X?CYe8JRlPvlvAAuICi!u9wLjUzUE!>?arzG4 z?U|E`XNQ~X8Z$aQd=QAxf-RZ1`f*UkazSaV9?^i#g3?04R!UPYIfd z4N7@G3{oOg2c{xls#l<}17~SbLraZ9h+J24h`Vhk>WRu!fa>{3Q#=A=pRB64p{|Y> zbnFwLybNE*59bSkQ}^pw#p;_iqA(T~MptHA?U|FR9QQPx$2_l-^3_)flxF&BsT7u&hsM@2gdTFCdV*S_{MdygCi* z!h+2?bU|) z{0O$N1~%#j<7i8G>KQVZzgoK&uJ9xB)iYl(M#)OwrUuzAFHcG`&=`gpA_lq9 zXu+wy4b#z2x71DZjK1BuAm?30X*LCt&2KFP8J;R5cB4_LC#(0EoZ(F-+Al_3EGIja;LYXy4B@?KfQ*=ND_9 z@XM%o(m0=ke0aJ#G<;ZVr3F_rH%t=QJE^t&E`5L0o|hma^p=H4VAGjodZ#h*5OcY2 z;HPvL`svyo%xKDqAZgl~)4V4Z{D}yhr#ddoX`+j9q@w7xpz+u2gVdP9*9CdelSAA! zMk6mL4nK7oWt!kWfOwo4h_PYQKoaDo?#C<-9cYf!@u;7IZ}twwc9j zD7O9Ay=qt54@tF|NABbC+;}%k+oa=l&ma!Kt&9O#;EAx^-64LuK26KG??^6W>@~9( z`uza>?3G#9@Y2w&gAGp`<~r?tX90LM8H&ceV_L$_&S>7zeU5_Gzc^O0(GLU)NWtWC z+LRF+MJoX)IU=SGwKhnT?5dhS+<-+o<>`PVvLbmirhYxuqVBJZP5rgnnIRIpqW%z~ zC8ET-Dp-pvy0#0ho-(Lxx=;TtX8!%N5sSTGXlg(C-jbkb<-%*C!AGSV5&mA;J zH0Uq*3>vP9p#C~Oe)RyOXM~M!pDFE43kFaBsu!ny6O=I378WmLs4@FJ5})}BGL^B` z>`7D*k{>i7*jmMiZmX6Es=E5jef=sA}Ch>=>%Wx*``i zsU|NUkz=GPFMp8TT7WlOhY*kP9h8@jh!uX)C-2lrPIhT$7csc*EFpQ%CwVTtC-8B`bGKFmm>~4}7j26|tq*}0?%I1&9$KSBF+bbGT zlMul^Xc6YB*`ra5{6tmnY4FZhC`C^#**nSfoaMz0WL)co3*~E)D@V&I~@M&Ll_n7JIj;+i?~3%BqmwWg6%vBDKs%=L=H_aU|18%R+j z$h;vC>QO&%YQ~+ZrPwcJ;6kq-^i!#Ka&o4GjyT%_|8R5G9`ovhulT0pk9VFs3$T}) z*MOYlnuG6JW-_K44{3{jZx0e#$h>dUOz~2-I8O3jEhQ_kJP5V?ujs9=PKctP1YUg_ z5G91w(J?p~5#}jm#xQ)qN~sZ85%4jd3oTSorY4%CED?ox=YHpCPU!tYMzpKQ)8vTusB$aer6L+dS2T z_;{BX4p%;E$2p?+dYEX5m{gXR2Z*d+c?@F=){@^TMViw317ybqL{L(cQ*+PEmkr{W zI#CC;Lhr=seplj3lO$?x1(7F)0?Qgx6)sT(pgvGrB@z4KG@kHCkasvlPg%p+X{2?W z)lClG(3NFbjWw^1OD4Fd=aY_Js^Wd|N5yAovF~0za2Mlwpbo2%paZv>A(0y^o-D7?VmewE8zdHwi9_i8(rVjiuSjTKJK z=YBW!1C8^H|KznGhGuOJ>My#IKw!QVWI}f&oA%(7F!JwY@v?H(n|uIif4Jh@;EDR} zM}V_PYcZ*@a0nrTmwN)u2N(V%K4Ud!XI9{ z8j%tLlhfzl(Z@kevr6(w_bZbm52JRcou+xbxmX|;#H85aYl3rH>&hM!Nntxa zyQshRQY3)x!0f)mynhuRe;I+C4PnV-^0>C*84PVS2!7jXYO1^M0a6E4nIY(MH&B3r zfaN>yG0o4OVi*Blkj!QXA{`>frDaS(5{}L9Ytjcx4=h+aDJ?{3#ukRXz==9H&ZNii zl>y(vNm5OUkH?5GuD>_F;uPoSZG|r7KtY`>Enk2W{)t!f)A2zqQ{}`~z-c<}Rzp#q zME#lIM8P%5kc2+bO|AAP#85nGd*tO=l9efdJx&SUCZs2r6?+cwpzJBe@kl$aDDmsr zU6Gi+aM~9MFZoZPfU&A11rIIWJ+{2+BNA{trj0geC%0jQpDwumV_=<0e3b47R&Aov z3WwMHqQKuPSu>#!G%n9L6P?T;^>K`#iDu1UkPAE z9S~dtdHI@{MQT>HHrU1*&Em~zoZtkALR5E zl7tO@D}qQ7i-(SdtugN+J@??*;lC_yZG)b}vt0%nNrqKaAAI6TTJyuWyQkGiC}Xh* zlC;Dj+8dxn#&ed*c-AmZ(pyn_1Y6)XZ0A()wx%kKb!yp zQR~Y^Yh$$xSE{jDfH`xiF>h;8)Ff|)vJ{7TijuHbL%W+Edi9qOiH8%sgX>d-49*_N zjbp&i8YJ8wU#M;x7zf92z%Xalob^CJ%5LwYiOzOY?V2|i!1n4;(}5MG=|wuc0CeQA zi!R_Z z=JthkIwP>0jXJS_YCY7+H}ZRx>fBvkPmRzmA>?g!Yu=pi79v>_zzjDRsuB89jt3d9 zwSe4ZORk-1qpcW&Ex?En5@#e)yCBIVH$U&FgyBP@z{THTm{}k~$Xzf*)a@5E=kc!~ ziSwR_@zLB`qfD;>JHmTw$Z>V`Bo%2%ClismafU7GuYS7Xuy+p@*i>D!?#AlfJV-uE zHDa7(YfTOQLCu`WDeooa)6>1plFVsw^lHy(;fBj!M@gKe_XL0Z`iPR+Dyyo_&Iyo< zwdY=TcQ>ChLE<$-5i2VVV25gyH2~m1+rGfr`;}=YPQ^5dM>vYWCGJ;|T!g7$ruaml zWxZ=&XQvZvJ5WjVGQCyPgvWCUo9uUMMseRMO+8$oUZ!X^3<(mIoE1*jnF`EllRNaW zYC({Fy6&xji`FCDkS6js>;`g%S8V-wZl|buizty_E#b?hSN!9Bi(p+|#k+a+gSJN9 z<;C>m+;bUdQXOQT_6)?Bc zeYN{Dn^)Km9P0`@hkFHrGcRz9SGl>--p&echmmxIbX+_pH zcl3E$){mPYd3p`$y)F=({)~_H%$qp1K%Ml{{n}V*l%4=tq}d8*zI9K@>AFg4$C7HP z_U$x4DC{~po9j!Vp1#tU&r`&AHK&k5luYuvpLaaQdZN~nRc-mJgahb_fxi>KST~ta z?YBqf52F=v^}pmPA9;>Qz$2Q+hCRe>oVl6B17Nj@)4h}-vyh-vU<$5y1RcNVB@0d? z;Qm3iw(o2v)dr=)5TuNeXGf{g-H1e`f=q*e&4uBh1Uu^I#qLB1enO(=`BTjTH`*Gl zo`S7CZ}1$JzH&Rw;SBnW=_e%cy}sA?^{nH?*05tb^UksQUU&3m3qg#&Fjl(JuZq_) zHzhh=T%k0IhorJS;XDhJ3KH3ElqB5sWmjH4*nJy#%FVVE&g<6M5*3oA4!N;6QpH;& zz=ySAMJ5CsRpzzaXG%qPP!e1Q%HaBKhMoUnJOM{_f4R%sLEWr{YhhubLa^I{rXfVl zAk?q2+g3Y0)z#f4yKKH$d>e!Y9h%ts$`UuixHgk&--O9bpB=44-Xj0_3ZGP4%gdqh zbE@X^B9@*~sL4JT>Yqy9mr1i9He2WmdJmis2u0to8=q#!NU__LZiiJXqWE+bg0zn% z(0dK2eXc!kr%4hw4i}`b(CC!>&||WN!XnlU&gjED1Bj>KaP?jDglxCw5A=%Zpyr)z zsnqtI9BIR#Oxs>wEUnxv0vYmW8oAKrcT7szK2Z`+~y z;e6l~(jEOhK3-3<6k&1xB3Z!2aI8Uq%b^J(q&+Wbpmh-zX{Q%!KUf)dM2-c4jaMRN zDLW3nWIbD?M*t+&o}dW+YIL2EAlw!m@Iv)gKh{(@R>ftk*iA8_EB%PS-@@O`)G8Pf zC+>1=%1z4;4e^Z)n`RxPc9?Xu@pReffkxgLM!1JN=nLq~hRfd=2B{;zc{3_m)tSoK zkgOao))Deg%!;t~$mkW8QM0?xIH|V+$J_KoZAEPJi4ECcyF<3nv&B9nnkb)30#!{r{AaRMzd8u zf0x4~J%x9s$V=ntL!zhXQ1Dhe4RiL9}QcRg^^&PJ>@= z5M2E4j_&f3|E4m2#k7>blvB(Z|`<-fVpw}N@N2v)RR?03{&4DQW5%({w zfr2r3Dz^AsNmWy~Usg=ZstuuqOCazu)U(2gEZGbV4cv#h!yv| z+k_ZDN2n)Yr^=8~D7|Ff#U{zh3b|^YA)X5uhE`n7NNh$ZIX+hAuKFp5M?bN;or~=$ z0YQ@9N4KquQ8ORjE%S>dND%+(=>0oEv{K$Q&t3*>0YeNv?rPpyF{s+;cQ~Q&1I^N# zOZ-+|-seQtF~9WMi;)0}RWU}x8-i2WC$R-=qk*U8z&277L4Qm8Zp?%OLfGlK0{AEG z2N(REm<)aGNWW@I_HO@iFh>KBzJ*2Wj1GNgP|Wlgw9a+-SeUMNY?u(b`WDm{k_KW7 zofTBSqU<#tTzFcN_=+?0*Pq_*Nl`)dfQ4^!oBT4B_hUha7g!B{*fLA~VsD=?F<+tW zo{Yg(GqoJsyI#9UUMMy6RmS%r)Y$}KF5r5m zGDr*8?K_}R(8MY*mvZ8Cw zeAn08oDcAcVldfby7Yl>pkDPW6nijSE=4GpgH2Yr*<3m6b3UL$UMbS8`tSEE;`kYB z3r&@HBEa6$3ENKnKYOUUzK37K5JU}i^`{L8UBjBV+HW&4TVvi|aiBL}uPWP{Dok~( z1SJ;e43eeb*+3cY#j*#`=9#awV49hufW}`i^$xuXv>dB+SRrU@TzysK@HJnCdc}P} zkn8{FP^s7O*o>e0Is?oQmBd;3`Jid`F#BVMr z_$gMO`L0xR0TlX>o1l^{Wc2HYUDzh7R2B%zSar?Xw*d=Ijw)ChH34w5+Kv;PlD{c` z$RO$b0cb_2dm}S;*kD-zxm49FbNOrY-m}a>fOO;rDw)swct@94;|P!^@XsW(o0V{o zpAkisKkPC3`4OHlPOS6*_@74>*fps|Rk-a%Pv^(M$@JZhe@6Yx5rdK;g5aiV#`yy+ zrKGIAYL@2;Z1U?}Y0eaeAZcGfg?q>zc+<4zyH3;t@Lk0rdwU_LJ-IY3kuMhZE^1dfOCmK-^H&rKY47jMz6IXA-990A>G zw(W`m2wKuh(>{KE3|d=iOE(Pwfe57rgha2cT7coL^bDUzz=wjf@c`W6k>O%1j4KfA zfPD!YSNB_&Y=APnbzEOw>d9!8v%@+aRldtQO= z?VWH*`;nyctM^XcAIdR+v^{62}8XZK-DydJ{(Tjvui$@3m$= z4|y1-nnL4Qsv$JlSm#7F6N`^$+2rfzL@n^a?hAeE5W2QjvGuz2%V%l9Dh*E`ZW^eLnnePO z-^YXi3MvQ&UFn1%0Xj=LZ5Y^%S82&-kl~&5-OkQemzBk0HGCRL=cae;@(OY74QNdh z#6o#PR5b7tF*}ord1G#a3bjWQ<=g<%!7XE{mbNNt@|3BM6@rneQMVO-8+e>VZ?y~A zbjFQFY74|h=K3k~jIPQjMnN)o<6Vs$-;{jLwdvq40XKH|k+i4$@#~4ly7?;=I!O&a zTxwUHRF-CZafk$Ehg5N%c&vD?<);kLz_S5*RqL}sP&?diYgmJ_BYn2~i?rUlazWa0 zKi0`4H%@4Z_I>XReRU5yq7|a9zAdKS?Y-*`V}-vZBALyzw`A$VzcU%xxyw-|;XyL>y&7ze)*k?RwV&G2fq??C_sDS!0L)vy!-{h>yG%IW^odLZ8~kLTiR{{qo@95f>f-E|&5t+q~Z z3dvF2TzE>yyqaxpBS3xiMDwZFRq1<>u)s*>tw2Q<7>xX8~>X zuEfv6!nLh=&rzUoX_c``aNjSoVXVz1W_0;K*FZG({wxtogjDPWRWC=`{ z1t!Zzoz%Q#ekaM+e}MX>Lc-@>tdd(;;T!=cCz6aPHP@t-%;b9CUtJy4k0u_@!Jx34 zkrE8o%?O~e6rEeRUVwv2nS&as_;qj~LIrtAOR}Q3Ruv!Lc-@6F3XPs6fye{APb&3n z&Hm0<;RAjL1;*5r_Y0fNkIO(u$EUmJg2P_7;Rn+f(X3|)fxb;=rC$7>p%cp{(4oF( zDu2}Ojzp_QqUR$;!Fdg=Mfz@D_?caiDt|>P>{z!{wNvZ zN}#LxYCt3kDnRheO?AwD3XP|lOPSZHybxc@dVP@a*x7{vj-(o=nuD@GR=`85x{WsC zhnjnMsd;i}Y=Kk$wkwm%ZMwyFRFYjUbat^IF;W~XZDVk}*tEh=(uHF5nVHu~wn_Rec2jY#|3Ah>}o0g8;E)*h%oRXho5 zyR3Ob)jXlkHwN9!_C`SpXh=^2%xQB=XL@obx2fN8Z`;bQJkV&&!;lO?dnU+CauXzm zIJKxZ9s86AA>vx4(T4pWL}}>mkPEuWj%uWQMy|F@mB5JNp%M$f?M|~!PJ8R$CN8X& zJ;Ls2gIsr$bfDJ`x%EPEpd-Vg%1jMT5@SC#DX#b(UT@gPhj{Pls7V5BsuWS*NqT@K zGmU}f(ApY+b0Br12|=ofUK-Rp4U`0FNs}>;@uu@uZyF6=`l*o`YjYoJ49w4KftB%0 z)1U@3#}C!zCi5XlQcaGexxtW{V%W-G0mXiinxsYk%gu#eN9(1^Ob3`?tQv%`y6j}~ zPs60(e++CO9IXbA&bmYmPDB#1ic>#OQS|654LH;>Tt3GS#IT39pNnA%ZL3CliJp5B zAW2|rmOivu0Pq63uLnS?M=mP(y|_vA?#>j8$iFM)dm~iWra+2X;RgkpElBr^!RZc( zq?#dy;S2T^v#-6z;cvn2QjW^ejlz0*A}>rWV&062T|oyRu0fIk-sm}W1xJZdLy2X; zj$?I27D&;Ta%*?vHMBv5lM4;mRVgsqro;Qm*msyzqd@(Q!azpwozWy?I zuvJCoh}!31mUiS~u)7k;L;)a&o#*tVO3~=$6(BCqg(i(G?DOSC7v&ARGl*$LXi{- z)ex+~>~KyzIyag8!iaKJg>@w9kJ?@E>nxX2WkGWpoAuoNc8@jZ{)D$#Ub8!9nzPV= z<9#uw_dnkhi3H77F?>xBK3o7%2v<3%a}NSkYA+hqDvt~3Z<|?jTgiFwc#EMl z6(C=B5A4i~@ z?-{Oi_R5HMBt4%q8omF(!?OibfUF(#8shY} z3HJSPe-#{DO->D7uz2zs4?$Ke=rEUcfx!%eg<60A-7ut$K?P`08`ZgbsFHJ z$TprcyW@hjlH9O)LysNbOgS1SxiQ0~3h4;PAApW9IGHrp5X=nJ1aGohBW-dx5QlJU z?#)Bl^nxLigK4+yuS!!33=l&heXS|UptrJt<1NKOD1P=8P=rzGJ*4#_tn#)rzI$cZ z0v(dly7K5Fg7_#a1JA6e#yp)w=d!x7EUR0hl%i*+l}V_>_f(|>Va&MI8^EX3mVKY5 zF`#`G$I$D-7;p%+2-c>DluLsp=VeXpZn6jHj zKdLN#8xXTB&$IbBK(;*33Id!w)^t4$v-QMM;`$^do35yv7}2x-YN0LLKuwcGA00gd zz+cmneGMsWtIpTmF2;VIbV~fL#C?CX?vBh+^PhwqynHRWhZ!Qa5vkF@FmdQ}nVl{_mkT~6*24lUmt89dzw zudEK5;|GBUd<{b8HdR-o=;Y6TT~RUm`3TOfMFB*Z1OPXs!J+Z`yuWM9bpxFHL{f!w zgQpL(Ggsn1K}1E1T{MDjaOSHpGjfoXAJ_gQx%#av9X_)Ec}gWf+-@sHn)pWyKtNU$h> zT#4IOg-@$?pYYQ;t_s#!p=(L+eZ=*r31(AcGLZMNA;T7v5-~5m;=t1T=ThSL&2yXZ z<<~WyfNgp6j8i2V=%Z>)@ROu1IdJ(KvdPcZrvb2N(#azFN#6J*$+!&8)*^eMVuFGY zhgTlzdHLz|mV}@?=e_s~0m4bdn@K+C=&8s>1^8%EeDz6Y5 zmvxv)E$kxQ4!))oXL37fUuAh4h9&!H9X>YwH#53S6xyh%4@!3;mqhNwrU3JMLW{b0fp{n+bhE7YOwj<(hVW zuq?{9AOQR$TW-(}UK z-%sm7dSvOBssCzK;=E!%h;#22tssOv9iMFm<+TsjhjgNW>a-Ai0nvkS&?dvEoNeJTayPOCho=yT4iT%tz7cB4#(0FWk$`sU| z$_xjWKY$|8D0&s(c@^V8j9C1EL+ZvNHp14aG0O{IiD5zWt+iR%mQD)*7?$3Kr>l9WNfmIB~1&QrmT5du{$^|Jk6;VH;Ck zRwH^ZS(XlQ6d}U&r88nrrO4(iM9>d_lvwg6Zr{qG#BM>N-Y0x-d9{CO;hNGqwf;2k1jSYU$WHah%;YG_D6)#16rkZlFousC2((v&*!@(qFI@FHUcr9ey31tSlS7|F-=LnUnPqgr0hULK@RE9#3+xB&RE_=+w6l#4v6s*7 zKidH8Xq}C=md>An2p1*(5hPP!{;vzxbs%nIq5KbOhR#vCX8LjD5g@-k2W7A0FSVGt zTNG+asDp9cwsw*UD98rIbM8AKp&N=l-G2{E7I(QyW1!3#t=>A(RBPZC5k#A8v~7>f zz~f4`Z!K{%CW*dy0RU_)>&>995W9ML~HR*f_Vnk8jG5RIGMVsU*FGCKYX4B z$~DhOKv_|inmD~+bzglabp>$W91ez&%6VF>iVst@?p+{hIv*$H3FD0-d}jEp zP(b#czL7>Zn&G5^IV~{0p$&q0)Tgo7zZG1XAee*2fHigz6~JVs?#ksrw8V-Cn3mN& zrmrt`;oOkaze2KGre=CB)M1*?#Mx*%W%t=vK(~0VH_)tqG?(QN2wl-Y0M1lRlw)gA zdBeEw0G`wz+EQ^!U=0;V00RR46U}B^9vuLZ z94_m*=EG&vig0%uL30tDR5RV&5j?&)6S>ydfzI($7C^2{uH(dy3F%`itK1%VRC{HT zquxDt;^f-sLF>n`eE>Y1LK24@x1+hJOjJ|dAnwmpVY;`QtdgUj3iZ`Vwl5*qmr#sb z^2I?vXk`2XclA*(?zogK6^5FY``<%5-k@>)codmLEJmNKSV( zeFk2l(wB051FACOPnC6pYXOy$CRw$#pkA(=^X!QAZinxKI)%+ zJL!2TQ;iCQ8s#7qq1H!}KfcdLX15fu(%TFgP11@^WwQ5uAb2@?){otaIzl7^pAy4N zvA5edN(}=>W$VHf=L~&v0q9ds!VwDRh_g@uD57r+`bdZUBx^wsr51)5uY&~L8IGp= zK~l~bY%f|EMX11wd(kU#>O0gbjwXd4_Mz1H94_`7kht?-6z>&Qm+6&Ry)xCv1s6Rt1xlf_V|me zovYmgL}Mc(NuaF_2EmL$-z&z;SmM^!{GD_4LhCVI2GMRRz?9j2lE&}3!8}RZg?PUS z@vZdZeW!ry;;zVQXw?-DrMGHGKZ>{y0aJHyVf{a;#*>T9BD3}vh@@pVbnUe)!ym|= z>c$LeZ?AO)+rmhXyUA+=Cb88Aj-dI9#$Gq#x$M9G#8ZeVyi=WP%rKhGqK+!g;FqA zB>;A&R|L*}FkSVAw#85oH>Kzs$=93Uq)KtIy$Uty=XN?Bpa>Y`<%a9m+6!0eR;s{XC zoI;DG8oUofAn)!JTSNj)bG+H_g)q%-(E***wBc8$4Or!qrb=My+xQ^ha4!M|*x3DS zRq))pn3A!U=V%#L+FCN*T%zJd;qBcp?#i$8L?pYjk!^vQ%iOEbEjdhcCKn8oxp$F` zy2!y@qu}XBKbzNlD8mgQ_5PisjzCs-<4IYd*J1s~d^n}rsc8SGGlgtV;hvdsktr2X zR{;Z@R(V==U6v;9xhZ8LByUNWRy+;RG!!^Q8mL+}7p1!!(MDs|SvNarkZ@|sgteS1 z&xW0)AvFT?> z6RrmqSt9Ea+;`=I_E5M^RBU~VQZr9*$(;qxb#T*)dli*u$-d={W`FUAI5YimcCVUr zSnXN#1fqbTR?tP}A^T~hK6>0JQ0bZcQ)d0GTqySVXXsVR9y<1DYdQN}vaDyV`lo^x z=WvDRz$~RTBiwDTmriZPsZj>tDqYAvC)h|GpZm*F`@cS)2ktmStl??VjHBdJj@7D+ zuI9A1>?VW)Lxugp*oC_sx6hN?F7Cl4Z%Fi{cr~H;BZ?29$?kbm+{j}y!b9C;;cfxs zQCgb>`R%7?{HU`ky9he1zMvE78otwFuobjk;mgt*V2BgtKD!aN*DPiY#F$3uRSfLNfIHAh-6bcNqMbxsOYrQ)=i@IQ7s7pv$C&>ak`}38C&b_mSEqL9U(OPScRG5 z{J=Yh#88WlZ26WYUMfpVryYlcjwxjnV6&KFy`w8lgVH;xg%O`)aw6_uI~VA@?76X zdpx#kwY7>9=&_=J3_2&leo+@9^){dU5q?_5I%Q%=^Bdu$Bp{)J8inZHb@#1G6!M zyD419PFM06cxIqSN(vP)SwLOx_C&J=jDFuBcwIQNK;m=;YjV?61IN87!>8#|mx2Al zd{IuU?X45|Fzy8R3o-fJ1Hk?n*V+dA4c)UK9+b(iwD5NIj&Ql-46l|f67;LM6NiJc z*AO{j-QjDO=$@oK=FztE{_6oPPS}MD@VG79rxsP;4pI*;+zfrqN_Kem8mq;#G@3P= zm`H^K*0h?#RzhMa!3^LZ{=Hs)znsF)dr|z&n2A5oi~R^=niJJvYV?h-Zt$p&=_@F) z2%_0(7{XayCyibR;QI9l@G8d$Y>R`z#D)98U8CrkxNXiy=9`FbjfjL=CIU&Q0B#R*m&lEyd2|kHdkIw!w3pi zv{sU9jV?2d0371k*^D=rMAQX`Bq540mUgsm(UUrE*n8G($N@-{*_J+yZ5-Y1KKbOo zk6AW5?}rrf{$0H%HlfYIr`JUHMy97ihlhA~wqmmT^GY92PZ}8<6T%?`lU6cOSAt#M z?`5`W)0G**A()qhs{I7>PMUFRhShN!27E!pu9S$$kAR|<(Y%&$9&Fu^X6tCQ6G$|f z^PLLp3{_gMe~MwtO1;9-)f#_Tk`T@${rmjt^EoT}w%2}{?Hb6HL0Fu2MA_gUwRWuN zA9?yr88WT-v-yi30juxNwp`}U$N&>a*uAE?ywE`PuE_pF5?oD;JV?SvP=O>k?otxO zhL1X_yP$Fjp_;>uMxrLve5m#3-joqAn1bd$B0YJPVDCAoIEP(>%AyGk8&U7=2ch(o z(<$>1kT{vCSble~m*5!8CtRlp=P%KXJFq;mvL|PHv^S7Q%#$OPOD^lz`8>?DTkk?4 z3&FcUuv*qzDnt^-&aDDiKMJbQV zC!L2ifYS|S_wMP23Fzkqd$(VDmV&>n!3jXf_(8#;r()>_b;2aA+<`As%?L29lai)Y zY>$N|3u6d5n!4vPH;H7;*R`}1l}FiHx9JkGSA)O2RivjzmByT{09-^*?!5L2V|};fRTF+521w>!Crcb3z38W@ zHAtKt6W4<8XlZHreGW)n4Vu{f%2qq|`C%Cusq76R-&R*y_)5Gt-1fHXuiDo2mf-Zp zPxx&8vLgc}0Q)6a(NZN%?V5Ed?Y_txOiPV|#f)XAQYO_%^n|F%tosvrZoV&8IgLmRvB5%&V|Qc)UDo*+iL?PI1bAI{Fut|AGw{zt!?&@NDvYp zJT&2k4L8RCMb-XY>^3t=|1PuXKPjODmqOzO6r`@ru>tsirePMEjNf#%_-zU2}qI|QzEnn%l_fvT^W(7ScWZsZ%gugd@!002us}GAC*n)eKo!Y0T3hW_t z;n97;{II7AzG4Jn@sE9qPd^YdjS3pAAS2moCfN)k&b!R){yMv4&tUO3Tlrhx(jj=$ z&oQm)^4^^x1tUNmF-1AJ{Pj+KJ*BavKRxyJ-qbyr5A1U!JQ|a|0)J=orbjbnvvGrq z!>NSqOyHXVV*|F}xX)a`Mw9F+t+G%P!qPx%#EDh=F3x~w|Q_H-WUDNEW<@rPD z(w=<%n$f6@MC<$Uo9JG|mRItSc7=!J-9{qzNu?rG`+rxR((bF{l!Uw;ctP^)RKU8k zHSUx>8lVZ~N2~e@#?zQBB?G54ofaHqW}QYC3&UB5kyiBSlrKO|1V|bm)D#X7Dv~31 zNU8-}EmGb2g#DQ_56DRD^$VLqP}$mc8gh4;)2M6W)e(bTfsloZ(0o!2Cwj;;hy1V*w%BmUu-XpUpc#hV)b z+=O8>HAKIG1DJ1HEP?%g`s^42vqCTmej((D$Yl``mhiQR0ZUJXCo+lso`1``^tv}6 z*fD1IbiiOnXqw7MXd>P!;T6r2>K!XC_e(B+VsH2NM}Eu)xjWCJeGDoj zyle-VDC&bv4ot5cDcNEnwlnL3eZ4^VLQ4Q9X$_|0v$T6*$fErPwyvoFifSs+AYx|~ zN$@bTjxw}?>y0cl?7!d3DtncvF-_DLy9V>ENs2=|;yytdV~IJw{r^-xlF|fCzB&9P z+X+7Np1;YM-}2|Izfwp$fYCNpFYRJFKB|msL`t*sNfTo3MEQEF7j>5d$wy_~)%C=J zm%gDl0Ll_lUmkZ0-D-ley6?$>3? z<>5dDAy_WEo9}1xw7)p7tQg@x3crGIn#g9!4gLR zMKs)fIXdc9cXv>!6n0u(iu8(|Q%#}C;A}>$VX8-kh1waoj^RuFGrTXrxHTYzFDszE z*zjJUiy(r{uuq5)koQF-rs%gzRsMGE7@tUZM~i0e6n>rxN?lC{w7x$cus7#5N5>DX0H4PC8Q%?nhZQI96PFUH|WMTf+bKYjHp-f*8m}ibcW&T-m{25 z$e7&K5>BI300JvI^@nH)2(Iip4Wt}XpOXvnu}Nk_@f2aKF*^^Ry`3kD2Oi*AbGgaD z6|Zkw{*+)hCRTE%|D>z^ki4A1>x}kkC(E|dpI@Rqd|TJk75L=v^W|DKokq{TH0eH2 zY(1=wCmxe0^RgSx`_Rwp0>0Rl05Hzbe$~+pvt<&iF`6d}?-gDxO)mFZx9&u&N*La8 z;6Uy7n27;;4SdDapSVc`zNKhT>%oTGDRUg*(_~YC8UK3Z>@=qf3RO2Mx3disZn7rU z9QY4_&8$K!5ge`iw+B*9x6`*ZwJga0Scpri+K(93mUxYk%zD+x44T(&D%-Kx9{*-b zLXuMwBw(S?NT@cl8TUml{M`F*!KC|PZ%R}X_uo$BKuVW0PMi+x-wCDXBf5?GKst;unW>vIWHobY+qOv+&VtCD`>L;0qlL6FSy7oSI zZO7UlKUgdTk$Boh1Pxbdw~ATQtEx+}P-)9+KvyrMmya1V;XlOM6>f5SW67X>c z{w>{8L3pX-6S_= z3a$#dZoDd9jGk<_xNNavZsl>JF- zR`T0qap+b~uHdR4K;}kmLG^6iEGIX(5JH9{_XY;MV)74w8Xl8bIGQHgA_)b)i!;K0 zp4zl2TsUPvjj>B%K0Cs-;8?dM+eQ#QH*##dlMzYFvZ**m1GU}qpWH~EL?juao$o6f zBM!NtkJ~`;%Z8U^bmL&LXEj6We~6d$k~*<^(~)n7ydn!e__OfpMJ7u-YZ{SG0sWPI z_3*>77gnrPp>=kob)TH*I$`T%&*y;_NYG09k>aW}uLw|LDQ0jTfe2Ynsvoi4IVIs_m@f zmE`uNT~_5dV;e2*G&s~B7PQH23>sOGXs&=O50Uj?X=q?tJ)*?+Ub^zcS@@1G>nrCT z+X~;oteSc_w#bH)O@R!*fdV({+K}4oZoSQ<{r zQmu?O9<}igGf&b_ks7A>wiS3*M+AsR5VYDO+ND9@?WzW1NCg;{0HX%UDkN*U^eIJ0nM0TXP z#--|HIW47pv4fq==iAp(1PyD;xiH0?s_JYxT>c=P*#x|>(ox{d7@9A<1(c{T0N5)8 z7qrb(i4F}4aIaFO2Dy5xsiu~^x^_Wf^)%Axe z+5wOQjIVxsoVP8t`U5*=9c%PJu&RKT}(5^Trla&~tgK+|7fba^uvqnxG; zJX$dMwkRW}SEd)@l)vUeH*0Z=n&Cb1lq;a0qi&mmY*wajlz6w%IEHl@~45Su{~#QA?3%Exd&Ms38m{2uS;vB7%>WLz2`qWp4Coo^#X!CfIK@f_!cE}veYJ?FSGCcJ zq`Bh8coEV~mNdMfGr39OAS$^G5tV$ja$fsrY&mKuYAL`YWP7213a=3EKzNSXg;m=(ea?xJB|Bn^oX%e0Ve-x*z3O@YpDfY-d{Nait4C1SDq&4RO7QHs|b1f{MLO^SCpA*KBIKlu>iCu%(F zU5ey`fEH1AwZA%Hd4(7YDp|B6&nAcIy| z3CF$pQB!?WyLPqgJUujDtC>PDd}^qg)8Q$J5yf=g-kzg6E~WfD%i{45G>d;#r@hY~ zX;=_^P@a5HT1Ghx%@qUQb!haX8BMUMF>xLlEwFp1h8qRY-8iKA1jUcs0^?u&EGr;m zYW9m*>tC5MH;{a=)|jpMu5_Z>C-YV?mhBcf^u7o9EVgj8_f8MJV!#2Vb@WG>+g10m z&&Jtpk{pSLZ~xBWjsJ@|zTa?YLy2=~2`z91mYvawbVI^(c+3I8o$oRHhfC~wFs-`- zV#X)Wal^?!xNGm0T7?1J+jLr0*gbhaeOsy838}G`QRAR7;i_4e;WtR7hF5pRe@53f zsWud_Xd+83;|6r<+hyvX)mz7qjpJ_55hS|v1i`cDdk-dfn29@))8ra=vB%H|P3GHHw_{#AL%9 z#2r_IF zN0yaJ1;GPL&YBsdT#!l9Xi&C8HKAv>KiSb4z2N|09cGXaJQmGRG6Nz84QU5=nyWHq zqpLX%xD3JRQ1f=%P+|`;)L~w$rfU5nigToQTQVs21unV*!M7L%qcpLlE1-G-B_Gx-$788IluR!# zFA$jLbv+4P$!j?tu3NmcA*g35h_qa!@!OYeV+{vSgBo4k2xAF?$@kk2DZ}_TAR(3q zI`n_`cR6M@ibgA%z0MvAyCg z%A;kfqHNYit<4+ch0RR>3V}s$W58^dupl4RSPnarvZn*k&GcPO#qPW*^m-Tk+2m&s zZ3t^Df&3Z_g$NVpY~{NdRznx*g)vEpMI>dK9t1$s)(VK#pU-RO#hu@hZhUok&|EZ8 zeAz#Gf234?XDwxvvCBE%HsSmT`jPc&%+`$5b>G}CUK#WHAdPQ)W3+BFOJdN-q@zi8 zbxF@>X|JoC((lp;o4z4$ry@e)zXTX5^n$uB(HMpOm{dvMX1va~)Zaji`~`;d4#>!5 zzKDf>aISD=40!n3@x-0Aoy#1N`hFSJI0FPZr_Dn^k)#mt$=?Bx016wB)`Qk-)KE$A z^90%qAT*AmOg|idI$3q)&u%ny(qsVv&u-W8<{l$e#WR|lrOI++{t{{4Y*iJUp|}%y z7-$A2S)*|rb*H~mSc7&<QRL4$V39N z-YGI$WCAMvWM@(7_r)$pQ8^MqB4>bcdqy^ehjg?Xymv|5BJnwkOjfoyU;N@&=lhkp z#oK8|#jzDz?hpukh(tgb<&&v>KOaKnw4Y7`Y6w`0L9i5iuWS??jx2S4&RjgNeWH9% zjN-Kdfv=qw8{H_REe!-UVm!e-p#TbaQ%$~4wwUR=0ZJe!2{BmSl<-)>6;Mk>xT$Zt z(WxUp=DaY1C0&E`ZBc!EZOArGb7#Kfc{N>+=ieiI=APH zZM(u**B{)jN;74LlRmp^P)JnkDwMUlOYAT2n%=v`u8ZBKWE#ty{$49Tr@^b;rI%xp z%WD`$z|x+v0C`TggySVEQdHZ3AXRhOUkBo(A9Zd@A_4-4$Ck3)jM7e@jdTN`2aX0M zYU38SKvN1Z`mXuqRv2d`QcuHM|H)dzSHp0-*(2V}nVneW+V{LIHWy#bnsd}VkH*iV zaR3t0bX#=cKh3TH6_gp_fHU*YR`~IvLz~SQQcR zgkcI642h^OjATU}zezTpp*Co=PpnMvBioX`TbMUfr6@PnsA3F3G4o~4t40r9&LOJj zwck29I2#ceyIHQ*VwX&1iQr#=x`GoNa#eVS%gR5JUnwEBy_t3R|iV(_KW|TE9 z58IT1KIK3nDJB!rDS!j}hk>1eArDds2CShSW^nDBtbkvQ6(KzwShWMss_#uifX{-@ z?D0z3UvItxzcqN&eO>)exrT&9H)>CMTspp8oO;Eu}A45On)#j#Skk4L)V}2}v#` zaB!f|t2mT^fXES|FdCKUn@An`mzE#Chw`1{9d(4?YQ?)k`Ggi0xT#U;7bG*|FlJ29 zhY=wgkcjD}#~I^IM=v{WfgThXGq?my8d`f_$L$CA+kW}O01)zS=oOsmYMcWbj>r_f z9_+Lj>4=OQTkp$@gi4}dvN+* zbYy`ZVj4DTZ4Ny@wbp7t)SL^1*~5)<4gu(;+nDY(i^ooXI#;Y|$i-~Vi89b!u&p^! zhBaKXHHgq)p~pHCb{@n#>^a#a+Y_iC#&kksW1&}g&Q9SEr_Z0<>;9E`s%VPv z=wJHJXP{h<6JkMApl(_Xqmj1Emqm0L)WF@H^D|*f;C}jKb$ENDt24n{tHVuFW5J$% z`<88!z)DtetUmmJ>NHy0Tr<#J`F)14E%Mz@j2_VZa%eODeJY^{LGk%a*AyBYwbCea zS%U^E%qMs^QWy!h^1{sP7JQ)vv{i?Oh9Gs;!p*c?Uj1lIr$X5zT7{rnKK%9R{4}`! z?Qi80qh0nNw?^{=uCvJHZtAb|BV00+++$0TP{_;z?O{>7E+7>UCZX}H& zvKM<~!Ju{lGD(GN5%pmVTig?Y0J~=hg;0xzpCKyS8W_U)^JB>2r#4uSADbEVpXe^l zA3En}d`D##$_qp>=Ij;M3}1=W8Hkz8e?qK(J&RM`2FVm$xJ?P^==J6~nl7HT>8>D1flYd~WwQ7QH9LNHmwy~v5 z!_0U?L<88X!3K1=KmrgOn{*EcqoGEeR1m3tI4~`Q4cbO680XY#b?g|M=n~cZ6C|S9 zyR?fXk{NXZm%VSwX5Ol1jgF~blwXbpjhyeF3IRq^FT=wI}0fl7vi zxMaIH%*9JPobDaCfWF8V4oETpB)s3i){viqEj*ML-wR`aB6>t~K&?$4;C;ip^8bI< zu;7Bfj>4e_r#z9}KYQBsCaf-eI^3n)0HbYB#|A&yOwT0@87nfQ1>~KKeK827d`9xw zH~9z0XJ8@s^WPP|f`In`g$P22$cuV+1`;>A^#)|bRpCjiF?n!i-b+C z%$7p0PzUh#nOg(29gsy$RQqR^iwm3)X`!O{2{B~ohzL(@j$Mma`jNAd)nN9)=-oXz z&bS%9O%}dZOVG`k-KLbECzBki84T>;AM0V|;PEw98K(ZAr9GUH67Wh`{8^ehn9ajI zDwc#WHGKsDBY=XJTY&aH_U-^fz3AaM#%nXAH z0epaLG+1w8+xy$7EU#plK<6$V72(}zJKX~DjV3dME|PA5Q&Dx6@HuUFply8j2A#@4 zuTLLvtmeG7y2dG9t7GeM6jd@|-YQT`wQTrcGd~91>9-HZ2|PaRD_ltVz?mJ)O2G46 zvhk#^@8*>++ZQZ0O85Dwx_^4Pz4MHE3}gB>pP@7UYfG@HZ4|+0e6>L##OT2|HuHj%R)Wn4EfG~Tw(8dmq6O7+nq`1hr zCdf#oSj^cF#gOoOSqJ_`ZhkLk;r_R)K=W9|DMv0rMw3f6~zo@0q6!SC=yP<2n{BT1o0h_44HW;3C8JPiAX zRzS3bUVr4fwNK7)nE?VAB~*lf_||f6|CL3ht?f|ja?mTVpq%WCb!Z<;YEWE+DqFsx z9*(@56S6%i7I3K8*l0v>iyLlBGtSnCba;ED%oWFN%ZU=6>D$>?HCO9UV~bOq>NwYq zK9?%;AgF+v! zeE-^Mx$?U5uWF2uv}EM6uCJ30MT4w2 zkhoEcHAs+0G%%RhE7%D!LP#wV~jzojM=iV@hWKAMj+FE9;%&Z=|JCyv}x(@uFrMdEtI3J<8A;S#n0y zm7jW3&b0xS$d4GpI$fGhp@NhVHH&gQaj|EjI6g^Kp6uQ9i#X4p0||fa^dzc+>;E4_ z(@o6q=IbZq!o!frMi6WyRC>DQb(%t}V;4jv!ihLgjxVHb4TQo>M#W!g{3J*-j5P?L z*V|Gk4lYkVESG4^=Fsn-_(u*pGefaCS#uCHG;Bgk@nz9l{pWkppX+!m#ioq(gaU}B zZj=-n%IfLfYiC)gvdOVuXi5nAl9+=jk0U@ALrcxZA+D!RL$_olKjzS``==UTCPNv< zC8Oz=eng)aq_1TlG8m=<`(15x>x7cAmh<-lM*%m?c+KNx#CzV41M5jXJ4+l~2=TYu zdL&}|_?~rwJfj-%kOlHJU5{H%rPX#$4ZUsan(LB}?Onc2ucr>;@nNV{pFn*b3C-=) za+mG`>QM|$&%>Za?aX=?%<96lhKZ@c){dYRml><78SVY9F)CK&R5t(q$;j8Z7B=yl z`|*+*(?quXn>78|9=HkS+E2ZRrxZmFMsI=V4RN;nFwS#nEr@;gkXVC?Gp4mA_$P}l zrL%)P=e1+{3jTGYpasza=i+K!ByUrAY43;D_Od+@mh40v8>nR-)GfZE3#7igbiODV|`hlNak@GI4IjC_d%@xZ-ueuTt%J8X8NXv zsio3i_%oU(Hd1ZT6`)_qf3MO7vRWeoNbcTFdW^I8tk|H#f#C89{3{=2bbnheBA9T6 zPFKUvF>8U`h9Fk~f7>u>hDFfEIM!5#2BpjlMhSo$S4x7e{dBlb-8lcGxl|nE&C22Z z+@-_b3cpWhlcT5q74c@Yyd@$UXi)UlU%MuhlxZbuN}B2uV;E99bno3|&b!O+UN+it zyF*!VZ}apLlH$gEM_#eiWyqsMq8!d9$#+1PYK*Tt^XQ%J=<}q7H#q_WUjlY==`f)o;ZgN~5v1rs+wxIEA)Uyvx`OiyweHNPOZ((n$a*rEFVA1U$* zVg0jiOoUmCeBfa9!ta+8>bul3H$7Q6|6h0cFxr~#Q$LZxw;P&D9gW5ks~3Mp9Agc9 zvZQyfEkkeFVIcaQub`ii%)1yqU1AiO za+ov4Xsu?C~oo`Yx8#K4b`Ou`IC zI|Rhrbb2h?-fMx<-qyMGLYEDlxTCYom?CGGR{yBncEzi?1p5@EN|E^H5$(?zNKI`H z)Mp!ptMKi#-2+tubg@kXd-oPbVqK9{q=D2SQ&KeYuR?r)(zIm)?!RVbcNL+^PZ$3^ z{9>?A#n--d6u<jWdI&FD4~`cgWy1Q2Nsp)y_JCbaRW z#$mW4|LQ~WRmn$Gu&JF@ix~@=Wy&&zYsIG(zgJ=JdvFW&tgq$PvTZ9Kmt0E6AC5c% zi4$LnFrD0xtomRQr?5s_&A3B7xuqfviuRkX`iW&oLFtLX>0yxOEwpYxn5#_NB*ptG zPOB6P{qv;hR!1+DjfNkO6iobZ*=x=~wL16`_(KYm*Md%Qx#@#oYZWe^y8aBl+|ihQmOkDx5lEOmm? z<<(@wZ9g4ha|$P2x}*;T&ZNIonn|D6MRg$Ch<1X~7!>F6YYN@eaRFatMa5sO^zuP$R*bBk+tp<6Czjhu8 zo=V3(98%xd{%N7_0k_pRojiGMCpMg-Yj4X8YZ-Z8U+jRA3I+BzZb#=e*%rHB!@U)? z-%n`Bv*QlvfvmBeAWb1`o0(E+p#F>Q1BB}6IPr5>s-`N1h}nz-9LzX<+@pbx-x9cm zG1G$K?2md+&S~qTxHKV&?%6#JMQ)gud65Eq50}Z^O$k*;Elt5uTbsa~sman#z z&e1w*Y|l<)8te(*W-q#<+@3W{@L*~n>SP+FRL(5VK*YO!y&r;|cy}m1M^!W!*9*5l zuC}`z9Ec^*LQk5XYX%mK(RdoonABR6Wm)k(#!ABmeAgPPu7y$s=w`qhn;A6(k>o3; zg4$}Mhy!Q@LJVvI2)Un4PC;Fz6G1n+)Ro|xB8oM|)py%U*|BCJAza~cEiLViwg_-b0z)nYe9a`jY9FvAn1=F+ljm|ShPbe*>nM~-Dq^(GIH0{zbmcTNy0Uqf{M%8UfUmd7=ca3OAh)tJF?5N>waEi6ErA3&t- zwmhC2*z0xb)G6>EZyq85(5Kh>f}7-^)Vb@s@ibQ@8XNDIs?vYlEKc(vtknAXvALK- z=-4Wu=%u?d`-+sEvkhuQHhw!b$Orv-HV+E-#RR0%ww)@APhZs`ei|H@SQNpcK+g^{ zFX?b!!C!}|dot#=`Zi`P6$1;GU=DJL3AaGLq|G=9y?!VhsS)@t+Xs-k!k#Gvb|wLt zHsCdg$HbvVC^^i))WM2uw6q5Cta#hCc%S(AA8oJfa&5_*_(xPUGfqC@2jMBJ3GHp{ z-Tmb=cFUPiWy*Ul7RQ?4Lumz3EfW|kGhvb%#+XZh6$sJ_#vjXo)_gl+g+F^tP?-&?ts+p_srxy?(up}tG&U-q^Qg`b=KARVOzX*(DFJ2 zJ#>hVw@V^OK22s&G!hTjN&zk5pF^nWsVE9nk`e3#B3Xmg??Biqh70qgyW~+wcS(kD zwn;)dLagVJ_PVcCpDmpR1UZ1KlN|wXxy;3#Mj?04a|8d`V?Rf$%@OrHqPvN*=7O%H zGVcE7S<=et&5{^y9eZRy;5j2$B})x2F3!t9rOM*1K7cq<*$2kn_RyUz=`=LXSyV6y z#o!G6=k^yeWVRf|Xb!c`f*nhxOg=;CIP6rj%7(%fxRYeaC2jxQa1NO@v;t-TBiAEz z2OIho2g=O#NQih7+urbMYh_&{M-n(iS_3l|fu=p>VozGUHfF6oP7iR)pQ;@1CpiD%JmrT@Dr1Z#eJOx87N+HmO=&aR9jwqO_r)-3stkZP=N;7JebK+UA?Nz zG213Z;YSDspi^9*bnwS540Sp`YKf<=qo#)ah}I4@JI0X=2`7ZVvg4R;A9~Ot+qz#I^q~s@karL_Q@-}&(^EAQe(LJO&AZDo;)xS zEQTTEu*}rC;z;8r0?QyvA-7aOcP={-O;KSLTkWHk+t+f7fCD5roakJQ8;I?7g_3&# z%(^;mp6X6UWaRfQ-@kmH=#^$1jIwJxWscS{-7ih99h8U;&8nDGUC!5kQ0|#hbLkfJ zgCXd*^GlUeXzHR<-0kJ~ybKE+6|vWBmxxGgRf~Tb2AX>W>4;KaTDn;GWNY5254A43 zNk;RwLp1wxA?h)`1{zNqo_#n#wZIzrgaoC7)oqZDj(kkNncNP|q~-*dv&;G(_D-iP z`nWakm2K{Oi@m<{8V5UrZgE0yyrsAN0Z0*T5AE71l|&4?UVtI=YAXdhmPU&$1%Ql4 zZ!or&YucEsIHo#v7@6jBRYO*iLzlh$C^9n5i%rDCAu-^813zExOAe)ExO-65i{Y1m9k6MZ0d}qWwAaJrUEv z>p}A)KwGacbV~#xfJsOUeh~)p+aP<8oQc$*G_4_kxTj`rxZYTrh(l@bllkA?uUW>D z^W=SO%6BSToYMNP(QMY$;o@CW{RiSh|0!|4QUcRF$KG8oW_!Q(LVw=!;J;P+&+7{N z&X6BB6DXB3&$x6?q-+e0-NZair^guJ4Rq!dRE|r9JvkCR(0ymtCrd3v5v?7XLUTXD zn*1C|$F+~3wnX+&melIn-3h}jAzzur{nHG-<`xX^K#svuT4ZlnX)B7yvZq#gXz$)= zaX_=Dh!(*N4+c^1 z15bpgoh-=jd>3~jWvo6&D4(x&)JMpPBDM^O+|riMQo-;(%t>FY|DZ;@et1WycERqd zfaZ>g=1%cTI_GxzSD<%ypqfM&j)ba4^>n<~SnQqLg4FKE>7ZIfZYtMY(tG|Fk#R&u zCPcoS>KZa(kpKJ3?RK@TMW*(API=1bsra0&eA|f$i+f~}N=^aUu8p=+&ZY7@J=6DG zI<%{Ra+a!mSitb@_C@ z_wuj5-o(p6sqhhff!IFr*lppkiOAdP%w04H$PZ&81i{*S zGK0TIpNTw>cA0=_EQT4j%O{=?bC5aZ!s6e-@Vds=C?}q9Y+>*m-2Fji;h}ec3on%u zuf$Lif}V>EWnz|^$%dnn?+vRMtAS8qYeGI{;(o92jVX)@PAG(a18ba^T~Q*k)B3A8 zY#{~0uAjLv*@yS)%wOa&RrqNXjY4F-HVNv*nV^2ZCboPzZpSNoK6iXn1QE2UrA6TQ!)NIs-V- zkh@$l23YRg<6t{$YKvvbH8rg&=9|8nw7yo(MtNiv|u$vuun& zdw1;uiU2xbHHk}tW)T-^*6%E-Il?G>Xk8lIMNL#4=nRX|#?v5~MW#q>MHTrT?h`}s z#g=W9-qE0Pyq072AAlU74Z+`iv9-b*egW~wrS;*ym?`a z@NQe&3-3rKIlBY+>-yup?#Xnu(qMwitk2Wba2Ftc-=BPBT9JH6;cc=oSB6=t)8t(W z0G7n=dF>7JG6{yQk;^}?wSKRsQAh8AIRNhi&re0+Q=HKN@;-OyYc=H;4WG)1K5{V< z9wf8Ra1h@vBl(!TA}rBz!SN}Apv+XtLbUB{fl_{k2g*}CN-xkzQuW)L&`o8LR$$!9 z2g&o=!jLl_0*D`A?-mVepneX=X>3zhT$hb$ph#_AJmuYS?ym1(PDMRG z5>hnI)L(0oD#tTZ2sW;Betw+$eN*{tp(rw|C|Rcn&X#SRy;xS!fLfT}lGRe~i#m*; z(cjyF2&O6Tg*Z)aot^rp3+m!eZXc#!Bti;zZXt{$H9&fAxBT^px4PotZ=frnbQxY~ zgOVpCs+aXbn9UnHLAMsU}K3$T(``B zZ_4M5z)OLNT5kQ&!o&_f_tgH}QO6N&pd&=eM9cOacg<_9WLEZeVTO&8T3;#WYHe-; z$@SXA*mluzq=y>f88Em9}tS1 zb2w#=Wu-kl@6uq8zJd5{u97A~29K;Zt!;HS^gD9#r{wbQt3H+nVHRFq;&%)45zIBf zZc&3_5g!SUW){q3sXupg+h);B^Q}Mh1;L`JE*pe+1p`J9?M)JXf`KS(PD=BV*&MLj ze=-*@FRy9tKr?Ck;P%F+6Fg#@cl20_vebaX9 zznbHVy))YVy1+Wo6h;zWF}j}fVN8tsx|T)&1VSywo=-Z3xU$=_kfG9OXfw6atx+MD z(jLm@X&v*nXHx?EIZ*&uFrIyJr?VF08zIO14~Vi7qFRD-z{n6xFOK7BkjYoq3^sSv zgy-~C4J&Lq%e7BH?TI%LCRID8eASq8t{tiJ^(-r+nrEnlqu_}go5K!={VfF^^UR4x zuO+^=2Vt%0Hx{~~r}$^27R-AjStscg=HFUr(RgKqryV7w@j0&~k)qUeRsWCQaW?v~ zBX_swd%t5Z3jFx48(JcObr2C{^`czj7DY)!b2<(eq#bt1I1I{?%C74&O{=G|CB@-U z15AdUnL0i^d1bW!VxcvnzJ`ruaS=6WXbTQMWO;{VT%swm9bOpM_7QOL|F+k|%7(wR zdzob+cGs(7F}<~&^xpBNS=_B!S~ph7Blrfg@reI0W?i#=0%7pL2a6;|w4+ZX6?>sd zk3k%4q`>(#C3alHH`W!>+OsnLP4Va`>!*0gJTn06FE&^bvcusqOt3{l81ATsTlB=> zdVIf_0z;KY%opB<;W7=0&S#SY2dwzq-WdO20z79>fA#8B9Vn%nP4^>Rf@zg=;$Zh0 zt)KTtsSk#F|Noa7goZzzSwcu*)(s6IIs46lGZ6%$F}{B2{@Kq;BEi;G#5BLb9Mt5tuaBU<4#OY>NT@;*L|5GUuj~#mbq#tU06eDEiC>n2 zDCY$-_Kn{Y8>x??4I;#{ajsvybkb>C5=%M2It82?pacSDv2H5v=~S1hvgK1C^`R_% z9m9<@*mV%W*-=kV!EjQLsXD?P1}5W*da^~5=PBCo3b+h$o}El%(R5vk-%PJGk4ypB zt;v75*9+QUq9@?rWdS`O-pZ3$7T~*RlbS6fDVYkuw~`Mxri<9qta{Z#rljec$*CK( z^=sC6dzgDJPdNf(tUvdkJSOQru{*=>&q7f_dM@r4qvb}2*HymVYU01)><0PPuNKYQ zA8?V@9_9SUANhuMzb*S_gL-phLC3bMKa8gwNSdE?>|4D1`5e<-+dEC~cI#vJ6JAcF zNPS>x9Vs@uR$)n5vh0MEG5p+CQo?9$D5iyOJJ^fUI$F2Ks)7&B@b5Ne`wR}@<{i8o zobY01UHld1fT#9u;6{k>*<3+wF|L6+aCiP#a0%a|AUDNt!t`n@CPxyJGuEyY0oLh( zk|DGQ^}gKDlPsMwPF1o1n){}wu%~oVO+&DTuFPb*>SY-+uY+6a>Loh<^$lCI4kKQ0 zYQt26X@}2zHnU$fOq_R2=Y`SL)`>bS=iy)fu->aQtNr(Z&QcuJjlFucM`gUum=%N$ z_M0xYI(L@o@;%g6{Wixul(b^sLCSRQ@)L_EYJ=Rwrp~!^)`Zg|+AsYD>;qfOlbn?i zMLS*<0CY$!-X_8{3i&A8UVV0~jEp^Q2dnbUJ7VcVEZrtG)1sbqGmPx!t2Wqh)^|+V zEYegK-e0Ku8Jc+OSlbhyC}cTSM_vyc9h2d-ccTi{TbWU&V+QA_%RMDK`^yEzP10iT zB45>{-jV+l8ozoQ^)@<+#(Py6%6!tfR{J5i7R63JYvC#vnwb~0TemiD zwCtZ7*jhBo56T#qZPn(AH_Mr=bu6vTXk~17-Qod-OW!}hEq)sJyV4wX=T1#$?trHw zI?5T^3(1nY9y37a-&xBFikkw|ibvzEiVDC)d3J~js^WU+qA2siPzMtqsM zdUA~`Gf~tTl^xhFPbuj*4mSrCKXC(oi(W@N$j7DeFO&EA3)T45O|kcDydw2n#vhLS zW8~~MP0p~W`v=|y&yo*u^^}4IH=SeM6UPtfH8T;7Sn#JegL3=ikJHjOaim(Vx}xMpXMWZEww<@tcO}wn zIU((JFRS_!UE$-Mp7+4&MdLs})fRj}qtDXp)QMv{w$t)4=KQw1^Isfaa{FQ3xZvi( z{2P~Yg@O)HVi3MFP0$|ovEnDMpr2wv-C%minFV$C=_!_?6Sn(#?6j2joU+{6?9_IL z#sn`ECdtgHEHq6U>tFDlBHSVPKE_Uz?@}L#A69kah zQ9MkFzCvrXLZ8CUs|z#~&Y_;@Rc}`OK_E5!h${ufso(zA+(*wGT*kyv9V2v9viy&k zDwSnJoZS=Ti#Q~mrdIh&FBKm78txkzKdIa}V({g!aG50BqEcB$lR`i0bwY~bq;l$Y zb%*IivNV_w>gkL-_tY$Y#2NlGF)1KN%A*jC!1ZH87ZjksZ4q?%w=!EP-6yBADqV_S zTDT<8=*9`QV?*OL@01o9@=oDdzVbCd@2jR|7C2k4%V`H}aZ}Y1dFV!&EnRNqQtiXA z?iQwB$do2w9NZ+nOcPA=CaJ&H6C=e#2gP>P!0diepSpP7gRW$cVp>cmNR!n0Z5ivW zAD_0WflRQexU)v4q{Bz%eSg#u9qqRTF|A(mO^WA$FLD^HiEfIe(_+g;b4q(I)DAyx z3JWwS$aGkE&2VA9+2pVczEmc%3$}?rRcp9oYV=+F#j*P6dtM@jOGc7wuv=MZH_uW` zNaIw< zZ1AZjS`>1Sq1gusW;?{X#(L8wJ8z^Yx}0vwRy&CcsZ|zqmMj{HZ7ca93vQ9ryrHFm zVmS&IsDrDC13j*Tr)+iL>4e-{n1nVcbx_h12|RRz-n3wP0n$>gn)q|SQ*hGt(1ZRh^?W*6#0sC1h9uaAM}&nX(|qx(1S zSay~f$*h7O8>K`QHyC*u5u$Ftl?Qv+PTT(&BDq`1Jsvv5t07K7H|vE5SzKHb{rcB} z(cX|QnN{+Gmi#|^OLAh04KGafJK9}JyY+oWLH(%J!R(Vc8y6PvXci9c^V;Q}v>TCc zA3fuav^f`WyY5DnGRFQKF#`l}r7m&(2^3*0Q%ZWdy7G1|?Z$qY`|1J7&H$`pd&lY~ z;=k@6dWpIaEam_8KX2&rFHWAU^PbO)HhJPt8KnpcOOK`qg1TPrY`1EN@GpvLj(ag* za+f|H8W1Zf)_g{(Z%J%0A!)nVrzE(3jA(YcO*L?6fdzy7w&usT9C#!y zD=KLfx@HRtAZ&cSS^=@7bo$5dIIg$SEL?-jt0{ssQJ zAq`20Wstx$QpUcT+qor4`(;~7bL(<)4>f((pGu6X`g;J%*Fwp&uXGh@_BcVaw+tE7+wcT}Rxt;5&8X_=TD*r=@Aiyexy;tW zD8WTKGm-H53Yf@8#J}rVZ5+_!?|ixlc-G zZb_o>U3h%$fCmJtv?HSfhn`U%HeiyfOYOUuxCX|60gKTTTQurZVlJsaY8m38GuB{r z3SCG&vu%iD_NvSm897qwMIkR4q8eZIIrHYEWW<^xd~R`%4>3-H*U+E7=*{&NoymIa zusg=&c(nuvaR6)buHhb2XY@Pw!B<|EkgYs!%QUm&$HWPyl)J!er_FoeI8}vCH6)qp zaooftnIb3nito`rtiPEqDL=}a?8p{$Pjox>WhcGhMQPoSuZa(Jx)D#x7?Xi)gjM67 zzjG&AG{?7j!F;TaRRBzJj`AoeEJf*9h67yW^y!e-q`3M%W@u1IR2t8!$tkBin8a1@ zqH51;kMHslx%b{6PWc#blD5>H9x4^uboq;hR>Y!Hq$Rn_gJ3Rd{EDYaW1erS!@_7r zj5yByeBDnCSS$5LyGaqGXZbia$k$RDGwtZpR8oELm`JX+O8$R!eR)(f zro#Pnn(L@`kiNU~u^evW7C}tbgb+D+Fq=g3^O?FkE8Buu3$Kb>r<$VX^I4YRF<2GU z^SlF{S+xsYT5tUy%5AaYFtKmw;z4)$POV*K2R`3L7Q=Y)a*M#{k0$u5WeXP@9``X3c#9 z{J%HKzj|s0@M6fs5J~P`S@W+nq0ake z!58A#XXxUfRzgZvwf?0swPQ3onUnaq)dzMB0WYgas-+H&lMvSAcW%{6`(@N< zEP-QHxNCH3=Mg^IOgn~3kG8Zj4b$@x_S@*Ipk$OZl6DIu-n?4wbFO;?==fJfCI07){fzdu%>);)Zej0!O3ip z!;~rEg|N49kiS3oMt&_AUOvH+oio%qRp4@`vBBB>-r3LdYtfB6|53(V{V(Qo1|i7W zD$u^#(kQR)Y$R~EDZ6hgQI9!|#eG>$E38nywm+xFK|>?r~ow^Raz3 zrVt%D34?&TYrE!X+u4n-n6EukZw=PW7RR@4h*HPjh1Xx5H+8!!7UWVp0&wgosx44i zW38ev2Z07T-nDA|?#nq%r)5Nr=t*B`Xhup_d$ve-l(6m~+bN)N-w;H|UJZ1oZjn1r zUVV4f*!mwNoQzG)@)!x9P7T>676+z>)%sqUY+Q@3y?@5A}Sc=~`!ybp5 z?@@MNXIP$n_N{Bf?Sx?ub+VKCri~KMgyjM10)nOQ*OT;HCnZ9Fw6%MyRz)i!Y5~)Q zCb-)4`uHvjr${>89sOGWYA#Ye)SlOmQ?oUyd1m+nt8_jLrpI-iUY%5Ek{-f2ZP^hy z_m^y%lVN$r5b1}|_qf)UMz-(cg*+2vTr#vd@;e0Dmsqg53Sr;LUa2A3gjR0AY$^L& z*6GvWC3L8fe=mx-Wz7S@!B$$eJ|$K%ui`b}#~2hXJ2$UC8|ApMQyjp4FWtHHl`Gd3 zB4!5pTCh9lGO(kPKtTp6eAB7=rSqQRVO(gURcUYaZ9OiD<0POUWLc+aU6zk>*7JBvLhFpQHPDQ-|>#S4j+kk$qkO z0yshf+G>tOWh7=^x==bOhY8FID3WAN7Lt%Du%_wqB5~}DgnQqXnMrbMXJszoM8W>% z`RVCqL9D!5Gq!u9DOqW%S|pk-sn4^*np9_YS>*n%E^0A8zShWeZ~2#Uc;o0lW5R4s^C|`h2K&Vc-AyZkOj5XY-Sw6Dz!m@@>PZ zK6mq*plS_B4Pd0I>!rSTCFn4Kgp$sLvXk#dhCVxj18DjKe92Fa#xMv=KPhFv4)aaz zeL{ZpNu5TXshfmV7tl(aVP8rBsfDy|0U9;E*xgzquABK&lTm*d-zxeMcpAK#jdv6U z<1hrE9CX;hv2BXVVr!l)kI*D~3?ohnl57FtAA&>Kpa^wt$Ghp>XZMB|cRdFB#wLt@Z;9h>HvZZWQXLIiPdNt=Z9kuozwvD`kN1<&8h!QpJ(XQ^undS>oj)Kb=ckrnh}8B{&%Y`G%0|r zb0aLHuA(Q&4sH^P>ca3KJ|lwU)>R|=r~V6Xy!t|WT~E@Xg<*GAH`eAh&fh>ms2#&(`F9YS+bK<=!1VBpn&}tg-0>9- z8Q@*(W*9(9_Ul>A+df)u-A3e#bk^MKi(YsLCts2{FFr#FM{!$o>TC|r$^u5E(hr3= z*2I#qw6>BbsVJVM-=i@XhT8yga?$CsYi63|b z-3bAaeWzmDw~44u#A0We8YmB~xRgUudCcJtKzrRyn`}HA!pBC+=!S4wNmVEV9 zC%?t#F0K)sQU!SwBug;BF6%C{&yh6l!{LIdM69VKW!1|prH4co(zWbMdRaLyHGmye zH{VSI*S0WSw=lq!l^M_0Pj^LS!d&p?EdjC_N}d0CB;TE?ynL1 zS}~ASQ9s2nWD^$p$3Z=Q0z919z*lG26an7($h+8caLHxdVwBH$dyS2B8y?)QqCAC* zn|~+#bfLjjsG@7f`JR8_Kj+b8MjPQMT{&30KAMK@GxKp)o3>*c4$jL|7GQ+sksuT6 zR(#j!twFHoHgpRjxRva-&$|~LeapA*^xxklPUrJ9%rr_tU(RpUKQ}!k8)e4NMM=>?K83=O)QV!THhQ`PqnbUy5 zC#qz-(penzZQZyw>O17_KtPIsP*(P7 zx+MeMQ5jqr=cq4$(t-QFIJqxQbUPd;)$P=Gjy2jmNtg_B8W-m)M?o@13$)XaV`oD@ zlvZGnsC(nDKkt;QB$Z7r!YXh1=t4QcoD44Rtdc!g80w2Pgdz{-Y+ZSa!wIY9$JGs> z{eCsc`@N#nH+J0V0c%)H6dgu3zI0gP$wj7PSMxbZzdh5BJL2^@cB;xkTY1F5)VIb} zVU7-UUb@p<1F%tcrnT&dH*bfkL~Wt$huINF5Xiv&_*2;>1QD~fo z_+3R)XaI6`Ll{&?ibIB&TZ zRYF(9u>CZ_8u((2M8TrVrRB8?$?M)+)TlRPrS|pw8>S{p-pN&eI{c`_Q_WfnjjE-}d{x^d*_tQRDPTtt)?m_I?Mg=;?H*ejw_Y!PAs->p1oDj6{-l%TS-^u0;8rx!8LHf!hy zT{^sYrKx4`pa}gcj1f0LSB?a^t|spH!HJ&K2K)FxZ3U1i>$l#9tp^-R=vkBJdncHi zMH-qz80}YcFS#=P>tK=*^T_3jq#0l<7wV^L6D&`wFTTQi$;*pN&tF%mJS&LfwsBiU z-;gFDf5Y4jZ{-F{X8dMF@FNR-nr_s+ov9f6Jj_N5!o<*J>~F31sWh0Zl`a|T43k7; zlENhSE@KDehDo}g{x#y)v+81tB??7<&uQ;hhPKykO&nix7-<7%8~2?YHoR&wRbft& zp8k#ozWXPvL%|LAMTfp?I%nYM9f)#cjmUeMl|=RhP^x6PxX4~SWn!;ODYRxN1pV9 zvj`XWUat-p*Jtm)Wa-{|%ond|umkow>maBs%_v3rchco#jo>+5fF z$1}{#s6K+kl@$H8qsqG{p_GHi9ApF4=nU9L-h+5^aSwR&tYGiW@|yTRTXR(aDU5d2 zX=|QX238O0EPih zAIV&I8{Iw#!K)&=$2e^MSZd$Ge4mlSC|NYcnKdt2&9qc$XF?jnv*9gx;`gS?=axT+ ze)sx(gJ8>b*ZrRDr~wfGcSjNt(M#xDF|=zg)i~pIY0;vjWrUCUy~jIl^I|`NX^R2_ z6+cI4$w>U&Flg6rt&@mj1eeGT4R9|t=F6fLOS!v0ZxD>dmNyUsnlGUB-{pLb(og-s zrI_TBK74e25j?-cy}1;E!RS7_JuJ%jC)97yG?pNl<9rr*xmTIwwbGA}6${0k$sz=o z+;-Kw0o|-I>_7M%|Ln=XWCf=H7d1-?IltpASlayk+}0ZT14^08?8|XT*^T$8SjE4V ztvI)WF0H%zzghZiglssq*sJj{%?6KAwTQmI#}b*R6%F8>YUg;?EifL46m-%~(a*t0 z;TVxcz2_ePQzM9+nrGb3PC6tsP=Rg*`oG|q-KvL3166(9yCTbK;wOmh0}iKQLrdhFdxy+OU!u(s91ORQUhlty&GQImS9J%?tee`Z{4VS0zZf80k1;*DP^{)f6#p(FxbY>| zdTRK8>0b+bx-S3;q#>+9Br`JoL`D6Xx|is_RHAp*maRTJ#b_gp6jic0YT={RZ(Z#h zM)|o*{qWH*$+=;^6pHKNBA5J$d37&p;7BsUx=zW~l98Qf)IH=T*H*-5H{*$7hN1MN z{w1jED%%@5Gy$ph`@p8aV{Z#&`ZvSYeTv8WrxuIOeLXCa{MfVNLFl_Ekg}-gIC!|0 zx^}7pT|li&p3+G!n*W5lvm$VWKJ@~Rpq0hHr{>k&dZVgrd=9zgALw+i`q@*-A3)dH zMYRq1Vh9M7K@~ga(UaSgQ+q1LmL1>oA*WQZ(+#408%$Os^Tn%&hp$YI^@N=_Zb+3- zofuYA70lV<%JDB@liRtOcdpk~7{WiX@>9fwl+c*e?%W+8kzpv9MD1g`$8HfPb!8j4 z&M~4w3Dz*%Ef_E7Fyx~}kDhF3p53FrwA2^>_55#_npw0@|6nbZN_HXublAz_R#nde!0DFmtrb3;L&z>2ru!X5}si}jXOK4oWdfxX$1ArlO+`G#@kfS^W~7@ z`jowVQB5YUrGrMJ0s55zz*yRh0lL$PpRO@2N!;&HAG3QGK&1HgM^D)q=A5H5zR0J8 z9Dz+PDzkG1ljc#9bzN(iF5|-`9IlT8qEPUqQ6J*Ew8gb4goKaCdx1T}u6)G$DSPty z(}La5-51Gl4VLarOWL#yHTYh8-lh2Dxm#@#@o2qMu%5`-=bp>G%8qR1M`o6eFnpB1 z-K(K!lmREYalROW!Kw0*DB}%uU+7V9*^uvx<$S|{s&<62OSShxv{n6F$P3QNoYSRi z3c3#8gEqPOzR*cg5d4z247Jw+Ec~7J`Aa#I=WbN4u`0W`KRLOmGznbWRrgD}ICXZf z3inDCm7R$=U!Otw_e2$wAsiKty~f9VQh$m&AuP9U#WY8%GtRCvmLsnCYRZwUJ?l$t zFy(Vq(Q|G50uRsG>%v&N`L1M^@Ouc#5kdOD6x3T=hZ+N-o`-LSF2Oa3sq2a*6uHD} zZUXZkSw(27*4%F4+K(P#5dOiX^KGN{S*0*|Dbm11(9X@xo$Vnf51gA~oL<=m;A5>c;T<&yBwaA(!H%wAI|R1ymQpb#`F7ovYRJk3=P! z@O#%KynOk^FgyZ+lbKVv^t3PlhSET+{DAv74R5|T2rF+Z>oB}=#H+ta^rUR?UZTVL zts5~LAyQ4Ss(Oh&A~Ro)+r6n&B*dpr6IP(MANx=;#;bC*n>!2zI+ENt{JeadBYb9= zVM^KS#uMBiD-V;EZIQ6(FTNNq(;A`HtV*B9QNK)WNF3`xT|7;J%5UH133SF<<%*3Ay8ZwEebnR@)!Cc*O4kaIBnOAj$K<8r%>BHrV*S9NjNRkfNF zUHSJG)4wuD{!6$PZoT(tr+a=$C@(Rd?G2fpMO zvpdP|%-lDLtMl4fy|$bcsJ#mx@bh}vl(^*Q_XKB-5=vbQO+4JIG%0K$!$ed8T}?a7 z!RS2BI%tdk>?SWO`53$4S8}RdZI6}?J14)`DFE|TEs_YZ$b@``Z07ClA|;h6@e}*K z&}D za(<{eswsDlh1QN)cc^d*Nm1U5ftr)DC^!h;zRV`Yg(}6O}A;U8H?bzl-cfjVIC)qEeAqly;)JH{l-1r`X32PPtVorY>85bwNK zrLz<%=zSkj0+6c0APzo-8-#_#A}ki3g0Eak;F#qjG}bt(q!Ccws69w;=7@oGnWQtU zdb_8ZO<^(!Sk@Hy-ZSPCQiO>R2|Sn>nKyFy_xqMSpW83+aX!?FPcncohcCobPI*)l zJ^>rlzj_1;tS0DOS5hVNS?hx@d8YJS_#$> zII6l5^(}NM^MV|Z+CgtbV>&>Ry|MxL?+`n~3BMjcGb)UQCbX=`xz@`TcKPfAXx>fP z`2oJl?&u@3{nOI5q6$M%1^jJ^uWZGBZt)!L9j_;}w^c>m4btA$1{c22;EW#zTFpUe zyaJ@er!zR82Q=Oqy4M^wK8Zkt@f<-+1`6f#fh4ep4&oybN^v14`tr)VuR5~-@kk|j zT_Sk(6;XSjA3^9R;Im~+*rs#Yp3qtGs9idgra{uMoUjY&R1) zCMH{Si+eE8nn?dwFbkBZ7yz$$O`)qiGG&{6UPA2ntHlf`Kt`pQ1yKh>4Gh8>#ekQM zPe&9)9@Zc77oq<=X}yePd@@Ck)hA!9ECvIobb*;i`eCbmkuiK}uz;C5@YE*%&VC`x zM&mTy4dVc70_KzrgM^}Mp1WoaZv;9iaFD68nOuBJSpMb$?Mt$wVM%(x#b@m? z<=wYNe)s;IcjsU)xpJMW5d`f$T;Cop0T?9U>*Ui$jh8(3y6tRNQZtraW{|yV4uSAJ zreYO1x0$h?>E7cs6e!MC=LI3DD(IgE*QO{MvtblEpf5V}oA9^~nxS1hL1zzl(fAtB z$ycCxF8pc;LCpqxYXw;+!2VDk7hR2Rws^jtn;am4v{|Y8Gg_0onA^+ji3S<4A(pif zNzbQZXr!KGF=@SIHH!Xj=GJ2oi&0d!H87Jli=GhDcRh49+@taTeEZS$o?m6;e~XmT zW33B|$5E(~AFxugXpBReDf~>XYK@%cC7Zwwzyk6%riOOkYnBgGrjKJeS=`#BJwc9V zaUx475P7db=2CSJV)}5P<4aREH~ht<4*bCzEr-$U$7G7WYTle=u%|l9dp+L+Y8nzR z=-v>B|1frN%ppw2$}yf1Q#0Yd>~yX zF=ar(uOpIpgB`8BIYVRyMZtUZa&N3=aT^&YpWcLVcbfy$`>N>eXulnNrh$ES;?*3! zWgF7VKLV^I7!>E?oIy&XXb)WdJKwBrna;HW{cC>bVe2QsWFaHPk4yoh- literal 0 HcmV?d00001 diff --git a/demos/occupancygrid.png b/demos/occupancygrid.png new file mode 100644 index 0000000000000000000000000000000000000000..15fcf97fb7f581d2e8ebd68160c46ea6f8d1c040 GIT binary patch literal 76486 zcmeFZdpwl+`#(O_wpzBlZAk~Qt1TgiO(n^wmaIc5$8t=ia)>mTaTx5D=xEC+#ON>% zIZRH888bz)&gGae(NRo}z^>81Rh3IAD!F*iJn%Bh#_hktx`;n2}TC{%8w z#H{m5`1cQ&|2Ty~p|*r0?`4raqb?{EpJ=3i$P(u`H0PD&(ue=Rov+usr&$o5@aX&w z`J20q*81(Zx#l(I`f*F<_s@e)tazQ`%Tvf*9-W?arkfrwQDCs*KQ5o2F1z^LRf|y}vXB z__Pj{HaPMg_OAPfrsvxNUy!v8Gc|6ht+FX#W|UQ*ECyHle?LuG^X<#eo{p%!o0$pF*U!q%?#bNoPGqkSZkK&SF-jDPrz6Ri91L)0au!y( z;m(qecW?M{?3dmL3bMjIOr|b^9dY(wSvfgJ^xwp5UKq2|c#*TqUTTft&t7F67Zul` z*0#2-3TG}|QgvEsk+w=q@HZ)Ym#p>=!B$sqv$!TiP?tX}5!TUFz~36z40j&&NLsZ~s7d$?adA*7zqpRO#Ql zH=8lP!MkVaR!BUqPD*7N|iOWCzYl=(l zl!pSV9Y_&gGj#tB5r^cVvPdLD{Wl*!+ET?sH~#xK<&Q*Fw<2Za`_n}^3I|SH7ud$D zi=w81M?q1PFKh-sWEq&7XLc}`$tF;HxqI*tO01@x$Pf%H~-GdoRzb@EV zX#9dUKRp+9z`&dEwHRAukVAG1hhEK~11N+x- zQ4ixf3uUXZ=bICrc3fgKKQ88=<*3jz!sz`#M${Hj?$5+w9HEdYo?OXrdXXu#l+3%3@I6K@j}|uQQ858HIZFP^i$QR;nfN^X=av>h?5I2S^k;0P2;ck|5q5S@Nl_ zNbUhMTQEkBsi-Xmo^*1GjEE>KEJSpEuti`PuXZl68o9>KE>|_k{-ORvfxeBGq&VFl zzrPx^3O<$ck!If5g`~l+OF}C4l;}NB7Qz^|eMtm!5Llv1jR~6~G~NHQTs1+IL7`56 z?^7o&2)>~uqBf(WU~OXq*rqmKb6Ocz(EGO_o(w=>gnz*+#aNsjv1GHT9|gPlFXMGs zuwB&Y1c5BxNs79j;Tu7AfXi+8*LX#3x6xjPE^51Lsw~WOTWo{Jsub;NP_Hfvtg$yt z)Ci>MujJOHULG0i_N2*@P#S1KtSnpvQ^aC5iWm~V|C5`!8;_g5B_%aFTql!c3=$YRAc>n(@ckM~0M3qiB=$ z4KHHDPb3^JQt_h7NJ;U>+)4WSZzhtk3JRZxv)k-yy03IDJLoTv!uZjpS6x)7M&FDY zMLJc(-Vvwh<)szI?XV*izBTNbS`j)UFiKIMfdw5C%J)8H!6ilgtj>k0i#U5ITt}W? z!|+m#w7r5wwiUJw*R5vZH4sj-opPdw0^C z_pcNa};8$!35<*$*0CCjj`B1*R?P52{ z()k?ud1rlndq!}Yf0wHx*S(Xl0(II}Al4=kf5lkgBoRmY`HW5O%*dDw7_&?q-&kLN zw!fEl^Mh4Dq_K1L&H-gIS7nQ0(+m}bDjZNQmqwtRo{`929*gQ6rLZnlyx4OTLZcZrfym&^(x z7S4u+3}QgC@9wl2UAlCs=Xa2%vipdvM6~!&izfP|-i7Qv8RQBLjqAm&$%eF<>KrG&|;0(VV z$(_;inlpp#WE#$Qw@$6)S2{(4n6T3HZu1A`_fJGdogfyoNR(+uef@_eypxl6=lU~8 zrVv(Q7PUFA1edHP64PjdO9-ZC9%#mPs&SsE3VZM*gZJm0G zNc#3;VY)xqB_j9j670nyOZ?|E@)ZLbL>W4=l*aB~W9WwK6WfZ49B)NLC=!D5Ca6Y8 zG=1>3eSR+Z`0btUzV zegDUdnze~Kd2N^y@3(=`D{W&>0AJwyDzis-U%>7f!fnLrSphydu8CY?T*M>cwsHuz zd-cZ=Rof`%3OA*7sY8|NmE|i`oLp6DrE>wC{pXpw?%>j>aU%qX1&WGJnbNjcPiaUK z8-B^saM3%WN{$rh5uBkgR+_%LQXa5UM&>HBXz-$1@x>iL^ff&Q+uT$*B4?%Qf(@pa z1_bpnBvB~iRLFoS){9VNw?!CNkP}kRG>&mnc9^zD=D_yfC)qRn(+WF@<7H%a_peFv zGxOlF#~%yv=Bq=C=0c3$L9toPU7;Drahf$H;%r!?7U>qZ@GY%ql$YJpNm);SGQgw3 z8Uz)fC|pUnvBY>Se)D{NYJZrLcT}EEvHSG<2;JT>Yh2L;KKLuIZv`qe0YNLGVfp;y zf5UQWHv6yqy*HcMcV~?p8!O|@)azvTJRQ%|=?@HH@n+v~8=yAKHwA%fgoqlOI9mW( zO$``5y_DnWtl!_LN&(xMG2p^ZoG0wG3rHr6+eL~!)A^q6a zlt(+_%-r>ccn5yVCaguFHaIOf+tQkH+1q#6Vr|m8Oc&!YtTNebC%w&<-`cAMfdN_l zs2ax_$6eSuYE3f0g3~jLOV1c63lzXnix%u_Z7;aW0F>G46rs@7h;dy;4BlBrUpO@c z4Ou_PzdtDsp({cOPZyDe)p|PAP{u7-rnWm=p<067c`vM6N)rNKBX|A-ca$NJTWwBG zaTx^cR|iBPwbrX&2FR;alg<>H^1l|%d%xMRlB-d;j^4fL1%DEMK$6D>2@b`0xdnVGpN zgv*~Zg=FOvJWvnOt-cUkeN-}dD!Y|;ggAsgc~=F%oAm-he7SLnuUTe+g`Idjd6pK2 zjq79S0vL$w@-uOteI3W}P>nQZI_$0d1%=X3fu#A$bJ6!Ktrl{Bv9$>^X@@B{jg-gx zr))GL;w57C5xA*;AkyMK{bL7f3ENx~N%QXM*3(=Q#`W-~!1nSF!}jt;pv|)#l)A3f z&x<~av%Qr}H#aF$qKb-~yc~-h-S0%2Fm>f+;{d2r{;3%m9v*JJV)GkFXXnzbc(h8e zz3bfk_q#IjXZq(s6n7eS^GpD7S>gz~{yP;E9A`g0ffeGi{qeokWHNm&D!Pl~VjZao znlgf9{OR&y{ckS45M6o`^2qXq(a)mR(`f-iCa@oO!Zb&?#i1>MIw2FKtHQLjny)}F z64i|CYi@~=9SmDXpW9J-GO1wb7{-@BtP`?VK_PhfuDlETW%2GfZnu|xl}+IeO5gAO zl@hSWEXcf~JVD0SB_RfLl-U*8c&lY@Jw0Oxorml8Wj4W@)PtFBgLtEaOy2l=J8;0< zj)XSIHGQPL82_{$eGs6r9vCF*;%4h>iqpGL%}eSjl(adH`(*r#FD;CFgUCy4tKivo z(*iyR!j%UJuE9@qj4J#b{rb#*n6HgV9k=#th--|Lfy-@gvbv_&D=wB|DPkKwLfb%1 z9+IM4n`G?wWa3%P!+_sF0RH@t5FbOZ)-E!2%WsFPk_HpX?U=ewZrYx3xqTb_rINp3 z!ukf6rFe;4@f`CK%QLim&!7QLl{kR7P8eo!|@uVs^b3kdVZ z2P;2CarX3afgc^*GKMgJuLS8D?f~5_fNZbcxT%zxs9PJVk`a6+jP~lYv)HYEG3_#> zJ){d}d$&!cHxkT<*vBJkP0!~7JG*^9aDn0pb%ml;LxiT3J|#qtq2jmg?#ji2YP==b z{eBkxhwg2CPEk=*`Qa)1oY(7b?Iafazc|z2A*F zH}E?an5QC={EdhRw!IG2%xzdY{H`urEGKZ$n#z##MZ2}Q)0sz$ljzvVFT>efVllai z7t`gE&^oWn^484;w2MNe9+FyfTyN1+l$XR2l=Oz8?{qH~MyGYJryC`>^M8EobTpPKRR z;xZ8HH2zzLd84>&nMl2AE)~XIWI|Et2m7~ub>3X4Kb$#o46Rg}Sf=y1_zP|7kY*d! zF;o%47P0W*4sy-jf#AK*8Y2g(d@5Y`c)p-i<}BfsP^MYqKNYMu)0^`_`&fkV>IqQ( z4eIE5-bpJia>9RQwc?b?WN{YIY%U4b{q{4UA(|Fkt#*aMK2hMF5wVaMEmOvq7p!-1 z!6xMMNb}7Xpe`w5`|AZ((#Nz*Fs^eI?se|UWkNkQ7RMsOM6UM^Aa=9})v%^;NnMhD zP<7kI{_E0o+E|k$5aeE6bLZXXp5G6A;N3TFjf=}BeMYWDqNyX-(lgj6+Ck_)F2NQd zdXL|;z4^|(M-Vh%b^ny5c~SNfxi;*n6G+|VuL!k9rXEjAo*y3(fl0dy`K}$}`djjC zTbv5{f`!d54l|>j6Bxu$C%~^n7&YSWs+1-n`_cP*|H}SDgUXbKB#)cJUQT-84qlfW zp)xz)*Jw|Ngyjx(209_O0}~W!3(oIl{8#`HpitD`xP~KAmxC+>=oU45?UZU6Cr@WO zh7ha)@tBv)0kn}3J27Yb<;-Ud;9nk4F!F2A4%SQL-k6O_DFA&p%alE-U7+K3hr@vsUTY|0%joK zov%+Pes!*qV2fE(f0B}-`EnB>1drSs%${(~VKo^h7MIAAhhtl3)cQyWb8{BP{r+53q9vN=2MG?fH_NdA;>s(o^@jkf)@H(lN70jYrWOIAuf{NoMf@oue&2QghPjqpS zi;7+Tuzr04;{v1I_2z#7woL9Qa~4SiJ}FDQH$@8{m*RgKF$NbcmVTMq?uJj zlekIQaPK7`I5hq}_J{r1WxURe4hS5Ob*7)ia%>n-6oZjp8T?$B+F8x-Ovhj&-5Qs_ zU=JU3*xnU#1~!_NWg3D}b_?H34j;isJz(^CIIIUFfFJA=IJfsWz&yG7Ld zO@?06FF#V_^A#g2z?=aadETh>B=>apG^(nq7E&Lm+u7M=tD{oSIy?Wie*OBh7cP*W zm1xgV?CcV=Np*F1K6G|Q+_@8J>r|ej*dKh>r6=~}sp4(1aW-fC{kMVXaA%GAA>a?E z{ibZ>z%7uMRl>jugaHL7Wd_zVd`Y&Cximk>K*w$w2`>!YkwM{-e$N4>Ix*x2c^c_a3l;#5QEDNbBgHP z&tmch`m_2Ib5ombY`fDU=^t(9nOm^%w|e|W^^n;M;2~Z3{1Wl&8+}7$v3i>)c*~ihN$zmr@o_sm_G0TiY#9B>sbhzSmInP$0UL7I_O<#d5@bdC6 zPAhqNT-sNmU{EQSEmSED54G2Np9N|=y#k2Z7|G!pq;8WMH4E|Eb|&&K-fRnCF=={3 zSD>;TUjUzo{!T35s{RSz-iV#v@98f=KI$Ga#N#cOjqT~_omWU=tg8?^ds2$}@fW<~ftq`@w9a5KTmAg}f*-T)ZYCVaD=1i}qEb{qU9=xNCs*X(B@)f`IJNlB@fj+;}(Cq>dHc-iIh;2PFeiAwNVuw(d{ ziJjen6f|$$#}GrR0hK)~JOCud{B&HfHhhAsOqza%?FH37X8^(S(4J$+S=TOs!akK5TVJ(n31JZuMM+F zVot%DazWE|xY;`@qi}b`wKv*gSLD06yJvowkqr$1y;RoM`*~ct^n$veioJW$Zg^jZ z5OCZxuC7Yf)}F3-Rdv!E2$4HgRg0()0YV;m(ZN%Za0AGpjoI$B5>?T`mZeu^N_KVG0(vL~>KtE?@j~6PBT%if08Jt{J!H6gviZGw zGm={a9+CqsyX$|W*rivt(?9`VCQzjnk7hF{#NW`Pc(U^2OKyp@+N<#sv6(Dy358Ab3t|plY8I z$P;6g9A9><@eq{)b~gH1Y)+=T@T+nO2Z_tRMis5;P7c?z#nS6Oe?GHQP3>)ceZ5(& zT`kk%lYG{RTR>4{f1uL`I@P)iri^#0lMvP~Y8BW>(aVgNuRh=Lz36@AGB(T{57=nn-ru^<}S)%aH=sq2ltS)1MC{~nu^JxSEZ zv-@5R+1lEAs(OKa$7DX;xg^Xx^V#-K8>;$R3MvH1_!<_3;57CxSknsOS zGlP=yr#HBE#plnT-;qvm^T+2MCWwxx-^XIzDM@djkSjBrRc-c=F^$2KG&*^z?2%l*n__ zEG%s^o5r87Bx;RU@T(U(pa)~N2Yf1peL~JbEbJP@&u(DLrUtg?-6YXRpS&F5Fz!g` z@w@f~j!g>Q;K2LfjT`CF>IN?Ewv66XdVb^G%@`kc;e3T8dKM?=m0(^?dE2Z!Oe?3p zc=4iEMG}Qkmj3jAK#K!+bwBkCfR@%aB*du~sf@z%A!~c!mjT^$84Iiv@;VqJ7+J%c zjbmUCA!0L83)S44k(TVHDt~GpunxdLxZWY?_y$7c)Ai5V6Fff(tfBQ3&Z05dp{!=Ao$g;Xi<7svd==t@q?PivUIc+&OTog4ig_zZ4tn{fi1a z4S-3Ti!FF=*Uxid=*b_yE0T^10nPF+dEDk2p-tnu&mVwr`6&g#G71Wi6&{lQy0J(V zHd4h!i{gW$&_fW`ZwnQHyOtv__9okzSOo5Zk1ME+qjD>svgfYY>M35Hihkw-d`OkI zrUNv#?+ZBYpHJX4RRbCEz?2F!!-O&Z)1F&E4S;AX0noig-V4ZOx&!SuKS1_|H$*D= zxi`SAt+tb_1rVG~AM`x^0wBs82$&vTULp2}u1p~a7l5vx-wUgZ+N1&o#17VUVR5k( zIBah2=m`&xpz*a_JrffZ=q={C`zs-d^8bZ-ktWWstTo@F8nt&p82Cn%R&a32S$RYd@|zclT?as=C(1f}S1%d~pc{F?jFMGmBInSaP&$6_*qL>!> z!i4=RAM*qV(XBCCo0Q$+C83VOvm>GKIH-L@^%refadzJHxof+Q4!+!2w8~7_{x^** zOLT4L9fP7(@DkT*6~O;U6@a)c&^x<B6Qa1iy8l-JsJ zwy0}tt*=%O#F$Nk5@*_iS6n{1UPk7uw>Rhu5G4A`h^RKNifXf^81w5Tc6N51E^QI% z+=RLX?a10sOXaU=bZ%&9w+9?;rO);v!=7i5A=^H zE8b+`lhI*!!*0kxf;WU7H$3sLz|Q+nSVw;Tyod9B>vnZ&IR3Xph(Q4aug#(DkAA&A zN;EsN&!c-ivp;ii{y1RDatCUVHsU#wzk78$e7hlX$mNToVrIW^VkiBr-b{9gtdx}D z`baI31mUiLL4%*rFYTCMnNeomb!GPm>qMyL3g0@-reqXbtW2hJYh$o>?7^`&Yt6p= zZkp0O6F^eF*8aYbanzlRo#Tei2*XWCdPGegxHkKe$JB1ZeFX2t7QNVOS0kI_uR|gV z^5te?wJwR$#Mc}1uP7>Nn)2ZDB|_U{2Urp^YF{!_M24Yun==vIASDI00L;FmzlBl; zIw(l7;2m{Xr;eOdJ!I+8x02f)RmZK;1)~qT_$&10VjQW*GN)Y7(bSL?Q5OG+Q<9GF zKR`iD`D!@~$0l+<)F?DfLvx4rexc7pij_ITv{$NxtL#=tn%4X9LuHlS`! zlKCTHxaml$ykaaX5}{QfcHFDz_O7fB^!7iispiQ0`ZlObVzl+GH6&fXT+N)_Tx`N% zpuN-lSRCh<$zRlEjbq}ZHSQ)QCEcUCY0HJ00sMdpsqD^SufFcFySu*hSs9!=6&q`f z&@D&&*^Zg(>fM|2)=KFBw(FYtNI&LemrY7a>Xq9i{i&+4(HH<$MPuXG9a1mfQBV*= z);&oX4bgHM^)_H_SaI41rm7_YEy0lWwDQ+5{z}1YA5itmT|R5rmcE1qoX!*W>7dvH zhy{I0+wQ7ji^{P_2x1>^jgab{4Tf~fd35gqne0?pd&y&sm$7Bd=!*PW+4nA*hCc1J zQV!eu3iEuE+MrB2NKmtX`JYE4=aE56;mfi=bt#8}HPfB2L_;ZMhMqo$E=Uv3`=qfv zjfWRzWSB%`+@xYN#)DQm@v$;wyTWH7B?6Sys_AoTEJ-^y;A$`+UKEg5e3qsS{n8z1 z%yp3(C9GVu@}G`(uXcNSZD-p*1n-nwryxtvYZ7el5L@utU^i4ENHZZ%cl{7_e0^>$Kb)7hS%I|dA7?ML)XeJ&0n4y>v-0KHXvcD zCbczsKY642`+gE}Ico1LRi0Q9x6h{pM+H5M3OuZhGz{E@Bb_f zG;-@svuEt$QfazNykGpY5mu%AY!Ph>kgQPA3ek?#Xl+by)P^hlINng?JaiP1;61UqH_UhOf0i%F$e|JP0{7mw%~K}xCgwx9$morrQFB7? zPi9Lv%Tu+FO~YlM0vDt~@YJI`QL2(=KG`_&5`}*Bvs&V?#om?P@otG*1L*rmg%Da& zO_+5Bi-cTb@;B|2h<|k!j@$^*RCuH#GJex>lsVVIrO*bu2(`nB#_S*#1I|oRTC>cK z$(I7$@^lCUY0QtS&-Jv<%$d*D$5~Q7vgU9z{b_bJ{ZSjo%-sH|8OEd~nE62q*ZF$g z>f~CUqSg+wGe6o-;9E#nWJ3F~dtZrWypTSueO42v4*Cg`kQuXjr?QCp+@ulmMmR6q z#awNo8-*LL8#gD?b z`N5cI;c*=1_@cvSSbZDV`pDwKH0T{WT$(nS#Gc&;#?h@==k=67b75w>u9s44iE9d{ z*0lL|g+TKqqqF|j;BGPQOAMB61NS!RH^4D?+O=y}dbfKJkkEae7k!lJ@B)%HFw=p7 z?C$OA<#o{68E7OTP3T4w^`6WWn??S%S^3|7$%9mHAw>fOT2)5}GQ;l0m)D32I4En$Ose17KN}^}*QERk zBj#|;%snLBKjmk&D8ON|D%+t@86iC|s8#7^<7J zMLl>7t!l_7?y9uHX~5?%shs*8Y>0V4-%1x{RnAWbj4*R(3{go_nhsrzia`p?@X305 zaZYh5hx2=zzq5V+fiZx!M}|fjbq$)t4_;E}>^a%q*TE)gYp%mGUYNCms`ByGKF7H$ zZ(jbCvV)?%Bhcyn!a`CmOGF+R`=|a}({FIuX}7nk6buRNgMA|x)?48|++%sXw*qTh zUl~=9HG=TwBu)u`sA#CZ2NT#=IR_qTIJ95=srE|@u%w&bpOs1uzUwn@3>_j)%ywxe zl;Ij?>z*NNK%5_R=W~4JZ#;_u-wT}z2l|mwK@B}5Sx8ACY?93((j@ip0t7n91Y?p- za0X@{n(P=KY+Xgiwz`G!5PDHHv zfGoq|ND>bQotB+Hl(9`_HJA@b!yGZ(G>`l|{5s~r$0NNdL->k?8-|vtf;hJ7AiY(w z(2R}Neu@Yp%{A=Df41P8yvcdItFBll1DLh^!cHtxm*m2t43aMv$`{6%2lrvFDn=y} z#u|0ht4!j%1Cd!Hyu8-&UEgl2D*Y_uQvtqum&(e~EMxAk@h9-suO zS+v-Kk)rul#>d~VS|~Bs<}#ijB*NUL*QMYmdy)qeEVN?&cIcj#rTgdZbM;QIO;V3y zsXGiAMrnUlnC;9+9YF`?IfSN}MdKzOk?p#n(Nxc1_|EUYI6ZyEylH=Miauec`Cf$e zqoWbcHva1cMFeJ^x%Xv)zUGv%b$Q;gH9eYuE&@%*IoW+=^fyjTyDq z^cNZysvh8y!nGW|g6XntPy4FWkQM&w5cbSGU`^V>H!(Ug^ zKzSmSW|`i!BLC^!pb<*L1(G++Y5;ne@zb<{9u2d)o*A$!2@e64x!3L_lPk;?I6%aun1zjkdusVR?SGwMb!d$7bH+ zkyL$u=ChGxRVV};2*;s94Gg@CHDc?*N({}Vl0y{Urq7_AdU?9FdF9HM9P|DtZ-Xh% z@Iw5CJK)*kEr_0s+ZaB23*dP7z@#@}CE=w=XTd^rm>rU*+Fnuliiu<1mKmoHAl&GcMr`gr)$Z88#hud)9YeWRIII!lLT4kH&FOjBwfR3JEmzgoM=^5X%c!{8$Zze&ILyb#&R?i#Z7p$K}&7w)duSu5R!% zK6}*C&uL-qILb!8gk1Qr!6;GYQ}Ouxg`C}C*c|qmT(2hOpQS$?zYFu&^+|4VozTmz zzu>TPDtNVy*>*fZJQ8lU%d}O9jai`e4{=So7UK;%eu)v)J^$~FQ>LXq8akB^Fsb;pxt9GX#6!}_(3nZ$cS+kGnIUT^Zz>ve|`O*2mp z*)di=y@ExzM^?XJlR<~pE%o?M}{FXXuG#Y=!&yvqkg+Ti#H13 zLsN7^Zl%AD9(#=r?U+05+D}R^*R;MQn%_4jT5ea0ss1#j1cvj%U&+$lg%^Fvg*eT% zoH-}gk@g!4AFB{V6=jn$KJc9U7BbfHegCfU0{2D*G_L9N;8Optfb2cpf>xcs zzC6z()-uUlQXy~T?mu+kKI$&^VJf z5)#1%L(0q59o-!X#bcgtm1zj<3 z!&`q29y|?cU8GwLV-u&{%-g$q0RGm8PezNgI-#{|Tl1v8B`LA3%r0Js0P@g*5v9(I z-l$z;oQny8Ix+2nE@!f(V?df&?>{x8t`^rY57r%aNt~SASZHayj(Mqxjy8Qei6}1B zhi=9{*3sGd5B;@s9=e)ICo-#72? zHY_O1+3Ej_rSWUxDzE4g{KXFfy9OVtn^fv(Y`o&`@17Z74vDwx!nQ(&*Tm8PYv3HD zjBgziV!stdRO#HzRR;p|;!XU_d8#Yil_*hEV+R*jP`^8^sy%YX`$HHv*tc#aI%6*Q zOl83iN`Lv&mEui%R65c~<{1TtU9DdJ!KS3Yw;z-MElWN;LNMo zCH7Vr78bn3;dn&~)`sq3JQy-v2oMI&a|8|+MkLnuB+1|%Fy*~$osdE$GG|n+Fs6&w zVl}CZ=`(2ye(p3$xM~%!ESP0U9!VaL(rHxm`_hBk)NqGaCD&~Z2>Pnp@eK_WPeP8l zl6v(09CO!?VU6%lTTv<5^>?HVqE)KcMJ25K`>r6P9^eL`U|^Po1xcH>&aiW48U^hhg%3Cmu*>omg38`YXH zSCc2K0#qn9*2YrF)oe=$mapDV{2=$ln4w-bt*iRPk^kwuvHJ1eq+!j3Z;S3cTqQ8F zMVqhtIN4v)U_8dl&f#U9>*Qrq!QgiW%4;vIR1g)m%Fw%wdmNQtn#munc_NLUw$H{l zyni-womq18GR)TQ`})&?B)-L{?!ZKfNy)KsJpLagP-eApKF!OcK(9Y^7j&cahf1hh ze16c(EHNfhjvK?zajK;!L{INo#Kaat0*8u6gy+pJno%xO7wHG5y0Nz|U`Z6B=F^|c z0zcSyxq7mUj_$vJJqGoA&hnSHc5N7Fv5}guQViWqa#dpmX(K^ByT{UxCO|=nT!Kza zuejISs9D|}SQU(Ao=|%IC>Srz%osV= zc561^@3&BXZ~SrjP$3{ZoHHv5<#5$BS0IM6kTv6Xsx((QNbR&Bb+p3lP4* z4-3?H9TeVs?7hStn7&(c5$G?N5IwAyMQ9&k-~HZ^ zdZL*^RoA?HQcd`251_%N$n_@q*0@$RQ1ch%pKHwR9_{xsz+LLNKoG*zS8u=}`nw{glL58|g4l7;`>D2{ zIj#3t62@zD^!fv$zrY|f&4QT}va5^SX z?;RxkeLPSKJ=l@vC#+t;S0EY>yF2lc02g)kvF<)N%+$?6bW6#cWo=56U97VpS3dZi z2jjQZtU(=+9Mo4^A6J&?7#Yx?VggjiycTSH=08bhlUry0mZ3XT_?09d@axD9%xNH+ zZQ3|V9mn%Y{LzqD((;wwOaaikM3iO<)o76(D~uU0NFj4v+ZqOcJ~6we(Km+S(CyHJ zZQIwhWX3sEd$%Vu=_bn(IkHHjQ#?ysH^~Dd*E9K?t2Z@vjwY2p!iw7!hyD=x^>;^H z+MrQ@E))wT7B_TRzHSeE@YOWNbF=OKaIBN_%lSW)&CLB5{59J6gU=SoQSitJQ^!}^ zz{!PJLTLnnr>Zon5~apGP*g-0eEv&Bco}-gcwB1YsdB0pqks-R9b^krG{w6ZLgC4XrnIG5yv7%A6qxOYsX9A$cp5ICwdB5B>$ z`N;?-o9P5ELXN`2tMJqeB)W!S5sC+Ch(Mm1uJbBs&%R*(`M`BhhuxzGXoi}-?d)r2fCo=YSy&RyD+SpLuI2qBg(h}m(WD^xjB*u zt3u3qISqPOaG3F$+4+wh;Z-nK{t5jEz-jzCy6@C%AMHQ6m7N37twjq$mHg9Ew(NiD z3yPc$>^wq9&RqCN+o+c{BDY=o3LGn-X~)JY&QWiaZ646dT4jT4NGnJ1aaT3zLRC5j z4`{vEVwfFe8sKnX2gf#4rD!1KM`Z+ZHHrrr;1Yqp0K4w2YN7~SPC_F2b)J!ZD6ifFdCid0lg`A)qBj>J`G=PAMB zI+g8)JAmh+WPWF642LRIMqDw3<4DqGbytf-_;vJ(gn|VtM`uk@+hrEr|SlQ zS{}TJ7Q?C0f@Al#aVfD~H+H2XqKdZjO-H=zk^vmP@W}Zc$>F`AOmX)9pwU}SH+SH8 zVDCoMVC-lqH%Sy1YKQ?(E8xa5$B$9rD4-PiX8srG%Y2=Gy3@TiZ8WFYD7@-cA)Mdr ziz-V*`wSaShEHEU31-2?+Vm&&&IFHMmE1bH<1LSxeAk^W;pO50%Rv^9nzgykS%%56 z{?zssf4JQ~ToBBs`v}0bS5%zWDIKfE=3$Tj1(Q|Y!)jD6m9t>vp=D4}_r7}mFIgrC z=0KJ`9os2=&f$n^%YEvt-C^9I0c8x=4I=40fL9>>|%U`jBbR!@q`7?PWavNGS8 zZ0dfO?XOOW@pZ9ijX7FuwHG{p+~HbU_gD4#$J4)VsQwI6VyzVj%Zc}q4JXw5&;W6) zVNmUq3I*H2JBB=o5qTjn@PRW-%`coCQt*@RYQqLYD?(Dfcs(>wfH;ff*TNL#9^xc) zlZs2_p?Yn-;`or*v%3w;f)Q=4hdkx_b#xAqq@b1d4vA!I4nyS3iE_YPA<#bB%Qszd z42@KgX5byLYr~4JWS$e~77?aK)+#4kH}MuT!eK}b6X0!@WjJ9xaEIzPd1R}JCw zhWSYk%42#J z=wl1V#Eb-yUpCc{%7clQsTzI<;l|O+mXn-mIt}$TTdwTFsStWhv#KF+Ib`WaOsw{{QaM| zyZEW8Qw&@7$hbl^&dFf!vbl$pw6duU^IscmNmamkL3IP)hSt-SMzc_s!O07xCP=__~7v^Af4X*mZ`$-iWY4;8#$M>^IJ09 z5sk=%ScVLm_xk4gAEna+vI`$R)M-(xK)O9=A|LBWpPQaaFX{a?DY`5Wt%T{nIv4R1 zG*|B59P-&xU&A{0!Jd)vrQT%p%j>vAMr{LMr`R8kT2ZU_r=Lh{LpPi?P#(@nuKpXTYrR}ANKli=AFf)`SzX*Vr4GkPv9EjsJA-xfd`nOgWSd+WscOZR(TFwm_>UM z058YeeFpybSz=IE>`gn3=*ptC1r+zfHs^Pa?KSe6m^$C|H4raKeEQ8{jF~*?{3hqh zR4JE!sWh_u+rw~#+IyEC#^vq})`RCTCAr-klF_>uyq1*t<7S}oDE~28*{*4`rdNxH zm^WKN>qKw83{Ps?W;lwnJ*M4Z8*bi6&BzgltzkMRiUB|SK4{_C4?{ZoHWqO35#&G39ne}DqEfqR-zW7BKsbdX z9&%`e0X?H4?S!0c^Pf&?=!$;}wjE`8y=U7gMs(MZOXn5Dy54q~9dQYHEQyz-w0yc`n)i#n9LrsEGbK-H5MoyIYyX@RZc?nMBh|eJZ1!?H zT%cDyHkJm7TY%@qw*A-gzRJ(F>cKn*G#4-35gaBjnXrXAtur|`r&t#l@sLrokBEo}WEE>2W;$dwgv?7wX`(A<=r&iDc>Na)mT;0nDnzSOq9|YY2j(f! zc&#??TVUSVwC3f?mk`o{tkE?s(L?5Qrk^>Q^46Zd?<&nib}w82$G*LB(r8;Ar_*P+ zXqA(_$BU*`YXP#7-AUMOz8BV{L>c_{Bov{s`~hcMVE_;gS@!NxCx=(nuy@B@uw^CW zb7ot(3X=~8HSg$QT=vrrr6T6X*1`J3A^Q{P-49?kasgJ1mNISZIHPe;$5ZLMdE_H3IvBu%gOG>!%G!TehJta3IO zZrx~7TsyC2!f2P+o<6Qd2FfNi_NbKQUQAXS*aWhW&D;Y;3~e}d9p#;@k_eKbP8KrY z2x9}D#ab1H&HYy19p4eA_3FoXYo@MeZj049Vwp~VCLBbw$TN~)Kl~hs?g19@G`iUu zj-=mZcM48;PTbg4Ol7HGKY?p|{qUiSg-6T6O%o^mk4e!b7xp{o#4l|f0{4!Mf}$L<;&$AFRJ$rkKL=ft;5v_F9#VAllp*A ztj8dL7CO0N-(G#V5?UB89N(Q(#{NWNRO7Qd_2Oeqvp;j6at8%}-vFRM+@~slOd!t7$tqE>k8egR$l>3c+T!}4FR6_@ z#XuVd3JZhMiJ7&>FdlbpPx|5sef6_-t-GRAgn4v^9{Ce*ZBw(26y3MWjJp~MjMH!+ zb82i}{2GnRoxc^Kd-I8F+#k1(x^Rrv!>!51Q1c1l!8Z_GX^tALpsk49Rdbi&D z*0Z3y4PW9_hP4lb`+vTnIQGj|2Zl?I0-|pDZIg<|yWFIb8%DdVLL-&&gz+1iPXeF< zhQrF+J35BDT{{(AJAboIhqMR1dtff{}wFeFd@MBWK5*N3m^%1kmL0y#mRO`>tITPIH>j9dMxRA%_Z zR5fu|;hO5^Jng$6gZ=j9ELx*?L1|Z~*YMC&-t|)X_?MD8C!vrdmIeAxBeU#f5+M&u zum1FnZxVq0n_GOCNys@~eSMh6q;KLQ$Jt_evBo)_nl>}>n-TKpi0ZmZVr`Nc9QvBv zYP`39e*PAJkkIL)ZL|`bu=c>l!jbtp#%y4AkE^tA`ORMqrs|Xi5CL56PWR}K+S%yO z@U~p<;lJg`O?BY zbYH!D{Ni!yRd}clkogu6B6F?wB1_s;ILVpJ@=neyf6A4>cZF=rzarl%Q+WbWld!%1 zX+e5lZ_VAfKT*o);~Hjs5S+Xm_0hWr1Kc}5Z^z*IRiipUzCB^{`S73C!b-^84QNjL zW>Vcu67+$t+V6LrT-`(oTSxy6Z`sXwGNsj(K zI_)|;{`~i>hp;O6-G8(>F36L;6^1##daq&Iqq)7oE#^4Ax$&mycSl>sxXZ5(W(HZ| zEFM!Q+4jM-CM#q-O&&&rJ9MP!4mn+|S$Z>v$Un+YL|qWHvC_p0*BKe7?3eX9QHhf^ z^t~(_Q|E2@!WJ!+8p|WOj^5C4;eBiihNH)5ZgKBgZ5ZcTs^cGHWX$tZV}AX%)IHh}c&EUMdEd&tW zOj`)4@S*sb>ahy-U?q4Q1&$fXvC>@fY(&(!XXoRA=Pl;@Re-pExsAAM!-E&z4JJ=M zvgiIt7=-NOs$JKGpQtB8uM(#S$9+Q3@_Nupc@-W*e`0=3tC44Z@7Z_CHCgL@^N*ac z*-JQgLJX4?SLfaQ6pX(eyEtaM?H$Z+W%f*TP zGl6&f=+&MC42lw^A=#svrAIsA#}^|xK`y6Fz9z5(u-s0D0}*?_clH=RX?(ttadBR! zX;-EJPT9i3HCoo^-W&QlU*F@+h@Qm2#$^q8O}_j+*$SQB|6PTcE{W=)^rPgdp-fy3 z@iJ?WotW9fHUp+yDGg6qkxycC%$>rpEK&&bb%evp$w3lreQsvwF_NIgS1-Xj(G!Ms z!r<99ss=clAEM*zjco1}l$LTQE;TFMDDCMubiyVzr#oWTJ|vJSCw6~5Jp|L->tzy$ zqwhWm(uMQW4&i4j6U=_*A?#{IgpK3$vB|sbOXy5gfQ|8}cGhiJpxh+)1Ic!Nems+X zKQFp_OS%oCkLU_xh3FEffJvpT(Or7;qu?Qvu?;J!PGWnCuuf}AR+)tz|44vw?L6%5 z)J%QjF@+3w&uV=sdTj4WGp^)3-#nIjcWY{mx8>f-6I;NDs@dhh`s6oxq`_ffnk0t5 z$3Zv%;NFJ54NtzHap~l2uJ_ADboB$^j#7)DN%v+r-6fsiQ#X+@lx&8ViN4Xj1u-or zIKLdyFF2|<|4DM*fU5i$9$cXr&b=kSyP_OMjNMAr9SG` zXPPRv`qeSJpk>ja*UHYmEP{X8js7l`rxb z1(4|Yk^Xj)w?rXjXN^Q2JX3`LZJRCZgRYZ-$(#4~aq-+PhHdcN1Ux~>D0oY~#GvIl ztOG&tpb~daI6!YvoD{;hpV0?!ouC&od5$wTHW7Zw7O9xvaQ0wR);g_xa|I$nb4!|Q zy=C>T%*yv!mt|X=ZC#Y-%;CWd(cKrVS>-cJNwvk;woS0Y(RLCHlPOoo3FZ}y|3A9k z1FY$*eIK{OJ@}#`T2$U*)v}$4%(j+VKtTaPAP|KDvIPXfNKzHBf=U%3B0`D^h>XYx zGb9QkH4&n$5JqCe5HW$ULkJ=N=L6Qh`u_f2=ylma4(FU_-S_=Gr?~jS5m@Myt64+{ z<*S@QnF---{B!f^r3wrGg9K(#CV|uNc6%fX_1dzAgHUtIwJSy^<|YJfsMmwkZ<`n6 zMqSFxXy{uY4&hi8{gS`k4!3!WV}4_EPXG6*4cI{ZO!i3eMO&-yGaxcRd)Uor_09wF zky}2yfX8EP2Cj>7#xQYUcHA7=ycJx<4DGN;tHLh3WB&oct`7>26f~xa{30O3ar7N# zsny=1aW^fpUDWQN(|ZE0jliVCybH!EY#0SKFuf4VP|;|oFS0sq0T|U;dP1Ya#jjay z-o+qs0kZB(QPTTy7i*M+J>yJsb!BA$zrzQC5=;3cC7Hi__onY0(V{5E6jOOcqp`zG zis&0Btt#B0VwCu{;MR|AT3eB`&JCvuYumqxn47(*n5u+O|7iSzaVpn$c!;t}{lpv= z=6Kb+=7&F;a@7FURL@S8{H1OhAz{9?Id_Xm<6Gb$S=nOQk{Q0?!v+e>n(7u~PjW4$ zS=1?G*m{rn$aFJ>RR3p@RxLM1d}^*P^47HFV0f-lF^zs(kn7QY zS2*7pee1{mwCmSm{@T}{)$~h8WImZYF4)Em#D95Y?7-Y5Zc^8YxI937g9CMwwN&^p z8%VNLy0cm2#Py22+pguRbrn)Ma>x4V`4yXKX0J(XGMd10f1vdqXnzvYo(#1wS`j@i zPX2A{Ktl2LkC9#rG+3`6iz?6DKA<$$f>+)B)AiKEf?`R|6j||_PUGmp= z0KUUc%BbqmpbduV%XDC(#d@e%cIoYWv*Qdfk9`~$^I`eL`WWg}7r&zgKff7(Fb_pk zpo?Vn1VdW9<{sz3OVVk{Y3Q{35x|nyOU;3#Pd1x@K^}9Hv^h?3z;%5kg9ic*Ls$$>KrWfAs6@UuCWkJ4D#dSndWls*>!L5ix35__JMH za;|uMOItQZ2QiCbH7E^bOLl}w$M{fg4jiCCmq=xAD~ez?^8o8+6j3OZG?aJ_;mzl% zmm@n=IQo>4Ch5cUk2n(yQHALs&&uif7Y+RKQ-!zNj8#rPzaQ_|8p+F4)YVSNx%{)? zsp(~*CSSF&!ndY7aC17#Tm0Qv%&@#}mh2qyPoSKclK}o?lEgRWdZE*(`x{${>cX;x zGQ-<9HDZI|zzw;nMdjmLVxVq7^v9r1qblSFTp4aazZ8!m1mhipkEN``Payw$k>Pl} zqq6uXZGvhqQRje{mHSyij-%Ou>AgDvV=oKB7%aRMk#1!1*3GdF(J8fO!h{{Yh z11HHlJ)^fZkE|G$%&;ey?~%&ucMYa^jLDJ_;PA~hENw!*Qi2shz(N);@q9IP0Q|dx}C~ zvX25;B@ngFj8QXjK;)XX2Qu{hDt)=E=I>Ox^1EypZeig9e&h`f5cj!PKopz1>zxac zK|{}ozmxPu!gRk$7TRA|U}1Ra&}da<@miDTNh9zlJ6Jg==$+B`TZJzr*stWF)PjrS zZtM@_(xzK#H6ItPl=QF7Ln3r)VA9RuD5Kn}h&t(JV=ENH1efRMuDG~ddzjXb<*ZESZr}T1$eH8Cw%riSD%NW)6M>TUh7?YFtHt-XN#m`KYTJ;+}As%{VOw3)o2v@cOXqP7V)*tSun;kDR zRv~NN`CIeFI&tiO5q68bJIfOvc2Au6{b<3hVWGe}cQUM%MEPBm)K3klFy8;JcF{K# zTydmgNH$ZAjvCDzcxSUcVz}c{cjJ$G&4Zb+%_uHy!WwA`!H+Ce+?}M_y@>fDYej## zB14;eL@L!IFjr@tYgW!0SmN|{()u9EKu~M+R#0mx7T;PUs4c|~`P0^w6#OSEuR2@l zrw^n{+e<0{8?zk+yg`LYm}z(S!bwB zh2Y*4iU-juzTuH9-Zw*1?`r9EN#2s$z5j5PMy%2LWUnx4K?9B%xmgF64BSfV37n#r zX$pFKaI&+t1}d+Ct7T!Xer92G>+k7%{L-g->+(RaTxb79nmq(((wp5OAJ?j>!oiQK zst*)Q<%s3Db~(0PDEbk`GsOlC-!B-M8#fjwc1_OFXyZ74EK6bx0>wtp)oUK!w+FhX zI$QWU)@do^LTldFJe`Y`3u!DDWF!5@q)hy`9;_)#egq&;3wjsA51%LrUlbl+`Td%v z2YhGu3poc5s^jmam+b}pdXM5chqja*-ghZetn@>q{SvP~uPpxC^T*9=#}0kxWzEyp zNi}``=)UEfuE;kpv{jtyH#r@>>h?qN&gw8Xtykikp>EU@A=L>-?uTyQ+Fhb)ytlvR z;>u?KT5y-v*i1@uYXIqu>9oDU%i%lp1xd1h~}9@i`!x*rLhl> z4V5u}DGTXjEB!s4h34jX4q$>0afQKsgZ6q#VfkcgmNzE>l1bOJZO(&8u_nRJ&>LZq_;#sYk9{Cv2zDq+&$$Yb?Y(v`ePhA3Tg18{#7T;UXgsQOHse`N!7ht z){jhtvfDl4_W}3;S6bcpt&qWj*mJ#=*`&#qLSyXv+L!NT@~o?TtocxQtUI~hm^s3c zMQcII+lazMN*F;=K{50cFW^Ye^;fi6)nvNFNw97n8_izbU0rMq|ESp7_-cKvF7PE~ z4^z41A@W#l1@@bdCG2fPq}rrrz1)IT?sd{Rf_1ZuYAy@R7vW$z_sTLWIub3Lq%97v z;uke-c~t8fOEEW!JVPZ;)eyHF{ByW+cTF4cdDeWNq@F95?hT^_}}`JXTXo z6tCNAXeukLx|&ueGPqc_+Ny>f;G`U6a8B)JL;pZc`w~`8h%s&!=K9?+hneJow^la? zxM)&*PH58(1UdclhQdo^VsyZ((wmOhd==Lm%lOEAgL`F;ICW#foY(t4RxbN5X~-N_ zUHbQ7>P*a{E@@|H>*VYD_;aRR52-7~UNr9Xbdx!VmoKf^0t&LcEUO&LgTh)JGLbga zw>!x-tEXG19*$bYCGe3=!~23|Okq1K{POAVDNPW&S9kjMuIB`@^W!D^K01+o$n5Wx zr6Mm!gFs#;Lsa@w&nMiw`tRH1Rlu^TaW+9`pY(}Rs%^>Fxw?C|u#Bw(`-;Xxk71H~ zNb+t{WI9aP7aOL(-u;DH=LLYn8a3y#Cgsu#m+~yC}k#JnHWdtHODd+ zPnUwChlgDF3Tw#{8!r%(| zr52aKn8DFm%${J{HVqA%tRr3$e^OmHo21X=rX~KNL+Ihle>zG{{+no$f=ADp zX_r4MB8A>M9moo|R5r^Pa@py9ZzSlV>{3X~G|%=Iov4Go7bs?IYkh3?IA&7-Zs`Yw z>!NL-ulW5L*)DeV3B%wMdZaN{@SH6&q#pyV$=I5%dvFYHEg~}t9xVv*ZJn#0Xd#-| zYt#In0i}4U=dWJ_4`~a_MHW?|RjU_v*B(>(Bd_Qm9__E=;OWkwv@M*t@#Du5wDM$g z<4TiZdbO5|`Gv@KWrm}J{QZNW*k7qiwKLnl0!uS5bL8ZyE2aURee*K=5ICiF`=%t* znG?7%YrRK|wX(m@2UTNPoC&kr5uFmOe%7_Fx3a0g;}#fgi}$5vHi2FF{If;N^sPq< z9pjR7zGhnZ&HbD-G#Ax%Clu2g`_mCMm?!Y6rQb{ElIvfe-MoFpsXrCuipQb~X7uv> z@zlx{r4Dghj0yC5UuzN--{Ms%TFfsM#>k6e)Iv|EB{fY>u58@e|573ggW&_zIWk%{ z+0w7-Zpe-@*>HFbO10$qi(!)jW5#xj9>vnD2$CFW;q zToaQm^y*y?W~F7$pPp2wW?7}p{9@p`!8!6fUAd|yr?D+rTLfJ71c+1%-1uLX$f33$ z+umVguU%+;NTrRem^*Y}%O73GFkUOfLohUPa5@0OJz@yub~jf|nho_F6U*@9!Ddj@ zlBhF&KSMrVP6uHwhmZYHkCL1zqo)emR*lSJYQ3>O)gz8;Du2A*y+l~P5%$X&XGUn? zj|Y$(hsV=0!@oho)&K0x>JxUaNG`n0)a|VMcGhguE7X-%O+IS>ea$Uz_(WW5J|=FX zuAZc#U9By~L6i-bOkL5BM~PnLcJHja84BNFFLfN-aM8!^$?ie3yTP!S`xQ@&u4be+ z^iOrpoJ(r|W5T=$d|H%GT-koUk>;hQ=SEk1M*ER*XS33Y=RYw}Ybt;E+y-E~ROGiE zFib06ovF93&K6?e?eI+hLcCh&!C2l;S{t4{BuV%$6Qa4n;h8hkH4;8t^ZYH>y`Pz# zjUHcn?~c^1M%>tz*_5PJho3l%*YRjr70e$o)C4O$7tl~H+$X+r)&gUm>$bDPiHiSQ za-AdSzdI7dFqOmt<^l6|M#u7V{%wStKf@Qt7OOxY+hvbwz}(~)jfc5bxU5ksip5`b zen+Kn{pWjPDi z7=dVhv>29p5!xj4?_`I(Inj=yh%HWZ>t?#M7J-ARDOcsW7{rC}jwPoG7 zY7uTMb|zYcn)&Tw(FU&hT)+9ND3i``mx!Xxwu}}d@@XB5hZ?i*pOxC6`rg0a5A%ho zRI*GtA>`k}=NFT*jZ-RmBl zdTF7(&|(_-6INn6JF;`z&4zncqK{lWl39Na{mBs&kBMk=I|j z8cT|)5DAIaHyDIA;Y$~uX+bvUF#DJ|k4&xvM-;y@|A@B{KfF$dJl>Cr7Bo2rc1Aj1 z;Nlf>WqP6a$vgPJ9=u7y-CW#NJ{ItDCo}IZudCXD!ymI=&LL&fkAT${Ds~lD4+u33C~NoubkzFP zz4!ckB5yl$BM;RPVN|*nNp^V6{k8WULkaxI!APzQCb?tgdc@a`8C}cL2=Bdl4Kg(O zgXSenx(3BS%|tuttgsz9IT$5VK0cj8puUWHVfePx*mWShdzSt|I5{6f7e()P7_^|# zTm5gKqWSg4j50HILpdMRC}MA2-8{ZwAUHOfNSI}P*TgdvEB~qF@C}K!&(Y4r`$)af z(s8ub=15*d9g{UVJ6T+p|A4u-CVBI({78=b1}-ge*Yb<%JlBzjuI{Nb-rjnM2@TlGE#D zx*2HA58Ha`?W{Sd32yb2grTMHHwXW|yNB!_De5L0!#JJTj`v39c;s7?l2rAPMwB=8 z@uYJ&zQDRRlJs=APrIaIs-lI|(Lshmq)DbRjz+WyF~_Zl@azmT%QQ@W`?v0J5C3bK zG24*eTMe-W$nW8p(FrHv@E;F?nADLb{AToYzxg%)xe;mAfD$oTJl*SKOxt)V);(&x z`9Q&VFdNso{5>ajJd`3GU~vd_;rNQJs`|xEGc#%>)VXI)68)iWvUbE!w~DrQK}l&T z%t2#41=B`jQ5*taro5<|SNPA9hAA%~6h)Iodp(+l)f8`20WTHfd8)=eu+e)B#oaxb zuhLDU=B~E%qrxHiugK^#z2fWlx3i&H&r3;-4}&`AnXXc0?;WQ!X?FG3GQ+YVm%Plo z1`RPTQ4tcJ9E4NmxQXuIUyV`enKOMPyrxG3_Q^#bYHyUubGd|z4!XP4^Po5+yfc3_ ze3cd356u;rshKbriRWkzFP0FS3x!WT(s_MpuEAI|G6^kXm_~@o{L~62{Mak&OXyw_ zG(b&g?JIlMd6zywoD^0L%SUnKB97%!oPQo z8M#rawq~E(tZU(?_N>B&FK4;-5NemH_ZYp(83{^4tU_^g;|H_&1wnS_SL;Zb)1UJd zjDD5J{3YP~k}+0;j3g8}X(bi-2hsLIc$9XE-v#)XVF@Ye{pH{pY2mgv8{Ehm6i1EJ z#z-7->I48;mrCB%*HVa8{=qKH*=b0lsM|E;w#TKodsCP9@Si4OHajxCw^obULsSSU#?tyn&xNGdDv|1 zdT3iNb=20qdTf95(-(8kgLBtvtDdO7rL~1aBaIuXI!EPtr!fkA@p`#!k-Ut9HgLOV z^kp@IpS+n_U=$~jLhZ@EG2tyAJ#Vba;V5%qJE>d#lu}HaOMrn!=iVKIOET%8^}BcY z+aGF_G{pyYJTId%Y;QZ?bfk-8O$LOPS*x237h?RQ0AahIG8O*3eeWcG+BaVndGNGE8Wipz8Wu+M8L#Io#eG8>UrTwvbO3K^~2Na|Cy1<#1?B1S1UH zbxw9S5hQrnQX6ph@YR++IaeswFu^NkFaHQCP>9$TJUL7q`EVZ)1Za_KsfhpjScQu> z;6x}JQ?QYiDQEtT_fnetE57}rdv`~MS>^GP!U%B-_khYT)g#5Jzs`d;?0`wLySXID z+NIPSom%VaMe0`C@s;E5YK8X5*LqIFgT716u5mtq1Z>4kr$965$m?3j3ZGu~f%CqI zm9;8{BZWnk7T;60eRKxp^Co3A3a?Z!3Q<3&?$sNg3QZgME-I~Z6X$W)0+dopua9G| za>Llx+Enk;V%&AP>;Od=ghcAF_A_^kKz3*LvH{jNN7S-De_=1+&;DbzN(_tX;l94` zn%ILy_C?Ex;lCKd%OjQFs&YC9bw5@Y2ne;PA{F{GNMHK9LvcFibtcVvc&QD(y3AD7 zQ8FjTzht+B-g3Yg6>m!UCp$oE5JfvkHf5(hTi)$Y z+7Pp<|L^nI#x#e-EgWuNme}=LrnUGU7`V8gkV1U!M~q7$J0khwF9C+s^`ZSYS(=2a ziR~eFYbueDhyroa3C^Wv<88f@#p*Dl<&0o-zVy8natwpl{q$guo=o#7cXZHoIk>IN z(FFT;o4V$KlCKlAOtNjO*FWF>d}b!zLn&e3P?X1UC_enQV;nc|QWC|M%*tF;-Vil7 zKb0FfbX2mNFF)e^yFivPwl0Y7{JIDkBs9o`8E#U!TK`{9gD-~r9dcd+Jtn>dLI=*J zIw6Cm0C3-AC~ zLlk;nyF9AsYb3=1_sRg$i_&vf+ee}b9-xUf+{JU~$PLdX}0_u)l&>}R2&X$zv zJp9jT|IW^uy=i%Fd5%oAc|SLgnP$HwYO6aXX^mD!qi_1es&nveJ~3I%SP41*q&bCV zypqyUZ%j)b3!hoY@qUH`4^pf6NVR7*He}hO0B2}2M#?j^|M<2~{P3scgcV*C9h*f>ZJoUJn_~pA=V+Q4?c1bixHu;48y+2f)^Jn zOKli7m$@6@qrljnxnP(NBh=G|IDK;2*nN#y9hR`aDH(KT(sA_Vu4Ai+rWt0V2_eTZ z_@d_IUq5WfM&udU$D3#Lo_XuusK}^~IXLMS;e%DT{Xck9JI#CCz3R^ui=PeN_HQ-1 znls@mkKN~>Y}Oe%{S|%$dFE!0tLXb-uv)*pvI&)~V*y<6SfZ#qDfah-! zi%d8{o^Cs9V2L-U1CL`WPdl^nBh(#RmN5M+reBslQQ-tuPj*TyPUijlCfmGUdU5)} zmjR-j%F>u>O^PqP8P+={y`S3Zlb4m33(rvK&{22Ysl8ZJx<>4AdcASX$O|_3@Cdyv z3a=7V5?aQj0$@Vz4EMt#PHw`(;B&O)JTBDgVlUQLkq9p0n9 zF=-IOXh z7i#j^+@w;-^-6eHN%U71#MLiPobqu`byPS9n=T2t-Iqo zHSVBo(aD4Xr8hH-LchpdIU*v~i8G9otwAvXP48Vm;5=s1pLba?O2Q7`Ttn(muKR^q(j+VRtGCZECm!>keYY$8T~o}kaDEF zb?#;dE}a7Zl`QJ(V7o_8bVq`%kWfcVpBIpFoq5h#Tik>6Q}@!;4Kr8d_yX(zall%e zmG9+)oV)rb=-~rMQjnab4%x=!%=+4o5{DmBki^6OKr zis)XE6@|j`e_y?u_s0`IEMM}dZoPBhMuyQ*t$KpI#?0X|%`HLiaT&mj)Z6?ti>#O?ifqb`<7aFk|JfE32`GvTeRMHq>WMw+@R8lyP(0IBdjooQ zr3u$N`E*7@nCy?3orV|j4Dn`tm)?3*iT6b1<*RU=rL*_n#I%m5|If+woMJO}|4!vQ zH>m38uALn7;`eSO+qI+uzu{Kt>YSJT!X-`+DjS(|7`wS0AlCHP`@JmZNSvrJAXZcI zaQYe=*En;5ut(RNsGwWMSEYF;DBc!V9uByr><&?is*usle>&f54Ck39pJlC>kLLZk zBkos9r}a{qtVDS4t8J&8GWv^A76NyT&+hq@PI~-@uIuq7yGSSuy6R8**UxrKTMGG-`)_3CQLF>tsk)yi5P6n_I|uEPhM|AyTxvZc z9+SOol_jXPvP5Ee9Zj_)`>z+F*JlSZ`V^YG)teIe1@?v&aQ~LD@(sXU|B2LC=ZJH_ zW2(kH+CqP0%!rrlXPpyk`&(cP2Bn$*Qt0!RVElt{`=-YfNcQ=^YGFHBZL5Nx<)^O2 z7XW!k7M6z=qpQCrhIdLz!t%fVfJqt!jZI|)o0Xpy|FKY*kYr*St#^G%b~{7RS6PvF z0i}!!2gCTD((~G=1MzIvwwl6#=>r^$eO!IaL{Qx%RypH^3rU3seDE7E)5V{r;$2_3 zXg4jIxjW(uqv%!_y>JP(I4CqG^ht$oF>N8o&CH)i5^cBpRdm$X!ZUl;@W}1vp1a`s z^+v~~^>VIZwQVqTdg+q?+Y1E$+gmh$y+wb-(GGx?_NlXu@A?tV!xoTM^_ z3(3NB+S_s3^!k_^z`!|&VeplOnpnmDr2v+9IH9j@JPk$;On0pf8RnxeDeLTcJv}%}455wVwykP?Z_!fzcC9AjNKJdxpp?_bgSn%a*Ub-B7R@LlsSMv$m#(Q;T zc53}$cr214+b;~?ZyfrUEB&oA7bF1u!K4GU1JJDhz8O)5)(PM~bXAvgAz=TQqRt9{ zDTD=%i6f3Jct%U%WCaqqXIZfIt`!9%StmYz{J#$Y&wu<64KCWx&NNWAcbBi{O;}#; zPH6h1p3n$&SAh z=;OzroFK0?$sjM&SJZl%Ds*cpHd6UtBU^#4P=h0E_$OuzQqP9~?!B-oZsF{|+$X|c z!;&WA1)hRffeB;Bso9`(=P=u*7?|3TWvxg5Vke34^@lc ziK(06ZxV*?w`YsKuq$rqb?BrN;x|`*QFNj2Ip*KEF|f<;a$3?*w}`ovdFN^secYKNKHrukC-7H@E51M8^GLMa zQ7_{et}n=|Gupo*+O4R1fi1ST&DjHLIb(dCf3Oh~5r?q&U?e^MtgyY*6fjFr?JT$o zNLvo+QJfrGclwzAQ+>qj`LvW5o$}PDZzNc5cPV;}^G_3WB#}(|_Yyq!uLv&w<#KnL z7m;i>R48t}OX3#Yd|=#hUl^>Z%1Jhz8XU`yf6%9Nlb+7?B#QvWfzru;JH{YQ19iC@ zxjhl@rNMazqbH!LtQXUNRC$H?l|9DxW8ddIwYiAu_sU{Z|E@r1N9~%i!j^4ITc=FM z%XF&422&vbddKQN{6B=|-rbt!l}R=WW}A|V+-X~!0{^xcT4%dCsq0z2F`A|%wv{aA zPf{FYafDbmeX-JpKuF8j*6l9KvjD_Z3U{XqXtU#pc%*RBpo(+`aoLre8R{Rak-L&4 z|CzEO0N3=PC|lqrPINNgnrgp;XCt zqY<#3(b}P!8O)3G306(6{A)rHoh6CrWj&V$*ZFg{QCmAeOk}3;uyLE7F78C=hHG6F&z2i?7AY4XX6)2k* zT#0Gb1$ia*lyX9FvF$49Gj13o#pnkVS%x*it){b}eTmUN9Qyq`i z?J1n>oG-BqvqF81BDm8#Ns#ud%V~22(8qu+CHp}16O3Cf#!!_oBS&h`x2951ehDxO z>_Omz)CXjZ*v?J7#1Wj13~S-<=+wp)#MU<&ekzFrl5*##IohITKmq3qtvm8`>*Cq{ zs;>dRMqRNrX1MbD5>O{KkN3RvyWCB1Tp|9$LCZU_I;3Zics7Ll3axn{{H;*t7E>!( z${%lQnV!Eu6*;7}CzQ=}nohXR7!_|!sINV`Lj3$A#yL;>J$|QI+tcdAGcB?#qxdrk z+i$hT^xiZLWDjolJ8J9|nL85n+{Uzc>ebROAR{SgC&=^bJ(E!iO zM*hk;>DT~X-6ah=!#dK2jEZkv1G|w;9nAv9=#eKKopkecv`>6TFe@?0mKBtfHok(c{R!U_`9ccSq?@ZM*~qo(eO<3^1KA z_Mpn|kakl?=|Ac<;&59S8#@&sS!cI#X}n~@fM)lBeOxHLH=06Bq_6d_Jpz-?EuAlT zMeV>inxXG4(vjm=w#U3NkG z%`?mO%hFz3wIfjjuJnR!H#uG~F7AG0pInd$1NtEXO#IIQQF@MTIO%ykNfeqU_zt8$ z+RqsBnY+uxEt(=))MS!`QL+?4 z8!L(=G?%8BLx2(r2W7i#7&w$y(Rv<0sfH1#s~PdeIbWk0%T_wyuqhEh3@6pE`9UOOLgyr2!m_C4cpTBP#IT*~m5P{04WzWiUc9-S%5s$jY3FI2B;Hlh5 z&k8BQPMBoqdxsD(`1$<@05u2D{o}crgU&4j#VQ=Ke7HMfMJeire)KbmV_>8*wZrZ^ zRST~l9kj0@h=#G7_fM6l19dYAW8o2<{fUh(Q~eLcvLs95?4Dq$Jf)ViwS*_D1AU@L z@=*3N?w$IWJAM+Mn5p}dTC9AX`ZCb`wJ9~7P@AVh)aX1wpmgB}UC(Lz%ol{;}fhw-vvBe3iaG{{TadS+LBc#`fzM$mNZmM$TiP71A%6k0e2E;%E``sJLgMr*^CWH}=Az}N%F zSXM=FC3S^P0@;U|^~V=0bXeTeIJhEno<&y_9ipf9R&|bI>$!;1vbjX^v0@Pv)$Xq|mD45V>s-J;>{ozzwP$79$lgCRi93zuun{mIKD&zA>69Jb_{ zntq!9KEAU)FreMZ(owrEH`V%4=`!_)>mh*Ui#1}swySVd_3qp5ICTdI96>zwnl`K9 z^z_@f#;*61vKe78&~Jw>tpVi8-gb-rR2PbBBiO{riS26{rcMPatC@Y_%@J1D_sA`* zU&Psf!Fp=egC{q{nYa;Kh_or9u8g_e0k#YsCd~ z<}}qmct&g*Wyai)N!q9e*`&cW>!M}cI^$-)7hcR9YhQ2Az&gJi!=zV{ydfjQLNeK5 zV&-jJh$g9jd;`asI!qwGxIyY6+v1|;DGdyO#9o|ILLb{Eb9tRT3{HbRMa?6`u2VzS z_+WF)uD+#r3`YY>mLlzW3%}+ujmLLx2Cm{EijWo-cczH@-UQF$ILz|*KnjKhZ-T<5 zZjW@Fqnc>%V=l|ASXgaEwoY{D7Y=EMoC6i5)5U>4{tFhHdbRjsL+I9kLs9P9jAy0G zh~E)7(sfRLh|d`;8nFSb_ump_aCf#hsxiB<7gjZN`6tlB9NTENo^ecPfpK~0+F?K$WM{&!Jxh=iKGwDhz%35j-Va7mc%pkVkkT6)X+2#7& z8LYwrq#0w^B5{)voqJT~#Z`xRrohjYQA|~N&dwJIxtYo~=AXh+q3le4y0HDzz_DoH zet_qTVdEL?%qFivaLjtCkh#(!NkintFoudUyIP(G!%IR}`G@asUi2cq<)tuZ88I26 zP|L-@=Yl5`8&^{jXr~Kx>hkKS`1i&NKf!2e8V5^Ux+!7&l&hno<2Hj{)wi<3Zn<+s zOk|Dub3co!wTM@S8rr8)n*Kp{x@ca`v1qSd`KudEb4^5{NsC37Ta10a+XfGQzuiIO ziEOcauBE@oZlc^PP`55w&;7{Wgi05KsiVqSM~v4Q5ni{2nr=oubAuZOSd_DFPfx56 z!#(!uQb-A607)WogV215;cwvrG)j|kB=dYqCKna;2h2x0qZqcb<5)EAT1Zqyr2KM29G%G?~Nu3AVGICoZHJf(%?ag*I zH@9((v(=*RG^L%fs;)Rms(5Q#Q+1Z7&9@IrpQ>>Sd;5bkCU4K!`8M>mD*B`uzLc?` zkwGBGu6u#7M}|rjITUr&&9OOA(NN+@^8%{zKT9c6y`n?#wJt%$@!1^bgJqDe`2ha` z%Dd7&Y+$6Kb}Cm6T^zb5q0WveNh4J2g9+Dt_P4mw$+)dWsjr=#b2}2Dr-qtpo@^J? z8{2B(IztUQ8q=3`f|?~DU6SObbDfS?7`s1;HT3pDMoUKTTQ zWQH(E{z$LS}z6Pi9-*yc#%IyU}~2w5qv@h4BB$ z(iihf#tAOe>QMY8U+{6`F6WeoO}Y?pU<~_$LY&?kL6((wCXRf{=^u!fh(1l17wzrN zU#wx==4f3K+UcWLJ}w$AoxOeEG2ye!tv^#xX{F53kC!}xoHUGmX2&^TN&+`N+{k$! zUaRi~$+K`8A|J6mRD_DAb(%f#aygXBP2^RSga2R;O&~C?tbAxbpS8mx>s3YtfB_;(9*o>(EmRT!&yXLxSqWJa)!S0s=Q`WIU+_Cx2~8Gqk- zM62Ej5udJq02E}XankPgBWDsy+E$7I?+8~E*A2!JNn)vyJ4f{nK8jcdGk_j`oPO1n zE9_u}$DEPk{=-#263PfGQ;7ow85Ui+F#&Qxm|F1n09{trI@~vic}~}umEaW;xZt*m zi4MR^X9bGy>yNyHGLRWGzU{+1%^y6UVTBREK4C;9?^kTV`MIS@&;H z3}i8{Ky5Bg3kcsaai9I#%hy4h>fbYHM<;tB%tnJz;H11y0xJV4JG2Y!%LhzF)B@JA zdllp>sLE&g6k8}avrG$sb$O;XxDL<3Y|B()W*x;dwUU71+yK7W_@g1rM>5ciTt_v( z%z=(DY>}I?TB6A1NoEp>*&AaEF1J5bKO&0>w4qd%R`x_z0YDesO6$;!9_bDI0JuLZm#UD80fH5KNzcAVd$3HgfARz4`o#l)9p_^PaBi{Z{x$5t|j}=U} z{CyxvGDCVRXE`M;IOn2O1u9-}%c68+cy$$>x)U-j(j8*L?kPK%#0GhpH8(!8xvN-^ z(q1gtk2D~`V4hj7LJ4G%kRN%8Sh_V}G5=MRWvu`2b~-jB37^u8i~c&~%dRL&I|Y6O ze;fxYlFnhOfl2_ts`fnDTj@US7|w+mX-_Ndq@vZBt5R}$Dk6*LmNDtJp-(DFl?glw zV{x2KT!wpu5BOM7xd$dsm6xQIz`i|e#@POT-j@uObO`a>G5J%TyswqC?;NjaV^Gqh zALG4WjXnxZ6wlpmd(ZNNTwi21HQi~L|OV)Qo(VI?PqoO!czRtpD+Sy$fJ*ZK;+e(p%Zy z%|vTA!v7rwEd)3iXXp^?Lk@N0W!@Av8fqp$!%s9Rk{wVhoCv9j(lhq(oJBzsdX?zBeoASD6@#4#`@n2kOJHBSEf+f zQ=_P-7{r7*0#HA&AWz09#0qyoNWMXygya=W z&`dVKW*L3z#uhn&aUXIvu(i`BmO%@_*g<28xtv<4lam*&kehc$^*U{`qpqp$(o<}% zG$GIvW{rBu2Tak!k_`3PV^0&(@1=PE>D@NWTCv^MmF|IIui*MJm{2Sa=qC7=AwdXE z*SI)uuQYq;lu+^gl5DSI-gWU9XiN0CTcE-Luy|(WWg5 z@YCU|wP`X25b{NFV-|$_4%&ys8T|~5U@ehGOgzHvs#EmykC>}m? z2RXt5iPWhP{e6P-6?pB=d5cMvlY=HhCGT&MXNeAlN#W zu;%@PW`}n7E@?dL3TQiabY^CN_{USj&8E@&;E7AhXzm|@-zTIq;aSBt2<~=>ki(dn zCcgNYyEwY~MEUNZLxffdS8-2Sjb2Ah43-byFr30jZEbrPgKwab$T{6W&2n3D|mRT4Lh z5?1a!HR*RW3i|!xd=U65vj{~?r%*x4H6LT)u?&K8>zlSXCkCVgye^n7keF3nl_- z^yxpMY_kz6=&~LueceK5_c(!Gv;e;vQ=)5lnwU`tDioj&yZ0?uCP*Bae%EwZBN{-g)0 z&~1yEcybp6uF36O7=ZLnZ^%v-N z7U(i++(GVvB@tR%`R4;V{f!{p&#Pr^TP5%&=OuE@?cqb9kHRkR_pa-nmsw3* zR<$)5#gr`dJjXOuzw*f46=riU;9P%M#!vi_bzc>2vu4u<6t-DeHN6MLfCQ^5H{zZjj! zSq;bFV!o*n7AJS@T6a6d7&FqR-05$PD*5P5Hi6Xg z2m2RL-{{>7RW3zX#EVf!ZV$Sp_(YgP3;-WQ)- zg)s$kET?wWMhsnZtBq*lGYCG#4*{+Ap>9^nl7?Xe?n0(-|C^Jtx#1X zsVC9+ZJjLcAJzoDz!~2k{(qYc#|qCTr25qD4U)#5sp}q@5enW+vY3tRGM|1CyNus< z8YT)llMt#*t%*J=VA1J*a0PHjm50}T;hnN_ z<^VT#FSIE(kNGaTm0qyx18jS=dy+ZFHXpZr08hrh>IvAot-lib7nDakqOG>Gl8MrE zqUM3gH~)0MAhK&1^#Gc`!)ruBQKYCB0GSX88JTm?Agg8icFmW)Hb6bNQQ}=8IV?R{H$}){HN)BsuYmsos{!Rj^iJ;0+Uobvd+Hz>C zU){z8C_4X9m!aR8c%u-U+}sGckjf!%o|ZLkJpymgE&M18N`=SQ?tZOK04RPDXf&rxnr@zmx7FrA^rN0m?t7S!0KaZum6FT=0bgB%1S!zOftCh$$*|JeklaJ@t)bll^=E&nO(7H zQQB>d*p1a^=oWv^cj^r6c3@{VyI_2xo=Ko;54pn-qt5zxK~3b$jY^Budp0h4-or?L zUDoZ3G~6L>5x%ghQdeDMFibsz{n{Ctqv3p?Cdfug6ch$LI|qtDfDYuJAsCNWt>?8J zzp%;^o`U=z2IW@scxAYCJn9UDq#Y22<#Rd_K@NQ>>k%dNQBR$fYesu&9#>Hw8`3g36h9erdYmawyHy^f5UoWf+tX?P~we zM|bWalFz4hc#T_M5SPDA3kZ7WckiaQhv6l4P`Ga^EJ67oB6@Fx0W{b_iaRhrGMGcw z%tT(Rl~yn0`D@kQ5iXh)F1`%Dzaz98X0H+)EpdyZ>96~r0sOz*b>47E3}5XElDu1L zoz;_NS}5=G{H|piT#)KZ>tFxnn&eoVIb-Q3#Y&AI9<)I&v7t_AR4&`0sz53i_X z>ZvlDerc%mvN-QjGsrQ9`bMKXcr0R*D1#kT45gTh6)~6Q>T2+0=!8=@?C9n~u@LuJNVd_Bn2~riJHKcy zp}FiRK-Lx}#|Cxw$mv>6yFy+w3XG^svDK>(aUPRNNB#2Kk#X<7aLV_ggEi&HVIQP5 z4TX0~!5P0TdV(x)b>BJ`U$7ixBWRnj*h?Pl;uwCxT;I#nQ}3kWneHwmq>hNZX|AY! z{%5J? zHo!UdrQ3)TfqoovaAa|I;{#&?5&16XsL*9oVjOM?Be*;SsG!{{MNlAi@j;&!bRU@p z!D4?R4aCo2JqejI8NIOiRYcbfdv5IB;_3MEnY#Br<2oigu$G-t3~kxn-CW)OeP8w7 zhWYKcFVp7gqN^pZRgVqV1N;>@sc> zy~ED~u~Xro8dE_t*NQ(LyT<(aKnt1bq~M6dUMD`8@au>Tx+mEiJmo{mTM+%GB4EbT zU67$y6T^2?7aM>M6U%@3Po~kTzhcuqP)RY^>qr0RG+Gi&tP0M5_(L(grQP+?yF#+t zrD^Lqv7L2tqMwz*X*C?dKT)#z@TZ684NNoKLbXrO&KuaHYk6a#_w-N%#+3Q1_=2s( zH?hdm6tu%xD8O`~ySfbOF4SCkN&38%607=rrSBkS#Mos-gp{hC;;x4DQ$gd;bZ|V5 zt$FpI&&f1IVKEs0ZsO{kqSv_&&Xf){|1pR5CxlKdZ?x=Z6p0ZI?QrmuVY@hH$pDO(bgbcFL+hlrrqUVH6EgBhb#^ za#YQq)`m9jATE!^WJQcYiB8!1VN@_AC&J>YSWF~oR{`?s|9TA8##P%GGKV4=)^a)0 zs$21Z8shI}yqj;YbWT1V%+ARhi(Um1V0WLYYO*4hKFRDCWt_3n;>FTM;+P5fWH_!$ zQndv+GeC<1_eI$~q_J{-rZCSmWwdg@R$7VJN`pVj+Zt6*bYStvRKb`gB&zFe%}cHgbBzKM=P_x@5E`>A&#>31h3k+Fm@jmF(cy0MlL%pM{Y4IJ_*Y{6ETHOO=5 zN~<2^zbxe&X-P=}kxp+W+mMfYur-|9kT0i9iy-H&ii@y;knsI<0?;5B1w&U13Dysw zLVU=Zw$9C+^gHN2A&cUk)Xl>EA;Mm19_)(s9)SPcv`I8?$#o>ye#Lz1F*{1^^tx;$ zn1RpId|)uq&G^ZOV7E}W9B{8(zqw@&b>h_6Rvmv&8cnJ+O4~);U!aQM2<@&6W0mIAM+a6+saOme+oTqnyX*ke)3N-xZ5q zJD;}AF6yS2p zEM9y|tjQyXh8EhAvLg&(xF}PH16tQJYrwFGxF3E`(+xywNB{=%G<}!GZ!k10S}`P| zZac8SvO?4t(=W1gGo<2#DG1^dt>srt9k8~h51>=N6Fveb+m zILwiTfyEzn5ACso%20NxH(qFFKe-X$NMb95Bm~xu_Xr#+?=Nx2r-dzz%ttT2_Vx8& znevid(wT>u?j^t(rW00`N47!Hl~Y4A&4%L6y+hWuR)z#q!I@g~HB=)yYh@e+wrWF- zm&@re(%_A1+wdPP$Hw!PW4s%HGKW%j=?+=vJ{`e7j9jJDL~W4A?2iivC)bJn_LGQV ze_8jFZ3$a2daY_O!EhLeP;s9HId6*tj1?8d$BqS08E9XaFhfbq1O>%S^-^d1IFoYd z{pH7Q@2Y)6KUlpIHB6W83Rz!^8%fTxls7wUu)JKBb=hCrQWTFX)c#=UW`)DF(W9(| zB!;Bbba|o|zSlfRU}>H{x@~oB8A0np2cmQ(X1+b@VQN1a1(ym8$^ERGp%LLO z!Oz$CnH+O-YaM7S%Zi}vC^rRfL%?7rV(d=JLZBw(T5)Gi(-UGQFFsSs=1aU0!IO9u zsMU~gtZePY@+ixr8+xy|+@3EcMy^~3QRqDILA768NLXLy>d@8NBtt+~zRFPs;AdF4 zpqq*#9_K1!R;jP^bL>6CApyyPesIM(rodi+XjKF3lvv=;3o{*T$Ub7mPVICfY zu*T4tyG!v4ytgCL4UJ!jJ%%%2_+kbTb4uoX;hKW=k4`nJbBfn@hg&qg6P$uQ9A34z zk9{{!HrYhB(=N8f#aSw2%cgqwQr4iA0SI?{mWrDmv~_l-%~yt*<=NVOqq zOY*OXop?ebf}|PA%`aX=hgBoi;CMb8{wG|-R5H~3hgGNCr|u@FVn>`HNLXYVcuuHC z-73kv)m0x~W{knPG&&3OJFc9i`&<}h(b`Inl1~r^S`fM9c0y@as!EsfilgjCw~k{y z36pyh6q;Lm;aXyvpQ4#U#oGzLhcGP}Yhy)K0PrA`Pal(>Mu*dkAzUr4zxm^A=zJ?s zz0CqL=by{SIPh$PcGrv8#@9FKm!8lCOKXiDgd;^`86inB-Xh_UN(y_#BWL-DKNBhq zPtR+2%SL#oaEO-AI)l!Vk_yHdASqMEYeLnzKh6Y~Yj4PGDKkS?IbvX2S+X9+ST7j2 z?34J-$Qsaz_<(lAk=ZeQ%9pwg&7ry`4II@qw17C^0zaq4imb`^$dz%~C1McGp!|MM znI7C6zC>AXTHrJ-i&YJ!!ov8&qBQ}(ZDim)O*;o%>)>I7AlUG;pl;)Z11pa)&F#ns z1Lm^=?(K;1^lzMe&ugCl0ItndWqE%AIPAdX^wE%E!kh64*aymtEjbd>uT%6y79PHz z*p_gqYyghqeM#~pH2P@BcP zUsd!P!^$9W5+@2pQJGRhJau!Iyw^Pd!*T#Wm;ZN4IYT9fI&>lK#t^Htx}a8x+&(qr zK!$a@T3oR5^B)4hVTb3Mt2><6_6}Ae%`1JUf-@sRl9M1hw;#_PeWPWW8k`)PnKC?$ zSp=uz?#%haUY9@ee7hm;-oSRBcn&`A1NAj9zBZmuSk)x)v*kZ8rm!hsJ>;-bAOi`? z_&RR81eO#5MV85Xi&?%hPuS|rzl)?%iiH0BDAaZ4px07ySEaa^Aw1C)jL45AjsCHj z>_3RLQ`(DWkDi?fDn;Yb^BD2IuNwu-qAea3euZ0^K8OBjekkarNwMH6U!6G62B#xv z5uP>@9u7b1Kkx=98Xji=Du`%`5v?eK#2roNONWA8ze|K%`gi5wt<7JtzMchwbS~gc zG&wYQIB1SHYPGEvr@?}IJ|$E>I@+H!Iu+Q4sTZ;Ca_UV{uZ%sIk{&n8L=BSSxI<;4 zRsJm_m_9nS3)?Gda$JR)x`Wa@@-D#)q#FOyfAKICh#UaZjqFwsj6?*!~2a87| zCfZPnG|1XAn1e{-f@KF_K;LggWuV9UIK1j*tO`%~O>`4Jbeng9hbD1Uc5$+LRWHfi!?puE((Kf00Rq+UZ8dZ@28h4n|CqvLSB znBx8sxrLbQru4QX4afyjd!vYMJjEpe#FWv^(o`Asc@iAv@f8pek<)zlG_(s@ccsnl zy1ud-ipf;fufj4(Pt~fATXAYea4@W>Q^;hy#BDkJUuGB6j5yCSrBAms^2`B>t<31_Val;Pvow7u2{ZTrcj}uO{scbkNnH+)s>zF(Kn52A%AoU zEs(k^D=Xnx=HYUhs(>6!4z4`WA#p6OC|2XEs_3>{8KHl#0gViR7s*s*Y^txYJ|dWi zXtXC=nuO|(UQF$H$Jp+*)dQ=$SnSU%aT*&b@2fh z3nXcM+FXh@Paq{6d*4%@ghA9<%lU!{VvAQ`;$&Y6v~`9{WfKfpGpv4C!j?0#ec1vG zUAs1q84lYQgaW8(UKCb7Y%CJE=0J}^(0u`=U3O&MnA%WdbfJ7Q_n{gnAa(rzE#UIY zH!G&AU=V8c?_WFTRuqXxqg*09GI=2KrSRPisloC;@~dvfm`|bs*iU$E;xmvL<-eq5 z8}fL2E&0zy?{XGLuQsI0pOle^*g2YHvrVy@N?@=CoFJ0IMLt6_GD}`FP z0uG%gpVjg-T+tr8zy7aD#i{Do7Qn-NXFSUB!DJPZHM1x#wdpB?UI8c^+Tb#%3AnIl??T9z+KSb1tQ(dP%Fg;`L?6xe zQcrE#%Rv6QfQxA93a5=j+Y+IHS+U5`pM|Q2PaMV9-$QH_wT{T+XQt<``L;&T1X%$~ z3I|x}-Wv)$fhFf-LZ=iLq_K=}@Bs#e*uSGTa2}e~kvpZ_BKtUxZziI1S)^c}${EeU z%U%)^Vri+ESr89SZzaJcsjGMr#k&rZX1n5#)uuOi_`*vCP$@&$R5D~umfOhNMn+_2 z+;QbA@H=nRU5w%5;0JleeCjJ+L>aXTXTi)|QfE#3o`?^hCHRkCsfj%#my-jdM$f#k z9rN}-J92L{su)2rCC7sHN|T!(*%7@#1YxOdZYaS(jA7XD3 z4RYfAlZO7n@*nPBL?3`N86(u@0}y#_j0ZNW$%9|Lf&}z5305E`RA`tsdtxWNpN1a% zw<&4bbkhHD%@u#ls=x(n2#k-4ixdB)%Y>~FlM~WHsg$`mU!Fcq3Fzp>K%TKp=R-op z0NfwC*zg2=uzzgKD2#2DO$N3`dq6w#^8!JLuJv`>$M4mC&C=3;)InDNOx#lgK{Yh4 zALlsW-5kVphgIjdzKW>0S690(i=SWq6~WCT64C*$(=2p?)8+$9DvuvEuDf732TT>R z88|x9ibr(Qi>)gvC6nVUuwIK;Q6xUnEQ|pN`Kt)?SK}d^@q=+$W>nPF%ha7AhhX)M zHU5m=`br+m0jJosEQ)`XIfOqnF!a+*wH~4gLF;5OY4+mLf3f{tryutJ*wteqB!OHiD8>8(Va88r%rW;&#B zo>35){Yy9b<fDHv$HHsMjyu^EZr!EFp{bSNK6b`BsAuv@y=dDsKcPX0ceJ z$7V%a;@?Iw@*AP0-LqweHzPSg{GM0@<<ag zm|bek+2bu#ezHSUrzt^+kuOHz=b*;7|-yE)a5bak02`J z4D)&7BYV+by%V|GVtJkPc$l)%q+a_NLYX}@)NOJZZo$`XHzYcvX>~(HjzC zAD7F;Ggk8mO{wu2YQyT%LZhb=qv5|{-pA!g*m#FtX`jUwdSo&6jlX&Si*qcx8tB)8S}JP4!WB>NYxpHJ0LTe(Kvv#u_T{OMJC1>j_`!!eqI{lY{8lvF za-zY*gvQi<>yNaPhC5>l(pYOSx`Am)Z_8--1`^Jk=nEE>%<)O%R5m`wMkl9y7|XJ% z5oST^W>BH}D?AD8TbcYy#G^G&j3@%5{_*zZ4C(i$epa)(*F@fTs{dvR#s4M5+RP_j zhh|KfmosS>b?(nK4NM9Yl!zmDLLbsXg`w2RI|2y<16cw^0Z2%X2UTr8SpyaCOT$Ml z6NgKiN3pWJ1FtNx07@K+CzEHl;4hZ6?T9c))w6|#P_Xv@OjNHL480R;%Co3nYa_3Y7b zYWFRjzTjKCdCmBXys=3q*CJOeL7kU&OC4{2PlLbxEbwCa3~ocVUXppWwW6P(Y#c56 zC8-zFpB8$eNvL|SThJ^2%U8~btuQr&kPsY--O>WK8S6u7qy5b0gAsbhpWOT0^B;@< z$A10nL_Dwo?05@E;_^$!T)tCIhl))sybqdCaFOgTt1ew`m+>G1f#=63nlK#ZiLrvZ zjf4iY;-}w$4oSdjPEKv^51YgKkD#K6{&uPLnD;d7gAj*qw zYVgLY%7737#R=G0UO=A(Jg8KGcNW<*opotn}PyQcGtVTnlnwS+_xEg@|GX zW?V5>gBd>ph)7pFH6H?IrMqwcfJLJ*E7Zqt!><=8ZK-6uxenE+>%!F2YeB64aJo=` z4y8o)D@N`5mB%@${3J$I`L%$X5X)xF7wb-!j_v;O0xx2mJq`y#G@J+Ks&f|y)GFMS zgu5F7^|zuSRX6qG#Vp?;UM#FufX3v0wnQg?NHHjmxm1?^){1ucP0&01er8mFu>~2L z^xq@m^~}I<-{}e|gmb1P)A29}#zq>5SL}(8iB)1DSzN6~SigUJQ@8e+&$-lb+q*G7 zV2!rWqJbmZx{{vTk~r3zMwr|MQpBN1Q2y1BS-#m2urL>< zWY|!P34c>258qY4>ZCu)G7nnSJKI;CDKox8KGMGD`R>Tyy)}8z^YWiS$_$(AkPaNX zX#@$kty255oLt^F0Iy~+$vkw)&@@+|i4o=u$?UV7zS=d;T{tY1T1;)EW24m7$3w!_$s zKsi*wrW5!ng;rezhVk;BK`7QLO?*4{&dhRox4XM$eM@Sui(#Dv^Ou0hb=p>hK&6a! zDv#arnt({8DQRj%Up0ZuCU{|0s#GeU2DU~VJuhvE`j?cyjMw}Z)LH^bZH)ewq`$-9 z&9%0}zb)Qt^TbMv?=K_Hg(rWl9eE`GMG!!V>_3{>QLnk+V4Uw~Zgq!K*Q{%6jUJ!s zMl>z}LhqM#V&Oa&oUw+QGpBqxC?(9>TT&@{)~FWNj7U-jfJ7Gh3K{EYKt*Bm2W+?d zbMT7SsrlkAwtn;a+6yxd-iQFJIe#+~{`(w;xj1|WC+3TFYrS%yFl6uOo4hDxzu^kb zjl6l{kL*vuS603U4=k{orNEqz2AC=OIFi)?#YtH`*#ZMP{vz)-V+6J*fHJ5?vwQmW zO?peJS_Ky_wR0~VUfofq5+LgPCzT<}MhDcWj<0)I&HW@Fv3&X-{J%)`+|O=Pl3H+c z`6{f3e~+M`KamUKB$UkoTw5t<&39O0lX=o;r^!6YNQGJ#MqGjJ23=S<5HpP*IrzV{ z2}vpXerK`+0K3)*jAB{_=r+>SD+t1ZBPP1MM3`KZb8`dEw< zYBTJJj&dvT1ecZ#DdN-#a7JBd)r=C8L=LQ!DuX`)liV#(OD`an2q4$om{&JGeqh<= zuyA^|au4IZM`4Jg;nzol!5L0Y6e|#NwOX{8u-}lzH=wljf`L&lyrZW!ig~Jc{S$!D zR0eBqL6cossaCYPgo@$Zj&iNXZ2aWQNY@4`xfV(|JhJD+xalXT6og@z@{w4_ss`MP z_*kAt*d^z45EwfE#OQ`MewS7Lxvu^xlkV4E{CepN_)d`=1e$2s#q{6{dLtQLSHdll zEp!Hv87~6SpMT$Fd-(ao<(hP$%u`I2lF_0oASKdOyx+Cv2TPQRNd6;;2^_m=+deJ@ z*mNG(^GzY1~=Soy2G}q{f2d)W;}=UhkgmebFP9plxix>5Ck-QdngvLN1POINHG&4#IXQ#8ev`!z~?IkKbVj8FJwgoq6gsL@t4HDXB|HO5!4}AY?MwHQVZ6H@rEI zk(Yuf5r&s2+SNh*i%M+EpR;$sgTwR0Yn|azv>K|q^9D?lM%kcxnr;s;HSzQ~0JbxF z$=bN>R+2v~(oY(%=d+KR-v942%lS3prBq1CuFW4t2zl>;MY#p|0Nzfc6XhDd08m&4 zf;5~YJ`!V-A!7z~_9ndV4fK@wu-7$zT66XjM`9|Kw-!q*}Z%zm1EY@_RSIV9K{&EI^haT;G}lsv=bsf=9Lhwh4< z2pNt~xo^bM2rR3p2@6TZyUcSk*d+u4^}&`eaq`8}&cXUEnQX`qpY@-)qDKBb`FD3WXKtwb zLgSXVUB>pKTPJoL_e}9Y3X`52?!Wi!a8Vb|tx}=C>vQ2-R?>FACnZAwP9ysVj=zv% zaj?t-eyI$4$)=Qjs2y&BW9>psX((j?KY=C15V9O=_+2MBid;i~kWx9s2S^)pk<{WB zLpFs-UmSA@VKSa`soEY-18*PFe^iKsd%v4~PxA|g1CFG_>9W!G(*0sXUqVRdj^i%c zTS)58u^^hy$AP@PI5_{F-u`*|l%6rjkmDdPCXp3z8~Adt<6kC0;mA6?wv_U?W-X;R z)CXCiaBbaA;eiwoVROef$!WeyfiD;aXUN7rn5`Im-xKj5oq?o> zb@TwrN5<_-zee2HYq0OsV?4w5v4gShQ3gr;=7Dse z1f4Twl8iR%-)=~&19ba3d!nI|raqUqY%BV@L!Yx@A27{?brfiP>9j2UFPYudN4x)FJu6w#W z(vx4HyDUuW0F9XW0tgbDQKT+Fm=_+W%(a+bjDo%ZUcNrn;vs`Y&8))P8e0+H4C!ltZg0s5%lT@CbAGb_2$CNMpwC2C}q!1sQ34;XTqS<1?y4d0mGj0%C&C9zzQ5~GOkS9a^ z>POZYpAMI}dp!@M`hLDK0>hPVz(g%U^?{v&?6;6Y`-27Fbp!*Y=QF3i!2YX+_G)$( z7)m@k>g1*axI~cX|D__Lc@zHkq_WrZ#JkTM{1!OVIkAxq8*}ADY3_T5QgQ3>{B;`w z&jun9uikX{^dI8>5JuDn#Y$!*M&|=&WBMnBTlI4J_{dmjvq@*A#_7!U`?_99Yk(H$ zOQ*(r(B1?75kUxcyBP;Z+%UdB+yY5wX4LA0w^0VS0kLf@w=xV&azcY9=AKIohvGI* zI!ICx7e}o|NnQcRbh2A_y1!*29>$*y%CX0e+hx$mnmiH~M|M;1-L3(7Uu|rxLv~)k*-E#VK&H>U$`c%R=*wj3Pl$^#(iP&mxOXA& zo|#}_jQX2?b>LYjK#n@`1r+(!-3|2*MM^E+)qq%4zUqCBRhO#Jcai`Zjut7Y+4iKI z2syi!_`kjc+gzw*pJVTpOP=4SMC;stk4M@Xdm8cL^B`psaJbdO%IS;-J6V~oeB|On z=}}5FQ<^BySG*efR$Y#c(fOcw0hH1%hzczRw3p4CNE+}%&tG*tGe=|Nxj}*Rq9Q~ZT>GPo$?PwYopF!UzTsN&BI=~*>hINXl5_&ntBFnnfi{>fAS z`&(A+T(U^x(H74Q$^D&0A~(&S!$Za3{t4J;a{v1qnJ!h1{zYzyjKL^LW{F)qG||;w zhJNcq60WdK|GIUJMFuY)Fe+xw=&c9JYP~(JcmXyhkyl}&um18*4r~*M8g5Q_&y$AU zyB+Jo!Mtx87>W#tZBCtj#?p1sJzZ;T11$AUz)*3g$LRMTa1h z83z}e)1ni}(7=;Vcxx?L^6g@}70dxeMzEgE1L5+ov&#t)E^o~6gn75yG=4^>r-YV= zHRd~TcbvFJXWojG|I|Tr>@eOi|8ZHZVq$D}v^Y+X0&7CTF7)8#BNaY1lXy=97)$cw zuyi2PYWGltl@7lC?{5ow#(L`KFFAEHP|Kg!3&2N}lY7&EXCCdK9YYtscO}qSvZA|g z?3Q8-4Y?w@fSJR0eG~vsee{3GN!xqZD7li%WM$QU2waXl&_XM@~nG1h(RtBVlON*6-JQ)tVk z5eyen!eq*|{49`UIUP7;E>k$yl9=E`p@)xRxH;i5D&HWxthZ2e5R5nZB=pb6H!KL0 ztodQ~3m|UT5W}_GG#>d8OYUYDR6E~We*dzAPo>wk#RsolZhzqq)>Rm!HUIuJ#XKhl zw4Mu!Ga}2jN;J#cpm4qwNv*iBt3@_NV=cg*ohK#+3F1T|1v;mnyQiBA$S-bkZ2x}< zyM@^--wh0hj?hCAx-LuvffgfJJ7D(U3?Ij(3XJQ6WLfs|kDhFcJ#5bhfDSA&^6=$T zt&iNy#BdS2gJD)m^{~nOTb`TL(}4Qj4eR^&S%mISRE%4Ik0Q_R0#qxC3a@A-dU5Zz z${~c{8CM1(d=0-e1#~P0Sd7m71yHH4@Ap-qbzy#|AL^7fMp2I(r{>x1im?o#M9E>n zA+*MPfB;3fP2n%Cc7rm=hZN$0>JGXmwJVCjS%faZet3m=*=T$@4LaJre~e*W<^g<~ zhA~Hx{|w4SE*QKPJl;Ij&gCeZyv6N}e)ynxa8RJ& z5)>Q)(g{~Z7@Q?luk+TA+>kU8QgbCe{b}#5VV-Rc!2_xi$RCIM;GTwy?eKSfk^h&q z5GL4ZC2rgapVJP=&jv-XNZgbwky97LNhh(LMLQV*-jzWR2~2Ax>~n0EGtpsz0FbU$)#Nn*Ac@9qo*8HFOgi*H?9F0d7PSy+YUK--*XXA z%!1~NJ*&Nk+*_u2_d5xviqCsi=B0}-AVerhoR5DuWCLHv65r%zM(cDOnlEl0>FrP3 z4i&@*YquH(Q8KAwRK;61J7X=~OkSruIHv$G6bxtbX2-s_I$Ajg)KQx^Y9+ zKIwV9#ddJFHAUxifMHb&iBPz`R;&*#w&T+$rlzWgL~drUYSfdl4w3LNilMHUthd#m zy;d47L9b6nu5R@_j=)o}nLeuK%nLvLMfSo)8kg;Z?HBzX9o$~pa>tDw+M!3C5QgN> zWqs|X+#ZZu{mlPfWQ2=$0%(|eM?=K%f^0qq(15!wiu0OY1jGwDTsZ#jdhlej znOgu(q1!_+kX?~$O_%^YWd=??xhtN&e5P6p(;t5gc~X<1%u!9Cpxv<8EBmqH`N)Ad z{%EK!h+$ERR*}vGuZF0kZnev*i|3kn{a4H=`{BcQGc=yi9+e$1fefTrqAqp&c+;Y9 z7l&aLv(gM+4bljDdXXKf-!&bsH?v#RX!+CMY|X%D2*9fHBsEKQDh5Ej~)TzT!o z2ZY999)~O+LRNIJD_>+DuI*`9K`tLt^FId>rF%93zATktWww%0@tLQBT$Y4!J0UPP zzQ4eDz8Kmiyj-c_25K$T6ONiv8*U?y;l^LwW-wn2w-oyhhz)|@_f};@2Lk|T#Xo~t z7DKJ?({=F39bVO8A%|ROW%j_$cC$&fSF_-+*=z=MYO3GY>c*;h-YZVnQcR z%R!j}Tk)~>1u74t8=hid7u=N1OAGjIvG@52A|*O_aC{XkPIF{mfs90II|UVNEN-Gm z=-$Tu4oabUyg(um4W(78?*ELfd#wi7GR9n{&ZW1yfgqGm4(ke(FlNs~4YiE!dXC;o zjb|jIAAq>~AdJ}A9uG&vAaT?_c)JX^ z^Fz6wiI@wmo*Ujs<=s$Sktx1q6emu%C-pQf5JMNL-=@)7Oz!9)f;Xn()g^IB62v%c zC_7g2qXNBV7upJBddqxBS5MdL+`sF0sDlU+6-~!PYJ0#rVFQeMm)in8cW-SN`9tjj z{6R>Up<+TKBOCf5>`@xsPWuG+e5+J`#HAZEx~EYgGb@_J$Hc^%zmk{0D{KaHraHOz z%Guuhpb3VvOjz*#E4%3^gyxK06b_Plw4qR9z(YGCA21s zzE6A`Rr&qQoh|C<6j`O`b%d^m8?Jm-bq3>uAg0d9DcC&o*p5()`4|}#SJ{pDHp=pb zZBMPk=mDrxO%K{zA;bSo(nRF_r{6)z>XwNXPbA7=tvq(K1dWdToiR(<=r)Ah+QX+( zeVo|s_Xe~Gz$p>+&c628Y*f?|Pl>wGYaeo*1I?c(+s0H0I|MoVF(kD4t0~IF)S`SC z=mx=qn4nkh^A5iXHw0gjYrB6f?r%ftn;D|sCp8e1WO8il)^O-ph z_C{)7XP&iwk`uucWd_DU85#gd=wOj~@Dd-xDNoZnxld(Y%8MJG!1dzb7alyf2m$b4 z^I%uDvtyBaNOB{Z=5T>`RhfjOz_vzOZwT-t#n9Xf+m4sA}*VElL*nj%=O2DsoYHAWEigi zhJw-YXU17Cpb2wYRJ?3;3c?F#|BmR}=v<)hkcpXjZ8h@FEg}n?4a5wdoPEaB3!atq zzVYyJ*vYTi#v;)q96TW|{eT$a1EB24!h>-H6yXZlYp%FYFIFGGS|8mvM=NBjOlO}? zZQe+ToT-@T^~~f@kKQ&#I)OP_)N%hnUtkAuVfAUZclroc6ez!-wUqjYz{$M-26M=T zhp^NfB<$7~{_mZUgzXa@A4K+-C;-%=I! zm6?cbIZ6q^n|e*Vq3hnFA}P`w_cFQ#+J3L4DZ0uQ#aZdM4%gZ)RT2V@r_tKcQP z&KgK)U`y=bQYx)#kycMz^YqG^1%q9$o00`=qAOpcn{9o_w=izNH zLD7hh2VP3xV@WEs$50?lpGG1_syxQW=VeyfjJz%5VO({V(U*XCTPl5BOK*Jl_ZdZ z?Vgdx1yscBoF#0W4uxvV=~X+vTl5HIIOZOe=70Ee)8CRkydBLpp9=EStPe@`T#~Cx zDhctKmnDMKKr7S*#4STmcOWgknd`MNG~m5UR55&_6QNuX7|xX2Z!{H_F5?oWyrko= z@8@0V>S&toSWo3#u1gF?bgS|J@O>kmL-<22B|N+vPKuZUuSf)(p{F;)OuHOeeLZD~ zs3Wrsu4Yewfrhl1XZT~0nK1p=GZ?0zsbSRznbb1tz%5zi?D;USsr5$3o+H;fI*?~< zMkhcAoWSoH7z(-9>)dTq0^O?r&vc=^-LykF8GOaf?7xHa$8bylBJS}Qovog~+xc-j z9~${9_ZcHY7jMLJfuTztwe~_ZVh(MY1xL*eM0jS((tJ?Q@~lmsVR4%WBcx~f8Mapi zFRTI*b(J&KeTVawJV+pB--0|8dttUPJv%Nuf9|)heJ))=zJLc9qP~P5TLJA07-4sg z9dI^FASEe3kpAI8Af6W(Jp!U#85z1GgkAu!-VDpi+taoe);#?F&N{2&=24`f3pqZr zSSFCgq5u&YTS5HcL)9tVX5@AJO%PHKG8cHXHcbzHN_@=|NhwS&aRdn_zOE2(iWzn_bYqbIQdRr8Y06e8S z;Vl6o;e=A`4Xg#v`#kZ;r$c^Td_{izMFAOL9KZfrLJAifIS1T%9-el_Ac!*Dk{QkQ zZ0j5tFW-UzZw(gDh=F<912(ZRbqtI|e#2lSdc(;LJe^e!Ym<83z|jo)*-$7LjSH@K zZtxEF#|AIsg`_iwp4Wta8rf-BUDI26$UHvaxXGfKRr@?$7V7d&AJIBeq773Zr_5Sy zEfE;1*rh$$eN&>g1uy|mjySVoOuY5Mdnw^|;OHt3>+%P@#kB09PxbeH>UcLBJYtZwbmn^!Rapt~b2Qd^* zmHFWUbdIN?B)I;#NfnHt{aN-Zv#$=}4`exo-Zy#-(0i&a60%H`Oxqr1w6u2+w?yUD za-aJ!YJ&LsTkRM)FX8$8;ea*C($9YT;h#UvEFWd6M;oj+ITcY~MRB8Fy-v$rPxZJ9 zSjZBiUqCDf1^dT%U7WJ$VU$GEqYE8@R3?dG(l5V;q8#V8f zt3YGL7v#sk5j`h7>WD7Rl*XF1h&r>iBD7E|Wp-2xPBou#$aZ-|#%Ag|));npuR-%@ z?+toN8_c=#D>JHL>QQ4>^rk?7@Gk6q>jA22rN&bw4^zTI~n zm{)+{V^}c&WE^B1_Ul|A-Jx^kJE}MI801F;li4Wc2q1Z%F0^=~hUEZ0=pKw_=i>y; zW5OxAPAT|TU>f$1N(h88_h>EXgNa;uIoID-5p8uZ=Kh%{bC7fMhKU=0E%Hp4>W_7N8Sj<` zx&x>;G5~tiue|dH3;MM+r2wx!@&4NO9O*cb7A6o~O&PXcW6i+gs=!H*>kl%`iRTKZA2$6n`^_$@b;b4UA`bkY3q!A14w^{A> zxRDt%*cmMdmh!g?dxXsvwYcR6)UX#v*uq8DzV9|O+|HSqFnx?NzZS*B!=?7XQS>qx z@nEXnFZO|HTZsuqO-tiiMP8aiz$)QoLFtL{Cf*BypfAZuB9s{Q={KTqCgn^yZF(Du z0HAX!4Gv$`PiebFZmy-OePsheW(S+k{$Oyc@?G$P}8JPLGC+J(0IPXB(-i31F<= zXHZX$pD)-AT&6wJBoC{h6Zw<36|bBW2S95yvNJ&evloa?N=s6_FMqHniBk}m8^2DC zMzyD_^)w@&*}X!p0^o7um{B(j6b0xZe%NH_sfLEZ{oTL*a)6jw5MoMZcWrqUQ8>Li z({Gb@a5uiaNnlDt4D`qV)YlxJ`^#S*H5*(Y2~t`6Z?FySwmtCM&D6>yhC7e#FNmig zl?JKcud8c7yIq{l1A>ZF^phQw3t;=Y&WJztdS;UfnCALPu@N9;e?o4@jc8aUSaPmS`&au^lA&d=E<*1)J#~&-%#>}`PK3@lOZ9;U&-XY>`5@{38m*Ut z%L884NM^AxF`R&yLI2!!SB|$no7lM{u45cOA#Z`v3mFBnIAo;C79A=TRiZ`$Lr#|N z0MlBfa9N*t&#n%Kb(}Evau+08&ve2sf&X(?w~g(m2jS_f_m_7Eoc+%lBgk(JF@RUx zm$T6JKv2_zbk|UkJgI2FXF-EEyJYQfOto@K2e!nEJi8@1%Rq&WK|eje*)r=5Ai5l_ z{*$=Bi9j+>tflPOmQx9F2%__yghe3Nho3geG>xqw*d$g+4s|z!=cg;?UwuAmFqMS53R^?G^M?t7NI4(fuvlBCuI9WbY2d1R??gNmT)u z3{t>CK)B-;$$scIH!wK3=n+FbR-x;*+ZojdlJdmUb>d1>OuvIWJr`Qz?mkGD0Weu8 z#u0H%M+XbDCkLxws}4Rr@9{!^pEY{m@%0V=v*{lkOMe^cdeVyvBY$Et-eR%}jL!F# zI@)3MKn}bqGALoBCwXqN^erGBnLRNO+H18}kD1uS6dBE^jE8fVJ7Hst-T|UHsJtxM9jqyTc^dsDOq9u9z8J9)Ms|oa0i@e3H3o0J8dAYRZ{Ax(I~?UTfYSSIwgc zNXU+36-3j%kk^t0l;`95TfEKF_6&nk5r#aJ*BDhYvpcs|57XtHW6JF@CNx|C{;^F^ zL7Y}t%{w~oiW&#Mb;P^9H`;9)AD{h}=?H%{)0|ppahFs*T*}q& zC|v`*PZBa_d{R~+5*{{JP5G(7~An3eZ`)(!TqpC z?I%I`{N=-&t9%U4ts@i- zaBd4rH4UCY9J4aX;n!c2q_Mczz{GyFGXFe>yA^hO^mAYRA|e`#0Uc8bl?Ua=&Iw{9 zJ%q_nNmaH`V3u?EgCXv5mG-ceatL{UXQD`(NaIn3^EuY8Aj>ey(j@870cD@wG%@=v zI%i>v-?pL7EwA+b!0uC>MR&sPN_>O zT+Z{)d&AcEd(~l<*q;wTBiKlf<}8L8=b&QtierrI^khIeQuGj~QZ7t%B9WqtK?^Q_ zs`jfv)MF3$;Qzh1e*VwQW&U*O^6u)nz+QxC#*117?y&3ad)hqvU2_(e&h<5F@a{U% zz;%Nb;8r*ckWGhC_)fRA^m-+s;^}fe{=gZbOD$5F%}S1Q^vxf>4J0T?gM~Y+w7NLi zW`UNe5||eFKKEE{2hwoyB1|{VlU3y$I7g=CCVYVA;WkW-91FILBYZl76Z;7C^}zeH zk3X>9D%yO~S+EcwGYj6sGa^?P7G7xwJ0fdCt=5wWc7;6vn5T+UaWG1NKH}uFfdCPl z+75HXEw=x$S1tCMbn_6p)o)m7K7&mknPEuvD zNmOxhvj!z-1zf@0PZsVG=tJ`AZF+#-5Wg*?EfwJW1UN_UC)KL zzyr;kR`8JNBnzYp=vrOH1?Q_ttr!Lq^k0yM+s;Ywm?yTLW2qaC$zZ@K3SQ-tS!-iV z9tI;LDHu3jHjhZ;-|a1h;cA^2KcsCEXv?yefKK-&ieUSl9T-BrVuY>e{|Rq3uGc|_ zY$lL=;%^Kjqxm;%5+~sLR`(Wqoo9DZPFATE@oCf>O3?lWd{5#EyNrSbhFS$OOBX1Y zq%nIzn3y~QlXhP*Q_Yg4AjK1#1-3+0WcgPBPaA{Ndxo6yjKaB$8ub9A-l5r>5mDRh zAbeJ#01D!m_c^IeN+!H2DkqFmSLk-8(pKk91iPSYb?l|#{t{w-b`#96;1oPOQqth< z=&@Rw5BG^kUR6v35jFTJ1$tJjF_ZbjAu6Q;ZfM7V-&nABygnirHCv`^hYBzl$zE|QRQE`?t%9LYv3&^oS%bD^NXfJkCM=pmK>x9v z4(euypH2+cn)p3o{Dd2%p#FG$cP=5;eA^RGgdpsE!lcGI%#k>@0nTCvXtaE?8I8Ll zKsz{`^hW3xfl=%L0#yaL6w2~8u1frEd+2Z0#T|RPVHrc*)OlG9>=kiGhjH*=RZa(d z5@LvM@Dinnp(N>^RW%t)pgI(hm zv)cn_MFtuxwjtZ`(P{2O5VkB$+L~VQk zwi!~$b^3fAuO;+7^Tfa3PnPm{*r)jtL9}$IKdn9V$Hf7x{pVD zg32yZ*)rb0qcfxw@k7z|&MHE|ndm8cyNM4HM=x})V@jK$doxaDF{v=)YdT?N?0*i<56}05 zssudO$&7HfL+v$N+dD{|5e-k<3K62nxTrB<)ylo47BHB0NVRD3Vw@tlXO$qCJTWxLPlB_)r_F)U{ICBzs zOR4+MIjyJaFXNTCQhLJ<=AWeOsL~ciRKB-#N24I@!oa^!9I(98LxyiA%XivOHb3+g z#}KdyQ_<2z=8pfAYi5zI&}LxQNWbxIU;U!Qjp9-UD_SKJ7SDfcprUK@OE&H&4!aq2 zxQ$aeMxI{=-d|qV4C;)sV(gpHVj$tc_bhf#>kZ}ACHi=baL1%s9wYeXN_<`7Lvl;p<4A1B6fjde9yKi}UrMcp^%WcM8XA7GfqSklC%Ut%E43<$9wNL@)&!nw z3(=MdQAXK`Wa-dQA63@Zn8mf~Ff^ecw{K8tssvTb& z*JUP4#aY8e%AXE!*|-0!-w98*bAgFx!)rkA=ybr43fndmZXZp$N1nN``NqC|``{*T z!Kbd7#}oPsVo`*HN$!ew<=Dkz_f@N*{5adoxHbFjHc*3ajQ8Pu&sj)@7Pg!i92&Cs zGC1b${Znc))qb+vVR%ByZs)b??fT7K8yPS6|4=rHn#6DIDoXTK8E5nteI@kfZX7(vuW8S^;99-;oIm=JLvf1T^l}bG7rMIP= zp|%VELgHo@)<|DmC^YWD@8y)6#8Dl023oP_FH|!5KS1)(a@VR`;Oc7-5XQYx5^fe8 zKK%dsy7sUpucTkAEod!DOSB5Yin|p>!D=DMb&I8LK}1C&5H3;*u|Nb=F5!|`0Z~+N z7ZFRiNEHMj2^SNT01;5BARy%uAx%Q00ybPiL%;+=zIopu>|&qqFP?`7&U?CDVES5lPU|F(l|F_Mr}ixikGoH*2WFI8vY%|47KLQVn*OU zsG=>eD7Lxjk-9x;x`tJ-;#hSzi_KmiUVJFG>RB!m8$Cn1rJ3g*xsrag^eL&5Ra>jP z;3V#8^Y7}f@o0gPFl@M7$|xL!g+FZ`H|NAor(bZI9wHD3t_*6a4nek5o3EB*8hAh3 z$c0mpR>-b2MHYD`8e@WaJS#YpB9&s5Y1e}UhF&XecN#a0F7u{J1Bt6dS=rd&BhhL5 zRL&vJxWp=X=}We1COm#2m~}*(0Ia?Mm(y^O*xW8kRenZ4m%lvA&mH>mF-T65K>Q_1 z>DsoGu=9`gpEE)Ajzn`OCtr6$FeN`#F?4!>oPS*`xHJ8Dx|9T3etK@PelV{}H!%&P z-;NXc%d0_HL9}X31JBLR;ykz2&hN|+-zvy`9t4JiVvPtO(rf+H0tww&0t0Nz^{i+z>67kWv16YZ9d-HgRZQ#Q>5?`u~PCoqUN&Fwe27bVVp= zz_qc~=LiHTwsE-oHhUpzhVLe&cgIYPctD0F#%!-|wQtc6-f%^u;!k#7`}VpfiO_&v zXaBaU_#^rf!|Jo3I{CH}?d*8P>pK9TO?LVKP;e^W=DUlr36-9XRZ-v;Lqa7H>qRK6 zri=tAl^B6IUqT19Fc%+lHLi(@n%?r8>9tPB*O43)G*dUuD_^C2?LsAF-g&-9TWf2h z{QSF{E(g-VGVTpyjqkl=n{qHBYW^8Kodi8vGx}p=H6VZ_&lRdVm_}@FBW&E>&>mJ5 zc3UE^nkhADj68J;`oTnv#p#L2`Poo@ywnWB%*_z?#$lE!-g`-5&OF5ky!0@ooqk@PQ#{@UmMBny`>9c`m6^3yH!ja+WfVp-%U+`!cOYf)<#djiQrs2RZtLpExmxx zsG2z=#(FI=l#r|T_d);CYu}su;d2L>~6V>=c;kfsVOZ$y4hK0)h%5QoT#?Q;gV!z zIyl473#<+%APhOuspc=QS}Kblh}%4M1QAPgzHFI#|2;T(YSL4|5CG~ zq|nr&@}(7(kp*@?H=SvJe;sO6fEU@Om*ewRGp=!@LOY_?tKP4FC=jG}b7zjh{FFo|BUUSEcS-j0?(r{I}Ip!B|V*v<*W4 zSeOhCC7Tf~sjlY>FakC^U51~mPV&1y7O_>lSh7|-&<~9ggQd4A$c!2r*BF|_?|bt4 zHJ5L7{nn_GKfdf_sDxVVb0Zbrmjx^Jly8~{b(Q9kvvd@Wof|<5JvjeGIbb23bgMMr zpMFZmg_85UtuEIoG$Z}WVMSmXO25HZ6~c!Kq3OG8tt6N04zkAxiEH}mc8p$2PZ9jGa${9Lu_a^-S4w0)A^dr3W zC)S9}-=;78dEI8w>@0Cw>-+)WN;BtUmY|{g7MB!c4m_59bcnv~EL;IT=)$>JM&{f- za&CNd6GR_!IdyJ7-a!;^BV8v#$Z6BT&0bVl$>_v@X`v50wCHiXugwx;Ed4jC19;=a zJZpJ{O8WzM&Z`$kwds=FB3$$_;{!u)E%7Mct`G!AR=oc153@$Nv;gs0^xSMo@dHr& zq^NhtwJ%2$T~_j1B1wSck)^^lQHEy^3=EKU%Kxb?fV)DAN(r%TW5o&WTnua9&ISys zCy)fVDWNacaMU1WcH{;mH9Dtmt5CK3Y&ZIe%{<-NPM0*WcZsA*8}DU=1LB$V`fJ=d ztdil1iz7(gUaKCkB9wP400ZL{kZbU%v!-SlCkF4etX?1f1D`xQ!Kseg_2n^&{d{+& zhYwLY+H(_=5;aZ+pG6>;La@_hK$+#{*?eL9{ZtsT)vzNiJ*LJDLwwzujY-pyPf@3f zV3)LljOe?kNU4zVG?U;N$nkgfGy!*?U#IkYRM5cA5GE%lX9{xGUxp`we_7=aREGR} z-^pq+7;MQpL2T@dcIGO7IM4MAj{GE+z^lxsD$G@kXm!in9AX?( zqqlVm&*P%U#}2|fctCS&6ILN=*r3Q*EC#4SVq@vuu$HO!+6PhncJEe{>(icF0C#}D zy;W9BED~pC^tU45)N$qL&KgW1bCcfe=P!?l_}@E3v-YzM< zNYmu2Wr`%UuQ6hEXVsoIc-OV9k7jC%sN`I*(zucH6=bh8)B??~%Ygonray#hUMr<^ zUlumHva-@jW(i4&z1%(HiZ6D+`-7jg$Xd)FC_Y_1Z^<8`{d~&oiKe5tLwUJmey#tF z3Y&-Oh+_L)y1}PC3pR53POY(vvy;W_K%bMjs~=GBHXp1yJIS*Qn5+aRi_IDc=4Xk(~k zldEsUw3fMfbAV)jjs#2?H*VTRb^IY^fHA)_+6zuDQ;h0=>4Re)8$!@!sNhhk z+5#%c)QHYcy!ZP!jpS;En zpakVHk3Ny1WS%^II*ANEMm_lg(+0aY{T#S#0XHb1`fWgtp81u%!7@p54>+~Lmw~vl zmL8QfWJckZFVTnIx!%X}ME^^gjBiWy3z3;ug;L<$6h+>m%8K#zJ-6pTDhDBJKxP7I z!ikBAE-|h~z@bor+5$&LNB4VePe8(32w}h-AQH`ctmu9lh5Q+U@Eiw`cjgibX#Ct! zG?n;9jZqaW@&bY|W=XymkYOM5D-f4NC`wZ3dyjd-DT+Pt6qzzG1eNcB@P$hYwtknKS>x(YM zwuVf9iVC^)1ATf_Tg*=gJ^`kSg`bQMNCk5L{4R*v(!!GW-EtVrWpPgv=P6H#%C0#HXvqAsX>XA)RjffXCGQ zBRU<4qlUqC_FLXFSwelT|7(LARfbOuStCK?E$ds)4KxCr5i?7g+vQcYg5jeX$|mAD z2vO$x8#%lgX!1Q!8)p5uAV3~}5r z#V$ulvJ>-{YmTg;LiYL@V>)X4{h6VLBBG)`%q68 zxK!8Sw8jdCzm7;;AQ4 zAaPWT!uiqr0g-Q!m|)wSg;+b?|A}8G_lu^cCRYZ2CA`h6EZ%$Uf0*kpjuKp?YKEh# zy5Pk95zWi!axXRhZdqu)u%!VgIl2DuQxS6;?}?vx03OLumG(a!K zm~QOUa_pOK9f28ClYlb%)Ml09DRbEowJ#~CEY%+`_M3V@N^j~pR8rl!qNfN1BO$}W*dZG5#Jc8E_>bH-W%a(PO$we z>A;wH--AZHpbagGfFu{Y_EotdK5+dO@u}`@w|LD8=c7C8L-|=}E?QZ!(L@3Zl7Ndj zgYxt3^>fu>J=Sd7XM?A}-EbY(7;>s7h+D?}N3nhM~;J3Qic^{|^e1T*KzFU!(fJgw%5uJfuu(GUPjH1+f_wl{0a$fqlTi&oR zGIyBKnj72lZ;W-XwQ+O>>6@S2;q6a7nCjr^F!yyphXu?l1rnd5k?}WLE5&RFhVHS) z@bM)J|LyGVa`S+f7Dl_xw;;nrl565;8iB`+u|v0fc<4>pXL$)sxt^W|{7}NBb+}#j zW;B$d3#Xdod8(~1H-Q)U^UcJ1S4OQ)HzE-q<~Xlk=C=A2Ht_1&Bv22w_|_i ztP^9kQZ8>)4A9`!WrMH1wnw(LwH5kcOH5+#=aQiZQ}E&Fv;+|QAU`3#qqg3Iw%*id zzDUvY(iuNKIr_`;#Y*-iY9Wmu{_;AZ3 zM9Dqs(_200q?WJGKOO3~m>fDB7FY7Il$`3)4^v=q#y$~M0G5E&IGA%c!_HuNS3^cuR5gO52$Ndi-S}j7Vi$sCfE;4B|)>#=g z=+4Snr}Sy9B#5}NTHS58QY07EuDt=9b1frhf2FuFBsYiRjio0qkckR(Xzo>;l?Qir zr)(_jwYtyB&)Z*l?oJ-z)j@Lu-Jy=Y?ES&I3eq+CWul5_TBmzD^ElhuBFn_26*+~L7xi^ltm_wBlUWx%y^ z;QFL5k+t{2cm{V{h7K=asXAFq|LP}qo_p@^LR?A_tkaub+W&gU<3W1sp47%Z#G|5P z?rOy++Qm$g5~U|dycpjXz6NbsgrPeQ41>(YauW%$&9fgE{ru!BZ8xgnUGt%i*5>9M z@VZuN_9={?9?h^LyvW|)R4+R~gb#SNUrvw?$0?+45TuEpfMZ;=Z`8@`xJfzZaq)2a zR(UY5r*`Uzy|$YZj;xZmuYss{WaL$s^^DiE!I1OfpTfgzT&d!pKrx!?NoO8Zz-S1S z0XO)zn1hyF9=>n=)R$UuM$hwNIO3}GT;}%dXuCD=eEnf$)s?5VQY*dYX9frjn?KAT zxHCp9%kyBDH8dd4J2BX*yC6lisja*DsL1)^7g~;&`}C5TJ4<$qBAYTY{jK>B->bcA z(ArXqP6#@!mzpq8c78-58RNUa{7osOy9={ZL*)C`%Y3Mx++qb}6og!_xW|exNcQOH zoE(ycq&0=q(O|3|Rb7;gYx+Q$d6OSeT$k%-W+FVcs3Yo%uZGLnw1kR#=KpB5FzO4^ zRfONbh`<^lI&-(s0>cUah5dl>nZ`7RxmT-c@u0JM2lpEN@Z_rw9CaW}4;FJ})M7*x zpQR2pi#$6b&rIIYZ1VGH{Z{-0^UOjB6lFM597$y;tsMFX_; zO(KgBak#}gI^juuyaOl$G$5SMK^#JxY8=;c%<9u2BA;;nc8?bAHUf$b;Wr?0j!tH_ zP%nAl<_=nGxCP)S$Q}6C+pVt25h}-`RFwvhhTJs@(tg?B|2H_E#*3B?I;;FY9GelX|1ulz>c!J2VcYaQng0vDWNP>LvfS26n}_&s1&(1&emjXdJo)70 zqbI4~`qXR=q!Ybwh{q%kR+ZgWozF{F-im H{M`Qm4!i-Y literal 0 HcmV?d00001 From 1d1ce5ac1684fed880389ef67344f27dd55951dc Mon Sep 17 00:00:00 2001 From: sophtsang Date: Fri, 7 Nov 2025 00:00:11 -0500 Subject: [PATCH 13/28] mispelled --- src/occupany_grid.cpp | 166 ------------------------------------------ 1 file changed, 166 deletions(-) delete mode 100644 src/occupany_grid.cpp diff --git a/src/occupany_grid.cpp b/src/occupany_grid.cpp deleted file mode 100644 index 9e4d056..0000000 --- a/src/occupany_grid.cpp +++ /dev/null @@ -1,166 +0,0 @@ -// src/occupancy_grid.cpp -#include -#include -#include -#include -#include -#include -#include -#include "cev_msgs/msg/obstacles.hpp" -#include "obstacle/msg/obstacle_array.hpp" - -#include -#include -#include -#include -#include -#include -#include - -using obstacle::msg::ObstacleArray; - -struct PointXYZCluster { - float x; - float y; - float z; - int32_t cluster_id; -}; - -class OccupancyGrid : public rclcpp::Node { -public: - OccupancyGrid() - : Node("occupancy_grid") - { - obs_sub_ = this->create_subscription( - "/rslidar_obstacles", 10, - std::bind(&OccupancyGrid::obstaclesCallback, this, std::placeholders::_1)); - - pc_sub_ = this->create_subscription( - "input_points", 10, - std::bind(&OccupancyGrid::pcCallback, this, std::placeholders::_1)); - - bev_pub_ = this->create_publisher("bev_obstacles", 10); - - RCLCPP_INFO(this->get_logger(), "OccupancyGrid started - waiting for PointCloud2 on 'input_points'"); - } - -private: - void obstaclesCallback(const cev_msgs::msg::Obstacles::SharedPtr msg) - { - RCLCPP_INFO(this->get_logger(), "Received Obstacles message with %zu clouds", msg->obstacles.size()); - - sensor_msgs::msg::PointCloud2 merged_cloud = msg->obstacles[0]; - - for (size_t i = 1; i < msg->obstacles.size(); ++i) - { - const auto &cloud = msg->obstacles[i]; - - pcl::concatenatePointCloud(merged_cloud, cloud, merged_cloud); - } - - auto cloud_ptr = std::make_shared(merged_cloud); - pcCallback(cloud_ptr); - } - - void pcCallback(const sensor_msgs::msg::PointCloud2::SharedPtr msg) { - // check required fields - bool has_x=false, has_y=false, has_z=false, has_id=false; - for (const auto &f : msg->fields) { - if (f.name == "x") has_x = true; - if (f.name == "y") has_y = true; - if (f.name == "z") has_z = true; - if (f.name == "id" || f.name == "cluster_id") has_id = true; - } - if (!(has_x && has_y && has_z && has_id)) { - RCLCPP_ERROR(this->get_logger(), - "PointCloud2 missing required fields (need x,y,z and id/cluster_id). Skipping this message."); - return; - } - - sensor_msgs::PointCloud2ConstIterator iter_x(*msg, "x"); - sensor_msgs::PointCloud2ConstIterator iter_y(*msg, "y"); - sensor_msgs::PointCloud2ConstIterator iter_z(*msg, "z"); - sensor_msgs::PointCloud2ConstIterator iter_id(*msg, "id"); - - std::unordered_map> clusters; - size_t total_points = 0; - for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z, ++iter_id) { - PointXYZCluster p; - p.x = *iter_x; - p.y = *iter_y; - p.z = *iter_z; - p.cluster_id = *iter_id; - clusters[p.cluster_id].push_back(p); - ++total_points; - } - - // z-axis filtering - const float z_min_allowed = 0.0f; - const float z_max_allowed = 2.5f; - - std::unordered_map> filtered_clusters; - - for (const auto &kv : clusters) { - int cid = kv.first; - const auto &pts = kv.second; - - std::vector kept; - float z_min = std::numeric_limits::max(); - float z_max = std::numeric_limits::lowest(); - - for (const auto &p : pts) { - z_min = std::min(z_min, p.z); - z_max = std::max(z_max, p.z); - if (p.z >= z_min_allowed && p.z <= z_max_allowed) { - kept.push_back(p); - } - } - - if (!kept.empty()) { - filtered_clusters[cid] = kept; - } - - } - - // === BEV projection + OBB === - ObstacleArray out; - out.header = msg->header; - - for (const auto &kv : filtered_clusters) { - int cid = kv.first; - const auto &pts = kv.second; - - if (pts.size() < 3) { - RCLCPP_WARN(this->get_logger(), - "Cluster %d has only %zu points, skipping OBB", - cid, pts.size()); - continue; - } - - std::vector cv_points; - cv_points.reserve(pts.size()); - float z_min = std::numeric_limits::max(); - float z_max = std::numeric_limits::lowest(); - for (const auto &p : pts) { - cv_points.emplace_back(p.x, p.y); - z_min = std::min(z_min, p.z); - z_max = std::max(z_max, p.z); - } - } - - // === publish ObstacleArray === - obs_pub_->publish(out); - } - - rclcpp::Subscription::SharedPtr obs_sub_; - rclcpp::Subscription::SharedPtr pc_sub_; - rclcpp::Publisher::SharedPtr bev_pub_; -}; - -int main(int argc, char ** argv) { - rclcpp::init(argc, argv); - auto node = std::make_shared(); - rclcpp::spin(node); - rclcpp::shutdown(); - return 0; -} From cb3f1e8ab5975517aa2be66608b46cc9a72a28b7 Mon Sep 17 00:00:00 2001 From: sophtsang Date: Fri, 7 Nov 2025 00:05:37 -0500 Subject: [PATCH 14/28] removed unnecessary method --- src/occupancy_grid.cpp | 16 +++------------- 1 file changed, 3 insertions(+), 13 deletions(-) diff --git a/src/occupancy_grid.cpp b/src/occupancy_grid.cpp index 06e5245..83f20de 100644 --- a/src/occupancy_grid.cpp +++ b/src/occupancy_grid.cpp @@ -255,7 +255,7 @@ class OccupancyGridNode : public rclcpp::Node { map_modifier.resize(total_kept_points); - worldScanToMap(filtered_clusters, map_scan); + worldToMap(filtered_clusters, map_scan); Obstacle2OccupancyGrid(bev_points, map_scan, angle_increment); bev_pub_->publish(bev_points); @@ -325,7 +325,7 @@ class OccupancyGridNode : public rclcpp::Node { if (xi < 0 || yi < 0 || xi >= static_cast(grid_msg_.info.width) || yi >= static_cast(grid_msg_.info.height)) - return; // skip out-of-bounds + return; size_t index = yi * grid_msg_.info.width + xi; switch (state) { @@ -364,17 +364,7 @@ class OccupancyGridNode : public rclcpp::Node { } } - // function to convert world (PointCloud2) coordinates to map coordinates - bool worldToMap(float wx, float wy, unsigned int &mx, unsigned int &my) { - mx = static_cast(std::floor(fabs((wx - (grid_msg_.info.origin.position.x)) / grid_msg_.info.resolution))); - my = static_cast(std::floor(fabs((wy - (grid_msg_.info.origin.position.y)) / grid_msg_.info.resolution))); - if (mx < grid_msg_.info.width && my < grid_msg_.info.height) { - return true; - } - return false; - } - - void worldScanToMap(std::unordered_map> &world_scan, sensor_msgs::msg::PointCloud2 &map_scan) { + void worldToMap(std::unordered_map> &world_scan, sensor_msgs::msg::PointCloud2 &map_scan) { sensor_msgs::PointCloud2Iterator mx(map_scan, "x"); sensor_msgs::PointCloud2Iterator my(map_scan, "y"); sensor_msgs::PointCloud2Iterator mz(map_scan, "z"); From 5794fff44e21201106cd5cb8e0da20f44dbb4bce Mon Sep 17 00:00:00 2001 From: sophtsang Date: Sat, 8 Nov 2025 04:58:49 +0000 Subject: [PATCH 15/28] param changes --- src/occupancy_grid.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/occupancy_grid.cpp b/src/occupancy_grid.cpp index 83f20de..3a71c45 100644 --- a/src/occupancy_grid.cpp +++ b/src/occupancy_grid.cpp @@ -134,7 +134,7 @@ class OccupancyGridNode : public rclcpp::Node { max_x += padding; max_y += padding; - float cell_size = 0.2f; + float cell_size = 0.05f; float angle_increment = deg2rad(0.4); // 26 fov has horizontal angle: 0.4° int width = static_cast((max_x - min_x) / cell_size); @@ -286,6 +286,7 @@ class OccupancyGridNode : public rclcpp::Node { { const double angle = atan2(*iter_y, *iter_x); int angle_bin_idx = (angle - min_angle) / angle_increment; + // BinInfo(l2-dist of obstacle point from origin, x, y) obstacle_angle_bins.at(angle_bin_idx) .push_back(BinInfo(std::hypot(*iter_y, *iter_x), *iter_wx, *iter_wy)); } From a65a76c50c3fbecfc2ac22cb491432af6f6a5db0 Mon Sep 17 00:00:00 2001 From: sophtsang Date: Thu, 13 Nov 2025 22:55:02 +0000 Subject: [PATCH 16/28] integrated pcCallback to take in /rslidar_clusters topic of PointCloud2 type --- src/obstacle_node.cpp | 2 +- src/obstacle_tracker.cpp | 272 +++++++++++++++++++++++++++++++++++++++ src/occupancy_grid.cpp | 2 +- 3 files changed, 274 insertions(+), 2 deletions(-) create mode 100644 src/obstacle_tracker.cpp diff --git a/src/obstacle_node.cpp b/src/obstacle_node.cpp index 9ec633a..bc11305 100644 --- a/src/obstacle_node.cpp +++ b/src/obstacle_node.cpp @@ -37,7 +37,7 @@ class ObstacleNode : public rclcpp::Node { std::bind(&ObstacleNode::obstaclesCallback, this, std::placeholders::_1)); pc_sub_ = this->create_subscription( - "input_points", 10, + "/rslidar_clusters", 10, std::bind(&ObstacleNode::pcCallback, this, std::placeholders::_1)); obs_pub_ = this->create_publisher("obstacles", 10); diff --git a/src/obstacle_tracker.cpp b/src/obstacle_tracker.cpp new file mode 100644 index 0000000..9ec633a --- /dev/null +++ b/src/obstacle_tracker.cpp @@ -0,0 +1,272 @@ +// src/obstacle_node.cpp +#include +#include +#include +#include +#include +#include +#include +#include "cev_msgs/msg/obstacles.hpp" +#include "obstacle/msg/obstacle_array.hpp" + +#include +#include +#include +#include +#include +#include +#include + + +using obstacle::msg::ObstacleArray; + +struct PointXYZCluster { + float x; + float y; + float z; + int32_t cluster_id; +}; + +class ObstacleNode : public rclcpp::Node { +public: + ObstacleNode() + : Node("obstacle_node") + { + obs_sub_ = this->create_subscription( + "/rslidar_obstacles", 10, + std::bind(&ObstacleNode::obstaclesCallback, this, std::placeholders::_1)); + + pc_sub_ = this->create_subscription( + "input_points", 10, + std::bind(&ObstacleNode::pcCallback, this, std::placeholders::_1)); + + obs_pub_ = this->create_publisher("obstacles", 10); + marker_pub_ = this->create_publisher("obstacle_markers", 10); + + RCLCPP_INFO(this->get_logger(), "ObstacleNode started - waiting for PointCloud2 on 'input_points'"); + } + +private: + void obstaclesCallback(const cev_msgs::msg::Obstacles::SharedPtr msg) + { + RCLCPP_INFO(this->get_logger(), "Received Obstacles message with %zu clouds", msg->obstacles.size()); + + sensor_msgs::msg::PointCloud2 merged_cloud = msg->obstacles[0]; + + for (size_t i = 1; i < msg->obstacles.size(); ++i) + { + const auto &cloud = msg->obstacles[i]; + + pcl::concatenatePointCloud(merged_cloud, cloud, merged_cloud); + } + + auto cloud_ptr = std::make_shared(merged_cloud); + pcCallback(cloud_ptr); + } + + void pcCallback(const sensor_msgs::msg::PointCloud2::SharedPtr msg) { + // check required fields + bool has_x=false, has_y=false, has_z=false, has_id=false; + for (const auto &f : msg->fields) { + if (f.name == "x") has_x = true; + if (f.name == "y") has_y = true; + if (f.name == "z") has_z = true; + if (f.name == "id" || f.name == "cluster_id") has_id = true; + } + if (!(has_x && has_y && has_z && has_id)) { + RCLCPP_ERROR(this->get_logger(), + "PointCloud2 missing required fields (need x,y,z and id/cluster_id). Skipping this message."); + return; + } + + sensor_msgs::PointCloud2ConstIterator iter_x(*msg, "x"); + sensor_msgs::PointCloud2ConstIterator iter_y(*msg, "y"); + sensor_msgs::PointCloud2ConstIterator iter_z(*msg, "z"); + sensor_msgs::PointCloud2ConstIterator iter_id(*msg, "id"); + + std::unordered_map> clusters; + size_t total_points = 0; + for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z, ++iter_id) { + PointXYZCluster p; + p.x = *iter_x; + p.y = *iter_y; + p.z = *iter_z; + p.cluster_id = *iter_id; + clusters[p.cluster_id].push_back(p); + ++total_points; + } + + // RCLCPP_INFO(this->get_logger(), + // "Received PointCloud2: points=%zu clusters=%zu", + // total_points, clusters.size()); + + // z-axis filtering + const float z_min_allowed = 0.0f; + const float z_max_allowed = 2.5f; + + std::unordered_map> filtered_clusters; + + for (const auto &kv : clusters) { + int cid = kv.first; + const auto &pts = kv.second; + + std::vector kept; + float z_min = std::numeric_limits::max(); + float z_max = std::numeric_limits::lowest(); + + for (const auto &p : pts) { + z_min = std::min(z_min, p.z); + z_max = std::max(z_max, p.z); + if (p.z >= z_min_allowed && p.z <= z_max_allowed) { + kept.push_back(p); + } + } + + if (!kept.empty()) { + filtered_clusters[cid] = kept; + // RCLCPP_INFO(this->get_logger(), + // "Cluster %d kept: %zu points (orig %zu, z_range=[%.2f, %.2f])", + // cid, kept.size(), pts.size(), z_min, z_max); + } + // else { + // RCLCPP_INFO(this->get_logger(), + // "Cluster %d discarded (all points outside z range [%.2f, %.2f], orig z_range=[%.2f, %.2f])", + // cid, z_min_allowed, z_max_allowed, z_min, z_max); + // } + } + + // RCLCPP_INFO(this->get_logger(), + // "After filtering: %zu clusters remain", filtered_clusters.size()); + + // === BEV projection + OBB === + ObstacleArray out; + out.header = msg->header; + + for (const auto &kv : filtered_clusters) { + int cid = kv.first; + const auto &pts = kv.second; + + if (pts.size() < 3) { + RCLCPP_WARN(this->get_logger(), + "Cluster %d has only %zu points, skipping OBB", + cid, pts.size()); + continue; + } + + std::vector cv_points; + cv_points.reserve(pts.size()); + float z_min = std::numeric_limits::max(); + float z_max = std::numeric_limits::lowest(); + for (const auto &p : pts) { + cv_points.emplace_back(p.x, p.y); + z_min = std::min(z_min, p.z); + z_max = std::max(z_max, p.z); + } + + cv::RotatedRect rect = cv::minAreaRect(cv_points); + + float cx = rect.center.x; + float cy = rect.center.y; + float w = rect.size.width; + float h = rect.size.height; + float angle_deg = rect.angle; + float yaw = angle_deg * M_PI / 180.0f; + + // length ≥ width + float length = std::max(w, h); + float width = std::min(w, h); + + // === Obstacle msg === + obstacle::msg::Obstacle ob; + ob.id = cid; + ob.pose.position.x = cx; + ob.pose.position.y = cy; + ob.pose.position.z = 0.0; // z_min + tf2::Quaternion q; + q.setRPY(0, 0, yaw); + ob.pose.orientation.x = q.x(); + ob.pose.orientation.y = q.y(); + ob.pose.orientation.z = q.z(); + ob.pose.orientation.w = q.w(); + + ob.length = length; + ob.width = width; + ob.z_min = z_min; + ob.z_max = z_max; + + // if height <0.1m then not blocking + ob.blocking = (z_max - z_min > 0.1); + + out.obstacles.push_back(ob); + + // RCLCPP_INFO(this->get_logger(), + // "Cluster %d -> obstacle center=(%.2f,%.2f), L=%.2f W=%.2f yaw=%.2f rad", + // cid, cx, cy, length, width, yaw); + } + + // === publish ObstacleArray === + obs_pub_->publish(out); + + visualization_msgs::msg::MarkerArray markers; + int id_counter = 0; + + for (const auto &ob : out.obstacles) { + visualization_msgs::msg::Marker m; + m.header = out.header; + m.header.frame_id = "rslidar"; + m.ns = "obstacle"; + m.id = id_counter++; + m.type = visualization_msgs::msg::Marker::CUBE; + m.action = visualization_msgs::msg::Marker::ADD; + + // centroid + m.pose = ob.pose; + + // size + m.scale.x = ob.length; + m.scale.y = ob.width; + m.scale.z = ob.z_max - ob.z_min; + + // z at the middle of the box + m.pose.position.z = (ob.z_min + ob.z_max) / 2.0; + + // color(convert cluster id to different color) + m.color = getColorFromId(m.id); + + markers.markers.push_back(m); + } + + RCLCPP_INFO(rclcpp::get_logger("MarkerPrinter"), + "Visualizing %d clouds", (int) markers.markers.size()); + + marker_pub_->publish(markers); + + } + + std_msgs::msg::ColorRGBA getColorFromId(int cluster_id) + { + std_msgs::msg::ColorRGBA color; + uint32_t hash = static_cast(cluster_id * 2654435761 % 4294967296); // Knuth's multiplicative hash + color.r = ((hash & 0xFF0000) >> 16) / 255.0f; + color.g = ((hash & 0x00FF00) >> 8) / 255.0f; + color.b = (hash & 0x0000FF) / 255.0f; + color.a = 0.5f; + + return color; + } + + rclcpp::Subscription::SharedPtr obs_sub_; + rclcpp::Subscription::SharedPtr pc_sub_; + rclcpp::Publisher::SharedPtr obs_pub_; + rclcpp::Publisher::SharedPtr marker_pub_; +}; + +#include "visualization_msgs/msg/marker_array.hpp" + +int main(int argc, char ** argv) { + rclcpp::init(argc, argv); + auto node = std::make_shared(); + rclcpp::spin(node); + rclcpp::shutdown(); + return 0; +} diff --git a/src/occupancy_grid.cpp b/src/occupancy_grid.cpp index 3a71c45..c51110e 100644 --- a/src/occupancy_grid.cpp +++ b/src/occupancy_grid.cpp @@ -58,7 +58,7 @@ class OccupancyGridNode : public rclcpp::Node { std::bind(&OccupancyGridNode::obstaclesCallback, this, std::placeholders::_1)); pc_sub_ = this->create_subscription( - "input_points", 10, + "/rslidar_clusters", 10, std::bind(&OccupancyGridNode::pcCallback, this, std::placeholders::_1)); bev_pub_ = this->create_publisher("/bev_obstacles", 10); From 1f9f1cf483ac702234ef8a73669f62c077b131a9 Mon Sep 17 00:00:00 2001 From: sophtsang Date: Thu, 13 Nov 2025 23:52:48 +0000 Subject: [PATCH 17/28] integrated pcCallback to take in /rslidar_clusters topic of PointCloud2 type --- CMakeLists.txt | 27 +++++- src/obstacle_tracker.cpp | 179 ++------------------------------------- 2 files changed, 34 insertions(+), 172 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index aa16036..4e60b4e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -31,6 +31,7 @@ rosidl_generate_interfaces(${PROJECT_NAME} add_executable(obstacle_node src/obstacle_node.cpp) add_executable(occupancy_grid src/occupancy_grid.cpp) +add_executable(obstacle_tracker src/obstacle_tracker.cpp) ament_target_dependencies( obstacle_node @@ -61,6 +62,21 @@ ament_target_dependencies( visualization_msgs ) +ament_target_dependencies( + obstacle_tracker + rclcpp + cev_msgs + sensor_msgs + std_msgs + nav_msgs + pcl_conversions + pcl_ros + geometry_msgs + tf2 + tf2_geometry_msgs + visualization_msgs +) + include_directories( ${PCL_INCLUDE_DIRS} ) @@ -75,17 +91,26 @@ target_link_libraries(occupancy_grid ${PCL_LIBRARIES} ) +target_link_libraries(obstacle_tracker + ${OpenCV_LIBS} + ${PCL_LIBRARIES} +) + ament_export_dependencies(rosidl_default_runtime) rosidl_target_interfaces(obstacle_node ${PROJECT_NAME} "rosidl_typesupport_cpp") - rosidl_target_interfaces(occupancy_grid +rosidl_target_interfaces(occupancy_grid + ${PROJECT_NAME} "rosidl_typesupport_cpp") + +rosidl_target_interfaces(obstacle_tracker ${PROJECT_NAME} "rosidl_typesupport_cpp") install(TARGETS obstacle_node occupancy_grid + obstacle_tracker DESTINATION lib/${PROJECT_NAME}) diff --git a/src/obstacle_tracker.cpp b/src/obstacle_tracker.cpp index 9ec633a..20296e8 100644 --- a/src/obstacle_tracker.cpp +++ b/src/obstacle_tracker.cpp @@ -1,4 +1,4 @@ -// src/obstacle_node.cpp +// src/obstacle_tracker.cpp #include #include #include @@ -27,43 +27,19 @@ struct PointXYZCluster { int32_t cluster_id; }; -class ObstacleNode : public rclcpp::Node { +class ObstacleTracker : public rclcpp::Node { public: - ObstacleNode() - : Node("obstacle_node") + ObstacleTracker() + : Node("obstacle_tracker") { - obs_sub_ = this->create_subscription( - "/rslidar_obstacles", 10, - std::bind(&ObstacleNode::obstaclesCallback, this, std::placeholders::_1)); - pc_sub_ = this->create_subscription( - "input_points", 10, - std::bind(&ObstacleNode::pcCallback, this, std::placeholders::_1)); - - obs_pub_ = this->create_publisher("obstacles", 10); - marker_pub_ = this->create_publisher("obstacle_markers", 10); + "/rslidar_clusters", 10, + std::bind(&ObstacleTracker::pcCallback, this, std::placeholders::_1)); - RCLCPP_INFO(this->get_logger(), "ObstacleNode started - waiting for PointCloud2 on 'input_points'"); + RCLCPP_INFO(this->get_logger(), "ObstacleTracker started - waiting for PointCloud2 on 'input_points'"); } private: - void obstaclesCallback(const cev_msgs::msg::Obstacles::SharedPtr msg) - { - RCLCPP_INFO(this->get_logger(), "Received Obstacles message with %zu clouds", msg->obstacles.size()); - - sensor_msgs::msg::PointCloud2 merged_cloud = msg->obstacles[0]; - - for (size_t i = 1; i < msg->obstacles.size(); ++i) - { - const auto &cloud = msg->obstacles[i]; - - pcl::concatenatePointCloud(merged_cloud, cloud, merged_cloud); - } - - auto cloud_ptr = std::make_shared(merged_cloud); - pcCallback(cloud_ptr); - } - void pcCallback(const sensor_msgs::msg::PointCloud2::SharedPtr msg) { // check required fields bool has_x=false, has_y=false, has_z=false, has_id=false; @@ -96,14 +72,6 @@ class ObstacleNode : public rclcpp::Node { ++total_points; } - // RCLCPP_INFO(this->get_logger(), - // "Received PointCloud2: points=%zu clusters=%zu", - // total_points, clusters.size()); - - // z-axis filtering - const float z_min_allowed = 0.0f; - const float z_max_allowed = 2.5f; - std::unordered_map> filtered_clusters; for (const auto &kv : clusters) { @@ -124,148 +92,17 @@ class ObstacleNode : public rclcpp::Node { if (!kept.empty()) { filtered_clusters[cid] = kept; - // RCLCPP_INFO(this->get_logger(), - // "Cluster %d kept: %zu points (orig %zu, z_range=[%.2f, %.2f])", - // cid, kept.size(), pts.size(), z_min, z_max); } - // else { - // RCLCPP_INFO(this->get_logger(), - // "Cluster %d discarded (all points outside z range [%.2f, %.2f], orig z_range=[%.2f, %.2f])", - // cid, z_min_allowed, z_max_allowed, z_min, z_max); - // } } - // RCLCPP_INFO(this->get_logger(), - // "After filtering: %zu clusters remain", filtered_clusters.size()); - - // === BEV projection + OBB === - ObstacleArray out; - out.header = msg->header; - - for (const auto &kv : filtered_clusters) { - int cid = kv.first; - const auto &pts = kv.second; - - if (pts.size() < 3) { - RCLCPP_WARN(this->get_logger(), - "Cluster %d has only %zu points, skipping OBB", - cid, pts.size()); - continue; - } - - std::vector cv_points; - cv_points.reserve(pts.size()); - float z_min = std::numeric_limits::max(); - float z_max = std::numeric_limits::lowest(); - for (const auto &p : pts) { - cv_points.emplace_back(p.x, p.y); - z_min = std::min(z_min, p.z); - z_max = std::max(z_max, p.z); - } - - cv::RotatedRect rect = cv::minAreaRect(cv_points); - - float cx = rect.center.x; - float cy = rect.center.y; - float w = rect.size.width; - float h = rect.size.height; - float angle_deg = rect.angle; - float yaw = angle_deg * M_PI / 180.0f; - - // length ≥ width - float length = std::max(w, h); - float width = std::min(w, h); - - // === Obstacle msg === - obstacle::msg::Obstacle ob; - ob.id = cid; - ob.pose.position.x = cx; - ob.pose.position.y = cy; - ob.pose.position.z = 0.0; // z_min - tf2::Quaternion q; - q.setRPY(0, 0, yaw); - ob.pose.orientation.x = q.x(); - ob.pose.orientation.y = q.y(); - ob.pose.orientation.z = q.z(); - ob.pose.orientation.w = q.w(); - - ob.length = length; - ob.width = width; - ob.z_min = z_min; - ob.z_max = z_max; - - // if height <0.1m then not blocking - ob.blocking = (z_max - z_min > 0.1); - - out.obstacles.push_back(ob); - - // RCLCPP_INFO(this->get_logger(), - // "Cluster %d -> obstacle center=(%.2f,%.2f), L=%.2f W=%.2f yaw=%.2f rad", - // cid, cx, cy, length, width, yaw); - } - - // === publish ObstacleArray === - obs_pub_->publish(out); - - visualization_msgs::msg::MarkerArray markers; - int id_counter = 0; - - for (const auto &ob : out.obstacles) { - visualization_msgs::msg::Marker m; - m.header = out.header; - m.header.frame_id = "rslidar"; - m.ns = "obstacle"; - m.id = id_counter++; - m.type = visualization_msgs::msg::Marker::CUBE; - m.action = visualization_msgs::msg::Marker::ADD; - - // centroid - m.pose = ob.pose; - - // size - m.scale.x = ob.length; - m.scale.y = ob.width; - m.scale.z = ob.z_max - ob.z_min; - - // z at the middle of the box - m.pose.position.z = (ob.z_min + ob.z_max) / 2.0; - - // color(convert cluster id to different color) - m.color = getColorFromId(m.id); - - markers.markers.push_back(m); - } - - RCLCPP_INFO(rclcpp::get_logger("MarkerPrinter"), - "Visualizing %d clouds", (int) markers.markers.size()); - - marker_pub_->publish(markers); - } - std_msgs::msg::ColorRGBA getColorFromId(int cluster_id) - { - std_msgs::msg::ColorRGBA color; - uint32_t hash = static_cast(cluster_id * 2654435761 % 4294967296); // Knuth's multiplicative hash - color.r = ((hash & 0xFF0000) >> 16) / 255.0f; - color.g = ((hash & 0x00FF00) >> 8) / 255.0f; - color.b = (hash & 0x0000FF) / 255.0f; - color.a = 0.5f; - - return color; - } - - rclcpp::Subscription::SharedPtr obs_sub_; rclcpp::Subscription::SharedPtr pc_sub_; - rclcpp::Publisher::SharedPtr obs_pub_; - rclcpp::Publisher::SharedPtr marker_pub_; }; -#include "visualization_msgs/msg/marker_array.hpp" - int main(int argc, char ** argv) { rclcpp::init(argc, argv); - auto node = std::make_shared(); + auto node = std::make_shared(); rclcpp::spin(node); rclcpp::shutdown(); return 0; From d6df87f300a7869d6e8174ca272dfb10b4ddaf93 Mon Sep 17 00:00:00 2001 From: sophtsang Date: Thu, 13 Nov 2025 23:53:45 +0000 Subject: [PATCH 18/28] method signatures for MHT and icp-based bipartite matching --- README.md | 4 ++- src/obstacle_tracker.cpp | 75 ++++++++++++++++++++++++++-------------- 2 files changed, 52 insertions(+), 27 deletions(-) diff --git a/README.md b/README.md index 17969df..c4d32c6 100644 --- a/README.md +++ b/README.md @@ -7,4 +7,6 @@ Hi all, I'm going to start yapping again! ![Occupancy Grid 2](demos/occupancygrid.png) # Important Links -[Rasterize a point cloud](https://r-lidar.github.io/lasR/reference/rasterize.html) \ No newline at end of file +[Rasterize a point cloud](https://r-lidar.github.io/lasR/reference/rasterize.html) + +[Dynamic Obstacle Detection and Tracking Based on 3D Lidar](https://www.jstage.jst.go.jp/article/jaciii/22/5/22_602/_pdf) \ No newline at end of file diff --git a/src/obstacle_tracker.cpp b/src/obstacle_tracker.cpp index 20296e8..78cca1c 100644 --- a/src/obstacle_tracker.cpp +++ b/src/obstacle_tracker.cpp @@ -32,10 +32,13 @@ class ObstacleTracker : public rclcpp::Node { ObstacleTracker() : Node("obstacle_tracker") { + // nearest neighbor association method -> MHT pc_sub_ = this->create_subscription( "/rslidar_clusters", 10, std::bind(&ObstacleTracker::pcCallback, this, std::placeholders::_1)); + // maybe implement joint probability data association (JPDA) also for clustering + RCLCPP_INFO(this->get_logger(), "ObstacleTracker started - waiting for PointCloud2 on 'input_points'"); } @@ -60,43 +63,63 @@ class ObstacleTracker : public rclcpp::Node { sensor_msgs::PointCloud2ConstIterator iter_z(*msg, "z"); sensor_msgs::PointCloud2ConstIterator iter_id(*msg, "id"); - std::unordered_map> clusters; + // get transformation matrix from 3d icp between *msg and *msg_prev_; + + std::unordered_map> C; size_t total_points = 0; for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z, ++iter_id) { - PointXYZCluster p; - p.x = *iter_x; - p.y = *iter_y; - p.z = *iter_z; - p.cluster_id = *iter_id; - clusters[p.cluster_id].push_back(p); + PointXYZCluster c; + c.x = *iter_x; + c.y = *iter_y; + c.z = *iter_z; + c.cluster_id = *iter_id; + C[c.cluster_id].push_back(c); ++total_points; } - std::unordered_map> filtered_clusters; - - for (const auto &kv : clusters) { - int cid = kv.first; - const auto &pts = kv.second; + // after all the cluster matching and whatever is done, update C_prev + // we can also use this to determine static v. dynamic obstacles - std::vector kept; - float z_min = std::numeric_limits::max(); - float z_max = std::numeric_limits::lowest(); + msg_prev_ = msg; + C_prev_ = C; + } - for (const auto &p : pts) { - z_min = std::min(z_min, p.z); - z_max = std::max(z_max, p.z); - if (p.z >= z_min_allowed && p.z <= z_max_allowed) { - kept.push_back(p); - } - } + void multi_hypothesis_tracking(std::unordered_map> C_prev, + std::unordered_map> C) { + // takes in ??? vector or the entire point cloud idrk + // tbh for both MHT and max bipartite matching, might need to consider all + // possible matches + // or like icp_cost_bipartite_matching is a way to generate all possible + // association hypothesis -> run SHT -> reduce number of hypotheses + } - if (!kept.empty()) { - filtered_clusters[cid] = kept; - } - } + void icp_cost_bipartite_matching(std::unordered_map> C_prev, + std::unordered_map> C, + double cost_threshold) { + // a way to implement MHT for clusters + + // matching on a bipartite graph where red vertices correspond to previous + // clusters at timestamp t-1 and black vertices correspond to current + // clusters at timestamp t + // we construct a fully connected (WLOG, each red vertex connected to all + // black vertices) bipartite graph where the weight of edge connecting each + // red-black vertex pair is defined by the quantitative ICP overlaying cost + // thing between the two clusters (maybe like determined by the returned + // transformation matrix [R | t]) + // somehow think about this? + // unmatched black (t) vertices are maybe categorized as new obstacles? + // unique id for clusters so we can do more long term obstacle tracking for + // the same cluster + + // complexity reduction / pruning: + // there should be a cost_threshold -> don't even create an edge if + // weight < cost_threshold + // cost func should consider diff in shape, position, orientation, # points -> ICP } + sensor_msgs::msg::PointCloud2::SharedPtr msg_prev_; + std::unordered_map> C_prev_; rclcpp::Subscription::SharedPtr pc_sub_; }; From a6cb1b2ce25d354c80d9c949cc98eecc564f06ad Mon Sep 17 00:00:00 2001 From: sophtsang Date: Tue, 18 Nov 2025 05:37:15 +0000 Subject: [PATCH 19/28] initialize bipartite graph --- CMakeLists.txt | 7 ++- lib/cev_icp | 1 + src/obstacle_tracker.cpp | 101 +++++++++++++++++++++++++++++++++++++-- 3 files changed, 104 insertions(+), 5 deletions(-) create mode 160000 lib/cev_icp diff --git a/CMakeLists.txt b/CMakeLists.txt index 4e60b4e..45999df 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -22,7 +22,6 @@ find_package(tf2 REQUIRED) find_package(tf2_geometry_msgs REQUIRED) find_package(visualization_msgs REQUIRED) - rosidl_generate_interfaces(${PROJECT_NAME} "msg/Obstacle.msg" "msg/ObstacleArray.msg" @@ -77,6 +76,11 @@ ament_target_dependencies( visualization_msgs ) +set(CEV_ICP_INCLUDE lib/cev_icp/include) +set(CEV_ICP_LIB lib/cev_icp/lib) + +include_directories(${CEV_ICP_INCLUDE}) +link_directories(${CEV_ICP_LIB}) include_directories( ${PCL_INCLUDE_DIRS} ) @@ -94,6 +98,7 @@ target_link_libraries(occupancy_grid target_link_libraries(obstacle_tracker ${OpenCV_LIBS} ${PCL_LIBRARIES} + cevicp ) ament_export_dependencies(rosidl_default_runtime) diff --git a/lib/cev_icp b/lib/cev_icp new file mode 160000 index 0000000..2e12d9e --- /dev/null +++ b/lib/cev_icp @@ -0,0 +1 @@ +Subproject commit 2e12d9e0fcc0d4611cb60e93030ddf49174a1b6a diff --git a/src/obstacle_tracker.cpp b/src/obstacle_tracker.cpp index 78cca1c..f776650 100644 --- a/src/obstacle_tracker.cpp +++ b/src/obstacle_tracker.cpp @@ -8,7 +8,11 @@ #include #include "cev_msgs/msg/obstacles.hpp" #include "obstacle/msg/obstacle_array.hpp" +#include "icp/icp.h" +#include "icp/geo.h" +#include "icp/driver.h" +#include #include #include #include @@ -17,7 +21,6 @@ #include #include - using obstacle::msg::ObstacleArray; struct PointXYZCluster { @@ -27,6 +30,11 @@ struct PointXYZCluster { int32_t cluster_id; }; +struct Edge { + std::tuple edge; + float weight; +}; + class ObstacleTracker : public rclcpp::Node { public: ObstacleTracker() @@ -37,6 +45,10 @@ class ObstacleTracker : public rclcpp::Node { "/rslidar_clusters", 10, std::bind(&ObstacleTracker::pcCallback, this, std::placeholders::_1)); + obs_sub_ = this->create_subscription( + "/rslidar_obstacles", 10, + std::bind(&ObstacleTracker::obsCallback, this, std::placeholders::_1)); + // maybe implement joint probability data association (JPDA) also for clustering RCLCPP_INFO(this->get_logger(), "ObstacleTracker started - waiting for PointCloud2 on 'input_points'"); @@ -77,6 +89,7 @@ class ObstacleTracker : public rclcpp::Node { ++total_points; } + // RCLCPP_INFO(this->get_logger(), "C_prev count: %d v. C_curr count: %d", C_prev_.size(), C.size()); // after all the cluster matching and whatever is done, update C_prev // we can also use this to determine static v. dynamic obstacles @@ -84,6 +97,65 @@ class ObstacleTracker : public rclcpp::Node { C_prev_ = C; } + icp::PointCloud pc_to_icp_pc(sensor_msgs::msg::PointCloud2 c) { + sensor_msgs::PointCloud2ConstIterator iter_x(c, "x"); + sensor_msgs::PointCloud2ConstIterator iter_y(c, "y"); + sensor_msgs::PointCloud2ConstIterator iter_z(c, "z"); + + icp::PointCloud eigen_c(3, c.width * c.height); + + for (size_t i = 0; iter_x != iter_x.end(); ++i, ++iter_x, ++iter_y, ++iter_z) { + eigen_c(0, i) = *iter_x; + eigen_c(1, i) = *iter_y; + eigen_c(2, i) = *iter_z; + } + + return eigen_c; + } + + void obsCallback(const cev_msgs::msg::Obstacles::SharedPtr msg) { + // initialize the bipartite graph + std::vector C_PREV = obs_msg_prev_; + std::vector C_CURR = msg->obstacles; + // or maybe a mapping from (c_prev, c) -> edge weight, we'll see + std::vector E; + + // bipartite graph construction: + // C_PREV (t-1), C_CURR (t): sets of clusters at time t-1 and t, C_PREV \intersect C_CURR = \emptyset + // E: set of edges with elements (c_prev, c) s.t. c_prev \in C_PREV and c \in C_CURR + // set cluster_ids of c \in C_CURR to be the bipartite matched cluster_ids of c_prev \in C_PREV: + // i.e. if (c_prev, c) is a match in max bipartite match, then set cluster_id of c_prev to be cluster_id of c + for (int i = 0; i < C_CURR.size(); ++i) { + sensor_msgs::msg::PointCloud2 c = C_CURR[i]; + icp::PointCloud icp_c = pc_to_icp_pc(c); + + for (int j = 0; j < C_PREV.size(); ++j) + { + sensor_msgs::msg::PointCloud2 c_prev = C_PREV[j]; + icp::PointCloud icp_c_prev = pc_to_icp_pc(c_prev); + + std::unique_ptr icp = icp::ICP3::from_method("vanilla", icp::Config()).value(); + icp::ICPDriver driver(std::move(icp)); + + driver.set_max_iterations(1); + driver.set_transform_tolerance(0.1 * M_PI / 180, 0.1); + auto result = driver.converge(icp_c_prev, icp_c, icp::RBTransform3::Identity()); + + // check whether translation between the two clusters are within max_radius (which we can define dynamically by past cluster's velocity) + std::cout << "Translation: " << result.transform.translation() << "\n"; + std::cout << "Cost: " << result.cost << "\n"; + + Edge edge; + edge.edge = std::make_tuple(j, i); + edge.weight = result.cost; + + E.push_back(edge); + } + } + + obs_msg_prev_ = msg->obstacles; + } + void multi_hypothesis_tracking(std::unordered_map> C_prev, std::unordered_map> C) { // takes in ??? vector or the entire point cloud idrk @@ -91,11 +163,21 @@ class ObstacleTracker : public rclcpp::Node { // possible matches // or like icp_cost_bipartite_matching is a way to generate all possible // association hypothesis -> run SHT -> reduce number of hypotheses + + // cases for matching clusters: + // 1) old obstacle being tracked gradually / suddenly disappear + // -> there are no obstacles associated w/ the current frame + // -> no cluster in C that matches old obstacle in C_prev_: {T_jN} + // 2) new obstacle suddenly / gradually enters the LiDAR range + // -> previous frame is not associated with the obstacle + // -> no cluster in C_prev_ that matches new obstacle in C: {Z_jN} + // 3) obstacle in current frame is assocaited with previously tracked obstacle + // -> denote as {Y(T_j, Z_j)} } - void icp_cost_bipartite_matching(std::unordered_map> C_prev, - std::unordered_map> C, - double cost_threshold) { + void max_bipartite_matching(std::vector C_PREV, + std::vector C_CURR, + std::vector E) { // a way to implement MHT for clusters // matching on a bipartite graph where red vertices correspond to previous @@ -116,10 +198,21 @@ class ObstacleTracker : public rclcpp::Node { // weight < cost_threshold // cost func should consider diff in shape, position, orientation, # points -> ICP + // problems: we have non-integral bipartite graph. + // multiplicative auction algo for (1-e)-approximation of max bipartite: + // one-sided vertex deletion (delete c_prev given corr obstacle left the frame) + // other-sided vertex insertion (insert c given corr new obstacle appear in frame) + // could scale up the edge weights by 10^6 to get integer weights -> run the algo + + // allow unmatched bidders: can assign matches s.t. (c_prev, null): c_prev's + // obstacle disappeared + // or (null, c): c's obstacle newly appeared in frame } sensor_msgs::msg::PointCloud2::SharedPtr msg_prev_; + std::vector obs_msg_prev_; std::unordered_map> C_prev_; + rclcpp::Subscription::SharedPtr obs_sub_; rclcpp::Subscription::SharedPtr pc_sub_; }; From a70dce97076c099b1560c8a06112893a4b5b1a61 Mon Sep 17 00:00:00 2001 From: sophtsang Date: Tue, 18 Nov 2025 23:15:54 +0000 Subject: [PATCH 20/28] some changes --- README.md | 9 +++++++++ src/obstacle_tracker.cpp | 2 ++ 2 files changed, 11 insertions(+) diff --git a/README.md b/README.md index c4d32c6..52197e9 100644 --- a/README.md +++ b/README.md @@ -6,6 +6,15 @@ Hi all, I'm going to start yapping again! ![Occupancy Grid 1](demos/occ.png) ![Occupancy Grid 2](demos/occupancygrid.png) +## Multi-Hypothesis Tracking +``` +cd Obstacle_node +git submodule add https://github.com/cornellev/icp.git lib/cev_icp +git submodule update --init --recursive +cd lib/cev_icp +sudo make install LIB_INSTALL=/usr/local/lib HEADER_INSTALL=/usr/local/include +``` + # Important Links [Rasterize a point cloud](https://r-lidar.github.io/lasR/reference/rasterize.html) diff --git a/src/obstacle_tracker.cpp b/src/obstacle_tracker.cpp index f776650..c5c1c3e 100644 --- a/src/obstacle_tracker.cpp +++ b/src/obstacle_tracker.cpp @@ -207,6 +207,8 @@ class ObstacleTracker : public rclcpp::Node { // allow unmatched bidders: can assign matches s.t. (c_prev, null): c_prev's // obstacle disappeared // or (null, c): c's obstacle newly appeared in frame + // WLOG: if there are no c_prev's remaining or if all remaining c_prev's have cost > threshold + // then (null, c) } sensor_msgs::msg::PointCloud2::SharedPtr msg_prev_; From d96caf5182d2a5a5ac53f211894ca01b2205fefd Mon Sep 17 00:00:00 2001 From: sophtsang Date: Tue, 18 Nov 2025 23:39:18 +0000 Subject: [PATCH 21/28] modifications to icp in overlay --- overlay/vanilla_3d.cpp | 112 +++++++++++++++++++++++++++++++++++++++++ overlay/vanilla_3d.h | 38 ++++++++++++++ 2 files changed, 150 insertions(+) create mode 100644 overlay/vanilla_3d.cpp create mode 100644 overlay/vanilla_3d.h diff --git a/overlay/vanilla_3d.cpp b/overlay/vanilla_3d.cpp new file mode 100644 index 0000000..5596412 --- /dev/null +++ b/overlay/vanilla_3d.cpp @@ -0,0 +1,112 @@ +/** + * @copyright Copyright (C) 2025 Cornell Electric Vehicles. + * SPDX-License-Identifier: MIT + */ + +#include +#include +#include +#include +#include +#include +#include +#include + +#include "icp/impl/vanilla_3d.h" +#include "algo/kdtree.h" +#include "icp/geo.h" + + +namespace icp { + Vanilla3d::Vanilla3d([[maybe_unused]] const Config& config) + : c(3, 0), current_cost_(std::numeric_limits::max()) {} + Vanilla3d::Vanilla3d(): c(3, 0), current_cost_(std::numeric_limits::max()) {} + Vanilla3d::~Vanilla3d() = default; + + // Euclidean distance between two points + double Vanilla3d::dist(const Eigen::Vector3d& pta, const Eigen::Vector3d& ptb) { + return (pta - ptb).norm(); + } + + double Vanilla3d::calculate_cost() const { + return current_cost_; + } + + Neighbors Vanilla3d::nearest_neighbor(const PointCloud& src) { + Neighbors neigh; + neigh.distances.resize(src.cols()); + neigh.indices.resize(src.cols()); + + for (Eigen::Index i = 0; i < src.cols(); ++i) { + const Eigen::Vector3d query = src.col(i); + double min_dist = 0.0; + int idx = kdtree_->search(query, &min_dist); + + neigh.indices[i] = idx; + neigh.distances[i] = std::sqrt(min_dist); + } + + return neigh; + } + + Vanilla3d::RBTransform Vanilla3d::best_fit_transform(const PointCloud& A, const PointCloud& B) { + Vector centroid_A = get_centroid(A); + Vector centroid_B = get_centroid(B); + + Eigen::Matrix3d N = (A.colwise() - centroid_A) * (B.colwise() - centroid_B).transpose(); + + Eigen::JacobiSVD svd(N, Eigen::ComputeFullU | Eigen::ComputeFullV); + Eigen::Matrix3d R = svd.matrixV() * svd.matrixU().transpose(); + + if (R.determinant() < 0) { + Eigen::Matrix3d V = svd.matrixV(); + V.col(2) *= -1; + R = V * svd.matrixU().transpose(); + } + + Vector t = centroid_B - R * centroid_A; + + RBTransform transform; + transform.linear() = R; + transform.translation() = t; + + return transform; + } + + void Vanilla3d::setup() { + c = a; + current_cost_ = std::numeric_limits::max(); + + std::vector dst_vec(b.cols()); + for (Eigen::Index i = 0; i < b.cols(); ++i) { + dst_vec[i] = b.col(i); + } + + kdtree_ = std::make_unique>(dst_vec, 3); + } + + void Vanilla3d::iterate() { + // Reorder target point set based on nearest neighbor + Neighbors neighbor = nearest_neighbor(c); + PointCloud dst_reordered(3, a.cols()); // Assuming PointCloud is a 3xN matrix + for (Eigen::Index i = 0; i < a.cols(); i++) { + dst_reordered.col(i) = b.col(neighbor.indices[i]); + } + RBTransform T = best_fit_transform(c, dst_reordered); + c = T * c; + + transform = T * transform; + + calculate_cost(neighbor.distances); + } + + void Vanilla3d::calculate_cost(const std::vector& distances) { + if (distances.empty()) { + current_cost_ = std::numeric_limits::max(); + return; + } + + double sum = std::accumulate(distances.begin(), distances.end(), 0.0); + current_cost_ = sum / static_cast(distances.size()); + } +} diff --git a/overlay/vanilla_3d.h b/overlay/vanilla_3d.h new file mode 100644 index 0000000..0f11cb2 --- /dev/null +++ b/overlay/vanilla_3d.h @@ -0,0 +1,38 @@ +/** + * @copyright Copyright (C) 2025 Cornell Electric Vehicles. + * SPDX-License-Identifier: MIT + */ +#pragma once + +#include +#include +#include "icp/icp.h" +#include "icp/config.h" +#include "algo/kdtree.h" + +namespace icp { + + class Vanilla3d final : public ICP3 { + public: + Vanilla3d(const Config& config); + Vanilla3d(); + ~Vanilla3d() override; + + protected: + void setup() override; + void iterate() override; + double calculate_cost() const override; + + private: + PointCloud c; + std::unique_ptr> target_kdtree_; + double current_cost_; + std::unique_ptr> kdtree_; + + Neighbors nearest_neighbor(const PointCloud& src); + static double dist(const Eigen::Vector3d& pta, const Eigen::Vector3d& ptb); + static RBTransform best_fit_transform(const PointCloud& A, const PointCloud& B); + void calculate_cost(const std::vector& distances); + }; + +} // namespace icp \ No newline at end of file From fc8369c7d11191377c6054dcd48a0abd295a307b Mon Sep 17 00:00:00 2001 From: sophtsang Date: Wed, 19 Nov 2025 00:34:34 +0000 Subject: [PATCH 22/28] another overlay --- overlay/icp.h | 180 ++++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 180 insertions(+) create mode 100644 overlay/icp.h diff --git a/overlay/icp.h b/overlay/icp.h new file mode 100644 index 0000000..5b79e1e --- /dev/null +++ b/overlay/icp.h @@ -0,0 +1,180 @@ +/** + * @author Ethan Uppal + * @copyright Copyright (C) 2024 Ethan Uppal. + * Copyright (C) 2025 Cornell Electric Vehicles. + * SPDX-License-Identifier: MIT + */ + +#pragma once + +#include +#include +#include +#include +#include + +#include "geo.h" +#include "config.h" + +namespace icp { + + /** + * Interface for iterative closest points. + * Generally, you should interact with ICP instances through this interface or `ICPDriver`, + * though interacting with implementations directly isn't explicitly disallowed. + * Read \ref write_icp_instance for additional information. + * + * \par Example + * @code + * // Construct a new vanilla ICP instance. + * std::unique_ptr icp = icp::ICP::from_method("vanilla"); + * @endcode + * + * \par Usage + * Let `a` and `b` be two point clouds of type `std::vector`. + * Then, given an ICP instance `icp` of type `std::unique_ptr`, + * perform the following steps. + * + * 1. Call `icp->begin(a, b, initial_guess)`. + * 2. Repeatedly call `icp->iterate()` until convergence. `ICPDriver` can also be used to + * specify convergence conditions. + * + * If these steps are not followed as described here, the behavior is + * undefined. + * + * At any point in the process, you may query `icp->calculate_cost()` and + * `icp->transform()`. Do note, however, that `icp->calculate_cost()` is not + * a constant-time operation. + */ + template + class ICP { + private: + using MethodConstructor = std::function>(const Config&)>; + static std::unordered_map methods; + + protected: + using Vector = icp::Vector; + using RBTransform = icp::RBTransform; + using PointCloud = icp::PointCloud; + + /** A matching between `point` and `pair` at (arbitrary) cost `cost`. */ + struct Match { + /** An index into the source point cloud. */ + Eigen::Index point; + + /** An index into the destination point cloud. */ + Eigen::Index pair; + + /** The (arbitrary) cost of the pair. */ + double cost; + }; + + /** The current point cloud transformation that is being optimized. */ + RBTransform transform = RBTransform::Identity(); + + /** The source point cloud. */ + PointCloud a; + + /** The destination point cloud. */ + PointCloud b; + + /** The pairing of each point in `a` to its closest in `b`. */ + std::vector matches; + + ICP(): a(Dim, 0), b(Dim, 0) {} + + /** + * @brief Per-method setup code. + * + * @post For implementers: must fill `matches` with match data for the initial point + * clouds. + */ + virtual void setup() = 0; + + public: + static std::optional>> from_method(const std::string& name, + const Config& config) { + if (methods.find(name) == methods.end()) { + return {}; + } + + return methods[name](config); + } + + static bool is_method_registered(const std::string& name) { + return methods.find(name) != methods.end(); + } + + static std::vector registered_methods() { + std::vector keys; + for (auto it = methods.begin(); it != methods.end(); ++it) { + keys.push_back(it->first); + } + return keys; + } + + virtual ~ICP() = default; + + /** Begins the ICP process for point clouds `source` and `target` with an initial + * guess for the transform `guess`.*/ + void begin(const PointCloud& source, const PointCloud& target, const RBTransform& guess) { + // Initial transform guess + this->transform = guess; + + // Copy in point clouds + this->a = source; + this->b = target; + + // Ensure arrays are the right size + matches.resize(this->a.cols()); + + // Per-instance customization routine + setup(); + } + + /** Perform one iteration of ICP for the point clouds `a` and `b` + * provided with ICP::begin. + * + * @pre ICP::begin must have been invoked. + * @post For implementers: must fill `matches` with newest match data. + */ + virtual void iterate() = 0; + + /** + * Computes the cost of the current transformation. + * + * \par Efficiency: + * `O(a.size())` where `a` is the source point cloud. + */ + [[nodiscard]] virtual double calculate_cost() const { + double sum_squares = 0.0; + for (auto& match: matches) { + sum_squares += match.cost; + } + return std::sqrt(sum_squares / a.cols()); + } + + /** The current transform. */ + [[nodiscard]] RBTransform current_transform() const { + return transform; + } + + /** + * @brief Gets the current point matching computed by ICP. + * + * @return A reference to the matching. Invalidates if `begin` or `iterate` are called. + */ + [[nodiscard]] const std::vector& get_matches() const { + return matches; + } + }; + + using ICP2 = ICP; + using ICP3 = ICP; + + template<> + std::unordered_map ICP2::methods; + + template<> + std::unordered_map ICP3::methods; +} From 87bf6c7f06548a4c57bef315be4f3d31d1a62946 Mon Sep 17 00:00:00 2001 From: sophtsang Date: Fri, 21 Nov 2025 04:54:06 +0000 Subject: [PATCH 23/28] probably need to parallelize weighting each edge with icp --- src/obstacle_tracker.cpp | 88 ++++++++++++++++++++++++++++++++++++---- 1 file changed, 81 insertions(+), 7 deletions(-) diff --git a/src/obstacle_tracker.cpp b/src/obstacle_tracker.cpp index c5c1c3e..c88fc39 100644 --- a/src/obstacle_tracker.cpp +++ b/src/obstacle_tracker.cpp @@ -89,7 +89,7 @@ class ObstacleTracker : public rclcpp::Node { ++total_points; } - // RCLCPP_INFO(this->get_logger(), "C_prev count: %d v. C_curr count: %d", C_prev_.size(), C.size()); + RCLCPP_INFO(this->get_logger(), "C_prev count: %d v. C_curr count: %d", C_prev_.size(), C.size()); // after all the cluster matching and whatever is done, update C_prev // we can also use this to determine static v. dynamic obstacles @@ -118,13 +118,18 @@ class ObstacleTracker : public rclcpp::Node { std::vector C_PREV = obs_msg_prev_; std::vector C_CURR = msg->obstacles; // or maybe a mapping from (c_prev, c) -> edge weight, we'll see + // hungarian algorithm takes in cost (adjacency) matrix where C_CURR is row + // C_PREV is col std::vector E; + // std::vector> C(C_CURR.size(), std::vector(C_PREV.size(), 0.0)); + Eigen::MatrixXf cost_matrix(C_CURR.size(), C_PREV.size()); // bipartite graph construction: // C_PREV (t-1), C_CURR (t): sets of clusters at time t-1 and t, C_PREV \intersect C_CURR = \emptyset // E: set of edges with elements (c_prev, c) s.t. c_prev \in C_PREV and c \in C_CURR // set cluster_ids of c \in C_CURR to be the bipartite matched cluster_ids of c_prev \in C_PREV: // i.e. if (c_prev, c) is a match in max bipartite match, then set cluster_id of c_prev to be cluster_id of c + float max_cost = 0.0; for (int i = 0; i < C_CURR.size(); ++i) { sensor_msgs::msg::PointCloud2 c = C_CURR[i]; icp::PointCloud icp_c = pc_to_icp_pc(c); @@ -141,18 +146,22 @@ class ObstacleTracker : public rclcpp::Node { driver.set_transform_tolerance(0.1 * M_PI / 180, 0.1); auto result = driver.converge(icp_c_prev, icp_c, icp::RBTransform3::Identity()); - // check whether translation between the two clusters are within max_radius (which we can define dynamically by past cluster's velocity) - std::cout << "Translation: " << result.transform.translation() << "\n"; - std::cout << "Cost: " << result.cost << "\n"; + if (result.cost > max_cost) max_cost = result.cost; + // check whether translation between the two clusters are within max_radius (which we can define dynamically by past cluster's velocity) Edge edge; edge.edge = std::make_tuple(j, i); edge.weight = result.cost; E.push_back(edge); + // C[i][j] = result.cost; + cost_matrix(i, j) = result.cost; } } + // hungarian_assignment(cost_matrix, max_cost); + // if (mat.size() <= mat[0].size()) std::vector assignments = hungarian_assignment(C, max_cost); + RCLCPP_INFO(this->get_logger(), "done"); obs_msg_prev_ = msg->obstacles; } @@ -175,9 +184,12 @@ class ObstacleTracker : public rclcpp::Node { // -> denote as {Y(T_j, Z_j)} } - void max_bipartite_matching(std::vector C_PREV, - std::vector C_CURR, - std::vector E) { + constexpr bool ckmin(float& a, const float& b) { + return b < a ? a = b, true : false; + } + + // void hungarian_assignment(Eigen::MatrixXf mat, float max_cost) { + std::vector hungarian_assignment(std::vector> mat, float max_cost) { // a way to implement MHT for clusters // matching on a bipartite graph where red vertices correspond to previous @@ -198,6 +210,68 @@ class ObstacleTracker : public rclcpp::Node { // weight < cost_threshold // cost func should consider diff in shape, position, orientation, # points -> ICP + // make matrix square: unassigned cells have val > max_cost + // eventually, if some assignment (c_prev, c) has weight > max_cost, remove that matching + // Eigen::Index n = std::max(mat.rows(), mat.cols()); + // Eigen::MatrixXf cost_matrix = Eigen::MatrixXf::Constant(n, n, max_cost + 1.0); + // cost_matrix.block(0, 0, mat.rows(), mat.cols()) = mat; + + // find perfect matching from C_PREV to C_CURR that minimizes total assignment cost + const int J = mat.size(); // cost_matrix.rows(); + const int W = mat[0].size(); // cost_matrix.cols(); + + // Eigen::VectorXf ys(J); + // Eigen::VectorXf yt(W + 1); + // Eigen::VectorXf answers; + std::vector job(W + 1, -1); + std::vector ys(J); + std::vector yt(W + 1); + std::vector answers; + + const float inf = std::numeric_limits::max(); + for (int jCur = 0; jCur < J; ++jCur) { // assign jCur-th job + int wCur = W; + job[wCur] = jCur; + + std::vector minTo(W + 1, inf); + std::vector prev(W + 1, -1); // previous worker on alternating path + std::vector inZ(W + 1); // whether worker is in Z + while (job[wCur] != -1) { // runs at most jCur + 1 times + inZ[wCur] = true; + const int j = job[wCur]; + float delta = inf; + int wNext; + for (int w = 0; w < W; ++w) { + if (!inZ[w]) { + if (ckmin(minTo[w], mat[j][w] - ys[j] - yt[w])) + prev[w] = wCur; + if (ckmin(delta, minTo[w])) + wNext = w; + } + } + // delta will always be nonnegative, + // except possibly during the first time this loop runs + // if any entries of C[jCur] are negative + for (int w = 0; w <= W; ++w) { + if (inZ[w]) { + ys[job[w]] += delta; + yt[w] -= delta; + } else { + minTo[w] -= delta; + } + } + wCur = wNext; + } + // update assignments along alternating path + for (int w; wCur != W; wCur = w) + job[wCur] = job[w = prev[wCur]]; + answers.push_back(-yt[W]); + } + return answers; + } + + void bertsekas_auction() { + // for parallelization approximate max bipartite matching // problems: we have non-integral bipartite graph. // multiplicative auction algo for (1-e)-approximation of max bipartite: // one-sided vertex deletion (delete c_prev given corr obstacle left the frame) From f99edbe43adbd75496af155dd862567405fc87ef Mon Sep 17 00:00:00 2001 From: sophtsang Date: Wed, 3 Dec 2025 05:22:29 +0000 Subject: [PATCH 24/28] square 2d vector for c_prev and c_curr bipartite adj matrix --- src/obstacle_tracker.cpp | 22 ++++++++++++---------- 1 file changed, 12 insertions(+), 10 deletions(-) diff --git a/src/obstacle_tracker.cpp b/src/obstacle_tracker.cpp index c88fc39..78a2f45 100644 --- a/src/obstacle_tracker.cpp +++ b/src/obstacle_tracker.cpp @@ -121,15 +121,17 @@ class ObstacleTracker : public rclcpp::Node { // hungarian algorithm takes in cost (adjacency) matrix where C_CURR is row // C_PREV is col std::vector E; - // std::vector> C(C_CURR.size(), std::vector(C_PREV.size(), 0.0)); - Eigen::MatrixXf cost_matrix(C_CURR.size(), C_PREV.size()); + int max_size = std::max(C_CURR.size(), C_PREV.size()); + std::vector> C(max_size, std::vector(max_size, std::numeric_limits::max())); + // Eigen::MatrixXf cost_matrix(C_CURR.size(), C_PREV.size()); // bipartite graph construction: // C_PREV (t-1), C_CURR (t): sets of clusters at time t-1 and t, C_PREV \intersect C_CURR = \emptyset // E: set of edges with elements (c_prev, c) s.t. c_prev \in C_PREV and c \in C_CURR // set cluster_ids of c \in C_CURR to be the bipartite matched cluster_ids of c_prev \in C_PREV: // i.e. if (c_prev, c) is a match in max bipartite match, then set cluster_id of c_prev to be cluster_id of c - float max_cost = 0.0; + if (max_size == 0) return; + for (int i = 0; i < C_CURR.size(); ++i) { sensor_msgs::msg::PointCloud2 c = C_CURR[i]; icp::PointCloud icp_c = pc_to_icp_pc(c); @@ -146,21 +148,19 @@ class ObstacleTracker : public rclcpp::Node { driver.set_transform_tolerance(0.1 * M_PI / 180, 0.1); auto result = driver.converge(icp_c_prev, icp_c, icp::RBTransform3::Identity()); - if (result.cost > max_cost) max_cost = result.cost; - // check whether translation between the two clusters are within max_radius (which we can define dynamically by past cluster's velocity) Edge edge; edge.edge = std::make_tuple(j, i); edge.weight = result.cost; E.push_back(edge); - // C[i][j] = result.cost; - cost_matrix(i, j) = result.cost; + C[i][j] = result.cost; + // cost_matrix(i, j) = result.cost; } } - // hungarian_assignment(cost_matrix, max_cost); - // if (mat.size() <= mat[0].size()) std::vector assignments = hungarian_assignment(C, max_cost); + hungarian_assignment(C); + // if (mat.size() <= mat[0].size()) std::vector assignments = hungarian_assignment(C); RCLCPP_INFO(this->get_logger(), "done"); obs_msg_prev_ = msg->obstacles; } @@ -189,7 +189,7 @@ class ObstacleTracker : public rclcpp::Node { } // void hungarian_assignment(Eigen::MatrixXf mat, float max_cost) { - std::vector hungarian_assignment(std::vector> mat, float max_cost) { + std::vector hungarian_assignment(std::vector> mat) { // a way to implement MHT for clusters // matching on a bipartite graph where red vertices correspond to previous @@ -228,6 +228,8 @@ class ObstacleTracker : public rclcpp::Node { std::vector yt(W + 1); std::vector answers; + return answers; + const float inf = std::numeric_limits::max(); for (int jCur = 0; jCur < J; ++jCur) { // assign jCur-th job int wCur = W; From 3e66718c10a9316dbcc32ce68a34b04a75942e1d Mon Sep 17 00:00:00 2001 From: sophtsang Date: Wed, 3 Dec 2025 05:52:16 +0000 Subject: [PATCH 25/28] cooked impl --- src/obstacle_tracker.cpp | 44 +++++++++++++++++++++++++++++++--------- 1 file changed, 34 insertions(+), 10 deletions(-) diff --git a/src/obstacle_tracker.cpp b/src/obstacle_tracker.cpp index 78a2f45..62544c4 100644 --- a/src/obstacle_tracker.cpp +++ b/src/obstacle_tracker.cpp @@ -218,32 +218,34 @@ class ObstacleTracker : public rclcpp::Node { // find perfect matching from C_PREV to C_CURR that minimizes total assignment cost const int J = mat.size(); // cost_matrix.rows(); + assert(J > 0); const int W = mat[0].size(); // cost_matrix.cols(); // Eigen::VectorXf ys(J); // Eigen::VectorXf yt(W + 1); // Eigen::VectorXf answers; std::vector job(W + 1, -1); - std::vector ys(J); - std::vector yt(W + 1); + std::vector ys(J, 0.0f); + std::vector yt(W + 1, 0.0f); std::vector answers; - - return answers; - const float inf = std::numeric_limits::max(); + for (int jCur = 0; jCur < J; ++jCur) { // assign jCur-th job int wCur = W; job[wCur] = jCur; std::vector minTo(W + 1, inf); std::vector prev(W + 1, -1); // previous worker on alternating path - std::vector inZ(W + 1); // whether worker is in Z + std::vector inZ(W + 1, false); // whether worker is in Z while (job[wCur] != -1) { // runs at most jCur + 1 times + RCLCPP_INFO(this->get_logger(), "in the while\n"); inZ[wCur] = true; const int j = job[wCur]; float delta = inf; - int wNext; + int wNext = -1; + for (int w = 0; w < W; ++w) { + // RCLCPP_INFO(this->get_logger(), "1st for %d\n", w); if (!inZ[w]) { if (ckmin(minTo[w], mat[j][w] - ys[j] - yt[w])) prev[w] = wCur; @@ -255,20 +257,42 @@ class ObstacleTracker : public rclcpp::Node { // except possibly during the first time this loop runs // if any entries of C[jCur] are negative for (int w = 0; w <= W; ++w) { + // RCLCPP_INFO(this->get_logger(), "2nd for %d\n", w); if (inZ[w]) { - ys[job[w]] += delta; + if (job[w] != -1) ys[job[w]] += delta; yt[w] -= delta; } else { minTo[w] -= delta; } } + + if (wNext == -1) break; wCur = wNext; } // update assignments along alternating path - for (int w; wCur != W; wCur = w) - job[wCur] = job[w = prev[wCur]]; + // for (int w; wCur != W; wCur = w) { + // int prevW = prev[wCur]; + // if (prevW == -1) break; + // job[wCur] = job[prevW]; + // wCur = prevW; + // } + + while (wCur != W && wCur != -1) { + // RCLCPP_INFO(this->get_logger(), "update assign while\n"); + int prevW = prev[wCur]; + if (prevW == -1) break; + job[wCur] = job[prevW]; + wCur = prevW; + } + + // RCLCPP_INFO(this->get_logger(), "push answers\n"); answers.push_back(-yt[W]); } + + for (int a = 0; a < answers.size(); ++a) { + RCLCPP_INFO(this->get_logger(), "a: %d has answer %f\n", a, answers[a]); + } + return answers; } From 7776e7ef6363b5179570bd89b8ff6d3fdde185bd Mon Sep 17 00:00:00 2001 From: sophtsang Date: Fri, 5 Dec 2025 00:00:09 +0000 Subject: [PATCH 26/28] dying inside, at least matches, no way to visualize yet --- src/obstacle_tracker.cpp | 206 +++++++++++++++++++++++++++++---------- 1 file changed, 155 insertions(+), 51 deletions(-) diff --git a/src/obstacle_tracker.cpp b/src/obstacle_tracker.cpp index 62544c4..9d41743 100644 --- a/src/obstacle_tracker.cpp +++ b/src/obstacle_tracker.cpp @@ -5,6 +5,7 @@ #include #include #include +#include #include #include "cev_msgs/msg/obstacles.hpp" #include "obstacle/msg/obstacle_array.hpp" @@ -12,6 +13,7 @@ #include "icp/geo.h" #include "icp/driver.h" +#include #include #include #include @@ -155,16 +157,141 @@ class ObstacleTracker : public rclcpp::Node { E.push_back(edge); C[i][j] = result.cost; + // RCLCPP_INFO(this->get_logger(), "C_CURR [%d] -- %f -- C_PREV [%d]\n", i, result.cost, j); // cost_matrix(i, j) = result.cost; } } - hungarian_assignment(C); - // if (mat.size() <= mat[0].size()) std::vector assignments = hungarian_assignment(C); + std::vector matchings = hungarian_assignment(C); + outputMatching(C_PREV, C_CURR, matchings); + // auto markers = outputMatching(C_PREV, C_CURR, matchings); + + // marker_pub_->publish(markers); + RCLCPP_INFO(this->get_logger(), "done"); obs_msg_prev_ = msg->obstacles; } + visualization_msgs::msg::MarkerArray outputMatching( + const std::vector& C_PREV, + const std::vector& C_CURR, + std::vector matchings) { + + visualization_msgs::msg::MarkerArray marker_array; + + for (int i = 0; i < matchings.size(); ++i) { + RCLCPP_INFO(this->get_logger(), "C_CURR [%d] -- C_PREV [%d]\n", i, matchings[i]); + } + for (int i = 0; i < matchings.size(); ++i) { + int prev_idx = matchings[i]; + + if (prev_idx < 0) { + continue; + } + + // Get centroids of matched clusters + Eigen::Vector4f centroid_prev, centroid_curr; + + // Convert to PCL and compute centroids + pcl::PointCloud::Ptr cloud_prev(new pcl::PointCloud); + pcl::PointCloud::Ptr cloud_curr(new pcl::PointCloud); + + pcl::fromROSMsg(C_PREV[prev_idx], *cloud_prev); + pcl::fromROSMsg(C_CURR[i], *cloud_curr); + + pcl::compute3DCentroid(*cloud_prev, centroid_prev); + pcl::compute3DCentroid(*cloud_curr, centroid_curr); + + // Create line marker + visualization_msgs::msg::Marker line; + line.header.frame_id = C_CURR[i].header.frame_id; + // line.header.stamp = rclcpp::Clock().now(); + line.ns = "cluster_matches"; + line.id = i; + line.type = visualization_msgs::msg::Marker::ARROW; + line.action = visualization_msgs::msg::Marker::ADD; + + // Start point (previous cluster) + geometry_msgs::msg::Point p1; + p1.x = centroid_prev[0]; + p1.y = centroid_prev[1]; + p1.z = centroid_prev[2]; + + // End point (current cluster) + geometry_msgs::msg::Point p2; + p2.x = centroid_curr[0]; + p2.y = centroid_curr[1]; + p2.z = centroid_curr[2]; + + line.points.push_back(p1); + line.points.push_back(p2); + + // Style + line.scale.x = 0.05; // Arrow shaft diameter + line.scale.y = 0.1; // Arrow head diameter + line.scale.z = 0.1; // Arrow head length + + // Color (green for matched) + line.color.r = 0.0; + line.color.g = 1.0; + line.color.b = 0.0; + line.color.a = 0.8; + + line.lifetime = rclcpp::Duration::from_seconds(0.5); + + marker_array.markers.push_back(line); + } + + // // Add text labels + // for (size_t i = 0; i < matchings.size(); ++i) { + // int prev_idx = matchings[i]; + // if (prev_idx == -1) continue; + + // pcl::PointCloud::Ptr cloud_curr(new pcl::PointCloud); + // pcl::fromROSMsg(C_CURR[i], *cloud_curr); + + // Eigen::Vector4f centroid; + // pcl::compute3DCentroid(*cloud_curr, centroid); + + // visualization_msgs::msg::Marker text; + // text.header.frame_id = C_CURR[i].header.frame_id; + // text.header.stamp = rclcpp::Clock().now(); + // text.ns = "cluster_labels"; + // text.id = i + 1000; // Offset to avoid ID collision + // text.type = visualization_msgs::msg::Marker::TEXT_VIEW_FACING; + // text.action = visualization_msgs::msg::Marker::ADD; + + // text.pose.position.x = centroid[0]; + // text.pose.position.y = centroid[1]; + // text.pose.position.z = centroid[2] + 0.5; // Slightly above + + // text.text = std::to_string(prev_idx) + "->" + std::to_string(i); + // text.scale.z = 0.3; // Text height + + // text.color.r = 1.0; + // text.color.g = 1.0; + // text.color.b = 1.0; + // text.color.a = 1.0; + + // text.lifetime = rclcpp::Duration::from_seconds(0.5); + + // marker_array.markers.push_back(text); + // } + + return marker_array; + } + + // void sanityCheckHungarian() { + // RCLCPP_INFO(this->get_logger(), "STARTING SANITY CHECK\n"); + // std::vector> costs{{8.0, 5.0, 9.0}, {4.0, 2.0, 4.0}, {7.0, 3.0, 8.0}}; + // // A B C + // // clean 8.0 5.0 9.0 + // // sweep 4.0 2.0 4.0 + // // wash 7.0 3.0 8.0 + // assert((hungarian_assignment(costs) == std::vector{5.0, 9.0, 15.0})); + // RCLCPP_INFO(this->get_logger(), "Sanity check passed\n"); + // } + void multi_hypothesis_tracking(std::unordered_map> C_prev, std::unordered_map> C) { // takes in ??? vector or the entire point cloud idrk @@ -184,12 +311,8 @@ class ObstacleTracker : public rclcpp::Node { // -> denote as {Y(T_j, Z_j)} } - constexpr bool ckmin(float& a, const float& b) { - return b < a ? a = b, true : false; - } - // void hungarian_assignment(Eigen::MatrixXf mat, float max_cost) { - std::vector hungarian_assignment(std::vector> mat) { + std::vector hungarian_assignment(std::vector> mat) { // a way to implement MHT for clusters // matching on a bipartite graph where red vertices correspond to previous @@ -205,30 +328,17 @@ class ObstacleTracker : public rclcpp::Node { // unique id for clusters so we can do more long term obstacle tracking for // the same cluster - // complexity reduction / pruning: - // there should be a cost_threshold -> don't even create an edge if - // weight < cost_threshold - // cost func should consider diff in shape, position, orientation, # points -> ICP - - // make matrix square: unassigned cells have val > max_cost - // eventually, if some assignment (c_prev, c) has weight > max_cost, remove that matching - // Eigen::Index n = std::max(mat.rows(), mat.cols()); - // Eigen::MatrixXf cost_matrix = Eigen::MatrixXf::Constant(n, n, max_cost + 1.0); - // cost_matrix.block(0, 0, mat.rows(), mat.cols()) = mat; - // find perfect matching from C_PREV to C_CURR that minimizes total assignment cost - const int J = mat.size(); // cost_matrix.rows(); + const int J = mat.size(); // cost_matrix.rows() is C_CURR idx assert(J > 0); - const int W = mat[0].size(); // cost_matrix.cols(); + const int W = mat[0].size(); // cost_matrix.cols() is C_PREV idx - // Eigen::VectorXf ys(J); - // Eigen::VectorXf yt(W + 1); - // Eigen::VectorXf answers; std::vector job(W + 1, -1); std::vector ys(J, 0.0f); std::vector yt(W + 1, 0.0f); std::vector answers; const float inf = std::numeric_limits::max(); + const float eps = static_cast(1e-9); for (int jCur = 0; jCur < J; ++jCur) { // assign jCur-th job int wCur = W; @@ -237,27 +347,35 @@ class ObstacleTracker : public rclcpp::Node { std::vector minTo(W + 1, inf); std::vector prev(W + 1, -1); // previous worker on alternating path std::vector inZ(W + 1, false); // whether worker is in Z + while (job[wCur] != -1) { // runs at most jCur + 1 times - RCLCPP_INFO(this->get_logger(), "in the while\n"); inZ[wCur] = true; const int j = job[wCur]; float delta = inf; int wNext = -1; for (int w = 0; w < W; ++w) { - // RCLCPP_INFO(this->get_logger(), "1st for %d\n", w); if (!inZ[w]) { - if (ckmin(minTo[w], mat[j][w] - ys[j] - yt[w])) - prev[w] = wCur; - if (ckmin(delta, minTo[w])) - wNext = w; + float new_cost = mat[j][w] - ys[j] - yt[w]; + if (new_cost < minTo[w] - eps) { + minTo[w] = new_cost; + prev[w] = wCur; + } + if (minTo[w] < delta - eps) { + delta = minTo[w]; + wNext = w; + } } } + + if (wNext == -1) { + RCLCPP_ERROR(this->get_logger(), "No valid worker found!"); + break; + } // delta will always be nonnegative, // except possibly during the first time this loop runs // if any entries of C[jCur] are negative for (int w = 0; w <= W; ++w) { - // RCLCPP_INFO(this->get_logger(), "2nd for %d\n", w); if (inZ[w]) { if (job[w] != -1) ys[job[w]] += delta; yt[w] -= delta; @@ -265,35 +383,20 @@ class ObstacleTracker : public rclcpp::Node { minTo[w] -= delta; } } - - if (wNext == -1) break; wCur = wNext; } // update assignments along alternating path - // for (int w; wCur != W; wCur = w) { - // int prevW = prev[wCur]; - // if (prevW == -1) break; - // job[wCur] = job[prevW]; - // wCur = prevW; - // } - - while (wCur != W && wCur != -1) { - // RCLCPP_INFO(this->get_logger(), "update assign while\n"); - int prevW = prev[wCur]; - if (prevW == -1) break; - job[wCur] = job[prevW]; - wCur = prevW; + while (wCur != W) { + int w = prev[wCur]; + job[wCur] = job[w]; + wCur = w; } - // RCLCPP_INFO(this->get_logger(), "push answers\n"); answers.push_back(-yt[W]); } - for (int a = 0; a < answers.size(); ++a) { - RCLCPP_INFO(this->get_logger(), "a: %d has answer %f\n", a, answers[a]); - } - - return answers; + job.pop_back(); + return job; } void bertsekas_auction() { @@ -311,6 +414,7 @@ class ObstacleTracker : public rclcpp::Node { // then (null, c) } + rclcpp::Publisher::SharedPtr marker_pub_; sensor_msgs::msg::PointCloud2::SharedPtr msg_prev_; std::vector obs_msg_prev_; std::unordered_map> C_prev_; From f10887b080c2bb08c220689577ea32bd53f432e4 Mon Sep 17 00:00:00 2001 From: sophtsang Date: Sat, 6 Dec 2025 18:19:31 +0000 Subject: [PATCH 27/28] preventing seg fault in iterating on empty clusters --- src/obstacle_tracker.cpp | 149 ++++++++++++++++----------------------- 1 file changed, 60 insertions(+), 89 deletions(-) diff --git a/src/obstacle_tracker.cpp b/src/obstacle_tracker.cpp index 9d41743..6f5d82e 100644 --- a/src/obstacle_tracker.cpp +++ b/src/obstacle_tracker.cpp @@ -42,6 +42,7 @@ class ObstacleTracker : public rclcpp::Node { ObstacleTracker() : Node("obstacle_tracker") { + match_pub_ = this->create_publisher("rslidar_matches", 10); // nearest neighbor association method -> MHT pc_sub_ = this->create_subscription( "/rslidar_clusters", 10, @@ -119,6 +120,7 @@ class ObstacleTracker : public rclcpp::Node { // initialize the bipartite graph std::vector C_PREV = obs_msg_prev_; std::vector C_CURR = msg->obstacles; + // or maybe a mapping from (c_prev, c) -> edge weight, we'll see // hungarian algorithm takes in cost (adjacency) matrix where C_CURR is row // C_PREV is col @@ -136,6 +138,8 @@ class ObstacleTracker : public rclcpp::Node { for (int i = 0; i < C_CURR.size(); ++i) { sensor_msgs::msg::PointCloud2 c = C_CURR[i]; + if (c.width * c.height == 0) continue; + icp::PointCloud icp_c = pc_to_icp_pc(c); for (int j = 0; j < C_PREV.size(); ++j) @@ -163,122 +167,85 @@ class ObstacleTracker : public rclcpp::Node { } std::vector matchings = hungarian_assignment(C); - outputMatching(C_PREV, C_CURR, matchings); // auto markers = outputMatching(C_PREV, C_CURR, matchings); + outputMatching(C_PREV, C_CURR, matchings); - // marker_pub_->publish(markers); + // match_pub_->publish(markers); RCLCPP_INFO(this->get_logger(), "done"); obs_msg_prev_ = msg->obstacles; } - visualization_msgs::msg::MarkerArray outputMatching( + // visualization_msgs::msg::MarkerArray + void outputMatching( const std::vector& C_PREV, const std::vector& C_CURR, std::vector matchings) { visualization_msgs::msg::MarkerArray marker_array; - for (int i = 0; i < matchings.size(); ++i) { - RCLCPP_INFO(this->get_logger(), "C_CURR [%d] -- C_PREV [%d]\n", i, matchings[i]); - } - for (int i = 0; i < matchings.size(); ++i) { - int prev_idx = matchings[i]; - - if (prev_idx < 0) { - continue; - } - - // Get centroids of matched clusters - Eigen::Vector4f centroid_prev, centroid_curr; - - // Convert to PCL and compute centroids - pcl::PointCloud::Ptr cloud_prev(new pcl::PointCloud); - pcl::PointCloud::Ptr cloud_curr(new pcl::PointCloud); - - pcl::fromROSMsg(C_PREV[prev_idx], *cloud_prev); - pcl::fromROSMsg(C_CURR[i], *cloud_curr); - - pcl::compute3DCentroid(*cloud_prev, centroid_prev); - pcl::compute3DCentroid(*cloud_curr, centroid_curr); - - // Create line marker - visualization_msgs::msg::Marker line; - line.header.frame_id = C_CURR[i].header.frame_id; - // line.header.stamp = rclcpp::Clock().now(); - line.ns = "cluster_matches"; - line.id = i; - line.type = visualization_msgs::msg::Marker::ARROW; - line.action = visualization_msgs::msg::Marker::ADD; - - // Start point (previous cluster) - geometry_msgs::msg::Point p1; - p1.x = centroid_prev[0]; - p1.y = centroid_prev[1]; - p1.z = centroid_prev[2]; - - // End point (current cluster) - geometry_msgs::msg::Point p2; - p2.x = centroid_curr[0]; - p2.y = centroid_curr[1]; - p2.z = centroid_curr[2]; + // RCLCPP_INFO(this->get_logger(), "matchings length %d", matchings.size()); + // for (int i = 0; i < matchings.size(); ++i) { + // RCLCPP_INFO(this->get_logger(), "C_CURR [%d] -- C_PREV [%d]\n", i, matchings[i]); + + // int prev_idx = matchings[i]; - line.points.push_back(p1); - line.points.push_back(p2); + // if (prev_idx < 0) { + // continue; + // } - // Style - line.scale.x = 0.05; // Arrow shaft diameter - line.scale.y = 0.1; // Arrow head diameter - line.scale.z = 0.1; // Arrow head length + // Eigen::Vector4f centroid_prev, centroid_curr; - // Color (green for matched) - line.color.r = 0.0; - line.color.g = 1.0; - line.color.b = 0.0; - line.color.a = 0.8; + // // Convert to PCL and compute centroids + // pcl::PointCloud::Ptr cloud_prev(new pcl::PointCloud); + // pcl::PointCloud::Ptr cloud_curr(new pcl::PointCloud); - line.lifetime = rclcpp::Duration::from_seconds(0.5); + // pcl::fromROSMsg(C_PREV[prev_idx], *cloud_prev); + // pcl::fromROSMsg(C_CURR[i], *cloud_curr); - marker_array.markers.push_back(line); - } - - // // Add text labels - // for (size_t i = 0; i < matchings.size(); ++i) { - // int prev_idx = matchings[i]; - // if (prev_idx == -1) continue; + // pcl::compute3DCentroid(*cloud_prev, centroid_prev); + // pcl::compute3DCentroid(*cloud_curr, centroid_curr); - // pcl::PointCloud::Ptr cloud_curr(new pcl::PointCloud); - // pcl::fromROSMsg(C_CURR[i], *cloud_curr); + // // Create line marker + // // visualization_msgs::msg::Marker line; + // // line.header.frame_id = C_CURR[i].header.frame_id; + // // line.ns = "cluster_matches"; + // // line.id = i; + // // line.type = visualization_msgs::msg::Marker::ARROW; + // // line.action = visualization_msgs::msg::Marker::ADD; - // Eigen::Vector4f centroid; - // pcl::compute3DCentroid(*cloud_curr, centroid); + // // // Start point (previous cluster) + // // geometry_msgs::msg::Point p1; + // // p1.x = centroid_prev[0]; + // // p1.y = centroid_prev[1]; + // // p1.z = centroid_prev[2]; - // visualization_msgs::msg::Marker text; - // text.header.frame_id = C_CURR[i].header.frame_id; - // text.header.stamp = rclcpp::Clock().now(); - // text.ns = "cluster_labels"; - // text.id = i + 1000; // Offset to avoid ID collision - // text.type = visualization_msgs::msg::Marker::TEXT_VIEW_FACING; - // text.action = visualization_msgs::msg::Marker::ADD; + // // // End point (current cluster) + // // geometry_msgs::msg::Point p2; + // // p2.x = centroid_curr[0]; + // // p2.y = centroid_curr[1]; + // // p2.z = centroid_curr[2]; - // text.pose.position.x = centroid[0]; - // text.pose.position.y = centroid[1]; - // text.pose.position.z = centroid[2] + 0.5; // Slightly above + // // line.points.push_back(p1); + // // line.points.push_back(p2); - // text.text = std::to_string(prev_idx) + "->" + std::to_string(i); - // text.scale.z = 0.3; // Text height + // // // Style + // // line.scale.x = 0.05; + // // line.scale.y = 0.1; + // // line.scale.z = 0.1; - // text.color.r = 1.0; - // text.color.g = 1.0; - // text.color.b = 1.0; - // text.color.a = 1.0; + // // Color (green for matched) + // // line.color.r = 0.0; + // // line.color.g = 1.0; + // // line.color.b = 0.0; + // // line.color.a = 0.8; - // text.lifetime = rclcpp::Duration::from_seconds(0.5); + // // line.lifetime = rclcpp::Duration::from_seconds(0.5); - // marker_array.markers.push_back(text); + // // marker_array.markers.push_back(line); // } - return marker_array; + // return marker_array; } // void sanityCheckHungarian() { @@ -395,6 +362,10 @@ class ObstacleTracker : public rclcpp::Node { answers.push_back(-yt[W]); } + for (int i = 0; i < job.size(); ++i) { + RCLCPP_INFO(this->get_logger(), "C_CURR [%d] -- C_PREV [%d]\n", i, job[i]); + } + job.pop_back(); return job; } @@ -414,7 +385,7 @@ class ObstacleTracker : public rclcpp::Node { // then (null, c) } - rclcpp::Publisher::SharedPtr marker_pub_; + rclcpp::Publisher::SharedPtr match_pub_; sensor_msgs::msg::PointCloud2::SharedPtr msg_prev_; std::vector obs_msg_prev_; std::unordered_map> C_prev_; From d6587f51a07dfcc230a4de89c0fdad13dfbc7687 Mon Sep 17 00:00:00 2001 From: sophtsang Date: Sat, 6 Dec 2025 20:40:20 +0000 Subject: [PATCH 28/28] able to display matches w/ lines between centroids, runs so slowly im cring --- src/obstacle_tracker.cpp | 237 +++++++++++++++++++++++---------------- 1 file changed, 143 insertions(+), 94 deletions(-) diff --git a/src/obstacle_tracker.cpp b/src/obstacle_tracker.cpp index 6f5d82e..1f21449 100644 --- a/src/obstacle_tracker.cpp +++ b/src/obstacle_tracker.cpp @@ -43,17 +43,20 @@ class ObstacleTracker : public rclcpp::Node { : Node("obstacle_tracker") { match_pub_ = this->create_publisher("rslidar_matches", 10); + prev_pub_ = this->create_publisher("/prev", 10); + curr_pub_ = this->create_publisher("/curr", 10); // nearest neighbor association method -> MHT pc_sub_ = this->create_subscription( "/rslidar_clusters", 10, std::bind(&ObstacleTracker::pcCallback, this, std::placeholders::_1)); obs_sub_ = this->create_subscription( - "/rslidar_obstacles", 10, - std::bind(&ObstacleTracker::obsCallback, this, std::placeholders::_1)); + "/rslidar_obstacles", 10, + std::bind(&ObstacleTracker::obsCallback, this, std::placeholders::_1)); // maybe implement joint probability data association (JPDA) also for clustering + RCLCPP_INFO(this->get_logger(), "ObstacleTracker started - waiting for PointCloud2 on 'input_points'"); } @@ -96,6 +99,10 @@ class ObstacleTracker : public rclcpp::Node { // after all the cluster matching and whatever is done, update C_prev // we can also use this to determine static v. dynamic obstacles + if (C_prev_.size() * C.size() != 0) { + prev_pub_->publish(*msg_prev_); + curr_pub_->publish(*msg); + } msg_prev_ = msg; C_prev_ = C; } @@ -136,116 +143,173 @@ class ObstacleTracker : public rclcpp::Node { // i.e. if (c_prev, c) is a match in max bipartite match, then set cluster_id of c_prev to be cluster_id of c if (max_size == 0) return; - for (int i = 0; i < C_CURR.size(); ++i) { - sensor_msgs::msg::PointCloud2 c = C_CURR[i]; - if (c.width * c.height == 0) continue; + auto start = std::chrono::high_resolution_clock::now(); + // std::vector> futures; - icp::PointCloud icp_c = pc_to_icp_pc(c); + // for (int i = 0; i < C_CURR.size(); ++i) { + // sensor_msgs::msg::PointCloud2 c = C_CURR[i]; + // if (c.width * c.height == 0) continue; - for (int j = 0; j < C_PREV.size(); ++j) - { - sensor_msgs::msg::PointCloud2 c_prev = C_PREV[j]; - icp::PointCloud icp_c_prev = pc_to_icp_pc(c_prev); + // auto start = std::chrono::high_resolution_clock::now(); + // icp::PointCloud icp_c = pc_to_icp_pc(c); - std::unique_ptr icp = icp::ICP3::from_method("vanilla", icp::Config()).value(); - icp::ICPDriver driver(std::move(icp)); + // for (int j = 0; j < C_PREV.size(); ++j) + // { + // sensor_msgs::msg::PointCloud2 c_prev = C_PREV[j]; + // icp::PointCloud icp_c_prev = pc_to_icp_pc(c_prev); - driver.set_max_iterations(1); - driver.set_transform_tolerance(0.1 * M_PI / 180, 0.1); - auto result = driver.converge(icp_c_prev, icp_c, icp::RBTransform3::Identity()); + // std::unique_ptr icp = icp::ICP3::from_method("vanilla", icp::Config()).value(); + // icp::ICPDriver driver(std::move(icp)); - // check whether translation between the two clusters are within max_radius (which we can define dynamically by past cluster's velocity) - Edge edge; - edge.edge = std::make_tuple(j, i); - edge.weight = result.cost; + // driver.set_max_iterations(1); + // driver.set_transform_tolerance(0.1 * M_PI / 180, 0.1); + // auto result = driver.converge(icp_c_prev, icp_c, icp::RBTransform3::Identity()); - E.push_back(edge); - C[i][j] = result.cost; - // RCLCPP_INFO(this->get_logger(), "C_CURR [%d] -- %f -- C_PREV [%d]\n", i, result.cost, j); - // cost_matrix(i, j) = result.cost; + // // check whether translation between the two clusters are within max_radius (which we can define dynamically by past cluster's velocity) + // Edge edge; + // edge.edge = std::make_tuple(j, i); + // edge.weight = result.cost; + + // E.push_back(edge); + // C[i][j] = result.cost; + // // cost_matrix(i, j) = result.cost; + // } + // } + + // for (auto &f : futures) f.get(); + + std::mutex mtx; + std::vector> futures; + + for (int i = 0; i < C_CURR.size(); ++i) { + sensor_msgs::msg::PointCloud2 c = C_CURR[i]; + if (c.width * c.height == 0) continue; + + icp::PointCloud icp_c = pc_to_icp_pc(c); + + for (int j = 0; j < C_PREV.size(); ++j) { + futures.push_back(std::async(std::launch::async, [&, i, j, icp_c]() { + sensor_msgs::msg::PointCloud2 c_prev = C_PREV[j]; + + if (c_prev.width * c_prev.height == 0) return; + icp::PointCloud icp_c_prev = pc_to_icp_pc(c_prev); + + std::unique_ptr icp = icp::ICP3::from_method("vanilla", icp::Config()).value(); + icp::ICPDriver driver(std::move(icp)); + + driver.set_max_iterations(1); + driver.set_transform_tolerance(0.1 * M_PI / 180, 0.1); + + auto result = driver.converge(icp_c_prev, icp_c, icp::RBTransform3::Identity()); + + Edge edge; + edge.edge = std::make_tuple(j, i); + edge.weight = result.cost; + + // Need mutex protection for shared data structures + { + std::lock_guard lock(mtx); + E.push_back(edge); + C[i][j] = result.cost; + } + })); } } + // Wait for all tasks to complete + for (auto& f : futures) { + f.get(); + } + + auto end = std::chrono::high_resolution_clock::now(); + auto duration = std::chrono::duration_cast(end - start); + RCLCPP_INFO(this->get_logger(), "RAN FOR: %ld ms", duration.count()); + std::vector matchings = hungarian_assignment(C); - // auto markers = outputMatching(C_PREV, C_CURR, matchings); - outputMatching(C_PREV, C_CURR, matchings); + auto markers = outputMatching(C_PREV, C_CURR, matchings); + // outputMatching(C_PREV, C_CURR, matchings); - // match_pub_->publish(markers); + match_pub_->publish(markers); RCLCPP_INFO(this->get_logger(), "done"); obs_msg_prev_ = msg->obstacles; } - // visualization_msgs::msg::MarkerArray - void outputMatching( + visualization_msgs::msg::MarkerArray outputMatching( const std::vector& C_PREV, const std::vector& C_CURR, std::vector matchings) { visualization_msgs::msg::MarkerArray marker_array; - // RCLCPP_INFO(this->get_logger(), "matchings length %d", matchings.size()); - // for (int i = 0; i < matchings.size(); ++i) { - // RCLCPP_INFO(this->get_logger(), "C_CURR [%d] -- C_PREV [%d]\n", i, matchings[i]); - - // int prev_idx = matchings[i]; + RCLCPP_INFO(this->get_logger(), "C_prev count: %d v. C_curr count: %d", C_PREV.size(), C_CURR.size()); + for (int i = 0; i < matchings.size(); ++i) { + int prev_idx = i; + int curr_idx = matchings[i]; - // if (prev_idx < 0) { - // continue; - // } + // if prev_idx or curr_idx is -1, then this is an invalid match + if (curr_idx == -1 || curr_idx >= C_CURR.size() || prev_idx == -1 || prev_idx >= C_PREV.size()) { + continue; + } + + RCLCPP_INFO(this->get_logger(), "C_PREV [%d] -- C_CURR [%d]\n", prev_idx, curr_idx); - // Eigen::Vector4f centroid_prev, centroid_curr; + Eigen::Vector4f centroid_prev, centroid_curr; - // // Convert to PCL and compute centroids - // pcl::PointCloud::Ptr cloud_prev(new pcl::PointCloud); - // pcl::PointCloud::Ptr cloud_curr(new pcl::PointCloud); + // Convert to PCL and compute centroids + pcl::PointCloud::Ptr cloud_prev(new pcl::PointCloud); + pcl::PointCloud::Ptr cloud_curr(new pcl::PointCloud); - // pcl::fromROSMsg(C_PREV[prev_idx], *cloud_prev); - // pcl::fromROSMsg(C_CURR[i], *cloud_curr); + pcl::fromROSMsg(C_PREV[prev_idx], *cloud_prev); + pcl::fromROSMsg(C_CURR[curr_idx], *cloud_curr); - // pcl::compute3DCentroid(*cloud_prev, centroid_prev); - // pcl::compute3DCentroid(*cloud_curr, centroid_curr); + pcl::compute3DCentroid(*cloud_prev, centroid_prev); + pcl::compute3DCentroid(*cloud_curr, centroid_curr); + + RCLCPP_INFO(this->get_logger(), "C_PREV: (%f, %f, %f) -- C_CURR: (%f, %f, %f)\n", + centroid_prev[0], centroid_prev[1], centroid_prev[2], centroid_curr[0], centroid_curr[1], centroid_curr[2]); - // // Create line marker - // // visualization_msgs::msg::Marker line; - // // line.header.frame_id = C_CURR[i].header.frame_id; - // // line.ns = "cluster_matches"; - // // line.id = i; - // // line.type = visualization_msgs::msg::Marker::ARROW; - // // line.action = visualization_msgs::msg::Marker::ADD; + // Create line marker + visualization_msgs::msg::Marker line; + line.header.frame_id = "rslidar"; + line.header.stamp = this->now(); + line.ns = "cluster_matches"; + line.id = i; + line.type = visualization_msgs::msg::Marker::ARROW; + line.action = visualization_msgs::msg::Marker::ADD; - // // // Start point (previous cluster) - // // geometry_msgs::msg::Point p1; - // // p1.x = centroid_prev[0]; - // // p1.y = centroid_prev[1]; - // // p1.z = centroid_prev[2]; + // Start point (previous cluster) + geometry_msgs::msg::Point p1; + p1.x = centroid_prev[0]; + p1.y = centroid_prev[1]; + p1.z = centroid_prev[2]; - // // // End point (current cluster) - // // geometry_msgs::msg::Point p2; - // // p2.x = centroid_curr[0]; - // // p2.y = centroid_curr[1]; - // // p2.z = centroid_curr[2]; + // End point (current cluster) + geometry_msgs::msg::Point p2; + p2.x = centroid_curr[0]; + p2.y = centroid_curr[1]; + p2.z = centroid_curr[2]; - // // line.points.push_back(p1); - // // line.points.push_back(p2); + line.points.push_back(p1); + line.points.push_back(p2); - // // // Style - // // line.scale.x = 0.05; - // // line.scale.y = 0.1; - // // line.scale.z = 0.1; + // Style + line.scale.x = 0.05; + line.scale.y = 0.1; + line.scale.z = 0.1; - // // Color (green for matched) - // // line.color.r = 0.0; - // // line.color.g = 1.0; - // // line.color.b = 0.0; - // // line.color.a = 0.8; + // Color (green for matched) + line.color.r = 0.0; + line.color.g = 1.0; + line.color.b = 0.0; + line.color.a = 0.8; - // // line.lifetime = rclcpp::Duration::from_seconds(0.5); + line.lifetime = rclcpp::Duration::from_seconds(2.0); - // // marker_array.markers.push_back(line); - // } + marker_array.markers.push_back(line); + } - // return marker_array; + return marker_array; } // void sanityCheckHungarian() { @@ -280,20 +344,7 @@ class ObstacleTracker : public rclcpp::Node { // void hungarian_assignment(Eigen::MatrixXf mat, float max_cost) { std::vector hungarian_assignment(std::vector> mat) { - // a way to implement MHT for clusters - - // matching on a bipartite graph where red vertices correspond to previous - // clusters at timestamp t-1 and black vertices correspond to current - // clusters at timestamp t - // we construct a fully connected (WLOG, each red vertex connected to all - // black vertices) bipartite graph where the weight of edge connecting each - // red-black vertex pair is defined by the quantitative ICP overlaying cost - // thing between the two clusters (maybe like determined by the returned - // transformation matrix [R | t]) - // somehow think about this? - // unmatched black (t) vertices are maybe categorized as new obstacles? - // unique id for clusters so we can do more long term obstacle tracking for - // the same cluster + // i is the cluster id of C_PREV, job[i] is the cluster id of C_CURR // find perfect matching from C_PREV to C_CURR that minimizes total assignment cost const int J = mat.size(); // cost_matrix.rows() is C_CURR idx @@ -362,10 +413,6 @@ class ObstacleTracker : public rclcpp::Node { answers.push_back(-yt[W]); } - for (int i = 0; i < job.size(); ++i) { - RCLCPP_INFO(this->get_logger(), "C_CURR [%d] -- C_PREV [%d]\n", i, job[i]); - } - job.pop_back(); return job; } @@ -385,6 +432,8 @@ class ObstacleTracker : public rclcpp::Node { // then (null, c) } + rclcpp::Publisher::SharedPtr prev_pub_; + rclcpp::Publisher::SharedPtr curr_pub_; rclcpp::Publisher::SharedPtr match_pub_; sensor_msgs::msg::PointCloud2::SharedPtr msg_prev_; std::vector obs_msg_prev_;