From e679068862ea8eeec2b37fc6de624d74f3327d56 Mon Sep 17 00:00:00 2001 From: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Date: Mon, 9 May 2022 11:10:17 +0900 Subject: [PATCH 01/55] fix(behavior_velocity): avoid insert same point on trajectory utils (#834) Signed-off-by: tanaka3 --- .../include/utilization/trajectory_utils.hpp | 14 +++++++++----- 1 file changed, 9 insertions(+), 5 deletions(-) diff --git a/planning/behavior_velocity_planner/include/utilization/trajectory_utils.hpp b/planning/behavior_velocity_planner/include/utilization/trajectory_utils.hpp index 93b3d9c3d961..729af3099f81 100644 --- a/planning/behavior_velocity_planner/include/utilization/trajectory_utils.hpp +++ b/planning/behavior_velocity_planner/include/utilization/trajectory_utils.hpp @@ -91,7 +91,7 @@ inline Quaternion lerpOrientation( * @param [in] point Interpolated point is nearest to this point. */ template -TrajectoryPointWithIdx getLerpTrajectoryPointWithIdx( +boost::optional getLerpTrajectoryPointWithIdx( const T & points, const geometry_msgs::msg::Point & point) { TrajectoryPoint interpolated_point; @@ -100,7 +100,9 @@ TrajectoryPointWithIdx getLerpTrajectoryPointWithIdx( tier4_autoware_utils::calcLongitudinalOffsetToSegment(points, nearest_seg_idx, point); const double len_segment = tier4_autoware_utils::calcSignedArcLength(points, nearest_seg_idx, nearest_seg_idx + 1); - const double interpolate_ratio = std::clamp(len_to_interpolated / len_segment, 0.0, 1.0); + const double ratio = len_to_interpolated / len_segment; + if (ratio <= 0.0 || 1.0 <= ratio) return boost::none; + const double interpolate_ratio = std::clamp(ratio, 0.0, 1.0); { const size_t i = nearest_seg_idx; const auto & pos0 = points.at(i).pose.position; @@ -154,14 +156,15 @@ inline bool smoothPath( // calc ego internal division point on path const auto traj_with_ego_point_with_idx = getLerpTrajectoryPointWithIdx(*traj_lateral_acc_filtered, current_pose.position); - TrajectoryPoint ego_point_on_path = traj_with_ego_point_with_idx.first; - const size_t nearest_seg_idx = traj_with_ego_point_with_idx.second; + if (traj_with_ego_point_with_idx == boost::none) return false; + TrajectoryPoint ego_point_on_path = traj_with_ego_point_with_idx->first; + const size_t nearest_seg_idx = traj_with_ego_point_with_idx->second; //! insert ego projected pose on path so new nearest segment will be nearest_seg_idx + 1 traj_with_ego_point_on_path.insert( traj_with_ego_point_on_path.begin() + nearest_seg_idx, ego_point_on_path); // ego point inserted is new nearest point - nearest_idx = traj_with_ego_point_with_idx.second + 1; + nearest_idx = nearest_seg_idx + 1; } // Resample trajectory with ego-velocity based interval distances auto traj_resampled = smoother->resampleTrajectory(traj_with_ego_point_on_path, v0, nearest_idx); @@ -182,6 +185,7 @@ inline bool smoothPath( traj_smoothed.insert( traj_smoothed.begin(), traj_resampled->begin(), traj_resampled->begin() + *traj_resampled_closest); + out_path = convertTrajectoryPointsToPath(traj_smoothed); return true; } From b3a0363b90f27c930d062c1bc316b636af73dfa4 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Mon, 9 May 2022 11:59:02 +0900 Subject: [PATCH 02/55] refactor(behavior_velocity_planner): simplify CMakeLists.txt (#855) Signed-off-by: Kenji Miyake --- .../behavior_velocity_planner/CMakeLists.txt | 296 ++---------------- 1 file changed, 27 insertions(+), 269 deletions(-) diff --git a/planning/behavior_velocity_planner/CMakeLists.txt b/planning/behavior_velocity_planner/CMakeLists.txt index 6acaa54b6481..47f6f999ecb0 100644 --- a/planning/behavior_velocity_planner/CMakeLists.txt +++ b/planning/behavior_velocity_planner/CMakeLists.txt @@ -11,292 +11,50 @@ find_package(Eigen3 REQUIRED) find_package(PCL REQUIRED COMPONENTS common) find_package(OpenCV REQUIRED) -set(BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES - tier4_api_msgs - autoware_auto_perception_msgs - autoware_auto_planning_msgs - tier4_planning_msgs - tier4_autoware_utils - Boost - Eigen3 - diagnostic_msgs - geometry_msgs - lanelet2_extension - PCL - pcl_conversions - rclcpp - sensor_msgs - interpolation - tf2 - tf2_eigen - tf2_geometry_msgs - tf2_ros - vehicle_info_util - visualization_msgs - nav_msgs - grid_map_ros -) +set(scene_modules + detection_area + blind_spot + stop_line + crosswalk + traffic_light + intersection + no_stopping_area + virtual_traffic_light + occlusion_spot +) + +foreach(scene_module IN LISTS scene_modules) + file(GLOB_RECURSE scene_module_src "src/scene_module/${scene_module}/*") + list(APPEND scene_modules_src ${scene_module_src}) +endforeach() - -# Common -ament_auto_add_library(scene_module_lib SHARED +ament_auto_add_library(behavior_velocity_planner SHARED + src/node.cpp + src/planner_manager.cpp src/utilization/path_utilization.cpp src/utilization/util.cpp + ${scene_modules_src} ) -target_include_directories(scene_module_lib +target_include_directories(behavior_velocity_planner SYSTEM PUBLIC ${BOOST_INCLUDE_DIRS} - ${tf2_geometry_msgs_INCLUDE_DIRS} -) - -target_include_directories(scene_module_lib - PUBLIC - $ - $ -) - -target_include_directories(scene_module_lib - SYSTEM PUBLIC ${PCL_INCLUDE_DIRS} -) - -ament_target_dependencies(scene_module_lib ${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - -# Scene Module: Stop Line -ament_auto_add_library(scene_module_stop_line SHARED - src/scene_module/stop_line/manager.cpp - src/scene_module/stop_line/scene.cpp - src/scene_module/stop_line/debug.cpp -) - -target_include_directories(scene_module_stop_line - PUBLIC - $ - $ -) - -ament_target_dependencies(scene_module_stop_line ${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - -target_link_libraries(scene_module_stop_line scene_module_lib) - -# Scene Module: Crosswalk -ament_auto_add_library(scene_module_crosswalk SHARED - src/scene_module/crosswalk/manager.cpp - src/scene_module/crosswalk/scene_crosswalk.cpp - src/scene_module/crosswalk/scene_walkway.cpp - src/scene_module/crosswalk/debug.cpp - src/scene_module/crosswalk/util.cpp -) - -target_include_directories(scene_module_crosswalk - PUBLIC - $ - $ -) - -ament_target_dependencies(scene_module_crosswalk ${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - -target_link_libraries(scene_module_crosswalk scene_module_lib) - -# Scene Module: Intersection -ament_auto_add_library(scene_module_intersection SHARED - src/scene_module/intersection/manager.cpp - src/scene_module/intersection/scene_intersection.cpp - src/scene_module/intersection/scene_merge_from_private_road.cpp - src/scene_module/intersection/debug.cpp - src/scene_module/intersection/util.cpp -) - -target_include_directories(scene_module_intersection - PUBLIC - $ - $ -) - -ament_target_dependencies(scene_module_intersection ${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - -target_link_libraries(scene_module_intersection scene_module_lib) - -# Scene Module: Traffic Light -ament_auto_add_library(scene_module_traffic_light SHARED - src/scene_module/traffic_light/manager.cpp - src/scene_module/traffic_light/scene.cpp - src/scene_module/traffic_light/debug.cpp -) - -target_include_directories(scene_module_traffic_light - PUBLIC - $ - $ -) - -ament_target_dependencies(scene_module_traffic_light ${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - -target_link_libraries(scene_module_traffic_light scene_module_lib) - -# Scene Module: Blind Spot -ament_auto_add_library(scene_module_blind_spot SHARED - src/scene_module/blind_spot/manager.cpp - src/scene_module/blind_spot/scene.cpp - src/scene_module/blind_spot/debug.cpp -) - -target_include_directories(scene_module_blind_spot - PUBLIC - $ - $ -) - -ament_target_dependencies(scene_module_blind_spot ${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - -target_link_libraries(scene_module_blind_spot scene_module_lib) - -# Scene Module: Detection Area -ament_auto_add_library(scene_module_detection_area SHARED - src/scene_module/detection_area/manager.cpp - src/scene_module/detection_area/scene.cpp - src/scene_module/detection_area/debug.cpp -) - -target_include_directories(scene_module_detection_area - PUBLIC - $ - $ -) - -ament_target_dependencies(scene_module_detection_area ${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - -target_link_libraries(scene_module_detection_area scene_module_lib) - -# Scene Module: No Stopping Area -ament_auto_add_library(scene_module_no_stopping_area SHARED - src/scene_module/no_stopping_area/manager.cpp - src/scene_module/no_stopping_area/scene_no_stopping_area.cpp - src/scene_module/no_stopping_area/debug.cpp -) - -target_include_directories(scene_module_no_stopping_area - PUBLIC - $ - $ -) - -ament_target_dependencies(scene_module_no_stopping_area ${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - -target_link_libraries(scene_module_no_stopping_area scene_module_lib) - -# Scene Module: Virtual Traffic Light -ament_auto_add_library(scene_module_virtual_traffic_light SHARED - src/scene_module/virtual_traffic_light/manager.cpp - src/scene_module/virtual_traffic_light/scene.cpp - src/scene_module/virtual_traffic_light/debug.cpp -) - -target_include_directories(scene_module_virtual_traffic_light - PUBLIC - $ - $ -) - -ament_target_dependencies(scene_module_virtual_traffic_light ${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - -target_link_libraries(scene_module_virtual_traffic_light scene_module_lib) - -# SceneModule OcclusionSpot -# Util -ament_auto_add_library(occlusion_spot_lib SHARED - src/scene_module/occlusion_spot/grid_utils.cpp - src/scene_module/occlusion_spot/occlusion_spot_utils.cpp - src/scene_module/occlusion_spot/risk_predictive_braking.cpp -) - -target_include_directories(occlusion_spot_lib - SYSTEM PUBLIC - ${BOOST_INCLUDE_DIRS} ${tf2_geometry_msgs_INCLUDE_DIRS} ) -target_include_directories(occlusion_spot_lib - PUBLIC - $ - $ -) - -ament_target_dependencies(occlusion_spot_lib ${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - -ament_auto_add_library(scene_module_occlusion_spot SHARED - src/scene_module/occlusion_spot/manager.cpp - src/scene_module/occlusion_spot/debug.cpp - src/scene_module/occlusion_spot/scene_occlusion_spot.cpp -) - -target_include_directories(scene_module_occlusion_spot - PUBLIC - $ - $ -) - -ament_target_dependencies(scene_module_occlusion_spot ${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - -target_link_libraries(scene_module_occlusion_spot scene_module_lib occlusion_spot_lib) - -# Scene Module Manager -ament_auto_add_library(scene_module_manager SHARED - src/planner_manager.cpp -) - -target_include_directories(scene_module_manager - PUBLIC - $ - $ -) - -ament_target_dependencies(scene_module_manager ${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - -target_link_libraries(scene_module_manager scene_module_lib) - -# Node -ament_auto_add_library(behavior_velocity_planner SHARED - src/node.cpp -) - -target_include_directories(behavior_velocity_planner - PUBLIC - $ - $ -) - -ament_target_dependencies(behavior_velocity_planner ${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - -target_link_libraries(behavior_velocity_planner - scene_module_lib - scene_module_stop_line - scene_module_crosswalk - scene_module_intersection - scene_module_traffic_light - scene_module_blind_spot - scene_module_occlusion_spot - scene_module_detection_area - scene_module_no_stopping_area - scene_module_virtual_traffic_light - scene_module_manager +ament_target_dependencies(behavior_velocity_planner + Boost + Eigen3 + PCL ) -ament_export_dependencies(${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES}) - rclcpp_components_register_node(behavior_velocity_planner PLUGIN "behavior_velocity_planner::BehaviorVelocityPlannerNode" EXECUTABLE behavior_velocity_planner_node ) - if(BUILD_TESTING) - # utils for test - ament_auto_add_library(utilization SHARED - src/utilization/util.cpp - ) - # Gtest for utilization ament_add_gtest(utilization-test test/src/test_state_machine.cpp @@ -305,7 +63,7 @@ if(BUILD_TESTING) ) target_link_libraries(utilization-test gtest_main - utilization + behavior_velocity_planner ) # Gtest for occlusion spot @@ -316,7 +74,7 @@ if(BUILD_TESTING) ) target_link_libraries(occlusion_spot-test gtest_main - scene_module_occlusion_spot + behavior_velocity_planner ) endif() From de8deed8e45177298fe34fbdbf46f7aafead7316 Mon Sep 17 00:00:00 2001 From: Shark <71419791+Sharrrrk@users.noreply.github.com> Date: Mon, 9 May 2022 11:31:50 +0800 Subject: [PATCH 03/55] fix(system_monitor): fix build error on tegra platform (#869) * fix(system_monitor): fix build error on tegra platform Signed-off-by: Shark Liu * ci(pre-commit): autofix * Update system/system_monitor/src/gpu_monitor/tegra_gpu_monitor.cpp Co-authored-by: Shark Liu Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> --- system/system_monitor/src/gpu_monitor/tegra_gpu_monitor.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/system/system_monitor/src/gpu_monitor/tegra_gpu_monitor.cpp b/system/system_monitor/src/gpu_monitor/tegra_gpu_monitor.cpp index a9ae72321efd..8da0d071de58 100644 --- a/system/system_monitor/src/gpu_monitor/tegra_gpu_monitor.cpp +++ b/system/system_monitor/src/gpu_monitor/tegra_gpu_monitor.cpp @@ -127,8 +127,10 @@ void GPUMonitor::checkUsage(diagnostic_updater::DiagnosticStatusWrapper & stat) } } -void GPUMonitor::checkThrottling(diagnostic_updater::DiagnosticStatusWrapper & stat) +void GPUMonitor::checkThrottling( + [[maybe_unused]] diagnostic_updater::DiagnosticStatusWrapper & stat) { + // Please remove the [[maybe_unused]] tag after implementation, it's a temp build fix // TODO(Fumihito Ito): implement me } From 391ebac4ebf8aeae386c2726929cdb1b334e0b7c Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 9 May 2022 14:07:00 +0900 Subject: [PATCH 04/55] feat(ad_service_state_monitor): limit odometry buffer size (#514) * feat(ad_service_state_monitor): limit odometry buffer size 40 Signed-off-by: Takayuki Murooka * Update system/ad_service_state_monitor/src/ad_service_state_monitor_node/ad_service_state_monitor_node.cpp Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> * Update ad_service_state_monitor_node.cpp Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> --- .../ad_service_state_monitor_node.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/system/ad_service_state_monitor/src/ad_service_state_monitor_node/ad_service_state_monitor_node.cpp b/system/ad_service_state_monitor/src/ad_service_state_monitor_node/ad_service_state_monitor_node.cpp index e5a59692983c..076f8d3a9f39 100644 --- a/system/ad_service_state_monitor/src/ad_service_state_monitor_node/ad_service_state_monitor_node.cpp +++ b/system/ad_service_state_monitor/src/ad_service_state_monitor_node/ad_service_state_monitor_node.cpp @@ -120,6 +120,11 @@ void AutowareStateMonitorNode::onOdometry(const nav_msgs::msg::Odometry::ConstSh state_input_.odometry_buffer.pop_front(); } + + constexpr size_t odometry_buffer_size = 200; // 40Hz * 5sec + if (state_input_.odometry_buffer.size() > odometry_buffer_size) { + state_input_.odometry_buffer.pop_front(); + } } bool AutowareStateMonitorNode::onShutdownService( From 03baceaf573e2ece3e04f1f4e8b00ecea8558a2f Mon Sep 17 00:00:00 2001 From: Shintaro Tomie <58775300+Shin-kyoto@users.noreply.github.com> Date: Mon, 9 May 2022 17:53:57 +0900 Subject: [PATCH 05/55] docs: fix 404 error caused by typo in url (#871) * docs: fix 404 error caused by typo in url Signed-off-by: Shin-kyoto * docs: fix typo in url for yolov4 Signed-off-by: Shin-kyoto --- perception/tensorrt_yolo/README.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/perception/tensorrt_yolo/README.md b/perception/tensorrt_yolo/README.md index 5dfae272f143..5811fa88a6b7 100644 --- a/perception/tensorrt_yolo/README.md +++ b/perception/tensorrt_yolo/README.md @@ -72,15 +72,15 @@ This package includes multiple licenses. ### YOLOv4 -[YOLOv4](https://drive.google.com//uc?id=1vkNmSwcIpTkJ_-BrKhxtit0PBJeJYTVX "YOLOv4"): Converted from darknet [weight file](https://github.com/AlexeyAB/darknet/releases/download/darknet_yolo_v3_optimal/yolov4.weights "weight file") and [conf file](https://github.com/AlexeyAB/darknet/blob/master/cfg/yolov4.cfg "conf file"). +[YOLOv4](https://drive.google.com/uc?id=1vkNmSwcIpTkJ_-BrKhxtit0PBJeJYTVX "YOLOv4"): Converted from darknet [weight file](https://github.com/AlexeyAB/darknet/releases/download/darknet_yolo_v3_optimal/yolov4.weights "weight file") and [conf file](https://github.com/AlexeyAB/darknet/blob/master/cfg/yolov4.cfg "conf file"). ### YOLOv5 Refer to [this guide](https://github.com/ultralytics/yolov5/issues/251 "guide") -- [YOLOv5s](https://drive.google.com//uc?id=1CF21nQWigwCPTr5psQZXg6cBQIOYKbad "YOLOv5s") +- [YOLOv5s](https://drive.google.com/uc?id=1CF21nQWigwCPTr5psQZXg6cBQIOYKbad "YOLOv5s") -- [YOLOv5m](https://drive.google.com//uc?id=1a1h50KJH6slwmjKZpPlS-errukF-BrgG "YOLOv5m") +- [YOLOv5m](https://drive.google.com/uc?id=1a1h50KJH6slwmjKZpPlS-errukF-BrgG "YOLOv5m") - [YOLOv5l](https://drive.google.com/uc?id=1xO8S92Cq7qrmx93UHHyA7Cd7-dJsBDP8 "YOLOv5l") From 8b480545a8d9cdcc1f7bd59fc2d3c115011be9c1 Mon Sep 17 00:00:00 2001 From: storrrrrrrrm <103425473+storrrrrrrrm@users.noreply.github.com> Date: Mon, 9 May 2022 17:15:57 +0800 Subject: [PATCH 06/55] fix(image_projection_based_fusion): set imagebuffersize (#820) * fix: set imagebuffersize configured Signed-off-by: suchang * ci(pre-commit): autofix Co-authored-by: suchang Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../include/image_projection_based_fusion/debugger.hpp | 5 +++-- .../launch/roi_cluster_fusion.launch.xml | 2 ++ .../launch/roi_detected_object_fusion.launch.xml | 2 ++ perception/image_projection_based_fusion/src/debugger.cpp | 7 +++++-- .../image_projection_based_fusion/src/fusion_node.cpp | 4 +++- 5 files changed, 15 insertions(+), 5 deletions(-) diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/debugger.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/debugger.hpp index ff790894658e..9ecd336818b5 100644 --- a/perception/image_projection_based_fusion/include/image_projection_based_fusion/debugger.hpp +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/debugger.hpp @@ -38,7 +38,8 @@ using sensor_msgs::msg::RegionOfInterest; class Debugger { public: - explicit Debugger(rclcpp::Node * node_ptr, const std::size_t image_num); + explicit Debugger( + rclcpp::Node * node_ptr, const std::size_t image_num, const std::size_t image_buffer_size); void publishImage(const std::size_t image_id, const rclcpp::Time & stamp); @@ -57,7 +58,7 @@ class Debugger std::vector image_subs_; std::vector image_pubs_; std::vector> image_buffers_; - std::size_t image_buffer_size{5}; + std::size_t image_buffer_size_; }; } // namespace image_projection_based_fusion diff --git a/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml b/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml index 8fe94963ff8c..e5824dfcff97 100644 --- a/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml @@ -24,6 +24,7 @@ + @@ -70,6 +71,7 @@ + diff --git a/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml b/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml index f6466e6512a0..be981478e78a 100644 --- a/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml @@ -24,6 +24,7 @@ + @@ -70,6 +71,7 @@ + diff --git a/perception/image_projection_based_fusion/src/debugger.cpp b/perception/image_projection_based_fusion/src/debugger.cpp index e1254fc13630..0bcfb019d93d 100644 --- a/perception/image_projection_based_fusion/src/debugger.cpp +++ b/perception/image_projection_based_fusion/src/debugger.cpp @@ -34,9 +34,12 @@ void drawRoiOnImage( namespace image_projection_based_fusion { -Debugger::Debugger(rclcpp::Node * node_ptr, const std::size_t image_num) : node_ptr_(node_ptr) +Debugger::Debugger( + rclcpp::Node * node_ptr, const std::size_t image_num, const std::size_t image_buffer_size) +: node_ptr_(node_ptr) { image_buffers_.resize(image_num); + image_buffer_size_ = image_buffer_size; for (std::size_t img_i = 0; img_i < image_num; ++img_i) { auto sub = image_transport::create_subscription( node_ptr, "input/image_raw" + std::to_string(img_i), @@ -54,7 +57,7 @@ Debugger::Debugger(rclcpp::Node * node_ptr, const std::size_t image_num) : node_ auto pub = image_transport::create_publisher(node_ptr, "output/image_raw" + std::to_string(img_i)); image_pubs_.push_back(pub); - image_buffers_.at(img_i).set_capacity(image_buffer_size); + image_buffers_.at(img_i).set_capacity(image_buffer_size_); } } diff --git a/perception/image_projection_based_fusion/src/fusion_node.cpp b/perception/image_projection_based_fusion/src/fusion_node.cpp index 57ed245f67bd..5d33303ca1bf 100644 --- a/perception/image_projection_based_fusion/src/fusion_node.cpp +++ b/perception/image_projection_based_fusion/src/fusion_node.cpp @@ -127,7 +127,9 @@ FusionNode::FusionNode(const std::string & node_name, const rclcpp::NodeOpt // debugger if (declare_parameter("debug_mode", false)) { - debugger_ = std::make_shared(this, rois_number_); + std::size_t image_buffer_size = + static_cast(declare_parameter("image_buffer_size", 15)); + debugger_ = std::make_shared(this, rois_number_, image_buffer_size); } } From c88ae056364cde55edcd0219b215f33d96df1332 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Mon, 9 May 2022 19:18:23 +0900 Subject: [PATCH 07/55] chore(avoidance_module): fix spell check (#732) Signed-off-by: Muhammad Zulfaqar Azmi --- .../scene_module/avoidance/debug.hpp | 2 +- .../src/scene_module/avoidance/avoidance_module.cpp | 8 ++++---- .../src/scene_module/avoidance/debug.cpp | 2 +- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/debug.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/debug.hpp index edfb7d7f84d7..d3f8f8060678 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/debug.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/debug.hpp @@ -93,7 +93,7 @@ MarkerArray createPoseMarkerArray( MarkerArray makeOverhangToRoadShoulderMarkerArray( const behavior_path_planner::ObjectDataArray & objects); -MarkerArray createOvehangFurthestLineStringMarkerArray( +MarkerArray createOverhangFurthestLineStringMarkerArray( const lanelet::ConstLineStrings3d & linestrings, const std::string & ns, const double r, const double g, const double b); diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp index b03282c735ec..876e5fc3112c 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp @@ -1939,8 +1939,8 @@ void AvoidanceModule::modifyPathVelocityToPreventAccelerationOnAvoidance(Shifted std::sqrt(v0 * v0 + 2.0 * s * parameters_.max_avoidance_acceleration)); // apply velocity limit - constexpr size_t VLIM_APPLY_IDX_MARGIN = 0; - for (size_t i = ego_idx + VLIM_APPLY_IDX_MARGIN; i < N; ++i) { + constexpr size_t V_LIM_APPLY_IDX_MARGIN = 0; + for (size_t i = ego_idx + V_LIM_APPLY_IDX_MARGIN; i < N; ++i) { path.path.points.at(i).point.longitudinal_velocity_mps = std::min(path.path.points.at(i).point.longitudinal_velocity_mps, static_cast(vmax)); } @@ -2619,7 +2619,7 @@ void AvoidanceModule::setDebugData(const PathShifter & shifter, const DebugData using marker_utils::createAvoidPointMarkerArray; using marker_utils::createLaneletsAreaMarkerArray; using marker_utils::createObjectsMarkerArray; - using marker_utils::createOvehangFurthestLineStringMarkerArray; + using marker_utils::createOverhangFurthestLineStringMarkerArray; using marker_utils::createPathMarkerArray; using marker_utils::createPoseMarkerArray; using marker_utils::createShiftLengthMarkerArray; @@ -2652,7 +2652,7 @@ void AvoidanceModule::setDebugData(const PathShifter & shifter, const DebugData add(createLaneletsAreaMarkerArray(*debug.expanded_lanelets, "expanded_lanelet", 0.8, 0.8, 0.0)); add(createAvoidanceObjectsMarkerArray(avoidance_data_.objects, "avoidance_object")); add(makeOverhangToRoadShoulderMarkerArray(avoidance_data_.objects)); - add(createOvehangFurthestLineStringMarkerArray( + add(createOverhangFurthestLineStringMarkerArray( *debug.farthest_linestring_from_overhang, "farthest_linestring_from_overhang", 1.0, 0.0, 1.0)); // parent object info diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/debug.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/debug.cpp index d7c3b1325f7d..88c8d102bd00 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/debug.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/debug.cpp @@ -512,7 +512,7 @@ MarkerArray makeOverhangToRoadShoulderMarkerArray( return msg; } -MarkerArray createOvehangFurthestLineStringMarkerArray( +MarkerArray createOverhangFurthestLineStringMarkerArray( const lanelet::ConstLineStrings3d & linestrings, const std::string & ns, const double r, const double g, const double b) { From 13d3b6d0fb464d24e77679a3c1575452713c4c13 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Mon, 9 May 2022 21:08:53 +0900 Subject: [PATCH 08/55] feat: isolate gtests in all packages (#693) Signed-off-by: Maxime CLEMENT --- common/autoware_auto_common/CMakeLists.txt | 2 +- common/autoware_auto_common/package.xml | 2 +- common/autoware_auto_geometry/CMakeLists.txt | 2 +- common/autoware_auto_geometry/package.xml | 2 +- common/autoware_auto_tf2/CMakeLists.txt | 2 +- common/autoware_auto_tf2/package.xml | 2 +- common/autoware_point_types/CMakeLists.txt | 2 +- common/autoware_point_types/package.xml | 2 +- common/fake_test_node/CMakeLists.txt | 2 +- common/fake_test_node/package.xml | 2 +- common/had_map_utils/package.xml | 2 +- common/interpolation/CMakeLists.txt | 2 +- common/interpolation/package.xml | 2 +- common/motion_testing/CMakeLists.txt | 2 +- common/motion_testing/package.xml | 2 +- common/osqp_interface/CMakeLists.txt | 2 +- common/osqp_interface/package.xml | 2 +- common/signal_processing/CMakeLists.txt | 2 +- common/signal_processing/package.xml | 2 +- common/tier4_api_utils/CMakeLists.txt | 2 +- common/tier4_api_utils/package.xml | 2 +- common/tier4_autoware_utils/CMakeLists.txt | 4 ++-- common/tier4_autoware_utils/package.xml | 2 +- common/time_utils/package.xml | 2 +- common/vehicle_constants_manager/CMakeLists.txt | 2 +- common/vehicle_constants_manager/package.xml | 2 +- control/trajectory_follower/CMakeLists.txt | 4 ++-- control/trajectory_follower/package.xml | 2 +- control/vehicle_cmd_gate/CMakeLists.txt | 2 +- control/vehicle_cmd_gate/package.xml | 2 +- localization/ekf_localizer/CMakeLists.txt | 4 ++-- localization/ekf_localizer/package.xml | 2 +- localization/stop_filter/package.xml | 2 +- map/lanelet2_extension/CMakeLists.txt | 10 +++++----- map/lanelet2_extension/package.xml | 2 +- .../detected_object_feature_remover/package.xml | 2 +- planning/behavior_velocity_planner/CMakeLists.txt | 4 ++-- planning/behavior_velocity_planner/package.xml | 2 +- planning/costmap_generator/CMakeLists.txt | 2 +- planning/costmap_generator/package.xml | 2 +- .../freespace_planning_algorithms/CMakeLists.txt | 4 ++-- planning/freespace_planning_algorithms/package.xml | 2 +- planning/planning_error_monitor/CMakeLists.txt | 2 +- planning/planning_error_monitor/package.xml | 2 +- planning/planning_evaluator/CMakeLists.txt | 2 +- planning/planning_evaluator/package.xml | 2 +- .../dummy_perception_publisher/CMakeLists.txt | 2 +- simulator/dummy_perception_publisher/package.xml | 1 + simulator/fault_injection/CMakeLists.txt | 2 +- simulator/fault_injection/package.xml | 2 +- simulator/simple_planning_simulator/CMakeLists.txt | 2 +- simulator/simple_planning_simulator/package.xml | 2 +- system/system_monitor/CMakeLists.txt | 14 +++++++------- system/system_monitor/package.xml | 2 +- vehicle/raw_vehicle_cmd_converter/CMakeLists.txt | 2 +- vehicle/raw_vehicle_cmd_converter/package.xml | 2 +- 56 files changed, 71 insertions(+), 70 deletions(-) diff --git a/common/autoware_auto_common/CMakeLists.txt b/common/autoware_auto_common/CMakeLists.txt index 4f7846c89eb7..b0957ad72685 100644 --- a/common/autoware_auto_common/CMakeLists.txt +++ b/common/autoware_auto_common/CMakeLists.txt @@ -9,7 +9,7 @@ include_directories(SYSTEM ${EIGEN3_INCLUDE_DIR}) if(BUILD_TESTING) set(TEST_COMMON test_common_gtest) - ament_add_gtest(${TEST_COMMON} + ament_add_ros_isolated_gtest(${TEST_COMMON} test/gtest_main.cpp test/test_bool_comparisons.cpp test/test_byte_reader.cpp diff --git a/common/autoware_auto_common/package.xml b/common/autoware_auto_common/package.xml index dca22e9b29ea..17d666e2273e 100644 --- a/common/autoware_auto_common/package.xml +++ b/common/autoware_auto_common/package.xml @@ -14,7 +14,7 @@ builtin_interfaces eigen - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common geometry_msgs diff --git a/common/autoware_auto_geometry/CMakeLists.txt b/common/autoware_auto_geometry/CMakeLists.txt index 0e964e3b064a..454e0e7ef044 100644 --- a/common/autoware_auto_geometry/CMakeLists.txt +++ b/common/autoware_auto_geometry/CMakeLists.txt @@ -23,7 +23,7 @@ if(BUILD_TESTING) test/src/test_common_2d.cpp test/src/test_intersection.cpp ) - ament_add_gtest(${GEOMETRY_GTEST} ${GEOMETRY_SRC}) + ament_add_ros_isolated_gtest(${GEOMETRY_GTEST} ${GEOMETRY_SRC}) target_compile_options(${GEOMETRY_GTEST} PRIVATE -Wno-conversion -Wno-sign-conversion) target_include_directories(${GEOMETRY_GTEST} PRIVATE "test/include" "include") ament_target_dependencies(${GEOMETRY_GTEST} diff --git a/common/autoware_auto_geometry/package.xml b/common/autoware_auto_geometry/package.xml index 976cf5901337..e19ac4897aab 100644 --- a/common/autoware_auto_geometry/package.xml +++ b/common/autoware_auto_geometry/package.xml @@ -18,7 +18,7 @@ autoware_auto_vehicle_msgs geometry_msgs - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common osrf_testing_tools_cpp diff --git a/common/autoware_auto_tf2/CMakeLists.txt b/common/autoware_auto_tf2/CMakeLists.txt index f4b3223391a7..a8ae9ec2d962 100755 --- a/common/autoware_auto_tf2/CMakeLists.txt +++ b/common/autoware_auto_tf2/CMakeLists.txt @@ -5,7 +5,7 @@ find_package(autoware_cmake REQUIRED) autoware_package() if(BUILD_TESTING) - ament_add_gtest(test_tf2_autoware_auto_msgs test/test_tf2_autoware_auto_msgs.cpp) + ament_add_ros_isolated_gtest(test_tf2_autoware_auto_msgs test/test_tf2_autoware_auto_msgs.cpp) target_include_directories(test_tf2_autoware_auto_msgs PRIVATE "include") ament_target_dependencies(test_tf2_autoware_auto_msgs "autoware_auto_common" diff --git a/common/autoware_auto_tf2/package.xml b/common/autoware_auto_tf2/package.xml index d6fbd4f4ce3d..c80ce45a217a 100644 --- a/common/autoware_auto_tf2/package.xml +++ b/common/autoware_auto_tf2/package.xml @@ -20,7 +20,7 @@ tf2_geometry_msgs tf2_ros - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/common/autoware_point_types/CMakeLists.txt b/common/autoware_point_types/CMakeLists.txt index e46081c5ea96..c149f79dab71 100644 --- a/common/autoware_point_types/CMakeLists.txt +++ b/common/autoware_point_types/CMakeLists.txt @@ -11,7 +11,7 @@ include_directories( ) if(BUILD_TESTING) - ament_add_gtest(test_autoware_point_types + ament_add_ros_isolated_gtest(test_autoware_point_types test/test_point_types.cpp ) target_include_directories(test_autoware_point_types diff --git a/common/autoware_point_types/package.xml b/common/autoware_point_types/package.xml index b7449dbbd13d..8829bd7538d9 100644 --- a/common/autoware_point_types/package.xml +++ b/common/autoware_point_types/package.xml @@ -23,7 +23,7 @@ pcl_ros point_cloud_msg_wrapper - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common point_cloud_msg_wrapper diff --git a/common/fake_test_node/CMakeLists.txt b/common/fake_test_node/CMakeLists.txt index cc80077163ab..8ad71df2777f 100644 --- a/common/fake_test_node/CMakeLists.txt +++ b/common/fake_test_node/CMakeLists.txt @@ -7,7 +7,7 @@ autoware_package() ament_auto_add_library(fake_test_node SHARED src/fake_test_node.cpp) if(BUILD_TESTING) - ament_add_gtest(test_fake_test_node + ament_add_ros_isolated_gtest(test_fake_test_node test/test_fake_test_node.cpp ) add_dependencies(test_fake_test_node fake_test_node) diff --git a/common/fake_test_node/package.xml b/common/fake_test_node/package.xml index 6d337906ff3b..8e919d719fc6 100644 --- a/common/fake_test_node/package.xml +++ b/common/fake_test_node/package.xml @@ -11,7 +11,7 @@ autoware_cmake - ament_cmake_gtest + ament_cmake_ros autoware_auto_common rclcpp rclcpp_components diff --git a/common/had_map_utils/package.xml b/common/had_map_utils/package.xml index 2baa56aa12c7..aa7f7a9e7884 100644 --- a/common/had_map_utils/package.xml +++ b/common/had_map_utils/package.xml @@ -23,7 +23,7 @@ lanelet2_io visualization_msgs - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/common/interpolation/CMakeLists.txt b/common/interpolation/CMakeLists.txt index bca79e0f23d9..7afed6fe57c4 100644 --- a/common/interpolation/CMakeLists.txt +++ b/common/interpolation/CMakeLists.txt @@ -13,7 +13,7 @@ ament_auto_add_library(interpolation SHARED if(BUILD_TESTING) file(GLOB_RECURSE test_files test/**/*.cpp) - ament_add_gtest(test_interpolation ${test_files}) + ament_add_ros_isolated_gtest(test_interpolation ${test_files}) target_link_libraries(test_interpolation interpolation diff --git a/common/interpolation/package.xml b/common/interpolation/package.xml index 213616b007a1..665e26bab9a0 100644 --- a/common/interpolation/package.xml +++ b/common/interpolation/package.xml @@ -14,7 +14,7 @@ tier4_autoware_utils - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/common/motion_testing/CMakeLists.txt b/common/motion_testing/CMakeLists.txt index 4e7006978ab2..f8428c0df709 100644 --- a/common/motion_testing/CMakeLists.txt +++ b/common/motion_testing/CMakeLists.txt @@ -7,7 +7,7 @@ autoware_package() ament_auto_add_library(${PROJECT_NAME} SHARED src/motion_testing/motion_testing.cpp) if(BUILD_TESTING) - ament_add_gtest(motion_testing_unit_tests + ament_add_ros_isolated_gtest(motion_testing_unit_tests test/gtest_main.cpp test/constant_trajectory.cpp test/trajectory_checks.cpp) diff --git a/common/motion_testing/package.xml b/common/motion_testing/package.xml index 33e7b4798d0e..f292a7e5bb54 100644 --- a/common/motion_testing/package.xml +++ b/common/motion_testing/package.xml @@ -19,7 +19,7 @@ autoware_auto_planning_msgs autoware_auto_vehicle_msgs - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/common/osqp_interface/CMakeLists.txt b/common/osqp_interface/CMakeLists.txt index 4180461cc261..996f8b6153cf 100644 --- a/common/osqp_interface/CMakeLists.txt +++ b/common/osqp_interface/CMakeLists.txt @@ -49,7 +49,7 @@ if(BUILD_TESTING) test/test_csc_matrix_conv.cpp ) set(TEST_OSQP_INTERFACE_EXE test_osqp_interface) - ament_add_gtest(${TEST_OSQP_INTERFACE_EXE} ${TEST_SOURCES}) + ament_add_ros_isolated_gtest(${TEST_OSQP_INTERFACE_EXE} ${TEST_SOURCES}) target_link_libraries(${TEST_OSQP_INTERFACE_EXE} ${PROJECT_NAME}) endif() diff --git a/common/osqp_interface/package.xml b/common/osqp_interface/package.xml index f89810ddda95..5260a3f2b07c 100644 --- a/common/osqp_interface/package.xml +++ b/common/osqp_interface/package.xml @@ -17,7 +17,7 @@ rclcpp rclcpp_components - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common eigen diff --git a/common/signal_processing/CMakeLists.txt b/common/signal_processing/CMakeLists.txt index e93023e703eb..93cb7aa225a0 100644 --- a/common/signal_processing/CMakeLists.txt +++ b/common/signal_processing/CMakeLists.txt @@ -9,7 +9,7 @@ ament_auto_add_library(lowpass_filter_1d SHARED ) if(BUILD_TESTING) - ament_add_gtest(test_signal_processing + ament_add_ros_isolated_gtest(test_signal_processing test/src/lowpass_filter_1d_test.cpp ) target_link_libraries(test_signal_processing diff --git a/common/signal_processing/package.xml b/common/signal_processing/package.xml index 563715af7724..867f2d05da60 100644 --- a/common/signal_processing/package.xml +++ b/common/signal_processing/package.xml @@ -12,7 +12,7 @@ ament_cmake_auto - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/common/tier4_api_utils/CMakeLists.txt b/common/tier4_api_utils/CMakeLists.txt index e65e538fe1df..4eda0296e520 100644 --- a/common/tier4_api_utils/CMakeLists.txt +++ b/common/tier4_api_utils/CMakeLists.txt @@ -6,7 +6,7 @@ autoware_package() if(BUILD_TESTING) include_directories(include) - ament_add_gtest(${PROJECT_NAME}_test test/test.cpp) + ament_add_ros_isolated_gtest(${PROJECT_NAME}_test test/test.cpp) ament_target_dependencies(${PROJECT_NAME}_test rclcpp tier4_external_api_msgs) endif() diff --git a/common/tier4_api_utils/package.xml b/common/tier4_api_utils/package.xml index 99a03ab92b0e..a8378b92352e 100644 --- a/common/tier4_api_utils/package.xml +++ b/common/tier4_api_utils/package.xml @@ -14,7 +14,7 @@ rclcpp tier4_external_api_msgs - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common rclcpp diff --git a/common/tier4_autoware_utils/CMakeLists.txt b/common/tier4_autoware_utils/CMakeLists.txt index eeca0a2d8363..7ba9c2020a36 100644 --- a/common/tier4_autoware_utils/CMakeLists.txt +++ b/common/tier4_autoware_utils/CMakeLists.txt @@ -12,11 +12,11 @@ ament_auto_add_library(tier4_autoware_utils SHARED ) if(BUILD_TESTING) - find_package(ament_cmake_gtest REQUIRED) + find_package(ament_cmake_ros REQUIRED) file(GLOB_RECURSE test_files test/**/*.cpp) - ament_add_gtest(test_tier4_autoware_utils ${test_files}) + ament_add_ros_isolated_gtest(test_tier4_autoware_utils ${test_files}) target_link_libraries(test_tier4_autoware_utils tier4_autoware_utils diff --git a/common/tier4_autoware_utils/package.xml b/common/tier4_autoware_utils/package.xml index f1bd523a8eda..63fd56ae09f8 100644 --- a/common/tier4_autoware_utils/package.xml +++ b/common/tier4_autoware_utils/package.xml @@ -23,7 +23,7 @@ tier4_debug_msgs visualization_msgs - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/common/time_utils/package.xml b/common/time_utils/package.xml index 9b553289e09b..a248e72f125f 100644 --- a/common/time_utils/package.xml +++ b/common/time_utils/package.xml @@ -12,7 +12,7 @@ autoware_cmake builtin_interfaces - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/common/vehicle_constants_manager/CMakeLists.txt b/common/vehicle_constants_manager/CMakeLists.txt index eb5f7b27663e..1e84c5f781d3 100644 --- a/common/vehicle_constants_manager/CMakeLists.txt +++ b/common/vehicle_constants_manager/CMakeLists.txt @@ -18,7 +18,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED # if(BUILD_TESTING) # set(TEST_SOURCES test/test_vehicle_constants_manager.cpp) # set(TEST_VEHICLE_CONSTANTS_MANAGER_EXE test_vehicle_constants_manager) -# ament_add_gtest(${TEST_VEHICLE_CONSTANTS_MANAGER_EXE} ${TEST_SOURCES}) +# ament_add_ros_isolated_gtest(${TEST_VEHICLE_CONSTANTS_MANAGER_EXE} ${TEST_SOURCES}) # target_link_libraries(${TEST_VEHICLE_CONSTANTS_MANAGER_EXE} ${PROJECT_NAME}) # endif() diff --git a/common/vehicle_constants_manager/package.xml b/common/vehicle_constants_manager/package.xml index eecb3e8f2108..8041ae90a2cb 100644 --- a/common/vehicle_constants_manager/package.xml +++ b/common/vehicle_constants_manager/package.xml @@ -15,7 +15,7 @@ rclcpp rclcpp_components - ament_cmake_gtest + ament_cmake_ros ament_cmake diff --git a/control/trajectory_follower/CMakeLists.txt b/control/trajectory_follower/CMakeLists.txt index 5c2961729678..67d157df835d 100644 --- a/control/trajectory_follower/CMakeLists.txt +++ b/control/trajectory_follower/CMakeLists.txt @@ -72,7 +72,7 @@ if(BUILD_TESTING) test/test_lowpass_filter.cpp ) set(TEST_LATERAL_CONTROLLER_EXE test_lateral_controller) - ament_add_gtest(${TEST_LATERAL_CONTROLLER_EXE} ${TEST_LAT_SOURCES}) + ament_add_ros_isolated_gtest(${TEST_LATERAL_CONTROLLER_EXE} ${TEST_LAT_SOURCES}) target_link_libraries(${TEST_LATERAL_CONTROLLER_EXE} ${LATERAL_CONTROLLER_LIB}) set(TEST_LON_SOURCES @@ -82,7 +82,7 @@ if(BUILD_TESTING) test/test_longitudinal_controller_utils.cpp ) set(TEST_LONGITUDINAL_CONTROLLER_EXE test_longitudinal_controller) - ament_add_gtest(${TEST_LONGITUDINAL_CONTROLLER_EXE} ${TEST_LON_SOURCES}) + ament_add_ros_isolated_gtest(${TEST_LONGITUDINAL_CONTROLLER_EXE} ${TEST_LON_SOURCES}) target_link_libraries(${TEST_LONGITUDINAL_CONTROLLER_EXE} ${LONGITUDINAL_CONTROLLER_LIB}) endif() diff --git a/control/trajectory_follower/package.xml b/control/trajectory_follower/package.xml index 4bc005335f4a..840cad74aeb5 100644 --- a/control/trajectory_follower/package.xml +++ b/control/trajectory_follower/package.xml @@ -28,7 +28,7 @@ tf2 tf2_ros - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common eigen diff --git a/control/vehicle_cmd_gate/CMakeLists.txt b/control/vehicle_cmd_gate/CMakeLists.txt index 886842aa7f63..309a296acc9d 100644 --- a/control/vehicle_cmd_gate/CMakeLists.txt +++ b/control/vehicle_cmd_gate/CMakeLists.txt @@ -15,7 +15,7 @@ rclcpp_components_register_node(vehicle_cmd_gate_node ) if(BUILD_TESTING) - ament_add_gtest(test_vehicle_cmd_gate + ament_add_ros_isolated_gtest(test_vehicle_cmd_gate test/src/test_main.cpp test/src/test_vehicle_cmd_filter.cpp ) diff --git a/control/vehicle_cmd_gate/package.xml b/control/vehicle_cmd_gate/package.xml index cb30c913ad76..7cb8b18244d1 100644 --- a/control/vehicle_cmd_gate/package.xml +++ b/control/vehicle_cmd_gate/package.xml @@ -26,7 +26,7 @@ tier4_vehicle_msgs vehicle_info_util - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/localization/ekf_localizer/CMakeLists.txt b/localization/ekf_localizer/CMakeLists.txt index fa894c8a7b1a..3a3edd5338a5 100644 --- a/localization/ekf_localizer/CMakeLists.txt +++ b/localization/ekf_localizer/CMakeLists.txt @@ -13,8 +13,8 @@ ament_auto_add_executable(ekf_localizer ament_target_dependencies(ekf_localizer kalman_filter) # if(BUILD_TESTING) -# find_package(ament_cmake_gtest REQUIRED) -# ament_add_gtest(ekf_localizer-test test/test_ekf_localizer.test +# find_package(ament_cmake_ros REQUIRED) +# ament_add_ros_isolated_gtest(ekf_localizer-test test/test_ekf_localizer.test # test/src/test_ekf_localizer.cpp # src/ekf_localizer.cpp # src/kalman_filter/kalman_filter.cpp diff --git a/localization/ekf_localizer/package.xml b/localization/ekf_localizer/package.xml index c67cfaa400a0..3e9d9735ae3b 100644 --- a/localization/ekf_localizer/package.xml +++ b/localization/ekf_localizer/package.xml @@ -24,7 +24,7 @@ tier4_autoware_utils tier4_debug_msgs - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/localization/stop_filter/package.xml b/localization/stop_filter/package.xml index b4b948c236af..47fcf3282efe 100644 --- a/localization/stop_filter/package.xml +++ b/localization/stop_filter/package.xml @@ -17,7 +17,7 @@ tf2 tier4_debug_msgs - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/map/lanelet2_extension/CMakeLists.txt b/map/lanelet2_extension/CMakeLists.txt index d256029e4041..709c7bdaa685 100644 --- a/map/lanelet2_extension/CMakeLists.txt +++ b/map/lanelet2_extension/CMakeLists.txt @@ -62,15 +62,15 @@ target_link_libraries(autoware_lanelet2_validation ) if(BUILD_TESTING) - ament_add_gtest(message_conversion-test test/src/test_message_conversion.cpp) + ament_add_ros_isolated_gtest(message_conversion-test test/src/test_message_conversion.cpp) target_link_libraries(message_conversion-test lanelet2_extension_lib) - ament_add_gtest(projector-test test/src/test_projector.cpp) + ament_add_ros_isolated_gtest(projector-test test/src/test_projector.cpp) target_link_libraries(projector-test lanelet2_extension_lib) - ament_add_gtest(query-test test/src/test_query.cpp) + ament_add_ros_isolated_gtest(query-test test/src/test_query.cpp) target_link_libraries(query-test lanelet2_extension_lib) - ament_add_gtest(regulatory_elements-test test/src/test_regulatory_elements.cpp) + ament_add_ros_isolated_gtest(regulatory_elements-test test/src/test_regulatory_elements.cpp) target_link_libraries(regulatory_elements-test lanelet2_extension_lib) - ament_add_gtest(utilities-test test/src/test_utilities.cpp) + ament_add_ros_isolated_gtest(utilities-test test/src/test_utilities.cpp) target_link_libraries(utilities-test lanelet2_extension_lib) endif() diff --git a/map/lanelet2_extension/package.xml b/map/lanelet2_extension/package.xml index e817b06f1be8..d46d05a7f306 100644 --- a/map/lanelet2_extension/package.xml +++ b/map/lanelet2_extension/package.xml @@ -27,7 +27,7 @@ tier4_autoware_utils visualization_msgs - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/perception/detected_object_feature_remover/package.xml b/perception/detected_object_feature_remover/package.xml index 686c01621c54..b609ff0257f1 100644 --- a/perception/detected_object_feature_remover/package.xml +++ b/perception/detected_object_feature_remover/package.xml @@ -16,7 +16,7 @@ rclcpp_components tier4_perception_msgs - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/planning/behavior_velocity_planner/CMakeLists.txt b/planning/behavior_velocity_planner/CMakeLists.txt index 47f6f999ecb0..6e9671c16651 100644 --- a/planning/behavior_velocity_planner/CMakeLists.txt +++ b/planning/behavior_velocity_planner/CMakeLists.txt @@ -56,7 +56,7 @@ rclcpp_components_register_node(behavior_velocity_planner if(BUILD_TESTING) # Gtest for utilization - ament_add_gtest(utilization-test + ament_add_ros_isolated_gtest(utilization-test test/src/test_state_machine.cpp test/src/test_arc_lane_util.cpp test/src/test_utilization.cpp @@ -67,7 +67,7 @@ if(BUILD_TESTING) ) # Gtest for occlusion spot - ament_add_gtest(occlusion_spot-test + ament_add_ros_isolated_gtest(occlusion_spot-test test/src/test_occlusion_spot_utils.cpp test/src/test_risk_predictive_braking.cpp test/src/test_grid_utils.cpp diff --git a/planning/behavior_velocity_planner/package.xml b/planning/behavior_velocity_planner/package.xml index a1f86fdf1941..16998b4f27f1 100644 --- a/planning/behavior_velocity_planner/package.xml +++ b/planning/behavior_velocity_planner/package.xml @@ -42,7 +42,7 @@ vehicle_info_util visualization_msgs - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/planning/costmap_generator/CMakeLists.txt b/planning/costmap_generator/CMakeLists.txt index a2c3f70b2f72..648d01ee4c4e 100644 --- a/planning/costmap_generator/CMakeLists.txt +++ b/planning/costmap_generator/CMakeLists.txt @@ -46,7 +46,7 @@ rclcpp_components_register_node(costmap_generator_node ) if(BUILD_TESTING) - find_package(ament_cmake_gtest REQUIRED) + find_package(ament_cmake_ros REQUIRED) endif() ament_auto_package(INSTALL_TO_SHARE launch) diff --git a/planning/costmap_generator/package.xml b/planning/costmap_generator/package.xml index 289e2be0197c..070c160d3aa0 100644 --- a/planning/costmap_generator/package.xml +++ b/planning/costmap_generator/package.xml @@ -29,7 +29,7 @@ tf2_ros tier4_planning_msgs - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/planning/freespace_planning_algorithms/CMakeLists.txt b/planning/freespace_planning_algorithms/CMakeLists.txt index 093eaffa23ba..a08e89143ef3 100644 --- a/planning/freespace_planning_algorithms/CMakeLists.txt +++ b/planning/freespace_planning_algorithms/CMakeLists.txt @@ -18,8 +18,8 @@ target_link_libraries(freespace_planning_algorithms ) if(BUILD_TESTING) - find_package(ament_cmake_gtest REQUIRED) - ament_add_gtest(freespace_planning_algorithms-test + find_package(ament_cmake_ros REQUIRED) + ament_add_ros_isolated_gtest(freespace_planning_algorithms-test test/src/test_freespace_planning_algorithms.cpp ) target_link_libraries(freespace_planning_algorithms-test diff --git a/planning/freespace_planning_algorithms/package.xml b/planning/freespace_planning_algorithms/package.xml index 72fc9d5a0dc4..db0ea35e9bb0 100644 --- a/planning/freespace_planning_algorithms/package.xml +++ b/planning/freespace_planning_algorithms/package.xml @@ -21,7 +21,7 @@ tf2_geometry_msgs tier4_autoware_utils - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/planning/planning_error_monitor/CMakeLists.txt b/planning/planning_error_monitor/CMakeLists.txt index 8bd30ea1fd00..66932c63e899 100644 --- a/planning/planning_error_monitor/CMakeLists.txt +++ b/planning/planning_error_monitor/CMakeLists.txt @@ -23,7 +23,7 @@ rclcpp_components_register_node(invalid_trajectory_publisher_node ) if(BUILD_TESTING) - ament_add_gtest(test_planning_error_monitor + ament_add_ros_isolated_gtest(test_planning_error_monitor test/src/test_main.cpp test/src/test_planning_error_monitor_functions.cpp test/src/test_planning_error_monitor_helper.hpp diff --git a/planning/planning_error_monitor/package.xml b/planning/planning_error_monitor/package.xml index b70e2f319cd0..e667c8179087 100644 --- a/planning/planning_error_monitor/package.xml +++ b/planning/planning_error_monitor/package.xml @@ -21,7 +21,7 @@ tier4_autoware_utils visualization_msgs - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/planning/planning_evaluator/CMakeLists.txt b/planning/planning_evaluator/CMakeLists.txt index 6641d08cc52a..6865f8eef700 100644 --- a/planning/planning_evaluator/CMakeLists.txt +++ b/planning/planning_evaluator/CMakeLists.txt @@ -26,7 +26,7 @@ rclcpp_components_register_node(${PROJECT_NAME}_node ) if(BUILD_TESTING) - ament_add_gtest(test_${PROJECT_NAME} + ament_add_ros_isolated_gtest(test_${PROJECT_NAME} test/test_planning_evaluator_node.cpp ) target_link_libraries(test_${PROJECT_NAME} diff --git a/planning/planning_evaluator/package.xml b/planning/planning_evaluator/package.xml index f7e1d5c3480d..8681543485c2 100644 --- a/planning/planning_evaluator/package.xml +++ b/planning/planning_evaluator/package.xml @@ -23,7 +23,7 @@ tf2_ros tier4_autoware_utils - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/simulator/dummy_perception_publisher/CMakeLists.txt b/simulator/dummy_perception_publisher/CMakeLists.txt index 85347b04b3be..63d07faf0634 100644 --- a/simulator/dummy_perception_publisher/CMakeLists.txt +++ b/simulator/dummy_perception_publisher/CMakeLists.txt @@ -74,7 +74,7 @@ ament_auto_add_executable(empty_objects_publisher ) if(BUILD_TESTING) - ament_add_gtest(signed_distance_function-test + ament_add_ros_isolated_gtest(signed_distance_function-test test/src/test_signed_distance_function.cpp ) target_link_libraries(signed_distance_function-test diff --git a/simulator/dummy_perception_publisher/package.xml b/simulator/dummy_perception_publisher/package.xml index e7ce4dc99c43..1635deda40a4 100644 --- a/simulator/dummy_perception_publisher/package.xml +++ b/simulator/dummy_perception_publisher/package.xml @@ -14,6 +14,7 @@ rosidl_default_runtime + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/simulator/fault_injection/CMakeLists.txt b/simulator/fault_injection/CMakeLists.txt index 7cd78e35aadd..0bc166341296 100644 --- a/simulator/fault_injection/CMakeLists.txt +++ b/simulator/fault_injection/CMakeLists.txt @@ -15,7 +15,7 @@ rclcpp_components_register_node(fault_injection_node_component if(BUILD_TESTING) # gtest - ament_add_gtest(test_fault_injection_node_component + ament_add_ros_isolated_gtest(test_fault_injection_node_component test/src/main.cpp test/src/test_diagnostic_storage.cpp ) diff --git a/simulator/fault_injection/package.xml b/simulator/fault_injection/package.xml index 961a0af1e585..95e50e644880 100644 --- a/simulator/fault_injection/package.xml +++ b/simulator/fault_injection/package.xml @@ -19,7 +19,7 @@ tier4_autoware_utils tier4_simulation_msgs - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common launch diff --git a/simulator/simple_planning_simulator/CMakeLists.txt b/simulator/simple_planning_simulator/CMakeLists.txt index d62a84e7d7b6..603469730405 100644 --- a/simulator/simple_planning_simulator/CMakeLists.txt +++ b/simulator/simple_planning_simulator/CMakeLists.txt @@ -28,7 +28,7 @@ rclcpp_components_register_node(${PROJECT_NAME} ) if(BUILD_TESTING) - ament_add_gtest(test_simple_planning_simulator + ament_add_ros_isolated_gtest(test_simple_planning_simulator test/test_simple_planning_simulator.cpp TIMEOUT 120 ) diff --git a/simulator/simple_planning_simulator/package.xml b/simulator/simple_planning_simulator/package.xml index 761aef0e322f..2c63c861039e 100644 --- a/simulator/simple_planning_simulator/package.xml +++ b/simulator/simple_planning_simulator/package.xml @@ -31,7 +31,7 @@ launch_ros - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/system/system_monitor/CMakeLists.txt b/system/system_monitor/CMakeLists.txt index 017e08393baa..65e933d07204 100644 --- a/system/system_monitor/CMakeLists.txt +++ b/system/system_monitor/CMakeLists.txt @@ -180,7 +180,7 @@ rclcpp_components_register_node(gpu_monitor_lib # TODO(yunus.caliskan): Port the tests to ROS2, robustify the tests. if(BUILD_TESTING) - # ament_add_gtest(test_cpu_monitor + # ament_add_ros_isolated_gtest(test_cpu_monitor # test/src/cpu_monitor/test_${CMAKE_CPU_PLATFORM}_cpu_monitor.cpp # ${CPU_MONITOR_SOURCE} # ) @@ -196,7 +196,7 @@ if(BUILD_TESTING) # target_link_libraries(test_cpu_monitor ${Boost_LIBRARIES} ${LIBRARIES}) - # ament_add_gtest(test_hdd_monitor + # ament_add_ros_isolated_gtest(test_hdd_monitor # test/src/hdd_monitor/test_hdd_monitor.cpp # src/hdd_monitor/hdd_monitor.cpp # ) @@ -213,7 +213,7 @@ if(BUILD_TESTING) # target_link_libraries(test_hdd_monitor ${Boost_LIBRARIES} ${LIBRARIES} # ) - # ament_add_gtest(test_mem_monitor + # ament_add_ros_isolated_gtest(test_mem_monitor # test/src/mem_monitor/test_mem_monitor.cpp # src/mem_monitor/mem_monitor.cpp # ) @@ -229,7 +229,7 @@ if(BUILD_TESTING) # target_link_libraries(test_mem_monitor ${Boost_LIBRARIES} ${LIBRARIES}) - # ament_add_gtest(test_net_monitor + # ament_add_ros_isolated_gtest(test_net_monitor # test/src/net_monitor/test_net_monitor.cpp # src/net_monitor/net_monitor.cpp # src/net_monitor/nl80211.cpp @@ -246,7 +246,7 @@ if(BUILD_TESTING) # target_link_libraries(test_net_monitor ${Boost_LIBRARIES} ${NL_LIBS} ${LIBRARIES}) - # ament_add_gtest(test_ntp_monitor + # ament_add_ros_isolated_gtest(test_ntp_monitor # test/src/ntp_monitor/test_ntp_monitor.cpp # src/ntp_monitor/ntp_monitor.cpp # ) @@ -262,7 +262,7 @@ if(BUILD_TESTING) # target_link_libraries(test_ntp_monitor ${Boost_LIBRARIES} ${LIBRARIES}) - # ament_add_gtest(test_process_monitor + # ament_add_ros_isolated_gtest(test_process_monitor # test/src/process_monitor/test_process_monitor.cpp # src/process_monitor/process_monitor.cpp # ) @@ -278,7 +278,7 @@ if(BUILD_TESTING) # target_link_libraries(test_process_monitor ${Boost_LIBRARIES} ${LIBRARIES}) - # ament_add_gtest(test_gpu_monitor + # ament_add_ros_isolated_gtest(test_gpu_monitor # test/src/gpu_monitor/test_${CMAKE_GPU_PLATFORM}_gpu_monitor.cpp # ${GPU_MONITOR_SOURCE} # ) diff --git a/system/system_monitor/package.xml b/system/system_monitor/package.xml index 8cca9d2c7154..559dc9c07259 100644 --- a/system/system_monitor/package.xml +++ b/system/system_monitor/package.xml @@ -23,7 +23,7 @@ chrony sysstat - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/vehicle/raw_vehicle_cmd_converter/CMakeLists.txt b/vehicle/raw_vehicle_cmd_converter/CMakeLists.txt index d85b418d6fcb..36b96a2a300c 100644 --- a/vehicle/raw_vehicle_cmd_converter/CMakeLists.txt +++ b/vehicle/raw_vehicle_cmd_converter/CMakeLists.txt @@ -28,7 +28,7 @@ if(BUILD_TESTING) test/test_raw_vehicle_cmd_converter.cpp ) set(TEST_RAW_VEHICLE_CMD_CONVERTER_EXE test_raw_vehicle_cmd_converter) - ament_add_gtest(${TEST_RAW_VEHICLE_CMD_CONVERTER_EXE} ${TEST_SOURCES}) + ament_add_ros_isolated_gtest(${TEST_RAW_VEHICLE_CMD_CONVERTER_EXE} ${TEST_SOURCES}) target_link_libraries(${TEST_RAW_VEHICLE_CMD_CONVERTER_EXE} actuation_map_converter raw_vehicle_cmd_converter_node_component) endif() diff --git a/vehicle/raw_vehicle_cmd_converter/package.xml b/vehicle/raw_vehicle_cmd_converter/package.xml index b14b00c9d396..4f36c95e5d82 100644 --- a/vehicle/raw_vehicle_cmd_converter/package.xml +++ b/vehicle/raw_vehicle_cmd_converter/package.xml @@ -26,7 +26,7 @@ rclpy - ament_cmake_gtest + ament_cmake_ros ament_lint_auto autoware_lint_common From d52721f6002782aa653a8d8f8a98b779221490b4 Mon Sep 17 00:00:00 2001 From: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Date: Tue, 10 May 2022 00:06:41 +0900 Subject: [PATCH 09/55] docs(virtual traffic light): add documentation (#245) * doc(behavior_velocity): add graph and fix link * doc(behavior_velocity): update virtual traffic light doc Signed-off-by: tanaka3 * doc(behavior_velocity): minor fix Signed-off-by: tanaka3 * doc : mediate to coordinate Signed-off-by: tanaka3 * doc: minor update Signed-off-by: tanaka3 * doc: fix pre-commit * doc: update docs Signed-off-by: tanaka3 * apply suggestion * doc: to intersection-coordination Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> --- planning/behavior_velocity_planner/README.md | 3 + ...iorVelocityPlanner-Architecture.drawio.svg | 1663 +++++++++++++++++ .../V2X_support_traffic_light.png | Bin 0 -> 91648 bytes .../intersection-coordination.png | Bin 0 -> 161821 bytes .../virtual-traffic-light-design.md | 267 +++ 5 files changed, 1933 insertions(+) create mode 100644 planning/behavior_velocity_planner/docs/BehaviorVelocityPlanner-Architecture.drawio.svg create mode 100644 planning/behavior_velocity_planner/docs/virtual_traffic_light/V2X_support_traffic_light.png create mode 100644 planning/behavior_velocity_planner/docs/virtual_traffic_light/intersection-coordination.png create mode 100644 planning/behavior_velocity_planner/virtual-traffic-light-design.md diff --git a/planning/behavior_velocity_planner/README.md b/planning/behavior_velocity_planner/README.md index a7feea30a301..20ad38140d33 100644 --- a/planning/behavior_velocity_planner/README.md +++ b/planning/behavior_velocity_planner/README.md @@ -5,12 +5,15 @@ `behavior_velocity_planner` is a planner that adjust velocity based on the traffic rules. It consists of several modules. Please refer to the links listed below for detail on each module. +![Architecture](./docs/BehaviorVelocityPlanner-Architecture.drawio.svg) + - [Blind Spot](blind-spot-design.md) - [Crosswalk](crosswalk-design.md) - [Detection Area](detection-area-design.md) - [Intersection](intersection-design.md) - [MergeFromPrivate](merge-from-private-design.md) - [Stop Line](stop-line-design.md) +- [Virtual Traffic Light](virtual-traffic-light-design.md) - [Traffic Light](traffic-light-design.md) - [Occlusion Spot](occlusion-spot-design.md) - [No Stopping Area](no-stopping-area-design.md) diff --git a/planning/behavior_velocity_planner/docs/BehaviorVelocityPlanner-Architecture.drawio.svg b/planning/behavior_velocity_planner/docs/BehaviorVelocityPlanner-Architecture.drawio.svg new file mode 100644 index 000000000000..4d2808a5be41 --- /dev/null +++ b/planning/behavior_velocity_planner/docs/BehaviorVelocityPlanner-Architecture.drawio.svg @@ -0,0 +1,1663 @@ + + + + + + + + +
+
+
+ /perception/occupancy_grid_map/map +
+
+
+
+ + /per... + +
+
+ + + + + + Blind Spot + + + + + + +
+
+
+ updateSceneModuleInstance +
+
+
+
+
+ + updateSceneModuleInstance + +
+
+ + + + + +
+
+
+ + add/delete modules + +
+
+
+
+ + add/delete modules + +
+
+ + + + +
+
+
+ modifyPathVelocity +
+
+
+
+ + modifyPathVelocity + +
+
+ + + + +
+
+
+ + scene_modules + +
+
+
+
+ + scene_modules + +
+
+ + + + +
+
+
+ Turn RIght +
+
+
+
+ + Turn RIght + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + + + +
+
+
+ Turn Left +
+
+
+
+ + Turn Left + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + + + Occlusion Spot + + + + + + +
+
+
+ updateSceneModuleInstance +
+
+
+
+
+ + updateSceneModuleInstance + +
+
+ + + + + +
+
+
+ + add/delete modules + +
+
+
+
+ + add/delete modules + +
+
+ + + + +
+
+
+ modifyPathVelocity +
+
+
+
+ + modifyPathVelocity + +
+
+ + + + +
+
+
+ + scene_modules + +
+
+
+
+ + scene_modules + +
+
+ + + + +
+
+
+ Private Area +
+
+
+
+ + Private Area + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + + + +
+
+
+ Public Area +
+
+
+
+ + Public Area + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + + + + + Stopline + + + + + + +
+
+
+ updateSceneModuleInstance +
+
+
+
+
+ + updateSceneModuleInstance + +
+
+ + + + + +
+
+
+ + add/delete modules + +
+
+
+
+ + add/delete modules + +
+
+ + + + +
+
+
+ modifyPathVelocity +
+
+
+
+ + modifyPathVelocity + +
+
+ + + + +
+
+
+ + scene_modules + +
+
+
+
+ + scene_modules + +
+
+ + + + +
+
+
+ Stopline 1 +
+
+
+
+ + Stopline 1 + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + + + +
+
+
+ Stoplin 2 +
+
+
+
+ + Stoplin 2 + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + + + + + + + + + + +
+
+
+ + /planning/behavior_planning/path_with_lane_id + +
+
+
+
+ + /pla... + +
+
+ + + + + + Behavior Velocity Planner + + + + + + +
+
+
+ UpdateModuleInstance +
+
+
+
+ + UpdateModuleInstance + +
+
+ + + + +
+
+
+ PlanVelocity +
+
+
+
+ + PlanVelocity + +
+
+ + + + +
+
+
+ RefinePath +
+
+
+
+ + RefinePath + +
+
+ + + + + +
+
+
+ path_with_lane_id +
+
+
+
+ + path_w... + +
+
+ + + + + +
+
+
+ + path_with_lane_id + +
+
+
+
+ + path_w... + +
+
+ + + + + +
+
+
+ path_with_lane_id +
+
+
+
+ + path_w... + +
+
+ + + + + +
+
+
+ Updated +
+ + path_with_lane_id + +
+
+
+
+ + Update... + +
+
+ + + + + +
+
+
+ + Updated + +
+ path_with_lane_id +
+
+
+
+ + Update... + +
+
+ + + + + +
+
+
+ Data +
+
+
+
+ + Data + +
+
+ + + + + +
+
+
+ /tf +
+
+
+
+ + /tf + +
+
+ + + + + +
+
+
+ /perception/object_recognition/objects +
+
+
+
+ + /per... + +
+
+ + + + + +
+
+
+ /perception/prediction/objects +
+
+
+
+ + /per... + +
+
+ + + + + +
+
+
+ /vehicle/status/twist +
+
+
+
+ + /veh... + +
+
+ + + + + +
+
+
+ /map/semantic +
+
+
+
+ + /map... + +
+
+ + + + +
+
+
+ Planner Data +
+
+
+
+ + Planner Data + +
+
+ + + + + + SceneManagers + + + + + + + + Crosswalk + + + + + + +
+
+
+ updateSceneModuleInstance +
+
+
+
+
+ + updateSceneModuleInstance + +
+
+ + + + + +
+
+
+ + add/delete modules + +
+
+
+
+ + add/delete modules + +
+
+ + + + +
+
+
+ modifyPathVelocity +
+
+
+
+ + modifyPathVelocity + +
+
+ + + + +
+
+
+ + scene_modules + +
+
+
+
+ + scene_modules + +
+
+ + + + +
+
+
+ Crosswalk 1 +
+
+
+
+ + Crosswalk 1 + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + + + +
+
+
+ Crosswalk2 +
+
+
+
+ + Crosswalk2 + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + + + + + + + + + + + Intersection + + + + + + +
+
+
+ updateSceneModuleInstance +
+
+
+
+
+ + updateSceneModuleInstance + +
+
+ + + + + +
+
+
+ + add/delete modules + +
+
+
+
+ + add/delete modules + +
+
+ + + + +
+
+
+ modifyPathVelocity +
+
+
+
+ + modifyPathVelocity + +
+
+ + + + +
+
+
+ + scene_modules + +
+
+
+
+ + scene_modules + +
+
+ + + + +
+
+
+ Intersection 1 +
+
+
+
+ + Intersection 1 + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + + + +
+
+
+ Intersection 2 +
+
+
+
+ + Intersection 2 + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + Virtual Traffic Light + + + + + + +
+
+
+ updateSceneModuleInstance +
+
+
+
+
+ + updateSceneModuleInstance + +
+
+ + + + + +
+
+
+ + add/delete modules + +
+
+
+
+ + add/delete modules + +
+
+ + + + +
+
+
+ modifyPathVelocity +
+
+
+
+ + modifyPathVelocity + +
+
+ + + + +
+
+
+ + scene_modules + +
+
+
+
+ + scene_modules + +
+
+ + + + +
+
+
+ Virtual Traffic Light 1 +
+
+
+
+ + Virtual Traffic Light 1 + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + + + +
+
+
+ Virtual Traffic Light 2 +
+
+
+
+ + Virtual Traffic Light 2 + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + Traffic LIght + + + + + + +
+
+
+ updateSceneModuleInstance +
+
+
+
+
+ + updateSceneModuleInstance + +
+
+ + + + + +
+
+
+ + add/delete modules + +
+
+
+
+ + add/delete modules + +
+
+ + + + +
+
+
+ modifyPathVelocity +
+
+
+
+ + modifyPathVelocity + +
+
+ + + + +
+
+
+ + scene_modules + +
+
+
+
+ + scene_modules + +
+
+ + + + +
+
+
+ Traffic LIght 1 +
+
+
+
+ + Traffic LIght 1 + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + + + +
+
+
+ Traffic Ligh 2 +
+
+
+
+ + Traffic Ligh 2 + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + + + + + + + No Stopping Area + + + + + + +
+
+
+ updateSceneModuleInstance +
+
+
+
+
+ + updateSceneModuleInstance + +
+
+ + + + + +
+
+
+ + add/delete modules + +
+
+
+
+ + add/delete modules + +
+
+ + + + +
+
+
+ modifyPathVelocity +
+
+
+
+ + modifyPathVelocity + +
+
+ + + + +
+
+
+ + scene_modules + +
+
+
+
+ + scene_modules + +
+
+ + + + +
+
+
+ No Stopping Area1 +
+
+
+
+ + No Stopping Area1 + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + + + + +
+
+
+ No Stopping Area2 +
+
+
+
+ + No Stopping Area2 + +
+
+ + + + +
+
+
+ Update +
+ Velocity +
+
+
+
+ + Update... + +
+
+ + + + + +
+
+
+ + /planning/behavior_planning/path + +
+
+
+
+ + /pla... + +
+
+ + + + +
+ + + + + Viewer does not support full SVG 1.1 + + + +
\ No newline at end of file diff --git a/planning/behavior_velocity_planner/docs/virtual_traffic_light/V2X_support_traffic_light.png b/planning/behavior_velocity_planner/docs/virtual_traffic_light/V2X_support_traffic_light.png new file mode 100644 index 0000000000000000000000000000000000000000..19240ca64224200e0b4b5791465ccf563f3fd50b GIT binary patch literal 91648 zcmeGDS6GwH_XdpOYe7-KMi+P$=~AQgfB(~cwD-Zju5S*KdD=YBnl-c5z1G|lqo=D*O~p(_K|w*S@%)(q z1;y0~3X043u3sacQP({ukpHguDr+9d&w@9^5)HjXc6bO!)dS>iQgMxu4pecJqe+Hor~ z%}F*tqoN#R1Cp12mChH(ztzwaj;8Plk(~)@l-@a2Nx8YS^5M2;sJvtP`kM{QRbMP? z7MjpL%bxe`+c%|4e?Odp;l6QXW#?`I;QuaIKLSzyul`l*J?{Tb z2gT^I{$E|_4)pT>>c2Ua{r~TD>$7s2|J7fo{lAU>f1z9YBI?PyNKd@B)I3_<&*tKt z-|_Q}^-K{VXgsu=qoF#Hp7QFCP09VDD}P^>?)gVwLcyT0-K3B5zBv0>i-Fwvjw=~O z{zu+0gHW~hqTcoK0$%|ztVRox6D4_cglhd!Jf5y<&f+$Lk?FEuwkbBVQ}9*laA9gZ z>Fh0@K{%MRNVVAg^QZk6RgXF;D6|L1;6?0~!=CEZ;GQGjp|5Lm2Yu&h=AclylhOmizfcndu=BxO?Qf5YkZQ!HD-Nxu4o zzW^Yhz{<;N4=u`a7b17l!kXk=A~Mui-9cmia)O;L#`quwy=FWw0|5-npJk{{cLpkqy_uZ9 zFTk@x0||GEsgx8yx6a{#jT#c7a1&pgNvi;ufoG!Vy?wQ68q!u=faJheXjmsAu#0b5 z*Kc3|kf=-AeH#D(_u71)1KOft_nMDlm2ufDV6L=?!3x@% zx_R`|+C4e_c0o!Vp_bOjgNQ(^W4D|=XfhV4rl$|8#&$45+D-gDx-Y?)EaahI8x4}I zhmF^kCSarB5)(*THsDC3ZIa7^5Zhr^>74hJ{_uwWw|7s$hk^0X2j*5l!=iu)=BmP$ zHsIS#q4D)#yZo(tWoO+ZinUmM>@Tb>s;hNS=FsGzPDa}%fN|)Kh4_%M0*@hH_ zgL@duPk9|2D(m6qm7rJ+$Bs*c##1BwCP?+2R!IVlS&@#-GX20qPgc0|c*P*B8oIGT zu=M|aMN<8*t@-M1@oLur7?`G;<25qET&CO9L-on&v$XO?5sQNtGjxY&slVQB?V+1# z9^_NsQ=zG1an;xIJsT@WzE^vY{#*kR+C0}!7XtRjCGTT?c}^5~srLhnzpydEY#vJ^ zcjH2Mr1sawZ3J;^tgsXoT({GK6rmMc;n-DO$q&ac_5O@ZzlNO9Jpbx1H?DJf(gqIu zh-NCTW5|I@grXmFRSidk`_{azB6SV{N6`FuO8bk}i5=_`Y$@cP|IxW>SAV~W(ziF} ztPct%yzgML0gG9}fz;q79Lq5*clPS9kVvk!WiBDRxFlY^jPC)!yL$)r={jE5O15W}!dEHZrvp-nOrA-{xs)3c zqr1M@9_%fHNp5yl3fJVrKV~e#Z3gREpyOf62yenOG}K~QCo1Ka0!TqS*PeZ5FqED* z#3-G{$j_40z%QkpWui;i<@_T$#g36FV*%JIXU~1`X~Bv z3Z*;+NiIZXX!wa_n7$n4%c&25VFbG0NAqM-2K*H-eatf~3MtLQ^P~7@ODe9UcPlw8 z?5z*O5b?vUe*`$Xw!e9{87;C!96zQ0VZD*krT5tjsmA94x;?hi3<0gs<;Q&LduP{93F}x zHmvLhJ!+g6skiYa1P7I!Erv=2Bwt2Q z%J1KY+A{G*+xYksG!Ps01q;mJHFg-(Q&`VU=m&4?2jsZoj2+agGr^SO95xy6NXXH< z&;yw#n8wjZ8_!JMl<8Ppc)>NRjc`3P1!Hq&A{s+M6(>Rv)Y%f|-t};lRY)FDkOg@` zDdZNo8_de=3bAbqf#}NJ=ISfLVI146L(J+W8XlO)sw~os<36aGxA??JSm-2!E@;XR zXd@V%q(;NgU}XT39FIgE%~Nv#ra<;;D{#%C$-PRE~>gSQSUBS zO-iuJZI4&1cp3#Bz@|k1JwD+D>whv`-Nz&ppWcH23Lh{K-IM zKlBw5+GJy(_x|I#cjRQaw^HABBK9B6BzN|l5maK74L8>ud~{q@vg5O;E7i2zq#?H) zmQQXDYDjGbZJZJHJAbZp=~8V}Mhdf?@d}g&E)IP4X~Pxb1J$XjIiDOWJ?rwA^)hyA zn{2oCI_fUpC@9ju2r9HD7PvieKBh9NirIPD&1NKH?zd2=wG8*n=~(#O&yjJNbpIZ6 zjQJqKVgbg*Hiq<-^%{DUkI7KRwCcd@pdTxb)O3F{-^_nb=%+^ zX}$ig4RF*eL|7vug|o-h&Hg)yI<+Bc?W?OdM0dpA^uk9I1#vbC+Xnm8$&)lcCb0Y= zfmxdb556<44-#dw6*(~v>t+iVeDc%Dj>WLp7@r~CsbC|eklbAkAoierJ+FTqVhb_NX#UeRAA^NWgFb`^B z1uz%yXz;aU^}vwcs6?B4o#i@j`E7v8EXrIh4n{{A+desdb~~f7zQ_1!u~o%F!PUrN zyIg?~vh*sTZ+>$$2IsgepI+X^zj`|JUjP#1W&0ktueX4@UXsmPHCP#dSa-)gg0nTu z9e)Zhn>`u5U3?^DK>S$acuCAg$7iDqY16>hu=_T_8deyH z#5v_XTf?6+^m%U;QdwM!VxYY>Hb}`)cH#IuB8}>z1#`NCY_N#dji?gMxd8}`_*Hpr zqpDsDV~*j>Vo1hGG>GwD1d_n(GW;p)1M}{}ixie2AH78iRVHNL(7V??wS zuJq>8$EI^{d2@QHsYnTipc*Wi0YCg^&PK05vR`vFU!6GQimaI~vYSgt^*`9!*&nMN zrm%`gFNFcCHs)@$f21LdHQvE}eVy4X*VX$6rF?6TS|-^Ov%rML#m=i9_3_z;FD+H3 zGq4!AiAXB1L;ZHP4y8$5efz53I;4;O!Kb2j{orkXp5sz(92;nPYRLchSXE7)vGCpj zZf)H)LnTQq+~&!T|8UG}*!2k~Ez|ctcFYbPV)sS-0RDyRG;nJX?_Wz$--PSJ1Kyv( ze&*9K3m9649yti^i=5r6bzVga0FK*z*GQM4l|JRdB9?S{j9p9$a1zF6IVz!{ zu!8v$en_0-G9h0T(+V)(NQ-oF_>eb_=2!1`V1>Dk7L>XzXR%EUO}YkxYKekb-9E-n zY3@l&i)AUxpHWD`NnH0OD%`eVPMt~#gE_(2aPHOfiK)`ObFVK+>}Ddt)n~JwQ((?M zlS#(d_PiG(=&s9jD>CIYCJiW7IKZzaq_K8xaq`<T*+lao^s_U23ZNYZX-8Vhnr@%CkysmGjsyoS|lfS-g!=$N1rz&R#)DMO}R_| zFBzQ~?@X|WYNf#rE*NJGE#OPEmgqwxTv*@+;jx#>nRI6sKJ_sHw?_F#>QBNRx*v_} z#kFB7q{q}hmT{vMH`73-%Latu!U2C9*VU$O$*n9Y*zCCidJyVKcaD~3ZIoE|{-oMr zs-U~Uq_HPO7_Yer7*ROD)IRHFizU32kM1LgNgCdrV00!b5Q zgE*+@o!~qj2p@dWkPr?y=y<1+lEql@^Ve;Gn|t~|VD+E`Vtv@D>(qp784tYc+S#3? z25;_W{tZW8TrW7OyfI#MqW}}OZvJDqY&4SwZ&@4k_Atl~Iw}4rJ6!CWNLzAfKt1jS z{#7-_KC8aD0+?p}MtYhBVPB{jL0A|D$YKFI3fQEFS44$kCbn9f{?%?8g}y^Z$zT2E z*!C%-+}$o{+iTPnrU8TBL7k1QqAuLadrx2F%>u?M;r*rDXIZuR!uYd*xAor{yBw46 z7Ih*dykpvJf|ZWxx+LW+)0qA9B{YR9cOGREZ|JRD<|lMo6`5n-3mKsHoIR|K%DB&m zAD<$vg1Rf(^8B3f@9d0r4$1RG$jJ5jcv0GH0s105=5G8P-RIcP>gcmW^-T; zJ7$ipfy%>Q^E4urf1uy1V2!ipq+8Ms88CSGBiB0FBM=z&j%J+YAHohJYq))eftuw@ za@^XL5*Cp@*<(50lMIKlr4(P9l5Z)lJ2d5v&~&U12KfC34xqiRKM&VzQP5XC6l4w# zzZS(ieYbQI;(<9nHD_hzYY3b`Zyd+o0oxv*;V&;9jTgMr?Hc1cf5>-4)bvPXnNs6_ zDx&SS&3w}SB`|K}TEEPQ*0$bAL#i|3gD>whSehv!T(xK~!bHKZP8a9mHg?0QlIn@! z>65>xZY6n|KPS`f=j3$<=1!{KG~FpK-0bk;cuRbgBIozQ&62U;>mmLJKmx!Y-Z?&0 zEMODc+BYn(m=Vze%IHbyXIwiH8YOxK>6^*X!L6Wc?BN-Wk38-3<&|HLwtG%EcFl!g zWLjO@MC?MfF?)wam;E^u;JVfoX~}W%lCpfH%I;yi2-$Yc<17f+#V_CUg>|iVb+Kxk z^VNm&wqnDgQ(i4x1q}U0E6SK=zJ~9FSgwfu!L66!5_8gR&{gkW?{*=5DCNZ{USD1U zma|*;U?>l%!%k2~aceD=5o{~~e0uE2!IFN^Z6{M3vb|wl6jCq|%kvt4*d+zO(N7p% zQ^fL!DTj2>!Im~w>(onDdox1)<;ftOFw{)FPk)6+2H&F?_G@B0ws68QOXv}gYlZa% zk^Iz7pjKRNg5;U^F#KcbwDaKK`2VX1o~T*AlBpOwDI|L3kx4dSL^ynCVrF%P z_ho&}top+KOF5*aw*f4C*7vq+UA2zx8`C|g$Sce2y}lR*@u@b-DnlY>zlsXKEd2TP zt42VAO?vHiEzg*1`$^ps(^x0bdsL!si^X`oP>9c*fdh*{ZLVY4ES~LxHR*BQ3%HGR z@VwWNLrk7k8+b!Gx&V0k zX!#h5sjEAz zHK*HpQsfP>uUO|3FKKrT3w6$|(i2lm>|uFVdub|5jgv@9^B+C>{;XV;WwG^) z??$X~mG|sxnlxRj+)(Y2{rN_18KDLlVa1Ve=!nMnYee!lg!gvlN{N6u?PDIw3>HREp>4v8)ZGpmD^aO@Af z>$ZGO-HFnf|ClrkvJ5tT|DjjS{Q${TrKi6T7l-2)%ikC5VpYylEKwVJqap9rxOL;d zbaexzGGS_^?)enIHs6{3TFvn+O`FB4{z`caH>-^lwa3j+NUE@$(MLIWJmw^t%ZT~3 z{KD$3kJm%OmP-X1sNkPy=Dl6+z4kT77Sra=r3^}zD4VPJcyX@G9fdJF@C#V`t(#J;-^uPPuuz3k(6sPPEY;eXj@TztI*Mc+0t1Iy*r)s#m}Tz<1>f+{NI@A(RN-tYPHAD6%C7H(Vdf;PT>%=L_?TR3C3!hE&7?_h>c zygq!F)@bXa%XNt502l{qb4OGC8}<)`6#oow3BGx$tW1mY;#Z-jijm8wj(IVb&9MRn zGkkb&x(y`P4+oD2@v+s8IdWE@A=`C{(@^nr6BGH1yU%@>4_K zL!eV+c^*BBS3~eMwJQj@B4{oHrOqTeI7Lw*<5q8JLtrj(F5vOWkCaBz zm1{}n`YK&&m{zc2BQOfxv&s96=J_klk>+mRvagb9@n1OUC(h_EUcUhXF74Q-3`(?3 zNVGN{CtQc;xYq5v0j3W?87d_vQP!tdc=q2sYy0$y-O@k z3Ugfgk^1;fqTA22LGdjwNX{g z`gD708of{R2UX`w*&-JrQ=9eaGHO=#@(t5ESO2q0^vVS3hl+_@?_IY!(GygJbKSP( zHN${~398>X^D;h4>i(X&m%u%KUA*9_GB==_)CqJmG{Hr-c-DkHCns0Ur#!A}kPt+- zKt35+Jva6b!+i<}YUJ4`s6yb{*F9mprHJpmp5Ak^eZOf)3`;r*F~W}XS{O#VQw!#} z;#=egb7{%~E@t7)$Urxz8QB|?A*bWE*GqNI#~RrwWt(T5g7B*{FZcTYjbOj(B6Vwf zov>DlX*dY7&(0G2IkyqD$*8h_48V(D!L4xCfS0$^_#D)>Oa~HJ2Bn8ydse3^$%`Zg zf$htENCBAtWd8XurDfpG%CdeGZvWDhYqrVdwQrs|N1bx5FUrlDyc=Hq0?YX2R~koK zqM?1H6e99jTgrVOH>1UOSaKv?`uU!z;2&65W!#^xq-l3mG8Bu@L}PKS)oYYVV_ea&LVL()FvITT1b1 zlmcbswfG<_d~;#eeB-7BLUIox?suuA!=}l)?X<})DB>jAWpz%VQqd~uEq%N!WmbzL zG-BLxxh!3^=Smwep~{Tq)?bx2$SD(=I_D~99J;BdOs@T9al`1 z5u>j%rOaEzdrAQH=knr#L~GLeR#q84Din!%d9?Rn(@52K?kM&z5_!#}S}yN&#OG1s zAoZT;S8-5iLCoxjw$r~lNl(f7;_M1z_uE)w7j*U-L*BKw;hbZwHrb+WK^luBExC?w ziAKeMmSHI&X>R*#bkWantGpZv)hF31kpg4FeU4tRdNz`2pO+;`<2Y=8setUHGmP!} zv%;kT>haxZU~GIa0V0nK(jS-=P4@Ky13>0p*T>J4Q|QI5(rVSq+Si!x{3`n%2Uz`Q zz?{XSm1(5ZF0EBID#ruhYAG>ZiH!BKZETPM=2=RHRZ*9Bk&NUXiRirTOmSoipBh^j z*Qhq{r2Ro$^*vd+2wcGpSuhv@h9pRtYn%m|t+Tu?iuJJ`vshC`#`H4Dzv+95^p@)r zt4V9m9a!!9$$RM1qN1f>V~sLdI4T`9)C){7U-ta`$EXvaVrk#kH-c zFk_(VPNDcVo6dtZYJAi`2hN3NBWN@hra~7F%{^cwR*cU+&a!Pvf#{pd-4mEl*I8Q2 z<@N~k%*@OC+2cDoRq{~-P;`Khz%}g`(P!?T_7)TPZvn@H00*NsLO?cp8*f~>-BBwo z6|E5}G)Lp{BjpU+E};-X@pVP4Jp=ajCIk*mzu9{j(8TpOhtqIX*awVYkSblY2eqv9|tIxp^1O8S>)8FqfDPlart|ETzf z0^N%0Lx*LRzRYq@N3RmbRl8QB)o|+}p58t)yH`%)8*M@8$u?n_KS>$FY%Apyl7l&2 zl@On~Bz*LLT!6&jaGD?9BL%IsJ^H>(w@`A_w6Q-CYeqFFYSwUkdDX-u^hSc4R~k+D z@8Ot@n@28qE5l=&91e0X9K-eyMlnkLE~I>;!x9SPg6vTW%3_O^?JH9 z6h3u|LyT{*&$)q?^*ryig+|U=FY0`d7N0zNRg$yLra!>1u}3>`vMedXRH9D&xQ{WH zdjNeVREK+E{=U$wUh`Gur`95~mW$D+3u-ERSYwZ-hv{tHtX!$-)vk~E$)oP`YU(FT4NR9h%znQcAm_j|OuH@2 z`*W-e5b5kOE~dK$aQg>&E?7sEm5sJ|BPBSFlfmnH=puL~9^~hrTT2TDZh$8){Fj-Tp}9W6?Ok7r2j>fF4EV!q32HncCo7Q; zc*T^bo>JF}$30;c7m8(;?kkgI#vLr8K2N+J@TYNTpKm<&K7PL*84tTPjfE9OK+(K* zuiXumNtN5{TT1VVo=I00UHjDmm-R6t4I{gD{x4EG)Tk*y9JzTQ6YRFp(>S)B@{ z!shU|zFF6V$(yulaafw(2SpK0Fr8qdE=lf83v=Y@yGd^}1M6nl3cuvk7#BI1x*X=Z z<-hTrDOxu><4Ediq$(~F;Vk5}bJWKy!lT}xPP`e90T*~Lbdyv-I|8stT|eQ05%BtS z80tc0ap!#NRmF}<8Wr~g&3vD+tAzgyQrj844anhI>pCm*j& zb%>W(Yx*VxM;a+qZ%|!W_VJkXmd)Ez@?&TvG6{ZBK6-xBc^QmIp$IR`@D<#IP zXHn`|7i$l|=JtvSQI2@`^v0G(X)a^cxsTbztb#ImKpB!9yV(*7A>;Xj&OP24#e*9o zsb1KMx(h4VJ#?-!(`GVWxyXIda!je(6_>p5#t%qk^fg9sV?hy!0h7V5Wte_l{^vf?B*nl|ei4Je(}4+b$mC zz#-iNh9)IFP^ERm6Q!%(Z)WjA>jwCBOc>|1*E!F&B804_DvIkPHcGQprjUNCu&-Mk`4i+fH;slXBc)3gNtG@1Qp zetL<@smxaxUOZaec{?x(5!kJbg*5j7Gi+>1H$U~IWncW0k`a*hF^Pc}oWx?F^w5@^ zmXhN;F;B0Ia)4z4#3C&`>b{yxe!r4)6kUS4wZD)j)S(D(lT_*mv9B;5I^aDtx4j*@f%zgG8I|Mj9a&F)RwN5x0dvdxL*yG7|J`_$Y+yHlvZO0PIx4KcoKA^iqengy zl4UCp5FY>#RioWKJf*9G{w!SToSQQ-m8vfmA%lZ|3`7%^Y%xinD+y`j1;tiF?ksYn zSnf0@XO<_ih)L#(?K!0BY(UCqF+|4zW@fyqK@hP4>Zi-WZzjWRsP+z%r5`_s6)8iS z9%*i*WqO9s7}7CUFtAaBa5gOdh<1zB>Y(w()v~ou|CXoqaPzM?!x_0<>i3JDZ>9@k~)tm26sUpo0`y;|0t-mVKLoyC-f&KGr zdWoTQZ9ICgqMs;BrXqs(8!8-=SrOZkWb8%ij4t}|pGomTX`kuAgKWwHzc*K%cWMI| z^3VnRD%Ar|`39^@zq^jRtqY_aXFSo78{!gA}i?z9rM%UI!PJk&*(=D?FSFCpCha z{nqLd=9|PrwZUsN|D(To(*0r3?JGIK!oho5tfWfgET9A`+~KW*oG0YGMlEu1-sWoe zGd`Kn9`zf4TK@XB_gM)A#m~zV$N@fl`$-2YfpF5>FrC80UP0(*;1_?QxT4rMfuEd; z3SgB(7aE|y?qrcv5G1c6hn$>(zo7j~{%tZ5Pnh;`mG1CO)(J4K_0&}>&6>PON-`+P z3zyzyA(35Py@5q%uoU%Qan`>^*pi=MKf1yvif7Ato;Zoo+de;*uy}$Y{lH?{WM4#4 z{$>At#lO=e6Z=-EZ8*71jZ(gV60VhL3X!ArSPOrXlZkPed^Q^e)#xiO{`TdQf{DXm zw+}z-V6x)BSH1e7KOL&{Vm&iZ=FW2z@_bka5Cx~C5qb!joCl3l; zNE`T>QBIx29|b&l^&g|NGDRyHP2swk z_}aGJ?0Sb1zU@!GJqlH>UeLFT4HZ9Q6_L2PF*{wTged%eDeTs7dQ@xX&*n zue)Jg)znAZ+ym!m`t~uT*8Su5;R=T*K}y=FR?ddgMF_WJ$Sb0AO2IvBTI`QbjMm`2 z2sJ%5zR!D+Au@2rL>_;yr>XxEQXOAg#778Dp2Ig%+~Z9q>w1k|!jkGDRurUN>~am5 z6E}YJ^%)TO=-83`Te~`_>pAmEkv+WrI#CA3KOL_gnwD-$H37FqX)L0Ma#;`i4`>g# z%u)zvY@BUPDj~XtRb;yA>vh#X`gpx=Vo}`M8&F=XVAV2P3F_jG#N0on3kz7dwhZ^i z<=7=35abOj7o8RmwuU`FO^mWe4-VX-k*hURiCOCD^^2gQ!nR(z2EuwqhtfQ}oEk&m zNTyMUFpaO1qyN+KJm+I@kzvnlj|8GAM(R=}m6JLbXJynqj4>08%eB!~#-CNHt zR|Wm9!*{k~B86yjY)%;KRR`Gv(Fq*8W8}rQPY7vXU&oWtdEaC3N$wQepJ`1`#rG#Q zDoi>P=u*Nz`9Rvb=Fp_&ch=?&a6O#%I~(BR43kuMDMD#81L<8YjG=c6-_bqD$sgZj zfc5O$i4(%L6+3(*{ z9x^VbJ!T~w3jKy)gY3?(w{&R-U-pQp<&KrqYn7v)^OktT&vErVC6#0KHdEtL)-9P1 z(wLpsR=smo&4l}*=hb`*j<_B4~s+(7OI!1SjmjWo?gt%dv>_%1lqrK=JAb|If#;x$>xUl9eQn}2lvZ)|OQ8t2%(UjJ5yC+Ts@LM*VKsOk?;oYrZQxF&~J0rm<|5SCIcOGS0rxM~*huF4QZ0)GiZaJ^e z`!?NwFgTd95jMYgG51c>=3&YCi|CK-ry+EY!N{)CK@XE|Zu*j~2W14U2*^i;sr=gH zkQ9l+IdD;e`w)8fD2z`bv-+rj#N4r9lR{Li^kMr|!rJTOcNSuDXuAlLL2M+0+MH#o z&gfKNjglI?iS|5%7{BF40TlD%;^HJ`}UsaPDZ9y z9O3oFQCmKA9aH%SIxJ!jF1Hx%v8%cUg{B3_i2<%l@_K~45pj+6KN{kYS27#ge0l|k z4$mowqnv@B*e|4V#P?DeJ;Ueo~=nre6f*Q&FM62;#&_0`$`!$94*E zAp@;5UcB-&`o(9j+0R%N%8pEEHR1C=>nrx2vk9-YERC*BA@3i^E>5{03x&47wO)v) zb_F#)S)^M&CCf4qAK@O_VM(MjLoqx3Gm?_>xJjYfz^LPKgVl0gdP+T)!)Bz402RAe zs6Krp%!*nd+5HcY_|3`onml{I{^MZKQ%e0YWb;D;dIk0(@^KScd~c)z!bZABb_QD> zMPH^_-@_ZUAqDf*TF=3cO67EUB^Xi*cy?o1!c`#0gc0>_x0wYm@$!N}xSB;m=NzNc z=kSJubVE;Yx7nR;G|UtnH$T!C43NfpYkth?Og+l7 zPcq!9F8wA;{xr|ae|@28V|zxCPCu2=nPWUv?#DEMmful>rvvK`W~TTI7DWm3HY;i}Q#DPYn$P`KrMB1d{(>T1jVJbgR`HrzkN<*rbp~X~rBa`PGdc|1)NLK*PbF$9N$@;{ih;|5-z?QRx#p zd3h*CR?OJDz*C$@cQ6y|HL3LXFQ$VlTL;*Y%*d-%7%Dt#}4JN9bp%ge!BlWf)0P3ur_a0luM zOG<;|rr*Q?Tn=znC)HNRt0H|7@T^``+_e&(L~4k{q(Z7#J3P{7ZB;#n&o4~NGV>~1 zPJ&lm$4yN*r)ySI_J7bA$<+fx*s}h;k$}k$tG@r^z$aBC{EJO@84P4-QUo3A##}sW zuI;%s?ese0qsXW>^ytgWGuPdx-Fz1%kCw$Y4SG1HK}QxXt~h2R-%@S$a{={rmYYT+ zwx-~HdAtU%$v3-T@K(Bx(JItl!K{)5v@id?*yye7+ko5?vsMMbA54tN7HUoMVfOl*#-KfWZthH@2#&` z+kcD?uC_d76A@EB1R8uB5uuacn%vE^=N0F)G6T{>`CJk;t^3E)#YtN}kTxL)+1$ZD zffhx&g#0^lsgt`-KA_k)b&9FSHt3xAmsp3|Z+%B^H8k*?bJMfdZyWZ^F#UmSE7E^q z6~#>E@Dn=s_=#N`)=86*9;}Qw-^qlG=B&A5{vSu<@)ti+{7&U01$FE_7+PPq^W`x1 z3bjikHmtf0(e~zT(*1co)qjy7KuUs z@VA8r{@XpJeRE9mu>43d>0@5rfP`>7;H+Py@z38u`B0SL0$d$^U=L&Rxj= zziifeav#Zwfn-&^Z+sQm%jwqJH^p{aI8VwUA~=h!T}XF+eqQsJUUB9W+g*wmy8mrQ z6XtG&X(2B99+Yr*^U6w@ejB-=X`NieDwI~yBj-AmER*se4Z3nV8eueU_ zJp{JSAUtBHOIZ_F%YS4P$n~N?=d-qS#WM?l)jOxNe%+iNhGwfzXp2isgLl2n4@JB; z#p?pyp$9XUzk!cTW?5roNxX~#pvzxvDH#e1MmzS%ah^A3-7%oL0p(Pzx)PJ|vMd_3n+uc%($I3h!{ zJO2K`hL%aA=;s>xbuwG)!dBA@@@Br{^bjk{4AcB5 zsxf$N3P|rVcdvr)WXl#p0>7ijq3^$*zWg_sdp))MWO7V_FDcxz^yBK7eVlL77SM3= zaMA_M!GxO5t%9N@emv4RT-x|OV#d7fmsRTFJt_X9>4|E^&EINWpzoeDWs59MA@`HC zUBD;EtG7|QMbf_RT%&X4QEI&F?Zs1UePT~}1)o~)TF?FXV1kjXUOR%3L$uwqn9JMY zEeWj#RVmSR5b9oCOqUKW) z?$S@Uzi#ns=Rv}y@ozV|429W} z@h{OvrjlTdGIt@bvE~%1$mpy5vhqgK)3Nqs^tdB4&jIFdNnGZYa*1{)c^a`!mt-T} z!?tUO~OtqO>dH|pyngsH23n+QpexpjzGCrZrHJqaE?e7o6*i^O(vmak6c8fq- za01`=_x7rPV>+#-^j$ps5{M$=1eYr{j4c~&N!(ttj)nkkwGE*$3AZnM3GuntU&P^m zVhTyy!4X?hKn9oIC_m0;ls4E^jdj$iSq-#j-DpeJs+e`E!X%CMrb*{zY0NH5OOGrP zrgbn=THqhu%^R$fn;TN6HaO?0pY3lyx0%Eq$$u7;RHNV*w|^XEC)y`1AqJkZ#uj8# zR^_V9PlDvmib#AczJbyX7Xv>w!m-3hQ*F&R0+HLzz^`3=mHx0G!<~uT#c#B*FGSp3 z2Ot^O8rIC9x&BF@G2RKJa(JM**w+a=1#IEYwVwBnB+UKtoIyL~vS1WEC(ek{%MOf# z{nRZW%P>M~6S&QKLxZjAeTqM37aFE^`Z;T>-*EOaIn>Auds~vt7ffiZlFhBoHjS6d z)c`*#mQ5|AJ~Uf8SZHCVSmFEYb6!+!Al94I4ImMn#neM-<*iTy$TllT=_Q0Hn_9rS z9h`hHVC!Orx-MWiAMvY)HtwaQ^N`yq!lnBezfV6=JE}I9*JOs4iky7WJFW>siO}(1 z>{{`;vDx80%TRe%W!Y&tsGyZEDEUggzBjUFv(u%O?5s?8GQ*a8zfIT3SrYr$fq$EvtHI1pbH&4YQ7RuqRTo zwdjm4s@q%>f!}4V73v>rN6(JP3^`FFpL_S8Z`1N~w&;n|-okIt#u6527wjV>RMr)w ze7b5rSC!+?!KmZIYb6)HpHc2~d=Yq?lv&I2KY6pIcO>(}UxG&88P>WR$ZC( z>tlJMNyNyLllLO87PS8dnV*VO$y60KbU_ZEMQPi~vL+uqk6MtIuk4&lh?q=gJ7Hiw z_isOsAZ{tt!vS*_XJa1eA+?e@HLIyDM8VC56$|2|8K14q30-|@%SZj{`h<@li)Cny zBA?@@ua{!DK+SNki?v49isaW<#Gk*exT5)~{BCi@!qyCxN#-EhwqYin&d3T+4s1zP zVI2oDyR0GyiYi0rpAkCuWNOBWHBcK*l|}9H*thqOLkD@o@)GCRtEukB{?K%c`9Ll| zYKh(a;r+jEH^`qmo=BQh7Oc*s)+~Q8GXMCMUe86?G1&Z8e_dGKgrsF{)lZ~Kc;2$d z4RiJO%&()|U;d8^us5};(LcRV|MFdtXyS$SFCPge;~k`sXK2837frvj$df~2V5Lyi zY%>Ysp0@0=YatiWdTdri+Ua&v>JO4~iMPyYC(WQoo!wI%%t|ERrtS{6XRNZY*1p`h z)qgtLI~kXH?D$>tywg)Ukcf>V;XXh@8Do)38_#VWfwyE`OvReu3AAO2&HTn&d9tY^ zFB@j26MlY}KEZvUL&(5QS5}^~uuYrz8l%BoRBbYKi7@10lgZmuEK~jL@nYNnd^DOh zwWZq)FC)5Kx$k_)R2A;ty)9ZvZWDpc2ooo^y^KGrYXEoX5C%TcwG4Si&K|v735?jR zc`M+_pPREcg}!VYU3Wq>+0*EsTc~N)wYjh#XAT;5nTi;(%gJKvg52RhzS*_V-bmO@ z*^UZ#Y1nLug7%s_$PTS#N%#C>sJ<$2dXg?K9QMIV&WV7S5;*i_p9@tB%|)DvZ=DLw z<^<27{Rnpa?So%BNurC#M_0>KlgDsDUMtB&)J}WfsxG8#hdt5sVHs(1KOz^=dM$M~ zwpd(*1S*l|Z=L)ShqQ+A%aFiTrtBTR>*H(=Ont2fI=(+~()z`mzOMvW&ywe#S;%F) zH+Rdd<}};5H(GRhtoF&qjBSU5Y$jsREY-h6!JTQtla(b^+%@bB7~Vg-Q2$n_%`VKc zQu6wp&k$A73DsxhlG;M854K)^^h<qj@$Wv!j?$%qHXuqVvtO4yC=P~Kp?N)^e=KD!?7 z{J7pMC9!0UB{50%w!KCvSnmSlJ;KKuLq?but>{>fIk?mhpZ-86Fmfz!ufqS7%lPxI=Ut4 z)VyEh)qJRYbGZIk4oC^D=6U}`(uJ*QQmlk@zV9GA5f!WSIG<}?f<0ydp29W)w4%>o| zYU7^%MSRBi@wxn-_*Tea@{N})^gNho8I8?sHoeH7EG{1{k{&mhm|=XwvU3@*OS8|P zhW1MZ+{I2u27;n)>A<;dvJ823Z%5aC*5?nLBA>~^)prNx%Up*z6SX+W8WoBuqzZ++1Y=LO( zv>G)Rz;A1$pS|+Po!Nok5NepV;>d7)5hOd&Usd_^l~~g*DCEtX%csocakB*yathk@ zo16xVN56~1vJz42GjRW348_>8sry_DKSxhPKhEzVNa)B99rrUchI3I{C5w?XtrL^s z?*H6sd}*C=_SN1#=t>uRrM`8S?g7^KR;yHSSvLDag)NS?>dye1?~yXFgqnS`+O*L3 z^~M?om!r^H8^5Hf7;Fbm+xzl^3pxW^oZ5Mq*&l{9E5Dc~7zm37*Q@SWqCU4si3>{R zQo^pTe09ErKAFrA`btsM{iaK-VqEk}{O!K^J8F9q=f~;A5i9=>XI~i=SI})40zra9 zf;$8W9^4b$NgzRj26uP2;O< zs!pA=_wKqZvzTBX{;(a#G{D&;KqS@p*gjy@5Pf6T&) zf~P~&dMFc=OuH4In~Ex2LB6<-jf53iCw(p zC9&%cEFCogz&*;X3)&dF=7S~sV^B>TbS;Z7PE8FWPr$+Co<5pc%dr-9H_@ezPs>L@ zYuEJt=yTGV3Ly@Nzt}RuVRMO0^lGHu<@=hh1adpK>~RmTb|vk};?9pIlpp=ERv)T) zfVI_+g(4UPll%K);X=!%yR+Vqsmbd5Ibz%#eGQ_q#SZ+ zb85Hp?e9|WwGD-2+)Jjzvo@EpX@AjuIC3zjnbzhd{m78`?b8G&V;#9xV+LYDWmt-9 z30+rj_$yXFu<$HtlvOO~T!)7xh+Zdm8*S~hhpKRLD6`expgedL1GAIV?viwL5`<0F zJSlPHs1`XP(NQGSjTwz2kV?&G;0)O{w7>5qv@PeN*Cy-9kD7gX)oh#cLiY8Kqxt>b z^*7-Vr}ZDmK^`-@gz~m)tuE{kC?A2MmW5mb%a@-wjL~uuVZ10zAe6bsXkYO1J1&D)Of6cYZWVy*Zk~WpSz6tLiS~B(U9swr8MWto{4Q-RdxH(*NL^%ua=5^ix??Pa;U>dBvPJ z8?xo)C%#llHO3Al4ntNClxv9XUh+-7S({21_ccn{NIc&s3-JU(es+H^hw_CD)FM|w ziG9~Z-mk5WhoS4&Omau|hxbD_g5RN{;$+2fROCEO_Htr`*W5RHydDYcUgBs8{MH-sP9Kbdd{a7vdM|1% zrmidC*6r5Nz2mBEveggy?e*a~7>_-wM-L%XXp7dPHhNt>>D)uYza_V(z1h@%!j^n5 z-r+pc?L}II#MftP;+vym@=n;PYeTHu_)HO^k%DtnWMfTYwE zn)#C1-5w~IUI=ZY0@Rb;O&V{jhDk`Gdt7{Xq??~zU>|go99(VN;+KDELo1#A;woXY z%0Vh)%#U{<&o0QD&uU6{pW3N5WMgRncu1M6*%H#0R%ju2H}gWJFFZfmn7yfvTu_I# z7fSdp*}!q}T}zw%BeB=3K1~ywn0bN^>p=Ho(tX-CC*QedvlZRJ7&2$vCH9jcR2!*7 zD8QZyrYgfbNk(=S1@_rmDa7$&ulLuUIZ!IBCqDOU^SV~kyX=7)qOCBRDOb7^5Jbl; z3-<}lZqnV>CQn%`2At4#(EBza3jk2v9B#(2+v4tD)PFWZYl@=TEE*6 zd7v&;t3+JAYJU_;X3ZHywANU!|X|fi==tLaf#dP0J*9I!>)*W8n56m@vKW6 z-enm}DXf(M#e>iEc=m=-h0>YaA#KSSUVg2?&AVP^A!8~Z=CWyKwtKCU`X9L^fG00U zH7rzt1>@f8k~2YjZj6dQsl|U~(41HzXXDCdn@E$(##M;#f-9B1jmAgv6w(C|TAkfj zz(!-_eUs}QZ8?{s*;&bxBm)h&78W~;4=lOqn(V_=HwHp97(2EQV2tY~hSnadM~Dvr z#@IAY~b%3m0V9u4wIld4A zng8$Igr*6Lu5&;V<+Y_itiAscsrMo?ZO_^V_sgq~b7{0K7w)C=DCE0FKbR$11}CS*^P^7mJ16G0&CfJOiV%HFF-LT3BQ)<@|U3o@XUj*F=qjTUoDSS!!`XBot>u z1mnzbf-C|lMqxLUw>om{ra{u#A%fZZP5acRQ) z&Js&F&0zOq#H9k8`-b)reGgEw-%CfUa7(&`{TRU3(Qg~pzu<5ViNsl$k_8u1jJJ8c zn(ZOrjo;|6Z&GGMe1Ipc4t}1n9EQEPN&TxW9WeAkxzEG2p(`W&P(ycaY@Q7a;0sSq@`t?CJK?;lZJ&KnRb6OnRm zNWZfHV$JOq)-lVTMucDMMdc*7xfCMwEKmp)Ri6ugrD_up2M4e$E@Lg-=OO40#NC)Y z9@y1h@A0vV>l?&Q)qLJIZ|CV?-R~SCBm=k zeeRs-l)unpb48-Y!Hy+QJo(lv^x>t49NOVmYn1_sB-S(aSAEt< zVm;IdYL@ou;^Kzi%nJXc`yq?>gVdWtEQ{cTkN8h16DaR*9T2ie`c|Wv+$X4$Py~;I z(3@Iel#o`-1yO!%6B@P`@h)BreT`2XJ@11u>2S5u~Y^S5gL`?&l0|BU^of9cGBBmdiNvC5<}5(SlggKf*woF(_O z!L4^I-q1rFDVqP>4prf)2FL67xm9`$l_K{_c>2wLyxWl@je?n)x%Z6ZocnApeXAhK za6A?N-8q1Oa@B6l)VlCy8Od~sBnLXeB;jDDKlsS+J2WZdZ28dF57^DU3H46e#W7a5 zKAHNgI0@*LTCd@&ZxNK9I?TNvStmuYD9{LDZ(ZF#1Z})LXSMKs zlc^GsLv_OM^=j~wt9};21W#;BnB0@zwf0C#&Hi|@$%Tr=)nE4pPWz@3f`N<+Sn z=gJ!~_>{JkX~_8E)}>*iW#z+J8gjsFcw3spyLRuOKJMkRr6Z5l_$hMZnQ~UZ1Hs60 zz-Cd8sZPJ`FKV`Ve3q{PpD?oM4YCfpoqXu#&1Vhq2=Bfm^a--0rKj7uk!_@^)hzCI zo_xr)u$((W8T06*fw>`lMAG3`GG8eIkFA1JpF{Y|E~%DKOZR89X~ra1P}hTbo$6_f z6;mdI7q?g9$4#W1m3FJA^^-TZY+LR_3=t-Kt?jA1Rc6zkLmJA!1|^b)Cc?h^a>2`~ z4~VQ&pDtVkfgdUZ`q^Rfd!i=DzD1En-|l?C^^Bn8ew@rn_lMk0RjsH2XEZwNZX2Ec zG3bFo?K0#?(|jlVvU79vw#gJHzz8jSf78#ya!zmwEgF6DuxUvK30>(&;+Gx)k_R=_z1nelUaq2rZu=ZCch zEAvu&;7^k6`+0drgO?j`ZnGm}T6f<(EIbnnKzWYH#y#B0EUe$og-kve!zv-tJvh7t$5;CJ>>)K#>9->ONlNFqUc#r1SQ-NI5xWLGIriqm`>T_9? zl`P@v>}=|*4?GWY3=5#FZ?@*YE5_A(QS*O)(C?$PH}ze#jT&B~zf`dkWi_TBnJ47Z z8adVdp*GfDdo!j?iMW{vM+>uai)O}vl`*qp(L^`Lf? zL%&=HY16Pu5%N0(u13U5H7q&i25o`FoA($IUi7?X2Lt#y-j8wrQz{?=;J_YzNK}c1VbNwYr(skIs6+;4V;@xJNph|7mhG;C-nS4Lp*YOQ8!^GMZt+++KLbGR}n z?)9T8E^to@v!gj|ZTu~bWd$l+Hmp$BR!Dz%sXh1c-dE4m)COh~5_ws3l6i<-?Hw+Y zJ6&~Y8NBQ;ympPHE~@F~k>}e`59-cB%MznT6LfLlY?*aCwh8QOZ9C730%mm!gXHcm zUdCQYx|%=}Jhoyf4k1#ErJA=PQcGC7Ek@T44^wq+)mo$P31wl)!tzvql*IBSq|K4C7yn`LiCvWdUw9&*g z-^C+W=SFskyRazdp@~;NYS5x!V}`m8NHE!S_7)O}wkQ$EI{Bt-6R`@)%!nIHo!X>)P!41yzld*JmO<}PHe3y0 zipmU4mzgEbfN>%=w0A_GizED(zB}ALC|FZLJ$9`frtMw@bWCci;Oz56V}pphxEA|X zzYhS3tmu9UNy6E}mQ~mKt+MDllO%jcxn~_C zfw$;aJ-gl$A1(v@22$6(`RIF zsS&;hv`7CIV{fhpMoj+Uj?6vgQ4Y%|qAn>q6==T$QKy|tfUOn953YlK?t9dOfMjD~ z&>^Tf#HN4z>XV&LRZ7w1x%Nw(6(NU1+>JF}Z2|N4FuW$se@S}vbIu0d5}%WpY~Qwy zCZL)t3PHylma*<5azW)N`>zJl*#fv`GM{I&y~v@_MDi7&rN+`b(v>zYMNf+hzWX4! z-bOyC+h}wQ`4x6qEH>v?^Wm=-waY0tUg3C1h_uF}7cg1sEY~zK@P=t#PFPg4lujP4 zGI^%T;T6j$H6Dl3kpujrvCZ_MS(S>x6mX!0D{!agRc8CBa>h*ksBZV}0w2fTXQAEg z{cI5u8ogHpP2MY9bBgar*k8VnCk6&gQ#tC@`dWBdOdGb2uXlV)`;50{_fa^Lx}8Pb zRO|xMrh~anj*5$N-?I-&dUmM!ZS_6R{UmsS#|^pt6`kwKg=@{L49W%aVml^}5NYB~ z#hq=_F-Saf@w1RAo?FVXG5dr$YZ~`?cK3 zq{C;jmsmgfyU`+&h=8)OEh&TTe@db_pbcGj;?%0qn=vZZ3 zauj(@;X^+(hB`e-jm{npgR2MxV+}T=jouolH9pr<{mCg|vU2s0htNf5ssc3?&L@N= z3^RpBj?kEAE;w#vr=^tgBn{HPp8Vd&1>D=MaifvhZop{16gLxEjA&q%{>3Z~y~KKe z;;niruw*F4-(5hhg%4|gCjj2+X900+&u8X-cUy)koL}T#l*dOkRR3yE7f%nbfIdfP zKtQoZ!JS`kD!7x}E5&K-;xL(B(OcEo$vxEweK~dA)A8KwxM|$>ATp{Q1Q6MW1cSc( zcW$NaiCbX@W#uJEb?$xj_F)-)Ofy!=bsWeSB!T7bkqW&Eb6-0HiCNkABMVNQ2#=hU zfi|Av-c0|hFO5CCys0kxZ&z5tY=N`WQ8qsQ52Wypi;7X3{~I+@AglO9jfDJw{OV~f zwCg|~ci2YG`Re0gY2It+rD{%HB~J!a&u>rUe^r^X^B*k$sCidlQex|lZGKY2zQ{e~ zD00KII{BQDlw-)2v%B>IU{RZ?nrp{KrVt~v@CkaM9S^UD8xCqEzV{!s|L^?D1&OhSQ5)WFnmHRB&;cGz zNMvYe2XEF;)QhZ&(~P^h|MSrP$={MW^6e*prCtN;zTl9=XWE+f@G?3XrMiWR_(g%= z2$wYdUZYkt(~Rek(Dg4M-9Or*n80l;B*uQqFVyjBrtw$Pj2$X*ktEm_8)unq znV4A)Btz}Z_FD(Oo2;zTwRS39Cqt#PAawQ2lAFHi4#9V4BD>f0J;hhrVu!Ww=CxUV zYIUmbWEmk|f z6Nk-S!Rvk9*Vd_320Ftr!bwImThA+J*8!RNUDwD>9JGE`IVBucj0O%FOtHzQO^JQYvjd7Y8jakuD>b_h0;gB5pM@FxNyHCHt zbRy>YnMnb70mg45R7+2Ez%9W7p$)J1=9e@J6n>lrbKYm`*qrq2X>Nc?ikDC(rsGDo zaJKA_D!`;r+Xz?9*r_b@6V?7Br7;unP@C+PR!~ruNTe_iQDj@^iA&3sl-T{Vn&<|i z1B*j~EkSCI2X!`vRz9~QzAUR{x?EQgIlJTTVMb(#$2f zqmX;>^!rU0a4!6s%6UTJYHcooydjxzaY=Dg&0+XXNAeHJA!wL=iQ~FYvA5B+3B+f} z0>VvyluvfY3oT{O;&9 zZha;P3?3B2vYshABn*~?k_)WCw*`iwEWn5>C4~%+YuB(*=1rohZ#Tl#YznY||On3TYl#RG8$MQ#>z4-VO@3fq&J&M>oL~WZlDD}hk01eK| zJG1kqao2;3==K+lB1HR0#^g4CnVX>}=0>?Mm?2|?!&6XUJ@nZjWFAEjA#t29>g*$a z8!I27>)U>gN)rNM%^$~RNe}nfqDW!9_UBn#%+~N?h#!J{>EZT^5e!`;O0-F$| zmwg!x+p{FOQ|aX^*4K0oUTb^Lau^0KgACa3XmrBA0muryT+)V%Uc59pGmLVc1RNr7 z2TV%JzZvSZ6<8u4nV_Iz%=m|?3}yLwn4}GVBk#FtLAmj|uJ7F|McCs@{kFm^vO-pH zJ&)W33?DL4J;*?7Wkq9qmqAs1NpkOz7sy>V(aa$2XhYuP#Ev++$ys~f3H(+XrET8o0>J#hQPC}d z>%7Fn1^tK0^qKm(O)sAJvt5(bztL+a<19|&UCU9gQmy@oy%4UH+)#KxE?3{(b{wOY zeF%(fl@PM~B5f?__C(yJvxdhxoa_c~&JQz;qB9&@)2UlPVr!8m$X1RU?riT}eGs#x z528C zoo=kqNC{;i;)&HuoaGfIHv|716&P6eLCe@IYJ=b!)3BfH|zc)w>WP`>;uv(F^8s*M7+XgxGB=Q+H@Bbf#=;l7feV|!KyFD~$= zuDKxVJ{mZZRn0Y!P(nf0i`f@A7H4Y~;W2_3YgZgJe2-SrhcivurQ4j-M*r;Gz^LI7A zg(z@Luw@R?qZKnhot(KKuu}o98i;pu-2~FG`n3P$TH)DBDE&_L$yRmQCTZSIFAf2D zAqY4BS3~z03v(L-Rpca03GmcnUwnHP$Lb4;)C^^hy^X{tAYocv!n+-RGj*}3PPK)7 zY6O!5$^H!QzoY+0UQGC|gFaEUj{=!09g3r;sy_J(?3d0mQ^m6w5;irYFY7M1F*phF zB)xwlceMdzQ@5znGD-R6!|)t8w#9EbAnZ>v&)HE|l{k1w;U_{XEll3K!^w~}U~A~( zzt~Gw-I73rYt|pc3*WB2Pl1=5MJ(5`EURY~rLHMJ4Q&arw(cPifRUO3G|SwfUMUof zmU#SFv5AuZG>GCvday~GvljY&6-U6c5$2ucbU(V=e%LvG&%LOqcAKg=pJ=DpC2+yD zDqUx!^;b|9rBkQax?vQx=9gOu@ogp4#ISy}uRk46Ommc(KfnD)u`s4De-DG@N$t>< zc7y4XQ1WM97t?AHk&(=H;{Rb`s>hykZ4C-ckvq0OBz?LK;2-?|LPIk-gIn1K60d3?Ua#!oc?U&N<_@K ztTSFq_GFHTJQTRU_;5<`sUiH5CmcO%mp}f2F3qkjC3EMYM&qYNjegWS?h>r9B1O=|V@Lsi)wmCBH^Vo(~|g~JsGkI`dN547n~oQH7V9T ztNS<=38fT)GeLkHSx>YG(|WH^Wq5j}>~13r7-$Ta=Y$eYPG^uBu9k%#mv%0Im|p#1 zp?ZYny6`Hp!(i_+@CDy2uDAbC*OS!b(Z+O_1}sVJ8Udf|3u}zN#($X4{^zA^woGDY zQ7rmk6L0V$A@v-msI_a=c1cU<0kSgRI1l(><1QHf)r&uE1e5 zcsdKi>AqmX>z}?R9te-ME7nO$1-ocBuB*$&X%MexD;rDsBITKxm7Z~h(362fQe4ng zcDA$Ch6X>xhSuG3n`@=|@rmmQ8@qP~9QAOFpb}yT-xHKy3D91ykQCRD-TuB%@wW9{ z-^R+R{!F!Ihx?nryqwo~e*(SqnfeW<@Op?GW` z5eDH}VYYU+6llp`C zqadZ?!`D6Yn3K75A?4gj~gK7+{15pIlO#5u+r$YNpgWP5Vee*x%Cd8al-{X(zuc4B)3!!yT5v3e)r(X@^zoQKfN;}2FT zdZgAJEmKZUiez%3a^gre=e62Om@T0~BtNE+u@;xa&gF3+7d`=GtYfp}KOj?B-*zqn zT#wz+!?FnWHiQDRGTu;nxy4lMAlZ@=ecNqHH&R&yw;{A*_@}qX2xI5&;B#G)55>(T z=DN8g<@lT~r&t|%uaQ0ncU*nu**hdxDo$KZX@(9AbDTDju82(2-@ntLFmaA0j#vXM zI};0D^LTWuDDJG$?_juriF zXfDCL;cYbeUUCVSNlXEKMbiZA4rtz=sm8Fkjfv)H&c3Ei)FZ%D)C^zXACGuD!voH} z+=mE}4;2()2<{`Vv~9f1+S$B`&_A*F_13Uq?SItXne-p5b1a_$TOm zx595niNu)EFD479Bqk$URQWDwF~^slFjarFI9K-fC+aKyGw-r(S{j#FhS&MRN=pCe z0UVx$2C#M%A)C})LFUS$aEkw>)Rna?iGmbFVi=9i&Q)%mMMk57GEwCvi{~mRwOuQt zCl`rB>rB4vBmtAi*U6?Wx^gQ5f5Ok%&7n*7RSe@~4D=r(2Z^{kY(r}e#8-s+I>PIe z7igPQ_#*1D{7Mw|{y=WSc^NW!_n%ol_4>7KpIgIAMM5&t?;3~PB=?KUb&_uy!k6{} zhh9tKzkT(`v=+rMWl{h0`9?cx7&+}5j?a3!Bl74L3e%csNDelZis?8DA~AQqAHW*i|$p2 zf+?j&>e*(Ri@9!yWfNFZ6N0IEg@0BJG@@uSrhN4A02XCeC}!li31{v*uIVQX8m$7{ z4n(@{Ks~1By=)`=c&<-s*jRFbKlQq_g$3iEZ5X!k{MiM05(ZicDA|dq9javsV|va_ z1EZkIuqi?F5J%km?mUwXr46T_pk!K272%NELN8mXnS`zukx1wcjSbEL{4Y zm(%vA|2}E1KLQiO@mJB3p@4Dub@jAk|AZ^kjH^)OEFj{ph$f{26Few4u#he?-4lUZ z?8r4qb~=xV6Mlu39L;1vEpyE(ZV5^dJ8Lm5&U0*o@sW>D+8J&?aZy!-FSC*UQ}bsF z_;^MxeI^V{6-W1zFN_L4+To-~Mv|q@5d(=;#g9G@hsw>L{h>>|T!(**vi;+qO~M8T ztf@T00+)$@fY$_6B-%=X`9p*=OjgTjyoyM~oe@ii(Hd~Q*@HG*{f{=jsE%-kqX9B= zc(ZZnxOiQ|LEDPk>4N_0Z!A#@LZf6Hg=W1+m-n^7*ryx^S7C zkKGqBCQ1C4Phpe__dnZ&NtOb(*V{+~m#}Whc>5;7v+SYQ!vi#RH)gEkV;uRcOp=_| zzm*W^Tj%9w$Y`6J+}G!>CE@`0EJ6JK;@;E1<9VvB@E50a%8o(L9kc0~E!Cgoh%<_I zO3?0`QG5p7w``sV6tT=puj(&j7Ww7kJgic(Ts8=7f{=x$hgRucge8Z)5+=;Qf>p33 zGFzHl3rb(O+)!@OB}XGZvyM+}c5=*!(P#X4G|c*aGr+w>L}}H%H-DHZ)KAM=wG;44 zHxkE-OYFfj_P2=!qOMoa>L^oL`i$h6S@MZs6UXWWbla5uX`N$F|IxO@O2qiEN)&4O zwZUn5SXfSN8m**a$6*F&z#h{W!G%!0{rIHO#Sv>Uy`a&cUSk|_Ia!4EQ95k1R7iY< z{v#2Gtraqsdr9=7L+1-t^!3FPj3%fG4aNnQSNZz^PFtZ@G_3++x5*EDatR=q5-)0Z6TzOl}zpAi3$FxXi`*QyM6f|IJOsH|yQ9 zz;AA+KQu>`=hwP_KX^d6v65*f*Vu4+^QkK9mz}7c zf_wTeq<^WasV+FWfyL>SlPQV=4X(~U{hw}MJn8EU{j?fw{l1jadOzdj=C1$WHFJ01 z_6M+XFvXLRpIW&5-%#{)3t0P~wQm1&y`msT>KhU=)n}}s2M?;Vvz)E?c7NQ}?Njrz zv={|c5_*--{R~yzDBw$}dL0pyqNx6G3;;w^OyPS znf>WG)$;X)lIf1OOzBoK75@|yOKH<+m27#`%)n*BxOkuYf_2;Jhe-AY}p; zEv(L*Yvpm1?#}i?K-K5|P3hwuU75#G=jEiaYSW{~!_o=G3imzwY}vGI*&hWj%oEXR zPxTw4??{^TPm${-pKZw7N2Et*yNJij$K?Pgr`M&=pz}Uk%aAoXm@U#%U~lDl+<5HB z_QqRp$*$~6%jk(R`UZF9DblM1eAKP=JY^_-e8v@-ryT#V9lP+DHHNJ`>$P?J#|AN@*YVTT1T^Krbx- zjlJ1wOG7T;2Q|PwIJ@)hi25Jt>C=w?M@@;>4+Bax+T6LG6)2m1h}-8L%H4xP?7Tm% z`tW6T+77FA2gTnlrQOY>3090$ zcT}gO5jQZg0b0VqEv2{x`fu@O2Nht>2HpWhZU`)J?@l0(Jb?Q>U`PFJeWlXh$qieY zPbI%$YPAMly@kl}si#c?6{+gvO6R&+>qbm6T9O{F{H;IDt95hs77a|~V^n%9a=(&&Y|^)K zx+Rw0IAhqNp(^>W^GzvHn8r1BYp}X;rv=h@RZ8Up-Fi_5srdLUw_EOv>pHX!_OjBR zx3s70r784>`WxepqQmzWPV~(L- zqM;zT#jX*go2gTl*+-D`J-NlcA6ivK=sm4u!?(tGh(Ry}VD`|%%`V4J-jNVK_5pGba+qW!sStcJT@0MeBJ448J( z%vtC?#iGo1nk$71T@@@tq1+ygT% zJ5L1v;Op?W=7#&ngC!rw_^Zs_o2xVFAgOLF2Fggz?-=@~NbGCer|2eB3QZh%VpkNb z^F4q8>oJ8<#DXSbd58MBk$E`umSF5nl3qoi%z>d2PG^?m<|0bp=&~)Ai!7sYkm`{Z z5o2b4h?!Xe_pmxMjVew6IVdjcUaXoKbc)%bry^WQ(x48kgq(SK_umSVdjZhJtA&3{ zZO|x6nmOw3@Y_(Lf=NbkJPM;$*&{p7*l~&sYK8XGAd(~HT5<5!sOdWLE8UTWW)~V^ zJ{wAB2J^PQpUpxyvz+L|zBj9J)GQD7zf0Gt_$BWXR% zcrA)45T-~>~U2( zcQ!O)ZH>9HTXG++suvChrO{KBn+W1_V;CQBja*~)m00u#(O1TVu|$#WpaZRSsE<+f z?pD;1!D&D37FPAsvT(7#f-ORXmt+oNFu_jNboE`5zVu$f_p^0meMGFwkt`$&PTae+ z<0LGt#GQ4X08RV*ZFAjo73^Gm&p@T1dF$--dS>1x>ojd)We<10hwkfAlMk6)^8~RC zh{&yE1!iDT(=jLB*)SI|I&>2p&hku1@2e(&TgC=Z{wzkcW{u>^U-8a1VTva$5tkl zi@ojY5EKkaBiE;isCak!I&ZvWH!mPQs=E^%EkQr9^%^oR=xp#iE&{;MJ!WQyAvw!& zTKb`rzCwYkLy+_H@MoUh>c#I^q9NeZ2e^F~$Mreahr7;I{koXp)ZhIzQi< z;0+~#B8~A81E0q4qrp2ZuhqU;#mp{eKqQA_`4*B7zUx#oE>7KH2%0wHq3)9aVrVnF z5He5yqXlqS*JkaUCjL;vZ(EUi-=^Zx5dhT+?2k@2b+f&7tLdY1-1fXal9Nw~qdb+T zW;aRc1}QWSVw78y6R*@i17zwDk)f_B)UU>hu?9ANm%hQL3{?M#2LC2mYG8{UEzE6S zQe!%4T+i9eccQwQInV82Q2l)yQ-jxUXW0Vn2z_bq&7#Ig{SIvjLe1oFKQlC23hhKR61Ab6&Fx$)TO^|1>=Z@bq(+3I-6kcFh;-MyasH&Weu`Kvp z3w(^ZRHhrpB|=w1N~w4rd=^R}+!k+Iuo|9K2(EnYs*S-U$IPpx^BmX%J0f{|bnM|m zUwf^YTBBNOKMXTJnR{$p#9OH5a7Xr{eFIq5TThMH#96iT+|r)!mpT)#R=Vq{fL-WTrw2>8vfqJSw&ax%m9S_l)yk!h9suX3%v!amF~CvQ=aHsW04JzChS z-Ob^aSRuKihaL4({v#SCTeU zstcXOc1Nmn$))BXO*p17e*+Ve`+NAQ&#!S`kqB&TqjCt+U8wr3*vgZNX4O0 zjgmy|EAyb?V%6uw;h>6}()IW0+R-5OdwG&-8LAdy$>>Cbd)h3|suo8bLm4u&!cLVE zfkXA+s}uNcI?_swOS6jb4&@gGgK}WE%sC9rD(Cvj#8_&6Cv+&&l9VW?rB-m4YW;&s zeDpk5Chpcd?0u$}gSS`%54vAdq?GjAhwrxt1& zxmoS)&jKxEB@8;ra-?O@+xXf?*Pu+ky71{QFT+Yxj~-yLq{mC6!Q|Ap^!7V%xssLs z(%^bi-2(1vM<|1NxrvJ70ps$DrCj(`e1`-31P>>MRo+o3qAR25Y=N1vhlprCNaFZ} zs4=OE`9S!&()F+OH$P#q;y?3HR2YVt+$F&hDPc9l+i<_b>eZ&41plot|D2z%rq-24 z4fW?N^?#Lw!8yE6E*=O&NE@(L}X|(?Z3p#DrRk2mIPM>pxfqRL$=`^fv-%OUu_I5@PB1( zG<&f2uPLsfSw>z1N8`-Ry@xiXE|gBT^#%JVJ@4B%>~8juCb8Mlf9G2tlEKBS33Ir_!(*AcM1=5G1CfEFS&aN-Z-EnU+_}6`_T{$2=~gz zxRF##6ng!82L)@|D-e*rYWeQNthY!KZltS)3wG(T{Etcj@q3lbIkK0yhy02j^Y7E) zlh+Rxh-jRZ;F)dS?CwQP0+wX;qqBqXTlN;(^p5H3vm`L(GYJkkravTVttEV0@3kxC?(^OPStbf|rNFp#rYgpc4Ha&9!|- zcPc_A(!Fi%-0~4M`n7X!mGGkI&K{Y&Vl8eho$2z#d+3eXrI7)u5Uh9ba(K(a$nw!T zfaWri{N9;j>4TmeM`+@Qg=N_>hm!a<;)z>L0uw1}FM!^ZTf5f1j-h4Z4qO_NU6C?CM{5s67M)0oK)0zcwxbk!A_z10I zP3W3LI2)d(-T+QS$=jDDC}LkeeZl?tR#q6Pi3AO^>qk_s?gv5=!|^e;@H4k0G|U>N zSKwLUgGemwgr zjfY1ueXA|Ti1j?Kj=xHYiIgoAKA6;<_58WfhZ1@J;a-Hk_Cq3O(zRw_9pSTv$DD5Xw3EDFCr$IeLz>PuH!*w@DHFIcfEA)Y*B9PZk}3=t9jbMZD)}xv!^k8>yPRExB$J)VGgaXB-x0jeK+&cQB_j zk2E@TUemxVzWBDF^xf4;&Ms4JvM6mjEU6|3?rR-7_%szhxfnk?|E4y*elinbHllpx z!Z*4Z9j;a2c_7a@miH>rt=CJ~2aM~U;gzW}&d6{b6&-;r%ppzm+Ue2p^aAx2b=Ivz z9AzH#AtD+|n}!Luuc=WRZH0D4ucpSl8`FCOvIYf|`73`djE(*JvWUOyT^C>2uu(ge zr0bwxjYDf+BpB zdtr-IY;(}V#qK{vPG?_>`G|@>C&R(U&;iLm`Hr`)>9TflKGs^9+FO2fGMfgQQMsF{ zw6J73<{QDLLstqKJnjzy#1gmw+C;w|qPA%l+r6Wff$}>q*uj6;`-9Ud06nQT3%-5Q zX+7=$b1Iuxs69V@Wta=n@xwGA-~Hi&{9=bb5fJ9kyOIb9~rZf-grOJ8ku`Z~MyWSx3g3v~G!U(6Fm})m#x! z_$}2=5xxAY7-V+*8`Hg`?fB>O5`3h>p_kjgGsjVtct|J!Tok0j}ErqUtNd;#!ty69^JC z!JQD?g1fuB2A2eP5AH4@xVyXi;O-3W?rwt(yvaHD-uK>*`7`s)?%vha)zzz3RT;R< zR9C@(NeAmkDS2}9&k@nq*tw`oed<%Xx^dzVG?Ld?iD(cr6U~T-_2`9ZU?M+o*xt8z zuvw>x@0;;V>-bK9jfEDJ=4?{$;lkt*uq-)=S7hvz1v^;py2X1?6+At&w;*Z-mQR1; zi;7zwM<50?j1%|>AZtsfEOFE-INE<@Ah+Z5XrvS58+f&&^@wSP??5BH6aq;{e!u8Ip!OF#t&lTiN(xaM?E?p-CwEdE5bDFk6Vc- zoWzLRJhNH^)wh;A&jOCD!bMowj;(Yz4MN4W)c$e-qua>x1HaWl;VmgDJe4MWK$z_n6MC6Xv1j}ceig@(g7^F z!iRMT)K#fr+eYE2``^VuSuBO-k^<%8Eh_Q5GGN2OAV$EoM1i3K@)R5nXV&%sRG)hGl$U5clgakbdMk!G}&ejr1Gy25aR0IpQ zLoLw(H!GthjC~hqn^#*`Z$L&S>>$=eF&ONelQ}d9HBrFNv97G`N)CRWrdY*PSDEPO zk2z7~Y0Gp3-pdhB)C!h?Ern7Gb-6_*+sp}wh%3W^Y*q>=Z=Y{z?#~(;7tVXW zQ=^oBuQA74ULHBATP~lf0>Uj|tLh6pl6>(Uw+MLUujT4ON&$ZSQ}$9{Rnbn=v=Zb^ zCq^^42$1W(bBdqHP|-P>iyq#ugvbzdRNYZFxq-QHx-b_IrtCl2((xn@7&WVbsX>Wd?k6rykW& z3Qsu|XQC6Z$ye_EA^r$vOIEKm2`dRF{{`KTgTGsEAohy7HswQ z4*H#YVmTM%Mn&7V)Iz^XY>=rIcWY&y`Eq%$BT5_Qx1UF8*2Xpt0z92dQe&&Kz;ir; zNk~@j{Z`qXN~g7_uctI>U|5HB-qFO`|E3s^~2EBk|WMumFEq(C^ALF8`)PNNxZ z9k(V<>H3bcUYRKwoEcM&IY}poReE{&b44BI?)IBHYo^6sC}%rR1@NLw{Wx!o7DzZd-=}85@2bL?fFZlggC(X2%g_Ty?r>Q+wQ<+%9(8ArQqa>u88aS>EBAc=p_x*(xW-VVd>_=h|jZK9e;O~TI!T6ML*YI zMH3?$3e1Zh_R;?e4E)r@G^`4FEtpc?i1utMq#Q*?r1KWHFom}(vLp>|Ca?$U2;r!2 zO;?NII}4`j%4pbGr|!4r94I~Rt^L%gbv~y?>8J!rdP~yHwi3ekQfdQ z+IPrv)97Rd>!SJ=n&Ld`gekJ_T(iGatcW0!Y_D;zG|AQpERltQSXVdFy&8Yo7Gfv1 zRgZHXc!KJJZ-fN8;lLj{*M#>MzrC#BFE$*X9==Opsj0kE?3@WEAG$Zmb};;N!n)z*UO~Wls>LLeJo1x!s6a~p-C%f`TNewZja}CIPG7hE z40duYtowd1YwOzh`1(z_O~bt&d0FrKrT6t}6T@tCwlvt?glzTgXw)e6tB|@tSgh@O z0%s!WxA^0M%KXb91#q=Qn-32%C?w3O$Y4|!rYi80(bjL-zwWFrhFEvkmlz?G=JL{) z(OUACIBV)Gl}*G>UWGY<7mkNJ1|_(v>_g~m{r6ymk*=Tdqe)8Ne4-r+h;I_S$C3mj zj^4^2ZXQjkvLIhRGV2^kv^c=*jr@%7elIJ+eZ2Y3)8RAu=fV3tmDLi|>ziZp+r`AI ztK3o}YFrFeFSTq#-eCZn=+1!NHYFu8x)z1V%ba@a zde$nl^_hz>k50Zqzm!}{dqOH)dVU*veo?aVrUf&Yvi0YrF7m|yUM;0DS)s+If>9qs z%ayy0LnXN3{>Tct){@UHi83rB`8aaO?nM-JJ_>+4NYzaJ&jK8XqgJ9C_f3qu%5=S& zk-o~p#R9ogIF`fcH{`2bozE(O=pLNj71ig<7qkTJnAM65#>0G`10;Zt@Z&63~GBCe1g$#Q&WxTk)+Fn0r8a5w&41NQ> z4NbkNOMJU@4t~=h?u~iDZ3%&ZLlUp?-4d_RA}ep{tI-v^S>Ay!=Yzv?9U8><&z`u16E}b3p>Hl$BOs{fAWx(jpopLq;o{0%m3im})~+2R-N@ zNv;wX@H5FM5T(D6h~PZY(DWH#qEjUD0ie>d8}=Fp&D+u$l4_cEsZh@5eZ*NIK>;^+ z>$+mjW0<$aw9#y3EC-x=uG?v1AqHEW?>*#*_ejw4N)O%rIfr@X1HxGYZG+5sF^nB_ z^ol@vbc?4zlcP4`kDK028PJpzRV0q(8PO*n_t$z3D#2UgP@?dJrYz6zVc&@|)F47U)y8Hq}By5c{J zPF~NTw?(8D&owW->qQ9||5NZ66j}A3viWO+T;6!2C``i7N877^w^) zptR?A=^vGZ8FY=HF&fIOx5*Wz4bTPk%fkhAvMiPO)p##m3Pfw{AM}jPOGZCm!vgr2(#ycfIVJ0Z2B9;>vrNmoDQ*^pbfAd9-2ldJElTx{ zq}`RXdV*0SeS1D0PE;>$jl>1uwKVDLnYU*OV@}b_>|ze611C1X@aqz6?hSMGHrs8< zQqY2R!QGvDD{oYDsWs=qauE`98-Or}{<}nVV|3kfDm(;uD=d;CvLs zcQrK>YFy9@@DNL_#Qr*ac4ah2(5$XIDrH0Ypd5Hk|K2kV7)UHo^H*y0o|KA zsx!~;%n<;cVD{i*HCV$WTBbf}88ealWA@s8Ss!(}x+6N(HGq|WYp`uSOgG?ELTY>P zYd!H%H-J+7up7SM{vpnmBIw5p3!@fP+E3+k*ths+XT+A7bN!hb z z1Qe%^M<}X3_QXMMcSsYIxqS_vat=gTUz{0Q=loVw6gDOO2Qck3$DC$d{ggjd#N4*= zktG&ko0&(IEHyR8a_$s?A6=Fq)frlU2U);ZSb5qpJ@e@W`HI|Z+7Yl)Z?z$|(g z^aWsAXEv(q)&y%Vuul${lOY&oyV&r&J<_SMu_5tZmO1HmNo@+21O+&&Ap@){$Xsj( z`4p@HPyBP27nYRGc`2I%F1MI+1PTqCX*75SE}u^&tIy{cx3Dwwy-XS08=x0p1)_96 z`lr$AhuoNuG%lQy+zO+Yn5JG;EY$Ghk+X?_uc#}E4;p|Ux%I3_uC1VRP(8Yj^9vg@ zFNdk_Kx=&+9$zH8fYKMGU;MuFE7i`Q@4;O>9=WjzAJC51r_02h!Hu8i59|~jol!+K zaJ*f`e-hSV=*OvG`V#m_tn+EE>Y)w70e`d^xX4GnQ>#m@`aK!@c8h-g6k=@kawMRH zGyk|JPMq}Sh<+TtG1#1JIPJp~dDBT~+&@U1$Bc%ep*Rv=OEuCbdmTH~!u)h$--+v+ zd%2WLqg?6i`E*-{1A1c$ntW1}cdB{neCg!me@)h3+u4-x0U!gHpOwZVXsk?Y3kto@ zD_dFjZrLp7H*X$I<^&+-Kd||u!y0RwXa4=I!%G+p&K=g@FOw<%7*YKN4N6n1S8F0Y z0L`gl%YTd>6Jwhjh663W``Z^KcqX)HP86_8QD-SpmyPpFl1YhTLIfV;1hy1jcNLnS&)cdzybuhSkz`?$6&XutN=vcoW-wty)TpVBB^`d% zoVOZcKp&CDI&?82p&Mn3vy*ap{65nbC zDg7P)h7P~zF^BRfm31gj9whS_?cV*E57LYi@{@3Akc>qsB1s>?<4h7DaQFvQIJr}0 z();XE42&V@7SBxK9A6_vB)hb-p|n|}dp9O}ubv(R>4GHcsty~*+G1ucUqS@fU8Qg# zCov(lcl|g~bND7K#f2y95`UjQ#&W{lK8pUq^5hT~cemz^?y46KzM~Y~lO@nr2y^P+ zHSj_E$N8;@*RJ$6s-#IY5~3FG8aF{|czAwbX28rnM3=6Qq^M1TItpjTvSCQ{dEaYA zgA%Wms=*enZ>y}th#Pb@?f!ST)!frrV);$p8R1ddw#zfwxVi9v-e7r`8O|NSqQ8>= z)I|L8@7qGLYfZp>$%4!4GV^ne`zS&Wv&f_vS(76X!8Q|R^bT;kLAs|OS=;6DNI-hG zgdA_g-a3pV&7@7JhFg)Przjf-b@z`>seQK>_)PI6>IT4v1Zp8CnauBO2)apUH?k<1 z+uuqT#2aqto105jki#U+bZyk-Nv6n;rc9iohvmS4%x!^Vj2I)UCN1Ptpqi&UjQu4` zf*PX^7;(bD_>ENW?{xo}^ENxlUv<&+jkkZR@>LRSffUMoyG2d*NfgB;3iSDf3QQO! z#ncfmtBL%uB~d$(aIGXG!xEnq!88CfD6{pj$~a>C8YQ+?#Q5DB=jq)5!=&LMbU!jK zOjrrTOa0Fnjb#6f(S<xma;bjzfGTFD7sbS#?&q z+RJmXJ=vO{|7#^z|XV$cj7`5q?69CqC`?4r7c0Y0jzlUjKiBGRpb$kM!LTifINQ7x=fjsyKZU zv6dIEN09qw#v4k2SHWX=w}W#%(O4jzvvIjmgjS*{KQoW`_Y|DE6#tu1q}Pyfq^0wL zp*^bhtiFe7fm|J2LF#zvuK$f8ylV3Ac{gR|rmZ9hBc{Z34(4;f@02&(qltf=R8mw_ zF;(I}$8TC)WGvXZnWjweq?R!v7Whp~MZps61tXHy*dt9jP~=4=(u;GE?nmohGtj2$ z^ZCC*>a&*2xPXO>mz=63%UR^>r!-`Y0~0Ci*E99S^Paj;h_Ihg{3IWnwhPCY+)#Y9 z6XT>X<^`_6Pmc1#0Hz>YSNdqqy_f&hcdR@`9KuB>r_W*o)R_N!`kB-}e!4GiIF$62 zx-O$MbQl%_2LBtNC)C90}0c&j(MyP z#lqcGv@^L>dGDPW2cRw)@sv2EtI`l*NBN&IZdyRYKVLD8k7|{_<3cNT{peBLZ7Ki1 znkw**rgB~1K z(s7C{zP;0L^$;sX)Bly>7oAA;ZBJFpZA4a1rH?^Ac|YDoxRzd}Zc7_p|9`mv|5L2( z#(#JDl=OS&ymybhNC%q>oj-=*It2-day7JN-_Q_yQ-l16MTL|`VCm>9gp?RD6p^7D z3>33f({gN}eB>mb@;t(cv}s^b2VAZoXX#6ehC|0kL%O6Xio?+n(r+kB8*5-{S}AK*mMmhGC1b#lCW*WSFx=R)N4y4H zID$I$HXV+OFzU&19(idHEFia&A;E(GscAF#Um5~lui!Xx9tv_c66zmHg>^QM1218tI2c zwcB3O)a&Bt!P~9z`QronIp_1FPRldVbr1oU15R%MRRA=V2)8PIkD?q$O~8NU08g?X z!@YqFkqVPZ{;G`H{a4qwL(cuI^xXw$uOB$V;7tP8w;LYKDxLjnW_%I-7Sx?e2H(=e z+{6CgkCK9GIK$$^UUE4Gf&f))udwf1L=hiPa*cwYBukvdl!{w-P!h|vLuyQrEpoc} zhznbGOr^e|dWtXOkfl9xjlKaQeiFCGa2MxAV%R|<7fc`rDU@brcA%S+aSP{jlrEN_9@?XW08jKRH6YOH-Vq@lalV0JLi_$HX=c zC7?Cc&%b7-wYfw&mPGghh1N!o@az4wwXeAtP!_&zgKyUUI8dWlRaYPNYriDxnwbJ; z@PscWTtzB@L(iM#F%qdmA}Hzt>)j0k^CM%`DkFR6)GH?*&j(4(Y;jyD{=XW2a) zVu&|@_Djh^$Wc3%Q{}lw3zR2*h_Zgd#OWWp-}d2|tkrLic-%qSb)dq~ynifORa0cr zF!%JXBJ6$qi7^fpFWny>-bNM9tiE5M%0p;u<))MX5uI-8NJa$4m@(5Y9BTZ$)Z!=q zfKne3gBC7?KLc1A1RmOe!u|(N^xIN+U2f_YdXE@_PO8MS*Pm0b;22VdL6qA9KE8nsmb$1 zT{(gX&YY! z6_lp%KpfY;vm*$*<>IifhC%+IX*JR-+Hq$|M`1G-`k{&alij`Di}?XByAx44^7V4s z%~~kTvHBtYxCrnh^Uc>Ku)&ojuvu)_>z7OZO9aG6BMXNL4}U6{ zqx0Ssa6EW>$a>h$(BG8#mB4_3QL1>TU;ClA1@>l!hbcvMEZjd=m`SFi{6)q-NYGwT zxemegoASdpp-Fj!YN_f^x@>vsOMdoN>O!#y&D(xV99nfoE9RQ=ceK|Cw5o`mAWRM! zs5VA{=8w)&caiTQ&fF&>_wU^IO~03MD44%x^A9|2>g9S^ND}Z0$^xS4{;?7JvH#e~ z=$E6cS8CT)d$>nWBHe`+hrN;ftel*j6rbP_Tw!w4XQ<=r4daxho{ZqI{-ABad<`sy zLIdq+BlZM~6l|H+Vu+Rlf{ea+v3}I`JEjTpNK7uS#KVtw+AT68L((rli8eIQs{L^O z2-PapAK5eG-=kZs%Fq_!50*hPcV$#%G-=RRxs&>}@z*8MyB|C|yo1(Db-ERb#C(fov z{Ajs`JKO~9|6_M4s1?7{$yqmlNts)8>HCsIaj)Ym_YDqWuR<)*6}&0+e)&A9IPtCs zLU5sv5HZA_mM#G|tnb zdb=8ebV2~7LZS)P+%Nu1@5J5Fw#E8&zy585g_7y0-|nQM29W9ehq7s&{V3^h?JcK9 z`j&dHM)|mQG?9aJrr(rJh2Shv`y*x+bM&0vI@`Dvj<1EYOR2p>?@0 zU;UJ`PVyB9zHHL+gq(;tWiXr<{X_ps(`=dv?l&@SXp7z_9hO>9e(IOgT!oX|_f=`r z)Gf${5X;Ul3YXMmp}sd!a)ImZ+mdsQ_1{&E`dOP_rNZ-Klj>f5o%rMFjO~2B-Og_M z4^xX_+!MY~y&XF$qqA}Q@!7(4?}Rxm7eb-4($aTXKjRcUeHp{dF>Rk8;kem>A4iQ6 zP~e_WTMzc;AMhhAFm9S1IF3RNT$dcTBOaT%Yc@`O{%QWSqq|e6f7W=5cvW*_Q4%$m z`3_EAw!DGgS?<;zTn+gPGBRtY*48@no{ir4qnZ$f{PRTXcE_+X_j(L5PKS-b{UDoT zX-6|dbnWwxf}2xeo;0g8Gf26HS|@N!rlmpyQ1{5QGxHgE=(5w#q&xz0mY}Uc9ol82m*n)mlnPT);b+26M5ZEf3J{%Am9>SMX8s>^Cc^5!Us1f z^)l2(Re|P}a=*E7O)sFE?6yXKaPYaA-;GtHs-pt#xX(5RYfBl(zF>K?^ zcb%+81OLjoZOTE`>L-l(*BB3T`A2xjjvu#{7%dEQCD;_~NXpbe6D4lgd2&ey6y;n* z!OnMV=H58rRKaRFKejqe0Hy@V%qg3Bde$-VP&fn=7j20BnyfxRCb)9gmpb}~drto0 zJMpV*`h&jeD|@f=nPp|n0}-*VKuO9zK`r{}F?se$U#9)EBu@$Ui-({sqb-N^-aLs0xTqCYukO#?rEg-iQrH9YgH zPwE6+>6Ayfp3reCJ88ED5+VZUH;`qhoUIICxql1Z(m@1_GrdsmuvWbrj8!`nDPVL+5_)0)136myT7V%pIH}dmxn6*pJUD45z1!Xl` z@C{z)=eQ?%!u0@X)>B)O`%=U*E}7#WftUQm>!9d3w;U^-P+4pR8x*@$JTj;1IQAq= zaGs43L&!(BZPw1Y;q@vxT?Y5Y1+D$XxCd_cD*=28_o*-!CaD8QxerYyHJQJVeU>O{ z1(3Eju)41`lN*hzw#p~|a8Ju0;xepZZxg)Tt1e_=zV$j^s>W;1D}ehl7n~nJplvVqK1(=0&T(AjqTKp(&=w!z*2C7>&dQ$?a=@TM{)WWPE0tkUf)$PU z%Ihb<1R_-4xw#zk2L4g6#F&sOWiRoCm9-Q|_f-%l;?RpH-A&knVP z0|6`kD<~;HB8PIs+XvA^73#N$7ZS@niJQM^Ji89wflh=e|AipIU`LSdt-n$i4$-!Q zPoj8dO#dYXPU0jxZB~n11nFhd6?>CNKR;W)Y7e+K%4Gz1?I%ghi4P~(1bUSk*maKC+v-}G9Dw|vOabc+3a?Oq1*JY z$8pAUWuJU~Yl@f5q{ef3|1$CA!yes}K}cI7Zr!w&*Gq-3^_g~P(&D2}K&eY_2DVh} zi*EKms3G>2>g9Nf74PvH_teYL1%B--J9TI%yr|+RJlen6C+};pr794cUVx3k=Q_`L zY;#`CE=`|2xVgCuH1<>P?;wp(Zmh{nI78|!Xtmh-!M)*Lk8CKvIaUDa_vmf%%zK*; zM~$@x$%r6v)cYsARFLT6YsbL!v+&a%r8(~osY5H>@0t;*2WyVTDi8DZPQo{tpQyjT zImK#vr}xQVLPfRMd@brBlRxk0bDwB4bJRZ6CC)cYix}X5F#DqEj(VIsv7h^$XFD*+ z!G{3UH`B1(#PpEH5bCLb zxSXv!BE1#%d3jKPx2FW&B|pqb;mNDCgZ*;WMYji4zvWL5`avqYr=@|eSLhH+*bLL; zr==yy13r@Nnp$t2oj!=1>sDme&`EfQ**#U(@J)YJi1D*zcTr{;w`v?0aCHPalxyH&84iJ72tj?A0~=G zE3?UV-1T-xUOE1U&PbWAf$G%#3p=ORUKsVM$a~YJB%&}QgA+BHIH|W~;6IGiOHyww z0Q($5<@HPH7qB?3k|XIAM{gv*h~D0hivXhXSG=CdL3qHnMA}yKu>cDCYF6R--3JJt zl&e@i-IDKtqpf&laVU<#3c@+UJ5FRzPmsF3n}4ec&A8GUZ0600aS4CMw5&-pHW zYFS_CBJ?e_c{FtQ zxv`vhlR*^;fW{Fw1hoD2cA)Vxi&96Rj!92v1= zryQRiX5N`_M1@e8!dv{MM~cy~jnhZOYq>nS??lcNbGPn&hKQLqi+=8OdD@* ztZ`x~5-XkM{5l9kjcnnJO+stVw5CQZj;Rq?9a)bu|5`Ps;~=h$PNqX*IjeTk`-?RsmN*Tfx~l;t$%oq8{u&|*nhU1U!8iT9}%Zo|C`C|T^X z{ReM-oT%QBFQ39E=jJIRV#;N#yAq698>9gtT#kvqL`_Vi!3;-J4L|#{TBo&#ObkK_ z4eN>E-_m)3@uCrg_$wM?6TyBp{E&Q$XDR$BIFS6gMES#gP{~EijQ6d(jOX{OixRul z3Vu&~C*_N%jMbF93ek_%O+AZP^A&Qem2#iFER|!Um{OCTD%iIrjM1fqejM@Q4K~vI zDzx2Oa}gt>XFBOEUCp-+0g`fEj}sv|R`MFozo$4TLa-a2@juQNhWXfr{~@)TJJ29s zvLemW(|1I@%@o(A*MU&a*fm|^vH8m1_gozW+oKU$^G z*pA7s&EvUr{Qi=1vy*a;o@S}LC);g-kH_sUP)#rucT2{`yWymfobsK2>K*$m(4Z>M z*_7ub6Lp(92C3p2_)xJ_p5J%c_qd1fKD6PERUUI}mX*~Bwh(bh?*yQ?z~zLzU&_!x z9lZ+XZ`TUU1UYHub+>R{A+mjFRDG@N*mtR`6p%g^xs18(oC|X-t=dn^Xa?w%2w0iT zZEDt48ZqiY3?I;A__#|gX)Hx=-^qWMM&L{(UBIRZ5v&=mio&~(#CK6>@8+2>N|eGz zx8TrR)-h}CHvk@gP!C@6_W90`tUH^OAU>2H9asBoo^^~*tuBDvFy+SmUg4oChlzB> zd0R{WNKmWhJKNI}oOI_2nLPQF1%8p+@57$6Ml|^XgOPR(!}S1_CXA#ZyA~AM63!xjHNkssF2BRY(kSK7E~+PkW-rPQLTRYipL)QR*T=#&sI?vbX?X?~JUqj3DqD8eM4a_#~uLwkF?u&7CWu!s^}ju*CsZ$NuQSw-v==b!5cgl?pwG zq_06dmsW@kH=(97X{5i`mnsE>v?F!1?|J65%Vt3;dKKFp zczbLwd_o^ss42RT;kI9yx+S;ptb_;FA*iZw4(D>ZJvKPv2TBy8o<_F-OqZ8lr3voY z&`X`C>U$z=>rglL-SODl1`;k0!Nu6=cfi@rdAmx7-(F2gbh7#<9`d&{9zvABHQ%!+ zYLnrkYH}Vg##_I4ceI{PgrlEc#A|$5Y@L5=s_CoGSVT9nS$=nCIO067lLNasw>U1N z;cB>g%We5F)-+kO^5Gk-kszKgZ#(NZjmMbw(}9#Hr#yzk9p_k0`)DZTnQu*esip5C zja@gt$nT@|3y|&~zdGfl4bgr!5;!HfQ^L|EHh4Exhr7tTlCWyv=wO=;b{3EmIUGOa z?A%Xo^%<8>mp^Qo8ZAGEN8f<6DO}m)gZnp(lxT>9!AOMz%LRjgU>59e6bS=}+Kxo` z--o3cF-vS=vTs#JSXL>0U-&MZnSG54c1mI)#t#=JP8n$yTc1X8=zv=C=x-`3j*TdF zP}-1%tHJpFpCi-Y$uJ0+x$A1v3h>njla<)dTK=o8OYGCVo=$!kq^(v9J+D{cLxZi| z0N3rzWIEMZ06W}sZbd2Os+z)~a(G_}=US0bVB`7MHb87+Fa3jt&H?N###zkl=ck~w zfwidmbNekFy^)?a4D!t|+0GY&bI95oKPwaa=np~MtV9;;hoWQrI+&F^qRz*7=(Fxm zSEMS)vPj9+oFkw&@pQ_$Z;b*z>1S{(WD5OZS<%3T6&V)(RQ>R3SLMe)C2OZ6@Z6ga z_RtPb(QtW1CdDC~feX4@pVafT{LF?~pH%8Z-pBNq`lwO6j5zD@R2T5zlh#BP!fAt? z=p<__--6tWQ+i(s7L*5GjR1tO_jndJ8mh+H>l#scZ|hGGM+B>L0j74$#eLgRs<$3L zeTooY)ps$VJ=31_Wh(bRC&n2hLl3~- zV|sX7YJ1zHsB)YJ=`X?RQM&v_i<6{g4MpY|!gnXdbSGs?ucHrMk7^%AnkRRyrWpG$ zJ@%m`h1w-~DSMn)bqd#_h~)#hBfLM$Z~_Z@WyT64)^j4^G*`aE1k>OMKS?M>eQuOC zb&ydIr;xAJn!w9SBHa?!V%N>^r%iCpy!*nl$iuIs%sE7i0yyI301{hF^BL&wo7<@@ zwPGB+kxZh{6qd_QR_MGLwfrOEemz!2lmNqrZo`va8LD&JiK!uwUU+tM@>jLb%<7N> z*F-Dw0TZU-=|0A|-8#}lw)tZtWr?mpH)?zsV~zqwq`>e&*=(F~WrfgNF!9^cnj4Ll z`Pr0;V^_MzAPhI_FnrAiu>P-!mJT99YtgnLZhuB^YH4N5^e>;g$r6qfX_>Zbdc2nO zN*E2+esr}C_n$)>rdn8YvY)_bluV|}lPW-p2bzUynjdlcTkAw?I-k#P1RHm(*~sV@ zwuVJ}exsYpB|!-H?y;3x9iQbUB&&p6sudWYJbt5`K}q&)|4{hJEEkTo^Q0AdVp+1W zA!!$b{Ol-yn^mt^2DA2+upOH;70Nm>p1ekeX?9r{CeiWeZ9vXdS*X*=-OFfkx63X& zVLsy9v3dW7VV}L*?wn3@>vdjsnPRB!QRej!XjoVOSA5f|?6?C9o4|V1fiTMivizyX zUHV4Wj-$kMZdvH(lhn;;L|vs^vzlEVPA($SXjtpu$!co8tUp4$D_&+UK@VRlky?*Ww$=0{$u9Rl44;lel~`gZ`?S~Ty~Uea9Lbm(EsKEoU&n55D^7b z;>m)UZ(Zl6uzH8JVDAajQprVbwb^dlEL2;1+mK>36`(tyJBwz#ZVR6e@qt8ti91R( zqe&x^LGX7tjC(AI^Hv2F12x~IM)AEV@Y=DwR%8Tgb~Ih_qwlDBqW6@vHmoVH^$>IV z*%q@#j5{$YBFQuAU4P)Jq~g_iw&2Q$C3g*5#ew_Hd6vT5qu6B5H>eenG}S3SW(+fb z)XyYc%B5^~Q}|)#niBhzfx=1*_fa>+orOfInJ=)l)WlPeFq<;PW7ozn`p%{8%xtV)5pO;P>{vYS)@oKn-eD*SZzY32+*d0D~p@?qQ(y*_W&`Z1l+%ylt{Tdxp% zD8vzc_9cEXb}ug9^1BG=T+8?AgT!`2dB~*>tCKdHv$A*Ui7r2DpJm^F%RKy8KYMQ8 zWj7GDle87-2i#rqvRYXQGdJaHgi^4B7YvI{J%|*I@h~$(F?O5C)K}ED?yY&R<-JAD z%x(~i1iUq|yS<`P*I~f>NN5LKWdk%nc-Y)$%e5U>%%*&KXk~at zy&@%>d^B4;D&P}AnH6P~ZptNMgHlq$IF#CrrS&mGoz)@?Q|Q@wX2vY|rGVZ|Mn;L` zg0-*d*r=)`c~4fDo@rd`l_GawFA!@V6$*SQ%}V|y`bDK?+kINl%m*4EgNtyCu*pNz zvU4O}OQS+XF63J1*|s##rxsF1BfS${h~xzohU&$dMd%%hXGw@7a9?||`!MxmJ0IJp z(E#)zew3u0XZ3;k3_s?xg83Bk1Q$3ST|*7yVnX&z?$hedKozH*^%$XG+Dk`bigz8N z#E3-i`aRP76|yZ?&kr}!D>;KT!=m|10YzN?KkK|!LGKYXG`#E6bQaOPc?X$4Jhr~L z#fVMIvRZimSJju7)YtcV?apxVCmX!j~^=N73qK)*JR@x@!H9WUF2h;_Iehy>&)7H3X9l3r`LBX z(?-DiR(h6sV zcl11K9u>(Js}JjlXs?{I&qwO*JZH(Jct`7}gFg7mok+}9wZ@Tf@Sav(0Q;UJMhQig zx~7lXvvST+Y5PFKuh?Jfvo4jJCWJnLn>U-cFo{FP&N$0T?K=s{9H`}Qg?TCj>WtTB zg1uu~vR zdRqAxqvS4p=S7zfOzk=x$3Y=R^#-Trc}ERjVi7;*{`xRfuC1&2&8>RjJnycTF*au9 zV|z!8wdMS_R0#7f- z7eTgp1oFa>^lDxvV!(oKa%*V=D*+-JU{>GsQWJVkO+J-jJohqqKG5DUem;PInL#vE zM|!tLKH|oi_&yo`q?NlJ8jQz>o&RX+LYLO=k&}%2^TeNgyj^ib&$1BHShd%CcrTWGSpuX{NY8K88#Cm zcmFg}-DwAocTxp0zP{J>(nJV{wW zxUjFR)wE*n#v=Kk^Tx8+mWK!2|MJA>yT;ku=uY0isj04k03^R>w( zc13$4b6<#hH)F#oTHG6>fSA?tKdWpRP0<89+kn>gNnzoV-JBppF-zvMjn;sOHf1MCFItr zAX(O9!s1^O345<$`RU?`jGo6jITFi?!6U5vcFLuh;$YYPohoEzg!xBDH~>O+nxvyC zd}~%nEmJQx$xZ$7yp@hsF`yn|4fLEU9{uc3X-dZVaCa?v!k%TIzhwuEiW)NV;6&cq zy6|BIEWruwmUMKeAxShF+}XZ39*52#C_PNN4t?W?ityhZG-Z1Qybh1Pv_vTvhfHz8 z??4#wP9cig@UnHqn9RK%B~2-2-KuCS<3nOV(@|?$DH_Xpz}+DaUUem_;Tp>}`IhJj z*1X-WY-k~|Gq4pHJ)AvQ4?x*CfaNU`W{pmzQ|x}Idhh>C-xtkYQ^{_)H0vv1((keT zi7jOY>!97GewGON^Qz&O>nC?k++AkKQ5vDfdDW&T$Q?84*n(vxn*Od7cyS|vOL-PN>`#Y-t$dpXg^ z3s7#6N}d8G13!xUR97IiwHu8a9D%$GoqtT<8>S5bozJPW338PCtWu`&*4G(>O#qP4yBZ=wrcBX1G{v;^h0QoB{dQJ zyBOvR{8d**f#=X|SjR@}C`o*l^lLFTRZHUA7*ExoY3mR)GO$^uf5pt2!(csZ?qkudf%0vQN+OD!B=_%gu{nWsFIi4+gR$1| zdW$a!vUvN6Wxsk}6yo1{EyCmBoZf8XyHw(vM zXz+FVc8HNvq-7fJrZi^cirJzqHg5?i5|@f1uguL!@_+bx>#(T1u5B0GYu-vGs>Y0;ETcK`E+b;5jhFUt^?y&s-2*Zp?!*Zro9 zNX@&Uz7=O+A`%a$C5&GZxm414k_m-LU2fSV+(s>%TsYh-H*S;0x7tDwsm3YcZA%4Z zg-DxzpgKdM3QS*Z3((fd$MSzu@S2?CvWgFNkeyIR|Jdz(0c}=3i3X7iC(G=lyyZPy zj}DRh9}+ry5{@}gU!;1W;~SRe)(;CO`T z&3W>PKdq;VQ|AraeADj8mHhSICw+_@WD)%J&2IZ-eqt}S-I%pXO}ayoR@0&vHM}r4 z;MsE44BxBWV0tDm`7I}ifntT4oa4`+lwA=oO_jI<<$GVP`7%ZLUKc%iUx0Cc?EyVJ zFQ|Y_6UTNkL;TYl7ZHZEK^4#2U32@QM{4bbat*5IPkE_*o@%OYu?w>5{tS?z^8B!H z(mTb3y-d2a9md|e0??N1rjh@py$2*k+=cRf%c~}!LEnQwApZIv3ZAi!^>GDio69o5 zS}ny8w5CF@5f^vU0uC0bMYscGU-a)qa6=|n!bq-F9xfr zPl-jsvtN$q?&d`qX*^Sx^h)p0o|8Ho{vqS#k13}~I^OY&h={1g_`gd{bHMdCkANlb z{&+XNk6@d>4Us^9`OUYOGes|EF?i)8qNwl4dF}=;BKt-0cqIfzw@f?-A1=rvdmOpq z8TeWj1F5HBaDQ_%m)bkvWnN-yMO)@hKkF7lSc9%eMoAPnQ6#+rw9 z?F2GxJ!5uoa2p75sB^Tv{8rR4ZJdZcPN%iE?C|F8?t%VOh@`Q%;O;W$Q6F7+5|jA{ z>%^=|FE2iutM|qH^hbZpkG@V7YL(_%W<{U#cO{jWu`PlMqGB z|4+usn(vFhG>qB-LyWtLm zI>lr!aYtZt;YjfD({ze#C-XTByv`?vqiyM>1DtowY@>ugC!kMcdY2*pDYPl1~s z&Go7h5pf`FF+PS=$im-MJn`DiNPVV}i}4ahE3xv`4{nyphtr+=x-s5t$%5py?;+}& z3^o1Ygv24WNDg96d%@$#ku3!*>2v(VYkRnP!VpLm{0|qO!{(nLL1QZ*AI@7Ro6DpZ zTdNO~M1;c*7ErkxohZLz1ThE#dX{Iek_>$is*)L^;1vr2b1 z1ULnj|7Hv=JOtJs;=JWpCO$xotgu^{tNDh3nn7*&Ia~Z7go#g`5_K>8N{qo_&lVLr z%AP@pqCW5MQhzpI6~79-ChW)!(>R0Yy_Ti(*a4@lw=dt~P7OWVZFGJwdh`O4_wg)V zxQn$mFy)Hzvge{L)}S?J31i?rXi?&7V1Pgcpx^%^h+Uw+IrNT+?@Kgt!{m3;c%xFH z*w(hzl|S!OqwwSiz&RTyiO-B79jOP*&%kM!JM%CD_OyY-fy8k{m-~)7QM8tyT;9vY z8JRI{;|ar)r_R(~sTlp+IYRk)+NY0;f=E8ww3{!Cvt%B&b0!HUy7Z+Y#hSwZX9NL% zv)2|}HKcOox5WA=)bjFjxrj2sP97kE2&S|xSVdFgv)j~|iZE58cLHVNd2$j>Nv&r- z_M|MiNTgM3j&X;1Q?JE=$A7n&=HTUDKixY*j+?9a)=Tao#Ol#RK0;YlfX~m0BQ8!% z^?0yO`#&oH+-BHb-U(!bOrC1AboZ}?+}w#>4*mB`050&auJ$n{@80D{{kw<2PwrTE z2IHUqX(;GY=3TAS%GS?(S8YpP7V^VB`st6pTA<>NJL7-<>{G->H=5#n2?y(hik_Za zkv(QYvOr5gHr-o0@WQ*I)<_d*ByarD2P$_roU(C}mk-RoXfVgj8{xL_u^%Ku^w-W! zghLFz$#EZ7&yq4)}L1jt_$t-Hg^*ADoZ&s)$?aFtyEkdvDo}l;c&Kl6(>$9-!LoV(U>y)RSEl> z)!bgJbwRrc{ZD4;d90kn;MvcHOUwkl#bf)tPs6#)T5-l=y|%2>axgD@=sT=ry)+{_POc2NpIF+?mqo3Hjhh^ zn>sCP%BKeWfiwzF_rQ6TR}c9U=*G&QL*oO1tYv=g>b0h4o(+g{&4}qQzE;S2=90nZ z>=#EM4dwL-LWdN-)g1bd-AymKK1ngd*{@deUZhA?VUt%bP{kK+R^>&`Rbq{21>fxUA%Dr@pyk(W<^BVh6X4oktG>u71sRg z*0+q!X~lpf2X6U7COMrC$@{>PXU2?`yt%!JU6an3`4l$<$|> zfAsBcN8Ka3WJJi)xvM_Bd!4sQmQY$Zar7yv+1IF5s8fW}3;{TP&s0KH{4K z&H&>WRXy<5FSAiqJ)_WJllJ3Nw6QFqCC3&~CaF9%RS?U&H62%Q`m&SYkZ{fb=8X@z zjW+J~CbzJD5Tf&#-{TWZaI@sjiDIF_7y$3 zha;>Nx*C0Rtk;$hzO6r^ZsttJVf8k)_b}&{3v=cQCDe^Vr5!q2J7xIryRT_+Y>dNj zsZSg+@&X^tsms3XUHmg7e}%YfVPB-<2bpk)Z@+$^`40u~BX^c}c}(3%rI-tH8;lb^ z1PYXUVdVgPXU?lJ=q0F53*?>e%}8Nmw;52}6HI(@BTZ?e4SmHrrRv@Uc7+k+$Q$8` zzYKQ>0__;=YL$PSxB0qB|Crk5m%WjHc}tv{A$)sqnZml z-u9n-z$Y5gYe{@`WeX1$Fg_bkr++~vy4b~I^AU_<)A7%nR)l@q!%^_r$jRy%M^Ug+ zdT8xg(Q~fxKfU~c887$klg*b6pj~H;!mXV@Zq|dU2H2GjFg+#`tE-GYn>`>9x-qz( z4%4GdW`2pErc6KIwqj{>pB(BxcS~T zF=05Q{4_~fLf5XdaZIeJxB0H4#SAO@VyPcQ4UG*`}`UL)>vLUpsOxa$`pQq>myt7$;F zGAH&|3GQS8v=Z`Xu&~nR-PLR3OGJSym~k=DoMN^x6O@&Qx-p7eUFPyIq{l>=vG!O% zB(?DtWGKrh=CWy9W&NqGbyjf>`MiGY9NQbA1TI~nBPHp_%K;2CoYVF zhtFRu>2YTn^6XXAPBbls-cnZXThaU(lRYZLn%IueaBv}{@+3RipNJvzF?N}twCSwX zX!kn8b1^<(IByNZjD4AxeUbjwba6h?7e;fRa(h?E6Mg37mEs6lkuR;p3lGj2$*f#6 zbobfMtpz6YFviI-*_BK}yC5Lq`pDm$t*on0pmc=C$@d%9a*>jN@}<=qM$3f{z1{~` z4QuO%d~eDeURsx~|K2@KjdB@pTE;!(uM*j&6hH-P`vYUx!ow(gC2v^M-L%_Ev8pl^ z+$8E^&Mk;pY{T!89ecX^0(iCUsmH81oV|na(X_L1$t`H?CYy4Ep0@leYfWua6?Umo zsvGc$BgV3ZWn4!Qifq@4i1Ao97EM=l&eT-Npdjdwh|V@pc7rjkz^5TW%CfX-RfMPu zQl2c~h*i$}HK2n=?_B3Sg>$7_FP+gNB`v5xzW_6%rF&1)qD^Vz;-ey-->hU|5 zY8)Hgr-$w5d!X{N_ERm|+AyrYhBg(*AildH4Ek#86)i9M`=WMy)~@oTS)_5Mxp6$w ztH&+|vFjYk2n;z0tcB;QjA7I=K}uLv<9Z$zw>6}-Ljl`UXv3X#gGIP# z!`!Q0tbVs;N|Ck{LedWcHMNSD>&zFP#G4~_Pu7LqgYkU#B}M<#Z8jfkyO?_c@34o} zPO`Jwif%F=A~hxp7M@gFZ*G z_^Z1b0n^IXkJHahsN6veA=D1}&HO-O#%d0?(54Im2&}P@k1^pefG8$qSE$}w2Cfp~I?Ld^#CPI-b%@K|LZ39q(2_5tPR;X zwL>?iOmEO_1EvQdy7ginrX=nds--<>r}L}tq!5_k$yR)XT@rreNq<0w(PLzNRHW#HG!^!&M^Bxg$Z~u!(cXL5Y8TmMv`Bx~EEZNB2 zWYMhKC5s9%EMT2J{Ru4cghtZu_xrodKtN7EHC{Nfmwi-P5Tz0&*7WTER?Q@LG_y)- zscT9XE35KM&e^^wGwwB=dfyl=0rTEu+lS{QlB(%WW0hGc3GPmtFv`k>ck3nab?5VJ zlQK>Tx{ga9H5?Y#HP4Se_8t=PL?G>?VTw)>!Vr5E*k~kcreqXInHER02@`?GdmU2x zS*^{{CsV1p@t#b+m~jaHj30jcM7ueMe$^}dm$VpvND4DfxEGOoi7$?tqILxE(j!Pa zZsiTRT1y$vni9`d?X=aab7&;QK$&*R%}2Im`sx0S{hhPrzCpKeQs z4?@yF$xqh2g#%12)`P!Xz1h!aaH|Me6BODK`7y|?`ilOMwQ)HqN?cn1t3`A4Z%5SV zrEL1~>fz6|IS!G;x|6uDtEz4Kyw0YHFbn5Ej@vLhoy4ACgWnD}pc@ZDUy8lqHy8n4 z62j%1G&hGI$vx8wILYD7w(AVj;navVW&WeR+QcRK7MvTdXK}W_EjpFS`{uVyp z+a#lE`_Vp5HGpGQb&5-q)Jz4OeFY!Ah(ydH;{<;A{_st>e9MHnli_X#+2}=#T`;=d zG(-`1`#FQo6J_QiWOnwB)>ZCLYVVG+R+}u3NuKUn`i}SlIh6PR1~))2(hhP;PWcwW zdr77gbCcZp@{e#=Z3SY%zK18;(_P}|tslAJ?J-_cH+0~Bl z6)mTFa?bcV3W!E#zt!*ak$QETW8Pc*#?&Cy)HCE!t$?ii$Wb&&DX_gmNc0y|vPTN{ z2OjB9hPyu$JA8m?`g?b zCoj5{W$jTYs76;=@pAI%PdbhXPzq8hww2h`k$!8!RUD##DEq1x<-1UYGYKhY=)_9$ z?I$Cj4ttBWAu)X2T^7ec zLJy-HXYnHHQLn+a>W$2UoqE11CN$X?-So}=6EZhmcY^CRA=c*NG1poZ)E`K$q>?68cAZ>VoQH{4Ps{*m5z$*c`F1hr31r4>I<-^alv_zkoQ|at5RHo6XzWMe zE>I|>5?a+CTH7xTmnPr())?86;=ya_`c1AirrUO>pznQ8h@onZvCzBXxNfhru8?j& z@dEC?-hJqVPTX^Wv#@H1Y{OC+%BU@H#vpnbF6Fy5Z8TOowq8@egpjs+4x=^Ow@dYU zkKH7LyJKAnt}=xBm`yy`G6>ANnqs=<_br$De#$ao!U*ZIep$UY>spgN8`=4psGluU z5j0%>Je+z!gg-X?xfLJle#-BWx zCUG+dneqk^;OiONWtxV4J3_v&6KzyB62Stn!hceE-KOhLX0X!~Mn-xOkj!DGV-g4~ z2Ad~h?Vl=M7?pK@XI66;toWfjsT>ruYjNXOg)VdV1&ITFW2`ie z{3!CRAU8&HRqI|hGLZ@!i#sj>O_IN+UGB|DOw5lFl2fmL|pb?R=MkXD`4D z>nNdr9QQT*f`3R@tvESU7MMAtg!caXveq-op9B8krNutCdmh%C+3|&8I{`D_8E#xELKBbbU{y{+b+m=&5;!*11(3v?lur3=XrQOEG zW=m<~(@w{~fTg6Azf!Hy9S>Phs&7;#*%=#?t_drpJz7u9rmO9djk-!76|2cI@w@T} z=Oe3mK=`Sc#4?Lkn%6V3S7bgICdNCgP9vlowLfv-x8fz@vcr@qSd?k(RnSJ8D^Z{s z48o`HyYQq#`w!pi-N+WD$*;yK$#qj>)JCW9J)cA1){=}l?2!5^-OK+GUc?WlO}tTu z;`W~tiaUgNq2^c5`-=W44boMbZ=z@Cf4;Kg(<>44m%=o+pTvEHJEpa+lbE}SBTA@9 z`20UaFJ6YYxIyAN`Ozh+caU*^8tq>!Q?iA$Ke)HuvI~BBc2tKF`c#KZJFnZQC(NuZ zS-9*=3{bJ^tOzQUEhNuNcMD{hI83>j(Ul+l=BcpS_&^^0O^YS$@Iz;k zSH>1Ox{-a48a~5k&UqsIg8dJSQ100+yQFMRZn8BOi@hVdnd;4s5hsxJyhIl|PkUWes6u3$MubuZyZg5MyuRQ__g>NU3Hra};zm^6egg3}xEv<6+&fm@q`loXC4#seMW(jF@JiORn4RuugY@{bM10?W+d)#oW zZ;J!Es?ibQ@3<=|{g4wSZW~(oq^QNa3MB#?M72Xy;)S&60g!aStev9bc6F4>wKB?V zNlZS<^vJq?p08%n4>BkLiojRol-^KaZtc7mH$_}S(k#0%cr9WG1P~T3c=)PXpLbSI zg<4ew!j4bTQxL1Z`t7sUBYfGOzeBx}edhx0!iaz;6SQ_!8O;Nh5#t^&{oGbv=6Ln5 ztWM(Yh%EtCQ+hi~yIJ-*_>h>58!J&o@08$D{w@smp{{|V*JoBC_rg>aCjf3rvf=Z7 zuAM}i>POu;6&HNZ%6oJ*hc1QTeA61)bU6W0ylcRVRBeo3yfyvsO1grbn~4sUFmM%V zabP&F`d&p(3~{ykQW0BN+J%s9hGW6BFmUwko|7=siQ=s-PJO8ul$wvkS5@r}zs`&m zQ^c8)#e>%ppUK5o22mfD(CF}7v8hf^ts2l)^^Q~+;ko%zhHXA3F*enD6Xdkg6|L2(3;yta4wo0XanN)p`Vys$cG^Sb;_P*+7 zdz)w|s04o?L?AV#G%3MKHTDG=CO+R*x3_frWdg=Li#G!%&4E3q8UW55U@#G3CEQx{ zQ+qq*>jQ=5%tCAaH*y6jzSu6ql_O)8a(4AwoL=-Aa$J1q(fVZI@qvp8hkm8V%$Gxd z-0kMH0NhVXQCWpU4f^_@neGXV=yQ;={y_wd+B=X=@IHXs+UGiUy84X#DC816#tC1T zZd+mWsCl%ROWr&i@Nu07x0ZR50&A>pSr%@+GyG<}el)JYolt1KGu^ry(&z6Ro!$?h zKQiQ6<0o1hZ8C_ad3d^n)_zND7L=x=ol zO;X~Gnha{>{BQgbb2bpXNdkS@K@8msB-FtHZoz}I->e1|M&y>LA+`U zyBs4RNRW#Jh{%qm_mAbdPpYctdEnFfJq z&hS{nr1IXYN}Z=Cz!bUOt4^K2gPlV|k7?K1a$a{FrLDR*f^XKTFZUh5f@g@66DJ;r zrPOMlJFizkqB!l**ZAM%&+XWMS1NLZxp?Z@9GTi3en5o&un)hB#B-4T=dJ)SEy6q) zR~v9|%`gl90zV4z|3)vLt{KHV9zWXS(d*4KksU`iMSZUeBs*2$Qn-u%tS$W|qCa6s zQ>r#;zfa}0Lqp}Ua&K!mO{=UXflg@wUWCED8y2U$T>{Ut3iF)=Ou zDWYKC;S&ueBIoVlk7L22>X( z54X#{_8uk_YQjUL$fh1PRV_uL&;5->Au#XG@%*xiim29B5j5m6HHza9bW-JUyyhRT zt)ZbYda^b6qjN%86zA8BF?a|lMQ6cg*u=&BU~kujTATgWy`S2U;SMf)x|Uv$w`KYG zwn~}|Z^m?yiau-SO_E&$P$hFmC?TbXP=B(ul60>8Y8Vm$x^4 zX8JdyitP;KZpJ7K{&w-%Ke3Cu0EVi`ogL$Nz3Y;!!Nff=lmrhA3)2N2H9g%PNkrat z@i)v7&=7P707vs;7Ai0O{5Ws{Evfj_1UyRgZ%f%?|IiUy@4-KC_5pJCo*@?PRcOb} z<>?Pzhb23!nV}S3SvrD+2FI^10z)mHrye_5L9bX@A*}E`Z*SRNvom^vT!%$*_{!I3 ztU6-R(y^`?m#5nkGcz)((H|E6euh^r%D1k zP0NiS0;Z(e6-JxDzYSVEq6^Z!o}?-9=G6gj_C|c>8#G2;&0yBc(-8oID1y3iZbd*2 zt1QQ|Ur)`r!;OR)O+ygD=)7G-y1$&Es1P8i6Sq|v&Sr#=23v5SRefHHg`fDOAdUsTi|m( zYvJjzjMz*xKvkgP&&2F6`kIbYmcQR1z|{3Oj@*MOZ}VRM&t$q-?g$o=TJ-evr0Q+C zYOet+nQw@kt+u!XgzaR>t@s}N9SYFAXzuN6of&<-d#qNz)j&W&{;!N%xBEX_Pk^7FpIk4aT1{MCTwSBz z(=jaMe}{uEf!VhDcy`#SQG+xpue_R@-b=mANr->_#{E%#$N@|-OWdjHe_H%U({+V! zjyl&9ZZAi``4trvnedxUc5q)48&#C^dQXJ^G-6v6#Sd!&#u>6Cq~5gwn=Z(R)YlTJ z$o$K%`bRQ@1to!Up~0n8K1c1215M4%SVkku$n*MA7$BT_M^_9?Z#6S(*mL?@T&xy; zjyFE6kp8doiZ9%|gZ@8oSqxJEcI>VFCGWD2`cV@@a_O1dB(G}I50^*{F7@c)Hzy#5 z@qdie-wy}x#sXzrU*=?I4@LzoEiL)a#4A~hoPr8qwDC+HpdbCLWTL2&yY2Xo6~X$g zBTFMGUBuG9xwf_j{JE9n&3>taIAP64JvnJndz4#k$}-B=y2!5e_IzGed8t^9NEP`f zc90qDvd{zwwU?Jy{$zqe>lL&ld|9MHfW2=@{#%I*Ui`Etb6Lb_+BN%`wF}kDho1jPWGO+X&&jxyFCk{8<#-2Km@O+Efx(Ybbo&n;C2qC z2?|`g>+0&Z!@O4fFn*RdQ^Jd;prx=-PK99s!)}4ahL2!aD~~DLWr%`no6Omke?p>S z-HAOh;(L?cA6XMX1s3$NMeTCznoT|4F})L-lRdIyXLEjQ7bN-%)#7VeoBh^A_d#H& z;Qa6}Egak%7wX#0TF{yfchl`7|7hvK>Kn$&AJB>Bua9o6nLkO5{01v3x%eLDJA(@p z&XGUL4idJbfE1m136beMbKr6IS z_s9#_uHfdhY#@GEOkJzcwh-(Ic`!dxs^d1fsy`Fx{5kl@iBV<=a=PDAAe*5i76CWD z)v;(IHFNv!eMc|1i2+jSqo<}y)+b_pwgs0-dA&eQ#B2shu8TQQBK=?SL_B(-%)U2{ zp`76?8IdvIiy+5=HEk@>dw0U(c&PRUS>s3MUz5&qle_kh^e6=09g4bl8b+GPu3uMb z;>w~|6AT;?$_^+0hmj0-0&??$7ib*6^bOha4aPQfaKx@CFg|K5-&yH zW~mj8+Twg~`4jLl5uDe-G(SW`JA8J6*PD$eoBQwEP?WzB%NNn@cgoq#PpRN_NvT| z-t+aB>qbBC4H=^~v6~@lIqgH*m~cWLyDsjk-;!`(_I}PJqWgIVy6ULbO#vow4bGvA zxwq{Z|Bs!UEg?j#kTjatORmEjM8;PD{x;`!t*9j&5h7CajZwWXy4*7tFTjc@lgj4x}DgY9$iw8N{@Aao}qjK;%^u6Z}PMDEe_T@ST)P~!MCJ`n@ulZLNq zAj)>hfGx_YBx0*qto0MgA6AU2MqTg;EI?e?>H0$i3L`wDJ~VBN+mbWWwqPV+Z5kkd zO*NDqe2GvYGw)k^jN!rCybp)Ue%Fsh(6{tTJ(K zYa?trLjU|SqX|px`~!Ux@+)l7c<}uqAcXn5YHuT%1X}~XEe_ELjG*(KnLpS@=s32- zz7})FlXE3(yPy0-F%l=X=J2Q4Jdt>Pw|pifcJx@stHY&VXhM({*J8TT^Gri zQ;hvTQEujot2z51QMUD!CfF!peo;Qz$TovP1;)QSbGL!!?KC^!~fa6f!IR3E6E~b|t&uK)72ANj3Gj(z!%6e!;v)~{#kt*4l{k_|+I5zMvoms@Q& zBv<(yA=@orq=nqsmE(YDqlahzMxMVV}7h0C0QS5qua>u}&skQ9kt<_*PUJ9}zf z*8Aq^8_v=_dOf02@lLMiIS@Yn(2JF zGVjMXB$!&WLyid%^ietsb2kStfYv$1PDer3l%Q)-&!z~NOlOU7#_CnWN`b2(d6ssW z1YtN?0(q52SCP+j2&=)@!?=v(ENs6=*vjPZlNCLp>elBnJbxlEM;v6!okbhX!vSv5 zZAgg3J}Vyy-m|KXFOF$M6Ixj3xyiE1`kvD=6SBewl^IuA>{?Jqk&o@UI+c5(k{%N) zaDv|YMX7=NyzRg2!@n|m7g3qV z>?W}di64bae=BScIh3TW+jg!u?Xa;aojtp`OJC6M1Hj_0fIBZce1Mw_XGG`}o1R|% zy6-a_I>n+F2mV~&(voVC?iu*=XAw^K1rpH~B_i=fkbFu4@AwxMyNXcv4K#G92XIbE z>swAc5)EP}fx1pK47B*a!1rwh4J7WtX{?zKDEa+=xHoRZKlU@`t2}sYI=3AB_ImOa zT0qLJq!xfD@`EQDhUF| zEoKz%iqDHncbYp~lxXNdFUN4KDd(!bCG1okTIFUjMSL(!}`UhTKUV9!e?B z8kLvkjwB>#=u+Qbh_Q5yqmhZ3?}{KEl0@%8#v;B-gGJfmyH8Vn)4>lmqR(I$sDjN5 zZ7U}4TNww$_yGgSK+psoBgO^_l<=rTI7s|R{!mgL;vMY4vo2Qn=y4-YrR354WmYAx{Nf8zCf9lI?O+IU9Ad z#fT`pob-j9p=t_G(`U3rZ~TpX*|@s!Hr0#*Qpl)h^Lh@n(%NSAA%~-;X|{iIgcb3j zvkNR>nG(Ij8^6Aup3%=&ZqY;5*a&)OqLQvnHFNcg2$F94?wFAZ7p?>O9pNiw=n-k6 z8}JO}&CtW{&_fH3!>U_SVg1Ey?Y3%TnX7|K;U!?vk+W3X+Y80@Qe{)#XOnf0orw;| zs-xtC@FXC*i#gPm(k2SGB32)TX{zmw2Rksea%bNzHOUhT-EGGh@}ZbQSy@?e zX{iPfZTg)wzdv1W*gQEuUjhUi3hV26bLqoPpQ}BwpZS*yP+VNB1_D8}N_99Y^bFV% z@1j=RJUq~o%>gJ3HZiEMGkn;oRr`}DpRYn=)8Ra&e zw<3`SC7UXg0)34s&RZ%;JE^a=)b1<6H(E(-TY1<`8ZxZzb$=*eDaT#X2po}Yqjqyo zuiYMUaz0XX*z8?f;8Vl~F&=$u z@SFVNVmVDs%^13j5yrOV3X?Y;-onj`>ErM{SJ$62Q?lSAj3<#1eP>>IVq((1t+qr& zF{YBBTOeRCwYbPyM3d)w53Mq;L5^%{!DX9jNpWzox?sb?Qpz!`*|QM}6q%s7WLQ%B+FkmK-k+&bt{GpoSK!Mpw2HTe^JA64*mRE4E-xSPDY znJ8TG$IUeX+EZRC1lk%W2S*m3=#5I0&`Ge9vvbZ8?AT*X(klP6DN4rA1dlhWRy?TgmbO`~p#f=*!scrluIh!Z21jyM=NWvqiT+ zKx*NFB;Qg{+zGO#9~>u?gePj$M{dT9Esf`GyjH{5cV?-%p+32tLhEBQB_i>KS6hdN zYsqANg7n%FEq1(|%7F39li}LDtK%V+QyT{HygP|w^vlcD1!)G zYA@ZP80&eD2_uS7i)ifF0lD8d{>S4PuO_fptxE0;r{D}=y2y(kVZnrg^ilu^p$CxXY8uf=3G2kUfGOV(##FRpG z`(8fU<5^85f9MluN}@lvDQ~rq>7HeXeEf5Yf%b+y0E$My$-|Sse6z*dIRbg87nE1=C`Gu72FV z4m_)-KA7oyo;A5uAzU$3a2|xSa=o-rF{Ac$vdMt$613FNcEFY>f8r_O{e{F~Y%9>H zmI50`{%ugb0U2y)g!W+J(jLUS!4Anl=tk6)Syv`hK)Pf-AqDL!!ATo_^uVbx| z(9=0jn6WyQhb+6uQjvD+b+KNj4`vHB)u>G`@d!gy@ba>yIVPl6TKIaw9*#UCf=q)B z(|jo}n;!_Ib~zBCW*=NFArP?lNq7z|X=!ARL}0hdtq1Ho-MxafsOwcIym&Ln8+bwc z)a!Vls<}w!>U4dsK}!FIRp9v+0t6G?n`v+NSc+R~vgHe@ z+18~Tv})Z}`6U85UMx7<16yGd`hQ|dbVIGM*Ib`4&s{5n#vB%pej43YTSJgR&G7v; z{z6&{{VA_fsfybp-Th0|f?~oQe9FG7ef^6`@u3;ZUi-%M}pj&{S9h&=zE<28x5PgEz^eg1eHPe4m4oR7-!?L zBQUY{Ft5$#ltaDKZ*78^7TySJ1R=W>szSNAx>-5RLjPrFdUE^?S3c1)gy&A}%R<+SDQEI&oG`gL(hj7G~K0-v34Tf-P#k5JyS-mUZ5TcRLYZ+my0mYgNwf@(_khyqGFJfR#l_n@;&vZRt?+>Kc5ieLDB}1K#OrFFpLa%#CYHUvB>^#@zy*A%h8C_kz z138?UJ)WYUkpO2UNMM}pEs)P$PZ?SpEEU3)ef2Te?5A7n@n8-a!4N^+;xTowv&uD( zJM>qEP#)_LtacMtQS7=dQrmJH>b5K>wfOdmItUjwwM;%nz6{pVPbRP3>`QdX%+bAG z5-HWDin17bNU(Xg$4+4>j(0_bB?4?S){gStUK~kCfgj9I7d=>>&4JsH)ozw} zyS@RGiElg`9wyu2!d{ z1RkvW>K>i+Pc0$0c|=N6A*I)vIT5+q3cXoMO~N6oSv z%f!gq+PcPZT^dMlmDOu{ca>)UaCh~->#j6ki`4`}nQpc8Ht?#sg+*>oC~>6KBiGIK zjDGb->5t6dUZ@iqTBY-DLC=-WLYvuhOp zvhBG3YKfmQ<-;4>Lj z7;Xl^JJywVyYP&sPoqi`2i%QVQ5T7G*Lc3bJ>R?5+p&fTV?6t+5tX$(syagUPt&dh zVjXS=3$mH%nLmGW-oX<6u5)E<57EBRm+Ot(tee)}m{bd(ko5aYe+uDIVEt=$9-G7Y zAb7p)7SPMAPR^&5J-B zPEAuYJ~T}Inmv}5mX_@K^Ux*`!Bus39Ud_1n4S3sZ`(0xyck)o0k({t?p zO{b!U2A%l$cqV4%u!}k6W{B7NVr1MjA>ITwwBG@hm?u2NU-%5|?u+GN093XCIC1s# z^~>03nIj@1tUi6}fpR9ah`q>cY;61v!@sdfy5Otwu?-V|cS3yiMJ!zn+`q)p!e%9cYuqEq!D{C*WIVk7P`zY*c zX+TY<= z05p`w=lJpfE^@gMn=A6BA+N1XbPodqMn0gihl!&3r(rZ=_PMqfHa-W=8P!bzal3#^ z*66%VYzw)%^4i=85Mg68ZY>3TyFqUxaJkUb*6!V_T3TEz1F&9c3a~RQ#r^hn7)wx- zhidL%13>#V0k^O#eY^e)fhd7Mgr(tCcY*|{PA*)+Sz^{7p*8a9;lqbsN9`DZ1b$RX z6UfWT8qN6qca~_oQiYMFtH&N2Zq2}N>9?xi3XuZBXIfEk@@uKCt}ZFdtA?0mbq-Q9 zQ)4r8QC^9tudnaLo{F`)B(N*@mVj%zN(Df%SjG=O{%!D!$6t?ib90ks2EfTSPA}E! zq`}~}79)qQV?d1}!owvg+Ugg>XjfEve~z}o>ap?gU{`P$elNtR;?bi=*&3$SZf zF9m4@%~0Vsf4xmWB9Xa0F+}#mp)ubscQGfhtxFGE@_W5VJ_!Fa*1XVjcC_sNfdMRU z;kojY4^s0XRCbW}K{0Y;`oAPooLyYF)^vV$lxZg&PS*Y=-%3Q6$lr^h;M^RIP^rPC**yFF=&O^iA^P7|b%RwXe~SfHeUARn@Ia2fFC*}?leIO|nobRT&PGH~ zfs64w?Zg|R%7=7|j~CnxA5$00=(Er1{A6Hclqla6*n4fvXlTp1$)&(gq*3nA+uAyrq{8##CwZX4kCLd6*YLbdU%_c>smX3MBOC5P+y!>rNO+~7XUz2R2xcaho zoTrGPS-E6CR?j{~E#6L=zNd5{IgFz4!Qak4kczvaseZH3eJT6x+qc)oC545r)^u{= zxD~=a+L^xcvmUeiCbz@qZ;s1J>{xWWySr&-dKf;bwJOos2T5!;^51naEs`aDotr@F z8$bJLlVdB+2Ay@+758uZ-(>;qmLz(N&Ltv3|ThALdoUklf*<4tOSGlY6l_i8@=Bb@J_ z2v0?G3kV99vC)|0;NteLA1}Dt0mK;rSExomE(`1H*Q!9szUvt1)Ke(E`9AVI`8?R~ ziuM2F>pR1m3c7Bw7qBBJN>S+`C{^i-2%!Z-F9DRIfPey_1Su9kMGz^{K_Cev^bUc5 zSm>QV=!*0Nf(ij?awi1e_xtYi+NOCe~&g_}J*Is+gIpxo2%L(9NA6s)DyFY#U zlvU^B;DFWC(vntCNcvdyQdC?VT3TA_1*dQ>Ie3c2MXvG*bsQ9g?wUNyf7$%v%#twoW=%y+;BMzO-27ng0+Y6+`gai*V5gVOT=rV$jTal8LrHsE-uGyr(**(=N z*Cp-7?aVT(rmdxLh^C;uyp5$JS>%Yb0}%}w%&D3xJoT6 zU`r@KYGM@2xNnK`^Hxk>h`>|L&dx?qoceMO4frL$i4ie&1UG+m!MyNZ5a6WV5jo0_ zUXDQlXIj90ayYxJ%m~B@T}OiaW%Dv^`mZWS{q1-Q%b>V+s&U#?^$!fo z6{yht@?u&x+f8iy^q4y^5FPmd>&CBckw!%5(r+PbpJvE2QUEi+%1%jXKygad4 z8W_h?;QJ#e?D*SKGhwx<$h;EuS;MJ z#V#)|7gY7SySXiaWSPIzhEP~|r*=`kHtHvZ{;DLDXO6g4jRjy)3Lchy;qsIBq7p%b zIA!SyYJ13ucj^<5uHCE;Pgw|ET|2+e@LsE9rL(4pa}=(it5#Fl2tqBurmlzyG~>cbLlNAi}D@P<|c7 z{yV zB)C;t2#bo+`AnkcRpa#r+UT#&&l2voxG!;rg<*eZ7~>y$Hcc+@#dZLnN$d3oX9 zP{2cJ9=#G~Y-rd!|9zt(TvukU0m{pUCP0?w~UQrd-;a@dVA4e zp3{?rY@^)BhVeo?Z_B>jyWn^a2)md?=iCHJllQcS1n=tQ;dt;?t5v4nhlK_yjG_4` z2W}LWo{^ynvK?V@aWK3w&CSgQCMH=RN66OFs;aEKzWPK7#BRD7M@B}94m|&@AzY5X z#;_EM6<8{o6_S=Nop?x zX)xJJffx}NvKwNE@A_?bM^b0C;egaMcRBv#b}NBzZUbAedOolze55HHS+ex@E(3sl zOa>l=XO|2lC^+qAPYIrZ)R{~I^*EV+O!S3~%pTp1U^J0KM@NsxJ_VJuL!A=PEtqq6 z*U}df!{hLHe7B5j2cx@1dw@ymfeIv7Y}Z*qW7sQ~CA|)h;E@Yaao--wD-o!Oa}pMfk%z{Z-F8%Cu52TTfkjlFhthnsin0q1Pk&hv-h~ z4uZte&y+n)zP;lUnQq<8I?6*CKxB-B4v}wmH%Xn2OO9-_k9`;Agpg)*@@$Je;G(Vh z%2Aq^f2nL@-sO!aoS_ymfIm~Vv9i^|Fxx3#r_#U;TmZW-M%4W|C~Z;OtC z5ego0i5*Hll3aY^)dlQLpc+(ks=>8cUG=_eUeu&sKAteQBdU`a2gF&EiES*v z=$7rZn+V&m@bIJAS}FyYVlFf{cN+WLk& z@Qx`khi-5i!!!F8b52@&;qCfYUo$SydSLc&;2Q(`1h=!ny>_-oKkGp@jk2>Dop1D> z18qOn1 z^{jF6MgLi4^*7Lsf*6NpjiT7)*qSBqMis4bcN9on7}JC8jjHTmjkSNZV&I%;tw+J=sRFwH5*X(%-k`V8#O_Dz`E+GMRIvQN3v`{GDKuDB))UJ> zsZ61#=~vIVwRDGpkw5;R`6Rql#1S6Bb<9jMd&$z=0sVE(;FyVMou zwe>R;Qyb&0aMh8MM#eU;z+?cp>c5krBw&|y<;`DL%nla+y}HkS^S^VyADi+5xLJUE z#L`HAHvd+5YO=GlX9HB3Rw*DLfB=R4xD`;c#igfTOsn)$N(JfIy-{N$BMd0FzL?@V zcTV5c)wOjUuo#9g*hL84eRp>1-K1DQZmC^m4-ATpjm=C?Pk&)aXFtcr#^P2gM_f*` z@h?jX_Vn~{oIU%>$Lhw7r=V7JGQro;Q4?TnpUa2xztl}lZMC30ayx&1eF`DteO}7EUH|E;xkYus3J@K?s&gI8 zcjk+Ns_qg}mtMWS!}j)i6}+sv`h}&9u8vSj`_j{-q!-ghE-n`C2ROsOP&~orey`54 zmrgG9WQx0bF+SeZz#XcqTaQTnwgB~}VzJnYg(~UtZ&2kK z^e2Y|*`or|EZJIh3ULxr&KwDna|uT^i;Em?2k*wDeYmUN8NFM=R`YkiPK?m9i>2uK z`?}%vBUE4vx$D@!*QoCD=MQx#{_v=m_PVPZ-rOza72kvXv3Huw^V*LDUpF_2v9fK) zANaN5iVjkomyTbM)5%^rfP{+22t7aU2@#BqHhEYoWs#~gH}^F9s!rH)(tF8T10OzG zlgU$LxeC-TQ+2=!o^KIrgsJ8nCtKv594tZ#rY6)Wd##U`R^BkPp`6;yY} zJf1$jZ48w@x(EH!9a{s)9gFN1jaS9@JIKS8?jWSFzU4gt$V^FxsRzR)P8Qb_q+_R6 zGC`phsz{5b<0Sco>Ws9s3)wB(P4Q5U<1S_Q&wFNTH9CsT){mh~ST``>C9-fONp=5$ z9I^X1elmg+)1n&aR-Jc_7*Aq6#-2aKuA`~aL(Q)mn1>|86G2| zs~;rM^KN{VxndWYbz1V$KB#8chigkdKwM{BM{755DJ3FTSem2&A>#xl2dl?}PLD=| zsZ9e$8z1l82F^b>Df0IrB71AxY-hx5#5YtGJ7Wapj`w)^SN}%~ut!4#i4}k2(1W?q zgS`{gAh&bYyBa2qbD5|o*`bZQZS2F>p6j-$UH2V~NF&p>AfD=@yNwutrC0m-BkB ziR5GLt|53K{bK!$!|gig0^#j80_RkL6BmjR;1b1pO3y@gOk^|QSHYQxZYB+^LN>F> zJ*6WR(w~n3MxTC&a?sIny;zeo;)Irl(}#~_2EJr^bPU9*BZiXr zoD0S!q-bmcyVDO-``JxV1tzVEBOE~A5HTAq+ju{j@m1*A*&~6`jgmTGSv;_*JAWij zcW1#csj$o$sNcTYf8?^mFF(%Tyw`KYEU<&&bLfp*ZxAs$x$w>?O4wA0gIsW`{L5Iasd)V&yTjnIVi=k-X$!y%Nxb+vLc9RVVKvGE_2nvwlTWx z%4wGUApD_Uy*jj$hkgG1*(jEAf#d8T6@sLtA~*OiTI6SocJ86zh{F+oEvKKVsQ9i> zdqK#h#pFNXo2PvJ;Z|t?gQbIL3hDmyr-IHl13U_H#n5bqe|h-^+~KFBbT5Ny%n{Y7 zm6B$mM)#S*+?LXs!iP7U&TdywtU9H~Cx3a<>s0`O=z@(r#@jfDv1VS-^QL!+RVB+t zP=IF2%36wIBs=~nK3yAJJE{1~`uVUJSMAufWL?FdANK&xpu5nf0k(GGBg}WdMxPSn zo*Io%a*Z5NrBxIo)BQ5rlZl`XUvKHNLU!3AwJB6fGNZzfohvMmK_n7qfH;lh8n8YT zO*8kpb{+{f0O?DR?)~gDcLkW1ZVBsMa@UwN&ZHrqJn@=?SryxdfgObp?@Gth;|N^^ z12&$~OHK6Sy9|hH8ZT9!aIn8U3po{h0RjptJ$sHR9N+vKf0jn0HBo4wMx%*w5C&-v z*IRXZMMzXs+rh8SS`QS`0YK`Sm_Y4*8knS;slfFXRGYd_+IEzd3U&5meE(U{8h>_R z*kwRi*w*zy#OBmf^a>!f=`4M3cXv8qS))liY@Q&n?V-mU!5+}mM=uhjbegUJvc43Q z?q05dX+7FzEfzQDpZGZ8Ti`k6P;MupG zPYn<6a^82~Dbiv?wpJbN4UPUhcF-4k|9+-!(zP_}D`(tmD5QKko$vVY;Tw)_^?Stw zOJGZprGRcyCjfk{>meZ_h>6A%Kz!x|I#@I`e<=StX%L4E*ffr}vAMc%#G(p=4OnGw zOP0?Z2D-G%%3FEAKxG6FU^-xLn@$CT1q?Ju58V^^;wQx7q5sH(El|co(+S0ulJas2 zC{sP&NA?1xDk2C>+=y78YakmX25dA0Jg~RtPoo#wW(g~!T7Ohpf- zGwEIoNfvL-`wLjb=sZSOBMwSP*oJ{!f*_PiScW@j?)UA@s635hXJZR~0~QwgVeHyv zK+*wj@u0lSl`9cHcV+y_DfgToEUe9{$hle*fCa0%E-nc4Vlv2eF8I*pYD9GxV9=o5!sY|;zkQ&Awy?6uF(E*J# zH8s7o!H%NEMy~zw@br|Ki;Kr}%3YH~lJb*v@0;~8?)T+^ZPUbIK-h7VyjtHT<+pjU zEs<;_S=cApQ<6fBC)tm4!?!#BQI7W%(~o;mw&nPjYSebWG4SYbTLn(}9L}R5Zw@No zh)7IK{7pkOE_~J~x~wG{+~7{izce4saG53t0e5hmor|rjZDfP;zNrZUv;-pvXvJr( zY09WHb)xdp8yObWV~R@=bIYrKQZO?!j>oM=cdq7Fer`84;vY{ruFUD|yxkF|A723@ z^!S3oTk2?>*OMm-6DhByUbF)zccOs`@0fH8ny01UXl@+m(5wsf<@si(-JF+FxG0Pt zGt&t^iz)W6Vt$eECm5D?J6-j`zAZjDL@%oUz$Rww#XBI za^tVnUpGq%B+{uPCBg|LnUIchV#==WPs$8iFafC12sTanfTWq8$biim6p+X;|>qpdxY3AToU$a89x z;7^Irk8L?k+H4Quem_fdT>E_Nl-aZ{)%D4xiSPP7QoREM@k>dOOG`b_4hk)_2>?fs z+0YFVxUc`oVIHx1Mft*C@xJD@!*0L?1%zI{S+HLnW@BUX$>}sJ>r7z-7xTG3^r@H#Y86|xiB9%GV1{f zb6G`2Fc1xzJ33Oma)Hf};K2t(5-AgGum|Tm+`D)4KhYhmBwz(CNEIpx!#^n{?Lh5; zN`uIy;#K}^&mI^L&n0na*>AUja~u=>6?e*TxR;Ab*B;*+E#2uGNb4e=vM_swox-WJ zIcMT|LEvtl_jHbQ^=7y6yP$m-rip3GRtFVD9*=qf z_2LojsoAt6(hj)-=M&p74P3t3;I#rKKTD&of`U_q`deIPW&;_<_&t?QGK%egioEqJ zm>lUbV_UwqUtp>Ky<7|{zT2pWzycm{S+iWa&)iiBNYXL-nYv#Q-Xhz-{dkjJJUg{X z%wSHyM60B(hi6|RSIDJvt{6Hk;)PF7$@iGRrz-q6@gUIkCo^IVn>0W=R|gz6Pu|hf z6x6HjX_#JH`c*-?gzQ`;cNW^OY(((<>&9ec%2)NPr zrv7D7Rc%g=Hof=<_H=u!EzL%64oosAO(s|!oq1Fjer1U z8F-F{KN=MJMEesKOF`uI`@5J5c3b53q8TowO{~ZE)BbPn8I%xCB(%Q;9ul)f_fn{yO;^QK63ogwWUdQQdask z@x1l>_wU;!V1Nrw5UINB;-U+H#h6LlXV~=A6f4XAaby6f9rgmT7%NMAd8i_n1Spz*dMf~lQ0bpR@izd1o54RtmVgZehVSv0!q=ZD!7JU=000IiD&J#UHInz^ z$2}k^!Gc9)7jP7lnTY@dDA>B*OrengL}e8xZ2b{s$s}xrSyOe>;srKBs;9baP;SIhx3b6%j08=9n;n!e>vB-8KhMt_2y>=;{TaVvtf$ z$Qc{E3+n7xQ0F}-^Dv@iQWHriE0Y1s)zQU8Y_5Vti6K#XgP7S%KxNZ;ums}bHFMxN zsICeN3TohY;OT05rW_M09&FYCCBIMMbU&W#HTvpIR>&go`egc^8hTm((PfaI(dDM# zi5daMACxA}M)Go+`tnXlCnqPbwYmCd05~mBI;zg?hXRx277K9!@VbTsurD2Kd9NQ z+P}ttn*{|u9@`D0IDhZ?v4VU$1Uf@u2{pb1%QJ&@BW@oxGE?hu@&s$qttEU)2TZ4^$FLyx2w|{gR z*b-p8)Rhf@59GY47Om^_w3SMw7TDAdueD^=)0tBF*`cf^pgSpz3?L1R0Chch=vhsHi^mUUWoL{0_(P+Rz(yMk zsCj~oBBcI^`+^U-fu>_7EdT{yh?D|C!nCx;v?me(KS}94+v(ULdV81NHk@*EuJNn? z{K_+M=KJ>#+C4-t+QhD|$E5z;J(>%)%!9h{T5rfw5T&=8udWS>o0U}ZU{RyBpsiH_qqz`)Xv0uYjzP!PIE z$pK*3Nhh^L$!>b5d9QUOHdSq|beVm;B`+w&xzMq&5@I2#BRRQ)?!JJ)z~pdJXz56~ zuOi$@&3vJ~PdwmH9k*tr|H|+J&NiLbR$=tIO&DK`J@aORq1-YJSucdR#VF#s6CHo#Mk6%-#ILcBQMYrKKhG z+WVYGl$}(bNd(YADhYdc?*jFb5DRf(Va-)D;3y7-jT~;V`a9WT=IcBUw*jh_wMDCq zO0c#sQjNqfUk(K_rON%>ZM6SnL0k%Z|Oz5S6LOfexy0961tH z1{D$%)B|C?xld3;L|;u!?aSlL9xPzb!6d;|S6f7ulzBOSQQ2Is2A!N*|He{j35Xdm zMPKGivZ#Vd{02M%&08TQB0sjx9>j8n)%Mc6dI!)d{S@FFpaUGhOTF}gy1OsJs~T+f zk;|jQVuO-J-h;{5GU@iU^tLF_f?gnfZ z6lG@SpsyeBu8-#>-rBY$NFSQ_wgPe=@T{b#D3Un{Q`Fk6zZDDlfR9+7ABwWfuc@&F z5#~rG)kAJJli@Q(>6LDWzMh^8u&#nQom^b{z`3WC`oU{)7NCMWvO4<8TdN(DG-N4w zpwbI3q-%e{g@+$GwNzD~bNTAw!33`isZhs67~A*yo?FgOc@l@uUD#?B9wf3wU7 za#3*HwX!K6GPJVF2SFZJP;e!UMg>_m-Kh*wfQ!FXT@KVtAPDK3nm!Qsf&j2<6T4$I z`jCq<0e#AN!&~(cKfkTb6(<1v@c;qcR#%@~S?3#h-~|KHnb)shNAGLCe*HRrp=RCV zo8O9qx3>v5G$1D=gv$u1eCQ)NL>YL9U46XldbJ7y1FJI0mgGYqGvX` zVf>DoS`diuU#=(V3RDrd9d_U(U~jFTf@j4v-OuitE+eT|H(X%>%9(n^p9i>Tu)9-v zWFuA6V?19<7>Lv$kb9xm&L0Iib0+rUwz&iUbm?<4v30&G^CxT$iO@wfU|M}r9ALzQ z?x18c(>)*!>MFW+th*YhhgyAsjs&n(`Z88P>@$48wO-N+fhYw(vRH(_v8g$7PG;C8 zL&7Up?|D?WZ)QlT4gB4(*xGaTakt9o*w}wnVWx7hre11+SkUVGtPYe75!H);ph0`o z0I6AYyR5V{-`DHkK&0h`_^r(y?>=RWu0O0_`t`BSRo8frkC`Jb;2n6D!`v>6Nh`_< z++~3Vk05+bmPnB{(0_nSR<~n92vYktSXEi$~22}qim*xpf}K1LjSqfVedYzqwL ztLvoxeiT@T_eRU_eLW12)Yoc|-pzs+ivdv`SX*G4spgU1_Y*DF2Uhz5sFib@Xq>n5 zRY-|*-)XpwZJnVW0t3K9_fLIsiSc@mT!0XrF(eZ7pkTYJhXuF(r9-+KLHw5kY=6Nx zhY8egcXC@M9(vVu=lDYJHsc7q_Rl*rF&)o5pUup~gi5{JZ-Bp7b)I^UzP*lqG;ZSt zzQaz`;vL0e;2U+ou~Y!--7-t5NxX` zcAERY$KlV`P*pJ(q+NtC-r@7@Wn*p`l^kRn_2c55?#^QCoU`H)PwPGg9|*pBWv((| z;k&Dp?BBgIEaxs+nFO=k-RmS3apjrkyNl@2Dtxw6$K@Z2H7{Sb=D5H#BV*w3ku7eM z99(N-WBFpbc#4uYV`hQ^6@C0I_fr#+6pW;=Utfq~^v!}k%0Ev&s-$lGtaV!GJJ!A~ z$oPi+9|8b>YW>%y){y_&bh}N)*@1ljwP^uruKE}glZj%~Y%}{-%x~(N4>tp@eWxdU zfw52H`||u}tDy{|JsP{SwIixw`WX3NQ<{K8ozXa>1K@X6TpJq!PFvKs9qYXRdKs#@ z>pS0fw`7GHbll4S=zY|Grr!Uno4jDP?i}ywvq^kcl+c2+u=fKhcu?<+cimA>0qV@A=k?dv;LD7%k}P3;Ct~wG;xa-0XZy`{OxIqO_z53fd1Re=;)Npj#ju=z(zUQ z3aOeX`}b!xl;N2k-361&yBW|3(th(!R*9R`&uR6tt|{ZMQmhKU8H2|qLKXkY1}w_D zt+-$7YH+WtSC9xxnx)Z8lswuf~|aB{FbOIX7# z$_G6YBZrfEiQX^MXQ$kS;Cx^nLN?*+%iFo{V&Is5w(>F$7S|}1h~P7Il3(QUH``vw zaudQH9nGH5G=%XvFc^>pHv1Q{{9JEtiX*LnK%nJ`4kc`A!G{dYOk-c zwz2FQ2Wvc)D`u^>_ImgF+jQdEK5^Hc}1Fo*RK)tsoa#$O?=5OZd%cN@zeva#qVTM-4y?P-RfE^^(x(LCv~jv z$Y|L?${QHt=GFA)xoD8DY2oL zt-Ra)bjQ~#?F0Tw#JF-c+?o71o-$^FS6;R8i`Yv0p&lz$gw+&}iHsi9!SMHP&LDC_ zW#5`FR;4Y12O)Yo%(2<0#9nuDsmY(vr*+4D_S zkTqJnyYPO3U{(&&Bk?3Lj7Cq(s1^<<*;#4m$FXgQx9g*>J6fk%H6C>zz_fdXk3-=uN zjIK$KcdkMFvrnSc%cik-lzz_?bpOmejfPlcQmAZOBTaM8Dfw>s6j+8V@(bP87jl5{ z&%c3s_#m^K2p@D)0_Hr{Gk_pK4zoK zxmtO=`hv)!xVC4@>#$hv0F z*#E+E1!fmCFZ3bA3?uJFXlFiiAgjc^YP&ke|i#ySZB*rQ&iH>G-G@FXKJQ}=! zQ(ak>7OK2ifT!~Hj?WdVVG46!{t7y-)L0FRV7+M|kpbOFFSI}?ERd+vzPcc68+4DQ zSyCuij`f%htp)4j0WDTSV2=_Ndv{gu%MNMh^GWdf&`@#w^-wh%roGe8GvBlWZ!x;m z_~N*oY2HtR%^m3}~;|Q<_9p1P}R!)^(Wmx;8D#Wd-W@zqoQJq9c99ko@1BgzJM#H{+Mf-6X42)QoC8fFLY3qiuYG6_nWt-3 z8(*yiU*JiA6xyl*NF{)OMUk0b-<5)}Bjo9#e*!PCK#hT%ukQWV$G$%eGTR>@9 z9Zu#`Ps=+}ocvwM_oi0jzU6FIrWm;9$3|8?Gj$h>3VLMUD{gLX{<_c-nJ~Q?KfDN( zglooIZT|~+6u3DnYH>Zc$djlnGGYH%5;dE`YYe-dEEt2vNg3jV(Zm-&!DE|CLz_f3 zbO_pPl3(M5>??~DQiFzIaOUwyj3K(n4N=s&l%?)-(CyA9Ben-l0@P#@pDsw8WsOYm zM`Sx`VC-Ngo1G?{#kx)i1^Ad%{r5$i-q%qE4Ar|uA3(nR-vJx*>~(KD`zZbC>w zvbZF8N`Vj_u zd+M6f)&}$fHqhB?&50z0os$k_GX#iFsq>culj=3szj+J!A%u^&PZyq$Gtk4`65@enj*IE8Ne8!8DTAiO> zp4PrbTU6SC$U$@!Y-wu()gv|@8+8CqzQ5KTqqWwvGTNPOEOTG~hjUy?wW+>iLT^@; z1-fdPKX2r5H*clIvH>@~DbXy};%W!++>*4(xd&!OYrSm^GCb*^U`&|?9<$$E=o5TEu;9-{OdT$WYI+HLvF)!mt)`wgh4A;Yy z`T_`c$Wc9vom6aAIPfh)^*QEPo& z3gSDCQrG#AGDx(f{m|D}9HHuTj)qs5pNc*fVl&U3BDjz<>n+vWK4ub<@yaa*KQvFF zJjd2_D;mjG44r0ADSx0SIKV(Un!E;Ou#I2KD6xn5h-r_omS%G7iNKL#vVQT)c-1U{HR$ZnMan_$sA;UZP2ak+cPA<>?^zUC;C(W2+_M5`q?}I>oYxXp0 zL`vmpuW)gaXKYauv&5S)Y|3rrcsw=L0C`P2LF)5t9qJ5uVcyEREuq_|7Eday^6hSV zkTcQ{a=1|My&X(=(o#AfN>(Ewjj&e)bQwg@$AvE_aHs4*^YdoORo0U>-h}ZtaCY*F zCU)I=EOCb%XM5+^a>$_16V!a0^l6_sFO&cYGK;*XIhaaJo_5wp4z=EcZF-2EGOO z^?Pf)MLbHJ^%COsO;w8EHxcQXy>%xJA@nby+!W6k z$tCp_Pv5=!n!stlvV7lb_0+-w)h)Ju{1untD5)ZP|7Liw`ugBpVjsyDx#5i}7h73^ zI_Hq2leX;sJX^*lYJ(hBSIIZMLL1xtf?Ze0QA(|hO(x)k3+D@Ays(4m3R00 z^sisGOCZ;WQG~Tfqkm1NActWOsOvuCOLUBSVT^I=Q50UKd50gu(y*rYsXZ4;s+wRFNln{0J77usT5$+HMA zbTrvxBnSKas$r8fhp}dJ@2scvS#Bry+zjJ9tFB~u`QHX1i&N0{$^cIwPNa_hSj1I-{yIroGT*b zUN$;FmH2u*+KYKoO}%IKmgcDuZ(8sgLD%n`Bwz0?@T}ET_&>=XJ3Ad>YEpmm1Rb}v zZ!XGeF?SlYSRjv$n)q}XW|s3iVOr7lgHL2`xad4^DQ*~4QRHjN@z+fVnX}h{ztJ`{ z6h0zgc5VVW-P1l-&wLod`W=7sqTN)8_)*HSO@!Ow8Hazk|jkUh&1%tQ(g;b@QQLC4R3+~f?epC$k9!y^f!)iSr4TXe0i zV1-lHaLuoj)&jQFjw%0HZcqZu88`wbuV8_rwQ!4iwr`(gWqgrn&(xI4NV|;=A$p>X z=%a{E>3(t%-gd7W!-SbNPBqLTxjq(t;)>}_43N-vz@3T8vl=pbbEB9m9wWoAmqtTcwf-l+HH-_nRSfU<(E@RA%FjQ%W#q-tU(hS znJK4t>`wFIl~g$>;!iHfTcv4N7K1R(myqlIPvRYh+Ni&yZP}!_!VKP{b#L2*HJsAn z*N^GZOvyAovvslQ^;4vIzEg#lQ`rn{{0f@Ev;Ld~pv9ZNxrjI~UnQr|9~^#eD=(uu3b!TtEF~B>+2al$hS?Z7h;7vB3Zd`U%F!BJy*~|qdu*$W91N|RK%o2 zFLP(xz#=EGmPe6x>qYxFEll4F@sWNtnfPR8TuDSNgD0a9UX{daq#6t zO~%Y5P)H zarZ|M2wBVPA^$G;kbc4Tgd2+r9boP`T$yoFNWl%w3%1$SNZYC^}Up{1<&IiB~{m6dd6C|PL?ig6)UrVz|Z0L^REZs*3V(+KZ))xqEXyy+QhdfRfiaH~L{YC%x@(${_HzNLI|kDRKGn``(e zLW-tqs9gdJJP+tNOP4Lh%i68YzgnC3M8PZNnKc;}RXV^A=CMIh7H^_qS*w%T;Gtjk zuZJo9zJ($L(I`xhhvP160!agAScwyELy}Yr28`u%xtdPU71&-W-P7FV_f#3 zX?Whs;i$-}?oT)Mi+S`PxIGCtWZ#P}oiFEuY_?eGHR7kAaBSNuFf??HohiG=BQ|s3 zmXD&Lzub2jQ~A=G&X7?hW2o^E)+~0)6g_eHf~a;u)$sHP1tIQB$nv-vSI#5UpA$Z1 zcRaLaE!L7`ok(WXvjRK7ei2|Q5eSSWGEt$IbH<@BfXhHONdOx!k#9AX$rdHHoKk+l zTT_X7crx;t{U#YvLH#`uDezT4REy$nV23s^gn1BtCTgDBoG-`vGY0h!y)c#&ZJw3c zqYsPGHO}?MJzw}f&(VdHAmjzUWBa`1c~cSn)rIE6^i8)&);N3M&R}(!v#YVbbktNG z0kRBZ{n#pE&6uBzu@rJQz5_D z7*|mer-y}cew}7bAq_iI@^W&>;Lx{NNP@1`k&sKLM~*mqiA%TKrjSabrY-sSX0a)V z#Wlc#`LtEbU~&TwwK?eqt8V_uJhoJq@1GlIM~7>$K*xat z2U53!8JF~?(i6=?UZl~ncQq@2#Y?x^4V&O0>J5V=Q-ynnQ#5Eqjo*C z7V}~%t%E%FIV6=r+qvvtFgLHcJ5R5UZz^uiZKgW?Y_8Q4>|1Is6&V~nFZlKbgr23{ zJ{1+9?S;2>f&~kn7A=~`i>#KRo&l&S!8}eD(!Q3jMSu|f;^X1g^Ex^_`+#O_}4S6&$0RwwB5uam~=7@*L;6D zo-u&m?=jbcht&R=>-I=D(BYFkt(GQwJIMO5QOE>;+xr(rF{GY(OK57tnP@xyVxJq@ z>lG!(Q>t1NOO0EX}= zl-ipZMCqQj_ABJLJykqLL&;S`g@n+W^N)N@ye~5v`#H4T#li0iFFu&!=MjC$u*eq5 ztKX)_T^#oym?J9{yKkVBZ_S|X~?me4L=2looUmA#6Ht3RWC0rPWY=q+b9ET zGW~&X_pJ$@B8-;V=X$#hp7+Z(o$%a7N7I;PAZHDoqM2W-;M0?48PN885g#x@INHcw zOQs}HX`;q4+VaP^ofIw`mJVs5G5Lf%G{kl%%QQI&im*m4Q-oQ2TJ1Q1PV&dRN*8BT z@@^h3JTyvid~aV3#~=?YO2Ow+z%w3dGf@-#P@N#{IA}>C`Ny(ohvAgs2%$D}zU3HV zyq-3&NKLpbp(qkSGY;t0p3wTX+V17CzC15kCCeC=lw;d7F0M%*m)Qf?G(X^sEUmMP&QLm|Z{;0HSg|5;TMQ7)SLN7X((n)uboJmeH1ThC0ICYWR4o9(X#=#8v zl9S$)22|t=FJuo{_5Adq!n$UOgNE&-(ROMOJ zpp;jiD|hFH9hr~0vqJqw${5*WH*y5w>y+>&47gU<-xAYPhE63G`A9$B#$7a~Z{F9t-e;ex5ZT)M0`f4y^rxDo3^$vQqHXg;?29 zKjVC7l&LciYtWCML)+}!jq=R=n#$bGoO}mz<2`;!{erBnpL&E(G<3P^3`j?TdvcQu zD$^pY<_$bTj$|qw>!d6g$$rgBc9zW+m>?bS^P8O~NzWjbimgV8V}J8x%EYpVxEn`$ zo0#E;Z3qNU)!0upyPyA?Q1orjF$MfQ3&9^+pB2S96_jC{ymLMiICEE?*ZiK8r8Uz; z$cWH^TgXIbQm;6(D!KS8+L3%$`$pu@58CL9dCYO0O-prG!mrmz!cFD1rV!+kxB8H= zrJGAW8)@#jX(Iz;q8TNTx(K+uvav|H5GT7VFyqIGt z;Rw6Zd!w@B67?&fp<=4BA*NYoP|I3=QPl6g4doUI0&)|FS5sHs__dB-`I%CdKcaU+ zr%uZhmyqWPLf!VU;Szn2PSHn;2pRL~k9fIgA}0s!;DctyDQf#5eMEd5X_pU-;2~AY z41pIPT9Vn)RXWx)v=W(M{rA;TPsyJ8dX@ZIPaPk7O+)Mh%qNRVzWDCqRTW0-kH)S7 ze`cqhmj^8!Q&lWL#F$2#W2~wJ^bHMXnZeYc-GG8wy+10%=WD2~TWs@0@g#~SRn>+W zh^o4`Xkxx6icKb--^KJ;R}NGJd%lqbwp`0 zzv-!>7QQGLPMrkL!)Xe)XxbTKMYWPy8jwG&jmuq>JL`U#P!f$xDhv6FKj?BeeTEVZ zO~1WX`N#YNnPGt(RU#^H?Wx$%t6-z7qO4L{3kQpgw8C{F)ZYi%3k}GA-jrSjb0 zm|&?+a8XxFX}YO*@P!jWiL zw})I;-J=}!10li!Z=+#oYuK9`7vgSa)wZCcyL0~XRf-tqO~4M`xeAtC&~K_894^jk z6J5zlFnAwnaf8A^DJ{v?l6zP9VJEz%Zm$IiNW4YWzCl=vsjJ?wYyo1TGJMt5};(_ND)`h*mGdC6H)t@CP+mPwkA6)&J^R zzhL_^{x8oy{tx(hG5^a!fAcNYdly~&Woo7^>$Yl>{t}v z_J4`Uy`b}6HzoO3)<2fMKjW{B4Bz>0&mif$LJw3FSx#2*e-*X#j!NqK)mwx`FE2Fv z{w^!|`#Q7J&bfQ)e1A{3($Wo2bqu^zw&qKg{mSXPo337dQMzitpd9sV<--ixTgFE>) z)@enqQwu?*!nT*EX5E?=skrOd*Y~-m-l6rC!cEb0JG>_?TGD5K@u854{F9*np(o>4 z#tS!1ni*8x6Z-cjB&CgumpnwoC}#? mMK|y;cf>-(QNssmu>61o<1zM~vPLZ}0x8gyAv{1abdm#je;981nN^y59#fk=(0xb~S9n#+Q({!?S^E7w0!U8!uIaqN)EM2Xv93eJN zZihG>l9+?|!CHE5vaVL8vx#9NV#l%kisf*WaH z_yEX=Fn;09l5gTaMXIo{UScV{lh*Re+*>l#TG-6mx~+QiHAG4VKZI8fH`wn1=y_(b zW>HpH;lz5{Txi>w*haBAx9z#bp1jr|2I7u z552@|5?nCD$~NLZjm#@<=&A_?Bk^=AA$f;sL0%0C|60{rIzv9-h@i_VV z3-a>$>XnlZOtjs3$%nZF^$qGCPNEb6KZ3?W5ClApVZlv|QNX`cO_N?RweQ6|Y-A$f zQ4hD>V$pXA)IK-ni+QZ(lc^^nlc|K6)f)&_p8PzmXvY$$c7#9^{Rza~OA_@#9zA0( zK*4z@*p~}brovZ?gKX%kSNb=m7lUjf7%{zYj{?)@Mk1)PU4V4K(byNPao#UAu`gh6 zje`R+qp`h`m}H$=l^&LCQ=RZUTD`r_|NLl2k`0cf1WehWJ2rmE3UF$d8o~V*u*+thg6ba6& z8v`6J9$g5`wna7f=?nB(KyTUzj@OKT7_R1l5dGKLr8BRL>Vo}kA?Ncmm#etI{S2_( zTk5*!et{GcDYwL2u`6{Dk&DlR*{o}w0Lr_b&I;ilvmRHY|9l@P;^AuJYx*9BxHXcI zH5wA<-L166WV>ywvZbU?=6=RA3lNJe_vg>nP7_ShX)a)U` zb>>aUGHYKQS5AA&CEk*e7nOmYOWru-%urjPlCT|Tt?OC9B4szp+ZToV6R&9OwFQ3v zu&9~H*EG6c%pvn@Og6Z@rmPT1+~O^>yZ{w!9eeEI_j1=ZE`($`sMT_BAqPNzx;%}u zgK#q*%bRnD(xg6tuMx>L9TKgcyf5Q0DHwb1y9`-4{J0JFuczJQS#k^M0-l5@Nysf% zOdX!YKgM|A5yHovpol=%FM}P#t2YKjGjTMZgj%19anbhzQ*PAOJ}{%7JG==CluW;w zL!*DPF-m=kD(}eY%))n@C0S_FYaZqtg^_pYyJb5!b0mfQE?!e`#7kk=i5l=a7emgb zd=ao!4r}9Y(f_nS??fuJkbTxtdg~=pk%d5#w)*;==gf7W4F;NCL#OOKhr5xz>1rpx_zr>}$G5I^0>QotJZj0TzIJfK!hYh-kpdU}$DRt7fe)9*vAR zrPieYozVC+c_#zjaZKH`{Y;FYAPb3M83R?GFa1X_Si~Y8x$}89nx&4#T0Ng1f?`56 z3v;@Y>li3c)LmMBPM@dYAO_d};$F=rWV7xlccEP>!EYz18OQutk2(o>gGjTS>>!D@ zkAdmj%M0S%gcJUe@0)Ea=3*Msy9Ibg=QwD7qx+tR@IdQ1Mh^FX&2DL5WJkmP3v){P zxZmCj36SY4BEjn>Jz($Y${A!TA$5){r=Vb$w{c)!;LkYZl}F<3h55nkmnNBy2A?{c zW3l;+6-0pdJWPw{@I3wv^O1zP>Y+Husk9B)Lw|pbk4Cszw~XuW@%b)*pT4VVLKBpT zUouPAXT3=db*;`Qw2zA2KNT`(S(x|{CBLQp!&=&|(|oR`;F;LI_o1iFv528v{(c+- zaMfSDJC>K9Qt3>`pXr~Ik{eH#tZ0=P?l9lpC@M44D;bet_f7Bu2(L zYFowuUx5TA+q=NX25%rSb@VEhxJB%gh6;CRVSI{~%-1YIPuyH1quusULgw-q8`4;Q z3=tPj{kC7(T!JhgzSY(jsRu-I(&yh2tjMVP{lgIANo^tzW*uCQMNFMk4dUkcw|eR= z@!o_yZBZ8Q^o;_C731^@46?uacWlHGW69U#;K4!CwqS&UZ}vZ!Vqy2@kxJOs89A!i z@yl87;*+4463?ogzM6C$qFq`>~mZ<7;HAiM>RR!M%+lIN0amLTupWK&gRQ-y#B$+&>EC! zc_mX#HZ)WiYJc1~ySE8d8(q%0xG`Jz9EA5;4(Hfv}8sd+P;#@Jyz~>s>9Rki%;V34($`2?ehp{Qi)m(%;)^{m1rAl zonj1wC)_T(n|j7V`F_Cjx{W%^ui=>u8N#jYFT*ChQ-pmdJ6q%@S|lk3VxX!{Pj$`c zodj@giKhMN+?gH;=p>CARjRekLHwcy?-!L8_PS-WDx$JyD5j^wZzbm$lt+2R6a0)* zkDav=k2ZMu&y-Cl8A;tZHv;5kd!!*dh#Yz({5)qhrb;q^=`a}24>6GziZ_6!%_(RZ zQM&$|Q~BrV!KjR}4SYsJ*CHSFThc(WwlO|C(EiI=`!Dazw0v;^Z~q{chDlVs#aKH6**Q(;4JQ4`dQ`8fJwG&$o_WI#vC`BjOt zYRL1MVOJ5G(mDBZF6}m&0z?7Ob(qf3tCSa|8l5F~O1lJ=yC`XAYxaBAivB#@4ezMT zf2EG=VVNPdjeX$f#4!EgtKqqv4TExG1?$!T$96yg0F}))KM^Ep8@Oxesj0sSIxoGn zzpQCHW2Iw3qgv=uv0_0*Guvki7h7V}lb2JVw#-XYM^Q>pEApW!xf*7Vy71SXn|=F$`DS;Yf-9IyGhAibNUgqD1-1{8>__4_iBtx4f;g^p%0z1rYHN zF$qiu8hHYNZ>kzSvHU*+h-#E0a@Pd)4C@r_3a1@(~bW zUHXU4^1AmTv}rwplHqpZQr9VrlMD?m`&I-E@DqN^XQGn(h>Gy8P?a8?_KyDWK?I_Y zQjS~nJHRx1P09$+87qckWQq{y2?PT7&*g1O#eOgFkXyTH^4uRirIe)3gLw2ZkZtZw zr_j@=YM~lj(1#4!C$5(XujW~FvpYli7A0Qf`OfyA0%-u(r?%YM#S<>jHCLE-xo_ry zHsfWlo#mJ8wa1P(>N$7y@yV>`49(uVB%~+rbndw10JJ^i**$_ACHr^yah7;Z$K%X{ zpV+(DDpy<}{;WSmzdnmyKgHWV!Q0+LI~V=#F4A?VBXd~C%6I8T;SX08PoxTI` zh1+qW=or$QZVUt~def+5JV`EGcqE7ZY@XiEJ!$I0m+t~f4nXfMQw{HuPIU+m-6Dp! zpJv@!*3p%%mzWBJJY?Hqhb`YkiSY$50A=N?!UJb@yBFdx6oW=9XnJReGx?gX5+^cj zYl~*JzmmGOJfN29&I}*)HU#3Fxtp^&aplTHSw4<$;aKv+xK`b$vg>qr-Z_L`ErcEl zec>5y12E}Y;7QlS9ZZygxTF#}FU^gd=E2Bkx-GJ$i6xfiOlKJu@pI>>vrytjpzKEYLse%N$Xj+eQs-vWUtiYuP? z1gPE%@scufLEQX~KSM}#@K$uwh@4L`P>bFOlsu|)(Uy5VBX6XzDc--i)jBh{4P`kh z_Hj&aJ-}A=tbFEYx?6jAcD%7P7dtpJaL%w*vfbdjk3Frp_EI?D`VojeL_^#qZg|CC zVIr&kfy{qdA1)x`PkphJ4*>diZm(33hZxEF5pPo7W**S0IK9jYJDSA@-PNa*+dVRv zUd_o|)#%6JCMkq;Mvg>01Yd7qgW5k7WaD4K7U$IDzw;%=c}0*&MC}gR|BA1O)ItFc zSR4b6c3JEmuINUMp{sK`Zp9(-B}ad^Wax6Hy<^tsPMtSWpiR8(T{YGf!$TIZl{L|? zM`XHzr%aplKgj(|5!NOki5k>pTer=~7;`=NF7;YCgKvt{xYgG{ z`$R|wy&mI5d!I{;HvnCJr}D6XvF=_-tm}N=h7|wOtDGOF>)c4i_0qJ4?Tc!8t7M&) z4Jl>#w6YTHwJTLtUQgC{9*QD}vm7epuj}{urn1gjZWhXxb+3d0^|&Mc!oM z=3~%dA+_Jg#~hRL3FfSn*j+BV>BW*46wSu|0=HKRKK`;V#rHP{@JO0O(+^HbHO97KR0%6_?0Zvtd1nuuumR5PUXTXWJ09&(AhEH z_8)QZ%a#vEQghuLH(@=RMwtUg*_}WGOwMvB0s?=@_{Ya-5M6+ZT_ou@uP7yrqH)k*1}A@U83#-1 zGi~e${C$RV7k|G?J$GEjiv9|LxtK|Eo6l4M_k>yg1xEMX9RhkNV#&4fl+f0U;pe}- z9+rUC0#&R@D+DQMbtK3Qjz&VZXtHyckfy|qcwG5;LSVU2rY1_gbh;OgP%B>m{fg{6kF7&V3A6X zyC)*crXnyf6q0&qH<3j1mSLMP|@b(W9}fD`~}V1+~Fm29pA$SGAq3&` zyqQ9Y7DU$eE7~kNbrzd8ogF}xM?C`VFZ-+kok>u7%lmS68XfY&y{R;Pj&m_%Jh|Y- zizALo4kz2cTVQdEqWYgtThxOc1BlNr$QtRr!G=$q<+cyD5t(Oi4=csPXbE)FQzo9i zDe}NfY5i5=yI&^o1;8;!xVq#C!zwE(>W&N2Lz^2u()IES#@3Duo-QNL&xlD}HY|w_ z1@(0C;-*ItGdt$BLrC$?5VW|;(TN%Z*GfE3buFi8n@n2$&1iE|@NfW?eQmG`R z+dK;cdpT8#4H-A$!(W7S{wDMCDntM|=+FPd9xM(2p^U54Bq?*z z%BVSmvN*Q)Iul=A&wG8W|8sXxDz+!#7h><%?p?;^FRyMGqShg*9z7S)jWM9Ea~1 zax8|vmg>go*|3gTj$_5+pUbm&AKu|RM6WnW{&L@Z8F#N0$%rf!kQVHu#tSC!bG*Qt6EB{k+xjI0yRE$!epPV!} zT~$q7xTJ3Gvk*ucT$K1XJ1u{MmBZGKl{3Ujzqu>Yn$Pg}$|Az!y;Qe}CcGt%yo^ME z#=eMRI62*giox~D(PG0_{M`Z$1IW~v(dl>(AbdqW@%&iX$gXapP#OHSpk%nXWY{_n zKs1e~w1q>V}hL4d!bEoGm@sNeJK&WKM`LPKgmnBzC^)aWRTCD@U)foYFMrB)>94{Pz?)qS%qY!hD{mOA_7Ci6z(mBpBC-x2e=NP#@>@v*Z zy}?U~vu`r#aR%ELKyL1nBH^C6OSVct+X?5RmHIkBoO6+Z_XEM%b4tq<({~f?lB)N^ z9dE1S!kfmBYbRw>RzxfKPHei~f2jcX`!w9lMUM zgXc6Bx!+w=M(Llhb5#U-Bo2}fjObYM)SL0tj~XqHY~Sm(^CEo&l=~lxsTgt#Jexlh z&y#g|@B@kGb-r-@4J~3vq!)`zD_E4-T!5eZUYOtO(depIUb?4=05b`N3hvH8G??2R zkevoy4rYlD8 z;_u39BiK{X52-6mgL*rtivoSWY4sa&*tcGTboK@Ssnef(96Mb~L(Wzt*T>ffGFBg^ z-0Nlj)^6kUb+>L9xK*7AT5Ud0Ew>!R7BvnEZR~)2Wkv>28W6eTO1KMgI5l5^ji1oI zcUkryI>qVNIHas`;PZrs$%i)`6}`U5F4){_B!-l|hE)nO4f{s>hd`pFsy&Y$r!bJY zqHWTHvT1QZ9r|!4!(+6=h99jq6Cl&nx!7}C70`HH++<(-NitS0J6@?u8`AL3n|G&% zlG}D5T%dkE*V6Av-+WUxD9cACF6IM$(~#R)UL#1LpQ7@Yc*B`RZhj zJnt6W>w)(&MXuj`xonIDs8U`u+yHHklChQa>O`)+TM&{^FbotS_Vsb7uI&89B+pcF zEi_~8bn0GC#VL?PjG#5K0cjNHrRA)jRp-<3)HvI|pNH+!F%WI=y~? zydtZ5{tsRF{1x($8*-r+a`!gKNAfn*ZeEUJlxT$zHBb&&N5)56C=}> zEj13}q|V7xs^MHTsRzOevfohl4+4aI#;S{4S^6**q@6(Gi2!nMpg~mBRkr1 zZ?0*F*V42{AVhd%Y`6jf9eVBgkhCE!lP+(o%B^kc%-y|=`fv5eFM-}L=iAKsM--K< zCdmR)r^H^_+{iFcNI5h`Y_#|m&ucU36iu_MH~>5Q_PX>r3Jo+W)2O%a+(hPNvw~F8 zynMBfjHL@o#>_W0MEQ|e=P5l3LG@R_GLvV1x*C>Zt`Uvp$#|k`DBk7MAATl@aV;jz zDa3}d2#zU^FNc4WkwVMf>b#$`NJf_%dsn#lWK+~oO-&*EDjRZ z$}^t{iw%OnCK&qnI&rXFa5h$7b-J7%b>{h9=iv%DhA_Nm8MqSe^FJIa9)DZ0{sPH> zM^;9vT(oFJ?Wa4w1-_i_Dr}xz0=Bo7naN-#g7!(*S(P}Te%O_i3%{D(-|-jPf4a`! z*xH}5JGPdl!WoEM3w*^P+s@gF%vEzw_m>b+)ZbwO{{B`+5^0r%F`gzI+9x0jx8)c4 z{8?H8>|9(cKlCwxx;SsG$X|eUNA&*h(EM#?2_{BxH)4yiF==uZstZ9k@!ba|#)Vsg zldv@vL=M~4v-4K3hwB~#eXT%W4zWsO1lT}0@}Q=AN1AjhRiv^-Qg*TIrM_e*p*k3R zxnW*uPv#fSdAeQ8`8-z>wqE*cpeU)!lPM{CnvyF@`zLQEBesc3gp zfn|PY|9B!@0&9~VPCcsTyN#jg&znMY?9(z7!AlEdc*Ay1CEhP^VklMoH0=Ayd<@ax zj!Ndc&rwv{tx2jat*>iGJ%B6SY6?zkk^UCAoTPXVjXgN`_JC@#idI(6@{b5ZJ=+&U z8b%fQp{BOTVD()#Bg^3C>f;ryols=Ki|S;`30qArq%#+%o&;5e?;5M8EhR%4@3tn9 zp5UZG-P^>ilip3L%(yO}p!y<&p!3;#r5)r-vBt2jkINY|t}mK@kv?i%t2PPCJZ3nY zbddkE7KVgZY|~mXutZKSVeLnD2A-2LEK?3N)VVE99V$IBnWQiOAd#R|R8qv8!%=V- ziw8teFT1lnFvR5#^c0^`wk9I#kE$l|q6kRw3K{OA=1yYA9WrM)s@KLTCT zJ4-y9Lz6&Ve47Dm)%A>g-tf3sRORar#T;Bn3-=wf#LBwNj;idx@LmtsY58lZ#4xh` z!tKrg?m3Ot!0c!8uiUtcUDAjUaWekQz9n*`Dr}mGrDbC3s*pq1jOS-pO>~R$yK<*V zib}gP1JfO24d8_p<{RUI<0OCgDGJ*TDuu~B-ez3pBYI=Yo_?Fp#J$QEL)J8&aK)t9 z?XwaW2`P*h*DvN;pAQsb8&3mk%&fe>oGfiq0&Cq&tkuo0ULndB&XwC8C73fp!$xiv z6@M)6&>pQ->2naN5N>{6FIHE@hU4j`1UtN7aFENU$iQtT6%M)SdTY|KtoF}iXL~;X zY^uaLkjoR|*e0pW**EJJ;Y$ysyOqq8wjz^N+2?%$nxT5SE`^=rfqEhhb8j7V(+bTVeD;1`Mb&PMUe`k`uv zR9Swe9l7CUHTg!#h4UMcl>O~nFmZMaQ{5gzA572jL4asU?r>|DohwAgp}T=X(}cL1 zsyBwz=X-2pz85HI42!5pKlZGYO|THf1c9)@&GS?rr9ydob?}m3Wim!Fu(9N91aBL6 zHn{SuFs8q|E$D9k88E1ml@{yTfpA}?%?ggn2w}%5At~{0lusG~`%2EVJWn$6OCHV> zF@S!uX!xu7dsT3k=7dAzU8#$f;kdG9UY|=LzHbglWT|VEY%M)jvv=!61ibhZu2M;2 zp)Lb?bFMl8>qv{NBQPLUA&1rREZancZyop9R4kUN4j&Qq(%F!*d-QzhG?Ia!@Fgq> zNO};Gj%tU7{y6rN{ozqz?d{`V{1=Fiw^IqXjYvL~spUA>Dtl)T-F#2z2cQ6Do4Vy} zT(gQnOFO$lxq=f$m1{cpG8vR-%H!1BCRxc`J8I3~PoiddE)@`%1EN6Xall?(e%{Bkc(#Xo=q6f;4~IkLNi!bA^_s>ziWiR=5@xH?8uAhvZ-@+oEqpWubf( zs?w5iDw9DCx0kcp{7TXr*OtS2mdoJ?$#Fl;-{R;HDjmHhWK)k zgUlHiESWemRr8MK+ZHF?0e*!-hGO3q{Rzie#cws=Z(Z5nk|b|cBi89MitQ{YW=?3A zodve%nJHA+cYUEW^6syu?;=C_M1b)9t|<bWUAxcM%0S079j65?fGU7|uXkKunyNXIWcqsBqM~G>ulMaH;Z2qSE`jGZOAy zlhXC$cRVTK6q?UMx3*j+#t?F#QAG6y zImmn59M0Sn^dd`DP1cH+tN({U;Q$c8P`EVLj|}?Fz5To5w-ZC`&!m_aYrp-h+ttL| z>xs{ejyHGfz}%jyN`!%LWD7p)S)|#o3zLj+ILVYvDAOgH)8JH8F(7{V3*UP}q4e*u z@$qEch(oq$sW#co_-I75jfc_-DE7)Ur<_<@Erc}l9258f^)x5!$r=LhUbjF*_4`uZ z9}4jzRhUM>lWFj>%nDKd9%MlOZs&(%@3&w~JPZ#5u53RRG8uSvfL>#%C04s4v>doY zGolv2tXkRUHg4uQscp{|RC06@+*ViwI@*$E(BsTM*hXXq?_PTIS@mv2*xe?V*W@j~i70-%V925D%hqqT7~Vq#xIZy?|A~(VTq!j1F!3Y+s-CNNgZ>QlY!&Lq@Jz;|9&@ zY8dKFr%SBiwh6btY3i`R(u-myD#8Fjn~zu{6{YufrWNT-N}#Z}Yj=n^3k>{K^r|=a zV|hux|&I!H<+Em z5O4tU#!4A`9I0Q)&#!;rX-L;J*UW^QXRLQ_J!pN%5awaVTzp$(;A1-9N3u9JS8V6S zyby9~V^hlgYe%*4Bw}O~1(31Zmr-cD*Q*Ja#^AGUdzsxOjXJ{YBBXaWfxfrB{)2Fu?xr&US!-UhtD!FpY^BatofhQs+@)Xq^8gM z+taHpYXg?78~a&lEGnruzp+Pc)WwQ%m-dX0JDoCEvzFAzx;zC>kErJG=FFgA%#03@(8djdrJHTcXB*8>;Zje}()JH;_&LkL|} z?-?5*x>PJ3WW7hL-xp6P5J|QT{|)adv<9D91LA!}_<_GN!U|oMkwrdJxw}%g4zlFZFD7a?{?aZu`=Pbh?CtXI*Rg zp+jVD5gPUIV4lzZ;Wn+oa1ChQDbHN~I(C6Y%>Rlodc+x_`Toebpa`k9Z&bN#^rT3l zY*t1yFT7k*?}G@U$EnfcwcL!9naFKS&DY}b)7=DP5y`0jZwv2YcjkaO7=Zqc;*bB{ z{&UpWonCxq17?h``XqVLt{6w*3k#i2VfWtTG0ANyOOHlI>C28i6%G*ob*lou(y-*C z23M!JY#WAeU+hvgot~~2s^GQBsx>W&HLklqa|9mqkX%7xjIK6R@m7L9JZ$8v&K)dr z7$*|0$!nDx+PIL#Nd2bjhk^_?^WLnt4v4soY{`95yO z!8@U4*p(z~3quFeA+ivcQM*D>=mX37h9-`rN~shrYooh4_na1r^F&u1L&1hGS?#IQ z`FS6!Y-}ymiyOWnz`_$q3vDvQk^Mt8xn-~LouP{4e{_Vq=#QukE^)fPwzQdRSwePt z19bh!hbwBSBBfV^7YkFOr%%p z^LKlQl>=Q+@}v+D&?1)sP z$^FtEhA7+&ox^d|GxeJR1>WYxJ*XkZ^F@GW`2l|OMSjvgWLZ?#0i+Fd0K%+4Lzgoo zkTN}&9URTYF|7ALazch=%)?1Zu?;y>ZCws z&H3S>+j_^G!*BO;!O@Fj^8nX(&t690dIy^E$8$caeRbKF1j5yw=gBTuD7Y|6N^V|X z0x)T-gqnz)3PpKF17|9Wct4gH=^v<79tx8|*NK=1oSl0K_m(t3#fJY7!z2};><11G zc4mfN)**eGzN$+QjW3GZCYMi6);NCsrdJjaF02kx#of|a1n}z<&gQ_Rlw+=!zgmRG z;bwTh&~@&Fj5FK6Q}K`WhS~Q9FVf?$(VtAzdO7So0awo2t#F9_94}dUaDK6OtnB3K zLi;;V^~)iFy|(oZ<>1~8A)VR=zOSDfcLR`JLS^bj9ZO45g(;g*xV$%mf3J!M1|`VY z$6+L_gHcvp+eF(sL*jZ$pE4o$PLzT`!;7l3nS#PS&+-$2`ID%?)P9L9@!g9%jPOUL z6$HO;9Yn58%Gl>9QZQjC7j7T7g`=5ArJhzKLY!Nm*IFZK3B#j>zBm1n$Be zS@~S~R6c&a#_5Zv#DYkM7^Qq#em{K<^7iiJb=J21w=xc{UwQb1O$^Y9w4k&hj+Ms# zeI@?Yr+?-8CE8IP&+q;Jsu-W?K6XKzF(g;zoJopmPzVd2V&ryT)RwoohEJx_ZK~Pv zhDlq6)2-9evU80u7ax!kwFsDoReWp|r-F{~0@|W=L_USkWA3a2eb{vSrfq=xW=gm9 zY$THJW<<^YOFP70z?-aB!~)DW=X|%f7+tFs}PvX!NsfS!zJF{yHz?1%fRb13rsE<`Wfwkp5f0 zRJqnyv?>RgRYOQy{+;CIge}^v1F4->IEpH-&?v}Od4SrLM#YueW<_~CrdbdQ@e8?M zZdq5@cAG`Kn!kIS?X$X$K7!&zVSB1#mo$jiDk?$h)t}kKjGk@dpHFOS^)oIuPxPPW zC4qf~`gN>|1GbMW-GEg2j8jj}Y`!*xPn3;R4J$_PE+D$Z#6c!z-ejc#XEyKXoo5Z>+q@vig=og!G~&x~ZK z7=2!a-9z00+0=r9gs9(UqGaJi&IJ9cR6%m&*rY1U)ktfzEkS+Ms&)U;m_X$% z{^2=$Wm~2n?Lbvg&DRXOt7IV*%d2 z>R{dya_QWoBmDcfU*(L&B)fqp9N8(L;v!d)_fo<9ZdV#W_-XIk{irjHQgGw6b&qa( zK098>{5_TjHG+LxLNH0$Y-GweaL=Nm5^N)cgL9SDqBoo8(ql;}D& z=>^#x1N1YE$drYYG@ka{{)UsE%i)|-ogaFCvsO3Yy8J_@s)EhJH9%V@S$Pxi;4q!8 zkLmzh73WvY+!o84@zs~>SGXXb)F7W1?Fp$LF6(atqAc0+crgw%=wRi(r z6^B35Gfy(u2SutyyELOPompav$oqNDxmPyLtQ zkF3*$XMekn3~J;A#H&-MK}R4f=WfE{lygexgvz9BJV(cvDo9%>$Oa=JqP)`e^Kf%= z8g=}x6_c?J@uKXAVa9N2Y||1>=nGckgFhcNTD-=u>?@v-V&GE4f(ebxzJmcj@cZ;Q z%9-~GuYCVud!b8psxU|FEP+-Ch_R_3r*-A9#Mh(3M2qa6w%S5YXDRZD0q&KJnlbo|*&pdouIeI#B8VQk5XYf`?U}iTV}tcNdSH_@cc!Y;XqHyDyH~t6QQt47QJTKI;s$yk69xr5$k0PD{st^8v#^=a|tB=HJ_645_&f?`tVTl zn1#glc*w{H#Rk#=W1>8^)Hyc`uKlxOqQ6W#4hxW}NySeX-TP?WexdM+U5HhgbD&;{ zUk%V?O5%b7?OLjcBP_be^Ao7A7n*WHfR4M^yCdjHR+RG_nZqrz{k8;vaIMyyR$u)U zmP!scZh5|2;Mm}K7(7!#M_D!v+cz6GAKk=K;u3&FZs_t43QOnnj#l!1=jKN2ivmjy znFb8s{GJNj?b5d_s-GWHsHI3?j#~l3!~IPhnX|+M<4A=J8Ucpdy6VHd$86k0OvHR! zi0+PnKl_Y22J8fwNP4isqdT*R>jKI7juTfUeIbIVi!n_&?$pH94z{S+q8syY+QNSE zHl-%UA{k3>Nsr(#XMoIM1oRBApbp9*Xa9pnE zKWk)8=}U1C@VZwKn==P=zw z=U+F`(mc0d+LUK-5qyUA1dkbT9{p0KpQ7C`ixjUFRRp=&d7Bz)s!q#v074ZZuY z`b<OnkdrPf3(qXTQa5IfnRZ8g{#kRNI$ZExmivV1!7hq*>6X#$9BO}4{N0E~RmY{> z<}^oHTj*}#<5!6P;KZxj1j)+4=HV-6ZElR%Y(XF^Cgjb@f_lKk;WBcLZSCcL4$0`_WRXez%lO z{F+ie6q_QYNNr@5P->|*S$WcIZ9feEjwCGk0Vtp&XV+6BQ$9G7g9s0-hd3}j+ZozR zx~8kb5xmTF0)*TLS2g8bI5r-@VD3%@hshT=lsQPEhk^i;8i+%{`-NrUU$FMr9fP+? z$*6;zea)fV6~;Q4o+ZSKaXS%vlsX!=QGKxYB%*DZd5g0ykz@=;6%!-Bbs-C+3)J(n z`To85+VI7Dw5y1=c4yM7z;VLGVp&7|?S_6#T!AE)gC~FPt@MILSn3>>F7Pqu=@Lyl z>a}nqUz)Vl>Yng`^PM&RriCVX?C3U4J|s)UU)h>bur>&pfmi!#5%RGEeoYUG3k$Pl zWNzfy4y!B}&(tygiHSM5y~hENms9;zz-h((IGP>I*RjsaszyJ1h!@nT}I zubl$#VWwy|QW2?K%W7O;xA}Z5DG_yGss#z?5NhiTQj~R=!d@1$>Zv&(s1s=S$viiy z`IuoXAOm{qdbc1C^LA^ac7+Lu#yQstVKn-2nZss(Z|wS;F7tW8orlK{KRly<&=$nd z=8ECU9535oSokU{}xDcYG_D*lzEc+%wvd|+VFTgDf(X#);7d$F!G zglya{Nx1ze+xd2I-s}Ci`mkooxMQBGq%pm(Cgc`;8L*orgi+bD&8H-#V8oV;w-N{| zIb~!{7izU3JVEYSgQA*=E96dz{=w91biEv3sD-WOj$ed~v;(y9S+f6hM*8-{H0p)r z%7rq#y*DhxfA4n@?ya^EY)1_?rJZ?eSvDr2(H+$j7A94+RyF@o;ckn5ZI$89678#J z46AF;;7&OG<5;3mx4*5$K*L3ZVb-QR2g?>-OsVksKLcK(aRe$dTdQ&Hz-+=Dx(YoF zn*pW{PK}RgXiO_}x7iMg(ukAatRxC#fQ>9I`fFLm{C%V}fA>~VT8?zzQX9Ka3wPKl z`Dc|0OzJFn9cl>%78rrah}IXURa*GfbWMiXtd`<6rO;h&6Aktg7py94>I@9rJa!wW z!Ns79zPf*GrNk%P8;=QUk!v|Rcn_lP^y=apSHnBvg#nFW zyc;F{Sodb{n`)2Gxt&A3hp8fBlG468B%69)uYAp|eDw%sr(P2QQDg5!F|GQlEQ z^i5&S1==@CD%8X6k43{C_-zny(L%^ZZK^l6t0|FVW*m7iJ_ft*joM%^z&jDThZ){7 zb9?xEZns0v`L`jZZ^@6Yx?Za;5Y&J_d+}}(%cp=ezH3L0EU)sr3Q$2#1VrM-oG}?a zc%+MGL*run{}QhpxP>5+L=6_p;@>VZ2`ADxjjpoOYO@uV4>JlOoFR5T^oM@-=E3vg zT<+F5amTOIZTSKTi~X$@?S&A2TSX2prBZ-jgrDQY;u^MRU;UIxhw4!dNY4%qgh-d^ zaSV8Geonf^K`grBU3_}|%j_-cdc%fQ5R($Zmb+%Q@h;rw|7ZaobCF*Oh#f>8dz8iu zFY}6q6>lGhx`gM4Ows)ChH0guF+E`DpzGa{yMo^9DvWnAQWVLw9`oq}Jxs!|pcLpWSUDT%lC^iO4@v~e^|f>3zW zf2TJ!5(ToOwOeU)KI7mylptQs#9zx+@zeDu7VMQ%rTaN<0G>5I-7#?_eG&!p zP#pY&$&HaDEA$jn)GO$+9bIEpMKA}+$%45#H-vsv)tQa#U?1}7Z%+i5<$pVGw_Ckx za}jNQwHQy;yl7-EC&3b{Cfuv9`w2OJ4$s_2A0Pb7_6ik!1eej5(6=sz^(k7Sx@#!t z*^0C~Qrk5`1w~2r!d`qZEaV+`eVO7hBNN~|flUybaVfgME2*eN2)L8K z8`CRLb^lgVnD8zBm%~sVf_Lp*0kJUuSTgR~UXvV6Z6J+VQ~~Q(Nz=_pTOAiSl|a(? zm=?ciN@S{yigT@-d(6hs=OVOxv zasCSJZO2b+A+ya?OM$e767lUyx>^HB1mCsszw}$Oxe#rPyiI6)^yp_Sg&M=YG(I%e zd96J%C+F?nNf0LAc-FC2Ix_+CG3uz>J-VtCHLRElS4wznLYcgz4nsNl6ix;Hx74@XN`Q}HqeCJ z46>2I7~xVT%ykX~&%fjxP=#k`Fqu=O-`N~Jd{oG>9=Hr-=n;Q9g`o@v8x z%#6DA3`{D-Cq6H+dg7?UbpsDa3lEi~JYaF)M^;^iC^MWE4WILWf6r{D<#Gw`t%f_P zb;b>QZxH_Ei|BP#QMql%KffmTzit+@SiC?UXaEb=*G$aus~(g_A%B%;*D6*?IYae} z65^&!X;L!0D5~SWpe)F5Nr@u;-AFy5p>fnG)@v1Y`;zs%5?r(Sy^eqRC1M3W!mJA` z&lKV?s!3~U;)-c5PV}~~67uJVPYSQo4n7%uQSt!%oWMrDK7R_@Y)*pHC64T0H;%IN z_797UBD~=(|GI2A#KIwHTXf!R=BVdZ9p$qBUky5Xi=5zd{+syUpZ^ElH}0Pfm%uI) zung$kj&{5lC2gGAt{(c_`$P{c)TT1$TE1x(kx2dv=Bs#MX~+c zMHBebV<6bHwfm(}Yz(&UZ2({;w%J&0KWW(yEcw4-K}`Rd0PFvZ6r{JSQvbUrDVZDi z%IE*w!-}*0`NHV`zWM)t^nbMY|Cda4eL0v?Hj6VN6BD)N*+tyVV4Oj9NlA-{Su4L+ zl$3l82*??mNR>dmgVwS5}n0YXVRj^j2<$y=xDO8?5|@DJdz>c)p2Fe%uPd z?>ELAywE8AODI^QU3ybT-!Pptc;NtFR&EA-$b0VMZV+* zUNMJDnuS<2^$T_iR2W)^ZR_y zO8I$8&b25;+`VU*KGUN-w(o2YhBd-z4X@IGy*#ue$H6>mbr}QV??Q~>LY3}dQN<^I z6Ns@-p4@qrr;k$nCT^ZQ?}%Z9hm>9MoQk#jN9EXM`4jO~OVF}cJ0L>kOgySy^9EqQ zCn9FBU|31E5Dw;SxukfjUR|EC---McU*Q3lt>R~dA(UFTsW`RwjJJS5`TP|ArdG*% zqhZgZ7x&Y|gDVrdKBKN*Nod55epof#CrhUjW>Kg27m-Tid{?E$IIO}<_utuI?1mJ+ zvr9%GrU#!L!$%*F1k{<_U2ZbZ5WEHk{k=SoEc;w*&fH;Rr|c<`T+Gy}ra#%Nsi**p&3xiCWsl!`M5lz&*gBQjUS8ml!Q<6*bB&Uiog&y@kZf7PO76nCCe3F%x z^XyJ39DY7#FPv|1Vqw+!|3Qon3j?uaK$^b&wVYN^Ht$}{5EYB_wav}@K*{Ng8dM1) zZx{G>Z)KHRJXKX3~(NP1vxNcTfFK;aV)mDc#0eHX{@dxu{FYULwN4f-5y7Erha!!2ZNw-q3NX?A4X_e>cclE&vEO6 zheK3S;?GNKF)cO<-p5=r$=KLp(HN1V?y|BU7vc14G9czuXzS@iH>mKNglYeFaqcPg zN51G4ZxceK9}Viiy|m2;k-8UO3^jeb4#wB@JkIOaN! zf(HRNUY74P!1&bERTDGM@1?$r7|3sKoU%#p^I_RhusT5domW5}omgBPcE_IY7PN+O6zblqY3s1a0pGT{k)zxRcd36{0)}%ekpZtu0kHE(F5X7`u-YGL^<} zEAFpj>M$0Kj05gvD?{X($XZ>W_-Cwx+&ORTO?qmYU-dL=nKfxcV&OY7B=-`&BVi}- z0>U%+HGIJhKiAzscKgOBuA9Nc#4$>4nF{f}RF>D7&OH^jbYov+c4uoMN8_o{F_YA8 z^vpcor7K~9o8w#U8SY28v4m#DE^^)v!|ea~l>44F6>%AMLh^s!8Vcc!@L>VqH@EEM zFhWjC@@aS(8x-6(w_XJD0Z*KxN3V=pI3c8BUOU~qz`-wW6nREE? zy*}}*8TT{!%Pk;gZ%+rg6zlJ~PYgtx%627Z5=g25MAo>U7@zYIEas7v!97Xsy zBYhe9JFJ+-mdMd{rFQ%K$zuwEPpQXEX{S$r@a}E}Q?I<=ITvM9E=gY2r%*!r8IPEf>elrrcy9cj; zuuB|ruRbyeVOFX%`MBUVV&3K(V0G3od|HaY*bk|><)4$>SjzyN9PDSECJD<=G?Mp| zFUwAxMmy*a{;?wdI{u(T{`)HDJ=sW-QMLa;o@VFOjH(eRr>!B} z0cDI6pul{~oP)5UrgNC(p^3Pq@2~Mlui(3*bl=e}2Zh5kLrU}HX|)x#O|#)m$?Y{1 z>E8!Qrs@1mzZIOZdqO+^7<2vV>Rr>)i}Cy8=XkG-acIwrU5acopY&^gY~ZdW?}`_T z1!J_lfPKHm^L6F{%>q+2nCYOBH0bO;8TGSe;f(y&^XE!BGRfS&}U$ z$18r>juLo~@8b{zf#&JYRp%g%ppsRJ@Zf$1;wP;$d9E4j$}dsjO@h4}U)I|$>nTR& zL9Rw7b@6V(fU1Xl$37j|0G|pqtnl`huJc7I|(Yvns=B}Y%^;I zXzJ(EZtIF%9F!&9r%ojl_|2FMbEB;lObL=k6k`}&T5`Kx`>JcrO^dN3koO#O82r3! zB$>s;hNebpQcHk`;1J}l zhL?i)X~xf%2=!2`+I-CbE=>vpZXY^=?CdDqv4DA&?TojRWv>lUg?+jQMt2ZrufBV0 zID6h9e6X9j96cNMIr1;=sxm-$fk_^lLDf@yVyz)5xk;P*Y!`0w&Ww+9`WQRfNNy&U z^LGyK^oIeoB{n->FOWIXO&iLY9QokY(r6SjQF*>s+Bta-G9t=B?U`NNZr@Xwm`ID| z!)ZBLbK`eGYpAP{3_UXG;ZO?O*WK%I=WL5xYg%eo8dEz^&>(G^bqX+wX*daz=hIorcDUeauq)PcNlpy&2;Tlj!&US5rJkZ;bO4Ybwh zn8Nx|Dae^TYs(f|OXWckHc?j^6hUJSFxK0r@n;q@3*zNA%mcRWwF@i@Fjt#XocnM6 zu566D$Ropv0c#d-5x+3$5g3u$_kiIB5Wa`oaF@UEx#6~4O<5cs^bQ8y0j}JUpYM!h zW)X#lDX@&F3!$_eP~CgHegaOJvuVx!_>Ia33EqfRFCYCz3-_%7YVt_D$(ahrlr@?K-P# z``#o^Q)Ulju*w)AbO~cmblgR;1ny#N9w|vAE^D~F{0_HS>pW*09e@G~ z9+t`TOFt^_Z5na!`p1mxT^j6$v4v++@2ry9zh=Ch(Dyz3Z6<+u)uV4KpsQ%}(xbXM zUPnuDihpV)sq6H zc+Ug%yoN|8gYSb4)k{mT`n4t2cp`eD^O_cJL%MpG#M-=~+u3H`PdQv44;o~}m2+%- z`DFKU3&v(lNte;Z8riDH{e(Mt;icF*awnIjK!T)IR;8Vmu2P?V`|BQ)9+45HnLUVo z@w`|4(zpGN=978-huU=3-MtS#)(XHC(EZ~eUn7GVuidfY4dRR6ex(FLd5;SOa2_V+VPtfxa-iGJP)$Er2D>OMApcPM`cDHfwR7E){G@O1cdqxy>=N0DF@$ndR zr_DA>n=JEJlSrU@9VS!~?@CGNN+SYNW@Jt)H3F|^xgqvQ5KifCItc++(!iBK$MfdK zksMFvtAoz^=$^0ptD2UKXA;o9or@(Ea6_<$KZh_YKX)ZZ2wQfXJSH2vnLnnxuwXbP z=-|#IZL)_on0g(;R30q4F1}8tyk;3X%1#Ua{foPCIow;~+nGK3BgG%uN=Dg@Ddk|Bl0GopzHyOYP|ZaSB`~5ScC?SXG72R=(Yt;bVEWdzVgY3 z4g{XBS~U49g43RXlQLMT00@77HL%GC82gQ%V;CuK!G_R0U{50YaB+w7BpKWetMKi(m8cjNYmSZT3-zKVaESBZcFJ{#nuUBm0u1 z@?iJ%qc$N}iX{#vBnvsDy>a~>q8RY1;m85lgaJOiZ2FqR)L#mXRjDaS=p1{!M8&lb z8l=H;OkH1s`gGf>Swg2@9zfN+F~m&)Q>}8kSiXWzk6omvRYwQB0@&w1xWpghpa{Zv z)YR9qy;f>H*JrGZ@X*<`;}?xm0Lx?4OLRDu&^a*^MV9cY%gLe)`ekx2!|BP<+7cH- zj2@du-4`n%(t^W=rWmOH*Z9<76r^;2*mNTvGUT+Jqu)I!26c`pnKjtw8)(bGZvEQr zi%(p~+u@AhF9|^_HCGl2&ql$fkg{E@Pi;-}_mKuMZKM{roq7o>C9S3XbbgkaL;n?? zHa^$n7@^1r*B{@%*koFr3Xzt~)pU-J`9kIa*{wUPR_|8YWhmu;F`oG&*(S3>L73{OOXn z$4I5C7{PU)TmgGdt!?~H2P<)Z>`A<3k(l?$R5oE?f#{Z)zloH#Je}b1i_bzonTG> zp{D7cjPVe|P8eQHjT-}bN$jdTnNPKJc#E#*7ADc#nVhvdkxC~_mF-Ivc>_Q^0qXOS`CEKbtu{ zvAHu&P;79xRYBNcA<2fn@8!(R=Uz_b5 z?pnr>G-JMb{mQ4ws45FS14G>M%BP9&w?PNRElbg8+Txd}JSTQ6(LL6FtlA%zWS6e! zmv=g5njSyHIdSG0X@dJaQ8Nb_>>!GFZ(b(@z>nz3a7;0!-}Hvhi_4KHB)(b9*_i=mF#@$`K0xb885HFNA-viW64?$_m^@DAsq5BD3#5 zakdTYNway#_s+HU7&v>Z4bSCq-CwRn(HlD~$>UI$Ul_pKJtu_IgG}L6@C2^V;Dgf^ zRUG8P$~{q$Ox~q=c-t6j$R!fH5R`D%VxR2@-$0_meOrB=iG+9X&$;5ZMuzpGdyj~~ zN?q2(U$7d~ezdmU8C3cNXNBisLHrMXS#*ITb6d@K#~aU={>m*JhmrZu6OtBse_p|@ zU?*85T4~nExS@}%s3~a4w7FGpI-EDCa zJ`ixQa}@C^6r%sta?>J7M#?o^oF!oS&wEfBGdiubpNBk0SRW^q5q3*;!lc6hfLL_|H((LgA?H~kkll=wGd*p|_k+_?C+{AN#6Y;0R zxeI+}o#y*=-KWQrn->AYq|B%-eZgJeuDyoDF=tm3vy3?$xP1RNxc&hUi)v^Son}@k zNsm#;%1zN5-cOx7C?x*IbERghy&wB>c(<>1N|R|#%mhi(FGV`%)}e8(bx1v&?gCK; zG3yCW-AhoZ6wfnElhjSLFOgbb*sS!g$B}Xo9V!%>e>8P23LWQ8T(gm8-cjt<46EWj zLmu$a>!|Q-9xigizdXK9@^p^v^#0&!RlkWMpi)s z_;80SkMk6L4))|Tggk{Sj4``uX|_lHXAO%n|JZ`1ja?Cqt0%p}TIW`b2|P#M<;M_g ztK*W#7C-Qt12yZ;mukhR`!!lCJ6AG+UlvqYx;blb>q{DKi0wA8i-2)n5vSKO1^A(7 z5tU$#iGH7>kCZdndrzHQn0W1}&?g<>H&DA-yMY8j`7hLdQ?K%@Tx&uMFb;AenT0Q6 znQwgnQr7C}T#Br(1SUGUhd}c&94BlFt*<_(82|J%NqF@oFf$rt;*91I!iNOoiw5a9 zZ~kOMCs0Tb8bljTXxUgedcth-9@!aeisWF?s>=TFSJe&uvwQS|Xp(YjcTn-kZ)J}8 z&k=XrAAWPBpbzq*JJf-ajck~?2#YZ%>oJ%4&d6*+)cm+ws#O2@^|aD|g$m%fC2xNI z`;q{?)+YIaQ1@6VGjDU&bg>7+-RV)}LTKBB*iMS-KMdt2R5p0=8h&1KgJ{w$AH!GN zW(dHo@qOPAtkT%|tXJ95BhV0-5b%z+OTnBzfRz}l)i`l#=g+duK>;Q!fpWg6CWsD% zgS=V%$ljZ1ZXa2#%>bF}$AEi`o;nB!mE?afRrKGNI#Nq@P8aU}yNqkaikurB9T?%w z)l$4qcoz*~ULjfTL*O7LvKFWq^&gwapE;slKE8~Zp8>Vm?o*=!wy`g{~OJs|5$FQ z=v}cs=ff3}c)l+*TcnHe{q zz_4&s*78YR;8BHcltS*iX-v}p ziA5*mXFUWrn+H?4sIgJ7!(X@DEkTRznI{Ha^P$4V_xi{?kJm(2xqzpy9FuxhI)Q@S zA74O}*HKw43IC?@^@Z*TD3m7$-`y;n#GG!Inj*t^Le+WKY5tcBfbTuzoVhVRrw)p{ zw!R&Pv=3UIfA}XN6f$sB+hebFHoex|*mAtUYo`i)WyTIxo_mxA=Z3XSmVcLZrRnKNc+*?q3*>XL~-O$H$6jB68e|&)(UUTSVMAJ>#J?WR!^BuFAO0w+`~@7U#{irxwa?sTM*)n+N54P^tY&u` zlEy{Z^|)#~PA8-dR2su9RG?iX(gP1BvDmc!nRu>>mawp>f9QgnI+r32m-Tq&9-Vn= zHsb`>$6+&JFAs_@(YQFB~<9{jwvg5OMm%DHz0veD9 zmd=wslW;0*@I$5|Y;}6^^&0hAl3?JG(EB+Qi zBJzI9PrDJZE;Tqbce1j z&!vT3@85(g5H0juKX!zX^cxLV*YsOE{eLVPEfS9zUjglJFbV#b&3oT;!}A*4haS&C zqguiUD@@)HzED^I-}#5S;PwfGy@nKLWAnDxXoCg;z>VV@LR9=96nunUEB2A}?Z_|4 z{1qj^cNi3A0o&LirrXXoN1AYf7-t(tlvk!it4QoJ>%99M8GU$f-6gL}daMzfdBx+4KSu6UVvDW=p%#?9qXx_trYCr6zjJ$vVAw zPCCql_^2UML0xuTrMhi)UCgP$d-q7veXp!W$~OjsrnotV0ugl;@t)19DS5i^M-W$G zQiH1iDgQRxufsKBV!*ASH%X>wSsuaKJZ`W;{O-t?zgP9H{G{;M$=v+_;gont(q=y_0mkRzt9^ib)L@VDSLZ9R7-0r}$^*&+XTv7amT@}Q@;@ZXjW$-r zmjey?w~=fV5q{eSbOzq-&5mNwk?4xd$aJ`V@+Zx@TI0kY@?LdefiFZaH8zHf&>QM( zQUPW-uEQWbmb&H*u@yIFw$(L+oO7wITU!!_1lp^Azc@t# zNg+wcr42zb0RYQG{`6nxRm56s-Wx8p`9wPWKe)ra+h1$r4|f^xMfM|19v?S?AW$S% zLZo9Bj`2`$6)kQv^uQnJ)WGc5hQXJwn^%&d6Pb3oZpV~%0Af$KU67E%PY_mdUGRaX zszk?Q;r01++D~8LXU%sUQf0S*6ha=D;G1Kj(-@)yXhOsg zcO#(hA@Jgq9$i@rqe&EM7c|0?KzM`H?@^vTDYkWt>(OJgSe}{#+lJ|CkX!UL7w)ow zIi))i+d0TE3}CF5m$^v4=(+{ANtQgI&hKkE!I1udX@N>bMzM2uF^~~oaor6Je6ph& zZ~m~Bdgv-8Nh|j69Nwc*Q6v-e528<4c(L}}b6LB9?qicPGd~+#l^ZG~w0#EsTp6^C ztif>LQh5;d`P&YN5>F%U_-uf2en=D*P%3v*?;QTwn% zjiz@r5dQW!m^YSQ`cJ2#%z0Q(jDoYH|LB6OgeHw=Pyd@H;+zeWs9t2t0qSRRL; z(&fqAK)_+7M5X8Ds5@iZux3(bCKVgVEeDtFeH2>MXaU$4w!<_v7%787x`Lm z8@&*PH`dB=-uh04#EzNa*J22HOyh1(vjYi*2YeR0-Dy1ZHHKo7owD|kqN(pu>4&3u z@2i(WpHjSp)4Z?`gxli~;P6uN?^9EXHg8%iLThYpt(*L1)Ib8gu$rFmX2Q-ofMnN% zYQ3~0m}lqOZzqZRtTxufodR#92IIlMoLScVN9?MQ_T#q?Re-1#;ZN%G%GXEyGJ+eG zqQ-&d#&1>%h<}-*#VPS(!2{!ihC{>N8y<(wYjb$A`xGee9*3wCUyIIvvh@9&YXn&H zUMH0${qU%jd^QpNS_`oUL~&Ian(tSRIMdmCMzXqa2alB#Pm6<8v2TH8%{baHPtF>u$y($37)VWiI z1+Fr4i!8Fj=598Uo_MUzIz3g>v!mN9qAjn1MD)C+$}yjGbZmdrh?PKSK zo^DSK$MnvbLH!oc5;yB!#sq1w7X&0JBju6NS0i{CoTu~4&|;>%F3QxxS}>OJJuU44 ztIHgbc-diAo*p7dWCIfqfBmgRhEDtaQszh@JtCX%?YqR%Y z%G+X^clE#vPxx4^B^Mr;r}x%YtM*48t7`a@Y?6MwRP`0WVr~sYokB&$WIb1_?^d3p zr3kD{SQ}_D8WLzezJUv3)67s8Yn%mqOo%2tOsHxFTLYTXWsrmvKhfvYSEUhu0!&LE z(mbtZz8o=Q+p>S~nZC_m-p{V^-LM4Hbs2}hvx`=3v9rN4fPN`*S(LvXB3uh)><+-( z!jwDbG8NR4`qZe&bFt%;6&n?v*9&&9-3$uS#u6|GoSD#5d;v=^`K61<2W=$7H z1lt7%j3OZVCJo%WD-fIm748l;;s;}F+zUjx8@FjQM3oGiJupg*)!|N0CJ~At)R0GM zU?#dVT<nn@gxCiY*M0{qOPIr^BqxAjGkn^85oI7l}Z^~aqe+mPPVuZlo0?) z$na3uj(nNoMQnWZ)4_hJ)TOa?o8}_ng+G)Rhs5ZozCl~HH7!x|j@ZtiMzcf*eyRW;6*%FpE&M|@=?PRFH<4?T!N zLwt(sLw_iyzvhn5+ih=FDNNRMDuRM8rM+CieZCvoH|<$KWh%v#_nsqnGEYSGtdRCmj$H~o*umu zg7iRg{QAPQ-MQO`o1E+*6mM6MS^nf+aS)Vw>%C=(Dc*V(Apb(Zi!QKbAX_9p%d6G) zU{q3J{xxUr1S=CWJ?4vLPlA+|qV<8fin|i!*l_V>TSz6|J@RSCnp^Lr*W}v?!M$XaVEG&8`pRG7afauN1%c1Fc^{6*=sp3 z)n<;^9)a}d$S`1Layjf zH+I9P>kP>&5sa^BesDY3TI|VBeNRFou{A}^%2X(2vt7U2n4RH{J`FT6ZDwLR8L_8c zhL|m^XNCJD0^vx@z+TWYxf&7eryM!@r!gNeYEVb_s(3?3?Aoc1G+D*n$MoS~JnoqD zWk#0E_~o?sae;0NRb=p!O8E~f3u)Mh5vtvR0AIkf-3~otlQ0JrnWfhv4Yim+=AzYj zD_i%C&h6kkyyKA=^U8;n7q}_3QUVFT3^4RrL%X<ICR-}dm|Lt0h zH+AVV8+9)G#)Zb*TGx;cI-OYweY(gjdoedxaem~WP-?b@Pp^gxcZOLqsOuZzru|(7 zV>}b~kFqh}XHZ(A4qqJReqGvYYuH4paod#}{}F>_bo^d;n0Bu+^eq2P6Ws?-M#OV@ zmzCrW!?~!;Ox$p9D#@$PFuHh;JioInAgvs#*jg9aY*N*P~7Y zGry9g1Q;K8sF|_BkZfF*c?(PXvp}5Nj?-;;+|yDJ6jAl#nu57b{M(|Gwm0#J_tJ*5 z_4(@Q$DTgc+6ZX4LVuqZWr<8!z@*svIqsgvBecz<;4Y#l13FpiocJ$#u7799A*9V(*9nM32|{>y zYE?xz8(|e!Hl#%Y*X${cI76>zLTp-UQXQ2iu^0^_fIn|99^NeD>xNwm(I1S{(N2 zUm9&)K2bdodN{ntGt zr0$RWPV72}fKtuJ=5Sl$n=U$X#6`#t!=D+$!GIx z_FP|f=x(IZt55(e$UQnLliTUJi4?4hG`84F48=EZaT{Fc8+MOVEzIK!1$t882b=xM z*XW+4@tW_e&sCQaF|XD;(4^vhD{uEBYXpgRxQMaT@GOgEFSRV>H7tnXo?J#ydMWWu zvGqFWBw>up-LNaIZO==h0P{|KWS9J8!p8tB?xo&WO*pV-7h>ARyD*#qzS`kWKj-*6 z4f^EtA|%kX!qio;PmpwzIdMR+jHFxT1j02m@X8wrn)U^TT<%^`$`%rcV&N#|(qj;% zThV6L=j^x%t6p-Y^Ike97;N59V#a^4)|Ql{{V*YRZ$i9MAHh+`qux{_{RAU1`&;Um zLh;myp$CgLSogH@A!qLJ|w9UX;pr(>_pXPd6&COR=aVjk{$c}Siev$p$qAc^gwP-mq{3SUs59IdWYvv%QNVB#SSjJKP zCFA_;VjPK8CYN+&K`X`J|a3T%^XcIT4$TY7U1Z1qRW=NigG>93-`DDW+MB&J852q z;#~4;w>RAa)GU1lIE9m%dTw5`kj2-vxgjSsjLny?EF>ER0$ay(17E@j`|VzA|@6Xlr&r{c>^M&1Ub;cx4N5op57wfjj8oT%ICErJ*VA zisSYwFJ9K~a2SQDL7w;P8|)AF?S#-V4>}=8_-I9S$m-XfUB)4%HpTcDW%X=`+*5Ag ziO^EQlgoY}v3Ozpq_g9Dj&2gZOVzL2vFhqzIM=;GgdY_*d3KIoVx(LYq6zA>p{>Gs z#a2DZZYvt=D2&nQHUnXbGRzB4J~k2|W3o&x_u#uPhO6hX2z7xj%j~5(A&&_5dPT|j zX?i2@u!ZJHxvM;)NC_f}@QlKtO3?61r_G}jdf|ZmCqMu1zk#37Q77UX_|)sl0*BN7 za*Hl4NS#T#E$Vy2cHcRSJHRvcl-8Z$fp1rMjQF_iWb|(0jnIHlzHU|O{1S(tvd4sf zW5VpQ9;3GA1ZW)z@(C!gmQ*0yq9(O9{bno{hZ+O!g=8o8dt#}f(&=gnw;eR;sk;Uo z=7`Dx7i@fJq}OeNHmOBrPMqJa3F*n0Y+&dC_NiU}Wb7^o%{IF6c&51ZABp@fK0goU z*r_jwF;xDYZ>%kQbW9lDeh~fW#`UPkA!q!@dZTuz<6MrsFt3<2A$y1z>RGIoEQ87 zi@Yw;Tm_fM?e@slE7R^R&U_k5eY>xOXan*MdfcD+Mg4JC6}d?N)nqeP_PNU=h}Ws; z_u&{JezUCd>;-2q5%h)D+@VTfrH%d?aMw7g_xGHm%0=p zp8dF{CA4yi!h&Oc-8(m`IAwf=rBGBHdbW<504|}0BaNe&i7RoQA51^3b#feGWf<$o zI37zDFG1@`KbX&$iDBDDn#y-P+G+FoKE-kSb*cs0tT_&bBBz064n_rO8=Vj)nj0&0 zyc}}jEqEre>>5x&X+c>&FMs8FHr?JE8(4xrl7&>D{X?~y@uLrgMibfA99}|3-|G^X zonqIGF7~fAUkXDut@6rAnIRn(6=}Wd=tP+JI@Iw)<+RLP0i&HaMV5s;>S>J~O0nVF zygYM61-eH9^G*mG-Oa5PXyCkruW?1`vShtdc&+a29WPs!ahHujQm!Qs(K1Jr5#mI> zRz!8H^-Yz^U`n8Q_-5!_y#*lMAz>(4tyOvvzy}$BYnKK*X~Ctsg>7j!LWX%RJ252x zDAcGm6r;t~L`57GUHr9sA7DbDsh--5z@P7PiJ({g{T-O&v$GV@qoSweM8H0*X6#xL zuelEXOFDPn%R!7@WMLC059E3^$n@ua^!oY|o5@M_u#L$Q;_ILG5wT2^uLyJVp`DRo z2C+>**!a{G54@rxpINv3Yk4{6i(!a}yuSXzA4jDTqh5lmmfCflkd)YQLok2aQ~i#n z95%%{a3>=jbSOL6ax>zxvy|MoqBeOAEvaYI6p3S$(du!S9~q(rMo9jvw0Qx)vvgI5Q+*jt>n;6EDYD zS@;CpjO5yyT|qj$Hs4h+<1;uK4kQ8!2^ib)y0ju4SP4;qK6Q8t{ zdommx`Lz{Vfe@JQh<2GVc|WGc;Lh72`@cJCgYy)Y!=X=PkzL{~w&JwfHr&pfb-7&d z>D_>gZTfb3)%`MVK(eX>`O{f7k3)Ovdk`uOAiUghPGLm#8PoakoVZX&LnweFpG!ey z9n{t8G1ykQz!A9E#a(w!(97XK!|Cqf*e;o)nziLc>T7yKx_yW^S+e(F6 zk6)y*7@s~)36xs2+ELk8WD!2sM|E%b7X)9&OYa-!Q(dbC6<3nMI02e$U2gzh<^*5y z;5(83pCDrG@v+n6P39BPXZfUVW19=RoTcw+m$j|Gd)hcI{d?#Ry?04QkUmQQhIb<>_^A1Ps(bY;Hs4ZX=I?&>V0n5I0k;tP( zfxmMO0b?5U7eGE_@UYD3jl~jsRNKPGsz!l=&mt|MQ`}`&hM&2N&5RVx@p(xZbNS9; zaJGFOo7LI>!m;Q`o6OUoH<+7);nN%NO(>;;QU%$2Deebxt7k78(CD+B?PzY=H|%)Q4U^zv2XQP;6a0}=+eb62xm_v9lHJ9dG`5_PJL*~PQR(qALZ&H0PzQJ zc$Uq7g3WG){}BVk3hZvW?9r!a1g8QZEV|AQ<3%e@ZQVM!0=rq`<{Dx!+xirnS8iLpmVA-6gvEWfmD;S%7H+ z98*5KVdRDGLGItf(eDesZ|Uv6Ik49Z3(KO1SeS5a@JIdnzY9|T^zYnaBjIcEpyKV< z8Q`CrQEWS7y3bIE=J6+VhzHC~qK#r2ykaH##=H6}u4TpfBY-xEJ@mogy2f-gHtwm$ z^c&Avk<;HfH1`ommlt#3+_|Ocm}W)k=Rz7V&Wl4-ra$(@InXZ0N~Kdl_-~Ghmb|`u zPQv;(oEYrH;F$z9uW{Z+mTvzXy`u5nS00oDwJ$=*hw*f8yhFcSqzhPBjnG<`Z8J>{ z88ojiaU%n3%(u^`&T?gk2Tcj_OW}s{d2YDrc4;!4?a-wB{c(+V&9$Crte%c*E*|cn z>`#aKgkO%FD&HK?!>tot-JW58h5~ZWSKn@H<4#bEsQm(?$VNg0_cIxD4yuMGn@RFE z)MxKq(#Ly<^H)?}{g!RSp>1qP0L2&wJwb_myrw?dr{NxzOsduJq40jPmOFX+9cVps zHFocTu6RU7tuD(L%bK&_WvIa>i{)DzbWE@=+z@qt?Hr2IvLri?v{y+6&GwuGsHS4> zab+Cp=*sjliN&)??Fwh)<{|f2ADiuDLpY4RZhe?MN4Uo!uY|sNCF1y%#S{eJ?3gPj zjWr5KxjT!LjVx(EZ9i0Azb&cY6Wgp~9|~0qe$wVU6aG)GK(B(@znqiT9o!rWIH>q& zIK3AMcMsOMPx`OmNhs;`3|TvX2WaxZfXT68GX9rzfl;jGR&K@8%>*}86Bh2|z7*Oz zkUB|J`>#T8oi?6@pY#jLxd)i(PQci@rwe7=r~Jr@Owvw+n+H=x`>1=+Cg<`Nd3-pv z%3B!{6w#TkYCb@#@hgjXZs)hysRTKD`G%E6_P+;?pAb87dJ<5zr%vmfslM2m8H^rXTaS8v{I(HFuxo%ajg_}8+;|(ILtj(B=&2IrLt+W z56tc&*uP!1V6!wMIn^uhUkan={Z~|d8!-J=qB4?ki*qm9mjS*lbH*}o4+%;&rS$^}`7-{b4n^ImNcbRtD$vt->=E_S4a$ctri=A^-H4@%+ z(mMCtgp7s{lX^ceb6#%W@9Vjud7U{Yz1RABM^mM&G3HuzmcKlyvFLlMh~jr< zLOVBe@SmXaVk>N-li3%C*VSM18NWicK^cJ4RUm6biG|KVx^DpEG3JCT>9Z^LJdFQk z0d9sgK%4Kb;Yrx&ADx}qj*gDBXU$1-QRJ}F z54Vg&Z!Dx!E~^Zil;31-=kdc$%{{8aVC)D}wu$_R@9??s&hG4Ex=iK{ImxYfRp}e1 z@4H!ynTa9dFUZ;H1?368yNpmGT zD^8AP?{5*U;2B@aGWn#U?x@;tmsOIAEMI%7=m}c`X99-w>+bHo0VY>A+gv7uA6l(8 z9lQlm5q6WKw-K5JW-Rh!X9@I2`H*{OlRC6MRIf%VIo*C4Zoh(nS5{0Oa}JyJAZZ{iYM z7H(D+et#&AY+y6aF%BIlBt!dqOY$Aj&NSq1)x%p_5j>KYGSB8#)`Sv3PkpxA^@`%oNpHLvH|FAX5 zBhir)Nxf-M?-LpIr77RlrPogqIi@#_V@fVJ+;+wk&SlAqq5gIUaCCLg617#$<^TEt6vrvF z!Mnt{$}`pZg_i@;El%fFvJCd6X6_i^jG6inbXF+9%3?G))uJ2eHp9tINH4h*T0N4N z)(0-Z6v_S!dHP_>O`l9aOs_2;V%>~MAcl;VE5&?$)nriR|3%G2ig#c=()br9+9>#v zF=q$Rb=IJS4}#RiNw}Zak9N0VAU`TvwZ@ox@||wX?KwLax5gb%yE+BUXd-)=M-+2t z+CgjHJq&SQsc*N61r?*3FD%La>IvM?o927?`6HRtx7zyre+K<9hyc%u6ykGy`2f0ulRZ_pM_4@Wo}L$_ftgD%05|jb7E_^(CzLcc5>( zwvK-cws&7*G#b{Ls#=L1?a^`({^ixep0%Yd&ko;I5f+i(iTv=(`bBm^>jv@IL)n^R zc?S1UWW4G*gV7`>&U`R=2#h~yOm-=OG0sp`?F(WhH%kM_ST*8_!N3l3(n48|Stl~I z&Bk{A>Z@&wi|_jTdyR+An5Msx*LPpo?0zrX{XF%-XEl}}f%nOHZaE=7C@3pN1@ASF zpUYlq!!hUS^qmtGc5nQI3`Bb8$alZup+EgF-%!&JT zhUk9fgz_({+)o3Rw#L!cpmwk9-Hs=EB!uo9D>*GtB$H(%hf!l#)yiinc<{CCY=z`8 z1yJ&oX;6i0wYDO*XU&@T>$-)2L}}N|OYNMEqg|8ANqSLR`G5&ayrFO|SzXorXYnP@ zvN65+74{#&PbLr2qzlBh{`27v;Z}OlAH-uFsO<-x%~yyi8wFd!AM&kIjU3*eG|_TX zea0K%8aixhDIGz7dC!LA;uyBNvNF6}Fm_ZeI;Oyd{$uYhs0wTwsnTs_8~By39z z8{x8Pf zGAOQS+ZKl40fM`9f?IIc1b26L*We!9A-H?c1a}Ya?(XjH@HWXg@7}NK{rI|yqM>)M zy>#w1=a_4Z`WU`ns~MHFLZjrq4Bp=oU{<^WY%-pZ#7j*PD9*&@^+zndf_+3Fuv^Vw z1mLjIWzhq@9`-xU)*N|2vO2oojq*`XW#Xd#fY#I(a%Sc zsMb%2+Hc$E?qx4whwl_*MIS)t$%yC)oi%JP}d7=iHzhOLxOl_v&IK*wS>9B zWtC*U7+NsU`1z;VMG}1pQgm8QY(Ec1QY)5Tsj~byCvIVR1N+$vkj1>oYBm4{l~w32k5#yH+{QjVwU9_?H~ zx8hrtzJ5@eOGu*sTv0L5fbyC_kzTnqT(U{PmyhAtMXnLMLl*y3gqNBddFS}s6K&P3 z^GbA3%09hiet{`lGVXwsmLD|aEZ|@7DEb~3SYUO`1Oz;@K{wqx^$U+s4}ZWKOYN0> zx*PCUAI`kTFZanc)vFR-LQltDOO*DUSN&QIDIYc%(UpYgD53no6^eX};KfzN`2t({ z!Fc$#dD_Y}Bf+H%*5v6LR>H2lUpPFMGqavgNE%9S88`MU=Vm z=AI6aLSq(Ekdj_9K6CM>wM(AlIuWUGI=wy~}8z-b_r$hL&*5egd{l+;xF zeUT_n9NPXp<4|Pun!$GaJ%kGLH!M1S8Kl6`SKsxjQHuL5wD3%$a?O1MvsbV%hdqIU z-mFO&nlVSWwx=|{w4*KYZa2)&FSw-6svlf{G1X_Bsd1VZg)v)*(LMFNoC;1W*B97x&A| zP~wi*eb;vTgQNRxOJQOOT5qb!!WEWq3f^R*os%$y`*UHNWDoF4lgzSG3Rulb*wkly z);a6L6#XV0?BqCyQyOxp7SH&ac%*iEUGVel6`O0GOzc#5yhGv6Iy@P5{DM&dMN32| zZ+*)D?GIo{>+=vxNqNCEr(v*V9UjKV`&W&W`{<_3#~i~OBNtXjXG^v7o+^9T+~_Jc z2IAxbq z{KVl~Ff6?mK%c=BG1ZckvR+HXS0y*+F?B;-FS^xu?lRAGS)|LOH1S?Y--{Qe<}=||SYe_IwQrdb@f5E) zM4pn22+f%SRkBPlT(4J6K<|0zhfT){jnmoK_|s3*uW~R~KN8q)m|JRK7%N}>+%?+c zNPMv1^nFgSS4v`ckjpYjl1#Gp$u6VNBcGT*eYU&U$nV+eL4&ad+RohNg z&0LXbZL-OUhdCK+@REAo%l&*Ak(34_8tDo$H|e>V&OAM=;Iu^BZUWh-Sw==!dNc4g zYj;$S&Tlx%)X7X*k5VwzpA1!hZlP3ndc5fM2!TqiN@>h=j%k3JML^bX6$8@-tf19b za*#iWV#`~lZ`5N{r1g?g$ARbdxR3r$mxK6y9%tMEXC5cb7|uhh;4J0WURjDVbooAt z08SVO0kfN2kLcz*-PM@nIAaUA2*AmeouP2k56p${~!9fsI zhpTp+v~Nw_5gASbS>-=^An}0M6f~5Z&3l;`8b_TcU*ZTH2fx19wgzQfE?4t1h*c(P zrX;9itzb3U9b1#VtW%-};T3XYWjC60SrKn)VCh?y73c4##Rk@)rirH$*|GZ<)Zx5B zgQE8%+alpiW4ALqdkBgI#nRi`sR@Iq&e#9}JCgkfd|FC@tNlZa-n;N@y{51aE zaMD0E2~0CBz+`^LyDF@5fUb4wf4=j+_kL^dIp0e=;xd|IVTZmX9pEcDa`gQb>(AhxyxLp!F(gU%Hx!70iy3cP;7ob6Z4brQ*Z(45&rz45BE& zid~-r0u#K8zTT6;txi3FU=vZxYS?QD+z8Gwx)jSabG{a&PUN^Fk+efldg(K-haVeM zf&B=k{b$bN zg7|SY+V|C^BN=>>r`oWu@VMD6l9$Z*KDQ)O77Cn97WJHzPNEdI2m@UWUJ zc+HTn>kvb7|9N`zC}m8KGV19J!tQ|1W>)1yWE;R;3GdZ-!zB`L^H?6}B9b&9$7aeX z=nQG5g-JxX7-oOA_PciT_l11Jpwujpc8}4jBY-S(zo*o;|>$=T;&~=7k zEoOQV+=|=stbB1eEQ2kD?whDB%ecFs52;;GdycG;=1xs#R#eJePtivhoQQ4n8fYUjf^wM`hfa(2{ueA24#)O#a8~fW;wz=%LoqR*TRN;UCUZkCd zSuau7ZFfi%wnXoO_)&{iy|xwEy@S_M0jEh=v$}j<&P$T*6Q`G(V`3eQsV{ z*J!=J=0jR4cYSTcxtZ~fb%@p{Yd%JZH5|kMX>PBA@o)Y-yxoq?6#9AM{}VJ=fcT3si8F9-q{e;kzSiyW+!6j8hWrrb7up1 zV{n@oirl`X3u>Qq)KGKdL*f}aAba%mZab?7W8uaQ-+Z4BbUeytSvWto_?bPxTC!|T zfH)_W?_nNW5oPqUUQH-)Ou|Qq1PS|FZ0t!nT1GC-jBG)#x2*&fV=UD3yN%TM88kRt zHZx|v{SM<_x|^Gb0I{5yF)OqOYgF0z*W;0t^RF5fi0cH>@-}QyVx)%o#wwjjYh1RB z;#)}pYxcyxr^L1ANAL=hi;`Q%N4B69(am`r+z+itr)eqV7UlR+D5p?k!7b={?h?VW z({mkE@lC!iBemmCUN6Z*i&D&+CZ|jzc5G%t8V7KtKpmymdEz3*Js_K#Lbs0C++mMX zRw6RyIZePRF6G;LxnA;TaQPzWrlMd!AjzLAD)Ccw7xnYXy6MHVCMZpmcPdnu9UOdI zH|dSa%N_80){H4NlWfi$0|tNLICM@4h?hg@p4+EgH(pU*&Lv(;2i%l%9ZGRM<7P%D>QLy3 z>u3$EoCiPfd(HJv>(0P_ib>g+k`P~Exqena!s3x&yIhnka9M=MvrsaTFlk>wt6rNwbD&5TOx(jUe6`2xt=7zK`xde|b zne*6zkG%gJ&Y z)g&QEN>ps@VF?98;dyt|{K0U2yX$XW)5Vn!c$!IX!xw|p7<3E)2C!@$QbE1NQFu4s1 zX|c%ms>=-Bm16(J?NZ#VXmc&!-~laS9}*GD5-BGCE!?7eOl777yxAStEd>@W$Ub9e+LT(S9Z*F?q zyR2K5Ou`Zq>X{dD1OsHRTm}#_s+LPDmW_uy8m%9$AS`25b~(+_A17rsL!Yd8*ffm- zLad&uA7o@%3)*)&YSum2c#07_%byUtp*;v zm!FJk)!G=?c6X2FF`rWX97MLDEyRKjJYrF12Jd8!7|DBpL36f-C^X9E3#%)My8l&yYCH1$EX7f{=Uh`c>PL|cN zyfEnfC?9@sqzYGYCVw?Pu&5gf4PY+35i_yEGSF5K8%_~7_o_}j+sAyT@$T+s5!jG# zYgRizVvN>;-5|=PjLx8HCgk%M%hkhHae@{=RQj_qYuRamv@d zgruY)v(JsR$>-ve@Wf@xx1zQ@lV;n;R}B-EV{ROEGN{FTx4O;xn`EyQOrdm5!?;^H zf7|4_ETh=gE6_PAUtfnuE;IurVZPjyva#w9%`ie{sy(a3;K|2xN0gX0nu~t8OXgAs z`?1+WCV0=3q3}{JCQFHA#Ht0U{70w9@Ob1)k$(>J=PL*m^Z=iZv@5UBZLQH=r%{** z__AFUo6pUqxzzW}j1Zj?O*1~Rk=kJD)H>V!D9nP&E|ENhAlc zLrBkdoo~uDC9GfBJja131ySRGYenJYVf=U}{ezr$IXTO{AvV+u(xN1u5Pw&{Ix{Wn zi%r^`ovlj4<@&(1wB|PDMlZQ4#l0kYTY--%CViu=&G)Woc7?LrBKd}PsTmqey#*k$Fw55H#GA&nr3e-z!@bw!DKpbRy7h9XqZOjLjQoC~TnOppBRr}Na3l#EjtJsbPy15uw}@9xNx?0EYcS-v0+``<|6(~RJo5xGr7noKHIttu&E zRIki)vrlPgdC!GIci)dZeuzR6q=G2KmKCD`&he#@#$NBS(M6ffO2;BX%)S?B$M1XF?^Z3UX&A7nl zbfMAgt#yj?cJm?acNzd!DvG>;-?4gVpGAdP3&_}QWaO^Jcxd!UhE!p*t^t|&%ER&? z70MXssK=C_`!#no&9~(2CSl1DyiyBsIGWDJOPE}(B0LUl)2drMh2!_%;`{~I0+LYv zGI`hMQ3j%7CU_z~uD;5g6g`oL8)1se(NlCXP3vvI?Gc+)MR_>wJ+3>PcJ3PsL*Bp$ zW8p|rBT-<7=Xo5LX?Zjqpd`?0NQ;G_peMfv;&A$IL$~vy-0RsV-K?B4`J$f41>5Aj ztS2WO&zi(F#2csk0*ghZRz$9NP(o#eW+ng41(th%ENg^VhV!6Z0pVBFKz$t;LPJ*+0!J z!E{)pR|`fSGE7bvYnbOhRGyIby5%nOO?nZL)Js-*g zMowFX<+6W*ro^ zRNKEm!(r~)a;Q%Vq*u%+c2Jye9XOO5`!d)CPC<=@XC zMR=MPcW^`@b>r`)7xL;Ro2XI=-zZ~wRodghUOYCv_QLgrm z_=CQXv(;z)sz84(b*E1mlnc*8^#C~D86e0MMSjdU^UuYgyh~lG2SRKu@HIAFX3yh$ zPov3EjiPCyYhSw?$oZc=g@|~BVSExG&$XOl=&X8MMx=$}Gtc1g+G`%_; z7Jo;vPSkHRj*Dn2DnbWmWOV0$s5Qxqy~1;JNq0Jm=f(YCV%Nsp$a4VU9s-Km7_32Y zn~U%aNDm!e49T!V6$jtMUjZY2U7BKdtR`t>=42CfdC4Wta>L zLmDfCyt9jzy~vwQXrniN685Or0@cJe-XzF^OLn1<8&OAZFGL>6eRD*ny<{R4p{tD?eY;rKUqVkp%f zg_SeMg|lg{$*C2Oct_(#mZf$Vze^!vQi6-bAGu1DmJ4tvtl68EBRiur111(12g|&l z4-ZQf*y6H2SJ=*LM$W5-PI!~H?Ih%6AqbC(Ku*PHU!4pDYn~B9ToGUVL9*t(viYQ1 z7BxsE^CA7$dz$tyZH=&2`&w6Ys$kH`&$Pg<5{M^66pY79`YdxD#6kk#YwkbXjco}y z3CWN;oHT3<5Xduf#Zy6-(rEMFWNahQFzX3sw?RUOXW=34k&^B~3-Ep{L)YMUJn}7( zH5_@A?ay|-2=$eh_tjSK_%8R!MDdFpJ+64Yp;}LOQ^^&c1o`hbi3s4{cFz-K_vg>d z9K3Xo4aP(^w`;C5&mf@j{z*)=ju?h@Znoa&M9sO-iAuztL_O`EpHL5RL-^jD@UEwS z>LH8%@1P;DTCdqWS~s+nJzRZ+2HhB}>cd{z%08Jqv3e{-ykx$H`3RCfWWI(^B;qx& zfI<9`MfMWpOj*BTdXJ4BSIMZ_gt-lR0qd_-NR-Fb^c_;-HEs6t{EoDD2cve;tzHuP6WMmQGmzy z#Xs9+YV3y#f0i>}GMdV+zP`#k9J1*Jpv{!#+H`+w<$lFcX}e2{@!>_-vTwknfLyM#58{z7Oi{hki=ZCf=yS<^e_B|ap!OpOAVEwVo3zrBLhUMN3s`3T2LM&)H@W&S0F zj{7Yd0_cf)>G71p$OxP7F}(7XQ(!fo_dyPT3w3kpp_(KQO z9%*3qSySW(2u^WYk^XpUiU$0~oUFa~rYd8vmjb03oWozl;GXlSS|kSVCj(z2ULS&n zJsf9eap)5Uj^08we=D)^f$X0zi=ibqhDd5^Bys=z{OV`_0c+cvvy<)R5aQ%z3n8EG zg@0cKOU>n;8q+k9qW?NOG2z?24Z+pQt@Bm_O@DzG8#eYAk%n&=ES{K`-f6mDM|Tn8 z;wI{3^F|eWriF}vavNL#F|E}X4c_O&(=(%cwmr6l9K5)7Zr1;HhJQWrKd|OlL~bk| zRTjZir|N7Umppm;Q1xy)k*4vE1E@zw4xKx_XR?vc4F)vSgG$Lql?vPe$@>6hM*{S* z#|O%aWr?0E#5?iLfgDC){da7WV$voL-Vb=NsbJFOdAIXFL;_#e9iU+VfaXxr)2XSaD<3_AMNco_sXx@y+0!ldZgo0iVMt0zhR-q4v_ z3p@~0JDuWBDgC;{e{189EQGz&1pYsN0`IzxMUDT0rRyWsd9!X^t?raMy&7kG)Z;j{2mP8rJ zvpesBbQh_=1J*?_ux^X)`BK_+5(5}1*iSpEDP&Oqsw>PVE~RRTQ4cE4-8aRxYE4yB zOxY7)Rpwdg7{-qcKdsht`?*a<(0S-U+tKqk31pep`tY11x3(C5lwExdkf< zr;n7Qyjz0ZjQma>56Dm%9-UrSW~pqrw+7_dmKwt^m%-jTVF(Dk_Ihs}*RAecj`D%7 zJ(QHDxobqK7fK%Ff|If4sti_$txr7B6qzexp`CcX>z zxCM{{eC}hiG)~b!>Mq|(Vh4upXE6b29!>NOJN2*kE759lqBwob3Nh|^GpAKjEQ@x( zaUSh^eJ-1{J@5`}XD!LA_t9b4iY_NwH-=oimcmV1Q$KaFjEiO-_B4;Q&pB(~?kgCo zsBG3^F3SRKVu|^eOjJMpOXc$U)I0Ok`}L7=(Jdol_`20{o{@@*YNv?hZR*os?zs8J zFITt5CY|QP+PU|e>Ee4UNKAq$Z5uZ(lLC(uh<_%0JzSVL42#bAe50F2y}Hme`GxCA zKpldu@D&3CgGQq^JSGP93#JYRe{kwZ1G|)rbr%3a_ZxQX*lw;)@)tX|;yDq|Rg|&D z4jcAGdOT>R<-fu3_Y4)k3w1YZ$@ERa6tnX}o*lUGX6MV3B$EAeAN( z%h^F2?IH<(-gO%Z9*g1nI)fRV|l>iqW@l`O_>dUE+@OHzfgW!c{RWgv!Bt_5rCz)(X zVu?AOcIJ*~)0tp1+SBG?ljmn{q*C7d&|II96=_`jdlp!#8ET;W-ir zM36YTY&B@Gvj)ZFF5s-zycc3v=lUJ(YP4C;f=zYfkn^1HqZDwe#V5AS#@z^}977d)waM#QrGEBAyq@iS)H~=lU*g(GGRF%^XYVdDO!JFc6g|3J zTjBWn#}Pf^gxJv~!&G1yH@_h_Oi%;6Y(`R7f}nx{!!XLS_fnR)0APwHJj^*%Wy(fW zBSKP{y!+~Ok(K%X1lvE}$VqVuDM+zIm|?Xi8aSi}qb=(dShOLnh83M(YX{5K<@s!V zD3U`*(FM60wF~VMITQR zp31Q@PdEaJ1tTr&gK0;{N7=g`NFkmh3{3!zV5C2#)BxwHTX3??t_5-$ze$5xxmquc zkmlr#G}#350M?P{TxC^Y%uY{$uZ8;M@=_Gr9gu=r+1$>KLML9VnZA;LNtmN$JK;&6 zt0f>w;O;I$WB9;p{i$Nn@3x>nyW*02R%rCzT6?uv-!muvFP!Tl_VZopAbBtL8Rd=nF~RFV=sD*5vqEDg^AX?og+`b| z+nYdYYot){X&Blo)^4HaoO_dP%Yx*^KL0DspmVkTeFVvIRD|@q(iSYTaz3f+R5~L_rff-K+l{*Q`V;QT&G^F}*MGYxZE21mIJimv#9)uW{^18selg5xb z^)wfkTA-<`dI($b%n~1HaD3F_ZQJH_WU*LOt+ct|`F(C@_FP&q+PtUn+ff*9dXuN1 zJ-E6KcI%1Or?&-FGl~s)`GMLuw&gVdSs(Q;_U&Ka ziI|@q{kGe&L*tm|ub%v>I~u(9_^~SJOG)fj#oe6)ah=}^LcjBewZ(}qvk%DY*;#pk zo)SrY)~9!CSqEKJ?ZOA0DEmaT#{2E^B;~~$OPKj~sqXBvH3@kID&5K?!6nL2W=p5N z97g(<7^fL$!MZv=^L{2Rz}MDsCe=mYhjEbFwc`&QOqjD6)?AtR^8CDcYvD~3%r+~1)P-QdGxKE)BVz4WgiFv$-K^V-)a!GSYg35v z(~+m~Qw6I{5s=^X^^&V@ds-RR&aV&Q4KQQ-Ea1KB!L}ZGzUGItae2SfgabU{-&c~O z{`_stjW$&8z`fj4)T>x(*Lp5Re6PTk4=@D_3rv2|(hj+;Fh+GZw?%lKHqW~VS@U;H z4hPNx_<0~(c_Q*!ut;$cDK;Z#O>h!b*G@>BC8OXaHWaNOv_B)d00dbrHi92l_Of=8 z%{(UlnD$nbx@67iEAQ{Oa9>G2_|aBcc-DvY%qvYX>axlsa8L;k+k)hczX}N)LJ6;A zl`rT}jq@>4oGD2$irUo=768TB(vhgp~}1wpjYkT7QZxNHJSx zz+O_8i_m3UEKiVOTz=9dA6Lok@|qMn*rZ8uN*?^4FdQzeAitA+uFABo^{M#=xmFx0 zgNkltc-rNpE)ou3y~va0!y_)N(tM%LNl#V3pNRrut5oFq{+CjP8xPC`wTfZu8he4k zG0*mJPtC?3D9Q^JvDsV@ngU=i3Aj;2jeOF%>5-eY%u=%a0@U#I&TaF?Vl8N-4^C-< zR8nM%u}F=(%#|sKyK#%7ifqeRq2Bt2KV0u6eW!62oTkUk5m8pzb`+59y7`mqQ}HbRi{`LeqS1T7lk+IV)p?OejUQoFO}m;r1lJj1YUrvJ9yJ3E zMbZHH)v9TUc`bW=o5KB_{@Bgo~J}aFE)oP2o{A;k!zjCDjd_& z{=9WYUXZYe>?%5Tt@NXmJO11tyn$;rj<=D+2Pbux$zgeKMjI$N!WuNrR%c&D8GH8^ zv+tWl$_vht-#$}Si2>fD-SEi|ox{J40z91=J?gqY0oIHhJq3^r3TAd4Tsf*YBzH>D zar6mdIR@qp5Tl(RxRGGyA3b97)#+YDtVkkfnM%o~L+$N9j||sL@y&{QWMZungCBuv z<+-?u<{9X!Izp`7bO*X=chk+gl~<&08)(pKZ!}YwXV%df1MHQlwcXM*%(+A97cGCZ zgf~`-zR%=H@G6N6j0>7U6T;+XN!g_^wQM(@7BwQ{AkROPjQeu}S^5lj5SBO5kZ@@u zY&kcOEuv6SmVgdKgBm`CmH+2ZR+m&y^Gd{~rY}IrUS_gVYOqjZbK{mh=3KB z7XIvowG#`sfkj3^AB)psPjJT4c&1p~71cwgDah<93oYrFc@JP6-D=EMA(K&Z(drcP4qb9wo*PJ{kgT@; z*yI{~ZCSQzszv|MR2XyjW{q03TJ%59Xd_ z<=u;u7=IFHT2_8cuOZQGz`!$W=4_pR<34TfCqK}&F5ti-Upw)36W%yE4YH=O|9#jBC9m!=5AbO zx0!T)0;|h~O6E{43VS6PHwI6+#PzNdK0HN>UBwA4inJGFcEyIo&BLM0#D?3rP_kPv zA>&Z%?535|SIG?5nI)PEwQKl=OnmSWEg&kWsQ7)$JkD0A3WJ7~A)jOnu6ryIK*6Dd zW`|g<*5;GF@f;1B!f*rtovM-D3RBLy!C;(K zKEz9d7Ni}m(E1l$p$n!(&g9UnxICDfG09ySg(`C+`by0;qk1ZA$^~S2BjCPoibOz8 zQ?MYhAoHYkXT8Wfj=b3>|S!IkQ2u zGZ*0TfibS2Gbhc)dS}X4mhGkzH}^;>PafN)ZIR_B5qD$=FCA&y4APTl(YIbE=zN+m>zGYU9^`=Peh9Y6W=WFv z>!5hHF#Qp|%mcnNs zO?g&Abs|u_<^rAp(1k#5;x^qL`W7`}Xbn5g-SjAU^6CrQxRy56NsXSfo0;i;`z3$cTokp)R&TBR zqp$N}c|Z z7T@yFGS!MF$~y^tNLIzQg$Yr8>4};`_Dn1CanwH!+>%m8P)-FwjVcQ4H(g@YkUiVH zb$rv3Pp(MGZ13vRf7x0sNE;L+H`W<2qpO+OJM|a@hR6GB7x#MQfRA!wWq6)jAXU?r ztzU1#rL@ipELwwTg9v7KICDT8upo&s_H-eSSxB>m)BMMKbE-7!gU~!#Tnj6nlHLy+ z`&Oj&^AW#_0|NyL%1=y5&y68ohB0jQX!C7S&$&V5t!*(^zZUJvstn4mP!43_o*2I# zMv)-}lY7ncSF#B#*1or7)rby)8VxJr-%rl;W;&5lB0fhOzME!W7g<(ZI_$VqB@Vgx zSTQnNl$>`B@<(UXqSja>lA|G!Njuv^L0OfeMid>JE%U-#DkcdcEF@87`Q+f=I0W~}B> zlM?8?^CzFrl@gTUI*)R-g#6Dm)r~Ar7yBJDc6Uktf+g=@K~-BrXs#WM<~G!i z|C!5eGUgnZ&~{BRLaG7C8=U<_zwHGu_2S?D`d2`(M*7dJxAQXpc|rs4cD}z=DMDXo z>%X}G|Lfymj(=h2|M{2xhySsC{|ZTh=()H44m6HywB>eX(7E-J0Ic=tLgM9k^~EYf z1Hjz=^KFL5e_O#oYD!AIc3&v4xP*iedyD`3`KO)0|99p7=kEOf|0?t^PW!(K{@cd? zPcdh&RnD)Uq|+Z;dspp8ua+>z>`}{qd=CgwEscIJRXFB9U_@kHnhdbRH`(#Sv((Bm zVbtb#%xJ!rkMrODgyO0g!-bL%E;J#sOor9C!L3jDshf;W)#F}w1WO>A)nQl#qiK@K z;l9deJar#Egp_WVc5~_bG;V0bvwF>K@tJG&dh3zmO(gE^#W?Mf-cj%z*Q-M7{}4}e z-$Xsz3XmMoAd>!9Je;stfgPL3Zj<*0BfLXZA;;f=^6BMJ52IsZyQ+_(|) zV9UkuLA}l$+X@bBQr8OKnjgMVWFM4;^p((n_JF< zSoSxLSa>T31+AJ=+)z7Tv1-{Ku$Jn!qu$kX^CTHW&1zp)9nUqBCt5kVU3;WufQYt6 zx^3&|WbmY>s~k$Mqo2Gs_>R*lFGSY27Rf2;UZF^URt*Zm{bQ_Ad*}GDdV#_%*Irc? z)e)hw)R;kD195Q*4eO=q^7teNjm$v}xn87Po}?i$s-Nc;v7pr0d+EH>k4ZL zzoAyAInHTogSfG}k-<9IXx9qA7zQU!t@>if(ZC7~Yk9fBsLUBdcCsy&Q8@9uuh%^K z#bbocoujrk>dquS{=*x)4dLXZN5;Pn=TnFX14Q|T1x~NOZs38M4||?tGQTtV-pcwO zEqar*dbw`WA6av!ax<-5uX%nJG}J)yIrEC)vL3H90H2?hVi@siq0y7BM0;B0@Ex4* zV(M!sNc7>MCJ?gU9#u%vKvUFqg|0jWs}CWJi1A{QT2HU?SFR+B1jdvbbNG!ut)NuB zM4kej0{#6{=If=mGABL?imN^%G%ZH?F^8n(=8;Ugy8+~45M_dLZDgS5uHMEAE<|D& zHEs}hE=}xF0JN4(kV^H6YiPicl~VdEL~Ot zk5!UGQjS*10nuM+W5b(_0|6Y=vd6i#NjA?e`2RsC1u(6 zIyq13tv+K5Vi0R<^2~{{WYx?78_#`K#MGqr`iAIRf@fP&v+mN~d*eKr1V5yqk;e^1 zEn08iqsASh_oxmcw_&C5Ug^B~Ol!%C#Ur4Qsx7D!p|r<`+P>?gt8w^e8<1J9LcLZd z4O-ywcWR{6Ce)m^fC7f^NuKgQi&myj>S*a>OOwVBUaNE101q4CsQ4(g^;rGvpYp|m zQQKCPEE5&qiwBApENC2VjE?zlAk6JmtKLVqz=Ih`ld|QFnFwxAn+A$ZSX7r^nFm9H z2QCpW&cr`Y+(I%5b?Gxn#340fh&B8U~k~UZHpB#Rh zEEK=zu1O^JXJd(4XrPwN${=@cQ4_8o`9q2}dqVL7BP4zZ<;Dp?(&jvA-(z?eq<2x^ zYx{{mi;L?KyF}w>r`DCSXV)k?cB@_t&zkX_pnqQhe4&mPmxQ5)|B>pCt!|<^syYe} z)NWRE@^WG^vsRKPm-rWJP_~TuUE~(McfHWL{<~Mvz|xWDEvz36rJ77Q%Lg``th#oG z4*q=&a=t;82rs-MOI-Kk`VZ#K{ABnfPEbSz&=d)w=)95opineU)vOsJRvQyAk^Y}| zN$|681a1Rzi2t!1%G-2I=sKa}j|1;vzLASK^?h{Vq(8Q@F#YkkJAlwS&w2b}yJ(}( zC9SyMD7$rZ0<#Dl*}XtpSkJc5NPEtFyx)905z)czSI}e=J(n~+nIH=!XafJu00z;^ z$#oOtUEvziy8dZ7GuL71kwWeRy)~n4p75G3_U-R<>2JcpC!#-^6}t`)q+jzomhtan zg7$immQK?C7*St%0yQF+4 z6?z^zTNG`X9g7!bqg2U$a082#=yd)do~ONF`*FI+f<(|L42X!O~P(E4Yd)qL0 zD)D80y!VT0odBzd?AL1EYHuPAw$b?>Y(zfw`}wmrw{pt*BC_`W;hWYFrV!J=CyU{{ z>S`v5*81 zw|PbApuioQtUX{P72GMZE7nT)-9!fcR5Zf}r)sX`(DmXPY<>Cj&cF$`Hk~3wOgN@n7JPlVQxNFSOd)UWYfy4Ai8J{rtnkQ1G$T5A19>qRl$1i29SN} zd(llLDka+{jqB|6v+S<$Ev~SmUsMoSQuyw%Q8A}T9B`nBO`B`~KPNpcrNVhe&me%M z%vJfn%X%k)XGY^pU{yuD+dSRYxRTB26{p(zMZW3R(iE+- zqO&N@suA8VZxmYq#Sju@C#Z$iMuC4A^wVva0MJAj#*p^h8PVKtIyh+oI62)izWonDgGg0bu z5b1Anzu&Zb#n0nQNZ4(`hkzmc8G{(^R6ei8KKuDAq;mQK57$W~$4;ely`4gVGK@M& z94Iq&F9WO}?Kueq16Kn6o9Lc87cxqCr%;2>OzOvp7Hdx8duFEqa^tPlAtqa{FO~yG z_X|-9O#kc#0-=3lpy&GgUPK z?^W}9viCDKTlw&`bX7jqq)LPwZUTJNA;UET?-bc_cJ5hM^e3=H3PcRr&+0koD>1Ui;ryp23uc;T?c}_fsLkI`2;CcG1 zAOBhoG$_@9t(IxUCKlpATb0(Jt=wdZ0aX`Qac=e%HQg~vMac+@v zS+ox*jo5CetK_myd{@R;7AaP=Lscym8yJBdAAvlVfWmd}K&L~bUq~ja{Bsj-CD(Dt zkDzHb)>1d{XPe4LKx;Cl*C`Pm_m+VZQ#EB5u3?5_O*`U&J!*F4QW{^e-FEZDWr^a5 z{Rq+A0F!3p7B}qR7Ypr?aD_Y#InY^K^FML_vz0U~-pv&pofFj_ zK+Py1yDy$RA>L!7FT*rd3TgW0_+#MVqfg}a`wnSS8`#oq?0SQkHglAvs$eMX#b?3W zdU`rU*=JUfRzea^gPUgeRM6=1yZ=MkSwKbgz5N~q0i{DiN?HZ!lo;t!5D<{=knS89 z5u`)9L68t>knZl5F3BNh7`kTW4*K)A?)$&*eeb$wEf$M4hdKM~v(Mho^Lf6{em*TI z(E`=aO8n>CjtjmS?iydWAg061TS%Ge?2~V%5_N~ld~=jRcDXg*%AS8O!zH*=CIj=X zzXY$7Jx_W^Q>J?BLxLvqfGAsTwtdtcUFVlC+BUL9s58q7zz0_4lzv_Q1G2WFxa4?n$1# z3F1MD`sEyfKo8r7_^7H&gDz)>HAZObUbg2mi8K4SQMm_ZoEkc;wRap>VY7t@t`&D) z_U~nj(r1{3zEeubzM<#O6)h`Cb@}}YB+Y@mnVZF>zfEV!Thm#a$j;7=z>tBV@=9Bf zS9)b&O(>qezB|XDY}9Yb#z^d2#S)h=C4|ALz9q+rGZCf}w&+BTzH}#tZu99?fD&t6OgkcC>ke)fy1@ae!1NTqs%iOE3-q0WBpc2bA5 z;KQ9(U{+~<6*!}7#4Pk@EQZI)=X#y|7itCGlex%FY=1GzAmr6-@JwLZ#g0Lf6!%Am zync{wp14{b&rg-3Qw}vykgsS+gyw;>}X`gYG!LxOVp`XEh1szG! z6g;#$HePz7ru~-YqWd)Ac-TN~nE{res%-E~71cV?c-Cf4`5PbdOtR6EUBR%of>%jp zKTuUrL)fYQaf>!W6FAMD{G>{jL$A{-B`bSem=C&Rojm? zZp>uZUx`?t$_0l%$o$IEjbMJ~>aL!C5{gzG-8j3CH|An)@%~}JuVrkAJ8O1#e3njU>CRo^~S^i4v>qfNnq1WPt``KrBT=36ohUN?)8?t>6;y*Lz^^aGDIXV zWM4h-AfvoCx%$2&bz>7Z#1Zb#NDo{_%MPG?mPz^vXPm6+hALSryw2Tqb?TWtYIZA9 zUH~9q(V${iLew8~32a*5rpUB7Pm=5>^Iu;8#nBK)Nv&K$LP9oatv5*-algYS;5bnurkmS9DR!4nA)Sl7mSWGjK7-zA zMB+$V@EP*C$z4g2PJ+v|ZndomPd(?D}(GFLRz_!yj=p6&r%J49#RLC%2SGY@3{DL%?jDawcb zdlp8*00^vB#A(^(X&Go3Rk0aqlh^s@8U^_hm&dd<4o<6%LbHS;Y8f|OD0^-#5-m+1 zpSl#!_ROOK*?D&g_7Lx#^hW5vKtx45!F5a)wdeH7jEewu=`e-?l-{>Gta`$@wC(|G z?ffi4`*c-g`pw5-4mwuUJXgNOYp|8;;k^i8MfsyOPSIig-YlDzXu1(EZ00oH}+A%v#j`$JZ=$UTo6$&?;Krb z5**{4-4x}itF$Ywto_-McY}POyb)%5G~_uGa9&LqV<(2uajgKUlUczxm09y)u?urL z+e^Tg+~AI!DV%DrGT(Ar`QqIeHb@6d29gt9*1x&`&#>~^n)RS%fs}DO*4IsBhxEnP zNAu(V81?(+zH(Qp--GCqQth7su%T_H@f7$2WRfkJhPQA`b=bTtwUu_ID0dcL=j8BX z^4rY&S1qQruEu*Krc2L10~yq5T}gSt*U5!2 zJ9m?7)H%~HX3P0e;K2F#;J&=vfpW77%y7<~ZE=T5^n3^+;>bM<09 z+jG3$ei5GsEbGtzhe~XW>)!GQm5&p3sKl_?5Kw2ApTX?V8M^ksFhS4+cyb|vdO*$o zZU4;xw+H+zn^r({MmCLA;(f7n2d`=;=y?37_;m?U+)3lY+|5VR91t9}{A5%>`%_{1 zhSP-vd7<`cAuH#r@o@fU8-R#P-@$m(1&`Q{jJXU$&lyy0wrsEc*H;7|DjvY)7%mn` zoEn<+Pk@>^+=;AfRvOVuIX6?1*Vi!v!Q%7t^N#y$MoS7Lo~4mBV7>iT0aOSCTwsdc zGDC8*VsAjS)S&)rqvfe@^K;1~6LZMb&bn8Q&4QH=$IGiI8RM*gni>Jy_LI&}s^Dgb z?5hc^29~RlGb7sxQi!sMwX!{mtt`6pcsxH^;+^^6SdRQIv+3dAfBINpjF%5KJP|WI zD>*kev$0XX>0_LupTzp|#0rp5A>0UBOUAFWD3jpcG{><>c2DG3yWu6UPZmP<6p@OD zRW7ZkMmUIE1Ne0p!^vD)31g;Y|D9Tg--X7B0K5Dg2*owNysPgnv9SzwDE>T8$>e00 ziMui?8PL;=8MGwcjCs?1SFDjZenxJmnXB(tA)zuF`#|eL)cGmy6l!-8gU0R>DzB?$ zXH{_`rbA7@6lJ)@G$)j`{Fo^riKUh^EnVzaK9J$%FC$~`oMMA71-vhhd<4ZTUj>0E zSU}IP$r&&jswU6H4DwnR1=$>U@qh!@7%5CU9&?8z7GWt!Zty*1`Cn$NMW=j0h~ORdsaI!CEd(ru$Kw zAyEzrsli-ys z=+WkAK>!8SI_@;8DTR`T;GZSzyIN-?K#}MQ5gB`{WD{|jz5$|zDJkO~dchV2;*(yk zgQXLF$}P>gTqqvar+_;Rep>b!fer+5aHsh3`NyzG%=Sr;#Yusxb!)T=d&JetqCJRv z5C{b_EBK*%!4ziqMA=9#c0zRK^{=-nI;W#IUR!$vy@zE^#EVqkt~cT0NJ!_q z6xX`&pIN~F;8O`ZX`H)$^bAEYev5yWqN9jHKd^6By%I&fTI!FX;la+tf913A=+OqEo+rRT8Q{IQKw3ef(ZE3}+<4t?X}_3u6X@=_ zJx^wd1p6T_5N0|D2AQ2$n2uSGEDoFH3T4k_Iq#GO{Hnny6qGz^!F*GId=qiUgR{HL zw2l=S>+V6_**c|QW)s_$hmG#TO8f9FU`6Fd_VfN}RUlp9#45|F4`-C&J^A!)7FU*# zJC3}=t15fa9Jns-=K*qfv`u9}*qPCUp5y|YxvjF!X7*>WUVvy=^y}Wf5~}WVZ@PMs zCF*6NOT;iAZ1hpp{7DmW?p_i0vhVSaIeVj8DkBdgqhI9<6@uENH7A>B!61i;1>x#Q z(M8y2QOj5$f7e$@CbB#>jjPhMF2UE&Rn%C09*?vgD-3mTHxY=>Z}%)vc7UF|oLNw~ z*({tHSbN+0>hl%-OT+gc-t}&zrHOiqNO`W{jhRzoSo-Z4WbS8(hvDo%Q*cGx(chV( zVMe*R@AFpiu0M2!-*J`-h#sLA^=!t}P>I-2FpzXmKHE!HI6A#^RHkYV@5CX``rwV_ zlxW&Vq$6g95c!z-rHzWN9-(HeCDKu|C$GjN{oR6 zc3&;Mll0_RTVEsJh^{pJp>T8(-mP9Gvk}~Nk@(bDp^TppdPExbIp?{lva$llIrvE{ z>G~mLPC@QGO~E8B)lH4$z+jDTG-~t^>psQ9XX-3ViPtV~b$;wDrahj2=F}t)X@07f z!Mor{ynQluku7QGom;meDr-9#!M8rlo??T)R*=sGpsOSi&14WwWOUhavTWDtH{@~J ze=V-qqA~~Cmd6EE4OuoOb=|$bhRxomv2(_s3&5z=dF$u-^Ces@m0C3l-Xp@MV6)Q{; zooGRKdg`iA6iObx`M>3JTPv;92Mx|69-B+4ig=5dETNU4(o@vBq& z+vHqmW@C3-dno0P(><918hXj+v8x7USbHiDpRKpqk+^ipSy>*-YXL&lpXL~{74j(N}^CchKts6NWb^PvKzS)klA0y9Oq4WA9~m;jucHxThW~s;wmqvjqlU`373@C z{MXg+BGcA*0Os8&Bcnv9XY|baLeSsgJvtaqh_YAkTpr|h{3Y>dw#^DFZRwNC5(97B zUqq;=<@yH^3J82#s&Z`Ju+pAxe+TwUZYzSn>u#_kcFfhi_o13afLpx!8UG+teYb4o z)HI6oQM5fdRdsC0wBXK8usViK`4#(%EHYhQfADYYlv%%igqJKv;v5bHZ^KC^zyNNREi_^NYzl9Og=(qk1>p)jVMR)3|p+P%BNy->K#W z>$H#)XFj!RC)1_!qrD6XZx3ZaKqCA`_s^~Wb=WfbJy0upgt|9<&#H%7S96+^nEVs{ z@O9zJobl(Bw>YuTEn}b(NQIfIGzGr(8dHj?4;%zZ4=hv&ifJeR4A4%?__CLYaHGOg@skpwOe81E~O z9WMwilj{?JB)C!bkC`wTq5edL^&6qetOzHHU#~TCi#>X#qGkZsQFxC{Fu0+5_>tBj@(UbP8{IgQy!4ii86Y z@D*eR2zd?y6M!x{6@yU*z>zH_UA||hwf1Ne_u26`WJ~V6F9sZQYwB)E;##pDO>U*Q z{1^1Lw%REy<~Zj`>5@-gt|Bp`EV~wswU@BP=WptoKfE(|K&&VD3b8Ah_~FO8&zw~C zTiX_+jk@YX>7$Qxu;w-UB^E~{rOvOJ9fCE=r(B*@-I%5y)=_wAH23jYl*5n0(SRwHe#&tIrwoOqT0u?C_P>H8%en z&U|x=GsPb1I(U#m&ncA!LK~g5%97T^vY6!h#GgIEQq=R~XS_BJQE1xg6LMh5(#T=8@5=kvrP@%q2({xaHW#9Fu zkYeS(oJLe#)RhjK`^qc659T)nWs7g+-$CjVEWpLyirq<{eiHdqVRZKr?&?C<{QiKfO{0+{>&Fj zVN}Lkeo%?5x|^5w@Y%}ieL>HhAe(g_*J-6-1!TTLS}$Xu@>?g4AIm=`gFSo`Zg$x7 z79OIaLvX||g;zV*D4|1je+#norMKbdKCggI!(43Tr*tMOG^`D!ZL5OBCj<$Fi=}TG zQkg07W517ZFm3=FlYS=tS3V2Z{G17;R?*waeb`CWCL$nz#Tz$p@L;O9B&mht6|`Qc z2TcD54rjkm%R92mJZVA8&JVq$oEO7rat|Y)*k~%1;(EVfa`OHrebMY!cV|-*M(=Sx{D0)cy(57z@oWPOlOkMksD*cK9};w1n%0d5t|>rIXa* z?KgPNF(2kK0p`=Q-g12vqBDn{1H6f2nR}zEaV8*J_cgas?J%wNI{Opir5egwlrJ4; zycqm|bo5g}5}FR(*8VBOj$vf%t(?GVePK@OOodi$ChWvrIpxj*gnrtvOB9mlT^js( zCUSv}-l;<3mupNrLDS@Jf)CQ;&hgt1^Ys+%CE|B|h&QYyc(kst8xsr4Zdh3sZcHkN zm+m{Ce>5vSnJ^FbBCoz@bsi_`OK~2F(f(ZgWAE@KNprMmB~-oaZ9gq`#ifiOYHOAU z2Sk<3ac{v9bG7zMps=9HZD z(JR_)1+(nefmK2^K!NX z4>a(8arHOOUf=isSB#!cGQqaNN&0?~SHae8)tTStQeH1>5m*6UF?s&m6IA^_fw(mr zP0#3vA!2Z38zjDp94a;8yg4UA6qcMCiv32Fw=A=O;x?Xe!w``q@A>g<)HDU~I_Vl| zLa?MvGW+7?Oe90EK#40Citax8%e+HEUVS4_FKu-6cyft9c43?xw%SuQRw;@ChP?mM z%Oj-;E`_F+teavPx!>WP4C4-$q%nkcMGHV7S470rNzo3=w_=sG?xeN`E15j3FuOs*B9fSA*|{CxnY@7A{~v9uHBbvWGhhmpDp- zWjGTeZU$zhq8Qd(nRn#SEW}RM1sH^| zL_;9XTaW3GFuJOmafagGHD-VF;%Xbi9W<1SlmzZ3H|zo*-#JWbz4_GM-u^J^R&ntA zoSj09$iKW9wPgJ#asIahZ}IE@CsF_F2mB_t|9_zSf4=Mi8_fsQ7&%&O@l8WsgOE_g z;M<`2?NM3$TWs|Z6^pqs&66VhgXD>{HJ{y<)j}Od5!?g~*J+x=_=2Lp_ z|2iJ<;MdWKQPguGCT+<-0zECbn~8pyiBC3`3($XofO&TR$myuD*Vb_{7krOuT&buT zY?kfEF*7i!2DcRvfGP~AmntklHx>T9U$%~8#A6U*GE29`UO#F*X=BJ#f zaAp$z9C|`>dKCgki2DclZYXu)t~_x(^Q4$LXT9%T8;7t*yiKq%{m>@B$ze)==ea+O zIF#JZHN!zP50gCqAB7&ytH+!Jyxv1>{eN|Q6EQ=F5s@0kS?Ikj9g4xQSu$UJ)a&++ z>ankncBc;6pf`awg9_Y_6TtSj7a7<(${QUWTseW)S~s2!mi>M{$;(>ciulR-S{CEn+T!G3TjsrB&PqOk zZlP;bswDl1zk-t7@HwfgBv1r7fZ_`z|!+PApt$`7Uvg6;gg;?~KerBd6? z7e6+x8Qmp&2}r2>W190n;@v)Cv%i5KFU`p0+;cn2V;p>28yed~IeCNcHy`&dUTk}d z+)b+5fDTv84YSY12G8n>d#1-?jyxW(4G>xYLv}3OJ`M*^u?!eQXgvjznm6`-8n)=% zoEt%?yiR=xwgM(G6XBPydM#|!ppq-E3q`;2i)OMm)Sxi(-CXE9(lcQe>kX{Qw{$fk z_4aMI@;#RG(;{5AFEEW8R*uXxzoLJu5HI`FUF891tZV^p%_42FSC_RPuqc-?RK_x$wEbe` zi&Kk@$?MQ+qASavkWvD3`6h^IfQ>UA_V0MZ9C%nh=pgFA3?lGEB?{bmu`>K7bvMN?+t%us$l0lMd-%kJDWiYO@~?8%*IoZk6R zyRUQ)zj3(MkvSf4p1jjCDYi&;Yo+6KnGn%-E=0AE>vU!J32WI%gZgXF3BLplg@4)j zcrtP{9O6r$gvJ=iuLo+1$`Lr=>o>5DS!~O3<&dl9m31Yl zA~|#iNB~I1N8h|pIdq)#eIaLE0O$VLL||$@v5JbT9}xl6jV^)|&OW5Ak`OUuDbtDU zr7^YBC=AeW|EA~zT$k!Zb&puf*O{1cto~b;%Ukkc^gn3)NUzXcD?<8jpP7Ub z8F!&;8-h6Bs6b_Hh!KtnMgwBQhxHouGO)D`@fw-FMNCKH!5Ip8p{#uw&Gj;MbruSx zbIYA~8g{;m2i4L*_b9*Xl90?S{a4lIb&n_Bu~o>ddB9jGbvIQfsdBI5vOMu(Oq<@z zi_>sbpvdIgX0dddROb@IC?X)^ary9NSrKK;DbLO1ldpNEo->}pnvYODsv6eYJXxzd zRISE2Hc9#TvNJbAJJ?YQzl?S>@3H1CwvO5!!N_O(KjI8G zjK^K@XGICtf0RZcq5;LwXLY3ycYF^dGDrzBlL9XE^)I4WcUHt+p0As0X_YyBSyI}6 zPO#$wf4eLkWVvNnZOSsI^fgdf&QWa>Q5+a_tMeGr7sI&eWQt-9fgYI{cC` z<}^Y~4|b0G^hf*HQml{*4?qhJYtZ@nvPRx4WPH6)*j}xH;1l?@hKC3$L-T~t9p<_B z-6Nc^Fj45%$WZWl^#ea&AKb+pa|KvQg3_Z`B9#KVswJYDkGP&Ka^fkcgXEOeX1x+W zFGVe(O;ddEH_h<%2KXg0`%b;COkY2grG>DbIiqC}J$C#aeUypi%f0Y1>QV>uxUT*~ zOVBR(I&=j)w%IT7Fo0v%G486FytnKwld>zx3zA%~IS|1r1g+mic%U_d=-4yGzl;q7 zKah?koqTD!S#(asmlR3Z2{&3vi;B?|41=DEJ9{(~oUGd7&{dI%TyV&oct%<+=hjXl z4zDYc&}{|oVi24XH^b^oHU4+5-m&msxO&SR^Vj@u2Cw35qD}oWynhHt1*e&oT~!1F zbH$$$UNZz%^h8wzg}RW4j8K9jPwm2HL!arBhovvUjT{&21TXI&9FA2#A3==5Z(#7J z(cV35@e5c_5aKu6+0!hjj!ydqP+W_9(#dMU)Ku_@?X##_n~Qa_|2gf!%+hLm>%AJE z$=tGDR^rhf(V3}N2bk`ScigcsG4UH|eB$nTllztY+yRi9wk;{a_T<1{8`miiCCUuC zaZDUC6tg0|=mVb&u8*nr!Xl;^9s&l5v)q?Z;{DiQ5!zVrtJpH}x>`<&)`9PNlqeP1 z(NFj>0LhCy;zV||-VC;uTMSbplb)kKz_Hj5i38fXKO2Le8RytM*eGRhD(4kV1?B5mu$>34OzX1Z=GJ+976Ns zNgnYj^AmI<+lZK}HW9X%y&c>&+NZoXj+pt~R-GLcBitf8d$@5oObS-3Ha|_87Nwk_ zapDQ@-(2wY!u9Xtw@z%_`0y%Q0Y7&{-rL_T!;^L5Q^0)Wd7ihuL~a$cZy;o93N-c= zGhlGBpjgTN`8DtY{eX6@HPjL54A`Pxhc45wcnXfTo%4!caLD;F$)DSwuh&jNm|?K^ zjq8B*M1JY$u74wv8WzL6{(6cenuAM8q@k<2E-Yq_b?{EII<|Y$%Xxdu*?kn4Jza(*;=2E z`ErR~lQWNS6`~tFOL87o5*6cuFnBUaSv$nxG%!j#nnn&BY&I8gUg*^Sqrj~im7DIB zZ`x^V5*o|tn#^UcKhv@*ChME$%aXNnh&T=%rP{d`mGSiY`~)uICMas zIovF?!l_W{3y9GKe7Rfw;E#L-HL^Br!r2F%o4P6@Im}=$&R$2ay34)r?R|`a3$vaH zO6C@u_(fqCS+SdE^)B}o9lEg}p^<48Nr$6mq4hiV@ONK5AzXf6B_T$HwF`159xSJ< z3S*uEf>}?Sdi?!Aot7_G#f_DsRhPvwacEgE8Q?bg5RmxT5mnJILFPg;x*wIjX)<2j zv*jiMz783RWKclfJ*(z_)%8AB{Bt(nalfow$c2Ms6{x-Z9nQht0?SrN^w`K2!IQrv zKjUl3DN)CQ^+qelYoEpwH-8<=_`U#rfU@o$&{HJUb`jEMUrRxgw%*?s7d7V@)8Q80 z7WMe`s6ZougIt2*CQL2hbdTksWk{)(j;#>^(N5sn>00_V41&9QDK0fC$1+8Ex|mVc zE!5=U?(CHaGalN*yW6OfWO=k7_KWhVT9e4BKDusrMq}+g$LP0p{93+FjY*L6Mwr0f zFZVW-$Q6E>1LDDH(%hX1j~9^)6yTpDJMzSJAf!~PU zBm4f<*(53juUO|V1}T1qIpXI2==@QUAGhW$!tS3u*)#xXt<62I;|yC@OkDh_@O8z! ze+ie+XYzQv`7)L=hy+?nQOJo&iKtM7tv^1U)W=xXkzYDs1^asXU=kMXutDuBXDw@t^FUhWvZUM+8Jfko$P|qN_cDpq z4@F*0QD{49C=e)a;0l=D@)9!p1#ukzHnWupzg7(EfUeITs|vK1`@i%A^p76J%aS<> zXuDaT@7IZJ)wTW(Ow^1~eVF_d{^;}`lN;5_smqa3-~nRT*4?4)^drs;j)b=*;=9Q` zRP@0F<)S$90YEg+t%^r@TR^>XR5w3}o>J3|MOl4H{QsnBnN4vUgcBWLkAW%__XX|S zIz(qw?Bv3%dQBlemO{^m4KQnkuA5fRH4vY<&rpSE(b!0TRGk86T%>wqoVdE$QANmN9Zk8zFgdrT zMts3`MCPZIPVOfb^Nft({w1MT>+biD8x&B&#qDvS5y43_z)nxqm+)?Z^WN|bf6rhVfcfM~kRI?dp1?kDY)1Dy*$K%&B?k2Fdio0`zg!P2>2C}AV zrzRiGnB}*mziqnr3@%9`tNzD~@~BHn0cR~{myZF!^KSY7mZ1qO48=SLe*UXOJOyIbqPZq8pJ+9*R& zclsNf;fUpv@4cG05jM0HUT})*>NJk zi2}>okC?9j2L(TKAwe!$u@^OuwyKX#2xu9dOlR>TWCO-6s$_bpB1Ycf^8MncXfd!A zXY*=$b#;1>eq(`fFVf;MD}8GTD(@LwWmKhJNh2j!dtmZ3R)h22{Zc9xP_=?+xC!AR zRl7TXw6Gka-*1VoD4@4kuxjR<=)u_e(ybsw?0R1)6(~gbYzLUV?&?_hT=v@c~>p&ZqGXZcYa54fZJAqzcG6YS#3pk@F>qyy)0jG zjh3M|$%)v!*v%x}?!qz+3YAr;@JPN{Z?n^YATD~3#SBM{y@djG{~PP0@~^5TJl3;L zLn51(uqdxH`;T2Kr*A|P9{bexgBkBtCOyM>_Q}K+hlB^SpL&4HD)7ETniHYY>~sga z-%x%Pi8w{46SKmaVw}tP_gG}*OSffby5~K+n-s8-XDN*DpH+3({EfJbie0yO3oG2L zTlBvRpO40K6mohM*~3-dV^Nx5%~}qkku@2PRcT_F~d|b zi^#h>oCBU`(ghBH0N)InuLc&Ln&&!i#Z_XP`-^j(iuS(e@nZ@k8rk_L`Gk0A?uh-g zZTbRxorr*L`Ms^0wQ0SqC>?tDJdJr1MK+|lHck~*-x)So)K5!?c z;frl!@P`>?m}KgW$HQl}D_O*Jdk`jz?;ts3=B)!viyXJ630iIE1oFB60*3 zI;z-Snvy|D**AYn**~eAlPp@UWjG-ym(i9hBqp*_-r8$@Q)ZzQgPsrzRt6fXd~QbR z=6UL~Mt!hpcwp4~^n5EOrO`e^uRX>4CcvDNll2*0UU5eoPAOm#SGS(+*2Xq5Dv6v% z8d452$NeZm+ap5b{&}4*-BEMJ(AGo-kHu~ykI#L<@OXR8!j+OYEveb8q>r7d1we$) zdj}NuUnR;vSKx|&>|?j4_svi1F-kzc(bT@msfGa-B~O=*W_3bsZ~zpPT3vW>>YcHB z&N9cSFWt%$0%zeVsX5y!5s%1bFDx>DR?GIYWT*GV7>%dv(o%_0rpiS1*WjZXgOL`& zb%P1}-a1;=I!-upt`Rw#4-s8Kj@nM9te16^`reBzNmJxb^5cwp`Mu<5YBtrCRF3k# z++$-L*+`9Cll-E!_$fm2_ideY5yrX79orMhkeWIx9pMDbZh0B*i7zkaji-0?zf;^N z{hHXA|Ev+lz8Ja?O6DQR3r9$NxG9e#B$gc5qnF{W0DxVV!7f0(Bk`)w*@g;8uyu1E(MapAP|n_kotk^rn!O5_q*& zLzCk#uBR1Y!IevH;Z?P*7s}QoD9uM3C&-2`;raqHQyri92}qxrWX7;^+#wL9W7rlb zx5pt$2TR@A+6n-=3M&;qtaOk&tZlGzZ8&TpX7n9Y00(TwH@VK^C}E4=6{9!#B`ue_Kfe4CX7TUf#v7V5E~`(Ij`rER^1>5DHE!bgX7it z?T%x$_>;Pfy%2mt8ZK-&i^%$M?-kcluvkRXxa`+S zsotdtlA>l;JhN@YGIpr1_@gY;<`sIjREB@G09PR=QEOs}^l;vDQENXG-(maaMz}j1 zE4-0=Xpbch&R7ovzUgogRYL9^8y-$KcSd(Q{#sGZ+qz(Y*!a;NrVkta0>T-c>4GZs z_ZepALwvsmw`KF$D#gNIThY1|Sqf{N`Y9Xq5&N{fG>MMxu{@}&kyDt#l*hFQ;UD#_ zrd$z`-;(^;<{7r_PH<+q&u72<8dXwb_L5z!ME$zFWmaY;ae>Lb&dN1devu7s{0rEe zW$S=F`H8~MgVDVpDXR8Z2;Z#lO!I{%m7PO=s4xzbflcS8RoB$=Yd_P7q07<-Gh=*i z_6;MaBunoeBf`jMSU3?<&7^{|J9P4dFrSJ9x%?4GnY+G*`W}mS6UlWq_A)98T_w87 zTM&9Y1@BZEaM%xHNfH!@H6X4akS(Jqb#IZ?YpW{qzR0@5hqWvu6Pk4J&$m?~3mk$XpS zfGZ-A-o8n<%=vsD4vh~QOirydfeV^AEPA&=IQBa-4f)x9b%NO z=kjC)u}36(>It*wf-My!i9GmoBSc;lsp71tpqZYO6uNSOOMU0RK^(RJ=(gLm3orRR zwfFT>@0@P;wunT+Takij>+9<`s|29r@vUfNeHilk)DW;cMoU#2gltpiU)NZ1u($8A zs1oZ4`P-=yw}~xBpKp_N*gde>MzjolyHP*(#<{O6@)Qt8^+r+TYUclfULi| zTk^YSP~gP#UoHP_>tmSz&EH@TKdR+CuZ~K7Ii%lxKX>r`w$LwsL z>tI_(>V-;DPMu~oVXG4|@91TqY+5*D7Q5j)lu6F>H`fN$5inb<%-0gcGFaJyYG%$- zxEZL)e^O#q8coY3aHynkAzr!K*ju2(==7Q03awTntoUfm*Ddp)7b{fMCg(i`Iq$t=8E%uOEFNAS!Sg5&5CLUCW9nt7PF z{lgaUcN|3*QBgJ+zHdK`xEI$SIJ`>l`6cOQ)*0*U^OmY)&+G={k757!xJLjFRdw|M zbFI{)YI{+YnK#EjBA37g_UhCjBy+naCBuR56C$f2XfYm`DXQ_Cvgu?>IIult=K=-{ zfs*dZfxyiaSsjB=-gn$PhAf~Lisgkw3(rXMH4=B>S}u%I=a~X}XCmOqqgRa28ygf1 zvwm8938+S0W<7*UNIQr#33f_mHEJJmDgv+WG*2Hc6Y~6 z^t%%(9Vy{oVSn%V6o!93S|~T?I6);YI9P!W$K(*vDl$a<4QVd$CZ%D>85MH;;Q5s&*AlVO6aOhkjMR%N!!=j zK`z>A!M@2OpJ03*pEHS+Qeq}0fPj7zpNjAnfBMQo3jcXNniBCSU}dt>_;OGM^%6qB zBugyycdyI+fd^z7nO!6J-q4ZHjrvC0ss5&4@g}>J&XSa!kIa3l@hvo3;vYMIO9IYC zoEIqI3q*bvr)EZ6GnjX_=|LHt*&`b5Rq?m(kZzyVa65Y@mqG!%zTrTshau3&&o+vm zeMh5DA%l3v$_+HhY4h7aUiq_vs7+kw)giwI6$}{UWUXOd!4-ssfNHZPeZ9jql#KUf z1PzzHXgHY_&aaCQlHGRnuQ{(wUv&5Qu|GT02&;Z!W%How`ne!ov%pTHhp0+vP4s?n zT#rXHdhLSp7!8v%d*9eni&DbpfHso&Tb2~Zi;7#SIHr*V%~92OW0m`3Pwp?w|s=yf{u z{c`izi6@xH%x||za3l)Pe&1B8Zdp0j=XsEe$txU(0~X-8(prbYjR!$(yYjviYa*R@ z2(^8$M~5yPIPBB3B{Z#;+E;2nzsY|~G8f8mudle$m&RwZLLU4`BO%CktqDHKKKV+ig<4)?{)ofPRE4pd&xz>FS^Shg zIoUmk8(0L{W%qmZk$|52U%mv;!E2%ehA}_Yx|7i0#0&wu8~q+=BC9KA zAxp1YP-9H9@Wwx6Xf(lqH~?P~i-kED%HwmtTBJW?w0PTQsNsM~iaZV@k}qRez;@Id zdw(zAJAj%ioTFsjfkdA?0q#(t3 ze};fBuR&YnM~rnktjsJ!TjpuPmc^OoXWv6aKTmYCdlg|hBv4L8&8XqFlI#7@ZW`=< z2L&5J2^kG>Cq2I4EkugHs4eZT;eL5CBuWBXmonpsKeUAnzsgr}w7vhUE{561cVL-Y z<8q=>(5rlA=vnPQ@e|SsBC8TV7Smkw6mU!w3*DGggY}zv$KX-xN=yZCIN@#hYS8E zhDtnc5IL}3La!XZg4;9kC02HregJ!1%=2`r5z_NYR_FwI6u$pK5k7@WI z{fjH(@1nX|(4GTq8z&0@lDj&mT~a%7LNo{w?jN2Dvv5uOoKmNlWq0!SbJmC7niDL} z^99ys&=i?!yoH?a9XTB2+i9g|58iioz#|ma&;E8Wh0zESs>lkZOIiv%NH~!W;JG|! z#PFMyOoJ-3(?B;MtOY$T)J|CPz*vTPKk%$*n$Grx(Gl<$&m{rm#L1FQA`16gTWK*a zW4CJge7PpuBOS|b1AvP=EUbFo|9msxJ$c zdE{uR`2jEL)tEhOKBf>GmEIsss1;a-!FIQ+uICRX*2EkZIGbSO#rSw9%cjqv7Mrk zS5a1UW@DW76QuY@4;5<57ZLDFuKxG{d`r$20+qG23oShh6~;n4_{k4t*Xy|rU(y|4 zX6Xig1td2X<{QKYwjHNT1)l3_X6865UhioYIN|~5u-P0jaccY+s8yg~UpwK)u4ti@ zEbT&2j9ibj4(2OGMBqU;O5kf?Sv zR=|FTJz6b~bj_!btlcc4syYut}~FOS^Y0 zEy2O~KG>oh=UBaWI^|}%GkuUHDcRG3=B1ST1i}XAqGG*O8c6Og{5%?`}FTQ z;_Gcl5tYH*(N@J8)@sa9@n$b~-8FUu3}Jl~0ljpL-00)v({^l*mgbh@G~pn~O$q%zz*Qye+KC;wlPcy~H<~eGedO_w;ebvt(;W&k%xcIci=X+Oc!Fy5&Tx z6N>M)#sRV39WYmts9Dl|P044_nAOz%HI3c9sYu3A$gm?N!9X|U_k6zg8Wvw=#yL8k zVccEg9T-DZHDukQ`sKsJh4j#yM*65XT_39_)(V0ig16jXL}%s#48J&BW9y4Zo{S{E zdpdQhTFji*^WEdogFE%cjt#6~t?gsKZsbTny{QHc#HCgU+cn=RMI zlWj@PBOUkj@4zdcTG%2Vym<0S7t`XHM^vnGb{z%e*@FI<&4XP$=1worZS?(@vpfiG z35XXdnd*+QQ*<>1vlcA9WT%B4UwMtUU02ac@>+a|{yg}w55eGA*7SM-H5;8-eprZ5 z{=wt0!=Skm2_=+{uGT846$P0)w=TYRmJ$@xW$7`s4G~oqofI)V=&5=(I<}Piy2MV0 zXSnU#b9F>nsQ8ia+JT*V6zfU*6Im}xMS>8~$Hy!xpHer^AF6naRTg=C;^?r>2a2KU zBm`-f^)&L2gB9hc8x9-rc)$}H*MnJmtcK9;NiJWygavZUs)(N=@6+YmlFD+o{a8DP z(km#T{@5)rTsXO9C~W@moGw04m-^u{yGx^}X$!oAUG~U5fE>C@uLdSV?09d(?zXi} zZsfR%zpl~2M8xr>=qigsyjXs6n)fBp)NNJW-8az<{B6Dc5&XpTN_c(#2Ix3E&S3J6 zV_H#)1wtP$2dC!>B1xqvGwqpBx)nH`@|6Ne`b;oe!Q5a(f?e-?smcv7-SD_nh%S-E0tu~ zqlKtT+s5in5k%j`eI+XY+7Y$a&e81l;%m!;9;J(iSaV;Ah-cWEK#ZuT<2QZJl+Ls1 zJ9UwpPx9mYIdW|21gyWX89Pq4`AT zYX*k!;_7NQi0sRXcN<5W^_hj4Adn#tc2BF!K>r8g!Kb@3rTV%*5aRF?b#dg)vDf)| z_qHMI5?SJxBX#tT}Wypa)p7s2^PNwhKoY(33B{=IJ_3Gt_ zM@uL2f)4q0%?D}Ni5&E>ZmmDR?xh0_Wg$)qybg3VzbX0VmKay29h{SlubU4LsQayH zVbnj{-J4B4Vi}lUU&9VO%ZEqPA*A{h) zl0c9^un^qc-92b<2!Y@P2?Tey;O@aKcnB680yOUK?yikn({MLAC#UXr-~ILKy)L?_ z>fO7S?zQF`bIdW1kGj*2J1a(gRF-8Y?7oZc`ZE*8gRv(0Y-5afv3Y4mY+JbAIZwWI z6`nXAisbF~=v#&{?RdWNT2tM*y{EC)5_N4!lk|5_bRn^n2m$5o0PU$r;O+t#H1pfm zoQG(KsB`(qn2-8em^PPB>gF@I6;VK~hnF9NG= zmb12lwWF4$u+bCp*B(oGiw1;F*oOzDXtoqr!aWB_?)FxWoOLlGjxnDcfOPg4K`fMe z!l`-pvZm8p1V+YJIrHv?MpT#wEWOY|A0wP8X z=yx)RU?~DAvyjOO+6rH(oE`B2=Z*dB9yJLGb;>7jEU`6}%VOJ7m2uc6zqByR+g;Cz zzU5{;-0jkoJ>^GnaaxsbHfu|d(bN1&1$$pNI@CgdJoGzLD?SjL$H>A=_b|4Hc9O?) z7PW=Qh={@B7PVsaq2eV^p`Q=xi5>F!Q7eeHcGeQ}|6hd14t zvn})Z&jU)mbHEUpCP$hIeGop4yP%Tm`9(K8NQmsWK5D!zHDYN?d?j6`fS4g;XWNl_ zJ$B)SE(e1h7@5f@!1tn+*?NxL2kCrw@xj^Bm1(LOY!1;YO&itYu=4nQda+#kTHo;Gqb`a~s2Xh>#Tl*^ zNe)!P)jXbQu=y!4!)HXDZ3QEzM>Xd~vY94|e$D9m- zPzMUEo>wIYI<5<^jeXY3&vadq@K!>jcRi?O4cScbCgozS(5o^! z_$-BK@r-R`Y+g&9STh=Vv&lRNiA+7JeOVR2qN!#O`$4DJ0E&O`oXG$WBB&jZPNwCb zLYaRrAGOw%ixy1>b?i~u3d-$lrggm$T6G<=FWH`EX2$_Si6URmVdk@P+YwnFP&bxC zANWb*XI-fI=0*o%^+(O~HD=4$wKM9HlSK;U%Q-VS}CI6Vh9T$sUxLckG zk*4=3StrZ4UX0S~qTiN_U!&E`JgM@n>FeJr-H-R!`@*xb7c z#Jx2OD%%dV8sLkn4r+jgqf~&CWGpXL1XH(G;lE<;c?pxlQWG}*-u19DpG!JxSejkn znC0R7B`?$N8d89|Ud99vDar1MSw{2@lgwE5S=^G7wJNrb)>axvC?8g!Ob>+4}-SZv6N9-+BZqYK`f{-0O6q30m z`w~oTQUpdr_JZv|UVAOiLrb}*j}LV#jTq1*zEn5xp7miKt*X>x6n;(!-_3WcZAl>i zQa5&`Zs04xIMLV)Ngq^1uZAIlqM}`e(AJgU0u0Gj@nB zbPj1IZ6BQ=?ljAh@R`%Jx{aQlncDNbB?O09%ZL-rR0C~P%QG825!a?NO>zz4e_Q}` zE+@F`i;kcjy<=MX#)O=MBlaWHdCj+bE--}UQYV=q!6G|`tb(L+B;kibc;JJ55ce$0+z*ECoN3VFpRRGcl;cLy)l0D^T zX!Ta1ZK^8IT`XqHHN!0|5Ketlcu@Nb{gVkX;Clu(m86mCXACtzw?FvLV{gzDCMPFHoqtN~eIVfC;+iaZIVu2utMAS#L_nrW z)tLGiXljVU(5y{fGZAF<@wcqK^Ex!6hz^W{uNn&(Z|_2%3E*<@j^g8aJ)fGp$k)9&`W@3mwv-WVSi7r_^tNo9Q&lgRaL=A(H z!E0?ET!+EK8I(;R(Q9=YE1NA-YQF)h%HRdWCbf1CQkm^_^gW}ugF6Bz&1W#k*-_Ck ze5(|W-K{RXGFQN*4YCrPTvu%hW0Oth0TdE6bXOp}83YFbZJ7p>^TSNOhooE|G= zvETA6*dD)AUM9@7u}xk(r$H(oz_7Z+#7kb5Nm-v;a@AKfundnS#3fG)TVtR>vfBI6 zG-4KJ>bx=M8E_wjNHc=Qkv?E+ADywd=2qsWEI%=JNao(B*b|B(o)r9!=(648ncz`q zL;PkwN=i7lpn_UivAwT^$JZMLv@un@AowcEYY*B?#L-HI8n~Jnk_*DG6@B3z*`I^n z{N(}&if^yyAUs9i&no}bYQ{H`wBNy$K)d)fpGAF#Xi>QU#FIPEOB&k{`tV11MYVXI z*&I{bx5z1_K$NV{lZ~`Zj2!2)q7?YA>8m7m2 z^iFUTCWKV{<3V*H1u*9t&3hizF9i^!ECilWh@R;nJ%+0$B`{?u#FZhB&Ipbj(6IRh zOCc7pJ94d9SVAnKdV;bHq}jBB$HL+MEwjXkjL}ovOr390 zE-$Nih(=;~W4kI^EZ(0%g%7T*QMuo|YZ59Ylr4=vA;`w-^XfS2GTQ7Lse7(i>VMVz zkis$e*TGPj@QiI^1t&%NjHo`2)O%U%W;bsWlIPtNYnBjxM62x7qD^iku~k(U#}JG@)FQDB91 zT&VCGE`;Ci_)Qh!BB*e-m{%o|Ns-XMae`1d9F*DCx^UdX9g}Bc-~7#xqzIXN-ld-A zZXgb%+&!_Mzy2c`sK(39^LWD_H5;=Ud+`2v;d7rHEo(1d_M^N)HK=b^TjzQ0>5>d; zj`}Ht#bVsYb#qc$eh-@1`+l$KJslVzZ5`=1=hrZgJB^3?M&zSOx;4($fOvSF@~PPH zGZ;XF16#H(Oe+L9T7zo-Qbw>73~H1ZU+%S@HYHs#q0TS9ZBIL+tQ%snYtlF@zd{$< zAp6bZd)=YD)kQD;GU8LmvT`$tg+Gx)MeFW!L)&}auF+aEB;6`2Zvt(r*rd0sC{m6PZc#D`jT?zNYUqa+c~Gi}Xyp=Q@1JfmyKe2BNpz zpItkZ`T%=Y5dU9BN$G@#l)2sGowT z=dFY4hsZ;aC=LruXEw&8K_d>(k#Ix?-JNv+;*2p1sh zgVp&Z@X#2pjBylY3VeO@xPWJv_A^U5-l@Vof&lF?>4Fz`B|MIAN)HN>Eq$@T2w^if zXfw5`Faas;+4$~!YC@?gkVFLnwl`1zXplbDJ5R7V7<2K;1>>j2#6qjOP44|^hUPSy zw&uOB)oz}t4@oAhfx9*&nGNh7Nkjm}vW8K^R$$U&QLg1r*=f4$QYFj|d2z5GXl3ou z4R0z%8{uEGuJ7|%sx10b?R?^4cSr@_yEH!0eRF98_Zv8F%BGHTvQeOx4&71j!OV2Q2?Eyk45-cSEy6TjaE6=65(JT{HaE*CHMno$#0+Vkm?r81@mB=C;o0V)@6(RU}qu)#}2!E(m`lD1MkHcXrqrlTV=ZtY(esJ}mx_ zU@YtuXGDUJ{S(ban2i~rK{hcXz+094j!xlvfsb&(zaA&`#)ny=zCqN}hvzm$fYgCj zb{rAYyLbLR$UvExL5(iNaCK>|$D2-O)0X8$U6yEv|AjS8{gNbzN2-J;dZ(+k`flIk z-a}ktSSmD~X?U?ohxAf0wVgasx5652gMlhELbY=Tzr{I(&^RlkYF-Us(fDEM%awd|sg)MmW7xs5>Y3Z`%ZpJeENe)k+_RSuJ{bwoWmVBe1S6S4JY=NbfuY z6>-E%@ixS8!DZI(TSiptRY*l*z8g8jNa!Y)c?}2eF3Rpo__e;nDrXT}_l#L3!^pvLJI^_y)Vye)PMn{cRIL0;ESqVTeY1J|~~CXrQITl6@T zCM{bK-)oy#TRq{$F_90>EWTOS?5_Eur|y}H4ZK9cXt54zJE1It<|0cy3$%weja4nh zFT!}vP%?$ZzH^CrJK$6dRpr;wWF$?auJ2F}4(cvQ&d zEYF9Wz9nFSVCIPo$G4^&u+5pIa>iqu<6!z-VAlyP)9wB&DO$nYYEa-^nh;T5t z#KhYq4{Ic|Rip8w`lbHLHi?760u390P;d3bERf=4Oo}%l|Iuj&b9fmz z&zqzsSBb9IaO*@#=^QO>@^ts6gWDm$oILiS=}j?ISDwC|#3Yd;^LAFzab>S!a0k&X zyl>h?r*Rs0=k3!vQE?)V(L?w0)qr*0nU`(9>86h9(;FCzud6_27R!%%q&W9w_B-7riGl$vq*~uxYQzPR9(ZDIlLh&Y=Fp zc|9MpM<64wjQb-%eo)>5y7sWJV6d1jNpWZ#NMdmS@J+sjTTkJ^?S@Cz;Vt{k^C^qS zLQ}@AJ(Yl|-Q50GE(- zm4&(aY_-`$Is~rX{gPha>vF2Z%G|=j?l1It-{W)NQ(^@=&j6n+I=uPFkhkYEeYR8x ze)PUN)C8PC5Y;tLVG@8*dLAZ;Ju;NWbGrogme$wT@48O#EH5c9FJDhC)vSUK?r1}1 zX%aOu+F+NUKEnl&ovzqc0p8BGR|7x5ffRN^ z?Yrtxj}I%40#B|8{;e98mixFB=&{TFu}h25P%2l`Njvh>`}}t(9XW$S=JE$(a3%ta z2t}1E$p3_zMyT+tx&>6Z|04-uoigmLyWS)Xused5{=trl)`86t1r05JWXDtiG&4DQ z^5i@N)LjIDauZwbKX1Qg0_4XY-N274&126N8MGS>1NLkkJFQC)?uq-=YkG+TO1shyZ^#Z6zFQEw|eQ58E~m zK|&r^KfcMn0QTli!-_Dl*>+=Zon~nJ6h_!BmM$bd`TFxI!z1X1n~<`iJhJv<)T%5| zCv-O2F81O9oz4_ZbI2RWwng(V$@m-yLdJjY3&R3*O0)6(65axg&;14opWS*u+{wfT zSrEe>^H~7yfNdVvJNrdn8>P6(mkhC$alC*~Js~ot2aVF>hVU?~Zf6h01t# zd>|4uYhdaX@UZhoU6(&duN&q+M-#yNpZLQU5?;65Idtk-(98Jb=ajXh86W+yqt`#&tge9EQ+-&3prcUe(`qb!T|o$i z4orN`^xkI)|IP9*TStv4uu68m5H2vfiLvf9)7&C=H*0`(vu)6K z{l&-M8^Pp4$&l6kUPApZ?g;RXc=Zm9ctt!Pch1mLCUgV1vECipuFYj-S1-OD{?rBn zP?=n!a{z%Aez&Rl+NzMaMJ2A^@<7lvHGMWBcz4sBCsPd|7Bg#UM3-v{Z-lca0$70P zkv#$+6!r8{qVBNlsaR$^QbQO9Ll8NgR!_my^ZfEk2OHlEI5wb~m|**0GKM%O4;-(B zB!Ms+gvk7m60HAHA4C(KZ!5MRW84iJCkbEyLm2zwPiB^VCi%U$Oo@ z@)5s-{dPj-31C-G0sKq9rin<;hF7cEc|W_mB>y@Zk`JR(9H2*An)!Yq&TbqwUuX61{H zA;@wy5bVL&kqAvN47$n0#?Pvd_k8dpI-Zv5cW8WfmjBzlkpB+YZJP_K7?BEm$$6N4}F4P@)_Z`vmpFcV5`(zF# z_p(b~(+SGV;I0gAa=jWZ#P&*wts?q=0-U5mrT*gp@>%E1)AOGrdRMrM_`OIa2X_PB>oHI$v_@?KW~ z{maXkWJjXH=of6S0#2)?@Cc0_vQGE9!6hVXLV_V)AJO*0J5VwNWL&*`k4qKjmw(!d zf7c=RsE=&brfNcnGiFAO6~^xL1i`K_L|+>Y05Ktd-GaSF1t*F$720p_Sguw}8zDb4 zMjePPx1^r8$YYwlQljh!<(E;(py0Yjdr<4qj(L#wD?9kzdptm7Zs7&k>R=a%4Z)kI zkCr(F_cTbqN9IDe;~dKx7jA}ef1{vf<_c}r_SjB8-@se%2|8(t-Ps(tmYxEYA%OY6 zTu93t4k_*z`ke}%*6C6r+?}o*wEIq&Dcc6TOFwGA9+#NhLaFeQiTKE2ylm@G*WPU8 zPhg|UW2J!cCBw@Vr3%kz(eD|q6ZT-SDKnC`FbRzVt@w7~FdgJq^s6;@0h!~P(2bS_ z@9$X);O$)>vwfQ4d%K9ywdYpg&wLF>#~#jy2TM0vMAck@bI`=JXuUKpF0Cc8ZX-dZ z${CK9(=ua51xFwJo-wjJy=IcS<~CmsifZ1*JrH_9q1(Rjj#m_k^3@RB+6TaM-MAoN zE12bHftmw03Gp5YR{7rv?&X<_a zpn{bn2#*q?+S4SwF|oC>sIci5pNZ@hK;3oZx-7R)K$@xh)-Ww7L`cLemq2Fyqx;Qn z-E~jIC4x*DF|b?*Z`NGRm3v{t@_qT6@@K=uE2hjSBR&r7g6EpH6f?qcAHxwvq76X* zrcvm#mDUC?4!atQx)_de>}ALIK2W*x(WvpNhm&HVo5OKgzjZ`2a?NEqNJ_v4p9rU0FJ`V&XqLl zD9k4u4ZluVM?9Js@axu=NNBDM1JmGN2{#=`_3CE`U%Nf*+`OHu?Fr#hdc4;>R@f+mxw)!j;ypd6&5u+* z5+}%^!n-ZY68aV)8}=cE2YpCS>`2jmhl4|oZm7pKs56u?3aSfq-?e6)i^H!X(eb(Z_;un?HP;b(%*hiM%FJRdU^EO9?YB$=|PRElkSueBMoE8G=j zn4MthJ_hxt*s3zIy6JG=B580qf`KTdbZ)Iz!tElbOW?*~ z@dcAz0mAI-@#+%CQrJhOcGrU)-efI-sK|uZUD#D^yR%0gS3th9zMRI{{&dZ84+~Z2c)3W;9!<0NPE4O#kIt%viJh~me%Uw!!c88F7^^Pu{sMnAaa`K^xlZZFNFMH^ zP|L(Di&Lq3&|U7lX8B{ZY1(g2$Heh);lzr8d_ack%O4|Gf>?U%`JSrX`<+S@FZDc5 z=d=ZwEzJD+ReR|=TEcSby#)>xc6iuaY8UDto)&;zegwC-f)@LjBhlb#s?(pp zKFLnyr1yK6CiEzLy-K>Gq1iRf>xR2-&1;#TY0fMkdW1q4hHh0mrU`Ca*za1{ry1RE zZR+*mOR`S<6q)dt)eMQY+8=)1{K)-kt3IGeC_qy?ez+55sSD$9b&=d)CA69?=eiqX z>XS$*v0=@7HdQM-_@Yip{F808ZdR@C0?gN{MWt`e6F%U7`>u_ZEAWMIk3D)~=^}Ja zj>QB{z@%W$Xylux#lx6YN>9DGDMOO1b3T2a5xaZ7mGfKt9hVwp z@u3({e#Zw6@!M!1PK-T|qm@wB>06ahC5aQJcU`!KPn@IFXIh>_iH|nEw}I?%7ck>l zdCKKozxKpmBr2;g2w^#;eBa%mQE*qLn%EJ0^!9by`tXIYcq3~V#kVaadz4Mhtd(;H zS$Pl3EF#(bC5zz?w(NmC+|&)~0CYoU%4aP9=IRa~8d6-0)Vs?(8@ns z*Be9_z+Y-oaikt37^-67Wp-!_-pEJ&rYo%Fz20?JjRAF~wp|T*HS;ZuOg1uJwC?p| zDdp)hu2-|ly?}PF_0_mHe~8igk1JV@AsY8D!ii*K1QgD6QrFK2gb!~NC3yu)1$$wC zjt+zGuqPQShNb!Pf|rRk@4WZh-Ruz|-YlgyaI7B>dXDo*B_WCe6~TmKumir8LrRD8 z4r{k$^cT3{gK%#=?tgr}onm&s8nR{lh~E=;g`63fTBDA&eh^V8g?s%uxD~c9Esf~TG1~;Yxr!NSKA!(!?)d1FV*XYVW4I~pWKBYT~chHN@U}S z2j8>Kw_(wtT+8)FnBs>i*eB)-3BOzy5)RlgOmD3%$}s&Rh|yBL8zI#j^?eeHmVrZ> zgG59sLX9<#KAC$^kGESRKUmw0oo|~<3T8TmbzIy$#?Qsj*t$UZRbsx~btt;wTnzrn zzlqf=k~iT)u8Ut-SephXNkgyWmUbz;2O^A2K`OQT)$U70=LYRN=ki+`X4#kD37~*h zh4uy*pcaoVuoWmaAn_jtd-B?|x!>&=kaVYH7KvZmrO%c=NB+j1y6WF>B|aa zmC6^`GJ3mYnpQpP91jxts6u!_XP~#Ajb)E+-K?U?KVu@rO`+BVr#2tgSe}4{=}Yr@X5QI{o?X|B0pC+=s?RoauSO^ zvkUIP@@pkQU&XrJ9%^Pe0Dj^G&@DO_T(NJ`U9%zM8swpOIZpO(1GQD|dvbp?Y^lJ4 zDAnL2@^I_p0$;_C4DAP#-GfcPd$&7~NS`#P<&=?yILRvPS<-jK)kRc-iQ)T z;qROj&@Bw*^=)2gT%6Z2$TkxIVQx1PB*#Xo!W(HA?K{-q0Tc@{6;UF+-ii%=LWm$P z0qhM6?-!f&$_xUGdz!deRHskPX$GTH21PQjBZ1h-&*SU+(r?L=CS@qT?UW12&KA=X z$x^q8!ZXHG&#K9Q_Gr%7lCeooMOf(HR2$gOL*!zHMp(X2>TLDOl25q*=U)st+ZqQrrur54{$^H9z^p1Cy3|s^K3H<+Q79#G^wyzO53ka5JVtu9Ndr;Et@eXHz3L3J5j2UXkpT~+TIAEE%RdbtV7+X#b2wU zJUs_`^#kK2HKzFWKytDVRwqObXLyJ79ArDwow;)(F5&~^mCn3v{8^1@wH^dy2u*YonJgPm#9V6tN5I_{R2`@_9*^| zfWp^m$rYN80n4w(tS$}9CXMEKo&4t95U&xQ@y}!Ordpv8p^R1z_{pd=%rCs%eHUWv zCD7vSBz7D75;@b$xgBAt{_?G7qzM+6WMy6aYEiK=2UYv6dGz}$Gil^Zd;yTIhsuKB ztisE=Nf;q;;GTR+g_WQ21KItS>5q>0895N+fC6!D$1n_sNL1EUzBk$BW079cFCWR! zqK2e;_42_w$*o0LQHnT2l9oAn8-@KcC)GH?6TV)f(LPzQay5SZ$)tDcUq9&+t-+7n zv{N_H_;=z9&Fagpt?YEFzY?E;?A|nFo#+cW5>+pw<#h^MdkcwqBhpk5PRD@$E5l1Y9FBX&Y?;_KitanW6JRfS`7CoR9Y&D}d55Y<|UB4ha zAFX~91P^A(Y7iD}5|MF7N*toiMC~ckpQsrTy{|`JnC3t9crKwP(6&t6E@E$}og3G% z0I%lk*UToiFfM`0`@?HKq;I`-hA#jr5wR6E0mNfeJLwWai)#&PkP-)pnm}>0n8|rkYu--+sAF5vB@QN?uG(0{)#i z#*?*vTbIP^8N}5|&v{F0k{O+~mSqivu_%`JQq)HlF3b@sHk{cDg=QHKiWVx8K4nEE zR;hTpm0=Dkd3^gmE_)(|_Ao@(UOrp2VBRw~En`xZmAQ;4Tu79g%B1$idIguXRk?c{V*UK|!(FRar3h zB}R4c9&%1ZB(9&(av}Xfze<)PEJ%ej_m>z)|I1H-@SM51UpRjmI$k`q;BB!*npoZ< z%pU(vsME-9;LvX*>x?@y{WNpD^xjVj@igRpD9E@|0YMzh-%m71PI?4vt%hdtz$^(d z`&nF^q&Bo+%-)wF5Z8+pX!f;-OaJ_4ccx@KLWtP(u)?r_@pnP1&rTb?)PQ^1d|eCl zh~3)jp)c?g@GEjs%#!3qhVH|hkjm)iW@t|zrBkj3qPszX)FWOE;>kRH#+AT2BWYZ- zJ>0x`w~<;7G~&aFQ$vTAW2Wmm(lijF0)V((qobpP$PrOzD}et=P7h4-aGTXo6~U~| zOnu-x7K;&saUvG-nL+%Tfq1=9pdbORPY)5J!KB-vTc=>Q|Lr_rG<2R(A-Mt-7??L7 zBFbDvE#`6=H3z}x>BJ`FrhqjG_Zu;zaAN&xlk`GWGSL^=;9mMSYZG?9 zlWK#JXL6npU|TWj$9=^C_OX&hg?f?fTYO1};5Tu$z$av#vfpBk;o^RPCdyRI{s8 z8pop8NPoI(Aoi)d#2ERshKQ!W9G|?hFPVJTt_xHa{m(NT9{rAg12b)wO<+?7!;Dr9M@60tFS7otIbRn6;C=?zzUR56>B>_CUKjE#A%l`*$<{ zG)?eB>gjuqgw}q0g#RjrSn>6bnY*5?!N%X8`i4Ox()0GeLe|Gf`Oty3A@8$w%ME?u z{P3;_?{9yJ35xx>)3B`s&!;yj^1o&fOUAv%0J;lY9YM96V2?olUk|EC{TXgH8+G*=3Jo{q=7N?g{B3T3IkXyZ4 z?de?o!k#Z>Mjlnsy}@&pK@31CgMt6F6a8qH)+cxDyOCwP+EaA}>u0?w=C`dU?GY+J zy$?9l;=~_{Kr6kZ?XwTolB$48RkJuUk9dE-T3gs7kE?mjOF-dW0bBk;l*)NjaiWNG z8WxOx5cyi@O{36Ek}77>F@q8ah6C@7U0Ah%-!M8m^7l%AJdZJ@S zsR#WIUN?izalzvkO(kguTG-2m;pbY23)9RxP&+Li=0%gqWke!>=jS-EoCMTOw#8{D zDP-w|8*t7`R%jfF@ICD>IKUUlweuD9)YM)%Xhl{}Q=a*$+c(v;wY87Yw}*hl%>4kh z5k$q#6XgE>m3M$230s8%?D#Gwd3RC)4KrHCfQ46 zM=5!N?Q}yNISpr4h1z+srAa#xp0c>XsWEe1I2?*?`Cw=k|F0wg6rk6`{r(IFR_XIm z*m+5lVZ=xZsHl5&eJF{$}~I=bh4+X|E@-C{`6pV z`o*?|1OLNvUQCnqUFXYcHrS81JYMXGoZIl&oQbgL7o3k%xr;m`TV#3nXSLkq$YZ=D z3+T0AmHIN`Y@RiqtD9@uJQet8Y40`-mnCWW=zigm6C;NKO-VZftfNxwTsHxal@L1{ z_hB8LV=jD72CD$;9}?HQJ^OtN;(64iY;r4jBxR)sY-M9PK0l+5$^$|a=;li^opQNq z&7F*%Y#ZOQC3}#5(Eaw|?+_j_XerpU zGJwjy!mo-3tqFT>SMcB01Y>TTQuCURjbAti$=e{hK;17aswbhGb}dB9S+l6!70$fz z$%H$6JX(?P8z9{M9_b=&zWgg6uaHSwtU7N`;;*J1MoyDe8Jwk>(O{kl{NPRxZ=LB1 z*Xp~=NkDYvGV#4va|ri<;|8}`1(cBudP5L3W;p%cgOvLrRdxqiD*|HFRbwU0(_uL? z%qrb3OX0zyXckJKB390+Vu~-Ik2|zrSLYO$KCg1@ooHGa6N<6Sb4s|ey&GsIWZRSy z=UCfNkrKH(6LBeiJ(80L@Soz)#lDIDS?o+Mfhl&KP{l-x&2;or?S=lpQbPw#o%Lz? zO!>LU!=?V-!-@DXwER)>@$pvVe(UNe7&jkSyJdv;+N%bX#t*6Ng@;@7nV$=McZepM zNsC^e%%fmUC*8Cpw{1oR7tz8(*~lUCD1>%v?nX@t^yw19c!sn~{x1H0&`mJzon^=c z!ZPG?(}9jZ?Z7tuovO<(|Jj7%&XsEeB9w{AUrEPB4GTJ{!yk3vthG)u4|56^qOCjw zoX;YuEg^O}Jxh;e5SdYzUQtSJt0K1!I zFO;NuBRRQx8IMeevvX?0`I|!NJ-<+GMq{+&WO&i|Tgc_9kBbMZeB@;&V}(EWA#nSV z8BHQ^yByI?rVNJna1aFgJan_6I;Bl!w?2N*jwL&q#!IwwUMu8-tC@%)4Y(CbzTg~Z zjz%=&(*u65N&?$dweYoaOrgq2Ozz^YLVL;ahx0wSt06UH!mHEw$`40d9C=JIt2uSQ z6*wlFT#R}%4~yF11lJWHf>zrf*S?jwQ_ITvzk2-qnyJtbMF;OYB$;U0$-p8irhjO8 zQVj9*N8BHy_+?xi$3V{{#tFymK`$a~3zX^U4YR_9f7=N5PKxB>vMedm{Ei5$PxATR z-#T5{6i*ObRNYMmwGTBS6((zL_ZFwP+|K%?MXx*s#%gIRvNVpV_=nO;l7kR_coh40 zM#E~*i;nFn+q+|l7ER_Br|MWUU2f|&L7mBymfPIwURlV)3IF=;GaUqe#}TFaI9HL7UpTsBVO{VO{VuwkQ`r;9%7MN|0e2%=+>S z8VI9P-kBpPE5i_e+=SbRbi`56;e1GUx8dzApCH>l5*(w!gzOV;o`=FFX zLgwMkB0WN2*34_*F-HpoVou_Cgk=0$Imj(|Wl|F9EFbACh+s*{pGKoQ81hK&S0^C# zYwf|fZrk+tS`gmj9`1ux)F~(~`}}J#vuex@i%@d62#e~FL5cRO`r5nG45zUg?SA~1 zWD>&c&-H+fPVc?Fi5Z@{8v7h0&$!vc(e{u>w7xC~f*0Nd-ewaI{e$UtskLEkWG=bT> z4KGm81_#SA?TMFkK;dcr^*5|91Zk#`e$Z9lfz7@wezx;jYXYhk8lXoG`$ID*=uLzh z=8mj?(kcc|B0|aMGRqU}x)F!D^6}iZi**A*0vhSueM?s*_!G+%P*o7TfRlOL<`BZ1 zwXkN6jSFk#g!BQ2TU0zwGq1gn1jJNBvd_w-)r~x0!~JWbKBYlD+GBLbiM>EuP_S~f z@I)jKkQyY8aldeE!{Wd#FFmZV8sgiufDCa{ zE*cSeuUTQR@KQIlm{r^^D!=vK96=W{=%%kqA1P1pXi?V8Gw%^6EA*0npOtl?cin=` z(BG+^;JhxwutHg2@$DHkFL#tk5r;v4oojw%fz%1{seuo@=y@Vi-{4D*;h8hAwoKU4 zPQ&30VX}OI8T9?!Zm0H_j4(gH{$9@{+CHk#>*7fwde)ql@wfFN0A}$05LlP8Q$|mT z86n!UX}CG!m!qmbE(V+W(dTxk?y9qH@{rl-PnUW7qoVvMP7>S^u70wff*4B)j(I}N zs`zXc-7|=Tf_t~WzUs7V9)J~;vJi#G$jmGJ#5DXn6wS(n)gua?;**=%?8BSDz^1Ltdzr1jd7vEIJL+@gPu(DUfaq?>63Ady)?*p9tV8^2`+LLGQE7VJS%H*(4Ntz zX~F|#pgU8L0tx-EfH18+gS<^HWU|iOw}19z7*|4#aQW)rG4PMB@eDk|saH+vni(#) zEsw`8&wfmrpHolL{QQ8$jT^~f?W5)kcfYSz%=+{&=on5n*Q79-A z=!Cost0xvbnEbOl*l}^c)hd#)RjTKa**&JDTW3LDA^wgM`A42LDqB*XvrJjw>;m`K zBZ=oqzPE51d;|IQ<;0&Le9E=Ap&4e(o+Ao@#JR@F0qEo`d_pgQgA+h()i_4)6t8}% zA;2#iNU2XU8{(b@@bmCsrhHU6_P9zb@k=XHZORGcN_@`yoF=52l{mG@pn|l58=(wGFu6=Hug@OGyd^Bgz43+qxZ+2jOe7@+?4MctZ1^AIQWzZ+ zzm60QeZaJFMKTd`Ovi6unHDpaM$61u(I@9>8zXt~j!P<}CApjej}8A@h06XW3!ON# zq&a%Tlmlepy(y=dGhBW*XEXfM*;li#NEKK=R#!>={r$I4#RVx}o-o14fJXY30wBFf z`X_s)Ev6F9uOg@x3aM9Tgd3uKZdf8ehu9DPOkltxBI^1vQ&sUhwQ#zOss0d<`Xn(l z1`O`Ae$^n$!`o-;P-U0AD}0beQ53Su*cexk2H zC!LM4XL{l|aNiWJIBa!GFWzj@!w_Wt{M?~h^I4%9C#OWG&u5`BkZ9%cA)?Ra>FDC` zUXd}nwO2GSnSxIAGk3K!cAfc!!+VA2c`;5SzI-q%SMxalFyfzy-H&%Z zr)ZD)v4t(F0~0Hn=@giyKG!byk;i0H*>3#4_DR>ZA01}zc~oDJqzuARUeXWFGV-s3gLWTiWzMv=_3X#* z-2s<{f2j}xkUiTq-&BRgK3_sw_Ub|N4BCnbY%U;`HQnFlQc!6m>4(eX_ zYF5yT8g-aJUH%!Yd@p$vT6pv-zd&v@#<()Jdi%_s^Y zY4bA;iMWc*_6L;@rcciMd2WKPIu;Zb_>)vM_LRYDX>I{x?S%MMZ9UfsUuXjBSoC{i zcvVW~0JFI@(vy_%lRmutx{>~`J0IXa&PRJmBd;MNz4ym^PZFIGZ#fc-cXN>bkr{x} zGQWMt01N_UsuO^XT+ti(qYm$W0*rSzV0vx-dnb)it++(58tG|r%B5g;9p)dz$o^mo z*tvlzGGMi?p77)kdc5uHVrHM|=^xKi`^A{ue$vO2s`1#3f@~=$e=iGjknY_;&pY4l zdUbO$8LaZZ_F#c&8|m(D>FyGw8|m(D9^zZD_c`bN z_5BgAi^W>A=RL<5_n2i`2a=zv)xpqBcr)xR);^=~uJ~Wmr61$=Qi8B;@50vwR-S0l!^?ZZlS##Ho_&p^HI- zyZ(83JJ1-a@#5`k$Lcts?&j-imsGAV%S=|A_9m*RxJOho>+msK^30F?FS6>hvb1o`}}&6VZlHfMw|o>9Br}rU{5Fv1#~7Om0VQ%Y|Dl*w(xp@GZ0Ah4}vS z6!2&=?i(W5N3yA#PJt%2%#>+5l@@L~-NQoa-B?`k!arklx^+5MvtvC6hN}-9gAZ{%R)dNUvgnf3yy!c0stP%6348MW$*xhLfZjTp192e2836GK}8lNFLSQOb)Lu; z78U@u)YjsDW%7=0y?^oo`VFWhuIhYV>ZAj}FY*|Pc%Fco3Gjp+gj~4O#FP~77M-&4 zMC3Cvjb;Zj%lS$=SF9@oGqd9V!!X@MB;O7oi8&N(I2}v?h|fq+ihRR9FVH;v)*E2| zROSB|mHuxXDc`Z$K4xVY-Un#1HF02tYra4RZlz`cqhk4A@H0eI_$?@^j^ORqSh*7) zTG?(TUH!k>F91{?@X1hBUXLNyAEUULG5P-o)?yT(16~3^WZ#_}TG1A&?Hw zi0Tw%s|Cvu|I-&li74-50i^-wUaZ+)1FW}n__ghcVOdRlg1T(6Z3BCbzqxW*ALf7G z87~4g&@U3#{x~r*;J2goTB75Cs2ccxX($ zce;t4-7nylR6u5Hk^@0N-U3Ww}S$^uzKgo_S?7ykjWrT;h-gEEIq z-moR$l)6?`(%o#GM!NRat<{|HVqA~0k(zlJCpdgZKsGx*^mOA43pj9q%F#uby!HyH ztI>uHfV}_m`O~g= z27HAIFzN)FkTM*Ns1@TxO#sGumkc%7Vv--%BxfM0w4L7~(i!jBZ1{68lNXP6ovBq_ zW)$*SqprUD&Kq{(h@L+GCsvDPNcEh+ecq?T~G@5Pw6H9iHOtQ|R~ z`Exf&R|J-%r{`|4=FKK6nQB&R@b7Ym5j@+_2-!qJB zX&7{5IOchm25MCP*$D=ncj9&1m8X5}-NaUizfXbBYYtqnYbK%c*IH?k6-!-}S@EUE z%-f-&JFN}hiKx*w4n4K)an$YhCYE|qioadi&Tu2duy5Wc0@zHnkehF&8)fL+J^|k&-=z6CjTlRV2hVQl(75S% zU?^N`=o52D(PY>THqEUL0Ya8pzwQIlhs?lBf3SVI3fPN9W`*_Y* zQE(uGJ;18_SzpVL#HpgG|LQizVSoW6un)JwDeXBRlVhag9M5Q+HOKp(xL!5p#{q1P zh2OJUjP${iT99Z~X;LK4H!ienk2QTa5`TeYKiqEbT>m*8wUIR1bxMHu82Kf(E!fjcsah>t_GtJl|ILxKl&{T0kr^ za(ESqd&c)-xFyy>y(t(NVF<+5Pz7t)UnY`?@3-k6X5Edh26e<1zo z@X{E7qhzU#g>uObJl8<0H69}pc{#83^W=OrqP!iI+8=MAfIw^Qd&C6IQi-Qjv|3re zS;GeZjHJWj%q`mn7jl;miNs&rA(XYWg0l!hb#FScc8rsjn;E`&p(a;@$OO0z(|RB% zNF6g8$~4C*i|!Z@-CJRAJ1(*rb?Nape3f|_2~x}Jz7>PLNylv$^B2o2I5?@k!Jz*f z1H2G%-c85pS=rgjmrR6KZzxG7;=H3e^sr8o?y<;X@nuS}#g_K_6gO1i3ISe<9C15~ zm3SnwJ4c{*bnv%zTRw|XIk{cz4l7ObW)tOg$SpZ2D|zAo&s85RA*-V%JNc~4 zu{1hx@zR;mZi|*2Vhivf7HOw2$n9MEDXSQBRWsR4pncraUQ>dyBt1{F#Ly2Ew=qha z3|~O{AJ-h6%k_#x%k<<|9QnDcb}ShZwn0A2H}!XxCt5o9W2Bc2g1319wQp_JUXaP~ z2_Ot?DZE&u4cZ8g<|7)nX!IX#c085MFA`?Xq>fGBhuEi`)Jh?oGl!d6u;dJ&sF$(OZyF~Qe;tuZ0HevU__S~}t zy*|xHdcVX(pEhb-7C8gW4^TM896}3f78B*HHFul$AGWSw@SZuPH%BoVY}s>Xam)|! zJ-KeePt54Vi}cI@md47_kOgb{&Iu0TEor)&2C6EYUSU7thyZpLtQv{ z_=KlSGEGgp#e0-{Ip7Kc1Ewa7?%913^BZKhPJHQlA$DvsufFh#JL<`B@bbSKn&0b# z*Q;%;pfsURp4cjI!`7wzC19B%4x`Lah?eP!uI_oSCDbgMTlkG}k# z1@rfI!n>ND`IVn{hoA0xq_P}V)7UL~e4zH>46<5{rWp8r7W8^$H0tq5x0VcUJT;UG z*TwPW78fen?_S9czG2;viJX=YUfUlpF+&W8E** zNcwD1ovWe_uc|FBM}msvgLwcK120>Pf<7cU#>T)m1 zaevWC*k_=ipzQ6`wlO%%_*GnQPy;j%@HVty^L`7iBKF!58%tm+i3+C03-?z_L+NYb z?JSX7-+x3IlE;suI6ar6kB`x|ytvveYe^>VgY%p^dhlAGh#bl8JA8|6*Z%-@!pY2J zAW*%GYhC&>5bbRWNbkT`&1(&(N{mnx|3$l1-xP-25@fcMD$vUw|MLIy8~-c@;R8AT zqEY-UiO(^Q()IPH>T#xy*hlZsL5W)qAG}s#Gd;KopBH?Ygm1B!J@?q|Awc#?KyRnbs_Y>^>C4U_R)ZpXL${PL@VI=N_LYhYMlbf3WZj1{o~% zAg7Ls=ez*(0?@Q>94Be;za)|P4hD4yDeS7D&f0n6!;aJo&J1Jz;_x~Z=oAw|RdWp3 z>4a@od;%yL^a$^}5zGwyw0_}jB^00Eb;A?yAv;EiDs6kHda!B&z)g(&F1>tC#p%#f zRzCd|K)FbHezt?KiF`+~-ulm2kYj6{);=%wlFX7p zl`M+aEtEst|MPNl)f|YWB~x(Xj!!3mRG_}uzw{zM>}RZQ z7?RY!BBv?b06$zk{Bp4cmI(WUHY4~6j#WgWgJ&aGC^GcNESwtd&&D{;*CF0Sq$#TG z>AdXh`GW~n*`@2YzASZmN%5k{sMSo+^G6npaG~L2A_xAEt^NyVZ>+An2EQ{U#Nfu| zGx);DGX-_7fQPTY_RH`&oeixgyqRS@)S)g=??6!{0}-fExq?S252oV&efF29Fm!3l`a@WP~v~ zodd1@JS$t{T*>&GI-$#DOX~&Z17ttyl)LmB#+B*ru-uILhMm=D~j$JA70W@vV2p4%w?9ZUKe|0kUS1 zXabu_2EM!}po}i$F|@jP6gUydXzIOS(quS!P5pG-WOs;2SXkKYuC0!Wx{Gxy((P)V z6wIFw041YCDqKZsFYo7+bw>TE2Fp=Dg#JD-x8GGg9q3u){OB_pQ`0T|ee=(b{TqE~ z2=l4td&vg{rV}`%)x+e>2u0e3qsV|tQbi^PFTLahgu$GyYoFX&!?jYBme`L2xD=42i~HMwdiL9+}vXY=N&eFR`F3+>zo;;2oM?g zui#J{!YmCF8ea2p`M?z>uuhc5(w|?671Rlz@L83R&N6-MAGJX2z!c_OJtJ;i^0(=DR2quUjgEx8nx_@szaouB zr}g~s@n+;1PiffIgI;Xg2^N&IAHXAb%DnE?A8KnFzwkSFcNhhvN(E~Ab#ehFLr!wo zUzYDMa$z9hPMf0;h_pFbjWa=Cz0K1FFl8O4jI?DfXL)8#d@X)eZV?RPY)=$4_ws7z zv->@XpOi?!1#C~fF5abA(sB&~a#P=XGby^^zQ5RWsOzaDN?v*|e_}YXUYV({M>0R| zR#yJrZ0X&{jIkUUc)R*_dW>6BZa{JyPXqH&{j46Vx|@4B@{B^|=jTc>Ev5!S>K#c8Stb3RHZDDZ$((sAIQTV&hde7M3?Q1Kq%4kD zZvAQi48@?=WWua^{MX7*5@B@OR;`p0?x6tmJh};qLJ!vfrgI z(|4w_5J}Z0n_&aZ+XX8Mv&hK^{#&%5GUNhPKl~MNo>AQoZ^4GY{*gZe;%Ucsrq$%y-S(xgMI3E*y# z-D!lbIUq;{hH^_uBET%zA$SN(zFbjBUup;ZS;V?93X^d$qb3{{wpZVgep zH{(+Xw(rCSMOFLkEE{KKIRg2aXpY zlgFpvsKg==H3)=NRVNOmTC?*^B-VyeR!l`&t0tJg;}ZC})0fBmFFo6&Uq98mf_CS3 zSI}QNC3kKB^%KGek6b|PXu*dEC+)X@p zTdq&7hl+2BYO*=s0fpw-ple}hWzuKkFD8KXLEu~WKv5$2J)dyGdfT9DUZWmX;NoZ= z?AwxgRzxopU|pj-q1?-DsOb_b% zU6%&GGDkg*Zz_Nc5BH*rji-#{=JnnSC8%L~LOOv91NVQNYQ2P5oCduK?v(l?3~ZA3 zf#gr~bZ&@lF!;=dr8rrHJ8DoimPW(4P8xdN!S`h+`TP+8yG-I@!tfJ<8&8~AL^ne> zw}6x@ne|ii_WR_bFZ-~o-nzfY(d&hkFyJnWL5=R(sO^XM1AI@5>4Vm1@jN!#E^pcY zaL6eexf+24TkTi#AMOf7WlHQ(_FXnR6G&Ha^Qt()d`&+uj_UrChq9MRF%raY#<>B&B%T0jE+Wd$71U|5A4(LYPA zV`USqc0NBjcz$=Tlv;K#?-j9{e zn~MkC&V7BehM%>MupmJMh=q^P_#9~$bNTz6sJ+()a3Hvp`WX=alO)duiTh#2n$A_C ziMG}Uk;mAHrZ4@}*3z3n}z(q*;}d|4U-O@^BWiyY$QCRiVo);kh+% zowpH?I(9&c*M=vimLa+blEx9>CTQJcUnI<(nd-V&v4Vb;e*dQ+vgwh5+@4CBVch05 zxxDY}frUeymUmySSpaTW!0mE378J~*o;YR}a11Ran>oeFl4_`jvo@fFo5LHUWIXWF zh7G#XMIe+%vT#{nwI=l`aem^Fq@v2xoO1O@K!&iNYD|7M34z*IuRYsZP6Yg%+(-FM zYrm;v#1yE}s-BhsaI&b;%|0bfqQYgnl47Fvr4GJ#gqEJb*x4y>H(`ew7LE?pkZbk2 zn7BB$j^7nGG|{kl<7|*Sqa1M8^gN5H)7+>CJK;RaJD#(+9%!OeGygAxXtI)gGP zq;>_fGnQ*@tgq^}zMQCa)-{GzIN7b=c~Ol++VOKiTL&dn#)d2}d?rfmOtDvlJ5E4m zkriMTq5I)xOOE*2xk)dTOTQ9dZpynb?fx9@^NxxNdVGRtA0uJbcqIR3;|QnAt~5kR zMDb@09*^$FB&l46sLF0GzGiqv-hwBghUhU4?t{N_dNaSLqZ|2Uj}3C0WcSkCFePsK zCDpZxD^i8M$ZkMNiK@Tnmj37-ldH)zxGLjg82{*adHTGU;lzokQx8KHm*QiSDk+NJ z0EpwFWA+R+6$(9QcGDDd=fgDI_#c)2lg)NoJp4yyFPd2@0}+)!YmZm=|H+pdSEV$g z(cf2l(an}C`KCAJ`uORyv#O*)66|t|BZ=SADM@O5Zh`n2nq|lw-?CppI%Gl z+S@a$f*GfYlFYM17Zt=G8+$F5>5sZYXSp!sC+4_nBTubPZ8pSw{WY}9J*=~<#rYG-A`MKevf+5azSU=B zWeU;=nyG8NI~2||3jHMMI4OU99ppSiN68j$P$417B4th^N^+KKwERCU1F!hGGwE-0 zbxYwqnBA`V3}=_2cO-qM?BQcSO(~q7d3pJ4fR*&bOmPpY-)ex@D`9(-7^6cx*s&Ap z*} zml?YHgSCSqPezRLwA9|VfuTOeedYd2Z(*l~rsqh0Uqfn)6mv>X(@@*?%gZ-|`Og7J zh=0#~UqL_?^6Pbo=uJNWBr(U=tkl+_gBSUI|))_5LacL zomr)&)IRsUgo!+8KsL_z9#3Y8@=5>a0<;%zIjdPlr}pTmED+4=tnhp{Xa`5h^mfW& zQfA$WCXr0j!H{|<*NE_#fb| zX<2{d5O39|KHe^rlufe4HcORXQNG-v@vc+`v%8nrBw^0yoZPRmuOGOKb*xZRY`8u* zrKT0P9(RLkAeKx}KS9=Hk%nYMBk{BR*ib-wZTL2)sy|>diR{54(l{I5tQ2j&g-3qN z(sX{xA7+{Ld99+isY2|YR`SU!;G7Fxx;?Z{AyraY3+M2+O3^+)cFw^s_zZ(SZRO3i z`YUu_@LN7zE7PZ@RHEN&Kbw`voXN!QN}%oI(92LrJUQ<44*J$Gx_u_1Kx#h{bueVO zv05g@?_dOS%H#fo*J6fc3k5q2g?mTit`R^b;y~VbM4S^5#z-;nL7nQUP*MFC&jQpD z<_ri$5TIC z{o2ddMQrR=vw#fgo2E1+DCg=gScQ@r_+WP!iTEXY5-nVorcqnKr##0UnT6fw?)x}9PGfLz42KFp?#=YV5Fih z5sCkE0Zo;GZLFl$TzBU5_Xzo^9U=Wy!1Io9SJRh}xCKVx z5mzgktUQK0LG3ZN3*DKFac=rHOn>F7^&3L<8wArbB=Nb0t-19=4l?|D;mSvKF6$4- zEQ{7m6oZ0>kI5J6CMapai~36-12iO`wiXh{ntdf+kY6Q82cy!r-JM0~4))Xcyh!my z$K9{J*v;-;$up~_2ceH|w$_sTeSQ1QK5!?@t5SoK|G8<)lo~oCPa^nS8gTxB>Vh{QiOc7X*0apJp*x@69*&?uUCFlbKeoQ0C8uCJ zS!{Cw$Mr67o3;xv;3kly-H-qz^+44fR(uzwR!ffAv@)2CPoBE`tE00YvsS|_moeAQ zi%vd9e{CFKi~9kEeiy~vaCWD}b3q>-emU@^Os}%=F;Kk3vkjN-?@!B$=&;={JGkj_ zC^^kq7R6lJQLo)zE?Tf9{Ak-Lt)^5nF>bn5IVQGb9o88lv_C!U;;t%8EK0N~S(3b0Xi=xs*FPIIe9yPFMIPjpvPeN4*q)A>G zH}^&M^De0f|1QqT^9&5xki+qdmZXQaWIr~3?VV%9FY5gzA=>IQA!28YUoTKrc>I8r zf&81nabraa+kC6f!FVJE2;Qj75`cDQ?R02#)gOF7;ItUX&(k@l?et6w#}*qNoja#n+)%Y~PJ(T{VOMGwe^aF69K!=;M(7rqYZ7C;gW+UZc6*~?HFv0@k)*ky8N$^l+a1WxGpQHngkkLk-!zEsPJy4CuJKuJi`f zVMOqf{dkt<<{L95$_Ie*fGdx3*!a$647|paBAsittY2Q%w8Zgsv_ntttDcqMa5OHv zjF+Lt0aL6wFSjq<_;F7;>0*e|h$rClhz>}DUU@y9-#kF=n`4VbTBEENYXXmt%QpT{ z0-_3Sh?YZ*v(mw(xiJ>k0-ofuE=7TdG$9r5nZCKd$rGy3F>MV+>dGjUncXnc*Ksvp znf91jSd?ErRG8xcmV`;#HXA*G$ucE3_5@g1UvS!;lq~7zGZGR4V-4yZ_4Ei^D)k(i zFAP_fmT2N$bRf$~Jv#Lu$7d5H+VrAWS`uvGXcQ05=y$thqE-N+3UD}-Y&=_OO#)Kd zQwyY%#@tp|9<(LYn6n7Oa(^WNgr6LP-OJO1G(Ab^yQF2r5;8%h+_`pd7D+2BHW!v? zclp5Nwk=2LWo|af3plBU)2uVRY%<)Rx-!gyoeQ0HzVc`JzC4g6X*Js5b1d5lOC7z8 z+WN$)c%oO$r#XB8MBQ5gZ^j1n&C6>~qierXQc|W`5b-#_%8wUN+*8rh6Y$wjEH6hC zjy|#~8zj=PM!2tmygQEAXua~Z4hGYm`v08#j~3ump^xpj19TcLe;@Cs_k5_H&gE#L z#0*+)c07KoWTppf+>nU9J(G!}Mb+9f=uVG0#hN{BvCdps>Il-z!otAL?mYKzaVdA6 zbLYhXZj#LDxKaDN)J0v6erH@wsk0=k1xmBHsqf=}P{?0oqTkcNWM)G|7T5k+=CyzVxioW&?hu9~*{Zi7ke$~CVqv6?VJ21xHB{?H~I^znR@D_wi zvRb4o-O%0^|$3%iaD^506Jx${r)@>))05)-h={emP{h$WF(ef@fI>tp5D@lgjgXY@h`M z0>vHP@N^K`>gi=&|LFW+!VOaf*_85-_T%*?m=GmOr0MLmb*NtN;c5gkEx>t#@uDC` zGK)!1{OodwwESvZhTl;vYGuPN+4mvIH^rs-^3tJA*H-FC?iNcRj{jt+TuTuRgI+uN zvc=QWlc8BgO${TB-8xnmkes|pop(37ds&(RturOvqOM|a`M;!2V-nV+AJ%gBiQ%La;b z8=c+r)5mgbuz8?G{m)0VY4Ra~4Ke?x5HGj@VdS;U6YoUU$5Z}V6A+_hGq|LVn9fpz)u^zI#zZ{SRyxf6iY}))(d0r%=XR!EAtL3I7cn)Z z@Vq+lC60RbpQeH)s`Po+QPLQJU!7&+K5e7cs3e?i?-cN$1^pU!wLg(6{NS@#WBlfg z+KV0{_TOUmB@pugiQAj7DYmm`oq$LUjJHg!fD2_Jlw$4135vK6-Qh1?quuNCU9Iuo z#L1=UuOWHh|BBl1pcX+DkW9f3I<9>Sx2hRmQO-G*PH0tT-6uT?gWVw8k_B=n zi}9dL7IQ_zfeL45Xa88T?exCBee;ywdwRG6!{hUaU$SYX(;)&MAI7

A=aQo0vS9dKH z1dJU6>Pf~5hEI09)#$FN9c;mO^QhX&a+10p4R2;jA&W$GW&uF$6{hjKcxT0V!5RAM zZ2*Vm=~Z!m9?~eE=ZCul)K~!zG|}!)Ah~(dj#I3Pkk5lPauS*e#O>RWiD!urO^|#=r+8GK zLpdCXSr&;mXu*4@uH>1GN*Bmx5nQTq^2hWpy`7Gyq;su1EEpGNe3rcOM^_wz6(T!1 zUjx3t#k!p;%6`V;Ew`R_^k{op)cy#8@6b)Brr?fv0qZf{pgURFTJH^->E2ef{Iq|2 zaq2GqZxE>UKw>BGEj2yFUG%NEOoOyRKiO6UNr53I=L(%S1`f;=;Fkto=ueY*;-UQp z<`H5c-)2Z{-nvwgi2fyR$tn~VwKeGrzaxjlu+ilL>o-U=# z%+ap$MyYAQU9iA;d)C0pRb`T09A?+avHW`d+ui^Zp)avp3-)WJT*HeM<--l;Gf zZ(MtD7^d*STl#tc5)0|um^6qoroPGpd2*r<-49WCx!=;>Rca>8X#}AKItIneVFe`1 z!@|NYbovT_0g}kY4NRaUwZYMEf!Q$fGHcBR-- zi6TFgch7-mI37e=Q&u+YzB9@N!_pmfmxX&iwnM&~vpmYiYAxrArhIho&i1ojH2`*3 z@D?A8!kA~c*t)E)DPfiG-6zLOrwhF3%f=Sy3I2eYiFt)NqyO2M301g@#{fsZ2G#Qs*bhlGxa#*PMWw^p~Nw z`nfrovfYAwv!2dXAYjeP7(b0Bae8Wty|KhwutK0lj9hbqHJruGy*N<1%-~w6akOg+ zFY&65Ja?iCrlt471#ZuE+eLhy1PeMabhnFggDE_I7@k7zWE0y zs4soIZ2aJecH4hqSVf8ZcBaghR3+o4$WHMH<9vyXB(~%lt z6>$2yqT)xfEYrJD!rY^udJAdCt01=VM?kx$LIuP9+;>0!vHZD2|)Z&vR~{ePFkg?0B_^xztQu`EtT<)x(qKIe!%q4yLn)?3Z_1{ zI-hnaA@!<@8>o1=&pac4J^1v25TE2;3_VcC84Z(9$`K{yXrdd8&+>DTm(AC$h0g`? zrzhR56`6^RxW#r9r&7k{xkQIjZSiNpQ>JOq4Up#Em2jXOSTFeo<`pZxQ({CeYj8i7 z^d_~pxpokD+V%_B;-_caCtkhtZz4M{=?f~N2TkgimK_{*j-Eh@^*;lv-2|2rTE zH;E;4x9h#YwyVCT_A?9eru@Kl>5lM5cEytg)i2VJDh`PY)zLnN zj>@;$;r|9c{c~v*ny#!>Nh*-R{D zzFcSF++zNPelat!eYLl|f5=n8yHN7I zPpH<@+2$(oS&|*|CMb2W?!TMr|3?&P{`wnLT<~RPT#;4eN}TK?f~s<|^Tw7EcG-EE z>b=0Qsk|2Ij(e!;@=i~CxAY4MffO50M@d8HK%{h8!82z(noK>A#|Er=?^zAx-x{p2 zY1Au$K)!Yt2(^IYS)G+9J*X4+Q}z$P52Tfhm5nXAKlJTdd%I=BF=7e|JF%nCtabQK z+wXMC)ht_jlhK3p&re&=3V9;((a_K$$kzox$1E>TdjgI??2*q!O{9c$l6@P>JwpLu zCI9Na#?-FQjWDO&o|k%CKl`y!JJ~?>tg^3@EXCp(x`JVLx;ZCt4ysVY#~6}LelG4+ z3Ex_v7+X5l^kJc63uWkzw23`w!>2N;uy+i3SRVv|$+M$B*tj@&YaRJ9 z^J)_}N#t~SUgW$|={CZtlt*_w^BIA9X#iz7FEK&+MuDz_BQ?Z|ig1O(*%)$GzL|oo zNk>#SecWY&0Q@f2TnN+@^T>|5BQ8b$df9ba;8m8^;t$U4yPf*@QMfL$CF$SL+8kr^ zPE5aOKcaMrdwERPm9E$Hvm@m{$zs&>v?5$#9#!wZ!u#bDNNQP6Q*7?Tvt~>CFO-vYi>5>ClfGX z`R&aFH-3V^&Ne#RYkSxWBO`9uE6~qwn$B&O{MKX-SS+qvg{kGy8_Hi5+DZo4m!BkVr7M&F%G;Zu=vuH_i?_@R#0wl zd;35o_v9mj`1x^qhiIgwGF7Fi7IbDnPmISWpwL!MTi;ZL4m1UvL4GRHYSos&s$0-% z$5Zf^{>2V7z#P_?FzqGL+i1S6M@58_#$zY2&?VvResA|HikHxNI$gxRRmTh@9FQB4 zVPsd4+0w&D1BDJ>ftgGWPRNBq8h_NyBl{eD6lxO1moKNc;>-Irn%4(51Ge z@#lo(xvZx_aq#KyFz*%@Zw!ht9`d!MDGgB`XrFwg`##pQXj&ew>A+x!L6k@Z&JUR8 zzewLgrU&u&kV(88Nj_}+2h-y#tm4SEp>bFI&=$Ta zFbRyC{VeA<@ma@}c#cOZ8N;8IM^NyreEhLeYKnBxhGpO|i{ z9>Q|NdK;Y=)Ff98<;p8g%3zxrG3IN8P@6bGzzGkUOf{oNF7JOSUF?d85(V$i&r3${ zU}wJPEpn#YJy>9Pe$U50{l}}H1O5EZ9jeZtI zje{_=zGNlNvn*rT*UOR?D>+>1#t!<;xA4_6KcK>8->o)utOr)=YJd&{@}|}2LzPVi z|E%RuHnJxZ|tPvSLHtb_DW$A`FOh4Qcmu9XbeMA z*C{yK(;gJI(tMac5mcwh*xpPjBi>n78V)NhUYM6Ma)jyjmc2%sRZ88yopCmfr@ff0 z6X=xefE+Sx?FEkkpJ^l2y3!^ejK$+zk>wm7X=r3k!s8Zn-W*9YM{{vF zMsD$BQ!*z`p3*Sp`dzjX(5k%j32YLYul<){R)^%fZPzY^atj17;Vf0D*9ar~3f6u* zjMSz7+WgL0Sj}x3(rIsU*_H8mp~(Qek&bz?$UI>Dc6w!6zNsksG!tA-^wY!UF_K<- z_>?pMK*<&NN;~(4u79Ra#%edEe=n1PNA5|)&_@iKUW|mRUD}uY@3VNo3(SWqD9{^~^{%_r1b&PM?p$^Im(7_mq!>{Hv-!JgNueS{$@gZQmNtZ~tH zpi7i9ULN4aQ^xXu@O@}ds~ClILdqyrR0z0ZVWtbK-6!OeX+lmHn>6S1=LOLv^|8sVz?(4#oc zLAnj3tNR7LdC@~xowRl;*=kW|YZ*^LZ~?1Y>E~!I61OJ9Lr~to>sOO7mudWlEp3nQQf`pO_GU$YCne}qt0`kut4d=mQZ?pfd|D@FWXPA)zne6(D{%H&&ON}w8x zTCMrD0n?!LY#tMYHKkY;#?EmUlIdgceT)3oxG9Khc6u;t?Aqb-+FdS_UtV5Mpv;!> z;+gF;;M%~P_Ih+Hqef3ao~!ZTzqu|y3=e0h&+ajK4e_{BB^Git%y+lU^5_bHz9%Oq zZ--0LVwZGxxpbPMmhEiKFBJ3Wotd6&jT67OJlpUFUo4)W3MIO;iU(i4pvSj%4CCU) zew3C@;HESTws;#-@w0t>ZqU?ZB`m;ImL6^)r0sQYLVo=`dTmA9%VF;@(@Il9d6;ja zMVCXx+!J$m2teN}R3X?+mNYwoM2DHynO+7YIJp~p@J@T&MOgu=H%b@D;p?@kGg;}I zFO_PCcY*YZNb6lYHPa811&L{23aTBHTKc8$j@VdTWVMy@P6|ByrmdeuLKK|XDw~fh z-}ebFqBjUMnWRLuizZ!|%*x17cRbtG4$GP|h~F)$BZr7TQshB){>xxTsGosJHJv{$ zhDmH(fkUrQ0@*ie=~`8rF*SQy-LA&t&&@YMw3jv`CjC?W%RW~IHl5~7jVsBcbhm-q z^h)1aCWa$Ru?K}v*S^jCebs-UyMu$oih@7KmJX$Ca6^AGj_S3NognYKF#-^c?VX)S z-6U!^d)cs$3pz?NvsxQY;;|?!LFzt? z)}@@y)=hj(o?6A;OkeliLdHUc<9G6`;xZbZ!Rz1)?v?1mI?4iSR0VO?aI)Qo4J&M` zk@sf|g^ylbo|*J*`#9S2v$aLP{fBdJRN8T}w~Ug{LjlTDO;KA#Zfi)oU{>{VekTtf z21Tj_(aXXx0i*ywd-??(_wPb`Rpi745`J)MiFcoLe=vgfbb1ynA5eyr*#%(YEuLP+y+a@yS!cj>B*!ym0xM zQp)d2UllifX()d+>0r-y@pYsF=CZ$&(N)S)lJyI>%Jh9^xw1iRF>uI zk*sJ3U7Av3duBOTbg6xjd+JHP{;qzy1Qk}5X1gQ>pYDZyJGoV8_BF6XM?XtcN>9}G zDyhrD-pSn-L_DlfYOqNr-)b!nP)C3&X|D?2Es`E`@=xk!*DKw1d&|2mbIi}eFWBN-*TNA4b0<>p1J8=nX+__j%O)*t!C@qHCZ=B< z?@ou&{LL~v|7Gikx=abCTa|&~&D_mVFy}PZ)XdwMv)gsgny6o8sdMwgg(a8KNSsK0 z)j3#=Bb$JIxsbLqT5obBLZ^^SRY5_Za*f0&D)+Xb8f}_NKT5Sq^WlwY{)f?>U>iF7k5k)a8j&cOnV)LDpTvD}g zL5vrTBqmuMrLmvFYSx)A^A|@7iX`YhWkJRm`skdi;~2j%3355P{?`)i-b3XJ_BS|# zRDJv>uH**s(}MKK#RKdPA5c2|8!eWv;>S_;b~v$VJ!z=3_GQoDb`Eo0^X6F5&o3`3 z3if?0^2KS_Ra0}3#ZO}ZYCvaXYFY%C4DMFlm1(qd3CZrGdwn}V*wsYNxe&x;E7LSz z+mUl+H0-%St19VrEY2`Jm2zbS0)haEgmeKQjqo5&o?p@xTAfWAcF0v!apKQ%em12TF&AMcfu8G=#}jj69pN{6AN<@f^brn} zT2X8QEU{_$$D#E$10X2)$Rg7v4N56XDl~V%lc-Hk$2)B~qUV3PH~g|1wCf=S92n@u z@=iw8>LS_P$R7B^kK=j2iQNc0*V%ZI-OTYj=5OtA{|hfIPI@=Mv{!ut&kbTLE9qNW z$VcJGlzv@ztAa!L`;=eDb^k(^kJ3UzB}XAU4Bh66P-%;P_1xz7*PzY(L1-?Scl4KN*-H>;6u`Uw-)c`AvR& zqR8^{6b^dcAsE21tD zTY5N}*Q$==Y5%6r`p3{mlUk|{{^};@b z6sdRNRYK~dKQ0I9)SfdQeTd=51xb{(t=m8GD5nT zCNK2r9ujR@qGlEAhTjfS$Y+BqV*sWJv66Xy3#5sP3h6dP7JERd4igjp+uTsZ>T zez9DQ<}E;;-${ZI(jM<&wZ7V1+@|=YC31R-IVP>l88|q!0H7Zie|R zk^0%uV{|+nAAFtyDnc>Xq`Xot=&Zy%`l4mdEx^K%tNb`}k!Il^b9>XH5%lXts#8am zQhD3_qE>cRnNIeAm};arHvi-gYPHzP#QOXVR&6yp z^YGWng0zLG;gKq>xL5-k32o-rfB2d8Es4KX4cg-C3EFm#V}!T7q^Rf(1{o;3T*PcS|4)!CeyEHAsSMAh>Sa zo!~yWyZZoxyZZzif}KV7zyIf)i*v&j&#Yd(x~sdY-umipLp(T43v7nvd^;!iV=C~! zL`pfu-^=~y1e;4>tM(Xi1Y#nBSxJ>P9!a6!=-PBzVsxRKXz*x4uFVLV1>eaK&3-X6 zljP{*$Z}@ow_;N#W+onihU~&*o5Nh@7C2sAMQrUj$(NKllFCR`kTKR zsaC@-6*OQlV>x(^+3O#@_cHfTM`;~Q*Y|+TIXX585xr zWSiF;VOX7&Gz#ng#}n<&9^Lqje?tun4gQIy>xpy&jwHZRKYetn&;Py6?sr6F31|oj zdg!1yw^>&I#mCj_9?p=F29EMAFPjaucUrt{eN~6B1Wvhm)fE%Y2yLkx1W)0gVokc_ z?8$OTWf~(1(|_9O^_kiHKLtYeO@JI!F7y{V5HP)oC@MX$iL7Leq%S+W*IAu@DU*#h~WcQR@N=LtP~+j9rDndj6f`x1Y`ZZ-;} zi&PHuy&GfXJ4izwKXbk|s59#+866D?y_}rod|l_ofhiL0NNFj7r&t`NRvmRmuJ7zw z;Y!PaR^rfUESK*Z=tJ|ig4Fn{HHa>jhuEN2E2jKM)LXntJ&dO##D-V+5hSSusr##|1&Y~K!9NgW?XiJ$nRsX7styW zdvfO+QzZV-#Ps5Jpg2XxvqKk)35Pl%g6ADSNZx)D7a8kd2UIq^OXVY?gPGezL5t%( zr;Ya2P>kDwpYx?XcxTclvC~_6LjN1>=_=J~a%3#gDBFMorFTys;_t(QOMcWm>HmCA z_<}(~9?OH*YeSx{#FHN--)2Q*d~9Y=I^?zGEy>YGJ7q|-PoeKzO0p8SM`|ZiQ%5Ye zeemhBIj09o48dYC!y^PU>LFD0Ft5>H)+XC#s?7Pk{b==+v4C$z?eFhP8~?Yi-@f}d zBQ+e8QOd2nU!GK!6dzs3m34^XPSq(og>AOQ>Af)>eGD`hbGq*`@iM{-xy3ys9UY1i z5!HK3S>Zu>qsERof%Tr_6?tUL-E_4Ikjv9)+RgBI*Wmr+ze)Zl{7gms?~2Qp+glVR z@BU$^+iy~9lq3%e(Ih|?Q4X*Te`lW6Z?soMR5i!mEkPpjMNH!7JtmH2Pax0596J$* zT&S-!vE^H1nwUFSJAvd|j)Ftv-lIT{1!d6;*Zz()Eka%TZX2p@D@kciw9KUyjJIY+ zoqou%bjE;C)!$Xm;UkUn*J>4|&FdI|t2*+HRYnYGaL<|m`((_M%#KMee<($|N6jl7 zJX4zWg@A>wBiL|{Bd3Z;qPsgpmfIo3*QhHdI)q1pmRhwpC0ZH;q9ab`<>ch#NFL2~ zAOd+dOLW6fI5oo1XeTN3pt-QNbFiR{cyRL5jDYY?=@m1!!r0mj0M7sj?)}e_>rwj~ zwgIywBeehrBdgiTh_>&39qG+LO_KMUZlfF@rGom3%!hTo@V#dO7-cN&jA3a37@sY` zF{Z;k36``FD^p)9$u;g`%@bjPD{^MA%nHz+$%d78KM{e$8SGWRR zDV>Jt;d1e%rM+{6CdPGIA^U<7O_B2^RNY2>_&nKJ{}^(_8rIUaKK}VsLi)BRZD4%d z9N>s9E-w*aOs-F{&c7SG=Z@yDzhx>DgJyxOBxm*pv6~$MT_e^{I%;we&uoSj@W0Rv*X{uHAWyBy!%SwObm^rO5IeBn*8sGNyB zy{(A4u+zlH46Y9%{ye;Qg&FAd^Sm3yocrer15v0SBZp;)Gy-^D&J2X|`7=f%3`MAZ z<4C4rW@lXEi;@&yKi^&}L${OBrPxEN?z~)@`DIIq-x%fm8e1L$E zc=pS8iOi$Q|2wu%bcO`LUUx1+EHV6H`y-#(lf3r#OjZb3f}^HTL5`0-briGTsK-dq zAe4R;FL57g&W_I&jJcmS>xg1xJop;}vV#(eD<*AFr=^ut`!Z;g?zgRz!T8X}+8;AE zq1U;59Yz|J`C1e2Vk^-(u1{Ld6>NdtrIUx8#3lb8HsT|Sz-IMNnxcF-3jzp&nI@CA zFTNkTd(40GKFET1pA#bh!_7skl^@f zhvGDby^q<~N8d?+iFq;U%!5t@tK$jHG0*_fc}Ezkysy>Tgkl978EE8X-d+~h*K0;1 zp6h)0fWXSi`d%2}(FG8cgJcxq0ij;{o|D=ec$C%amD1w5#Kr-(3+1-5&@z`r2;K^< zMNsho;OpA>2#w?C38fr%$CG_`^R5s9GNs?@wkM_eUWrQhC{6JRBbYRjJDOL-4rpU6Sc zw}x%qR#Mm@7>C;_#|})BhM*FMXiGhi0L{FQ=0$Uw{05D74!+(f61^(%l^)$# zv|^jjx5&X7izlIvR%pLnKAj@>Yw(AmxynQM-7gpb6)gFuvniScilc4e=Ba~GX5nvd zF60Y6EM&0B+kSmIaW=6;6ZbCYz<&KRYB}wGH9#!pvX9=;>4I0iXH z3@qzNKz1CZ9K2#F&H!}e7cojQUAhq0EyEYb$kRC|GTwmH*Ly5=Ry`==xeVxEMm|EJ z=EM_$?3l(i?z(($NPtav;0g5T;>^R7r&%NjR%}AgojC|m6AD4$Hr_t(n6Qt_7;r;D z$Txf# zZr(r9eNQHKBCh+_MI_^w(4tS59DhOYX9=`t;A%-9zWXKcV9i9Q*5XMS0U@*S?NPX3e$TMQ~_Sn zx?ju#?d>s5*IoOOM?*^K{D~hF8$70T7eX|g#i}!AhQC*u?p7MmOrbF zDx>#t!{$xJ3L2J}j|7Rgs zvs<|_`0S%#;i`sA8yAeM^z(QwTVxMq_9iesj7?+P@1=d`XSUDrgp3r3&a2)dPK)RX zH=U$ymwbLavrSQygIRrYp5L#FCrT{7J^#F3X*ldG_o(AIQzg16af}vBRu&~@R)nRk z;K@Q7rFdgS{=G1UKm)lK&~UaRRR`2Wm9<)PH~o5R@XDq|6Xptz(%|P!;Ao|o-LmJ3 zV?Q)OeZBrNtvry(Ot9=#QeD2l^Y5{*%`)x)8W( znhT#P%8VO(4K@CLns40Yp)52xbW#>lHQ-RWpxt+ZXjt_<|sF$bn(Tp>f(=t0uYH2D$ej`^q15NG-q+ z>Nl!AJP<5*O+t;EbJK5Hs?T+D<7vWIrrJa9`VCnisz$sfb~ZDvYK7`h zT!WX7q1E%2Er`1xQnj6@pN8v+xnEe2Y$(u?3f)@*k9ufyDBpz$iJhrN%We~hz@Yee+}kCl)!u)G)g=o53&xot=LuRZy0 z6!~7l_lP?AiW!cIa~t-QQ`o+(P`jw2W!Q6J1r^BD`CBf$?tr}~4oH~3etQ8n5{^Qx z{92ZMIZy?!#u0jPaE1w*TF;&s}-3?cHC5}h->`}E59Wc#n!pXzJ4YQVsnLB63Rb54x?%a5 zL)b1KJdo1P4$<^brbtM%+q8f}Qqa4J;`-jnvAk>}{%1eGb6&Ctj?muRcJH}8b$Tpr z4$1N@Gt9f4_|n&k1iKc`ro69!N2#qSW;RU3?a<2Nu_-8{&fMO-(Jj9$D5JvT#R(bd z(!g7>l`c*aZng*LPqM=oQ!T?m$M2Cda%8^53Tr~Yw`5ey&p0+Q&7Eufb0r}!41Onm z->oO3pYczNJZvtnb+^B{Q&CFK&2vQjm|IL69Tfm}=Hyd(!KQ3+vTon`MD$%CmA#Q( zvWUz2*AwTGh}!*%{KUs^E4yXqOJ21Ik-Q+YEC5KKBUEOX$m~GgI*?U@YcbByFRQgo ze3S)KMhP|>iJ>CAzVm-1p}AYuU6|wBqhNO4ABOFC&vIaCCKqI#Oa{lt`4d zP?1|D{^RXy53bQ(_%C-d>5SR=_w#*B&m+T*%yCaC|Nm^#?TsUId}{HYmIi3lnzcsw zFia6Ub*hTC*Fk!RYeYr-{2MaG9v=8r%N#b4*_6CN#0 zUzfv>NH7%5#)@vW$&@i$QSlW--3UY{^>8aI*gS49uF`4r0YU%-VCIcFZ8#09k_JaA zjjED3Qst6H=&2ldNa zOS{=tPz_Hux8!fw%|LdTS8aXu^+)EE%8@~oltrC5kzEBZ${d7)47>hwonXy2F<$Jk zc#pGk{~22EgG|h7uWecsF!QIaedm>%PA$PcfNxq+XS!))DyIBhWiCM#lRFc4e3V}* z@Lqm$;G;JTx?(l+(?uK0RI1n^$^P4E*83p7pK;F1stCsJ5_L97rr(A z%qW+jsIeTY70a>?f$BE(cj(af7VQwo#Hfn_~ML7KZ_lOHd z)$Q*h@3#2g`fw#x9cQM6+nKo2gFJZcn+jp}YBq(m5_H&Cd*zmLKPex*0U^b3SvN_E z>3gcoKnYgk3PzoVWv2AmB?@uwl?YPp_@YRPf(PUqoXmp_^+VhYlE& zep7Ae{MkMr%T+ENW#!Qra%>mnv)W`&z}=1Z`k@u!ZZ-YkQsi(m@xXxwx%2g5kwsgN zx8A|MMACmSn?Rk|Sc^G>PO2<`_Nd>=ST1n#VlQM9qFgyo{GJFHx02~ki0h-h8E2od zm5SKOdTynGeN~jvj^SVA)8d!^%lmoR_!>os$1gmW=%}u*6rt^>1(n8kw`5ee*Aq?P z_>PA0cTn8`evie$M@d9-#gQX{R*Fx^0Q8?1;g|8LgV_wv42%Z;Y&eJ&_Brbd`vt>n zc)-W9u$zsvkX5fq#eVZwq7O&hlwMQv{rx^0?cUeKr}t0??1vqf8ZzN7HXNiIeY^JI z)OODx07}2NTX8+tJhJ}7^SHW*@X)%g`vv%;;;f?##iY2o&JKejdprj;D=7Xkdd z@`wMFq&o|KJX9P$v&D#cw87dQ?mNLaE&1iknQ@ctp+Ys-W+_Ba;>X<*UpROFFHR;T zLr33vq&HOGw9iiz{P z?ETBJ$(&?#idwvKcULD_kDyg}XC}=^u$rlZQADU-sEm+M9rYp7POF0%^V^4L&bEz5F0@A;t4$nx7LN|0fmr0q#Lv!jLVp+c`8oFyr6wA1B1q@b=R|{P%)f2$)gwKgdwY&0vj|BL@~Mx>F@q8K1Kp?ZVuzj$D))t$#mMmZlX4eS6U|>Db8@4&VkbyX3nE z#fQ0=jfTA6#0kYwhebk3620JYIT*1~e=|5GW(DQoN>>ZHqMW7RPtjneZaEd(SUL7W z#ZSuJ(YPl^i%J)l)yRk;#L5X7JlNBPoXpZ{_zJ`#dSjK}^v_YRtd^(oJ3f}yfM0y8 zGAH%F2ksMMwG);*>up9343xRT{wU-%^g zxd$E6G*afmIew=)Y4r~gR;t%#Z9|SnL;Ysph-QYlg!245c?N6Dsoy_g>KP=R5+A0i zRxL<_F&gcgkNt5!XAMNZ$=1PHu`KS^RpkDDR9g*Kyof@5;kdoI$nVrz{KVy56J^Ij zPQ$#6iF<1%Joo%iIJtRU*1YYlbM$y>z1|EXMs5c$}n!uW7|fJDP2Nf1x}5 z5h`e^ZuD-&=^YiN6OF=0BukOf^?7zlqgNdnQ9>256L31{6XKU&Qm3Y@TVAyI#-wCR zE3F~l)B9VcxkTRXM#Z;l5M?>eVd0(hk1;fQ(QoaVV^^%kAvtOZ=`;%pYxYRvbgMN4 zqvi6y8k+o&6eF7_H+pK#ilycTt4b~|uyq_C^AlakzcM6Ky`m^6KVR3K`cTOl5}qVD znqlt7pi}bdz=E=svDR4iU7I{blm4~prG|xgGY!FY!f~9>xadz)a|>zFlNLtX`YnTc z>x&Bo*Vg%TetHovu<(_tz>0ztH>KVB^mteb&m})U6c{r>86#z7G7TBgDY0J;T`KFak3M&%{3ZEP zm@KVwaz<6N!F)R_CtKICJn%5}jvbH@pBl(ZdWPrjNEB-XQpN`|hyqtO3SMr65>dS+ zlkzYYxCP~P&&Lw#M%bhV*XHl-CJOyolh90S9(+8)5?>x;6EE~83S*1POyuHZJFi1J z7BdVY6u>;=8PG+CzZM^{zFzu{(|&(!hp=~YveOfSSE}PyE( za?9np{6KidD&C`#aI$9>a2P_DLP44-x|hFx8fNJjFCV>inBOc*y`&*CMhYoqFYfGn zK{7#p;;Vz&2=O``9qJW`d4G8FzXapPUxINkfQ3z)Z=PWhfZ9~0g*$&caLMo7gr{ zis#R;gj+?}ozVA(m8H9JGwU`-ng>L8 z1srhmg)m2Mr0fBt0BiS}43f!R$?qVT-CB~GET-v9*68d`MP1SFj~^*NMxSC)t5)Tu zEgDI$3xnE4N5!DF7@xKiv!se@8XUEsSvU$SWY}5cr%Z3DavV=);KOQz>B> zA*&3)jOPH78UNB1BSlXY`%A8y5uWFxeD8q^DUbov*;e3HsjKp<+upW$ytQIlDsc$+ zoD|jaJ>0JW@mWuk(U+@lmMrPQUDPK$+cQ)8z0_8{)_;?%{rP~$8l`yRBh17cO(eU$ zXp67pHBC1E)2^xiv(1)H&4NxZcs}U36Xgpvtxc^&f2zDAp@vclU$@t@fp1lpH-vSf zr1_glKRVW*jV=nSt^Yds<(`o|J@kfWq2UoX;4!oH7RRO zL8BEm10UU>vkCvB6X!qFJP`0RTDB^hW)ODEd-y#zJ~RlBC$qq*f`*UVxjrHy)qjDV zV7_vI4gIsQHfBuAx9Xrd-PE2qhpR0`v%_-Rywg(!S>fo$bKlNsK zs{g|zLV&m5q_z*jf&oe)G3&DGOBZv>zPDxQ+Kg-X=OJ zi{D)7oE< zR$EITYId7IjkO}{AZQUS!=|^rQ}I#(mEKw1v&a-d>Fb=V$Nq8S`*#+K;Y7SkiNCn2 z$(!YQs$G+t$WV)jswgVi?l~jo@h=?MCD_3i)+RBYkXodNkuiq%0v zdQ#5hiA_T5(hleK!BLJK-vXmFXkY#r1_y>WLYh>mvk(o6aw4F}Z8mn;I?-sFaL!q> zY6v!I@5N@j#+Bue5A=#zfwXFUeGShKN+Ku%tielxn4(Gr537q|Ip5I&lnR6SF1Wu~B?*W5IZ3}lM;9bP zH_#YKLWnJw24dxe!KdEW&AHd(86v}^b}iA}lP})3#Z5a<^~XSFQx!0E$S+q5%yZ48 z$j5S{&f(c;tY?K<$8-)2_s>U_`n5D0$14U!6z<-WTi4f+)Q+E?tucxy+-3{Zf=P{w zI_d`%;O|MRpkFMaJkGunJ-!>WrHrwwg~8a)c`$$d$TvN+OCc8PeBxUIiZqdQ#}=N^=ZJ=aQGOl~ z+Rx7tgOQ%@k*Iw`0}NUF;o+EE_E#99H#D8eihpj7z+g-qtlR<~&RR$^x zwF#aS^(LZER)VcVpMhddUW@yKCl7?I&NM$-uFQBpR2MO@D%MU|e<$)apOHBJsX*0C z@*+LMNLVD@A6pLQE!SB)AGB$~?7Mt?QE|PV9@iZLUP(PD+<4Y&F~G%K>g>V95y z`dVQwQ||VmWv#QH&ZBXQPhlp0EE>fWFx7AD@4GwCyB}zbYs4VZN9Z?qy?WS6w>@ef zU^K0#^jSTiL9zsqOoG#H?<3ToNZ9hP1ceBw&P?#HySqj#f#%!DB7Mh6cJLs zecs$O_NYVG?B=N*{BY?6H&cp!=av_c0NE9z@X8P2ZBeruK#4JTv#q|Ef_-G|L{#-m zP-*RP?{v;}x*FC4P-Yrb+;jKnZ&%+>J8HXRuGiUjbvI=FExm20+)MR5NwbbAQ|NgS zMoZiGlh0a?SAQk9Gw%s=j>5XrouU+iQnsonELm(}B*7RgZoA&LW?&7Dp{aXzuV45mKQ6DfEx;OrCG0U|TwZ0;OEr z3ldk!Z|xrL_c**sZ`dB-VyDq$Bot6JbqQ!~NQ9OXbym4$U;BKi3+U%bzQgC!p}lr@ zI*6WZf${_~1qoF$nUSlj|N8nX5J<(Mh&zAeTs%0y(39})u%cao(=EXK6WZJS^}HQJ zwtK~!!j(xGcm%_8MS$gfkl?Jw^sDbpRkXL#;TQ}(S7Pr?bFohRZLWRrA!H2Wm%L`2U>qsWgVd|PT;ZNIi zr#Hy5W?&p^k{7n&cuQK+Yd0fF?m3RFOa6AoKk!NpVXHhpIX;)AxpqlhDr%#(6Ht2# z%0SN%nD}_2=cYdyENeyP{%L)~Ds<#HO*HIcns6#QEtd|J@6Ij)yRwOqwvi){1>Lz) z*yNwrGQeEZ=12|2qtrJ%^m-p-59IQ%Y!cGHIO{D~Ey2BK6`<0_dR@1OYUL%l9!}J^ z6e&R|fHsbftZ~gL_M{W1%!T6)MEQ&4CZzT(4mwu=jTm>i&Ne%kbwkT2%6Gd)KG2R@ zt)J2pPi2Z2zb_(!sp{4|mZl7m)1Muot8lr$vP{^`&tZBlv_$4J!o_P2Bbr>T`wic* zO2Jj1UOr5_uYRpmS4?*KDR?d0Hitg9XLmD=|FBULCaM!u!u;cO{pC7ePLF~!p7*+g zr!~b|gVQ%gQf76b)U&?lY8uEEB1T8D&`w}HH!n7m>Pxp|d3-cS+)SD_QAr!>b>b*=nR)(2v3uA#U#o zh;z6-{rbj{AN*M1GF8(nap@iZr{Je+dD2clM&@737X-rRvcys;;=a%H1|2!#6g=#T ztazPDh~9I5V2THEFeZ(no5fnzWB{-q<9S2$x~*`=*ABr2TPK~ylo9IW{s^BSl-RUC zo0gGxx2N!WpGWeF`|{N5l~ZI9ycRxbxNdNO$@Wlu?zNL{A`5V^vG?Dz`e&Aji{NK9 z<&a(Xq0T{msnm*z_rDX1FUe{*x4D4}^@os!O?k{9t@-})_KV_waf&`6a02u^m8V`e zW`$3)cX}+vE$c<@u7Ie1)jB#K=URF8I5cL~<$i@vEBK`j0Ri2}-SwAM@gJz9NMPYn zk=ki+ZEAm)hF}rxAn107va){pf*y#le}hg5u>K)b`+MT)+xe2DzH$lE~>R6sut3oA2Kj0-QN{ZYLWH59p}>i+3Eo&8FLGF%X6M_ zkVT`g6KZ1pZ>gw zsv7I`7r$h~<-X2-_t|w`&_`S2pZ|Dyz-gYu!?uNo)Xm27+%9~z>l5r9O5`0jLpj*Zt|a{ zCs>K=8v5y1ch)C;n!GIfa)suw@95}w)`?2Fp!CONf# z(NeZLz(6S!@BI~}VsO^mN0Dv4_CoXKjRPUxPkdGlW&8lZ9E%={g*CxZ%A42eM$9(r zEAvhDznV0VE>f19V&k1E&gGXYT1*KF$8Bw{TnGEulZd1bl@g$%zXm(*a}L>l8DWA1 zE#+lODqj#o{T`EKAsqMMn)ruk>+8e^R%DT+_$9CQTcEA!IDH(~=K%oTM)W>UT?K}m zIQk@%^lhUD?OB=vz1RaR>br1GVcF7JDV|2<=oGJg-LL)yt>iiynG}aqW zeHWZQ)MoZayCiS+{CV`8eu!6MtbGk^Dp43$d;~*44Y=9_;rCi3eaZR)KhSI&s;*cZ z93S6YYNWBtgi~kYF#U)@D`w8x%VM7Y=qyJ^i}!<)QU^NegghZNJZ6z1`qnkG>^dXS ze7%IvC!jY>U4@!4Fi?t!WVTXkgyBbs4Yz*z40@GPsZQfJ?q`${p#8(cTtH5QssfMz z0eA?_Hk$tC+_f`3j@6H^#C6jCc1k2uQkqcyl*$5%RVV-bo23x>hJ{IukwuL|dnC8$ zs80+;2$VoG;%Nm{eL2fL9OE_~T>KsuCCsZmi{zV$0*7ipQaKK(hoGOOH)&22A-Ld~)9Yc?lwZ?&~d_ z`fdsQ{)K~S^fMqXz7-tlmruI>HCBMs=1I;ZHT*W#cy-ff+UZjPPmLUskC7zDW?TM# z@=j^2btmbt)^9m{0)py1R}Lrvn;9%eoP`jBE|wTvZVc)=6=&fFC~`cjPD&wXmLMRH z{4^I}Q+;KSQ9bH)LcUxqRPKEH(&?iHl4Xnj)Bn@_4j=&hz=zxRM~{_R)-w9Oy&vV4 z3>NrWBU&T*a#=bbptWeVOHSmD@_f&)@~h;oZ3dG=J~(^nbkA1xhjVfh-CUz@eID7` z)n+$OEikIfeyML1N%}zj`Igw@xfp^gpj0E^^@kg% z${0S*`gfYb3thezkxv8dF8IC1Nu_J)Vx?;Oom|Jv;3*?b~~E?@Q}o~5691_4ExXE(c+9 zrodt?Go(_r_P&VuVZw}2HSvj<gCI_>MA1FA$ z%JW%Ud%J$y%zy3p1m4hE^t5OLps{S?yU|Pba_QFA)<%jho^?Q|;Z3^2_#Y?1fBLv* z8FisdHBF(ey!)%7)(A2Q_ING6T=5U?{Ei;?=?R=x4QstwHvpN)q)v3@6i zPprFA$W@WGMNG>6tJadFAylUskU&#b=K)OQK~b@cw6t`25C{EJ$&QS+HmT3uCM5zt zusnc51D{AKKp*JuGKLbOb%eQH10RSUD$!szxTH_fez(oGi~mFM5S>vj4@_%@kF2XX z!MSZz-RVqD9vj0dpR4$yM-e)}d7H*rZtubSQcN^=#fUfBoFmGIwkgLL5Mar^ zniEqXR_6a21s_qL?ae$Ktiz0)T-MWl&en1XEtiH`pK!klp!f1h1()I{3d!G zzbGzH8mfeU!}GRByw2@>XYzJ;EPeA=qTYXY0}z#2ppGVZ>py@j`2m$1f2s+@nVeT~ zstTBH>Zg0s%Hx}{4j@l?*lo@=3$aXBV~WVPOp-IP>NQWTVcHxTVPH?;u$%S{s@ld( zmUD^aOi|91`4zF&oMSKrVTb|1Yd@fgsCR5TJglAQ{-*b}{>cBBtiO+@1r&H+J*`fYp%F2q~ zk+aADHQ6YCcb{qgpChk%f_<(^ z_^X$c!>;2fvzL>gqRrHDk`j`V*A<8spuyDjbwkmcJ!;WE{E@}QS}bND&=e+}Q^U&M zKru6}=WC;EK&_{_sH}|q??i0%i#<4COFb2eJ{eFb_P+y(`qbVV4>>uP`$@_UlFf>r(SgxKzUxDs@N?OPo63RMLZfL>1g&I1R>#1nP+v9_ zVmQ@kUOq!dL>BX%Uhirw0ccqkO9-y`cmG6!HJgkGRe~O%4F= z3;d%{AZ;nwWMt;*nxtlh6r1x;rd@XB8_L=@nRhM1BXp|yX_)V?B9(VVJcbie2WQ>+ z!e`tw$r_-J6WkFk!WjCG3!`z(LvXPA>bjz)cdA&U7qOKg!X60_tx^*-ZF&EqD(mY? z3()IF@Xt9gA#qQ^seg};T8Zap0QicSlFz}(=@`q>DTx zqSRT0)P~RW`H5h%q!eSQ-@MIIAJmsJlhH1&iX)q_nB_}N@Ww{3Rt2+Bbg>a{@(0=6 z2u$Mn--#|(fO?I|`OawWwZ12;mn`z*|2(&x9QUa(hHS!df`BW(<$0VOyY8S#rFAkc zr#r7!Iq@S2mKHcdgG*lBiO70r$fC~UsW31s3oUWASOS-5=9kR@MO#Jpr=675Bi4>X82Z?u}XRN!UNLBoA?hMq^d{%s&LZ zA?tk+8HLhOJ0ee6cAn8{3SRJa*tWcw9J#jn>S|Dv7cp-`CAR7ZoHv}q1w7=jgP2W` z`PLw`v|&*J0Ht1oxx)MS+Bp7zK*HKWOiO0{V`l;SZZfA1I(UC~{ z*C%TdnS7cE2QGzq5E=;`w;B1cKV=xynq-r6wI6kjOIyWJjt(z0Ckvq{4#X7CJG5#+ z5?XFprA33N7hEy`XK`hepzeuh1@4huDb6vC6a&Jt83%d$(N;?eLbL%u$9Pv}(~=TP zS0=e5tJRx;{0j2SZiQ{tDxD}3_aa*g7lP`m*P3TU?fzQ`lmYeAuM|chDDEkrwRIHM zBHX?_;>SplFn|-!;fINKshZ5mvTw_E{(h=qxp9+*f+@kKdB5^QP^gwuvh4*C%StRI%Ls=MQX?N?86vIi+<42+OlT9+Q zCGkx!1tX6VMt#Wp2D=Sw+*@YGmR8^L8}#>PznUx>TK^fk4{=+Wc&=hn;8}|bt&Y)& zLQ>#ef9DKwNq9Wq8!0n(rrS4e~g*INLI2o5=3EMd`;h;sf_@*>Y6i zV24rx!NEg8Iynml(55PKpcE+BXS%=NTvQ_WS+B`pT<%*)lKNnrujVsWh($aa!nF;r zFhg=jGt7UGTSIomriz_A?`)7h)9`U9Vv8|fPJk2(JRfevk)37Co62@R0*DJi>f7(X zJ{*ldgsXrh~j2?_w0snrQMfC`GPZJgs%k#I}uREvDmq}2L|k8 zqSxPo0#Uf?fxkhYA~0iRuwqGw-=-^=r_>&3vA89jqlfsUt!;8;W?7P0%;WN+yIUdY z%0`=4W##U=5Ba}LoPe{ypEO@R|Lhk$?Zu50r_$K7A3+OJbSSG*1nMv6c77&G)LhE{ ztGLwD_2y~gG>qVP*zm^c*C46ti3*bJ#z@@3E>P2iFA;V@a$5u}MhrK|McGKSl9d;9 z1dCX1aroBw+c?qVyL%GmL?nCLNA#z^_oWKp@Sm%Y+Z8nTRj*X|E&ZMs+fdMH##XnB z&p7I7M&9m)w7bG%MwG{@G4Ojg$N}LNZfSSj9%(ml)j(Corx>3l7Hhn?VgY+{-d*@h z&D7CUK1KNF6rdP3;1CT`W6Ek;AE%@RsE!fLAYp%e?fn%_9M`6#=?1fNRN;R%nVA4^ z!nE3g(iv7==>=I^^KNTra7~(!wwE3CO_&}IZv%RrZOaPt4So1xF;r=A;0%tyX8dTm z{6+ePl@^~+6CyehS)uh|@H@njNqRQ{7hf`a0@CAOya8h$#nDtbVaTqm{3k|xNXuh& zvnDg8QwRbXS%|6S&QzFaZTCG;uUAn?``rI?)KT88({KmKfx$){=hc#$w9#SYL>|I! z9a7m~-*UB>J>O?D1e;ge>o1p8vEO}wsyeAP9raa5ek-mI+*9bWc<>$!IIO2E+ME?e z?wx-Reg7Iu0U)Xw7H7R4!Y}Q}Tr z84i}kJ!bjN#;W?X#TE#3_Us62!DA2{el_(q066Btni_Quj z;}a4Zxs-4FW(M_(o)-~QRM6}Vky&4Dh|AbAnjim^_or_SfMmP|x%9x(qR4~#1RB?q z%ZsAAKgP|Hi{|!AR&jW*jtdr?*hPm=K0vCxSZhf84R`k(hzf3Q0|5Ga`vEEBJ|1AD zRdnPJJ1)K_6NpXOv}9g6>_!#!Ed!Hp#3x_y2KHw}3{gB7BNi7Z{&OHU9qwdlzAFfC!<_hH^s~O5gpD(f$byeFNcG!$LCTXxo0sA7NyPf8%Y`_Z zMeF6jA!T71;V3xziK+L@J~VsX5Ct`eACmaSdxy)h?1j@LE=t=T{hwRNl1;lW5Dm#q zh$uHyezO`AByH7!;h=s4XvE5xn$nV!lmAc-+&O(XIsGQg1bD71cHQk9p!FRT@hJYP zDOnc}E?-uPrrRz@;jNL&7rW(MVFd$H=O^zxoAU?#>eXL)mJc;NS|mLLWjzL14LJ*0 z3X$}b`F)Ag<^Qm&fzy^Kdv-b}v1^4otLC>CZRQu{cGlPJ|G2{AAXKFHg|d_`rZ~sj zMI+v&ix<| z@_I!Q<*3wrM|GQdK-)4ZYtbQbJVxk;%^YGu@8OJcRvI?xkoRhQ55>IE4otlIYcA2m zZ(vMDyxmEqxh$aLSR=-+4$@GDZKwZsnQg{^R6D8sD@BXqhs#JaL8w3#okvIw-}>sy zJ`VfnwUq-CYLL} z_*r>KX2V1IGj+wZth-JiEN&CW&)KiR1S&LRb?PUZKADp+s72&?Mg3a^FY2*Fau?5V zf#RFO{Y`qbz=%|F<{2-}aYf>|K^y%yy$gQMK729wvy552mMCP)`R(^25c$RN1DM?> z1CctM(}sP8JKi5I#=%`4KaT_&aHN#|_Oi{MM>Xsppg~}T*4XDaM@3m;PW39E*n5fJRSYsl+aGb1We!rcCA|LgBZw`RAVwQzZE+<^;QabRCk3JjzbmdELMuclfy`VVBy22)X zxYF|+q)CtBFZz|dXUkSB*(Y$x8~@(r4XU&lJ{w7@qc@bV2@~OypWsh*x)wZ*xG?*Rmx3S zY^*H8QFK~-2A-v?C=@+~P36&wXFZ}_R#=3q_MVlg^NS$I6uw7x2%#+NdZM423196< z=T$RPrTZ|N=zPed894qRgOWK}Dn&k8izr}yH{b(GK(ih5B^#~p@X`^qR zb3pnhbZY7#fBRE^Lq`o>qAcys1)kts@b$`w7HSvLiCwfZHH)6(;GNsk?xsTDp`L#}uj;IP%t*K4Mo*HXBV<)+yeF+cOScnXKivJ4L295J9e*cDyY)IjNzIeI zj#P%>aVJwrMTdnL;FSVS+HP&toLC0VHp19;?778*_X`iL&^%A?CJHtm+&v}J0o=G9 zkm5I5Y>3+I|8iE8K3!2|+`cS-IZO8?s>e*%h~CmkwHayR+lT*H0HNT=vGd*Gx;_av zAm?|HM<3cUZFfG_)M-sMiK8J@H<((@59Cunb(7roY8pAHoPV0RNgk?W^22Ekrm!Gp zHRfFON*#s28*OVS^y(60{7E>Cj$_Ls!!3BFauAHtV=p+LqM=~2I#iSJ2IKv%=(cV5-!(0T1(y*S--HNzpU=rYzwGo7~6 zy^&)WcrL=H(X!}=2kt^Br4TNO`M659`2Oxa9xHtAA@&@+R7QGGq)U;#y^Rrv-}LN~ zSFDq=%WFspX6(wowE+Z9#rBWf3p>_XPXVO?(N&}boc4gd*25HL}H8^XLR*@2u!3A|) zJz?SPGceb!q6UpK6tG#wL z>@vdWzzd6m*>ZYwE zoU(b$i*FU~Y~Nb2Zp9gc<2h-3Oyitga(k8DK{W%}EZQe9#kc*x>o)A8+Ajv!8x3Ix z*O3Eb2J=PBax$AH{wFwB%yyuRv-fZ84_M-4++8EE8wEXXe`!1 zw&cPy@znouwYHgeKvC;w6!6cqs zk($wnjF`6V6h&`fb19^ktjWeTmi6!7KYwJJdh-(ndC)*2WZMT)^$G)vEC6o2mihfX zR;gqtC1rmXGp-FA{1ByE!6?`7kxZfzn9Q2tASb-T$M1h>(6a`m=}*XFO?i%~q45 zz9vrIWjxve(WU&2(C2a%LT>XGMXReHRaa;&c&uDbo!yT*G-j+}Z^wSuU7H+Cv5L(4 z2w9vujhBnf6=^s{ucyA-jvF<>SBOMYdCx9O-^wGtsW}tZ!Z7lsn6z|k!}SlFh&7{> zj_~KHd|cAlkJLtSnpU~H`wT}W#Ff1=&p+5Q90|D({}gHMrO6EfcKK-_R(F|9ddf21 zAUadP2jsOGr;~c3uT!O`&Ki3zU7O6_>Zy!BM0duMY4{Ppdp`my5sXJE7j$d5Nh9RLN#SufQqWqW0&~|B4GkHM zv9xTty36v_rk7ig;MiX`MzJA>Wj)Js)&6%Bzf4jB2M`1DDu0j04Mf8N^)T4abR;FQ zf6@sWs%uZ!MzUr-86_@vB_K~5idNJlr&uW>Ck3|}L0BG`*^-<>|GzX!+%#?S#Uwwt z`+WO(01H@a-5OFOP{Z4vr^^~y+1F+5>gSNIdlW@P2GQF@m-c5ghxt?SUr)MNAg}K4 zF8mN1n8Ycs=ocS}C73=6o$@4=0%)2yWmdRn)I7)8$SVNWwbpXn0Nj<$Lg z*}FauuL{p{7g}2b4cg}KG7kVXN8d?DsZc@Rm`%>nbJQNh)Jw{`)&BMcuT_snW+D%l zKy@onG@ccuE>On1xEx9PJ0cffWmK}@Ee$A1C|r3mYm^&TuZaHL==*Y7?2rN^u|ap6 z_=Rg>m#Z+IMPZT*>ciXn-)Sabstg40L#O{K!;~|?ZJt9br#ku?we{^U%gfH=Y_8E(23VSTKSZnHd>f)0iZX z|3vj>t5F2*R96&A`1P9ETWu2}aNpzzu%F1gN{d-F4$T32X113K$p(SeAGSx^7E=wH zn#JSapM*4b+1oxm8RR=z2!W4({bb8a>R><4Z@s!9EzoxT$G=3l4*MiXgYp9kutqv2 zlB}{=*_0n39k}m6(Q#m?&#g7$&`Nc1Z%^v!E!7$u@Z$i;`!pnR>cmXK;ZcSCYBV<`2KFV(Bo_aXVvrd`-{y1 zkJc&gK%405w)g65T#uxcf$fB2k^>+VrjX<9i(^@n{ZAyrj+jGQ%kqLfT3-(I=jbAG zFQzJndqo_~pM-EDFGUtHyct#yLAHMqs-vmk=;ec}L(EZ+xIiA%9>iYg< z(uxyVnr)GtAShB_^BAX0sa#EITFCFE_=Y4t%ezyN{%t!Xdd%2Dx{lFPlXeFc`wj^R zx%2x>GjDj(8n@MtnR(E6pJwNjxtDOy3OXI|nf@O#Ba`a6CEcK8u78xwl;WczY-XYF zXfktp`tXm)LP0W*BKt*q%PTpUiG0H4q1{Ta&)wnTAAn=5q4$ULFMf#!fke=#-QO4; zxd9SW#@s@MJn7#m4g@{IbI~$|pKxU^v`!(uS4H6vO5_wOBn|&I{uZ5?DC#A^`~KdQ zGIYW~>05Fyi;fZ_nK^Np0CoO1X70|j;7Bs<{GvN@cx>8U14iF+1^&@N}CHA(Soj&Txw0f8C_31LK+OSl;N#YuLaOD=eU; zrA4w1^z`&(inoGAPuHs_A?sp6en|mT!49IiTY?JM{>*#rb*~v#JxkY+wld33sh$lM zZnmyPJ;O*d;};pM6#xq@a5sR0YEE{&1)o;(2OcUUgiKAYYVnA)sVStOg}v`p+lpG` zFp|7e9CNPJFPZue{D7|)xp8E#)<+cfgZ4{}nLOi|D^R8n8Xg(8x+k@Sx;gf>v$E8% zj;zDvl>^(TdrEQTu;rQ&6G*a}{_pzYQP=gQ5h35U@!CU(dN`3q!SyzxeMgugy!bd@ z?&6Alo?DUUxbQvtJ2kdCIi_MM@uwY#C?eZ+zD)v8jyU8Rotcpxs`8Vh7-S zmI1jJi^(B3PB=%7Gs~1F(^G%iw2<)@7QyN-oi|+MJUFLh8Ppx|JgO(9xlYndNb0FY zZuu`Qj4~l>fnddw;-9AP!(d*qU@}%B94yW9a!j6L#G5j#3hcW@ZJw-(sRwYbA*wb# z=c7D5f46_8cPIDkW&aG?IcTAw6{6p8k}sReb4^7OnhWyB9g#F)q^HF8 zMe3E&4G5j@2`gR;5U9*}GT)vtNEiwsHEgJ#wohm$OqKvwtq?%*RA9Itwm`Mc?S`8jCQ1NEa-EfL4>XX~DS;S+DeQZ_Sfkl@6F z`^BbPa;AyYmmt~jQ3l0}m4BTd&i7X>I$d{M8MUY{U{7V#WIPw=box#xVWJ#nt26*hHK&Rw0E zx9Cs0+nT~JkRpT_f9@V=F2NBY$)}r9R1QRJVZj(45)nHL3ZL2d^BfwX!PY68Q~(<07KzKSjHSDO zq^M>r<8MpFVk7CcciVyXj~vBWHaj1Vy=uv^n+_oMcHN@IJs<(iN6=%7Xp!trRt) zoKQ@!60@Nx%dSRUMY~u-)0V|*c@X^azDXoi_R91C2IQP1f~+hd3G>-*4&Jr=C6b6~KYrUM@c(A64chk5~O@U7qnR_j&nEyO#a z&Cb`7d`fsghOr6E+R^XRrWy$9(aUaW@enz5e>|?g2NFqi4N_iSyw0nxdvRlBF9ka- zh=5|_rCTeFCa0{a{2P}fiH~Qb)G_ePfq<_quBVn}M)=p%cL#NPf?Mqei<|eNyTJU$ za$LJ~Ng&pedDkWmI5x0$pr?mM4V^eJZ zTH;995+*s2-fI3MGiW%SZ#nes6~+zwkzN9Oqk{C0^@7PS`i?Bh0fd>4abZ0k(axds z*gL0Mqe`I3C^>aG(a*Md*d!w>>vz{jluZdA#uAbG&VhtpOEgGtT-hs@uUI3()ZkN3 zo?PX;;096;WluhMR}cfBOTO_og70Hsr);#pp0qv|rJMxRP@iR+wuQf z3%Gwp`>)Y4#Za-WeD7m(vcQ~4!2FqEa8gapc?_JSk>3q@mI>mm)F{TWh4Tg(6qnb zSe*Yu2eECWDchO(TiZw|{PCyl3Q^w9i%vO=UBK^q;9g78^Z5T8oA*C|aLND1S$SKC z|9$J`{y+ZNzn_0Y{#P9M?-zhy9fo?_7T~)7B)EW5&_p@RdCVzRs9m4x?X|5hfRa|d zqwMpxH6CSi#Y)54oW%7p@;C>>t>u48f~rY0jfDRu19f}YFQaeHXqGQqwA2L3sbJ3L zEL;4i_$qWF_6Fkt{wnw1gg=dhe*b%s!T7)5O7j4~Uvf(+_FxcS&n9)xfI~k$E##|6 zTU>EJTZ=|YqX0j+(q5N+gAYTHPjovQW6tKCi5$bsE^m&8NAM@2D)e+@D$k9m$&?!R zF35~Qitu-Gt2C^?QDgGeJQj*=&kEfF5xaYV1v~Hl_tvW_|Mz;zT?b5pd+Vu9ti0n@ zq6jITycJW35KzasiM&^3Efa$ha#6LA+9dkW>Auhhh>x0@!*OPsWuI+ealY&*ed${~ z15NOsiS6#kj@&u*7P&nrX+0;ZxL%(TQb$g2dUM!{-~1C)e!KG>lK&xGX8@_Wi`yM59i&2VM|6q8H6G#*w1NG*Nj=@@w^}Q}95~=$ zWzlYcGY=tH@^1@;m&ajdTvqs&bINtL%z93Cka+j?Pq$He4dbUHNyt_Q=RUAUNz6%R zggY;bSoQR`zHs;dY^w3C%M;kF;IJwTt%8R`@&2!cH;o_7615VL{lnF_b7GUxVLhYfE{-<}7MO0-F|G zfJogtui5FQ8mQ|6_G?t>L0NALNLMoNt2PVLV&9jK4{ft1ae3^~wr*w&be^5MQDpKhi}(LQZ3aKhUNS};NT7Rl%NVwVyd;{@DbU9ZQ7#B~1)8ZHT{9Dy^cuc*q~eb` z(5m^bBoK@3QE z&&;P|aTEWs@Jf=*YPTAW?J$urRbqr>=|l2?YzzgD?E&9KrM&A<0#65aXO0;hpK%l@Np$@|ls0R`I81^N4jWpM$L3fe+J# zsr!S>N(w4>MJvoVFjM%-nk>sO08?P4uv(dNifIbjCmEUC>cVp zy_4W!UWPe_(YK#Z`riiwY!!cA0To}IL<}^1MN5v-+dk3p{|+_$a$PXJQv}rgZp_I zP=pvW97(Y#Z7)q0&-bbMUK=bbJ?f?YW(!Hl-PWltI`%A}%z(yC?=8ae+zTSmaKJrj z*{u@#L9+n~AWd(@qnkpgA^DGt1Q2VQ&MnQ!IDa4dYI<#mTICx^Qsn8q^10s~bM*A(36`6l3UX7_hfpp zE>7M>h;`eXB8}#eR>dT#9STpHk#^y7>z7`Y7g-&O#l=t%y0y|9nd;r}oRi$Ur*7k^ z!RH~+I{JgNRh|7j{wNajbfv%n>qpFej-?F&Dvf@vVLwN(ZVbJgVIOG4%_fO8mdBIl zdSWBG-B`*)EVV)PYKsD$dlxf%R`BGB8@v}lf!_EQ=UoDKn!Is(VV7{0&0W6L+O2I* zb22c+hgfZ@ZMNZ^zg%I5?Jp8l7y>RtZYJ-Bguv)uU-ZQv=nI37mB4)9-e)5#lW)Jm=8efD0(hTFNbyCz1@?_X zIv-!EJT7*)c?iFblDsd4*~}}~Ao1k%u_TsI@MH=Zs9Lh~&ET;TWTUx@x|vLb)gvNo zjCcPF_qd8to53(JG}n+IJyAO))zszdxyFp`ZagIe@r;YAg1+&@yu`hBjBBl*^pZ*@ zk?cg{h_%Q>Cc!3|$3>oznZPKZ;qLYggz_Z=Owy$Jo;l|6cz%g7$=Nx2SZix>hg6d* zA`h9}CK6fAI#Ql8zQJkUx27(h2s`iq=l(0{Go_`-;qyWAeNiE$*$|usOO9w(~9BjxZh0QyN1B;`k0f+*hMoK>-EZ=vy$@iS7pxh0}}M99xAS4*|&WZtd251-CqoA z(!%g5>kGBB zK);LI1ECWM^v1gZ^c8I4=5Hboapp7-jgzwV(!#6rLWk;FlNHiTzWe%OTyw&Jl*<9j z5SSygX*Q5?KI+;f?P%yT&4=FxIK>u1ka?UW7Z)KgFHcJ&cl2Drng_islZ{_71y9u( zyyj%qvtahBY&)iXq4#$@^P)H?v|4Bjg9-Qhyx2u=%d60(4VADXl`4BNN$cpP&Eq*h zMrIT~UY{lYkg#mAj+r<2GKuw9Lsz51!R6AB$c~Oh%Is=nluJ@QmGs45=>Bep3u({i zU7U;HsVF_^RZ|gMAtJy3fuG2&9Hj+AtgAs6RbcsEXJP!IcZcx;ac%CQhj@g76cYQv z#M>)R>%E~R5vx7=EL1uv970>2Z`*WLO2bIT>j z{vIq9A0{bFr4tEo%}MQXFqL8V&J>ct9YtoHf=L_=EPQ;cC37uy}t-Icv)1dU*AJ}{6X`e5VrYc@1jjL`FBmU0*(AR1KIHI`G<0yzPfd1E3epk zca?;)i(l2?YIUmt(=;azDIN!OUP>i@Tcvp<9vOo$|T< z793J?5l1*bV%W~k=J*_YYyYcw_OfR6U>U-N_h1$M8kc1kXE$4SNKz}rHo4KMzhlx< ztn{ntBhYK`>#M2wKf|7qiM67f9a=MFDH6+K7uSUL`nHy)e$AohvTL?N{;=Q^*T$afZ>B_IjF|aZc;VTPg}gmI^%C(>|IMV&5WYanhSHO>@!Z zkLn<=TB4#^*C3XiTIAfXR7FQF!l1T{lDBZRGM|QxH!evFJ@ukt#g_1NGg5Kj(lRpNgFD@>IdiS1+6k24~42pu4hTugW3W7Oqli}u~VMk>JYg*!ebs%;m=2n)3**rsuscB2Cug!%O(~8)1se1M>$!{9c zXaB-HIVt%&?lvBDu7Q0nzV>Uk?6cr?>>Pt`g~~+vHf1=sBag@&2NNw!pWkV&@*V6E zLk#E2Be?Je9a_Le3~LS6h14PlfPaCoR$-AJ=B@QR&-K#g6E^6P7eXpP2x|}0Ma^AT zAd8NguQF*60(<1l;(m-p>N(xoxOgmIcnex#?jHy`Jcz+=T!f0e2D zEM~Jr&iu0L3)c#DDWW_d*N4$9iHGO_)l+oKo@eB$|=x;kFw^&+nxANf#MpM^z;IeGa|%w7fyfUm4>Z2fu8F@$mMK?CCiL4r;%SdlnQho#7Z>p zO5&-+#lXv2U<|Sy{QV)$**a>Hhr=`>`of7qyf~grUMAOI{FAQgihx~ z`OFLPGC4}C`eDMte2F9~AC|s^GXg$n**ffMoKk-QlN@CJV3;O4$xgvdk$rNI;t2P3g|s`QeXeivLpEpYBDr3P#mfK9xU^jE*F zO^D!Sph_<`5?b=C8aE&t)^OmU#ET+6PH)sS@84Fd-URlNYiVzMKJ!37N1Q+CQ#xzG zJKWG>G(=$i9t}dMZHO9}nm+6c@;|uPz=tC*las#&<|$(Pj72vX^u~TdAS`P3yCaXV zORWP6kJJMeet)T|Q;@?D2PIptl+|RaH}MGsD7NPJiS4M7B0kbQ>Z?lWSNxnC>PFzy z5sJRdV{*kug8z~J>x>Ucb2`hc6+OsO;*jS~L<9m?vGglE2J`w9Y2#k&_YP;D9htN` z%2-A+giew&IU3&qZYPW6(oz2(v@1Pdz6`)09KfWB6#g#EDum@#m#iH8(p0XKsubyo zp0Py*hD9l5n`-Ke%UI&)OmWP%lr?Ex9{N_eAQmZWGiS$1jCUFp4PNN1V&-^ouj4YNVPnv+#jt)z!( z-8=gS1V62x_8kJ?c7|}thClW3QK;K+^G$=2>nkRmkd{!sh=i-EGi?aS9Xvxj{WRir z)TaBz>Oj(@sPg4pBzW4`=iSvIhYM=E|DI~nb_gZyDOLlm`uWM_mIm1fNUQ6PkZ?|x z3~B#xrtk>eUsxcmc!kf9-wqA59Pn3-56|pddC|q9fg^PWiKoj)%mFQ_=%%+)IU32{{C$En-y9-{Yo(tWlpD?CQ==6 znV2D6xo?gW7Lu4gvC0B@s@42L+#xziQ4lY$^S;)T0vrI@+ABc|eJbXlM9O+-2^}C&i zQIjyY<-pxJj(Qh<9&~BLZELVO`EqBIDf@)ar0$%;uzyDw_(~_I=L&z`;C}P>Z6sZH(f|! z{TPtLtkGs4O##QDc$foB(0E(J&Sh~Vt?<201Cgyd&PL>FlO!8v@Kpw3Dm;VtH)${S z#4^v+fUAk_`Mkm&=!qe$<*mP?5vn_#^5Fm*w}XZIr~0*VQcd82Iflk?EN(UsN91wE!A7 zoN>1^PLgdAJID$-c|_d&i=)G`16PUzQQIFR!X{Kd5>HKM1q58yx38V1eVO<1;NcJJBhk{gShbE`d8Az+S zWv~I0>9*V4^g362)~F{3Bp%H?E!uP9Wc(1laY##L$S86Fl|G><*N18lA|G|W}++O`_`-4+X1X|XncaOidI{Ntz zV@%$9B}eoJ1Y&pCRt(aH5hO>n2jU|7KpP4E88>5`&S-pSuIfAIrjP-&>9UT}<=6dl zXkCG_>-E0@A@~yO?tLt_9@ZS9Psi*5NLt@qOw`a~pdZ%rFh0jXy%J&`W9G(nhD2z3LrX@NM;q0Oj{n3K3Fk5&YMi50 z4}>QS#C+wV*rlM~+uslVJxNA`zytRcZ4|q8x=B#zhRZ~o%eJKEQa%S@Wz@#eGTich z1vU=9pn*lE$QImsfgd^Eyec~c2jfXUdKQwVzjlEA>uz=Wyp4!36}bR%N||r9OUo~) zCGX=RIjGGoVYKd3elO+f{(~Opq1xG;DBMxhx?3Bj_k+7A=OdV*C2FU4$LA>C)|(~e z&b@U?tK$++&(Q{KoIG5QjnAK?RH?YdF`h)b@^C%bop#|)9Cfwd<;ya5d!vv(5b?Sp zhp(8$@-0XWy^kN~DpSRpxF+|kWG$PZC2&;!e-q4y7C!f=EVx*S(qI8(2~`D4|5 zXXu1BXk3T*&5G5X-|yt`AANu39E7z*z!sv zq=?iDUMHkbM#m^84IzL>om%d8FBn+kB|!)2e`Ac$!bfuTv*b-1OA%-m*|mrpui_ph zWXo_(qz7^qF6wbqCNb`*z_?t!()5Vm)&AfV%d_W)hNXgXr^%;XC=gGDMEc@AaXNMZ z&I}7mej^D}3AGW8xnd;P_tCK=?d?g%Ey5d$N+7+T6YEMJ;F^1#%_^QG6Wy)Ovn}HF z5vhB>*|3Lh*ANpcb%xiC{(3V$#=lNY9%R^4#U}D{kFp=8i@&w$)Fb;Ku01NRYOs)C zXU%#Zejzo(XYZLb+#)I?$ z6QS5MYB#}RBWYNcmS0=3n`{toHmz&)%bZc!U6H0%wI&N8UGV1G%ZlG^yHjkjr+sl8 z7kP1Ex-kx_V{?)3ywyrsO%}=PI(j_Xl6eZcWJeaYk;aWEKRWnQ!z-;*pvY{$zZ7Px zH|J<)-R#vSmjlqmImURA2>Qes%-DP-@v?{ECFa9*pY z)7NxhP&QrV|({A6<#b` zcHS?0-lLQGlA=U-FWa*GDQ;%BZ<>)AjCu9GO)fP}ydP8nbv8L3QiJNw zmp*_vXUm?zqI@aiyoFN(p_pH(OR1Kz-6At0Q9OnD=hhdLbG-K&5{2GHMRQMJbIPNw zV2ZZ$(E#ZK$i9b0O9;>L;7hqrYX`#2G^+mqEU=P&og@w^%+3!%@?Z8I2Q=Y`Es@3- z*-v6l_+v(Y!NJG)^HSv==e);`YFKNa#_r(S#o=1cJm={=|=-7 zRbM#~vD&dnTO@_KCZx<|3Y4Mxd>JxkAUFqrk?M7H+(Yj!gl?|Z*=Hj!bmPX|UHQMq zrqvMHAw^79$Q61NB=c*sX-3F#uZe>-;0Cg?XE;pxz$xraZAoA3*u~!wSdNG9>2O8b zrj|z~J;trkLo#} zGZa_Bqfr};?GgvuB$X?C9>#X-r@JHNc*7}Yl{+DzaVfiO&=&7W-hTVhkM5ClnHwPl zt3HbKnj$@WL|LIP+1#|z6T|?tJc&i?kPS?jV3A{K*XhxDBz=0I`u5j-IWS1K?%9b% zV(N1MXlt~wjN-qWK11Qjc<0hkNIUgSZw)UcMg`npf%pn#gV6s`)dP3zh1Oi3PS-xM@^uEv)-048%vc z*ZzfK+^lvKPK4|$yQ6Nl(k`oMuTHP ziV^F=f$N&d7B-1GZjhyGPPtJ|;Vby%gKF)$az{Oe0(?%p9p9 zo@o^KB13Y?Knm2_P}G}g|1GH-cz6jdw)}}ojKV!9xd1y*%iNWO#m#=Lo0%6knN9ud z#G?1mcB+O+Py{dKwy=>_=H!R}ZmT@wL*DhEa7+c;){V=#+j7HgZ~w=S*sj^{Zx4Bd zZdtZg_6zo#wQ`8Y4xAw0>JI;~q5Dlzqz~JMsr}@_gkYA8AW*`1&d$DK!s41FBoYwx zC*RA(sroF&fY)AMi2b)T7f;iF_K%eNpSsZiMwIRvSC=%k^w{w*4oG*k-_mGqKRetj z)dIHqWgt_z;7$;T=X{MSrxrg)!N1IFnXj9AdPDOW|CLB zpNtQ8R?;I~Rv=;;vx9PmZ^b?;QIoBbA1=Udp>eaKr(DNk;Jlm0{fB;W@cp^@?teKy z7{mhD20;VXz^akmIRy^c3q4xTQ-|D7{9MO9?u=1em;q1fUO7L4@7$@;fGnbxAhtW) zTojURBHrRY;qa6qkTj2h8y|@Hszrpq8mMs4QYS!-EvETr85Cj_`%=j5d%03G`)-cJ z!px$>wjlA&9PK;DHB@)~?Plzc|8MGaXA8DN@}u6Vd*I~0$EWV|muai1vG=e@5BofZ z0+6AnP3P%0led2|ty*)2g*jX!)vkKD)UGdZC(PtJx5VO}Y<!_gQ7__(A!N1pXi7<|jGvOiObK8Xk+i^UW+D2Y$C!p4YtOg-jWr49=e(X-0Wypjam-@l-+{eU1`wlB;(G# zVY}2^_X+Pc2Ec^8GG>s1+l=ylN!12Ky`DG2vLQen3|Re{R}CkbugPRF%=yCuhC^-l zNZK!b-r<^`k{o<>@`ekoR`Uw#oJ?AqnjR;E{3?Hw4)|Ipa;6PR>y7+Hx7?l&ib z!6C~T+c%L#Ji`I|sxV_cU5sdy=FUyo)mF1@JV$I8<|8xaN&@N@duEJGcgo@USyazc zY1yxAxwZ}AL93hyv(zu@9{*lx#+HZAu8O~-NsWR9!VMJU@%>Tmj6f$Ixqh3>aVYB9 z1J}^~P?a-%FV!ZguwXEnH87YhNo49MnMT>AuzmWcM=#Z$mbi=Ufgv2~TVG|G-)-aKmkrqu`RXER zoF-(y+jzr3v1At%zq;v=_qrw?sAw|xJB55>I>KEA&*67>a08-iIMEk1xa_(9$Cm)_ zSi!LEKpt_~+WCb02#XuVIg!qDUK*&9DHU#dkcFeKiy)7<3x0~tUdYcX9t{3zyUycP zu`~Q5-m-z{vTA6^kY=f?tJsTt5J#Z7xC@bGZ|wq=T24E$1(&fLoMz2^gy2t0;^ zoM;&Rk8y)xz2N5mwQpGDg)I)a5+Gs3ZLtPQ2Z4&IP)`$tP_R(%z)=_ zVW?>lu6w3|2`bC05-P@kVnYnRDF*ep4Te^k8;{T@u{klcm~y40SkWFOpsIJGnrVjJ zMJla@|K)4K|9yeU!3n@7BR<}bd5_+LZh1iWBi7aWeIG%u&!?Aw`rc*6P?@WsNIQv0 zJ3Vd^4nA-(iJBxGA6OsqeH9CNzBjsod&R1)5tg5Aq`F` zgjF72qp!^gP06EID-NZ&!6dWbbg!|^jihsRB3Hnvmz@x+5Zn+=; zu2k4|0TM_5o*x_8C5`U4Co4fK!R~govAYPsu$Yzc2hs3@u#Cf=eG-p3;*&_#TO)E%HRxgWQ;`=BNbX!%sV*EIqr7w;JJJudj~ zfo@w*&!11dGuvJc+sd0(fe7U*=;>l;qA&3E(wn@6?)tjw==9Y~7w-}FLHbJv_Umz* z{AGl-&25QxS%Xw#=L$p{Aa#GA=zX6!(dYft=Z)Cj_L?23{!ndth>wq-c5@AoTR=Cp z6(iGEKY@YapMK{p2>oAYv8ghY9XVfoU-kF_#|8W5hJWbYOca|INuWoKu z6RW?zKPY*Bx`%$I-CvFPMX8Tu|8k5k^I|#5>x#tdDwpWI9uT4Qczs+m?u#Vg1_C$q zg!_NeY_HAECud7iMxBR}p~4x^fq-OU{_9SgT)hzzOYPsx?K42;|JuLr_2u;SW4m?R zonHsnt&{FC5LhyOnAywGprbc&&Gde8?RoyV&gSgZ6_Y|i>KXl?sRB1sfMtkL=>nws zOp&(i;1=Z8>s+@3FrvG};lU=qjJRPu!KWf(TBEV%Oj~^54mwW=!tN zF5oRfZj+O+P8R}R#mLwyqXft*0Df|S6Q7I5TY|Hcr_3<}(EXs8Lcb}PYbr043MJjq(>2mBR z5PE})#s<8dPnMINguq*yL-cJzbB+$ryi!fhM4u1?gPcC=lsnS4261oyT{-o-h|N5U z&3y8I8_A*znAyAq>uk9u0{;lM_L(+C#Tm48=R=A1bLg7Usic$Xf4~v&0RF`7IeZ6TA)4y!e-;D+$JzWz$Pjs{L>^}AdH%lhS zQDWTv%s#73{qldC0T6qNsd~I~;m;X_b}3o*|JX?0nv&|8jI5w=m{efAOLQ}eYAUJ6 zf!6yON`<6GBdIAa67_Kv<=C8}tl53nk%(eSTIR0ktv7^lUf3_7!KHG3Pb*^-$o1TJ z5xuk%0SOxzwbKYZwg%g+52vlSgs-RCPw$slE!Mq@y0Eu1enW8USwa1u8vuu;U1JdN z{yrANRS|>#wUmK*a9O8E%ZkjaE5Mp8Yi|H4NnS;+!sS8sakCS7o)hdIZk3^m-QkKa*@+A*jGORyk{~p-}Z12(S>(0 z_1a(6JMWiEK6xW8$BE`(&04*x zyL#`cy`S1v?-O21IU~CuII@nD^ow!-b`|>l%ZBQ~_v$kO{+W`dh$Gs}g1EKTi#lXh zpOh(Ngg2OUHQubv8R#yPymK&@If_&ERU@`CBDfPjapw_=f2>JaaB!YX){N9Qz@FP8 z?C!sos1rm!LHgu9`vT0@^vi%?afjq$j&2&mS4H`sqQ{$NT9CPR%f8TOZ37=?`n#b4 zl6s7MbCvc;{WNacS!YS$smls=QvGzepI{0-T9h|J((Hy0LQsA;2%?ce+^y8;wGzRSCx zO?$urOmbHDr$m+C!C^ORh^Bp;<>~jV5k{2<#y^_{%RD7cJQ*BhHJ|z!>&!k_)8cL} z|418jf>7QbVln6Ngxu0zE%81~zKoktX#TKn&#h9f+X-#{N5u1b!A04F`~tOlqKINX zlq!_7IwRQMl=IaIe1-Xh4S1F^Ow1TT>*9i!Yw5(it8jJ~_Asx~q@$EwU{+{UZ?H-G@zu4)`KY~Qq9wXLhQ-yLh)NY<**XASGm ztY^O4jF%k{u6*YIi5OLv@txwk{u~d%eL_dQEn3-*a{m?2swnWgHfCvxZu5EE1ESmB zr|2{Y6Ih`cyJb&&m2X-Wa=xyKErn`qjqW)oyOZ*2s#IvV(oCPhWWl4yXlxe5ro7xE z-TZSSn`b#-7)IT=>maoCO4Bw^z4Ep8&UTW@xnOA9l%@n<^p+gnK%_IRAYEkUlgmpa zobv*<8C<@qgL9pRZVsC2VX3c7g1daO)i^7JzY8Ee>TiT+v%AXZ_l6Jkj*8;v+(qur zG&l{1#X~q|KuNPg21* zQ=Q-Qf_kt3sm&%8@D zzY|5h7w9=7jxwWg!ecs;k@>F4TsXtQ{Uu)3O_K+YoPCG5%DX(O)R0jgy(5JeVI94iXR(%DkSh4n&fw#R`I&2n$exRF zz<1&lfOy`W!bz7D=*Al2RF(Yxq*ygk#+N>P*jb&uj0cbKzug|E4ZbNFF#AZ|h}^#6KAI z)KInXr@#Sa1(!6W9T%fEKP zDv)YE2;(eAG{nCY8AI2k0%F@J^L@pdmxH+(K$#_=m6^59^679_(YLPbp@%jIFBE4* zeJN*(VOH0E+Y48{4l(mOpH_>}q2wYHb*oxl#x{c;lV|#HhOzV+{k|Ok?V(_?Fu! zPr(!S(9lZ20Q@m|#t+^`%Ll-$Ku}r~ZPU$GQk2+RLdoiDCW~JP*9?@mPP%qr+6}p~ zSI{S1nee(B$4aLzaT|VIF&=#4wsAGZ^f42UhAvw+{eF)8V%sMX>1%#uv#qd}zliB{ z0bt41s{Qlv(Zl0zJnih-^Xd8-yH=`R=jUOrX8hxn6kXO1PX#<6!I5(YA_H+0s!M%e z)O{&aC#i43eXZSab2kTZY!hWOBDrunnrx5^_2{d$JmK~c>4h1?hs)*3?iN)|O-+rt z^D|P+GjntO6Adg~M1}(Rk##jdK|3uY?F)F0re>yP%?Y9c`<=>Pg`}nFr78XUic>KK zN$r?_xIVD_il5YVo9oNvLzRz}2S3M)vm-UtR99oCX}0I4q>%A9MSR+4rkZ!>4B_iw zkog*sO5#Wpp;r@u)77hFXuGnw*`ohjUX;trNd<{b@=%z6Qv8Tr{_9tvVp8TyUajG1 z=f!@CNhu2pdP4{FL95)~&fL5|Nto+ookYc!uxkc7F;i7kg~D)&S$@4wpZfCkYkMN- z;9{QDgD61~QaHjNit60j$D&o5Gj;Q33JdB&y>vp0yKekbBi^*OrlRB_Gt2PI0*s6y z?UmP+TX0#Q_WELl5wo=FFBPE<&U{jYN3yNZ0GBR0(Raiiv8Ft*YhW zQla7PaBWA_>+C_1HO`T=$Qj?mG_=?yOUKb<@QY6BF7CDZ)>z-tHy< zVFp>Xur;-b`*IBwxl2v;mo0V1D-BJ}2CLNZUAUg6C`{>7zA{#saJg_d&U|C(G7w6m zJjN40!(hKpy~>fzlRV8HuPnwq2T#m=g_dKduSCDKuU#_X$78vY=K9<}UhO9aqGw6o>Xb&H1?r|(&%u{>aC37j}?7J z+PM#=L-U;T1|dv|re?ptvx_+bSqIGa>c!vLIjbJd4+~#!_*3B5L|u4ro>xR9e#T~# zKP5`tM)8`(KA>cZe{oNVfM)lQa`Uq%?EM^`f63=fMv5J*m(HKCf%M?g=0|SK{sp6* zxJ}VZu>PtI$b7aUVDT9fta{LF2iD`?40%DmFz!kvZs;(ceHIvU7k`b?;ErhG7jg2Q zXBxSBfSZzIlegSL5g(p~s-Zzl6D;y{Yk6OIF05HLa&aZLGU&@Fmu_GA(XAo0kxypT zFlfxkhWFc9ZDA=H^#a|d-Wj5;ujAH4u}*WK;*`C0=6Fs_7|ZkFgj;v!s1I5yeW_`nU5B`gxx<%Ggij1x zb>og_SnlLmPydZn_8)bZxINbk5zN_(a@)d;3L!=7Do70?Mz9OK+ z?g7Xw*qJjVs~eUX-{7LKyjUrALLWb+Et9BW2^+?Z#CgE%Ii&5%@XRdg1< zEHPHW_0iEU{v@CO4w)-pd}3!~$+WG4-hT-@lfy2|46FXMv=7bP`fV-eMC)E5HIQ&| zzxEs2BsL8!2z)%g#^pNgXr1Fk7$gNP{DJ9iDPld%l7oT5B)B(IC3R>}hK1BnEhXLcj#lNG)%kYjYwk%xJ%*~V9V+3*X(A!7NaN~Od?@)yH$Y1iGCIC>)aE3s~o^t z_g?xFSmh(_R>pg&X=GRcjS@=8M}2G{U)_1Nt^zv;FDH1s`4UOmcFd#4&$cOgi?k+^ zisUKc3GZAM{lZ8eiqaGTY>byg08Y-zqnD_s^U8g1g@DR>jp|mD_GtSvrfrLrsuTTx%o+kaZEm1vhwfu5u}1veC>#&d9l?cD?rEy&XISjO zQ8(d?{lN9eUl#wwQGR-xD%=_U(p#y>-oWLw7~jLTI5?-(%b|v#hGE_97m~VmUkQVt zQ4!45XB+YdDwgE@ttC?m>t4a>98I@E5y?;POP|JF7_SyJ1@|Ecd?@lMp$hO7FvNPQ z{Ov0U;v#V^R4?I3f#eAmq?(@Q#n7h;pP3v>byAzV*w-1?^w`a2l-46Y=QAT*ijVfb zwXL#yO(V+T7qPDo@yvTvw^NSqCm>o2!=D)4T*RDk8j%>elqQNH9SAm)h^!1gC zi;S1eclk7@CC4S&*e!FfyFBCJ9o$J0spQ@<6>$vfN!%C11BP!A9-gclc&^kx7WBpR2-ObL_aG>nyQU zv3&MjBaoF%s(FW^x-|-}JG{2L3k6(4N5S$90-u*_-9LY?!-Gha9ld!wf2Ma|=nu)y zik%34yW25?54Wd^7%qb7bw^=e#L^UEU7cpG(#gm5dHlnJE>X>L?^uoA*yn}_L1&)V z&gj%_m!!vj-c~6oY*7T=j~|wRoSgP<;ytpDxZH5kkD;-4WF@s?8gF!xY~*)H_#o~V zG&*C)w;~axeSMDR`_i@3@CeB^;|&^ytyej9fWjcG8M>eSCA~Z_Ey_f)jp04ZS-cKb za@#*pCg-^l($KH*-@;KC`kOB_Q9C>>A+X4f@m&wS*y_7@GyA*q{>K*4o!oe^qz0!* zy-SXFeQS8dcz7wjKg50c3s>c0=^ML+E-pISUgjuu#0iq&^IC2milY5@-tm>jzgavu z1SBw5U)|XBeYfRAAV3~>pz*yGM44sY7$Vb_#aboRuqU$l+5F3=_5X+gK+yp8@0+~> zk4x`(dZ2hFA?}M1t)2p5(~j`Q1R+k7^2Uwu$t@% zjx+a_IS%{vV1|)3OlT$n;Eyowz$-KImX!C=5y1yGFN&PW4Wq`HA?)58dUu`5M%90h zm#{rH1dYg(sX*1;N4#zOop-l?&E@RI4hZVEnoyN_)taeU_oW4%CYz}4&7R7s8|FAW zsv8!}>SIBEeyjEe?GM<1Z3D1Wgg;vWd3Db&Qe|`&2=NiY5zMQm=K}oEYT@!H1V}o= za3)+#?Nk%C!87HodtN8CD-i7QsaJ=1=N;jc+dt*k2xC};BQEt8iEyzvaSgwmHm_}6 z%@WGDhmBUD^%zP;FAMp2H;_uDFYy+dUWUAknaj9%`}GlgM9%bmz5mT+Hyjao(q!#e z5&P4PN%G8R*kemPv~(p2gt9r&<4x98xRe`0TElZ(_QN-CxuP>_e-JPfp8<9d=FJ6# zVyE;s`nyB~6Zu)dv4MOm$+)4Bbe!yoy&Cz+!5gj7HlS}avik7hm)v!nHV@^_~JS00J5(oOXI%u2{uYI+sn?Rz{+UCv^84G%8%cg z`m=~sK+Y6`_>708Qj1C(gT*&Wc|mCe{JF;BYuhb#&29K_6+SDEvl=&J{JnC@8R-ft z%Bs_X){qU&330+Oxfy&iWr6Rqv1NzX>$Q=@kE3+BA11WbA<&htz|hlr_9-mmwj&&u zYg@00ya+_(^IQXtgH_VqO@^{nJlT(uo<^v2ir(_Zl^r0XE?J~`79E(Pl!peF7PoCn zI}OvZeyoKL))g7nO0u5r z(k-inK7nHag^`lB4N^IfOZ=GA&a$QxyO8p4Y!!!u(5OpCf>TKrFv(^x$&yDu5pg$C z?OU)6t2UJ&u;FE%3r7tgv7{>TeYIrl*XpY@?60LQQN!O!c+8lh?wk1raq-i2Tq~xH zqo=8}<4PA>Hb}@t0#*)%Q(cI*+D~mYeuE;$u_X#Wn0jitnx*8C`oshz^B* zZFL7<7L^8SJIP1@SDVrD<5kTp$O3O3WU>BSV~o(z?hnKq%`_6%iY&7zijqy2>AKNY zyU;E=8=ur6UmO)Y=wj{H82(A4YR#b-0+nDqXa2b%CiR=ltg9p6XVaG8%JMUn9R2b# z!;?AV4`X9H!VjDh{dm-8(PQ3;;PosA$izq8PTMrA97Z5;DyLZr#wbUy?*+{gAF^#; zu8e-XJEh3bRyzlCMU6VSIlbBm!O`ZN5$xD;m2R|c$2HfNceG1H*_ei@P!7_Yk+}{c zWcC-MU>2SE&F*TDZRsSgKWIJjRSVv`2_xD=N@fw2OjgdgGf~yUw&s30F2(oHc`$^B zM(9I>j<1j55RwO_B^b$cW|xAGc`9*eY2?%lw!gB^$-&vGH?XB$4O%p(JydY-hL~i# zP+kQeDwZqj+t#hF98P*v7|@2(D1F$hpY=mWtdStbD~xDVjLG*pvQ69|Cvf%2I{U3L z8*E^Zs%{yF{)qD~#%j>=-s)67@j!xdXfjr-Mp@xP*0vp8hj9YTDr$FQzQD1sQ7cVN z;+myTp(U-p+wl~P?vR>wSlw@8OTiQV8Y}GOL_E4W&n7`Ii$`L{Q(UmSUaZ)rKk=^l zyZDZ$;iZRec8BfTX3w$Qly)gqnflef*^CBf(BxX+(3&~z!NT_6 z@JBH7%mZr0pb0_kzrs5>i~WOkkyjK=V-;{?h%q{gFei;OBwT7Rjux4j#?Oiya22oU zX1k=uZRc!yA4mmW-F`wtqa#cjw=JNVs=kOVArwzy0-k+|Z|l zZjq&VpE|*n+?YbQE}}~aGvRu@>Y(_2b-kB0YD^K*+d1X~D1HtXEYf%NzXdi(ASUpq zdM`~~Xo4O$?jqN|-g$wG(6+q{(Xgb@u9a44e~^8yt?`@TJ1Ecf%BP{I6v$eEJ0$wu zmJmK>(<(Bi8D!<5i9zz*?1Vr`Mc=%$^p}wAh~gg-M7+BfU}{898`-)Rw07T_NR%-W zG!V_p^B7XFv3RBfH6@EVTLUoB@UwypW^Itj(1?&xT?+&6QrKdSv;ys_;fGBbG4_E9 zZ&GV!9cIilscA_PU_}yOfA8 z3_@#zAG|a$YSHE9k_stN=UHoKK3#l?nc*=Kf8-A_&{%z~ZNO4yNCBN7qY~AfDIC#d zBAeTz-vEi4;|eMI);6MMe`TZ=hyn9^Sx%(a5k8g8efry`3(8ecXcS>Yu`k-1e*MZE zmgCx~^j>|M^*rlt2xdY!P4E&v=}|JQS*7w18*1qqIlOqXS6~IJ%u-&^sdneeSpF zthBuq8pH+u&$M9`PH_QrytHq2-0No%_L}+h-j;nzD|6p;7u|h2F5+@Y(rZDR88S3Mp`}9GF$d%=Z8O zPR?{WEQnl!=fk^uL*cY2TU89pnQDS_UO9ccN@-76lsu)cvwXcJo;vzCx)~cV6i#4P z5uKZNZr!xi0#sXbD|(>dUyTm`aMYT{^&K2%snazkAy}M}?YS(o&O#_L#^k+!5W`PM z>}d0vV7X)X+z;Kv9({UJKb*;GTaU(H7MWjkpkHe@xlr1hXD<)~SD6nJI0TrA^_7J< z+Kg&|2}_x+qv=(6lsS6}XM^{|;{wTr-f=ZE0|UoFeoo13M_EOg3&$f=%Wl`q9;sO1 zh(EEH@XxtJ?Wj(ge2SZ@S&qKPadyFmxiS}KeJsc;0dCvrt4o=&?urSNP-jn8u@9&% zHPwD-<83qrWL0ir0}o*W2(anf1^{q_XgpfY^280x=u9_jyNll&<#`-hV-M4V5 zgZu}yS*-4=VV)+zxzlSi9G#~ND^Ze7IK;m$-p=w!G+lb7Dk*%eCK0Y8MKJ58%3@6^ znv7cf@;4TMGs8kI*s=QjDnjHjOp8@iKrp}E0Vax2b&1E@>86*Vc67%K8j_{y7U6Qr zM?_)Qh-~G6;ULMwW$QCmwceKv5!u9)WdrwWTyt2?b0jv+GnWZ`@ani+Lklh<+ok*9 zCwKDM5Y^r(dXVX~NHrrYO0e*FHwE6%aZju=8>T|(LtMB#?zX?>nd;thx4O&(UMDgy z9=@ z@(sLY-scS|sHw0sj-F!qVeSZgf#A2!{n8IZhMAH9#p+va8u%oRB%dFCd+He&^Vne8 z89eN;b>z+4qNJ|9DyEdbNyA}8`1RhSHmJxg{^f^r*A1Zx`WLtyXzf&Y1g&b zuN^!Dw|za~W!kK*l`!-zMAxV)a9oaI9@epP4wWrt9Bh{cdY}$Bm>-MV_}KPKrDYY1 zp-pGsx^Zu#h8AW}xZ}X&C292h3%+(RygrYy2fg3JuBm$a-24>mX=!N1u|Cw4%u3e~ z_9f&i!C`iMEj2wj=!U{!Q8u^O%Pc49z)Nv0Zrh(D;)SxN|G07HIv?UP6~cxbB>|yd zT}OCi?@u@iw~+kwH`fxs1qdk{%54)v1{Qv~=OA{MV3(i2PwwwF;U$=s&k#q&sTZX; zva-oBs@kk%bl??y!}#dX4vxU$&R(*PW2%Fp+F+w=rpYfWk>li;OA|o$=@;S7DEpIbkj>KaSgFCUaDuIKU*c z=eE#8HazJ(hBa>8>~vtuU-SFBinj;_sbqKQ-bs_D;NV?C6Cy41ID-_sbph^8m zDF`DRv+^||JPoY*+}%obc+LlH#hL%~?Pt{bB}_O<;fAI2iIu|`Sb($d)@z`g7$P%! zYH_K_@p}5ho1)Z%i{-`-yf-!6#-28U&L-j+J?n)Pjs zKUpZ^Sk>V*Iybk(Y_58u0=31W$CR}84YxCc&->lJ3ndTl7nD6O2yyKB+;3U zNjLV=r8%i|z&+>oPS$r4^h=;3vZ}Z< zu(%V@&6C=ElMipEr^=3v;d{@;(ehMHW)51PJ|TqbG&kgF7UpEudv)+i4B(+mqd&+Y zhd-RFgaMaG0^sIU556eFQ?JUMqV<_^-TCRq1p}}FbUCuO;Xz@t5yaacFqRjVd;)}TmykF(C zb(2rmXBR&1^N7o1eI=9qoUaDhQAT8)yQ`CEqJypErys}!NIPSFwJ!A<*E-J?po@>M zx*sfQk&+gjOC<-AoUcVr9{I&S8~oh*>b{J~9WMI&ToIMlTFPAiPM+h4TzqahX~9A7 zUL!D+d@i7J_YgeSYaEPSlK{eV|U2ySr;1o{=mbQgd)LZyK3HmI;$(kN>fD zOo9E|;Y4l{O0;YSL$Q>Q@%u`e1w4}EhsNezdv!@z8Mk@fY|WC4txfEpbLuFf4ion} z%;7Fhx)hf)le?iows3l#dy$wvN+@B-u-ulQ_YAFrvr~tSc`4r6MueA>8o^LFG247* zhk#fVcN+2I7QdZ9z|AK`Zd2tWPdNu&+5s%Cf@rCH&cS_7(=j3hOF zz_Ht-v$NtxM%(5A&v=#@3WTE%#q@GsT zQ&}XxU-aUh)t~$AFd=2W(*6ne;f%&Nn5BU=ertE$uB?Wjv>^FdGxFNjum=yG95b^Z zO=~pnS()`j95?1!U{&w5IHwydY@>qPXahdk@#j2yC z%mJM|a|?pe2m)Uj5W1%OVX{njwZ3O=(2WO5f|7e}%5s*uH2o@abbS^R)Hu_f9ry6y z4_$zMHn@b+=!>g47p-UqGK^kZmb{FeK@S}c50~Y-9K}|!}1QEd|FKoAwWgs>~VLeSi~O=<8zROGt`rLgeo%|&~wEkvNHs0+k)tMrPzklVrML%c8=S` zEv`=@U^xqj%>o70QPh5e-JkSP6XXbZB=ZM+#lZZP=TuSwT#6NhJ)H>V{cm{{__k$0 zfdi@Id9u(Wv$MT9lJPML$iJdc`z!EmzRTP3E? zGbrhy-(BUtkKi9~h{&}ATamGUZMIr|5lN_+ni7HxUjvgo0t(uW@H5=2y6hp{pN5!?`SS%gVf zr}cz<97|z+#W$fI@U`bdJY05Lp(2;T3oR|l2rs^U`{tr6{M__wHyeVEey8j1^Y^Jj z&g4m$ALOlW@+B3}_;ypGvzB$jDOQRVFd>qnCs;lXMRE1$m?aK}!n%&$@b|wyUKtZ) zplh}{imBwVvIUey<~S(9A7QoEzF8T6RSnN`a^MhFBZ->OuBxgEr{#G*$U!4S${e1- zQOwQ5*p7-n+5-7FvUR>b~1CzqI1yt%Xq5 zeK@MoA*--vkb!&;p>3FhC@N#t-fc0}2&}ci{WPO|w504>B6c5tFsPGXY4HvkUZ5qh z>l+zkdC}C=M5kQ#17PvjZ{OG?<$Ak`JO?P#+@LPpr8lOSfBu+8Cw-npH9_PaOOFcz z^Kt{9C`yQGF1LRP>(5~*j$s!jA5!I-%TTO{#`;86zZ6vSpN!_>C|ZR6=Brtx(5A7$ z&SX!<*y0U~2p3QLQot2_yM+h*l4g;GM40S{VECAxpAR%`fN7T(~Lz`&E`4=SDD%fjw`b z$qgkWB@y6!ri%*;3UG^_N|;$mrr&tdYyh3G?Na_3ZD6P@f-`DDyi6KDpXr%<%SW`w zfdm#7{Dhujlbd9OToXV@kQ_A}^QV`x4z_F*{X={bW+sW2kRD(lV>wLG$It}@1=gJS z5;Vcq53jDZKlA|A-UrhjX4A@DF85l=8dI^KmnqN^@X1#`>ucUU#~mY71H+QnFheCy zI7kZS#eO5Ns>)s4SWpl=S*TR$e7e@k{@=@BD+zuC1}=CUHJ-~nA2#@+M6;<+Nz0wB zA9ZmFZc7R~)s5)G2ctGXuGHD@Mp>!`{quEFKhaKrsj^P!cJisOukS^z+by$&g+(R) z=;7hT?zkSsGW;8|)z}|c{|=8cHXZn{ZjkS4Mvp@ZjDjuJ7V^)NdODtw1&M7^(m>!< z5ZT`6f5@F3@%)1S+V^yT^#3(6!asff-i?9>X!hUDzzwheXI;O1n130#@TJ5jy)sI% zGA62Fr&-scmL2w$xvlPyt#iA>0ZrCpD#e`V!LP$F|IQOYV#QIvWUK*0akQ?}E1>Al zyGF4dU#v>|1~zRZD5LSmYcKb`y+RkdODG6IrAe(Y4xQFJ*4miEpj5OjT*Q1^cX@y0 z)V!V*!4H*QQ{x1b3jeqDqQs_0*5!?Sx@@H|Wq^6rq&MiuI!(*U6gG=2xG^<7Ki>~< zxX$IW;6DN|TLD9{iy>GZN7fxYoW?X*V>K^HzdyC@X@6f37u?;Se-iig(HRLMqyIt-EHBx)^~y*f zR30LX;g$8!?|GEFX1%3~axC)OH8a`P3U)Kqw!jf|)j7ckZVIi>A`o^`kXxnieh|aK zXwX&P*ZGx7HcId<#`R9mqtV|zucR6jKJ^8Zm9PV{?MpV8ARG+$OkTgB{>x+%4pDMr z{UK(2gI@vB`X}0z+^_gCGIlyCmON%)=%Pv|R_0AeJ- zG~clk;{B8yZLEXyv#Lz8O(uF3LJotz{)Gl2`&q5qea@YP^kdlwJ1cyIn zi3F78|Etgs6n}vILW9Y4dTQJyGpKJ3teCGSCtu2LbCqrZ)omj6TlOzIQ4@H>e#F=H ze^547QGZ#{jk~Lilli#nbx`l67eeGD%5o}KIHBBu!mi`VKNBAVM^*N;V+I|4Vq*EcAYi1!tKlFv;Xjt`SU zQF-(|G27hB^(A!D`g{SoC8Fr-Rx%?-b+d0(xv49AUOu?noRl+p|1Bh`RFRhc1p|XR z-CuMtQ9&^IUtiKJHI%$uoUu{+xOx&cPKHK3H>@OgdiJxE3-NW~E+~r3<_nuS|2Lp` z#)+@DWHhIix9ju?g34j7k}|7@@h8u*rVhh~5`WaCGCCvPZm%JA~+|wxGrNe{t;k5~{mo(x`@k75)BuGTle7pz;sWrqevidzGMsL-tST zn-idG^cZ<1?;pJM>p!1`y;x;Ysb!vGU&r5;zWkphg`R=NYP;WGjb1=U$?aS{XKfMs z)^)B|+wW2kYgJDN_v(hq6E+kIQ3?x;RS21%$zPC{nDl2}V-OHUzAY>LowphLsx<{8 zX8TPjK6by^tHZ;>UQ1vL;2#ftLul1Pvol}1Eh>HBQR|ro_$l^8+#+JuXYg}3XLY`f z$4`%++4{Cj*^+QULnG?>MdS)is%u@kd%wn?XkN>*3<#(Yz>upNX#s;$N3K}Q%`vex zt-#A+;gv0pcJ9Gaqkt+51FDsNY;d`x;p1~T5d4?sTWPQWnrf;f@C_6L=g3n#9xn~% zN+&5dI38AAx!>Q|jP0_HI4RjJR$cMexWU{zLLJ7@tBI(n;Jk=u)XFU`wh&Hw0=weG zV|h5aKqm`5?nMx|6<+r#DB_BqNUb&O16fZZV<#?OCS* zh8$PGsY)D6O-LH!eoD?W)0pSTwu$I?<<&rN3klD@iqjDF}3yg-?wcz zW&)aZKoU4H25Kcw;9>W-_{~4?3OPV8R|x&zH$~3-0y>4+iVGk4IY06_dU|Yek+0T` z_!jJZsvDd3cSMnma=@o-6?YT5zWFiC4+(7#K>2fmSgW`a{8azI{^22ce1ByBCJ@+d zWypj7_xX)fzYbpr3!mjwRmDJ#8X}&%4huZt|B#|!sntZdnLTeS=yIFrcBm6U1o2J)lbS|gR#`y1{^3P+bE*GgYyJ+~k^f!{8zoZl?CIhFWpuiL} z^S`0b2R+|8F4kCQdJM~7=jkX# ze^Zyf2*t9~UdAF-;58VXc%Jp<3=w!|xV@YsLORx&U!c%cq^!)9iDp3uNPC-mluIg#kKE+Go~ zlRE-9i~h!#yoy#(6!T3Bv&PMJz;E@}jYJuSR_Fv+EXnSf-eONy?2AOXy<{}MojYX) zy+jHGO0q7L$y4C@UMOR!A{+*dM6$J1e2DvoK6l*C)kSp+pd4>TP}IRoTevHv_ie+R zOqDi!Q>-h_Sx8S6V9*rLCtd+fv5gJOWZ2>f&iQ;vUnZ1kG|s7^S(J>cAjjk+5?_v) zl6l!JV*+rycu_04k{D$ar>4YcMK6FytY8qpku5YY`kAfG-=Hq79W=CBGYNJYhOAU# zjZW^tu>0SH!b2$ci?{ z!5uHm?5^R#xrf1J4Tk-5Im(quB(J*A;1$|hsS6I1=7XDWBA>~gmOEYqQcsTYlDbbb zr^q-Q%IX6X?>yc~$DWNc0ZiI)`rgSrClaw!F<$q7KxtHRWQLt}45ZUD%c&A@y-6d8 z2g&SfloJ|cLXj@k!T0+SoB7=g<6G4TD5q4E7Ki-)6Y1#G;xAbD?fxbf@9X8etAy|E zq8g$YqD!y!IDV9HdR_99lvb~LYM*H_{j>IPk|=b5^&F`d=;f;RvoGf%s~RzRg1{ov zqq7={xhqSvZww)-j;S77^h(+HDz^2#J1%D`@*1sJ6z*u==X-7Rt8E|mUZ)>WJd-@M zVgzB4u%VOhaS1Imj<5(it|p?3EVDgs2Rj{8q-Y=cOx)o2ZQi}8g9(GDcZ0tN`n_nE zxs-evDul`nr_0d<<8jb>(2S$QyVnU+_DLyK_wJf*dD1n|IwMG*5n7=(=1WcVPya{E z>r;h2%l}9<3Axh|rX4s?8`+=$P_gvj2r@_>|9;e<+co+jk6%W|v&ZJ44T|znC`5kC${c!YWtY!!>f1vILDmI}c-^~E3mwd(;8nG`=Avyn z@ni+0(sy4E+T3N)jaXKoLOaQ4N+3v9@8Oj0`sOZ@$rGeT!v<~gB0`XDajkZEIaB%?S1kc{Xg3vvVWDKr3O*e+sa#nl4>o< zgl)Q_Bsu|TZ6{7Ka`g7N+`xx|*o~ekPC_ws0lTcxRTWhy-<_pLb_)TiFU@&+J!A#Z zMos8#o?}A#rTcgDFn-ARRdyh=88{7sDkmOmDShN`mG4ALe6B*izWR6fMIrS^uhu!x zmw$~4MIF9qu92@gdObSju$dcuvc*l5%JLp}NJBC@FZ_t~g796KvBk>b7HPw>?8SZc z)gQoB#rS(5$wRR21rpvN5Y>>qrOxLStw(l%81kVWBGMaCKr6CxO9u97fKb>F6tsvh zD*E(4pUg!EYW|-+YESmgsva=8 zfia$r*H(tlIT-kcl3*_BwVz7`u5?l@YP5v)wT0%42<=qUwQ69*7$IGCW@TZSR7yr(i~;~*w;$DLR9=+ZE+T>5));Wk>z`31*W&`Wcg zNpWAizzh`^{-nTT9?G+^kVyG^PL|2 z^4^2(z@;qzEm;UAec$|Jn(Gml)cA%UmS)d9|Gzk8i|3C4;jcda|Dh>109>6N9G!17 z4JG5$>9%^0E~BU{@hHwS&B^8-ukMR1PAflzj@A&|Yz;pppLnZzT_aK&+ac9?b)oNHL*izZG^_IIXt9GN{-7eERVhJ{ih+NRB8| z>k1TRxaB0-0!kU!^@2oqcKY@;yRT$^jOD39G=YO6FSU`1`6}Q2Z&r!{v+q(ZMnQ+a zGrhP~Wvb5|?=64vL6E=V#*JL3?jczSbrw^^L5q4%e(4&hlLadr3QUb;Y8xW zjO1Fc+fH52&r8j$t4laKI+{f`^1v;Y3i}u2^jJ`NBHXC+6zBE*_FVGgQr_um0l$~h z7DpeI>w7=UI&L`R_=<$N9UwE1u$c}dsXb$^vol+d(-5tb)c~R)N8^9>4+-<|h7F7x z0;ug>kZb@W$H|dZ#v|(gx&Oy`QG{3wWl(-T_bkEk=Q7%6{Uf=FFKboZibLR0<>&YQ5 zGl|Hh+v@M&ZPj{~$%y{X+Q|=EOW?CG-|D_cP~k(viff3xV;_OsFva=1M+s8f2q?I0%zW z?wF3Sy-G0`hx1bs^+5+VBbpF*8e7}pts9NtXoz&rM_>=eqR@lA6GY+=?FxG1i22#hvCJ_hx==cd-Zb|^#t0Sp}=!3^NvzmBM{v^ zpKy2-S5@_aQ)Dm=Z{~G0>l2-XT15k6o4UVnJi+l##m}ANTFuXf0DiRg6$z!~eSMNo zdkQ~-ul+$~J6+-PP)J@_33!&QP>&)@?$;X6zem6joB%m)_O#Z&NAWoE*`M3|v5Y)_ zg}36BG*|fVqz@c0xRq?V))zCB#+URD)%R@idD0Gz%3JUapB|~wi4p!a`KgTg)iBZf zJ9JkqO&+Ygq1oh`FO+@NS$?@;eN`a~H2hEZb_{@Xhdqhl`pIiLLCWwxy!#Zg{FEvb zfNZlf^8ToH9T~89-pn^Yr~%j9)&Dk9`rsZdsK=(a-%4vuo}}5P^Jb+FB;QobGVOuf zMg#}8^4yCb=F-oS{n(bW3%+kT_k3ED;+Ybebj3ZD(W_o4R7Jo z{w0N!$|Kqd?Zb_Srq5HEPY>p{Hrf(5)_eO*-#)#EP0iPUDjSaK^=f*dteZ!MLz~?!*PShr?0#sd4tFZ(GKK;yHzaoKvhg)1$qAO6x;!*b`$P3t}jZaOn z_oM!6Lk1iv_v9;x_!Bkkqm2T>gX=hSKNc`PEGjfl`C6HH@{EUAIgo-y`)tgS$Ipt= zx>6h_N@z*--<6*b;-wl1!Z3>L9zn&0Hc1*)qv%EBT_8Ju^ybt zJ-)_<#r(zK#)wR`%E-)dad9C<<;6c$&)9r#3qsNHWl;-&+K|GenL6nxZV{8q*?j_CfbPEEx^IZLHFt0Ge>^r zarkN1mF0xK=ILo)ezH9t$&6>NeiW3Zu)JQ>kf8i{(sUeY%Uu@<&^3$)3cRo8+53cD zb9_;a@_72j>C%I5>kjY~MSTvz+_ZQa=DWtvH92cTWZd}2?+8f3bB#w4z^U*H{CKxd zO*vxq+0W1Kt3*0p*T6to8Q`kKqgV+E4xXuZparADPAin+cPaO8Q?tC6iE`m1vj z)BwF$hwxm-BnEA#M)wwo^Tm|nG~ri-dKlt4PCjh^^>&=K4)8AoZhD?`c(VL*W~3Ua z5&f?}uEDPj(D?j3&#K&(UU9>>{+iHu;^xsi*W)H9fEitH80Swr&}GXU_7!PpXbh=I z{_7bL^CO;Xd%v_fRiVPI%Ah8*t*uQwjGYKHf;j-z0It{d&4?h#m0 zsasoH^QIHc|4EfbUc>teGED^3+mSZbmOUn$<5%)c13%80be&Hbl7yWUy=QRHj}v)w z(}oYTuJqYNJ@oU|w_lFQ2IN;slckbHrW`t7L(Zb`hY8JykKWkn`*5*rzmHHXQSaqB zZe*F)3AMgnbdsep;dgsDiK4JILxh269|sYB1aT zmz?~TIcyxgFmA&ts)|7rW@b`Hc>mG#+-^vJLOh zJ!@2}-un}r-Q<%{@6&YOEOKR)*9x>>m)v)Twv(*}++H1F576*Bvu8 z0wOg!+6Jw4|EsR+fNCmfqqL>Tf&_&~FVZAJDAGlWNKXV=ih#6GBmxnnOEt8mgP<4$ zktQxRh=4!RHDx>rtqEnb*U;U~;X|-baQ08i%a!!GThvIHE|e0pJ`t|` zicT#lY!^im)?01THgBWjxIBy^!0o$j2Z9R+t^1m5F!ZReg?3KGoZC)P_S+E-wIHG{ zdOYo1a^%O{QZ*L>AdyN~K3=>;{PKcWWlom(i6ul8!hm1GajtCD^!ThY*Usdbr{k)% z=a(7s&?*6!F~_d7F*c&O&vYtj-Jr33&=8y8%e+8qVI^%gByxksAyODP>LEA@*;QrX z5csls!qtUyc24B#sPP*UWxP1EkGE(&PLSQe(3hF(8si5LX^LCC>7~)u5JM%3xOd@qUGn<~Q{)!I3Td-Mm<-*5`bUl_|Z9(2@q!zq&tL&%q7a!md4dGYzG zd;iwW$<9lw+*r2(ZXg`0i)P6FZ!Bg3RM?V8BwVt$itFm*=52^|cId>vddm@v5==RM zd%$JR!TOVCK}l(3HidHn4Z;WBtBbtYqGMzv?Z&a~``hK1nNJd!flQKN`fhl-(}6O< zo|AB3oE{L&NPLcA*U;|-tv%0{9mau9zpYD;EjC0r*o<0Rc{EPjPWlVJq}SmIeRB1+ zX&B=fR%28pztoj0F|9S2)wv~PiOvTP9V`TG!t$CdqoTFue{*ug&Ytk+yPbE~_Usi6 zNiNMGMQ^G_0+?jebU;)@?(g#wZ~u{Di4{jJ{?QW?>L+R5!|^RR!(wiPO>Z(e*9MZ;w)W?wmeTgth{w z6CZ_zE%#_Ne^z`@>}<`pWa6wTfvSprk+pCm^GK>MnH-t9!3Ge93t4c$84uUWU4i}# zVH?Y-E!%m?uTc>HmGD(otEz*5Xj-*nQKW9jM|w)^M3}ng!6m$Md27B(h%_l0^-8J63%!8!P{eKLk2UF+J8neWtRVULOZZ`V)Uos)o7By}uY zA5cZX5mKSDX6j3ip0!;J{n#34(PTc{JxZxUx#oF^s*RFdG7%Gav!CA!&^bRYdNZ^% ziCo+s5Lph~%0||PLX4j?>|J`KF$1;>XJFyH>S*?gT_~W}1j=eG6^ifbPaQAh@~}>y zEU-gIkRIL&IoYeIGu=!#maimV3$>cyy1H8EqsP=S6mY+rk#PnruGgTj<`ZDiP?-~m zVbRxD_2!<5Qd7!bVp7JMw+;;8&Id5C{#qf6T4kQ2Q4ka5Ep5N!8z8WaAxcRrL%FAF z({iGO0tIz}^IM;fJ5RDz!!$`HZ2}j-w#OebK%Wl#TLqx`XKb71pdC+-EH9%Y54nkmn zUFUnSs|!InCN;iD`trUT08j0g1U9VVfWPE8Jsbc0DBorzN&{THPk*M@%Mo}hW~|&w zU1(z-!rz?Iq};V?L=IB~#%~(NdhD3I8CR6Otbs&U?qWhQK->dvC;!i{#eoOh9S*|j z!QmW^5nsh=0L8(5eZISnzvRcbkiu&J8gO`yLEKa>^otKqG?(DLDxaEixp<_f{!6?vvH zda#@^rt&&A_e2HDo5sG>fM+?{bDX>rfIUCei2^1G`a#M%~Fe6^)Kx}pYAtmLAfj;rgX+ghH!3MY% zb~Je;B&(%oS9N((=w5Bdj3x2>WDhumx z%FP##ha|RTlx|!G!)a~GcoS|r&DpCXBnhw=LSCo8C)4Iio!gsQua+v>E>U%pJ7?~| zW}j?Pzu6y9tEP;8VuJWIjl&r8Az-COC&&B|ZS;oNFXiqazMuv0TVWo_$vKJdUgC`D z!6nh;3Z^ffr*=gu(iHEKF2q!WD_rZx9@d~Lk&>V~F3tD73|Ipq^TRdJH4jrtF%U4P zPsex4e|!O0RZb-zJs%Ct*b;0#e#Mc-o*&Cq#5Phy36qvB#P_=_X66kwJ&{@U zb**!i<1cH`(P62|rcaCqkz!|VIX1jYnGh6S+w^Hc%B*Q#N%N;$YDWd5c6yzseLD>i zbM|@UO>XPJ`kl%e2+ECiiXjx(gwdB)=;j$GcO>Ry^kKd}mdtgJspjU?eBWtBlRL5O z$sl#hJQA-@e#1WBOEAoGlJU^O8kl z0?>7#t%a6c8^6m~Wo^$S&?+#`kf)^d0PH&efD0O%Ccj09f%uPHs-QBHF*4lz=2XT0 zM4zJc4H)08lA6^ZCm9;N-*d6VUl4Gm;~_$WC9-ECEz>kkN;-=t?u%aPshP7`5PR15 zs7Op>KlK>@-BT>{4wNs=3dNN&MbGGER66c7y*2LSla>m6PiW+8JFoM7eixJC70b6^ z$<-H~1?+>v665TE`8b&H^ywMXH~gkJxoa)=fBVB~$j|a9%llu6FldjQyyR)kX9bTV zxd_b}(B2LPu!VaVi+G$);t+d*-Ti;H%?|JRZF<9~I~^2sSnwE!bFIM@My!{WE5> zV|(e)DaQ-zpZ)^KLv>5Ql3c3{UcjjI_32Sev4nhDSy>q}8CfEm2R(hz74%ZT%l|DVml{%2N0a!;$Zf|Hz+ETM<84yn@uTU* z($!P~yY|r=pg?H7W(KO~-pp}ZCwLUlu6 Autoware API +behavior_planner -up-> autoware_api : infrastructure\n command +autoware_api -down-> behavior_planner : infrastructure\n state + +'' Vector Map +vector_map -left-> behavior_planner : vector map + +'' Autoware API <-> Infrastructure +autoware_api -up-> fms : lock\n request +fms -down-> autoware_api : right-of-way\n state + +autoware_api -up-> automatic_shutter : approach\n notification +automatic_shutter -down-> autoware_api : shutter\n state + +autoware_api -up-> manual_shutter : open/close\n command +manual_shutter -down-> autoware_api : shutter\n state + +autoware_api -up-> remote_controllable_traffic_light : light change\n command +remote_controllable_traffic_light -down-> autoware_api : light\n state + +autoware_api -up-> warning_light : activation\n command +warning_light -down-> autoware_api : warning light\n state + +' Layout +'' Infrastructure +fms -[hidden]right-> automatic_shutter +automatic_shutter -[hidden]right-> manual_shutter +manual_shutter -[hidden]right-> remote_controllable_traffic_light +remote_controllable_traffic_light -[hidden]right-> warning_light + +@enduml +``` + +Planner and each infrastructure communicate with each other using common abstracted messages. + +- Special handling for each infrastructure is not scalable. The interface is defined as an Autoware API. +- The requirements for each infrastructure are slightly different, but will be handled flexibly. + +FMS: Intersection coordination when multiple vehicles are in operation and the relevant lane is occupied + +- Automatic shutter: Open the shutter when approaching/close it when leaving +- Manual shutter: Have the driver open and close the shutter. +- Remote control signal: Have the driver change the signal status to match the direction of travel. +- Warning light: Activate the warning light + +Support different communication methods for different infrastructures + +- HTTP +- Bluetooth +- ZigBee + +Have different meta-information for each geographic location + +- Associated lane ID +- Hardware ID +- Communication method + +FMS: Fleet Management System + +```plantuml +@startuml +!theme cerulean-outline + +' Component +node "Autoware ECU" as autoware_ecu { +component "Behavior Planner" as behavior_planner +component "Autoware API" as autoware_api +component "Web.Auto Agent" as web_auto_agent +note right of web_auto_agent : (fms_bridge) +database "Vector Map" as vector_map + +package "Infrastructure Bridges" as infrastructure_bridges { + component "Automatic Shutter Bridge" as automatic_shutter_bridge + component "Manual Shutter Bridge" as manual_shutter_bridge + component "Remove Controllable Traffic Light Bridge" as remote_controllable_traffic_light_bridge + component "Warning Light Bridge" as warning_light_bridge +} +} + +cloud "FMS" as fms { + component "FMS Gateway" as fms_gateway + + component "Intersection Arbitrator" as intersection_arbitrator + database "Intersection Lock Table" as intersection_lock_table + + component "Vector Map Builder" as vector_map_builder + database "Vector Map Database" as vector_map_database +} + +package "Infrastructures" as infrastructures { + node "Automatic Shutter" as automatic_shutter + node "Manual Shutter" as manual_shutter + node "Remote Controllable Traffic Light" as remote_controllable_traffic_light + node "Warning Light" as warning_light +} + +' Relationship +'' Behavior Planner <-> Autoware API +behavior_planner -up-> autoware_api : infrastructure\n command +autoware_api -down-> behavior_planner : infrastructure state\n as virtual traffic light + +'' Autoware API <-> Web.Auto +autoware_api -up-> web_auto_agent : infrastructure\n command +web_auto_agent -down-> autoware_api : infrastructure state\n as virtual traffic light + +'' Autoware API <-> Infrastructure Bridge +autoware_api -right-> infrastructure_bridges : infrastructure\n command +infrastructure_bridges -left-> autoware_api : infrastructure state\n as virtual traffic light + +'' Infrastructure Bridge <-> Infrastructure +automatic_shutter_bridge -right-> automatic_shutter : approach notification +automatic_shutter -left-> automatic_shutter_bridge : shutter state + +manual_shutter_bridge -right-> manual_shutter : open/close command +manual_shutter -left-> manual_shutter_bridge : shutter state + +remote_controllable_traffic_light_bridge -right-> remote_controllable_traffic_light : light change command +remote_controllable_traffic_light -left-> remote_controllable_traffic_light_bridge : light state + +warning_light_bridge -right-> warning_light : activation command +warning_light -left-> warning_light_bridge : warning light state + +'' Web.Auto +web_auto_agent -up-> fms_gateway : infrastructure\n command +fms_gateway -down-> web_auto_agent : infrastructure state\n as virtual traffic light + +fms_gateway -up-> intersection_arbitrator : lock request +intersection_arbitrator -down-> fms_gateway : right-of-way state + +intersection_arbitrator -up-> intersection_lock_table : lock request +intersection_lock_table -down-> intersection_arbitrator : lock result + +vector_map_builder -down-> vector_map_database : create vector map +vector_map_database -left-> intersection_arbitrator : vector map + +'' Vector Map +vector_map_database .down.> web_auto_agent : vector map +web_auto_agent -left-> vector_map : vector map +vector_map -down-> behavior_planner : vector map + +' Layout +'' Infrastructure Bridge +automatic_shutter_bridge -[hidden]down-> manual_shutter_bridge +manual_shutter_bridge -[hidden]down-> remote_controllable_traffic_light_bridge +remote_controllable_traffic_light_bridge -[hidden]down-> warning_light_bridge + +'' Infrastructure +automatic_shutter -[hidden]down-> manual_shutter +manual_shutter -[hidden]down-> remote_controllable_traffic_light +remote_controllable_traffic_light -[hidden]down-> warning_light + +@enduml +``` + +#### Module Parameters + +| Parameter | Type | Description | +| ------------------------------- | ------ | --------------------------------------------------------------------- | +| `max_delay_sec` | double | [s] maximum allowed delay for command | +| `near_line_distance` | double | [m] threshold distance to stop line to check ego stop. | +| `dead_line_margin` | double | [m] threshold distance that this module continue to insert stop line. | +| `check_timeout_after_stop_line` | bool | [-] check timeout to stop when linkage is disconnected | + +#### Flowchart + +```plantuml +@startuml +!theme cerulean-outline +start + +if (before start line?) then (yes) + stop +else (no) +endif + +if (after end line?) then (yes) + stop +else (no) +endif + +:send command to infrastructure; + +if (no stop line?) then (yes) + stop +else (no) +endif + +:check infrastructure state; + +if (timeout or not received?) then (yes) + :stop at stop line; + stop +else (no) +endif + +if (no right of way?) then (yes) + :stop at stop line; +else (no) +endif + +if (finalization is requested?) then (yes) + if (not finalized?) then (yes) + :stop at end line; + else (no) + endif +else (no) +endif + +stop +@enduml +``` + +##### Known Limits + +- tbd. From 7eb4b6c58d157c78a6594c3e405adac209fc8b61 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 10 May 2022 08:29:37 +0900 Subject: [PATCH 10/55] feat(surround_obstacle_checker): separate surround_obstacle_checker from hierarchical planning flow (#830) * fix(surroud_obstacle_checker): use alias Signed-off-by: satoshi-ota * feat(surround_obstacle_checker): use velocity limit Signed-off-by: satoshi-ota * chore(surround_obstacle_checker): rename publisher, subscriber and callback functions Signed-off-by: satoshi-ota * refactor(surround_obstacle_checker): use parameter struct Signed-off-by: satoshi-ota * fix(surround_obstacle_checker): use alias Signed-off-by: satoshi-ota * refactor(surround_obstacle_checker): cleanup member functions Signed-off-by: satoshi-ota * refactor(surround_obstacle_checker): cleanup polygon handling Signed-off-by: satoshi-ota * refactor(surround_obstacle_checker): use marker helper Signed-off-by: satoshi-ota * feat(planning_launch): separate surround_obstacle_checker from hierarchical motion planning flow Signed-off-by: satoshi-ota --- .../motion_planning/motion_planning.launch.py | 35 +- .../motion_planning.launch.xml | 13 +- .../surround_obstacle_checker/CMakeLists.txt | 2 +- .../surround_obstacle_checker.param.yaml | 1 + .../debug_marker.hpp | 20 +- .../surround_obstacle_checker/node.hpp | 136 ++-- .../surround_obstacle_checker.launch.xml | 12 +- .../surround_obstacle_checker/package.xml | 1 + .../src/debug_marker.cpp | 105 +-- .../surround_obstacle_checker/src/node.cpp | 632 +++++++++--------- 10 files changed, 433 insertions(+), 524 deletions(-) diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py index e8661322215f..89d04bc5b3a0 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py @@ -92,20 +92,23 @@ def launch_setup(context, *args, **kwargs): surround_obstacle_checker_param = yaml.safe_load(f)["/**"]["ros__parameters"] surround_obstacle_checker_component = ComposableNode( package="surround_obstacle_checker", - plugin="SurroundObstacleCheckerNode", + plugin="surround_obstacle_checker::SurroundObstacleCheckerNode", name="surround_obstacle_checker", namespace="", remappings=[ ("~/output/no_start_reason", "/planning/scenario_planning/status/no_start_reason"), ("~/output/stop_reasons", "/planning/scenario_planning/status/stop_reasons"), - ("~/output/trajectory", "surround_obstacle_checker/trajectory"), + ("~/output/max_velocity", "/planning/scenario_planning/max_velocity_candidates"), + ( + "~/output/velocity_limit_clear_command", + "/planning/scenario_planning/clear_velocity_limit", + ), ( "~/input/pointcloud", "/perception/obstacle_segmentation/pointcloud", ), ("~/input/objects", "/perception/object_recognition/objects"), ("~/input/odometry", "/localization/kinematic_state"), - ("~/input/trajectory", "obstacle_avoidance_planner/trajectory"), ], parameters=[ surround_obstacle_checker_param, @@ -114,22 +117,6 @@ def launch_setup(context, *args, **kwargs): extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) - # relay - relay_component = ComposableNode( - package="topic_tools", - plugin="topic_tools::RelayNode", - name="skip_surround_obstacle_check_relay", - namespace="", - parameters=[ - { - "input_topic": "obstacle_avoidance_planner/trajectory", - "output_topic": "surround_obstacle_checker/trajectory", - "type": "autoware_auto_planning_msgs/msg/Trajectory", - } - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - # obstacle stop planner obstacle_stop_planner_param_path = os.path.join( get_package_share_directory("tier4_planning_launch"), @@ -173,7 +160,7 @@ def launch_setup(context, *args, **kwargs): ), ("~/input/objects", "/perception/object_recognition/objects"), ("~/input/odometry", "/localization/kinematic_state"), - ("~/input/trajectory", "surround_obstacle_checker/trajectory"), + ("~/input/trajectory", "obstacle_avoidance_planner/trajectory"), ], parameters=[ common_param, @@ -202,13 +189,7 @@ def launch_setup(context, *args, **kwargs): condition=IfCondition(LaunchConfiguration("use_surround_obstacle_check")), ) - relay_loader = LoadComposableNodes( - composable_node_descriptions=[relay_component], - target_container=container, - condition=UnlessCondition(LaunchConfiguration("use_surround_obstacle_check")), - ) - - group = GroupAction([container, surround_obstacle_checker_loader, relay_loader]) + group = GroupAction([container, surround_obstacle_checker_loader]) return [group] diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml index 0fa8707e4fda..3d195185d9bd 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml @@ -19,22 +19,11 @@ - - - - - - - - - - - @@ -45,7 +34,7 @@ - + diff --git a/planning/surround_obstacle_checker/CMakeLists.txt b/planning/surround_obstacle_checker/CMakeLists.txt index b40b7c22c98c..ab61405c9f33 100644 --- a/planning/surround_obstacle_checker/CMakeLists.txt +++ b/planning/surround_obstacle_checker/CMakeLists.txt @@ -18,7 +18,7 @@ target_link_libraries(${PROJECT_NAME} ) rclcpp_components_register_node(${PROJECT_NAME} - PLUGIN "SurroundObstacleCheckerNode" + PLUGIN "surround_obstacle_checker::SurroundObstacleCheckerNode" EXECUTABLE ${PROJECT_NAME}_node ) diff --git a/planning/surround_obstacle_checker/config/surround_obstacle_checker.param.yaml b/planning/surround_obstacle_checker/config/surround_obstacle_checker.param.yaml index b57d7506b057..afcc532b7c60 100644 --- a/planning/surround_obstacle_checker/config/surround_obstacle_checker.param.yaml +++ b/planning/surround_obstacle_checker/config/surround_obstacle_checker.param.yaml @@ -9,3 +9,4 @@ # ego stop state stop_state_ego_speed: 0.1 #[m/s] + stop_state_entry_duration_time: 0.1 #[s] diff --git a/planning/surround_obstacle_checker/include/surround_obstacle_checker/debug_marker.hpp b/planning/surround_obstacle_checker/include/surround_obstacle_checker/debug_marker.hpp index d076e26afc00..2891ac63c5df 100644 --- a/planning/surround_obstacle_checker/include/surround_obstacle_checker/debug_marker.hpp +++ b/planning/surround_obstacle_checker/include/surround_obstacle_checker/debug_marker.hpp @@ -25,8 +25,18 @@ #include #include +namespace surround_obstacle_checker +{ + +using tier4_planning_msgs::msg::StopFactor; +using tier4_planning_msgs::msg::StopReason; +using tier4_planning_msgs::msg::StopReasonArray; +using visualization_msgs::msg::Marker; +using visualization_msgs::msg::MarkerArray; + enum class PoseType : int8_t { NoStart = 0 }; enum class PointType : int8_t { NoStart = 0 }; + class SurroundObstacleCheckerDebugNode { public: @@ -38,16 +48,16 @@ class SurroundObstacleCheckerDebugNode void publish(); private: - rclcpp::Publisher::SharedPtr debug_viz_pub_; - rclcpp::Publisher::SharedPtr stop_reason_pub_; + rclcpp::Publisher::SharedPtr debug_viz_pub_; + rclcpp::Publisher::SharedPtr stop_reason_pub_; double base_link2front_; - visualization_msgs::msg::MarkerArray makeVisualizationMarker(); - tier4_planning_msgs::msg::StopReasonArray makeStopReasonArray(); + MarkerArray makeVisualizationMarker(); + StopReasonArray makeStopReasonArray(); std::shared_ptr stop_obstacle_point_ptr_; std::shared_ptr stop_pose_ptr_; rclcpp::Clock::SharedPtr clock_; }; - +} // namespace surround_obstacle_checker #endif // SURROUND_OBSTACLE_CHECKER__DEBUG_MARKER_HPP_ diff --git a/planning/surround_obstacle_checker/include/surround_obstacle_checker/node.hpp b/planning/surround_obstacle_checker/include/surround_obstacle_checker/node.hpp index 7e4bbb9ffd15..e437787c234a 100644 --- a/planning/surround_obstacle_checker/include/surround_obstacle_checker/node.hpp +++ b/planning/surround_obstacle_checker/include/surround_obstacle_checker/node.hpp @@ -16,9 +16,9 @@ #define SURROUND_OBSTACLE_CHECKER__NODE_HPP_ #include "surround_obstacle_checker/debug_marker.hpp" -#include "tier4_autoware_utils/trajectory/tmp_conversion.hpp" #include +#include #include #include @@ -27,30 +27,31 @@ #include #include #include +#include +#include #include -#include -#include -#include -#include -#include -#include - -#include #include #include #include #include #include +#include #include -using Point2d = boost::geometry::model::d2::point_xy; -using Polygon2d = - boost::geometry::model::polygon; // counter-clockwise, open +namespace surround_obstacle_checker +{ + +using autoware_auto_perception_msgs::msg::PredictedObjects; +using autoware_auto_perception_msgs::msg::Shape; using autoware_auto_planning_msgs::msg::Trajectory; using autoware_auto_planning_msgs::msg::TrajectoryPoint; -using TrajectoryPoints = std::vector; +using tier4_planning_msgs::msg::VelocityLimit; +using tier4_planning_msgs::msg::VelocityLimitClearCommand; +using vehicle_info_util::VehicleInfo; + +using Obstacle = std::pair; enum class State { PASS, STOP }; @@ -59,70 +60,73 @@ class SurroundObstacleCheckerNode : public rclcpp::Node public: explicit SurroundObstacleCheckerNode(const rclcpp::NodeOptions & node_options); + struct NodeParam + { + bool use_pointcloud; + bool use_dynamic_object; + bool is_surround_obstacle; + // For preventing chattering, + // surround_check_recover_distance_ must be bigger than surround_check_distance_ + double surround_check_recover_distance; + double surround_check_distance; + double state_clear_time; + double stop_state_ego_speed; + double stop_state_entry_duration_time; + }; + private: - void pathCallback(const Trajectory::ConstSharedPtr input_msg); - void pointCloudCallback(const sensor_msgs::msg::PointCloud2::ConstSharedPtr input_msg); - void dynamicObjectCallback( - const autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr input_msg); - void currentVelocityCallback(const nav_msgs::msg::Odometry::ConstSharedPtr input_msg); - void insertStopVelocity(const size_t closest_idx, TrajectoryPoints * traj); - bool convertPose( - const geometry_msgs::msg::Pose & pose, const std::string & source, const std::string & target, - const rclcpp::Time & time, geometry_msgs::msg::Pose & conv_pose); - bool getPose( - const std::string & source, const std::string & target, geometry_msgs::msg::Pose & pose); - void getNearestObstacle(double * min_dist_to_obj, geometry_msgs::msg::Point * nearest_obj_point); - void getNearestObstacleByPointCloud( - double * min_dist_to_obj, geometry_msgs::msg::Point * nearest_obj_point); - void getNearestObstacleByDynamicObject( - double * min_dist_to_obj, geometry_msgs::msg::Point * nearest_obj_point); - bool isObstacleFound(const double min_dist_to_obj); + void onTimer(); + + void onPointCloud(const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg); + + void onDynamicObjects(const PredictedObjects::ConstSharedPtr msg); + + void onOdometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg); + + boost::optional getNearestObstacle() const; + + boost::optional getNearestObstacleByPointCloud() const; + + boost::optional getNearestObstacleByDynamicObject() const; + + boost::optional getTransform( + const std::string & source, const std::string & target, const rclcpp::Time & stamp, + double duration_sec) const; + bool isStopRequired(const bool is_obstacle_found, const bool is_stopped); - size_t getClosestIdx(const TrajectoryPoints & traj, const geometry_msgs::msg::Pose current_pose); - bool checkStop(const TrajectoryPoint & closest_point); - Polygon2d createSelfPolygon(); - Polygon2d createObjPolygon( - const geometry_msgs::msg::Pose & pose, const geometry_msgs::msg::Vector3 & size); - Polygon2d createObjPolygon( - const geometry_msgs::msg::Pose & pose, const geometry_msgs::msg::Polygon & footprint); - diagnostic_msgs::msg::DiagnosticStatus makeStopReasonDiag( - const std::string no_start_reason, const geometry_msgs::msg::Pose & stop_pose); - std::string jsonDumpsPose(const geometry_msgs::msg::Pose & pose); - - /* - * ROS - */ + + bool isVehicleStopped(); + + // ros + mutable tf2_ros::Buffer tf_buffer_{get_clock()}; + mutable tf2_ros::TransformListener tf_listener_{tf_buffer_}; + rclcpp::TimerBase::SharedPtr timer_; + // publisher and subscriber - rclcpp::Subscription::SharedPtr path_sub_; - rclcpp::Subscription::SharedPtr pointcloud_sub_; - rclcpp::Subscription::SharedPtr - dynamic_object_sub_; - rclcpp::Subscription::SharedPtr current_velocity_sub_; - rclcpp::Publisher::SharedPtr path_pub_; - rclcpp::Publisher::SharedPtr stop_reason_diag_pub_; + rclcpp::Subscription::SharedPtr sub_pointcloud_; + rclcpp::Subscription::SharedPtr sub_dynamic_objects_; + rclcpp::Subscription::SharedPtr sub_odometry_; + rclcpp::Publisher::SharedPtr pub_stop_reason_; + rclcpp::Publisher::SharedPtr pub_clear_velocity_limit_; + rclcpp::Publisher::SharedPtr pub_velocity_limit_; + + // debug std::shared_ptr debug_ptr_; - tf2_ros::Buffer tf_buffer_; - tf2_ros::TransformListener tf_listener_; // parameter - nav_msgs::msg::Odometry::ConstSharedPtr current_velocity_ptr_; - sensor_msgs::msg::PointCloud2::ConstSharedPtr pointcloud_ptr_; - autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr object_ptr_; + NodeParam node_param_; vehicle_info_util::VehicleInfo vehicle_info_; - Polygon2d self_poly_; - bool use_pointcloud_; - bool use_dynamic_object_; - double surround_check_distance_; - // For preventing chattering, - // surround_check_recover_distance_ must be bigger than surround_check_distance_ - double surround_check_recover_distance_; - double state_clear_time_; - double stop_state_ego_speed_; - bool is_surround_obstacle_; + + // data + nav_msgs::msg::Odometry::ConstSharedPtr odometry_ptr_; + sensor_msgs::msg::PointCloud2::ConstSharedPtr pointcloud_ptr_; + PredictedObjects::ConstSharedPtr object_ptr_; // State Machine State state_ = State::PASS; std::shared_ptr last_obstacle_found_time_; + std::shared_ptr last_running_time_; }; +} // namespace surround_obstacle_checker #endif // SURROUND_OBSTACLE_CHECKER__NODE_HPP_ diff --git a/planning/surround_obstacle_checker/launch/surround_obstacle_checker.launch.xml b/planning/surround_obstacle_checker/launch/surround_obstacle_checker.launch.xml index a0dd4b307f49..53f26a05c87c 100644 --- a/planning/surround_obstacle_checker/launch/surround_obstacle_checker.launch.xml +++ b/planning/surround_obstacle_checker/launch/surround_obstacle_checker.launch.xml @@ -1,24 +1,20 @@ - - - - - + + - - + + - diff --git a/planning/surround_obstacle_checker/package.xml b/planning/surround_obstacle_checker/package.xml index 5dfed9ddb19a..b74ad2ccec25 100644 --- a/planning/surround_obstacle_checker/package.xml +++ b/planning/surround_obstacle_checker/package.xml @@ -14,6 +14,7 @@ autoware_auto_perception_msgs autoware_auto_planning_msgs + autoware_auto_tf2 diagnostic_msgs eigen libpcl-all-dev diff --git a/planning/surround_obstacle_checker/src/debug_marker.cpp b/planning/surround_obstacle_checker/src/debug_marker.cpp index 64dbc2f349f1..8abdb67e8b2c 100644 --- a/planning/surround_obstacle_checker/src/debug_marker.cpp +++ b/planning/surround_obstacle_checker/src/debug_marker.cpp @@ -14,6 +14,7 @@ #include "surround_obstacle_checker/debug_marker.hpp" +#include #ifdef ROS_DISTRO_GALACTIC #include #else @@ -22,13 +23,23 @@ #include +namespace surround_obstacle_checker +{ + +using tier4_autoware_utils::appendMarkerArray; +using tier4_autoware_utils::calcOffsetPose; +using tier4_autoware_utils::createDefaultMarker; +using tier4_autoware_utils::createMarkerColor; +using tier4_autoware_utils::createMarkerScale; +using tier4_autoware_utils::createPoint; +using tier4_autoware_utils::createStopVirtualWallMarker; + SurroundObstacleCheckerDebugNode::SurroundObstacleCheckerDebugNode( const double base_link2front, const rclcpp::Clock::SharedPtr clock, rclcpp::Node & node) : base_link2front_(base_link2front), clock_(clock) { debug_viz_pub_ = node.create_publisher("~/debug/marker", 1); - stop_reason_pub_ = - node.create_publisher("~/output/stop_reasons", 1); + stop_reason_pub_ = node.create_publisher("~/output/stop_reasons", 1); } bool SurroundObstacleCheckerDebugNode::pushPose( @@ -70,87 +81,25 @@ void SurroundObstacleCheckerDebugNode::publish() stop_obstacle_point_ptr_ = nullptr; } -visualization_msgs::msg::MarkerArray SurroundObstacleCheckerDebugNode::makeVisualizationMarker() +MarkerArray SurroundObstacleCheckerDebugNode::makeVisualizationMarker() { - visualization_msgs::msg::MarkerArray msg; + MarkerArray msg; rclcpp::Time current_time = this->clock_->now(); - tf2::Transform tf_base_link2front( - tf2::Quaternion(0.0, 0.0, 0.0, 1.0), tf2::Vector3(base_link2front_, 0.0, 0.0)); // visualize stop line if (stop_pose_ptr_ != nullptr) { - visualization_msgs::msg::Marker marker; - marker.header.frame_id = "map"; - marker.header.stamp = current_time; - marker.ns = "virtual_wall/no_start"; - marker.id = 0; - marker.lifetime = rclcpp::Duration::from_seconds(0.5); - marker.type = visualization_msgs::msg::Marker::CUBE; - marker.action = visualization_msgs::msg::Marker::ADD; - tf2::Transform tf_map2base_link; - tf2::fromMsg(*stop_pose_ptr_, tf_map2base_link); - tf2::Transform tf_map2front = tf_map2base_link * tf_base_link2front; - tf2::toMsg(tf_map2front, marker.pose); - marker.pose.position.z += 1.0; - marker.scale.x = 0.1; - marker.scale.y = 5.0; - marker.scale.z = 2.0; - marker.color.a = 0.5; // Don't forget to set the alpha! - marker.color.r = 1.0; - marker.color.g = 0.0; - marker.color.b = 0.0; - msg.markers.push_back(marker); - } - - // visualize stop reason - if (stop_pose_ptr_ != nullptr) { - visualization_msgs::msg::Marker marker; - marker.header.frame_id = "map"; - marker.header.stamp = current_time; - marker.ns = "factor_text/no_start"; - marker.id = 0; - marker.lifetime = rclcpp::Duration::from_seconds(0.5); - marker.type = visualization_msgs::msg::Marker::TEXT_VIEW_FACING; - marker.action = visualization_msgs::msg::Marker::ADD; - tf2::Transform tf_map2base_link; - tf2::fromMsg(*stop_pose_ptr_, tf_map2base_link); - tf2::Transform tf_map2front = tf_map2base_link * tf_base_link2front; - tf2::toMsg(tf_map2front, marker.pose); - marker.pose.position.z += 2.0; - marker.scale.x = 0.0; - marker.scale.y = 0.0; - marker.scale.z = 1.0; - marker.color.a = 0.999; // Don't forget to set the alpha! - marker.color.r = 1.0; - marker.color.g = 1.0; - marker.color.b = 1.0; - marker.text = "surround obstacle"; - msg.markers.push_back(marker); + const auto p = calcOffsetPose(*stop_pose_ptr_, base_link2front_, 0.0, 0.0); + const auto markers = createStopVirtualWallMarker(p, "surround obstacle", current_time, 0); + appendMarkerArray(markers, &msg); } // visualize surround object if (stop_obstacle_point_ptr_ != nullptr) { - visualization_msgs::msg::Marker marker; - marker.header.frame_id = "map"; - marker.header.stamp = current_time; - marker.ns = "no_start_obstacle_text"; - marker.id = 0; - marker.lifetime = rclcpp::Duration::from_seconds(0.5); - marker.type = visualization_msgs::msg::Marker::TEXT_VIEW_FACING; - marker.action = visualization_msgs::msg::Marker::ADD; + auto marker = createDefaultMarker( + "map", current_time, "no_start_obstacle_text", 0, Marker::TEXT_VIEW_FACING, + createMarkerScale(0.0, 0.0, 1.0), createMarkerColor(1.0, 1.0, 1.0, 0.999)); marker.pose.position = *stop_obstacle_point_ptr_; marker.pose.position.z += 2.0; // add half of the heights of obj roughly - marker.pose.orientation.x = 0.0; - marker.pose.orientation.y = 0.0; - marker.pose.orientation.z = 0.0; - marker.pose.orientation.w = 1.0; - marker.scale.x = 0.0; - marker.scale.y = 0.0; - marker.scale.z = 1.0; - marker.color.a = 0.999; // Don't forget to set the alpha! - marker.color.r = 1.0; - marker.color.g = 1.0; - marker.color.b = 1.0; marker.text = "!"; msg.markers.push_back(marker); } @@ -158,7 +107,7 @@ visualization_msgs::msg::MarkerArray SurroundObstacleCheckerDebugNode::makeVisua return msg; } -tier4_planning_msgs::msg::StopReasonArray SurroundObstacleCheckerDebugNode::makeStopReasonArray() +StopReasonArray SurroundObstacleCheckerDebugNode::makeStopReasonArray() { // create header std_msgs::msg::Header header; @@ -166,9 +115,9 @@ tier4_planning_msgs::msg::StopReasonArray SurroundObstacleCheckerDebugNode::make header.stamp = this->clock_->now(); // create stop reason stamped - tier4_planning_msgs::msg::StopReason stop_reason_msg; - stop_reason_msg.reason = tier4_planning_msgs::msg::StopReason::SURROUND_OBSTACLE_CHECK; - tier4_planning_msgs::msg::StopFactor stop_factor; + StopReason stop_reason_msg; + stop_reason_msg.reason = StopReason::SURROUND_OBSTACLE_CHECK; + StopFactor stop_factor; if (stop_pose_ptr_ != nullptr) { stop_factor.stop_pose = *stop_pose_ptr_; @@ -179,8 +128,10 @@ tier4_planning_msgs::msg::StopReasonArray SurroundObstacleCheckerDebugNode::make } // create stop reason array - tier4_planning_msgs::msg::StopReasonArray stop_reason_array; + StopReasonArray stop_reason_array; stop_reason_array.header = header; stop_reason_array.stop_reasons.emplace_back(stop_reason_msg); return stop_reason_array; } + +} // namespace surround_obstacle_checker diff --git a/planning/surround_obstacle_checker/src/node.cpp b/planning/surround_obstacle_checker/src/node.cpp index 09fe48f35b57..9e1fc6711bd3 100644 --- a/planning/surround_obstacle_checker/src/node.cpp +++ b/planning/surround_obstacle_checker/src/node.cpp @@ -14,9 +14,17 @@ #include "surround_obstacle_checker/node.hpp" +#include + +#include +#include +#include +#include +#include +#include + #include #include -#include #include #ifdef ROS_DISTRO_GALACTIC #include @@ -34,313 +42,381 @@ #include #include +namespace surround_obstacle_checker +{ + +namespace bg = boost::geometry; +using Point2d = bg::model::d2::point_xy; +using Polygon2d = bg::model::polygon; +using tier4_autoware_utils::createPoint; +using tier4_autoware_utils::pose2transform; + +namespace +{ +std::string jsonDumpsPose(const geometry_msgs::msg::Pose & pose) +{ + const std::string json_dumps_pose = + (boost::format( + R"({"position":{"x":%lf,"y":%lf,"z":%lf},"orientation":{"w":%lf,"x":%lf,"y":%lf,"z":%lf}})") % + pose.position.x % pose.position.y % pose.position.z % pose.orientation.w % pose.orientation.x % + pose.orientation.y % pose.orientation.z) + .str(); + return json_dumps_pose; +} + +diagnostic_msgs::msg::DiagnosticStatus makeStopReasonDiag( + const std::string no_start_reason, const geometry_msgs::msg::Pose & stop_pose) +{ + diagnostic_msgs::msg::DiagnosticStatus no_start_reason_diag; + diagnostic_msgs::msg::KeyValue no_start_reason_diag_kv; + no_start_reason_diag.level = diagnostic_msgs::msg::DiagnosticStatus::OK; + no_start_reason_diag.name = "no_start_reason"; + no_start_reason_diag.message = no_start_reason; + no_start_reason_diag_kv.key = "no_start_pose"; + no_start_reason_diag_kv.value = jsonDumpsPose(stop_pose); + no_start_reason_diag.values.push_back(no_start_reason_diag_kv); + return no_start_reason_diag; +} + +geometry_msgs::msg::Point32 createPoint32(const double x, const double y, const double z) +{ + geometry_msgs::msg::Point32 p; + p.x = x; + p.y = y; + p.z = z; + return p; +} + +Polygon2d createObjPolygon( + const geometry_msgs::msg::Pose & pose, const geometry_msgs::msg::Polygon & footprint) +{ + geometry_msgs::msg::Polygon transformed_polygon{}; + geometry_msgs::msg::TransformStamped geometry_tf{}; + geometry_tf.transform = pose2transform(pose); + tf2::doTransform(footprint, transformed_polygon, geometry_tf); + + Polygon2d object_polygon; + for (const auto & p : transformed_polygon.points) { + object_polygon.outer().push_back(Point2d(p.x, p.y)); + } + + bg::correct(object_polygon); + + return object_polygon; +} + +Polygon2d createObjPolygon( + const geometry_msgs::msg::Pose & pose, const geometry_msgs::msg::Vector3 & size) +{ + const double & length_m = size.x / 2.0; + const double & width_m = size.y / 2.0; + + geometry_msgs::msg::Polygon polygon{}; + + polygon.points.push_back(createPoint32(length_m, -width_m, 0.0)); + polygon.points.push_back(createPoint32(length_m, width_m, 0.0)); + polygon.points.push_back(createPoint32(-length_m, width_m, 0.0)); + polygon.points.push_back(createPoint32(-length_m, -width_m, 0.0)); + + return createObjPolygon(pose, polygon); +} + +Polygon2d createSelfPolygon(const VehicleInfo & vehicle_info) +{ + const double & front_m = vehicle_info.max_longitudinal_offset_m; + const double & width_m = vehicle_info.min_lateral_offset_m; + const double & rear_m = vehicle_info.min_longitudinal_offset_m; + + Polygon2d ego_polygon; + + ego_polygon.outer().push_back(Point2d(front_m, -width_m)); + ego_polygon.outer().push_back(Point2d(front_m, width_m)); + ego_polygon.outer().push_back(Point2d(-rear_m, width_m)); + ego_polygon.outer().push_back(Point2d(-rear_m, -width_m)); + + bg::correct(ego_polygon); + + return ego_polygon; +} +} // namespace + SurroundObstacleCheckerNode::SurroundObstacleCheckerNode(const rclcpp::NodeOptions & node_options) -: Node("surround_obstacle_checker_node", node_options), - tf_buffer_(this->get_clock()), - tf_listener_(tf_buffer_), - vehicle_info_(vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo()) +: Node("surround_obstacle_checker_node", node_options) { // Parameters - use_pointcloud_ = this->declare_parameter("use_pointcloud", true); - use_dynamic_object_ = this->declare_parameter("use_dynamic_object", true); - surround_check_distance_ = this->declare_parameter("surround_check_distance", 2.0); - surround_check_recover_distance_ = - this->declare_parameter("surround_check_recover_distance", 2.5); - state_clear_time_ = this->declare_parameter("state_clear_time", 2.0); - stop_state_ego_speed_ = this->declare_parameter("stop_state_ego_speed", 0.1); - debug_ptr_ = std::make_shared( - vehicle_info_.max_longitudinal_offset_m, this->get_clock(), *this); - self_poly_ = createSelfPolygon(); + { + auto & p = node_param_; + p.use_pointcloud = this->declare_parameter("use_pointcloud", true); + p.use_dynamic_object = this->declare_parameter("use_dynamic_object", true); + p.surround_check_distance = this->declare_parameter("surround_check_distance", 2.0); + p.surround_check_recover_distance = + this->declare_parameter("surround_check_recover_distance", 2.5); + p.state_clear_time = this->declare_parameter("state_clear_time", 2.0); + p.stop_state_ego_speed = this->declare_parameter("stop_state_ego_speed", 0.1); + p.stop_state_entry_duration_time = + this->declare_parameter("stop_state_entry_duration_time", 0.1); + } + + vehicle_info_ = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo(); // Publishers - path_pub_ = - this->create_publisher("~/output/trajectory", 1); - stop_reason_diag_pub_ = + pub_stop_reason_ = this->create_publisher("~/output/no_start_reason", 1); + pub_clear_velocity_limit_ = + this->create_publisher("~/output/velocity_limit_clear_command", 1); + pub_velocity_limit_ = this->create_publisher("~/output/max_velocity", 1); - // Subscriber - path_sub_ = this->create_subscription( - "~/input/trajectory", 1, - std::bind(&SurroundObstacleCheckerNode::pathCallback, this, std::placeholders::_1)); - pointcloud_sub_ = this->create_subscription( + // Subscribers + sub_pointcloud_ = this->create_subscription( "~/input/pointcloud", rclcpp::SensorDataQoS(), - std::bind(&SurroundObstacleCheckerNode::pointCloudCallback, this, std::placeholders::_1)); - dynamic_object_sub_ = - this->create_subscription( - "~/input/objects", 1, - std::bind(&SurroundObstacleCheckerNode::dynamicObjectCallback, this, std::placeholders::_1)); - current_velocity_sub_ = this->create_subscription( + std::bind(&SurroundObstacleCheckerNode::onPointCloud, this, std::placeholders::_1)); + sub_dynamic_objects_ = this->create_subscription( + "~/input/objects", 1, + std::bind(&SurroundObstacleCheckerNode::onDynamicObjects, this, std::placeholders::_1)); + sub_odometry_ = this->create_subscription( "~/input/odometry", 1, - std::bind(&SurroundObstacleCheckerNode::currentVelocityCallback, this, std::placeholders::_1)); + std::bind(&SurroundObstacleCheckerNode::onOdometry, this, std::placeholders::_1)); + + using std::chrono_literals::operator""ms; + timer_ = rclcpp::create_timer( + this, get_clock(), 100ms, std::bind(&SurroundObstacleCheckerNode::onTimer, this)); + + last_running_time_ = std::make_shared(this->now()); + + // Debug + debug_ptr_ = std::make_shared( + vehicle_info_.max_longitudinal_offset_m, this->get_clock(), *this); } -void SurroundObstacleCheckerNode::pathCallback( - const autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr input_msg) +void SurroundObstacleCheckerNode::onTimer() { - if (use_pointcloud_ && !pointcloud_ptr_) { + if (node_param_.use_pointcloud && !pointcloud_ptr_) { RCLCPP_WARN_THROTTLE( this->get_logger(), *this->get_clock(), 1000 /* ms */, "waiting for pointcloud info..."); return; } - if (use_dynamic_object_ && !object_ptr_) { + if (node_param_.use_dynamic_object && !object_ptr_) { RCLCPP_WARN_THROTTLE( this->get_logger(), *this->get_clock(), 1000 /* ms */, "waiting for dynamic object info..."); return; } - if (!current_velocity_ptr_) { + if (!odometry_ptr_) { RCLCPP_WARN_THROTTLE( this->get_logger(), *this->get_clock(), 1000 /* ms */, "waiting for current velocity..."); return; } - // parameter description - TrajectoryPoints output_trajectory_points = - tier4_autoware_utils::convertToTrajectoryPointArray(*input_msg); + const auto nearest_obstacle = getNearestObstacle(); + const auto is_vehicle_stopped = isVehicleStopped(); - diagnostic_msgs::msg::DiagnosticStatus no_start_reason_diag; + switch (state_) { + case State::PASS: { + const auto is_obstacle_found = + !nearest_obstacle ? false + : nearest_obstacle.get().first < node_param_.surround_check_distance; - // get current pose in traj frame - geometry_msgs::msg::Pose current_pose; - if (!getPose(input_msg->header.frame_id, "base_link", current_pose)) { - return; - } + if (!isStopRequired(is_obstacle_found, is_vehicle_stopped)) { + break; + } + + state_ = State::STOP; - // get closest idx - const size_t closest_idx = getClosestIdx(output_trajectory_points, current_pose); + auto velocity_limit = std::make_shared(); + velocity_limit->stamp = this->now(); + velocity_limit->max_velocity = 0.0; + velocity_limit->use_constraints = false; + velocity_limit->sender = "surround_obstacle_checker"; - // get nearest object - double min_dist_to_obj = std::numeric_limits::max(); - geometry_msgs::msg::Point nearest_obj_point; - getNearestObstacle(&min_dist_to_obj, &nearest_obj_point); + pub_velocity_limit_->publish(*velocity_limit); - // check current obstacle status (exist or not) - const auto is_obstacle_found = isObstacleFound(min_dist_to_obj); + // do not start when there is a obstacle near the ego vehicle. + RCLCPP_WARN(get_logger(), "do not start because there is obstacle near the ego vehicle."); - // check current stop status (stop or not) - const auto is_stopped = checkStop(input_msg->points.at(closest_idx)); + break; + } - const auto is_stop_required = isStopRequired(is_obstacle_found, is_stopped); + case State::STOP: { + const auto is_obstacle_found = + !nearest_obstacle + ? false + : nearest_obstacle.get().first < node_param_.surround_check_recover_distance; - // insert stop velocity - if (is_stop_required) { - state_ = State::STOP; + if (isStopRequired(is_obstacle_found, is_vehicle_stopped)) { + break; + } - // do not start when there is a obstacle near the ego vehicle. - RCLCPP_WARN_THROTTLE( - get_logger(), *this->get_clock(), 500 /* ms */, - "do not start because there is obstacle near the ego vehicle."); - insertStopVelocity(closest_idx, &output_trajectory_points); + state_ = State::PASS; + + auto velocity_limit_clear_command = std::make_shared(); + velocity_limit_clear_command->stamp = this->now(); + velocity_limit_clear_command->command = true; + velocity_limit_clear_command->sender = "surround_obstacle_checker"; - // visualization for debug - if (is_obstacle_found) { - debug_ptr_->pushObstaclePoint(nearest_obj_point, PointType::NoStart); + pub_clear_velocity_limit_->publish(*velocity_limit_clear_command); + + break; } - debug_ptr_->pushPose(input_msg->points.at(closest_idx).pose, PoseType::NoStart); - no_start_reason_diag = makeStopReasonDiag("obstacle", input_msg->points.at(closest_idx).pose); - } else { - state_ = State::PASS; + + default: + break; } - // publish trajectory and debug info - auto output_msg = tier4_autoware_utils::convertToTrajectory(output_trajectory_points); - output_msg.header = input_msg->header; - path_pub_->publish(output_msg); - stop_reason_diag_pub_->publish(no_start_reason_diag); + if (nearest_obstacle) { + debug_ptr_->pushObstaclePoint(nearest_obstacle.get().second, PointType::NoStart); + } + + diagnostic_msgs::msg::DiagnosticStatus no_start_reason_diag; + if (state_ == State::STOP) { + debug_ptr_->pushPose(odometry_ptr_->pose.pose, PoseType::NoStart); + no_start_reason_diag = makeStopReasonDiag("obstacle", odometry_ptr_->pose.pose); + } + + pub_stop_reason_->publish(no_start_reason_diag); debug_ptr_->publish(); } -void SurroundObstacleCheckerNode::pointCloudCallback( - const sensor_msgs::msg::PointCloud2::ConstSharedPtr input_msg) +void SurroundObstacleCheckerNode::onPointCloud( + const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg) { - pointcloud_ptr_ = input_msg; + pointcloud_ptr_ = msg; } -void SurroundObstacleCheckerNode::dynamicObjectCallback( - const autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr input_msg) +void SurroundObstacleCheckerNode::onDynamicObjects(const PredictedObjects::ConstSharedPtr msg) { - object_ptr_ = input_msg; + object_ptr_ = msg; } -void SurroundObstacleCheckerNode::currentVelocityCallback( - const nav_msgs::msg::Odometry::ConstSharedPtr input_msg) +void SurroundObstacleCheckerNode::onOdometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg) { - current_velocity_ptr_ = input_msg; + odometry_ptr_ = msg; } -void SurroundObstacleCheckerNode::insertStopVelocity( - const size_t closest_idx, TrajectoryPoints * traj) +boost::optional SurroundObstacleCheckerNode::getNearestObstacle() const { - // set zero velocity from closest idx to last idx - for (size_t i = closest_idx; i < traj->size(); i++) { - traj->at(i).longitudinal_velocity_mps = 0.0; - } -} + boost::optional nearest_pointcloud{boost::none}; + boost::optional nearest_object{boost::none}; -bool SurroundObstacleCheckerNode::getPose( - const std::string & source, const std::string & target, geometry_msgs::msg::Pose & pose) -{ - try { - // get transform from source to target - geometry_msgs::msg::TransformStamped ros_src2tgt = - tf_buffer_.lookupTransform(source, target, tf2::TimePointZero); - // convert geometry_msgs::msg::Transform to geometry_msgs::msg::Pose - tf2::Transform transform; - tf2::fromMsg(ros_src2tgt.transform, transform); - tf2::toMsg(transform, pose); - } catch (tf2::TransformException & ex) { - RCLCPP_WARN_STREAM_THROTTLE( - get_logger(), *this->get_clock(), 500 /* ms */, - "cannot get tf from " << source << " to " << target); - return false; + if (node_param_.use_pointcloud) { + nearest_pointcloud = getNearestObstacleByPointCloud(); } - return true; -} -bool SurroundObstacleCheckerNode::convertPose( - const geometry_msgs::msg::Pose & pose, const std::string & source, const std::string & target, - const rclcpp::Time & time, geometry_msgs::msg::Pose & conv_pose) -{ - tf2::Transform src2tgt; - try { - // get transform from source to target - geometry_msgs::msg::TransformStamped ros_src2tgt = - tf_buffer_.lookupTransform(source, target, time, tf2::durationFromSec(0.1)); - tf2::fromMsg(ros_src2tgt.transform, src2tgt); - } catch (tf2::TransformException & ex) { - RCLCPP_WARN_STREAM_THROTTLE( - get_logger(), *this->get_clock(), 500 /* ms */, - "cannot get tf from " << source << " to " << target); - return false; + if (node_param_.use_dynamic_object) { + nearest_object = getNearestObstacleByDynamicObject(); } - tf2::Transform src2obj; - tf2::fromMsg(pose, src2obj); - tf2::Transform tgt2obj = src2tgt.inverse() * src2obj; - tf2::toMsg(tgt2obj, conv_pose); - return true; -} - -size_t SurroundObstacleCheckerNode::getClosestIdx( - const TrajectoryPoints & traj, const geometry_msgs::msg::Pose current_pose) -{ - double min_dist = std::numeric_limits::max(); - size_t min_dist_idx = 0; - for (size_t i = 0; i < traj.size(); ++i) { - const double x = traj.at(i).pose.position.x - current_pose.position.x; - const double y = traj.at(i).pose.position.y - current_pose.position.y; - const double dist = std::hypot(x, y); - if (dist < min_dist) { - min_dist_idx = i; - min_dist = dist; - } + if (!nearest_pointcloud && !nearest_object) { + return {}; } - return min_dist_idx; -} -void SurroundObstacleCheckerNode::getNearestObstacle( - double * min_dist_to_obj, geometry_msgs::msg::Point * nearest_obj_point) -{ - if (use_pointcloud_) { - getNearestObstacleByPointCloud(min_dist_to_obj, nearest_obj_point); + if (!nearest_pointcloud) { + return nearest_object; } - if (use_dynamic_object_) { - getNearestObstacleByDynamicObject(min_dist_to_obj, nearest_obj_point); + if (!nearest_object) { + return nearest_pointcloud; } + + return nearest_pointcloud.get().first < nearest_object.get().first ? nearest_pointcloud + : nearest_object; } -void SurroundObstacleCheckerNode::getNearestObstacleByPointCloud( - double * min_dist_to_obj, geometry_msgs::msg::Point * nearest_obj_point) +boost::optional SurroundObstacleCheckerNode::getNearestObstacleByPointCloud() const { - // wait to transform pointcloud - geometry_msgs::msg::TransformStamped transform_stamped; - try { - transform_stamped = tf_buffer_.lookupTransform( - "base_link", pointcloud_ptr_->header.frame_id, pointcloud_ptr_->header.stamp, - tf2::durationFromSec(0.5)); - } catch (tf2::TransformException & ex) { - RCLCPP_WARN_STREAM_THROTTLE( - get_logger(), *this->get_clock(), 500 /* ms */, - "failed to get base_link to " << pointcloud_ptr_->header.frame_id << " transform."); - return; + const auto transform_stamped = + getTransform("base_link", pointcloud_ptr_->header.frame_id, pointcloud_ptr_->header.stamp, 0.5); + + geometry_msgs::msg::Point nearest_point; + auto minimum_distance = std::numeric_limits::max(); + + if (!transform_stamped) { + return {}; } - Eigen::Affine3f isometry = tf2::transformToEigen(transform_stamped.transform).cast(); - pcl::PointCloud pcl; - pcl::fromROSMsg(*pointcloud_ptr_, pcl); - pcl::transformPointCloud(pcl, pcl, isometry); - for (const auto & p : pcl) { - // create boost point - Point2d boost_p(p.x, p.y); - - // calc distance - const double dist_to_obj = boost::geometry::distance(self_poly_, boost_p); - - // get minimum distance to obj - if (dist_to_obj < *min_dist_to_obj) { - *min_dist_to_obj = dist_to_obj; - nearest_obj_point->x = p.x; - nearest_obj_point->y = p.y; - nearest_obj_point->z = p.z; + Eigen::Affine3f isometry = tf2::transformToEigen(transform_stamped.get().transform).cast(); + pcl::PointCloud transformed_pointcloud; + pcl::fromROSMsg(*pointcloud_ptr_, transformed_pointcloud); + pcl::transformPointCloud(transformed_pointcloud, transformed_pointcloud, isometry); + + const auto ego_polygon = createSelfPolygon(vehicle_info_); + + for (const auto & p : transformed_pointcloud) { + Point2d boost_point(p.x, p.y); + + const auto distance_to_object = bg::distance(ego_polygon, boost_point); + + if (distance_to_object < minimum_distance) { + nearest_point = createPoint(p.x, p.y, p.z); + minimum_distance = distance_to_object; } } + + return std::make_pair(minimum_distance, nearest_point); } -void SurroundObstacleCheckerNode::getNearestObstacleByDynamicObject( - double * min_dist_to_obj, geometry_msgs::msg::Point * nearest_obj_point) +boost::optional SurroundObstacleCheckerNode::getNearestObstacleByDynamicObject() const { - const auto obj_frame = object_ptr_->header.frame_id; - const auto obj_time = object_ptr_->header.stamp; - for (const auto & obj : object_ptr_->objects) { - // change frame of obj_pose to base_link - geometry_msgs::msg::Pose pose_baselink; - if (!convertPose( - obj.kinematics.initial_pose_with_covariance.pose, obj_frame, "base_link", obj_time, - pose_baselink)) { - return; - } + const auto transform_stamped = + getTransform(object_ptr_->header.frame_id, "base_link", object_ptr_->header.stamp, 0.5); - // create obj polygon - Polygon2d obj_poly; - if (obj.shape.type == autoware_auto_perception_msgs::msg::Shape::POLYGON) { - obj_poly = createObjPolygon(pose_baselink, obj.shape.footprint); - } else { - obj_poly = createObjPolygon(pose_baselink, obj.shape.dimensions); - } + geometry_msgs::msg::Point nearest_point; + auto minimum_distance = std::numeric_limits::max(); + + if (!transform_stamped) { + return {}; + } + + tf2::Transform tf_src2target; + tf2::fromMsg(transform_stamped.get().transform, tf_src2target); + + const auto ego_polygon = createSelfPolygon(vehicle_info_); - // calc distance - const double dist_to_obj = boost::geometry::distance(self_poly_, obj_poly); + for (const auto & object : object_ptr_->objects) { + const auto & object_pose = object.kinematics.initial_pose_with_covariance.pose; - // get minimum distance to obj - if (dist_to_obj < *min_dist_to_obj) { - *min_dist_to_obj = dist_to_obj; - *nearest_obj_point = obj.kinematics.initial_pose_with_covariance.pose.position; + tf2::Transform tf_src2object; + tf2::fromMsg(object_pose, tf_src2object); + + geometry_msgs::msg::Pose transformed_object_pose; + tf2::toMsg(tf_src2target.inverse() * tf_src2object, transformed_object_pose); + + const auto object_polygon = + object.shape.type == Shape::POLYGON + ? createObjPolygon(transformed_object_pose, object.shape.footprint) + : createObjPolygon(transformed_object_pose, object.shape.dimensions); + + const auto distance_to_object = bg::distance(ego_polygon, object_polygon); + + if (distance_to_object < minimum_distance) { + nearest_point = object_pose.position; + minimum_distance = distance_to_object; } } + + return std::make_pair(minimum_distance, nearest_point); } -bool SurroundObstacleCheckerNode::isObstacleFound(const double min_dist_to_obj) +boost::optional SurroundObstacleCheckerNode::getTransform( + const std::string & source, const std::string & target, const rclcpp::Time & stamp, + double duration_sec) const { - const auto is_obstacle_inside_range = min_dist_to_obj < surround_check_distance_; - const auto is_obstacle_outside_range = min_dist_to_obj > surround_check_recover_distance_; - - if (state_ == State::PASS) { - return is_obstacle_inside_range; - } + geometry_msgs::msg::TransformStamped transform_stamped; - if (state_ == State::STOP) { - return !is_obstacle_outside_range; + try { + transform_stamped = + tf_buffer_.lookupTransform(source, target, stamp, tf2::durationFromSec(duration_sec)); + } catch (tf2::TransformException & ex) { + return {}; } - throw std::runtime_error("invalid state"); + return transform_stamped; } bool SurroundObstacleCheckerNode::isStopRequired( - const bool is_obstacle_found, const bool is_stopped) + const bool is_obstacle_found, const bool is_vehicle_stopped) { - if (!is_stopped) { + if (!is_vehicle_stopped) { return false; } @@ -356,7 +432,7 @@ bool SurroundObstacleCheckerNode::isStopRequired( // Keep stop state if (last_obstacle_found_time_) { const auto elapsed_time = this->now() - *last_obstacle_found_time_; - if (elapsed_time.seconds() <= state_clear_time_) { + if (elapsed_time.seconds() <= node_param_.state_clear_time) { return true; } } @@ -365,118 +441,18 @@ bool SurroundObstacleCheckerNode::isStopRequired( return false; } -bool SurroundObstacleCheckerNode::checkStop( - const autoware_auto_planning_msgs::msg::TrajectoryPoint & closest_point) -{ - if (std::fabs(current_velocity_ptr_->twist.twist.linear.x) > stop_state_ego_speed_) { - // ego vehicle has high velocity now. not stop. - return false; - } - - const double closest_vel = closest_point.longitudinal_velocity_mps; - const double closest_acc = closest_point.acceleration_mps2; - - if (closest_vel * closest_acc < 0) { - // ego vehicle is about to stop (during deceleration). not stop. - return false; - } - - return true; -} - -Polygon2d SurroundObstacleCheckerNode::createSelfPolygon() -{ - const double front = vehicle_info_.max_longitudinal_offset_m; - const double rear = vehicle_info_.min_longitudinal_offset_m; - const double left = vehicle_info_.max_lateral_offset_m; - const double right = vehicle_info_.min_lateral_offset_m; - - Polygon2d poly; - boost::geometry::exterior_ring(poly) = boost::assign::list_of(front, left)(front, right)( - rear, right)(rear, left)(front, left); - return poly; -} - -Polygon2d SurroundObstacleCheckerNode::createObjPolygon( - const geometry_msgs::msg::Pose & pose, const geometry_msgs::msg::Vector3 & size) +bool SurroundObstacleCheckerNode::isVehicleStopped() { - // rename - const double x = pose.position.x; - const double y = pose.position.y; - const double h = size.x; - const double w = size.y; - const double yaw = tf2::getYaw(pose.orientation); - - // create base polygon - Polygon2d obj_poly; - boost::geometry::exterior_ring(obj_poly) = boost::assign::list_of(h / 2.0, w / 2.0)( - -h / 2.0, w / 2.0)(-h / 2.0, -w / 2.0)(h / 2.0, -w / 2.0)(h / 2.0, w / 2.0); - - // rotate polygon(yaw) - boost::geometry::strategy::transform::rotate_transformer - rotate(-yaw); // anti-clockwise -> :clockwise rotation - Polygon2d rotate_obj_poly; - boost::geometry::transform(obj_poly, rotate_obj_poly, rotate); - - // translate polygon(x, y) - boost::geometry::strategy::transform::translate_transformer translate(x, y); - Polygon2d translate_obj_poly; - boost::geometry::transform(rotate_obj_poly, translate_obj_poly, translate); - return translate_obj_poly; -} + const auto current_velocity = std::abs(odometry_ptr_->twist.twist.linear.x); -Polygon2d SurroundObstacleCheckerNode::createObjPolygon( - const geometry_msgs::msg::Pose & pose, const geometry_msgs::msg::Polygon & footprint) -{ - // rename - const double x = pose.position.x; - const double y = pose.position.y; - const double yaw = tf2::getYaw(pose.orientation); - - // create base polygon - Polygon2d obj_poly; - for (const auto point : footprint.points) { - const Point2d point2d(point.x, point.y); - obj_poly.outer().push_back(point2d); + if (node_param_.stop_state_ego_speed < current_velocity) { + last_running_time_ = std::make_shared(this->now()); } - // rotate polygon(yaw) - boost::geometry::strategy::transform::rotate_transformer - rotate(-yaw); // anti-clockwise -> :clockwise rotation - Polygon2d rotate_obj_poly; - boost::geometry::transform(obj_poly, rotate_obj_poly, rotate); - - // translate polygon(x, y) - boost::geometry::strategy::transform::translate_transformer translate(x, y); - Polygon2d translate_obj_poly; - boost::geometry::transform(rotate_obj_poly, translate_obj_poly, translate); - return translate_obj_poly; -} - -diagnostic_msgs::msg::DiagnosticStatus SurroundObstacleCheckerNode::makeStopReasonDiag( - const std::string no_start_reason, const geometry_msgs::msg::Pose & stop_pose) -{ - diagnostic_msgs::msg::DiagnosticStatus no_start_reason_diag; - diagnostic_msgs::msg::KeyValue no_start_reason_diag_kv; - no_start_reason_diag.level = diagnostic_msgs::msg::DiagnosticStatus::OK; - no_start_reason_diag.name = "no_start_reason"; - no_start_reason_diag.message = no_start_reason; - no_start_reason_diag_kv.key = "no_start_pose"; - no_start_reason_diag_kv.value = jsonDumpsPose(stop_pose); - no_start_reason_diag.values.push_back(no_start_reason_diag_kv); - return no_start_reason_diag; + return node_param_.stop_state_entry_duration_time < (this->now() - *last_running_time_).seconds(); } -std::string SurroundObstacleCheckerNode::jsonDumpsPose(const geometry_msgs::msg::Pose & pose) -{ - const std::string json_dumps_pose = - (boost::format( - R"({"position":{"x":%lf,"y":%lf,"z":%lf},"orientation":{"w":%lf,"x":%lf,"y":%lf,"z":%lf}})") % - pose.position.x % pose.position.y % pose.position.z % pose.orientation.w % pose.orientation.x % - pose.orientation.y % pose.orientation.z) - .str(); - return json_dumps_pose; -} +} // namespace surround_obstacle_checker #include -RCLCPP_COMPONENTS_REGISTER_NODE(SurroundObstacleCheckerNode) +RCLCPP_COMPONENTS_REGISTER_NODE(surround_obstacle_checker::SurroundObstacleCheckerNode) From 178a65c40a5d3caad2c1d66cd0853dc14ffd79e2 Mon Sep 17 00:00:00 2001 From: Yukihiro Saito Date: Tue, 10 May 2022 10:15:23 +0900 Subject: [PATCH 11/55] feat: remove deprecated package in prediction launch (#875) Signed-off-by: Yukihiro Saito --- .../launch/object_recognition/prediction/prediction.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/launch/tier4_perception_launch/launch/object_recognition/prediction/prediction.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/prediction/prediction.launch.xml index 4749bd45d3e3..fd9d1ba6f3cd 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/prediction/prediction.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/prediction/prediction.launch.xml @@ -9,6 +9,6 @@ - + From 429a06c385faf4d588947a56ec4ebdf4d7f635cd Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 10 May 2022 12:43:47 +0900 Subject: [PATCH 12/55] fix(surround_obstacle_checker): fix ego footprint polygon (#877) Signed-off-by: satoshi-ota --- planning/surround_obstacle_checker/src/node.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/planning/surround_obstacle_checker/src/node.cpp b/planning/surround_obstacle_checker/src/node.cpp index 9e1fc6711bd3..cd7117f36014 100644 --- a/planning/surround_obstacle_checker/src/node.cpp +++ b/planning/surround_obstacle_checker/src/node.cpp @@ -131,8 +131,8 @@ Polygon2d createSelfPolygon(const VehicleInfo & vehicle_info) ego_polygon.outer().push_back(Point2d(front_m, -width_m)); ego_polygon.outer().push_back(Point2d(front_m, width_m)); - ego_polygon.outer().push_back(Point2d(-rear_m, width_m)); - ego_polygon.outer().push_back(Point2d(-rear_m, -width_m)); + ego_polygon.outer().push_back(Point2d(rear_m, width_m)); + ego_polygon.outer().push_back(Point2d(rear_m, -width_m)); bg::correct(ego_polygon); From c092de0ea6d2e5c8c1d47eb034faf958d4d4d8ac Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Tue, 10 May 2022 15:21:49 +0900 Subject: [PATCH 13/55] fix: update nvinfer api (#863) * fix(lidar_centerpoint): update nvinfer api Signed-off-by: Daisuke Nishimatsu * fix(tensorrt_yolo): update nvinfer api Signed-off-by: Daisuke Nishimatsu * fix(lidar_apollo_instance_segmentation): update nvinfer api Signed-off-by: Daisuke Nishimatsu * fix(traffic_light_classifier): update nvinfer api Signed-off-by: Daisuke Nishimatsu * fix(traffic_light_ssd_fine_detector): update nvinfer api Signed-off-by: Daisuke Nishimatsu * pre-commit run Signed-off-by: Daisuke Nishimatsu --- .../CMakeLists.txt | 3 --- .../lib/include/TrtNet.hpp | 6 ++--- .../lib/src/TrtNet.cpp | 2 +- .../src/detector.cpp | 26 +++++++++++++------ perception/lidar_centerpoint/CMakeLists.txt | 10 ++++--- .../lib/include/tensorrt_wrapper.hpp | 3 ++- .../lib/src/tensorrt_wrapper.cpp | 14 ++++++---- perception/tensorrt_yolo/CMakeLists.txt | 3 --- .../tensorrt_yolo/lib/include/trt_yolo.hpp | 3 ++- perception/tensorrt_yolo/lib/src/trt_yolo.cpp | 16 +++++++----- .../traffic_light_classifier/CMakeLists.txt | 3 --- .../utils/trt_common.cpp | 14 ++++++---- .../CMakeLists.txt | 3 --- .../lib/include/trt_ssd.hpp | 3 ++- .../lib/src/trt_ssd.cpp | 14 ++++++---- 15 files changed, 72 insertions(+), 51 deletions(-) diff --git a/perception/lidar_apollo_instance_segmentation/CMakeLists.txt b/perception/lidar_apollo_instance_segmentation/CMakeLists.txt index 4fee2ecdd2f3..433999051097 100644 --- a/perception/lidar_apollo_instance_segmentation/CMakeLists.txt +++ b/perception/lidar_apollo_instance_segmentation/CMakeLists.txt @@ -4,9 +4,6 @@ project(lidar_apollo_instance_segmentation) find_package(autoware_cmake REQUIRED) autoware_package() -# TODO: remove (https://github.com/autowarefoundation/autoware.universe/issues/850) -add_compile_options(-Wno-deprecated-declarations) - option(CUDA_VERBOSE "Verbose output of CUDA modules" OFF) # set flags for CUDA availability diff --git a/perception/lidar_apollo_instance_segmentation/lib/include/TrtNet.hpp b/perception/lidar_apollo_instance_segmentation/lib/include/TrtNet.hpp index 30d560135cb4..14c1ff6d44c6 100644 --- a/perception/lidar_apollo_instance_segmentation/lib/include/TrtNet.hpp +++ b/perception/lidar_apollo_instance_segmentation/lib/include/TrtNet.hpp @@ -56,13 +56,13 @@ class trtNet } if (!mTrtRunTime) { - mTrtRunTime->destroy(); + delete mTrtRunTime; } if (!mTrtContext) { - mTrtContext->destroy(); + delete mTrtContext; } if (!mTrtEngine) { - mTrtEngine->destroy(); + delete mTrtEngine; } } diff --git a/perception/lidar_apollo_instance_segmentation/lib/src/TrtNet.cpp b/perception/lidar_apollo_instance_segmentation/lib/src/TrtNet.cpp index c51adc83e07c..0f1da4bdac8a 100644 --- a/perception/lidar_apollo_instance_segmentation/lib/src/TrtNet.cpp +++ b/perception/lidar_apollo_instance_segmentation/lib/src/TrtNet.cpp @@ -100,7 +100,7 @@ trtNet::trtNet(const std::string & engineFile) mTrtRunTime = createInferRuntime(gLogger); assert(mTrtRunTime != nullptr); - mTrtEngine = mTrtRunTime->deserializeCudaEngine(data.get(), length, nullptr); + mTrtEngine = mTrtRunTime->deserializeCudaEngine(data.get(), length); assert(mTrtEngine != nullptr); InitEngine(); diff --git a/perception/lidar_apollo_instance_segmentation/src/detector.cpp b/perception/lidar_apollo_instance_segmentation/src/detector.cpp index 7d628173b2e4..af8b29f55f34 100644 --- a/perception/lidar_apollo_instance_segmentation/src/detector.cpp +++ b/perception/lidar_apollo_instance_segmentation/src/detector.cpp @@ -63,17 +63,27 @@ LidarApolloInstanceSegmentation::LidarApolloInstanceSegmentation(rclcpp::Node * const int batch_size = 1; builder->setMaxBatchSize(batch_size); config->setMaxWorkspaceSize(1 << 30); - nvinfer1::ICudaEngine * engine = builder->buildEngineWithConfig(*network, *config); - nvinfer1::IHostMemory * trt_model_stream = engine->serialize(); - assert(trt_model_stream != nullptr); + nvinfer1::IHostMemory * plan = builder->buildSerializedNetwork(*network, *config); + assert(plan != nullptr); std::ofstream outfile(engine_file, std::ofstream::binary); assert(!outfile.fail()); - outfile.write(reinterpret_cast(trt_model_stream->data()), trt_model_stream->size()); + outfile.write(reinterpret_cast(plan->data()), plan->size()); outfile.close(); - network->destroy(); - parser->destroy(); - builder->destroy(); - config->destroy(); + if (network) { + delete network; + } + if (parser) { + delete parser; + } + if (builder) { + delete builder; + } + if (config) { + delete config; + } + if (plan) { + delete plan; + } } net_ptr_.reset(new Tn::trtNet(engine_file)); diff --git a/perception/lidar_centerpoint/CMakeLists.txt b/perception/lidar_centerpoint/CMakeLists.txt index 1f5c869136eb..0cf1f51654bb 100644 --- a/perception/lidar_centerpoint/CMakeLists.txt +++ b/perception/lidar_centerpoint/CMakeLists.txt @@ -4,9 +4,6 @@ project(lidar_centerpoint) find_package(autoware_cmake REQUIRED) autoware_package() -# TODO: remove (https://github.com/autowarefoundation/autoware.universe/issues/850) -add_compile_options(-Wno-deprecated-declarations -Wno-unknown-pragmas) - option(CUDA_VERBOSE "Verbose output of CUDA modules" OFF) # set flags for CUDA availability @@ -144,6 +141,13 @@ if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL) centerpoint_cuda_libraries ) + # To suppress unknown-pragmas error. The root-cause is CUB library in CUDA 11.6. + # This issue was fixed by https://github.com/NVIDIA/cub/commit/7d608bf1dc14553e2fb219eabeed80b76621b6fe + target_include_directories(centerpoint + SYSTEM PUBLIC + ${CUDA_INCLUDE_DIRS} + ) + ## node ## ament_auto_add_library(lidar_centerpoint_component SHARED src/node.cpp diff --git a/perception/lidar_centerpoint/lib/include/tensorrt_wrapper.hpp b/perception/lidar_centerpoint/lib/include/tensorrt_wrapper.hpp index dd49723a5265..b334be9e2230 100644 --- a/perception/lidar_centerpoint/lib/include/tensorrt_wrapper.hpp +++ b/perception/lidar_centerpoint/lib/include/tensorrt_wrapper.hpp @@ -29,7 +29,7 @@ struct Deleter void operator()(T * obj) const { if (obj) { - obj->destroy(); + delete obj; } } }; @@ -82,6 +82,7 @@ class TensorRTWrapper bool createContext(); unique_ptr runtime_ = nullptr; + unique_ptr plan_ = nullptr; unique_ptr engine_ = nullptr; }; diff --git a/perception/lidar_centerpoint/lib/src/tensorrt_wrapper.cpp b/perception/lidar_centerpoint/lib/src/tensorrt_wrapper.cpp index 3691128137c3..f9882afac8f9 100644 --- a/perception/lidar_centerpoint/lib/src/tensorrt_wrapper.cpp +++ b/perception/lidar_centerpoint/lib/src/tensorrt_wrapper.cpp @@ -104,7 +104,13 @@ bool TensorRTWrapper::parseONNX( std::cout << "Applying optimizations and building TRT CUDA engine (" << onnx_path << ") ..." << std::endl; - engine_ = unique_ptr(builder->buildEngineWithConfig(*network, *config)); + plan_ = unique_ptr(builder->buildSerializedNetwork(*network, *config)); + if (!plan_) { + std::cout << "Fail to create serialized network" << std::endl; + return false; + } + engine_ = unique_ptr( + runtime_->deserializeCudaEngine(plan_->data(), plan_->size())); if (!engine_) { std::cout << "Fail to create engine" << std::endl; return false; @@ -116,9 +122,8 @@ bool TensorRTWrapper::parseONNX( bool TensorRTWrapper::saveEngine(const std::string & engine_path) { std::cout << "Writing to " << engine_path << std::endl; - auto serialized = unique_ptr(engine_->serialize()); std::ofstream file(engine_path, std::ios::out | std::ios::binary); - file.write(reinterpret_cast(serialized->data()), serialized->size()); + file.write(reinterpret_cast(plan_->data()), plan_->size()); return true; } @@ -139,8 +144,7 @@ bool TensorRTWrapper::loadEngine(const std::string & engine_path) } std::cout << "Loading from " << engine_path << std::endl; - engine_ = - unique_ptr(runtime_->deserializeCudaEngine(buffer.get(), size, nullptr)); + engine_ = unique_ptr(runtime_->deserializeCudaEngine(buffer.get(), size)); return true; } diff --git a/perception/tensorrt_yolo/CMakeLists.txt b/perception/tensorrt_yolo/CMakeLists.txt index c05fefc38d15..a50af6bfa9ab 100755 --- a/perception/tensorrt_yolo/CMakeLists.txt +++ b/perception/tensorrt_yolo/CMakeLists.txt @@ -4,9 +4,6 @@ project(tensorrt_yolo) find_package(autoware_cmake REQUIRED) autoware_package() -# TODO: remove (https://github.com/autowarefoundation/autoware.universe/issues/850) -add_compile_options(-Wno-deprecated-declarations) - option(CUDA_VERBOSE "Verbose output of CUDA modules" OFF) find_package(OpenCV REQUIRED) diff --git a/perception/tensorrt_yolo/lib/include/trt_yolo.hpp b/perception/tensorrt_yolo/lib/include/trt_yolo.hpp index 813811226a0a..c951154820f1 100644 --- a/perception/tensorrt_yolo/lib/include/trt_yolo.hpp +++ b/perception/tensorrt_yolo/lib/include/trt_yolo.hpp @@ -59,7 +59,7 @@ struct Deleter void operator()(T * obj) const { if (obj) { - obj->destroy(); + delete obj; } } }; @@ -130,6 +130,7 @@ class Net private: unique_ptr runtime_ = nullptr; + unique_ptr plan_ = nullptr; unique_ptr engine_ = nullptr; unique_ptr context_ = nullptr; cudaStream_t stream_ = nullptr; diff --git a/perception/tensorrt_yolo/lib/src/trt_yolo.cpp b/perception/tensorrt_yolo/lib/src/trt_yolo.cpp index 1be5f279714b..748680266ca9 100644 --- a/perception/tensorrt_yolo/lib/src/trt_yolo.cpp +++ b/perception/tensorrt_yolo/lib/src/trt_yolo.cpp @@ -65,8 +65,7 @@ void Net::load(const std::string & path) file.read(buffer, size); file.close(); if (runtime_) { - engine_ = - unique_ptr(runtime_->deserializeCudaEngine(buffer, size, nullptr)); + engine_ = unique_ptr(runtime_->deserializeCudaEngine(buffer, size)); } delete[] buffer; } @@ -253,9 +252,15 @@ Net::Net( // Build engine std::cout << "Applying optimizations and building TRT CUDA engine..." << std::endl; - engine_ = unique_ptr(builder->buildEngineWithConfig(*network, *config)); + plan_ = unique_ptr(builder->buildSerializedNetwork(*network, *config)); + if (!plan_) { + std::cout << "Fail to create serialized network" << std::endl; + return; + } + engine_ = unique_ptr( + runtime_->deserializeCudaEngine(plan_->data(), plan_->size())); if (!prepare()) { - std::cout << "Fail to prepare engine" << std::endl; + std::cout << "Fail to create engine" << std::endl; return; } } @@ -263,9 +268,8 @@ Net::Net( void Net::save(const std::string & path) const { std::cout << "Writing to " << path << "..." << std::endl; - auto serialized = unique_ptr(engine_->serialize()); std::ofstream file(path, std::ios::out | std::ios::binary); - file.write(reinterpret_cast(serialized->data()), serialized->size()); + file.write(reinterpret_cast(plan_->data()), plan_->size()); } void Net::infer(std::vector & buffers, const int batch_size) diff --git a/perception/traffic_light_classifier/CMakeLists.txt b/perception/traffic_light_classifier/CMakeLists.txt index 08897bfa3cf5..8ebd5f32db99 100644 --- a/perception/traffic_light_classifier/CMakeLists.txt +++ b/perception/traffic_light_classifier/CMakeLists.txt @@ -4,9 +4,6 @@ project(traffic_light_classifier) find_package(autoware_cmake REQUIRED) autoware_package() -# TODO: remove (https://github.com/autowarefoundation/autoware.universe/issues/850) -add_compile_options(-Wno-deprecated-declarations) - option(CUDA_VERBOSE "Verbose output of CUDA modules" OFF) # set flags for CUDA availability option(CUDA_AVAIL "CUDA available" OFF) diff --git a/perception/traffic_light_classifier/utils/trt_common.cpp b/perception/traffic_light_classifier/utils/trt_common.cpp index a920d47fa295..cae9f0cd1682 100644 --- a/perception/traffic_light_classifier/utils/trt_common.cpp +++ b/perception/traffic_light_classifier/utils/trt_common.cpp @@ -45,6 +45,7 @@ TrtCommon::TrtCommon(std::string model_path, std::string precision) is_initialized_(false), max_batch_size_(1) { + runtime_ = UniquePtr(nvinfer1::createInferRuntime(logger_)); } void TrtCommon::setup() @@ -86,9 +87,8 @@ bool TrtCommon::loadEngine(std::string engine_file_path) std::stringstream engine_buffer; engine_buffer << engine_file.rdbuf(); std::string engine_str = engine_buffer.str(); - runtime_ = UniquePtr(nvinfer1::createInferRuntime(logger_)); engine_ = UniquePtr(runtime_->deserializeCudaEngine( - reinterpret_cast(engine_str.data()), engine_str.size(), nullptr)); + reinterpret_cast(engine_str.data()), engine_str.size())); return true; } @@ -117,19 +117,23 @@ bool TrtCommon::buildEngineFromOnnx(std::string onnx_file_path, std::string outp return false; } - engine_ = UniquePtr(builder->buildEngineWithConfig(*network, *config)); + auto plan = UniquePtr(builder->buildSerializedNetwork(*network, *config)); + if (!plan) { + return false; + } + engine_ = + UniquePtr(runtime_->deserializeCudaEngine(plan->data(), plan->size())); if (!engine_) { return false; } // save engine - nvinfer1::IHostMemory * data = engine_->serialize(); std::ofstream file; file.open(output_engine_file_path, std::ios::binary | std::ios::out); if (!file.is_open()) { return false; } - file.write((const char *)data->data(), data->size()); + file.write((const char *)plan->data(), plan->size()); file.close(); return true; diff --git a/perception/traffic_light_ssd_fine_detector/CMakeLists.txt b/perception/traffic_light_ssd_fine_detector/CMakeLists.txt index e82c790f4fd1..eb172b7faf98 100644 --- a/perception/traffic_light_ssd_fine_detector/CMakeLists.txt +++ b/perception/traffic_light_ssd_fine_detector/CMakeLists.txt @@ -4,9 +4,6 @@ project(traffic_light_ssd_fine_detector) find_package(autoware_cmake REQUIRED) autoware_package() -# TODO: remove (https://github.com/autowarefoundation/autoware.universe/issues/850) -add_compile_options(-Wno-deprecated-declarations) - option(CUDA_VERBOSE "Verbose output of CUDA modules" OFF) find_package(OpenCV REQUIRED) diff --git a/perception/traffic_light_ssd_fine_detector/lib/include/trt_ssd.hpp b/perception/traffic_light_ssd_fine_detector/lib/include/trt_ssd.hpp index bbe5ae8da513..cfb6c8a6d575 100644 --- a/perception/traffic_light_ssd_fine_detector/lib/include/trt_ssd.hpp +++ b/perception/traffic_light_ssd_fine_detector/lib/include/trt_ssd.hpp @@ -31,7 +31,7 @@ struct Deleter void operator()(T * obj) const { if (obj) { - obj->destroy(); + delete obj; } } }; @@ -87,6 +87,7 @@ class Net private: unique_ptr runtime_ = nullptr; + unique_ptr plan_ = nullptr; unique_ptr engine_ = nullptr; unique_ptr context_ = nullptr; cudaStream_t stream_ = nullptr; diff --git a/perception/traffic_light_ssd_fine_detector/lib/src/trt_ssd.cpp b/perception/traffic_light_ssd_fine_detector/lib/src/trt_ssd.cpp index 766de7eb4cde..ba9f94b01451 100644 --- a/perception/traffic_light_ssd_fine_detector/lib/src/trt_ssd.cpp +++ b/perception/traffic_light_ssd_fine_detector/lib/src/trt_ssd.cpp @@ -36,8 +36,7 @@ void Net::load(const std::string & path) file.read(buffer, size); file.close(); if (runtime_) { - engine_ = - unique_ptr(runtime_->deserializeCudaEngine(buffer, size, nullptr)); + engine_ = unique_ptr(runtime_->deserializeCudaEngine(buffer, size)); } delete[] buffer; } @@ -136,7 +135,13 @@ Net::Net( // Build engine std::cout << "Applying optimizations and building TRT CUDA engine..." << std::endl; - engine_ = unique_ptr(builder->buildEngineWithConfig(*network, *config)); + plan_ = unique_ptr(builder->buildSerializedNetwork(*network, *config)); + if (!plan_) { + std::cout << "Fail to create serialized network" << std::endl; + return; + } + engine_ = unique_ptr( + runtime_->deserializeCudaEngine(plan_->data(), plan_->size())); if (!engine_) { std::cout << "Fail to create engine" << std::endl; return; @@ -151,9 +156,8 @@ Net::Net( void Net::save(const std::string & path) { std::cout << "Writing to " << path << "..." << std::endl; - auto serialized = unique_ptr(engine_->serialize()); std::ofstream file(path, std::ios::out | std::ios::binary); - file.write(reinterpret_cast(serialized->data()), serialized->size()); + file.write(reinterpret_cast(plan_->data()), plan_->size()); } void Net::infer(std::vector & buffers, const int batch_size) From 8c0cc86273c299021f493c231b124f2318c6ba33 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Tue, 10 May 2022 17:39:28 +0900 Subject: [PATCH 14/55] fix(avoidance_module): ignore object instead of creating zero shift (#731) * fix: ignore object instead of creating zero shift instead of creating zero shift point, the object will be ignored. no behavior changes should be observed. Signed-off-by: Muhammad Zulfaqar Azmi * refactor: sync continue with upstream Signed-off-by: Muhammad Zulfaqar Azmi * fix: fix debug message for insufficient lateral margin Signed-off-by: Muhammad Zulfaqar Azmi --- .../avoidance/avoidance_module.cpp | 19 +++++++------------ 1 file changed, 7 insertions(+), 12 deletions(-) diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp index 876e5fc3112c..2923996ca869 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp @@ -490,24 +490,19 @@ AvoidPointArray AvoidanceModule::calcRawShiftPointsFromObjects( avoidance_debug_msg.max_shift_length = max_allowable_lateral_distance; if (!(o.to_road_shoulder_distance > max_allowable_lateral_distance)) { - avoidance_debug_msg.allow_avoidance = false; - avoidance_debug_msg.failed_reason = AvoidanceDebugFactor::INSUFFICIENT_LATERAL_MARGIN; + avoidance_debug_array_false_and_push_back(AvoidanceDebugFactor::INSUFFICIENT_LATERAL_MARGIN); + continue; } const auto max_shift_length = o.to_road_shoulder_distance - road_shoulder_safety_margin - 0.5 * vehicle_width; - const auto max_left_shift_limit = [&o, &max_allowable_lateral_distance, &max_shift_length, - this]() noexcept { - const auto left_shift_constraint = std::min(getLeftShiftBound(), max_shift_length); - return (o.to_road_shoulder_distance > max_allowable_lateral_distance) ? left_shift_constraint - : 0.0; + + const auto max_left_shift_limit = [&max_shift_length, this]() noexcept { + return std::min(getLeftShiftBound(), max_shift_length); }; - const auto max_right_shift_limit = [&o, &max_allowable_lateral_distance, &max_shift_length, - this]() noexcept { - const auto right_shift_constraint = std::max(getRightShiftBound(), -max_shift_length); - return (o.to_road_shoulder_distance > max_allowable_lateral_distance) ? right_shift_constraint - : 0.0; + const auto max_right_shift_limit = [&max_shift_length, this]() noexcept { + return std::max(getRightShiftBound(), -max_shift_length); }; const auto shift_length = isOnRight(o) From 667fb38f45474a65a8fab0c9433c7813d8fc1b2a Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Tue, 10 May 2022 18:33:56 +0900 Subject: [PATCH 15/55] fix(motion_velocity_smoother): curve deceleration not working with a specific parameter set (#738) Signed-off-by: Takamasa Horibe --- .../motion_velocity_smoother/src/smoother/smoother_base.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/motion_velocity_smoother/src/smoother/smoother_base.cpp b/planning/motion_velocity_smoother/src/smoother/smoother_base.cpp index 2ecf683fd302..31c6420a6787 100644 --- a/planning/motion_velocity_smoother/src/smoother/smoother_base.cpp +++ b/planning/motion_velocity_smoother/src/smoother/smoother_base.cpp @@ -105,7 +105,7 @@ boost::optional SmootherBase::applyLateralAccelerationFilter( for (size_t i = 0; i < output->size(); ++i) { double curvature = 0.0; const size_t start = i > after_decel_index ? i - after_decel_index : 0; - const size_t end = std::min(output->size(), i + before_decel_index); + const size_t end = std::min(output->size(), i + before_decel_index + 1); for (size_t j = start; j < end; ++j) { curvature = std::max(curvature, std::fabs(curvature_v->at(j))); } From f8a136c7e38a41a5d21c71022d8b5fa7750a4b57 Mon Sep 17 00:00:00 2001 From: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> Date: Tue, 10 May 2022 21:29:41 +0900 Subject: [PATCH 16/55] test(autoware_testing): fix smoke_test (#479) * fix(autoware_testing): fix smoke_test Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> * restore smoke_test for trajectory_follower_nodes Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> * add support multiple parameter files Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> * ci(pre-commit): autofix * minor fix Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../autoware_testing/smoke_test.py | 39 +++++++++++++------ .../cmake/add_smoke_test.cmake | 10 ++--- .../trajectory_follower_nodes/CMakeLists.txt | 14 +++++-- 3 files changed, 42 insertions(+), 21 deletions(-) diff --git a/common/autoware_testing/autoware_testing/smoke_test.py b/common/autoware_testing/autoware_testing/smoke_test.py index 275386126912..8c361474034a 100644 --- a/common/autoware_testing/autoware_testing/smoke_test.py +++ b/common/autoware_testing/autoware_testing/smoke_test.py @@ -16,6 +16,7 @@ import os import shlex +import time import unittest from ament_index_python import get_package_share_directory @@ -26,21 +27,24 @@ from launch_ros.actions import Node import launch_testing import pytest +import rclpy def resolve_node(context, *args, **kwargs): + parameters = [ + os.path.join( + get_package_share_directory(LaunchConfiguration("arg_package").perform(context)), + "param", + file_name, + ) + for file_name in shlex.split(LaunchConfiguration("arg_param_filenames").perform(context)) + ] smoke_test_node = Node( package=LaunchConfiguration("arg_package"), executable=LaunchConfiguration("arg_package_exe"), namespace="test", - parameters=[ - os.path.join( - get_package_share_directory(LaunchConfiguration("arg_package").perform(context)), - "param", - LaunchConfiguration("arg_param_filename").perform(context), - ) - ], + parameters=parameters, arguments=shlex.split(LaunchConfiguration("arg_executable_arguments").perform(context)), ) return [smoke_test_node] @@ -55,8 +59,8 @@ def generate_test_description(): arg_package_exe = DeclareLaunchArgument( "arg_package_exe", default_value=["default"], description="Tested executable" ) - arg_param_filename = DeclareLaunchArgument( - "arg_param_filename", default_value=["test.param.yaml"], description="Test param file" + arg_param_filenames = DeclareLaunchArgument( + "arg_param_filenames", default_value=["test.param.yaml"], description="Test param file" ) arg_executable_arguments = DeclareLaunchArgument( "arg_executable_arguments", default_value=[""], description="Tested executable arguments" @@ -66,7 +70,7 @@ def generate_test_description(): [ arg_package, arg_package_exe, - arg_param_filename, + arg_param_filenames, arg_executable_arguments, OpaqueFunction(function=resolve_node), launch_testing.actions.ReadyToTest(), @@ -74,8 +78,19 @@ def generate_test_description(): ) +class DummyTest(unittest.TestCase): + def test_wait_for_node_ready(self): + """Waiting for the node is ready.""" + rclpy.init() + test_node = rclpy.create_node("test_node") + while len(test_node.get_node_names()) == 0: + time.sleep(0.1) + print("waiting for Node to be ready") + rclpy.shutdown() + + @launch_testing.post_shutdown_test() class TestProcessOutput(unittest.TestCase): def test_exit_code(self, proc_output, proc_info): - # Check that process exits with code -15 code: termination request, sent to the program - launch_testing.asserts.assertExitCodes(proc_info, [-15]) + # Check that process exits with code 0 + launch_testing.asserts.assertExitCodes(proc_info) diff --git a/common/autoware_testing/cmake/add_smoke_test.cmake b/common/autoware_testing/cmake/add_smoke_test.cmake index 2998db4960de..ee2cb0f06e78 100644 --- a/common/autoware_testing/cmake/add_smoke_test.cmake +++ b/common/autoware_testing/cmake/add_smoke_test.cmake @@ -19,18 +19,18 @@ # :type package_name: string # :param package_exec: package executable to run during smoke test # :type executable_name: string -# :param PARAM_FILENAME: yaml filename containing test parameters -# :type PARAM_FILENAME: string +# :param PARAM_FILENAMES: yaml filenames containing test parameters +# :type PARAM_FILENAMES: string # :param EXECUTABLE_ARGUMENTS: arguments passed to tested executable # :type EXECUTABLE_ARGUMENTS: string function(add_smoke_test package_name executable_name) - cmake_parse_arguments(PARSE_ARGV 2 smoke_test "" "PARAM_FILENAME;EXECUTABLE_ARGUMENTS" "") + cmake_parse_arguments(PARSE_ARGV 2 smoke_test "" "PARAM_FILENAMES;EXECUTABLE_ARGUMENTS" "") set(ARGUMENTS "arg_package:=${package_name}" "arg_package_exe:=${executable_name}") - if(smoke_test_PARAM_FILENAME) - list(APPEND ARGUMENTS "arg_param_filename:=${smoke_test_PARAM_FILENAME}") + if(smoke_test_PARAM_FILENAMES) + list(APPEND ARGUMENTS "arg_param_filenames:=${smoke_test_PARAM_FILENAMES}") endif() if(smoke_test_EXECUTABLE_ARGUMENTS) diff --git a/control/trajectory_follower_nodes/CMakeLists.txt b/control/trajectory_follower_nodes/CMakeLists.txt index 7996ac071310..fa005c1c0bfd 100644 --- a/control/trajectory_follower_nodes/CMakeLists.txt +++ b/control/trajectory_follower_nodes/CMakeLists.txt @@ -57,10 +57,16 @@ if(BUILD_TESTING) ament_target_dependencies(${TRAJECTORY_FOLLOWER_NODES_TEST} fake_test_node) target_link_libraries(${TRAJECTORY_FOLLOWER_NODES_TEST} ${LATLON_MUXER_NODE} ${LATERAL_CONTROLLER_NODE} ${LONGITUDINAL_CONTROLLER_NODE}) - #find_package(autoware_testing REQUIRED) - #add_smoke_test(${PROJECT_NAME} ${LATLON_MUXER_NODE}_exe PARAM_FILENAME latlon_muxer_defaults.param.yaml) - #add_smoke_test(${PROJECT_NAME} ${LATERAL_CONTROLLER_NODE}_exe PARAM_FILENAME lateral_controller_defaults.param.yaml) - #add_smoke_test(${PROJECT_NAME} ${LONGITUDINAL_CONTROLLER_NODE}_exe PARAM_FILENAME longitudinal_controller_defaults.param.yaml) + find_package(autoware_testing REQUIRED) + add_smoke_test(${PROJECT_NAME} ${LATLON_MUXER_NODE}_exe + PARAM_FILENAMES "latlon_muxer_defaults.param.yaml" + ) + add_smoke_test(${PROJECT_NAME} ${LATERAL_CONTROLLER_NODE}_exe + PARAM_FILENAMES "lateral_controller_defaults.param.yaml test_vehicle_info.param.yaml" + ) + add_smoke_test(${PROJECT_NAME} ${LONGITUDINAL_CONTROLLER_NODE}_exe + PARAM_FILENAMES "longitudinal_controller_defaults.param.yaml test_vehicle_info.param.yaml" + ) endif() ament_auto_package( From 7bdd7a83ecb971575abd3a869a8988223fd911da Mon Sep 17 00:00:00 2001 From: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Date: Wed, 11 May 2022 10:22:56 +0900 Subject: [PATCH 17/55] feat(rviz_plugins): add velocity limit to autoware state panel (#879) * feat(rviz_plugins): add velocity limit to autoware state panel Signed-off-by: tanaka3 * chore(rviz_plugin): change ms to kmh Signed-off-by: tanaka3 --- common/tier4_state_rviz_plugin/package.xml | 1 + .../src/autoware_state_panel.cpp | 23 +++++++++++++++++++ .../src/autoware_state_panel.hpp | 7 ++++++ 3 files changed, 31 insertions(+) diff --git a/common/tier4_state_rviz_plugin/package.xml b/common/tier4_state_rviz_plugin/package.xml index 2afbe9c315f7..74f7a7418815 100644 --- a/common/tier4_state_rviz_plugin/package.xml +++ b/common/tier4_state_rviz_plugin/package.xml @@ -21,6 +21,7 @@ rviz_common tier4_control_msgs tier4_external_api_msgs + tier4_planning_msgs ament_lint_auto autoware_lint_common diff --git a/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp b/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp index 78681106b3d6..825e06dac1cd 100644 --- a/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp +++ b/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp @@ -80,13 +80,26 @@ AutowareStatePanel::AutowareStatePanel(QWidget * parent) : rviz_common::Panel(pa engage_button_ptr_ = new QPushButton("Engage"); connect(engage_button_ptr_, SIGNAL(clicked()), SLOT(onClickAutowareEngage())); + velocity_limit_button_ptr_ = new QPushButton("Send Velocity Limit"); + pub_velocity_limit_input_ = new QSpinBox(); + pub_velocity_limit_input_->setRange(-100.0, 100.0); + pub_velocity_limit_input_->setValue(0.0); + pub_velocity_limit_input_->setSingleStep(5.0); + connect(velocity_limit_button_ptr_, SIGNAL(clicked()), this, SLOT(onClickVelocityLimit())); + auto * v_layout = new QVBoxLayout; + auto * velocity_limit_layout = new QHBoxLayout(); v_layout->addLayout(gate_layout); v_layout->addLayout(selector_layout); v_layout->addLayout(state_layout); v_layout->addLayout(gear_layout); v_layout->addLayout(engage_status_layout); v_layout->addWidget(engage_button_ptr_); + v_layout->addLayout(engage_status_layout); + velocity_limit_layout->addWidget(velocity_limit_button_ptr_); + velocity_limit_layout->addWidget(pub_velocity_limit_input_); + velocity_limit_layout->addWidget(new QLabel(" [km/h]")); + v_layout->addLayout(velocity_limit_layout); setLayout(v_layout); } @@ -114,6 +127,9 @@ void AutowareStatePanel::onInitialize() client_engage_ = raw_node_->create_client( "/api/autoware/set/engage", rmw_qos_profile_services_default); + + pub_velocity_limit_ = raw_node_->create_publisher( + "/planning/scenario_planning/max_velocity_default", rclcpp::QoS(1)); } void AutowareStatePanel::onGateMode(const tier4_control_msgs::msg::GateMode::ConstSharedPtr msg) @@ -215,6 +231,13 @@ void AutowareStatePanel::onEngageStatus( engage_status_label_ptr_->setText(QString::fromStdString(Bool2String(current_engage_))); } +void AutowareStatePanel::onClickVelocityLimit() +{ + auto velocity_limit = std::make_shared(); + velocity_limit->max_velocity = pub_velocity_limit_input_->value() / 3.6; + pub_velocity_limit_->publish(*velocity_limit); +} + void AutowareStatePanel::onClickAutowareEngage() { auto req = std::make_shared(); diff --git a/common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp b/common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp index 45cd290e5f4a..97c559bdfb3d 100644 --- a/common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp +++ b/common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp @@ -19,6 +19,7 @@ #include #include +#include #include #include @@ -28,6 +29,7 @@ #include #include #include +#include namespace rviz_plugins { @@ -41,6 +43,7 @@ class AutowareStatePanel : public rviz_common::Panel public Q_SLOTS: void onClickAutowareEngage(); + void onClickVelocityLimit(); protected: void onGateMode(const tier4_control_msgs::msg::GateMode::ConstSharedPtr msg); @@ -61,12 +64,16 @@ public Q_SLOTS: rclcpp::Client::SharedPtr client_engage_; + rclcpp::Publisher::SharedPtr pub_velocity_limit_; + QLabel * gate_mode_label_ptr_; QLabel * selector_mode_label_ptr_; QLabel * autoware_state_label_ptr_; QLabel * gear_label_ptr_; QLabel * engage_status_label_ptr_; QPushButton * engage_button_ptr_; + QPushButton * velocity_limit_button_ptr_; + QSpinBox * pub_velocity_limit_input_; bool current_engage_; }; From c00e120cfe627c9f2fdeddaf5e6aea271e44e3f0 Mon Sep 17 00:00:00 2001 From: Hirokazu Ishida <38597814+HiroIshida@users.noreply.github.com> Date: Wed, 11 May 2022 11:00:51 +0900 Subject: [PATCH 18/55] fix(dummy_perception_publisher): publish multiple layers of pointcloud (#882) * fix: single -> multiple layers pointcloud Signed-off-by: Hirokazu Ishida * refactor: share common among different pcloud creators Signed-off-by: Hirokazu Ishida --- .../src/pointcloud_creator.cpp | 56 ++++++++++++++----- 1 file changed, 41 insertions(+), 15 deletions(-) diff --git a/simulator/dummy_perception_publisher/src/pointcloud_creator.cpp b/simulator/dummy_perception_publisher/src/pointcloud_creator.cpp index 6c964625a3e6..d55c42a0c28b 100644 --- a/simulator/dummy_perception_publisher/src/pointcloud_creator.cpp +++ b/simulator/dummy_perception_publisher/src/pointcloud_creator.cpp @@ -25,6 +25,18 @@ #include #include +namespace +{ + +static constexpr double epsilon = 0.001; +static constexpr double step = 0.05; +static constexpr double vertical_theta_step = (1.0 / 180.0) * M_PI; +static constexpr double vertical_min_theta = (-15.0 / 180.0) * M_PI; +static constexpr double vertical_max_theta = (15.0 / 180.0) * M_PI; +static constexpr double horizontal_theta_step = (0.1 / 180.0) * M_PI; +static constexpr double horizontal_min_theta = (-180.0 / 180.0) * M_PI; +static constexpr double horizontal_max_theta = (180.0 / 180.0) * M_PI; + pcl::PointXYZ getPointWrtBaseLink( const tf2::Transform & tf_base_link2moved_object, double x, double y, double z) { @@ -32,6 +44,8 @@ pcl::PointXYZ getPointWrtBaseLink( return pcl::PointXYZ(p_wrt_base.x(), p_wrt_base.y(), p_wrt_base.z()); } +} // namespace + void ObjectCentricPointCloudCreator::create_object_pointcloud( const ObjectInfo & obj_info, const tf2::Transform & tf_base_link2map, std::mt19937 & random_generator, pcl::PointCloud::Ptr pointcloud) const @@ -39,14 +53,6 @@ void ObjectCentricPointCloudCreator::create_object_pointcloud( std::normal_distribution<> x_random(0.0, obj_info.std_dev_x); std::normal_distribution<> y_random(0.0, obj_info.std_dev_y); std::normal_distribution<> z_random(0.0, obj_info.std_dev_z); - const double epsilon = 0.001; - const double step = 0.05; - const double vertical_theta_step = (1.0 / 180.0) * M_PI; - const double vertical_min_theta = (-15.0 / 180.0) * M_PI; - const double vertical_max_theta = (15.0 / 180.0) * M_PI; - const double horizontal_theta_step = (0.1 / 180.0) * M_PI; - const double horizontal_min_theta = (-180.0 / 180.0) * M_PI; - const double horizontal_max_theta = (180.0 / 180.0) * M_PI; const auto tf_base_link2moved_object = tf_base_link2map * obj_info.tf_map2moved_object; @@ -206,7 +212,18 @@ std::vector::Ptr> EgoCentricPointCloudCreator::cr pointclouds.at(i) = (pcl::PointCloud::Ptr(new pcl::PointCloud)); } - const double horizontal_theta_step = 0.25 * M_PI / 180.0; + std::vector min_zs(obj_infos.size()); + std::vector max_zs(obj_infos.size()); + + for (size_t idx = 0; idx < obj_infos.size(); ++idx) { + const auto & obj_info = obj_infos.at(idx); + const auto tf_base_link2moved_object = tf_base_link2map * obj_info.tf_map2moved_object; + const double min_z = -1.0 * (obj_info.height / 2.0) + tf_base_link2moved_object.getOrigin().z(); + const double max_z = 1.0 * (obj_info.height / 2.0) + tf_base_link2moved_object.getOrigin().z(); + min_zs.at(idx) = min_z; + max_zs.at(idx) = max_z; + } + double angle = 0.0; const auto n_scan = static_cast(std::floor(2 * M_PI / horizontal_theta_step)); for (size_t i = 0; i < n_scan; ++i) { @@ -217,13 +234,22 @@ std::vector::Ptr> EgoCentricPointCloudCreator::cr const auto x_hit = dist * cos(angle); const auto y_hit = dist * sin(angle); const auto idx_hit = composite_sdf.nearest_sdf_index(x_hit, y_hit); + const auto obj_info_here = obj_infos.at(idx_hit); + const auto min_z_here = min_zs.at(idx_hit); + const auto max_z_here = max_zs.at(idx_hit); + std::normal_distribution<> x_random(0.0, obj_info_here.std_dev_x); + std::normal_distribution<> y_random(0.0, obj_info_here.std_dev_y); + std::normal_distribution<> z_random(0.0, obj_info_here.std_dev_z); - std::normal_distribution<> x_random(0.0, obj_infos.at(idx_hit).std_dev_x); - std::normal_distribution<> y_random(0.0, obj_infos.at(idx_hit).std_dev_y); - std::normal_distribution<> z_random(0.0, obj_infos.at(idx_hit).std_dev_z); - pointclouds.at(idx_hit)->push_back(pcl::PointXYZ( - x_hit + x_random(random_generator), y_hit + y_random(random_generator), - z_random(random_generator))); + for (double vertical_theta = vertical_min_theta; + vertical_theta <= vertical_max_theta + epsilon; vertical_theta += vertical_theta_step) { + const double z = dist * std::tan(vertical_theta); + if (min_z_here <= z && z <= max_z_here + epsilon) { + pointclouds.at(idx_hit)->push_back(pcl::PointXYZ( + x_hit + x_random(random_generator), y_hit + y_random(random_generator), + z + z_random(random_generator))); + } + } } } From 344111e54143dd36469391d2e3ed3180dc0b7a03 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 11 May 2022 12:56:26 +0900 Subject: [PATCH 19/55] feat(vehicle_info_util): add max_steer_angle (#740) * feat(vehicle_info_util): add max_steer_angle Signed-off-by: Takayuki Murooka * applied pre-commit Signed-off-by: Takayuki Murooka * Added max_steer_angle in test config Signed-off-by: Takayuki Murooka Co-authored-by: Tomoya Kimura --- .../param/test_vehicle_info.param.yaml | 1 + .../param/vehicle_characteristics.param.yaml | 1 + .../test/test_simple_planning_simulator.cpp | 1 + vehicle/vehicle_info_util/config/vehicle_info.param.yaml | 1 + .../include/vehicle_info_util/vehicle_info.hpp | 5 ++++- vehicle/vehicle_info_util/src/vehicle_info_util.cpp | 4 +++- 6 files changed, 11 insertions(+), 2 deletions(-) diff --git a/control/trajectory_follower_nodes/param/test_vehicle_info.param.yaml b/control/trajectory_follower_nodes/param/test_vehicle_info.param.yaml index b1279b50ef04..8941b92b4e78 100644 --- a/control/trajectory_follower_nodes/param/test_vehicle_info.param.yaml +++ b/control/trajectory_follower_nodes/param/test_vehicle_info.param.yaml @@ -9,3 +9,4 @@ left_overhang: 0.1 # between left wheel center and vehicle left right_overhang: 0.1 # between right wheel center and vehicle right vehicle_height: 2.5 + max_steer_angle: 0.70 # [rad] diff --git a/simulator/simple_planning_simulator/param/vehicle_characteristics.param.yaml b/simulator/simple_planning_simulator/param/vehicle_characteristics.param.yaml index 12b6efa79d1c..ef594927dac4 100644 --- a/simulator/simple_planning_simulator/param/vehicle_characteristics.param.yaml +++ b/simulator/simple_planning_simulator/param/vehicle_characteristics.param.yaml @@ -10,3 +10,4 @@ width_m: 2.0 front_overhang_m: 0.5 rear_overhang_m: 0.5 + max_steer_angle: 0.70 # [rad] diff --git a/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp b/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp index d983aeed4d8c..fea6cd16db9d 100644 --- a/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp +++ b/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp @@ -190,6 +190,7 @@ void declareVehicleInfoParams(rclcpp::NodeOptions & node_options) node_options.append_parameter_override("left_overhang", 0.5); node_options.append_parameter_override("right_overhang", 0.5); node_options.append_parameter_override("vehicle_height", 1.5); + node_options.append_parameter_override("max_steer_angle", 0.7); } // Send a control command and run the simulation. diff --git a/vehicle/vehicle_info_util/config/vehicle_info.param.yaml b/vehicle/vehicle_info_util/config/vehicle_info.param.yaml index b1279b50ef04..8941b92b4e78 100644 --- a/vehicle/vehicle_info_util/config/vehicle_info.param.yaml +++ b/vehicle/vehicle_info_util/config/vehicle_info.param.yaml @@ -9,3 +9,4 @@ left_overhang: 0.1 # between left wheel center and vehicle left right_overhang: 0.1 # between right wheel center and vehicle right vehicle_height: 2.5 + max_steer_angle: 0.70 # [rad] diff --git a/vehicle/vehicle_info_util/include/vehicle_info_util/vehicle_info.hpp b/vehicle/vehicle_info_util/include/vehicle_info_util/vehicle_info.hpp index e7ba44605188..8df6d4cfe04c 100644 --- a/vehicle/vehicle_info_util/include/vehicle_info_util/vehicle_info.hpp +++ b/vehicle/vehicle_info_util/include/vehicle_info_util/vehicle_info.hpp @@ -31,6 +31,7 @@ struct VehicleInfo double left_overhang_m; double right_overhang_m; double vehicle_height_m; + double max_steer_angle_m; // Derived parameters, i.e. calculated from base parameters // The offset values are relative to the base frame origin, which is located @@ -49,7 +50,8 @@ struct VehicleInfo inline VehicleInfo createVehicleInfo( const double wheel_radius_m, const double wheel_width_m, const double wheel_base_m, const double wheel_tread_m, const double front_overhang_m, const double rear_overhang_m, - const double left_overhang_m, const double right_overhang_m, const double vehicle_height_m) + const double left_overhang_m, const double right_overhang_m, const double vehicle_height_m, + const double max_steer_angle_m) { // Calculate derived parameters const double vehicle_length_m_ = front_overhang_m + wheel_base_m + rear_overhang_m; @@ -72,6 +74,7 @@ inline VehicleInfo createVehicleInfo( left_overhang_m, right_overhang_m, vehicle_height_m, + max_steer_angle_m, // Derived parameters vehicle_length_m_, vehicle_width_m_, diff --git a/vehicle/vehicle_info_util/src/vehicle_info_util.cpp b/vehicle/vehicle_info_util/src/vehicle_info_util.cpp index 6cc2d2f27e9c..c295155727e6 100644 --- a/vehicle/vehicle_info_util/src/vehicle_info_util.cpp +++ b/vehicle/vehicle_info_util/src/vehicle_info_util.cpp @@ -49,6 +49,7 @@ VehicleInfoUtil::VehicleInfoUtil(rclcpp::Node & node) vehicle_info_.left_overhang_m = getParameter(node, "left_overhang"); vehicle_info_.right_overhang_m = getParameter(node, "right_overhang"); vehicle_info_.vehicle_height_m = getParameter(node, "vehicle_height"); + vehicle_info_.max_steer_angle_m = getParameter(node, "max_steer_angle"); } VehicleInfo VehicleInfoUtil::getVehicleInfo() @@ -56,7 +57,8 @@ VehicleInfo VehicleInfoUtil::getVehicleInfo() return createVehicleInfo( vehicle_info_.wheel_radius_m, vehicle_info_.wheel_width_m, vehicle_info_.wheel_base_m, vehicle_info_.wheel_tread_m, vehicle_info_.front_overhang_m, vehicle_info_.rear_overhang_m, - vehicle_info_.left_overhang_m, vehicle_info_.right_overhang_m, vehicle_info_.vehicle_height_m); + vehicle_info_.left_overhang_m, vehicle_info_.right_overhang_m, vehicle_info_.vehicle_height_m, + vehicle_info_.max_steer_angle_m); } } // namespace vehicle_info_util From 176d33fc1c4238d999b446d22bdbf98c06a7630c Mon Sep 17 00:00:00 2001 From: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> Date: Wed, 11 May 2022 14:52:58 +0900 Subject: [PATCH 20/55] ci(deploy-docs): remove mdx_unimoji (#883) Signed-off-by: Shumpei Wakabayashi --- mkdocs.yaml | 1 - 1 file changed, 1 deletion(-) diff --git a/mkdocs.yaml b/mkdocs.yaml index 2bd16349b24b..02c3bb42383e 100644 --- a/mkdocs.yaml +++ b/mkdocs.yaml @@ -66,7 +66,6 @@ markdown_extensions: - mdx_math - mdx_truly_sane_lists: nested_indent: 2 - - mdx_unimoji - plantuml_markdown: server: http://www.plantuml.com/plantuml format: svg From bb96ae7b56085a6054ad1ade970bad399faef35a Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Wed, 11 May 2022 06:17:37 +0000 Subject: [PATCH 21/55] chore: sync files (#884) Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .github/workflows/github-release.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/github-release.yaml b/.github/workflows/github-release.yaml index 23508e63bc43..93533b54e1dd 100644 --- a/.github/workflows/github-release.yaml +++ b/.github/workflows/github-release.yaml @@ -54,7 +54,7 @@ jobs: - name: Select verb id: select-verb run: | - has_previous_draft=$(gh release view --json isDraft -q ".isDraft" "${{ steps.set-tag-name.outputs.tag-name }}") + has_previous_draft=$(gh release view --json isDraft -q ".isDraft" "${{ steps.set-tag-name.outputs.tag-name }}") || true verb=create if [ "$has_previous_draft" = "true" ]; then From 7307ce775c46083ae426e4c534caf59f6a2b61bf Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Thu, 12 May 2022 15:45:49 +0900 Subject: [PATCH 22/55] fix(lidar_centerpoint): fix google drive url to avoid 404 (#889) * fix(lidar_centerpoint): fix google drive url to avoid 404 * Update CMakeLists.txt Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> --- perception/lidar_centerpoint/CMakeLists.txt | 4 ++-- perception/tensorrt_yolo/CMakeLists.txt | 6 +++--- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/perception/lidar_centerpoint/CMakeLists.txt b/perception/lidar_centerpoint/CMakeLists.txt index 0cf1f51654bb..4f1557518134 100644 --- a/perception/lidar_centerpoint/CMakeLists.txt +++ b/perception/lidar_centerpoint/CMakeLists.txt @@ -86,13 +86,13 @@ if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL) message(STATUS "File already exists.") else() message(STATUS "File hash changes. Downloading now ...") - execute_process(COMMAND gdown --quiet https://drive.google.com//uc?id=${GFILE_ID} -O ${FILE_PATH}) + execute_process(COMMAND gdown --quiet https://drive.google.com/uc?id=${GFILE_ID} -O ${FILE_PATH}) # file(MD5 ${FILE_PATH} DOWNLOADED_FILE_HASH) # disable to pass ci message(STATUS "Downloaded file hash: ${DOWNLOADED_FILE_HASH}") endif() else() message(STATUS "File doesn't exists. Downloading now ...") - execute_process(COMMAND gdown --quiet https://drive.google.com//uc?id=${GFILE_ID} -O ${FILE_PATH}) + execute_process(COMMAND gdown --quiet https://drive.google.com/uc?id=${GFILE_ID} -O ${FILE_PATH}) # file(MD5 ${FILE_PATH} DOWNLOADED_FILE_HASH) # disable to pass ci message(STATUS "Downloaded file hash: ${DOWNLOADED_FILE_HASH}") endif() diff --git a/perception/tensorrt_yolo/CMakeLists.txt b/perception/tensorrt_yolo/CMakeLists.txt index a50af6bfa9ab..e8ac60c30ed3 100755 --- a/perception/tensorrt_yolo/CMakeLists.txt +++ b/perception/tensorrt_yolo/CMakeLists.txt @@ -93,7 +93,7 @@ message(STATUS "Checking and downloading yolov4.onnx") if(NOT EXISTS "${FILE}") message(STATUS "... file does not exist. Downloading now ...") execute_process( - COMMAND gdown "https://drive.google.com//uc?id=1vkNmSwcIpTkJ_-BrKhxtit0PBJeJYTVX" -O ${PATH}/yolov4.onnx + COMMAND gdown "https://drive.google.com/uc?id=1vkNmSwcIpTkJ_-BrKhxtit0PBJeJYTVX" -O ${PATH}/yolov4.onnx ERROR_QUIET ) endif() @@ -115,7 +115,7 @@ message(STATUS "Checking and downloading yolov5s.onnx") if(NOT EXISTS "${FILE}") message(STATUS "... file does not exist. Downloading now ...") execute_process( - COMMAND gdown "https://drive.google.com//uc?id=1CF21nQWigwCPTr5psQZXg6cBQIOYKbad" -O ${PATH}/yolov5s.onnx + COMMAND gdown "https://drive.google.com/uc?id=1CF21nQWigwCPTr5psQZXg6cBQIOYKbad" -O ${PATH}/yolov5s.onnx ERROR_QUIET ) endif() @@ -126,7 +126,7 @@ message(STATUS "Checking and downloading yolov5m.onnx") if(NOT EXISTS "${FILE}") message(STATUS "... file does not exist. Downloading now ...") execute_process( - COMMAND gdown "https://drive.google.com//uc?id=1a1h50KJH6slwmjKZpPlS-errukF-BrgG" -O ${PATH}/yolov5m.onnx + COMMAND gdown "https://drive.google.com/uc?id=1a1h50KJH6slwmjKZpPlS-errukF-BrgG" -O ${PATH}/yolov5m.onnx ERROR_QUIET ) endif() From 90f8d8c214de752ad402afea23f2968e987d7087 Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Thu, 12 May 2022 21:01:04 +0900 Subject: [PATCH 23/55] chore: fix typos (#886) Signed-off-by: badai-nguyen --- .../src/blockage_diag/blockage_diag_nodelet.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp b/sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp index 3f3665bf0653..821e2de462bd 100644 --- a/sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp @@ -42,7 +42,7 @@ BlockageDiagComponent::BlockageDiagComponent(const rclcpp::NodeOptions & options updater_.setHardwareID("blockage_diag"); updater_.add( - std::string(this->get_namespace()) + ": ground_blockage_validation", this, + std::string(this->get_namespace()) + ": blockage_validation", this, &BlockageDiagComponent::onBlockageChecker); updater_.setPeriod(0.1); @@ -93,9 +93,9 @@ void BlockageDiagComponent::onBlockageChecker(DiagnosticStatusWrapper & stat) if (level == DiagnosticStatus::OK) { msg = "OK"; } else if (level == DiagnosticStatus::WARN) { - msg = "WARNING: LiDAR ground blockage"; + msg = "WARNING: LiDAR blockage"; } else if (level == DiagnosticStatus::ERROR) { - msg = "ERROR: LiDAR ground blockage"; + msg = "ERROR: LiDAR blockage"; } else if (level == DiagnosticStatus::STALE) { msg = "STALE"; } From 06fe0e72bd34f488ef8161027f915797c8e31822 Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Fri, 13 May 2022 11:22:08 +0900 Subject: [PATCH 24/55] feat(state_rviz_plugin): add GateMode and PathChangeApproval Button (#894) * feat(state_rviz_plugin): add GateMode and PathChangeApproval Button * ci(pre-commit): autofix Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../src/autoware_state_panel.cpp | 40 +++++++++++++++++++ .../src/autoware_state_panel.hpp | 7 ++++ 2 files changed, 47 insertions(+) diff --git a/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp b/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp index 825e06dac1cd..33177729e835 100644 --- a/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp +++ b/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp @@ -16,6 +16,7 @@ #include "autoware_state_panel.hpp" +#include #include #include #include @@ -80,6 +81,15 @@ AutowareStatePanel::AutowareStatePanel(QWidget * parent) : rviz_common::Panel(pa engage_button_ptr_ = new QPushButton("Engage"); connect(engage_button_ptr_, SIGNAL(clicked()), SLOT(onClickAutowareEngage())); + // Gate Mode Button + gate_mode_button_ptr_ = new QPushButton("Gate Mode"); + connect(gate_mode_button_ptr_, SIGNAL(clicked()), SLOT(onClickGateMode())); + + // Path Change Approval Button + path_change_approval_button_ptr_ = new QPushButton("Path Change Approval"); + connect(path_change_approval_button_ptr_, SIGNAL(clicked()), SLOT(onClickPathChangeApproval())); + + // Velocity Limit velocity_limit_button_ptr_ = new QPushButton("Send Velocity Limit"); pub_velocity_limit_input_ = new QSpinBox(); pub_velocity_limit_input_->setRange(-100.0, 100.0); @@ -87,7 +97,9 @@ AutowareStatePanel::AutowareStatePanel(QWidget * parent) : rviz_common::Panel(pa pub_velocity_limit_input_->setSingleStep(5.0); connect(velocity_limit_button_ptr_, SIGNAL(clicked()), this, SLOT(onClickVelocityLimit())); + // Layout auto * v_layout = new QVBoxLayout; + auto * gate_mode_path_change_approval_layout = new QHBoxLayout; auto * velocity_limit_layout = new QHBoxLayout(); v_layout->addLayout(gate_layout); v_layout->addLayout(selector_layout); @@ -96,6 +108,9 @@ AutowareStatePanel::AutowareStatePanel(QWidget * parent) : rviz_common::Panel(pa v_layout->addLayout(engage_status_layout); v_layout->addWidget(engage_button_ptr_); v_layout->addLayout(engage_status_layout); + gate_mode_path_change_approval_layout->addWidget(gate_mode_button_ptr_); + gate_mode_path_change_approval_layout->addWidget(path_change_approval_button_ptr_); + v_layout->addLayout(gate_mode_path_change_approval_layout); velocity_limit_layout->addWidget(velocity_limit_button_ptr_); velocity_limit_layout->addWidget(pub_velocity_limit_input_); velocity_limit_layout->addWidget(new QLabel(" [km/h]")); @@ -130,6 +145,14 @@ void AutowareStatePanel::onInitialize() pub_velocity_limit_ = raw_node_->create_publisher( "/planning/scenario_planning/max_velocity_default", rclcpp::QoS(1)); + + pub_gate_mode_ = raw_node_->create_publisher( + "/control/gate_mode_cmd", rclcpp::QoS(1)); + + pub_path_change_approval_ = raw_node_->create_publisher( + "/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/" + "path_change_approval", + rclcpp::QoS(1)); } void AutowareStatePanel::onGateMode(const tier4_control_msgs::msg::GateMode::ConstSharedPtr msg) @@ -258,6 +281,23 @@ void AutowareStatePanel::onClickAutowareEngage() }); } +void AutowareStatePanel::onClickGateMode() +{ + const auto data = gate_mode_label_ptr_->text().toStdString() == "AUTO" + ? tier4_control_msgs::msg::GateMode::EXTERNAL + : tier4_control_msgs::msg::GateMode::AUTO; + RCLCPP_INFO(raw_node_->get_logger(), "data : %d", data); + pub_gate_mode_->publish( + tier4_control_msgs::build().data(data)); +} + +void AutowareStatePanel::onClickPathChangeApproval() +{ + pub_path_change_approval_->publish( + tier4_planning_msgs::build() + .stamp(raw_node_->now()) + .approval(true)); +} } // namespace rviz_plugins #include diff --git a/common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp b/common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp index 97c559bdfb3d..a53bea54452f 100644 --- a/common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp +++ b/common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp @@ -29,6 +29,7 @@ #include #include #include +#include #include namespace rviz_plugins @@ -44,6 +45,8 @@ class AutowareStatePanel : public rviz_common::Panel public Q_SLOTS: void onClickAutowareEngage(); void onClickVelocityLimit(); + void onClickGateMode(); + void onClickPathChangeApproval(); protected: void onGateMode(const tier4_control_msgs::msg::GateMode::ConstSharedPtr msg); @@ -65,6 +68,8 @@ public Q_SLOTS: rclcpp::Client::SharedPtr client_engage_; rclcpp::Publisher::SharedPtr pub_velocity_limit_; + rclcpp::Publisher::SharedPtr pub_gate_mode_; + rclcpp::Publisher::SharedPtr pub_path_change_approval_; QLabel * gate_mode_label_ptr_; QLabel * selector_mode_label_ptr_; @@ -73,6 +78,8 @@ public Q_SLOTS: QLabel * engage_status_label_ptr_; QPushButton * engage_button_ptr_; QPushButton * velocity_limit_button_ptr_; + QPushButton * gate_mode_button_ptr_; + QPushButton * path_change_approval_button_ptr_; QSpinBox * pub_velocity_limit_input_; bool current_engage_; From 3bcb248ef312f73bf5f489e2a742be0472b8b842 Mon Sep 17 00:00:00 2001 From: Takeshi Ishita Date: Fri, 13 May 2022 13:50:09 +0900 Subject: [PATCH 25/55] feat(map_tf_generator): accelerate the 'viewer' coordinate calculation (#890) * add random point sampling function to quickly calculate the 'viewer' coordinate Signed-off-by: IshitaTakeshi Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> --- map/map_tf_generator/CMakeLists.txt | 17 ++++++++ .../map_tf_generator/uniform_random.hpp | 33 ++++++++++++++ map/map_tf_generator/package.xml | 1 + .../src/map_tf_generator_node.cpp | 18 +++++--- .../test/test_uniform_random.cpp | 43 +++++++++++++++++++ 5 files changed, 107 insertions(+), 5 deletions(-) create mode 100644 map/map_tf_generator/include/map_tf_generator/uniform_random.hpp create mode 100644 map/map_tf_generator/test/test_uniform_random.cpp diff --git a/map/map_tf_generator/CMakeLists.txt b/map/map_tf_generator/CMakeLists.txt index 1170dfef0047..506f763c4bb3 100644 --- a/map/map_tf_generator/CMakeLists.txt +++ b/map/map_tf_generator/CMakeLists.txt @@ -16,6 +16,23 @@ rclcpp_components_register_node(map_tf_generator_node EXECUTABLE map_tf_generator ) + +if(BUILD_TESTING) + function(add_testcase filepath) + get_filename_component(filename ${filepath} NAME) + string(REGEX REPLACE ".cpp" "" test_name ${filename}) + + ament_add_gmock(${test_name} ${filepath}) + target_include_directories(${test_name} PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}/include) + ament_target_dependencies(${test_name} ${${PROJECT_NAME}_FOUND_BUILD_DEPENDS}) + endfunction() + + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() + + add_testcase(test/test_uniform_random.cpp) +endif() + ament_auto_package(INSTALL_TO_SHARE launch ) diff --git a/map/map_tf_generator/include/map_tf_generator/uniform_random.hpp b/map/map_tf_generator/include/map_tf_generator/uniform_random.hpp new file mode 100644 index 000000000000..345703a19bc0 --- /dev/null +++ b/map/map_tf_generator/include/map_tf_generator/uniform_random.hpp @@ -0,0 +1,33 @@ +// Copyright 2022 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef MAP_TF_GENERATOR__UNIFORM_RANDOM_HPP_ +#define MAP_TF_GENERATOR__UNIFORM_RANDOM_HPP_ + +#include +#include + +std::vector UniformRandom(const size_t max_exclusive, const size_t n) +{ + std::default_random_engine generator; + std::uniform_int_distribution distribution(0, max_exclusive - 1); + + std::vector v(n); + for (size_t i = 0; i < n; i++) { + v[i] = distribution(generator); + } + return v; +} + +#endif // MAP_TF_GENERATOR__UNIFORM_RANDOM_HPP_ diff --git a/map/map_tf_generator/package.xml b/map/map_tf_generator/package.xml index 9aaf14bc5fda..3adcf8069066 100644 --- a/map/map_tf_generator/package.xml +++ b/map/map_tf_generator/package.xml @@ -19,6 +19,7 @@ tf2 tf2_ros + ament_cmake_gmock ament_lint_auto autoware_lint_common diff --git a/map/map_tf_generator/src/map_tf_generator_node.cpp b/map/map_tf_generator/src/map_tf_generator_node.cpp index 378d739ffbef..b99514f18e65 100644 --- a/map/map_tf_generator/src/map_tf_generator_node.cpp +++ b/map/map_tf_generator/src/map_tf_generator_node.cpp @@ -12,6 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include "map_tf_generator/uniform_random.hpp" + #include #include @@ -25,6 +27,8 @@ #include #include +constexpr size_t N_SAMPLES = 20; + class MapTFGeneratorNode : public rclcpp::Node { public: @@ -51,19 +55,23 @@ class MapTFGeneratorNode : public rclcpp::Node void onPointCloud(const sensor_msgs::msg::PointCloud2::ConstSharedPtr clouds_ros) { + // fix random seed to produce the same viewer position every time + // 3939 is just the author's favorite number + srand(3939); + PointCloud clouds; pcl::fromROSMsg(*clouds_ros, clouds); - const unsigned int sum = clouds.points.size(); + const std::vector indices = UniformRandom(clouds.size(), N_SAMPLES); double coordinate[3] = {0, 0, 0}; - for (unsigned int i = 0; i < sum; i++) { + for (const auto i : indices) { coordinate[0] += clouds.points[i].x; coordinate[1] += clouds.points[i].y; coordinate[2] += clouds.points[i].z; } - coordinate[0] = coordinate[0] / sum; - coordinate[1] = coordinate[1] / sum; - coordinate[2] = coordinate[2] / sum; + coordinate[0] = coordinate[0] / indices.size(); + coordinate[1] = coordinate[1] / indices.size(); + coordinate[2] = coordinate[2] / indices.size(); geometry_msgs::msg::TransformStamped static_transformStamped; static_transformStamped.header.stamp = this->now(); diff --git a/map/map_tf_generator/test/test_uniform_random.cpp b/map/map_tf_generator/test/test_uniform_random.cpp new file mode 100644 index 000000000000..76ee174a3487 --- /dev/null +++ b/map/map_tf_generator/test/test_uniform_random.cpp @@ -0,0 +1,43 @@ +// Copyright 2022 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "map_tf_generator/uniform_random.hpp" + +#include + +using testing::AllOf; +using testing::Each; +using testing::Ge; +using testing::Lt; + +TEST(UniformRandom, UniformRandom) +{ + { + const std::vector random = UniformRandom(4, 0); + ASSERT_EQ(random.size(), static_cast(0)); + } + + // checks if the returned values are in range of [min, max) + // note that the minimun range is always zero and the max value is exclusive + { + const size_t min_inclusive = 0; + const size_t max_exclusive = 4; + + for (int i = 0; i < 50; i++) { + const std::vector random = UniformRandom(4, 10); + ASSERT_EQ(random.size(), 10U); + ASSERT_THAT(random, Each(AllOf(Ge(min_inclusive), Lt(max_exclusive)))); // in range [0, 4) + } + } +} From e89e06d2067c85656123bcd64dbabf59163ece22 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 13 May 2022 17:45:37 +0900 Subject: [PATCH 26/55] docs(obstacle_stop_planner): update documentation (#880) Signed-off-by: satoshi-ota --- planning/obstacle_stop_planner/README.md | 13 +- .../docs/insert_decel_velocity.drawio.svg | 273 +----------------- .../docs/insert_velocity1.drawio.svg | 4 + .../docs/insert_velocity2.drawio.svg | 4 + 4 files changed, 22 insertions(+), 272 deletions(-) create mode 100644 planning/obstacle_stop_planner/docs/insert_velocity1.drawio.svg create mode 100644 planning/obstacle_stop_planner/docs/insert_velocity2.drawio.svg diff --git a/planning/obstacle_stop_planner/README.md b/planning/obstacle_stop_planner/README.md index 95274b6a4829..9c8fc714fb9c 100644 --- a/planning/obstacle_stop_planner/README.md +++ b/planning/obstacle_stop_planner/README.md @@ -11,13 +11,20 @@ - Adaptive Cruise Controller (ACC) - embeds target velocity in trajectory when there is a dynamic point cloud on the trajectory. -When the stop point that has 0 velocity is inserted, the point is inserted in front of the target point cloud by the distance of `baselink to front` + `stop margin`. The `baselink to front` means the distance between `base_link`(center of rear-wheel axis) and front of the car. `stop margin` is determined by the parameters described below. +In order to stop with a `stop margin` from the obstacle exists, the stop point (`v=0`) is inserted at a distance of `baselink to front` + `stop margin` from the obstacle. The `baselink to front` means the distance between `base_link`(center of rear-wheel axis) and front of the car. -![insert_stop_velocity](./docs/insert_velocity.drawio.svg) +If a stop point has already been inserted by other nodes between the obstacle and a position which is `stop margin` meters away from the obstacle, the stop point is inserted at a distance of `baselink to front` + `min behavior stop margin` from the obstacle. + +

+ + +
When the deceleration section is inserted, the start point of the section is inserted in front of the target point cloud by the distance of `baselink to front` + `slow down forward margin`. the end point of the section is inserted behind the target point cloud by the distance of `slow down backward margin` + `baselink to rear`. The `baselink to rear` means the distance between `base_link` and rear of the car. The velocities of points in the deceleration section are modified to the deceleration velocity. `slow down backward margin` and `slow down forward margin` are determined by the parameters described below. -![insert_stop_velocity](./docs/insert_decel_velocity.drawio.svg) +
+ +
## Input topics diff --git a/planning/obstacle_stop_planner/docs/insert_decel_velocity.drawio.svg b/planning/obstacle_stop_planner/docs/insert_decel_velocity.drawio.svg index 80cb8c2ed501..a49853974a2f 100644 --- a/planning/obstacle_stop_planner/docs/insert_decel_velocity.drawio.svg +++ b/planning/obstacle_stop_planner/docs/insert_decel_velocity.drawio.svg @@ -1,269 +1,4 @@ - - - - - - - -
-
-
- -

- - backward - - - margin - -

-
-
-
-
-
- - backward margin - -
-
- - - - - - - - -
-
-
- -

- - - deceleration point - - -

-
-
-
-
-
- - deceleration point - -
-
- - - - - - - - -
-
-
- -

- - - v - - -

-
-
-
-
-
- - v - -
-
- - - - -
-
-
- -

- - - x - - -

-
-
-
-
-
- - x - -
-
- - - - -
-
-
- -

- - - baselink to front - - -

-
-
-
-
-
- - baselink to front - -
-
- - - - - - - - - - -
-
-
- -

- - - output velocity - - -

-
-
-
-
-
- - output velocity - -
-
- - - - - -
-
-
- -

- - - reference velocity - - -

-
-
-
-
-
- - reference velocity - -
-
- - - - - -
-
-
- -

- - forward margin - -

-
-
-
-
-
- - forward margin - -
-
- - - - - - - - - - - - - - - - - - - - -
-
-
- -

- - - baselink to rear - - -

-
-
-
-
-
- - baselink to rear - -
-
-
- - - - - Viewer does not support full SVG 1.1 - - - -
\ No newline at end of file + + + +
Obstacle
Obsta...
velocity
velocity
travel
distance
travel...
baselink to front
baselink to front
slow down forward margin
slow down forward margin
reference velocity
reference velocity
output velocity
output velocity
slow down backward margin
slow down backwa...
baselink to rear
baselink to rear
slow down
velocity
slow down...
Text is not SVG - cannot display
\ No newline at end of file diff --git a/planning/obstacle_stop_planner/docs/insert_velocity1.drawio.svg b/planning/obstacle_stop_planner/docs/insert_velocity1.drawio.svg new file mode 100644 index 000000000000..dd1054e17fb1 --- /dev/null +++ b/planning/obstacle_stop_planner/docs/insert_velocity1.drawio.svg @@ -0,0 +1,4 @@ + + + +
Obstacle
Obsta...
velocity
velocity
baselink to front
baselink to front
stop margin
stop margin
reference velocity
reference velocity
output velocity
output velocity
travel
distance
travel...
Text is not SVG - cannot display
\ No newline at end of file diff --git a/planning/obstacle_stop_planner/docs/insert_velocity2.drawio.svg b/planning/obstacle_stop_planner/docs/insert_velocity2.drawio.svg new file mode 100644 index 000000000000..941668f909b6 --- /dev/null +++ b/planning/obstacle_stop_planner/docs/insert_velocity2.drawio.svg @@ -0,0 +1,4 @@ + + + +
Obstacle
Obsta...
velocity
velocity
baselink to front
baselink to front
min behavior stop margin
min behavior stop margin
reference velocity
reference velocity
output velocity
output velocity
travel
distance
travel...
stop point
(inserted by other nodes)
stop point...
Text is not SVG - cannot display
\ No newline at end of file From 12b7af1f1c79bc07b3d2d76ce70c2db590e866df Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 17 May 2022 07:12:30 +0900 Subject: [PATCH 27/55] docs(tier4_traffic_light_rviz_plugin): update documentation (#905) Signed-off-by: satoshi-ota --- .../images/traffic_light_publish_panel.gif | Bin 416094 -> 552084 bytes 1 file changed, 0 insertions(+), 0 deletions(-) diff --git a/common/tier4_traffic_light_rviz_plugin/images/traffic_light_publish_panel.gif b/common/tier4_traffic_light_rviz_plugin/images/traffic_light_publish_panel.gif index c1063c27ea98291c0af9e1fd6d90f1e3d20b1f9b..23aea952a0fd0d964b81384c2e3691617c055e7e 100644 GIT binary patch literal 552084 zcmW(+cR1Y7^M5->^j?ERIij72AZm0@jdmh>k8nf_iIO0Q?({B*dOAnc=)Lz-qxT*X z;o^Ru-}k?L_L-fTXLn|I%4^lsRV5^?`SAg~KM$V(000317yuvu00{tS0KfnM_J6Yw z2mpfs2nc|L0B8t+fdJV5kwRbq3b}OVEuy7<6j>f_R=rK%#Bo>9nqA*w#7K;J^90b6@02~6q zApsm3z+nI!7Qg`z90Y=cL2w8N4hg}bAvg>KhlSt(7!Cr%!C*K942Oi_&@dbZhQq>e z00IX=;9v+G0)ay!aA*V$gTP@CH~@)*AaO7x4uQlWkvKFGhe6`7NF0F1LC`oD8izpR zkZ2qljl-aESTqj6;2;^>nrPH{yxl`>MRhpUBBA{yUwT&Hk8Ivo-`xwcEpK zPn}msn(B6kDxXI^&~8TWPnQ^!S&TNU{VZ;evBj(N-F$!xbN?$gQ2d+)R5=|r`5i+>;fEG-Rx zl9PM>@AmhvPyOwd?H_R41OpE~;jUg=1rd=D{R|?R>t7256tCBUi8YKlLdj{;tV5Vg z8rMT8ESNYwA&P&P+-W5pq9S8M=ZvAyT1;A0ML8xdMroZXmRu{6YVl~2T;i3Ha-g#s z+aHom_5#VTg&HH(VbptHgTp9p_P(Z4?Cs}g=13hB)K&T(mi1HI9#zes+#CnHDjv%g z3Qx*Y>s(W~S^q(v@5$}Na}IWmJeAQwX#fBim@%k2_oydgeBxe-1O-B38fpkY8KTYN zL+3RKfspRdETFX+S{z8Tx z`l?mP2Uiy|imXj8i{=)5{ddSDB_ZWI+Md}wec0keKcyM6{n%Y{#44XA?FU_vNSykJ z{Y7ospk2|EulrhdioY^u5k;ck)JI)x>Yg;)!sxxPNd)}Y>EP_ajGUlG6ZxShnI*lv zM>P@gf0bzU9KW33ea6+WQ&m5qAqu_};>A1Qwx&CF?54X(1wVs%_^LZ9?Sdo-f_OUL zv(u&iQJrKGfhhPgyM%&3ZsJ6QuY(=AdhdiVX`vgGc=KFJz`#T-6zS#5A!7xi&yasM zLQO<;W+nhag73Hkza3XU^q@PFs9P76xTggue@9LjC9UWA)0OISbk|V$)+;|K*LvA` z1E)=XSMI=FW->iwgl?V{c}p)~w#z@??2%mQQ}1m2YiPdh=BoVtzeAJF#g`oiv(=$& z2rFs)L{Z@+y*p=A%iWy1pMd!K2c@o@X z@)1!=QN+_@@8ykMA_27U^wfpT{0P#m6yffq9NF?T<-B;C;tp})8@JNjNW9sW$Kk8^oR=`+2q7E z_A05?#z*+uF-R};X&QMX=E-ccYo-qxGi05ROo#9YuallMhSIYFGSTQ?**!r*z+%uU zm`)i-a!W_=^{SKNSrRAk(ku3l_)rW)j zGW1{~H+Wn@08$>T^n+MVv6{hP?cr5IwnSV?(l(7Z*}KGHcXT0|KAX&5y!g#%p=aIx zs@Ki47WH=}FU>PwzLuJ+7`v+QGe5NYbTi-k;CHD{+mZeYznS@*ceO2S8SB`7zE(4W zpYPI%tE`IcsKm35jZRPb3}&-l;Xwhj7sVO8pHXUg)5nscpxE|rMfmcsx9ki*uW}I- zsm(F*$yBltU&|EK3;(r!ECZMzH*7Vmuh$T%MI|}~>!vH$v8pdfuDgGA;kh}l#&uoZ zkjm2)l!Sn1m^<*mc}hR$c|p$brHS!|%Np%}E^6&J^WX0->*M|%t9`1&HLBqF?pys~ zOTptH(lZs{QT$F{y0EugsPE{Ob58p0?V29Y6#7iqYz4wdyt+X`J0a%jrLr5WIu~kQ zF8rT;3+c1tg-l5f5LiKdJXXG0)Vm4AxChJBf978mi zLNxb6w3$K;i9(ISLtYw(z{5k$NU$^xio}DDs}zcc1+omc*F9YGhT~_GWky6K+pQ)!NCo3 zG#$i@A?CKZd^xF43;=N7ri2?4n2Ps##XakcN9J9Hj`MXe+YXXOBl(Io^RNwPBq3se z$1v}Uh^a71-nv;qM?gnfK-XSC4RXTjH}P)4zN=>YbXY-|8oSs_(Eq;38mllp_uV z_uK35<_GO@tIyyE)mIaf=*qsCVNw^i#yO|~Q~*raYL!Un(3n*GokZ-qr{lDkRZo0n zb?mMp35XbMtE;{ZH%;Zxx~okPTu2c5n;^`bC?c5{hbPR`NiBir4dU0W%>nVp2fhO^(x&S!kxcG za=%d>>LHQc#KN}2^lgDBBVFhzC+yv4Zs{;-^ta3gF6p+W%pZf9UCdcM#94iRGY2HI z`b)D0-#m&a;hoqweHQF6(&*x{W(dfe4>e}bE@ThxWsfrDEaU!WZ}H`3e!of0$Gq$hYi{baBF74cft(okbFI6fJV+fesbV_3 zVsEKppN!)7&BeZp#r`+NAMck0N|gkgl!W+}gk_Y3H7E7XUN@DMqBBe?bOiGh{ zOH&St`K@WSYM5BoOCvjJqSmRXIZ$HfrTH1C&(>50i=}x|OvN{-N?%$+4(bZuGR`2> zeGZy}3?{P4vNlxNTrH|cs=SW`Rme{}AXQ$sSl)b4UVBqMb-!XpqkO`tVmh*7cBp(| zsA8$Pd<}(~Kd4wVsoe6dTt}5}ELQAGRUQvj9^O=(J5`?YR~`6Pok&&fp{lMls<1az z*CbVV&Q*08rD-Ik-0szcE!8AT)nvET6f8AV(ls=uHFSP844E}dEj9O-YV3zfLz!zI zKB?t2t%dm2@?_TXw$$=3)e7F$vT;xgN!JPA){5Xv>qIl_BwFgEmg;0~>z=cq<)zVz zrf6k9v}z_A)`HepLTlZkby(_khwE5P>mT^l8)eoTx73>~)tlYcTd*`(NjKP-HhjLJ z0y3-c538J8s$7<;T+14?IH+0h%FBJf_wtwf-lF<6zJmp-JxCjaZ@-5OHw2kBx=S~P zl{H30HM-q4z8P*r-ZsP^HYT?;rf4>0_%)_2HN_k@B_7f`NH^P=HW&Cc7iBh=v^1ms z+qT>0O6gKAzdC)>76a!NDb1Gee(2_?mX^boj@y9!ipwmH)_j9=SgX4`U0+bT=VFWgXRf?v~D(;ra^bqi9po6_{`)Xj&(P3}uS zwhn)!leQ0|7`@{eA1_tdEVf(Uv|HWpu<#8~bf+#Ec34Y*t}F7Ak!6w`b&zLukjr#Z zYIQPTJNof!5Z;}vW}Od~JK3?Foc^86%WVvPFJkv1(Tz}2n73Z=~K8#Nmp#g5nuj`EPzBqK(vqDLjmM;!(G zw-9|h*uK4yUYym)u1x=l851IFY@4h*WMS+jVjRXgu75Q4OQz>YaQvEV0#q?JWkdRE zWMs;w+ar2HQBW9fbQ~r)=44W_VcLFnGg77nWp;tyUzue6H6i2Bl^`lUY8a zl|7@xHmq4O&FRuZ5kH|CFsm0ctJQ|mIUY98p0!$;c_>S@$}?vjF!Mtfif=oo9Wb@! z+bkY1E#Q*)>1c$8W!@uuUY~Zz>t9<6$(V0Ncc6B6z$mqhf1jFv;$;@b9o0uwfpKca ze0Ik~$6&Tu$G@`^;7^ZlNB1Sf^yta-{`IE{_2@A^!lcCXAkB;9wHC_R7OMX(BFRVJ zX)k@1?M>3|H6)*G(1sdm5nfe~mj*0VLnj{|)}@)Hz4xzu&xWZgpR!;T77joU%GQn^ zFAI>b49TpBMtxMnEuqGjP;4Blw^4QTF)Ns^!6oyw46`YN(ZNP7syp3T)#afs?5ga@ zT$k2x`x*%m)$%CoNI(DDSpYPAoys7Wz&Tr#>~2{9-OGaBC#@7TntknOaB3ajZ+vw1(I% z^!0&lRe#D#0Q{S38!#W=*OF=1^#`c%s^3xK8*jdCU8L0RG1nQR@)m#ii!vo_7qOgX zMK*5wqeljZ*dZnakXw|`O2@4bZwjgh;%NH^Y$Y71QKWv z17#Lk6-@tTTV;L<+#PUeLtW&d4b{Y^?8K%WvyY%Lzu9U2tR3c4)Oy~Mu8h$BkzEJJ z{u~fGM7tg~R345WP=0r#%)6ugUS0NVeXpJUxRMHQ`r8Y2_5rGO5(6rNe^#{j;>#G^ znK%?slGLcPk?%S8=LvO$;pV5e|EAQRI!{9nC$1@yNHszPEbOhx=$m;-lC zP_uT8dmtA3{Ng_Oxq>!Tm%YpvMJkqDunXd-dx$`zIS;nj7lt=~A*&Q%gt^(Bvi( zFBOOS_qLzOO_}Sudv-H!ZxI7)nm>n=v()1MMoUO;1>KQ~_qr2dFy2nn-e|RVPFoozH;6vSe<-;%HX)ZmJ0zZR*vlG0i! zQv^`jBZ0x4ZfjSwI@xY7Xs7larSwN^iqrO{?gq&Omdtuv9l4*-JQi_4N-Rupm3#ag z$NH8=xBq+K+bdnB2Ed#>G2(=Tm)Sdkaw$zXsu0n_}aYNMC;t_UXFShyuCA}`ZG zvY=bk5sC{`#xg!FE&~&@Q?$G1}d zm>$QK2oBWiZJ>fV)pIMfSmGk3?&fz~Ehb{6Q&r8Sj;p*Y%o06Tt}V+N>TwIM>KntW zNsx-g_;?zt#H!XmUR(_;MhzSKMB?>&R4O)32eTEHFWQ=~4l%KB+OKv`Q<8@5U@i-2 zjGOybJ9gijHctgp4_BjPmqt%{=o)%dgKzN1$q$~0}7vGrp*eh8Im6aUHH5UHp*`cGzg{5_U1yj->k zV=rnL(`#0d&i?SE^MO_kyuj?NyGeHvu<9EnjWH9v+y`x(^1(s`2}G3rPj*CT2Dz;5 zhPBwa?ds}GLCCIL`c0c+@(T%4RJM47{F(-!nkRtA9q!2;0bM+&!u3Et`=6IEjce%# z$657Mr1&DJtCCDi&WSXHlFmj`J~c2IwkOCyY%6^|OuS&dSVb#%?sB&tsrNvjaFq}h zdoj5Vz#dwWk8s~*cu8gT1q$}HwFdzR!OIEd+laSG6dXsV7+w=Tf+8ajQamu^hh|Mf zy6ZZiRY5n=^RQYfA-^a-g{?d~FTu+GF`usfaBiO>od$0fyOLs;B^g|hScm7PI0<}k z{s@Q?8X{_$f$h)N1PQx3T896TbxZ`yZ$W}k4z;hF{CL74d8UCSLpJHJf5h6>Gd28W z7or(Jaood02GV^})DJFMCFJkTuXJ*EgQoyQ@^}R7l7cv)Xbf|+?pHctejX7i#r%}E z@{}$$zs75#?N7owu&!o}c&la_)SZQtF1GZtkZ~ zMZ^AmH8p-tR@Oy#LlCZqsL5_vP`y(l$vRnhTfM-X5O85s5IEp~B%X>$`l6k&mdm$c z=op+Jp$BXXk)qViLv(_#bHoEnwo^n%Rs|y7ey znve(tkCH0~O0I)U98!y3HocLn|B%RVV@-;Y;KfSW6+ zda9p0@;HeqFJvuD!c1CQH!!d?6ca=`U^5w~-_5x|6ag!XA8?rx5AC4ZVIUp|mUB}P zGWy%g_{4MJ3+!8<`ou_-rI!}VeS*>j!!tNBQd#>hFVoZwgqPvi%X8P00%!%BT9Uko z5wfQwv34STW*z!P3&-|&9zE!aa((X^Wz=)Pc#E6VH+67~yEb-G>Ctk?aH1W9gl#?dtx>64 zD<~u-(WLc_AOkfg$1*}@TYbr!rhI^K2YF|Z|d0TSSW@DThj5<}{RwUXkOSl#Q>!3n1ZAr^*e`(1- zd6gX5RDpjJ9uZ8&Q@)fK@|n0=idsl>4)DpnTY3d@PDIoT_or zI?4!>&$be<>O-E&qm#S^@u+>s=ak1B{x6mNXqxTxw<5{G{);A;b4vw^u*A+C=Z_I8 z#P(M&&5g|FKNQDc=nkZRqUGnj=IRg1X{rfcV!l71G0Y5J0|f@ezGKZ+N4*-^m{156 z1>|%2{%cj|dNkQf3I(r6m*W`D-I9FIB7rEr#{bI3PJ63&M1Q`<=mls4&Te0Y#HP48RO@8?$jDz%Fjhdd&{0nQB;0)P(IMBBiM=UxitFR$fe{bW^{L?RJY;!10 zt}Z1-qx5nCyUxQG`#Cu5niGeu(4Zowi$&|-{kh*+T0tb!t{X=sYN?taYgi#mPDM$^ zAg9XL+)F4+eare`gm;m!WGE5U(u0I9!;c{*cAi(xB-Z$vooHq>-rG|@d{!6VLcy|K zdod0U1>;~Y>U?cp1x5Od*zU#o1gg-js9-qhT$PV3O7&j5$SWPVbSko-d*LXy^Jb0d zf)vt`%pUEzytqXx^KT{Qo#di1$VrcMEAll+7r8NTp!XBs;yt@*`24Mf7BU-Z-}C!A zd(n(EBROWfUO4J->U(Zr5Z1=446U<>uPJ$!^VmI#G?3>&fy9gta31_u@$u^)QXMd0 zS-k*;Z4E{0V{uPDHn0#l76L4#D~z?(&%%#hZ$v`9&f>DRvp*<3lfsG8V1T!C?&V{jEfafa2hUSR2S);C zVLn0X`^4)-l!M|HT-0U)T#O=xQ)gcUJQHUl#Czp4AtGI~5^+3+IoiTG6BCNQEJbfQ zQC1$ki-XiTR-&b-9zida4}QHyhGcb3ot9e2eLRueH=#@NplEi+Wk-Tf)dUBf;fs!; z?7}%+11eUn&&+!YX{ggfV9eC&WZ0A4CxQSWBR-si=bI)15^$Z$Lw*y*5^&Z`MT-1}xt%1c({xd3D@Q9mcEHlbn;SHEva zcYpNk`J5;FM+Igb%`~W6bn0aA2momP{Zf#KEC@>b=hup^P5-6);8dEZVv~_i7r?B6 z4@n49{UTaoVI#vCyGZT0(TXj_Y zi7GumB(tzCl$a`q!j~tTmNQErCMJqQSGCHID<2-6Ko&CXQPJrwL6j|BGc_3xAJ~X_eX@Jh9b3?zsZRx$4xg<5AMbE^OA6a z0Lzjun)rbbSQ#`kX3C4&C`vTy@(VPL&-ylXAn-*W73b$@kc6^koo4-vl1NvNkJ3^aq(g0EEng!j?>O~1_I=LQ9`Un|B(pm~NM`Rw<|#ONB?pJm_=Szcv6o^Q(>iQ1-+x#4IC)AOk4&=7>U_Z0_bX{^OAGgT zT5Ptd$I3G0n<(~l8tq$0DcwyYW1Z~lH$}%hC8RyZULV6PTPz8gdJv%hGV#A8D!0%5 zzJa^RfRBJk?|Vu-N%Ez}I8$N02iXyA!Vh=fJp3Y$To(+d&eP&`CxgwTDcc)Pq)~(^ z#HgvXbSP?f=w+r^@o$2qXM`Vh+>E1_S$~3tm%(G7!)2Nk$Mm_wfBz-;r2u!oY0jIR zX+RhnStpvfWKQkP)D^_G2b0$;eO-hYTB|UxLgolH#;lJSZQ({?)od@>ji&y460_i^ z%`?^&a}J|v+ky%vwckBAAkiLCo*-q(C@0&Us(*Ur-brl`O8oF zxwKFv@3vS$78K%=)VTKhUle(0SGtF&GP24(L!*h#dW75)J2mPKl zR>bPn8(!|SH_I<~!E!JmEP^(`!+w7aARZ*K4qG zrAP2&x=nYryV`(_oOt_+a)V$fpnm0aZ7MlQ>?gtM@%HM;)#@q1&og?jW( z_(`%M3>riDdqzdJ*~G zgX~OQ*-yF#CK@~QP(+k(Ax3m?{Z-AnvA@`@(`VOpig_vXI= zT2*h@(&)1jZMD-L+fut*(K&hfg2rBV_2r8qI~`SfgH^j1zm4_p>A17Xl(Iumx#P@W z>GWe~7EZeP&SHyTm+sBm|PX8#%@GPXBG#?z4a??>_M-0k1V$U;8EQ zzTer!TZ!czU zFLq~dC3+9ZupiH}pOE6<>KZQ7*DL64{BW*Is$o7QW&d4eu9U;;(E$8+%Q?u|5seu0Hk389l+E%{Hly@|#4D;@ia9|sj-Tjh67 zG}3o8I(Ia-b2Og9-NkS`$#XpQ z{LS-Y=O0GLGY-eI-p6yUE_(4+(?!RN|KY@bP~1P+dC<3xD~f$nNO%(bjwh4H^{2%* zb-ROHA*a$J?pwu8u_7Dsk0;`)c8cCM3OZX#bFK%gCx?};ies)P3~x_QPR@8v&&5wK z8(gml-yS+_!Tp^ZbetQ#5C5i|-t@h_nLE8*eOrBUS`+&gw{wcecm}%XHaoCCZ*(>@ z6G8AOeqm*eA?KLB@0jGC1&zWR$A&ZV-7|_uZ@Qm{kH#MP{W|JV)faa`eEhF+L+I#t zamM)U&AL4~Q}Oxz@8^y=jz0oj?)^Ns7Bjq;6U+Y9h2!1@$FmDgHIEKX4{kXRo);I~ zUoLp!E*_;`@E2bQ_;_?2RIuz`2>tPh$jQw=+0SRF*b;EUeb8}LZBj`0MEHH)&&rAC zfuD%R9eg#K*GqXSle(=x_v`uYFS&6~`Jcb!A6+Uu^OAe)rTow0@^^X#`RW4tg9!Jm9I9(!au(B}EzoO*Y%AVJ*8 zXP0LFMGMr@Zr6kL>bD!?pU30wcG*Vf&EcWf_v0MpNHj;ON147Tyupvv{(x(qyK{fp ze-WfR6Y$+5;NG{}e4t#VS;$vm=@K2b}HTnE8F6rZ&*fc(NC80Kn*p;?; z5_j@X^7M(bAom#?l3*T><1zQ#cXjl&0lk)YN_;}wqRgg;}Oxwak_ zuA4s;gv{dYGyXRGqK82C4||ggV$KFdB_64Ij<4<+!6)iQ*3XG9;)TMP z3_qXUGjMBDSjqN&A}FW_=s1SzNzefb;hTrsgx{TKwpbjjL-Wq!g$9PSYX}~dqB3?< z@~WA$-?MSZh0j>d%(kb`za^SW4Zx^{FT@2b`utm(|A$-b58xROSbfPdK_y83>3ZYY z$4)}`V9exLEe{r%kpBA1Ip%(zWaiCsOnPLX?{(+Q;sBVpZ;|)!mcM}bqN=rK_BDHC z24ftzm8kZ>_2i4#n}H`B(&w%Rls=CA;I!aO{!k)-h#e?c&PXU&t@3L>f+7aa^18#R z9*HBaPB+>u4f3yVuTG5sy?;aC(%H$My_O{CT&x5Eo?^6!?2y*0=^gD1v3Fyw>64FM zL@T(TfSp8lC-Y&c{4R@$e5!sGMfxti)kU-6$NnD22Uh}^YMcH9sPk{ZMYPj=t;^wW zs98DPqs7~oe=1kv>;q@Y4*7$UOpcCLJXBE0NjR|ScbFC2xr~mu0#W}f)lPGzC(|Up zHZ;{B(D&}lVl2z*R}r`Xn@p2iXyg?8od=eOpnRJSY^m8Qyezu9gOlq9o#gWqZk(_&sFa2xrIjzv0YwKPAYfg}kb=PNaK56^(ht4th<2eIT z@BN_K@u!-TPj}n&>_PbViPnNZoQ=7`}%stfh(m=xn~~K@=&68 zJ-U3t+>jk7;~OQyY_|H~4&FBpz>o3)qx2HBXp>jp)P4k}#VfMNq6vV_ZNfl#%i7Wo z9yY#9N>BoJI$pPwrjWJ_b%#ckRdh)mmemjahca!N@)f9R-e@kXs#u(g{F2z@L|4QQ|D#I>{MsdVpsQ2W*c zk#cB$ed*w+yd&PvF)2+pu~`FCbFsOX&e>w~rk}s(g-d@4V2pU25g@+!rmRhT$)O)s zuS{JUL1m2>eX%p3j-1qSwexV_%4WTD98YXV=5H!~ejKu$NlBmcTJ~A9h=ZJiH~2%Q zN%+oqOjI1Po?41HIzi55;!Rw_kL7eA$rFEY!rOhETl$!+7gM5e)R?af`dy-seEk)i;KeB z3U=c7=n#mISfpE~aX4MDd|0Xc*2AV(T<{|WRY}4?y5kPIbU`0d{f+{5B8d?r{~lzw zx^;{lCKw(jo}9PP^)QhI-6cnm%G9^eb)1 zpXVuFQnFgTlKEcnd`tNt)FsC`^L(SIrIJ_&5&0`~XJkimIAZJ_sxEugZdYaJU9$4R z+sCa7FWZlTOLO@GwLl}JT_?4|IC^zQ`Mm`>4WhtM(3&LM#V|u45?JLZrX!IblU)SB z$IG0=3S5pBR9xsF;}B!TvX~!@XEmnE9C!c*)L)P&awIbnuBTLzmz#)$+TGJ7+olsZ z;lRtqlLuv-X;CLSO&9Xlmudw#Ss;1odG+g2Ms55?Eh4?ylVcjs4p@~>@a95zb&@=v zST4&j&4n%Fx}R1I%w#i&7%A{PcFh+pOZiwp725O8Fd{SD-02Z!L9c*5>VEP8NP7HV zs}M(!Y{Vl*)4svg`pBeuggtlW!mtxVUCyzfqoly%Xu|KhZ(=TQly0eRp4bJv3Vh9978{#O>vt)QeNZ8fb51z-SVPlTfRNX4?d-`>f+vWe z$kj|0jsE%D}io8x16g0s`t97LEhNItrKW;|LWQo?k)TyH-%lO7{4{*`@l#1r1V zzfS!nEei)>aF38A8>jP0>lIL~(cV%YT7rE4A|b#z_MYn-%fs*e-U=mgpUrGJXg>_# zj9tAF%eT0de45v(1wZr+Asd5TtBoki4i*nrV0hjYA@vs)Tr|=czJ~w6<02UWFGn96 zD3_nFT%<2#{bwLeV_rY%vVTSI%8pZ1(Z;`4G8^7fplzPeEQgv$BMjF0llvn-qGz4f z?aqWVrecLeia09v*C|MCM#Mx*l%NL;>eS9R@2Z5m4?C~>=2PE6g;A6v2L_M5`!)z1 z%549Y+&X2o6k^Dg`P(kV4;a)q+g#_?#BGd*j$BrX0aUF$DA&VC$dRa z@!4D?FV%1J`+QI~zPm{8XWel@H`%|{@ywq0-<8BQ*?m}DjHGSbQ@ux;&vxPVTi590=$Ky{9q6^U zZsVTD{T+RsbMO);vzMOruH&}t)UUE-V3+k`HuJ|N>+7~d)5o`%>5spQ7`^s9t8RCA z{&8gBWOuu#DNI?5uCpY6oF~R%w*}h&j(qy@>l@|2ea-fpnf4!7b^k$3o!f7hi(CQ+D}1ROLMf|z9&3bzW}TA;XLvtPpD+gJ zfuRkG@FzbXJqtHIMj0E2NP38xTR1Q$OvW@Y^(ubxbU*nf`GA?MRCpB3nFMQ3M9Js?H z(x(n{D>Z@eOfQw1FDGYLz>RvWqsXP^szUPd2ub-sQUB%TRarLt`8IsD`TPwV{C%9N zS_W&OYariTsF9VB&6?21T+jih5Fr;)E$KFV(!hMNkU3odsqn~MO+=C0q7nb8hxHu0 zW?82mkr#uphy4cdtE$1{gP86)2R&OxS@Wp84Xle}ExU5^qjX|_I*)oIF=&*E3>a$~L zMGzuLfL)C^rpp$q#IZlZ!!GY5LpRIxg-_ud*s)WaJ4jO$ZOq@jYvS(UN4A< zFG)+W$q@eBo`$Nnne337F zm+wpQ&9Aoj@#==(&?EofocOV8j~AkPXXuJB`T~tzU?TEKY&TCDBS<3Y10JB36lRW% zhR$}q4hf6>r-a)hWfq>HWB>AkGf2}#;n66eo&t?L_m=qGXLok_iGox^K|1n%+Q@_? zAB2LZDqhGc{^#e(Vnb@ob|j(?UJYL3Gj>En1 zAb2d*U0~jz*MKT*Z6uAG@{8*T`}_7ZSVcYnkS_oEwmL+owR5+6NG5*#GGx4Bk^lGJ z!DZ5m%A12qkaN`?e+{8?4TbYB_OLIo&Q>b|i$O?=>fr+ij+mhSe}PEPi?Dn9aX-&e z^f=$(TZaiO>-z{!gz$9IaxIOxaRHU`VH|bcKf@K)D4q1}z|@B7>xh7OAmEE5SM;ZlyU^X>Np(O2|pn)aX{V z;x<^L`;vNpZR8=t$SxX`-8zVx>VAw?1iLu`%AMTxhowy5R3XD)5Wpt`j+oiu5z^qp zfMMZ|6=_ZYyL@rrz~d2ejv{cT*6VX@&*H(@nai$EVw zHWxRzYq?8F884}oo^OC+6HCv0UUfiM!NmdH!UhYPzjUVQTQ-hGb%mr;^{M7YtjH+S z993adNz^E;XLV9C0*O#m`AZJ!HWTDlC9#jKdZ24ALxkHtGZk0pAiMWULbF_DRFWRx7L1eIi@ywBH=e~pLK}z3ai0XO# zV@IlOYbK*!!Dy$ME;>V`yH%2G`aKXEp#=iO%&Llft|qW|2sP7{b<>45g6^?*6|>_B zBq=J_cR|_D-nbFQlg+ruzE#6h6-WXxheS4c2lwPty%kX==Ef5+?B|*3@|Oq6_WT#N zD#DRf*C`%d*+>2 z+-&c~6$SI4hYdSK;EFHgz77v{tbA5{G86Hud_w`&q_hKdzD7eJm(iN2V>V}Al%Nip z-KQAn1T5|>{APrZ{Q6*x>vN=e4a`)@BEhxj&tP!p2lb9Zo**4X_hMl>F@rRP7fg!Z z%tQGu6`p!2KE9O8dL;HrNX5X_U$s(YX?M#;RL#~^t$(`e4SAgG=7|Zp`liY=+ZpxL z%P}Ixww+#qBg(eQOMSd_o6vr5jGEiJ=!>_HlkU)bK5EG*5k0Q+p*bBpu{pwLa}Ln@ z)7Gq)+C40uVPMul2#ryCe2!A|tcATEn!F+Ih|(3%zs{)?be%})|(&Jo4>FQqp!F6VnKs1HkZq7MW#cZf|#4|dXH8wVa?LM zS8r|bn=0?Z>b3af6>fcj0TWoC%O#E}8~yqz^h#uV(R>`kJNeMyg@cO8hLlf(8rd-S z-J%K;Cudjof|#iCuZFjBmv5!fZhsntCpqa|(Q1$Ws0e&lwLI~V^YMHss_N{@{1<6! z`ukm-*W36Dr2TjMm%n$k=da(0fB2Gdlk$L;zdEPzd)i=*fzMXf)p7D9&(VaBpQrH0 zZl8~*-;V~r-y}T?v|Z5-{^LVCZ|7+Fj@L5y@y|4V%g>*_{!x(#dC?g1QXnR z-dk|R*=F0KxVr~}1ef6M4uv};NPq;l-~^AR5;!?&hqUAED^3xkS9V z`h0mG?s81|3TiIIDM3)|OmT9&MZ&H{at(1Q&BZy*F;U1)Iw9#hO{M*OWekKF_q^re zDoH1Lm|aa3Exak1%eAQdRroDcr2N%1E!E8YHQX&V!u++&_sQmxD zdbl^V7$CQw@(>~jPEoule|TS#GwkOf*yS-aPBGe_Gn(Tuy7@5LoilbLFrL#Am)tVZ zJzgGl?N*}^|0*jkM0UzADV~nn{o|rLG=K67&DK-|oV)u<6K8p}wt4JFZyl0;Qx8nZ zmoKU}7UvC?f;_x3v-GkJwb#Duj4E9;&XAw=Y#%s-nM2uA&oc5`2Obyu8Um}P?&1I(z5PLyL$6R4d2hOlj7Vc z#@Lto;|;xW-gpJe^DJ#Nh@)P>BjiYW`L0lWJ^6kU)UoOZCVKC@meCP*c&EHasp~YR z3hvg4fFuI-5L}iqqvM@k&f-}?kx|o&z!ZKz$!OERwxOF)Ju&F^ss~U(M3W&hcp3XH zu$i5{>yFULHM``orx*+*mdocTsx~U|0)OtbqJc&5rqn?YT8V`afubuzxU0ea@_xh% z-w&lHII{qU>nXfFmT)#6Cj_y6!T0VX*bl4hDN}Z``pQ_nMr|@au9=H|xz2p8KH%9n z9cgwx7}7|&DSy{$cMoTiSG}s&9fV1v*_vqgp+D-Cbi6>4z434YtLfZ>^XZV^HBunl zYA6RjL@59juZ@snR{?4N7Fy6))^e^v)By=&+4*ES4+^K=)6$oEvBc$xQZjJ1Be=^B z97Epea&_V> zSM}hgeHe`&H3(PfdtqKW*+*mt9syNN);jFw2Fi+Nru*6?iIKxB+y-=}51sXrPDAVt zrXyy<`0~+Fp223NxmoOF9uHt3(EB}sL_+l+nv9V{pp@T}aYF$hLLeUG)F2@&mMHW6 z@=xh$8HW+bWMMF>EwX<+EM^ZO9By8Wy3mk^*du|BB{TD-#7WF0 zqat28U^XZS2wSo&8`addYM8BGvgv%(T=4@iG{kWU#38LJg3s7k+Sg%UziZwqOZe)( zGo+>MaWi|v{26>TU*WR`uG3ogg{1!U)erx8e#4tob74Ig(`3OQL5OiU{m_OEI(XAc zWt~RzkhKn1tCY~bK+}TG3JGzkDlbmohHaqu642CNAN&bfA(T<1r3qINi=a0{jnkYe z8}Q^)neH6PZdUNaia`=W)yiinoeLm$o00I=d@+OW!O{&1UQeYEPZO@@Is922M#McU zBDXBM{1y9qV}dT`mt8fj#e3514;01?6E=$wA%$88Vm?k=2R5e=3m`O;%jEoZo1?Ac z)QfRJbmGfN$+Z``(=ttrS6>^aC$HuWqx7y9&F3fc4h8%|kYAxk;~sxi;hQCAik=8n zq7sM}iPqN@HAszP0TT{T(2ZGrPSuf@yi(tDsi4UU@J=Wz=ISq$X3*trlcv}>S|mqg zj9MaJwVzk=Kp zQ$?5pc|q7%4dlcojKIW|rS?Amd0BdjW(-)G3<0zfa>#}QVlT>pfy}8{b=r2#5b1gB zRCMx3-UJe_&_KbGu`1|VU93^FIW|Zv+LrQu-aH@*6{O03yTW+6ipx`B4Q;%-X{l)Z&YN8c!TfF-f`vXC>z){tUqtV znMh@bM{^WG1V^|WP9l{6I!Vg_5JayQIbbDdtv7>pZ4T8k(w(YE=UAtJBH|e91QBk? zs=f@=7_X$pq8;mUzcX6j@~T=HIu$#BFnwOg8=}P|R=4OmN?aA`!-Tv-K>R}ca|jZh zMeOrlQh4CBFcARhO4~WbJVZtb`rsvzeowF?DI?HNV2Px(A_p8roI9 z#8Ht7*vCRW?kT_q_4ZXSAslOw>}x|@zx|$ki`i1CxMI8#dab&p*^+N>ON_9Ywx?Bq0@Z4zwnE<3*JYF+0@o6=iYjC$KBI!ZuT zX24RBn+yia9W)Q(BYa-C+M+`CHJ%Jm%qkx`S!W@eCZ+qkgBFqAu3|%co7HGoXp-KM zO+w2m=Ll>ujoFxGDIAQA!GE{<}y%-Wa4N_ zn_zSou{<1{hu&mBXDB5o207IXmSF$_MkY-b>5xoPkZXO-x%PeK6~YX`f+!o0j1P`A zz&Dp{D%9Bu5`k@ahFSTW@QVf*1!lW$oJ2J^&8lx?NC2o8@i{Os1f!(R2oS+dTm;e8 z*~CT*P*B-qq68;{r0oWCrq#c!xaDkyi;9QGcAc@UH(eIo*sS$OP66a}blvU*ElyR*uq$g$$U+EUg zU}z)1gkb5Vz6SW>?Q;dB(?V)|u^SW|q9xUl5G5z(M4HXW?X zrjRcqf+K4ZcyZaoQwD)9xdivTCZvJ0%&GSk@uS4{QI)V&DUnh(C8kbrbc0K1G!9-` znzNaqGOWiODI!!Bk8Hx~h|NvQs`aX`LBhmU{Y~515dq1D;s|d*A=?M}N%xrx>Bqi8 z9kBH&Br4oz_!Gsxm&d2xULk4%oIE|OpU=YdIg$tyXggOe)PST^o8z+I#W%FhB6nuK zz1DXfHhi*AVs_eQD!3iBPQOUp^w?p3i!Zrar&)`XRw{Y3KiMC8Swkqer=Z_FHA?7I zhnBW4@6|m0eM&RrGu&6b8(j-P49xzgw8P^*Ma$85&UFQ8N0u(`&RfKT9^+}?W2b)Z zPaoMgK|MdbJm*{1-il!h5W5VqZr`tAqW|b&{(8c$CLJvr z8v514CIhM4MAT=>RBra~GEsL^VV|#xG9C_kSMGSj7AL&w?~m*<+zkl%sH|@UZRQ@` zH!ARsK6WTD7*W?~lX?9Z}_~@Jn~yhe|h`R z-Aj6YR-ylRR6%>Y2!7IUEZG)p01uUT*r%(dg74;CA0chQFsER+(gCZGHTZUICLe4r5Jc306LZd20)+ z2V6ATPALBfXI=@%PI0g4cjl;k_DQ)9uKWV+2A3Ng+WF{u(U?G!PK z1u4%Ksi+dE>=dbr1$l3n(rO&8?G(B5lTIP$J~PS&3!16z z8c=2vpa||_M&B5JBxl;ZWO=${d6crnfIdUNoj|_H~_ zs$fuIV$hvoF|zK80HIkia5yWWX>4)CK{&#dIKr5??6$Z{AgH>rZ_ghDn%m)7SK-;6 z;boLKZB^oXvfkKEaE03vgj5oQoDoE@z5v<1h^u;$boL^Rl`zZh4BUK*Uv@@_XpO=x zhVM{C)O1GF#`<#l6t$}A<)~eYFDnNJYuw!qrm@o1I_9;a5{W_u$y;WU59p*jtfYHq zB=?h7KUm3b?8uHV$q=VVVXMj3&PeguUSXb-q1s~!9*@6K!O@$ zoH7?2Z>QP$p?B%oxb#^m#G@&tRk_SBxJ(@=oY=V~+3@(s_*7|V`Eps{FL(}oS)_Y- zVz7DF#CUoAc{8SY^J@4KF8Fe=`NP!sX(%~%#O>d8@pr}W7pd{%J4k(t#2>H&rz9fEA+hH0pe@a*P|FF{V&_!3l+dV^RCClmhJ0;c z#XRs$^6iY27KgOnrIf3>^ldogP6gM28o(t6;K?owas;?f3&qp|oTe#-C3(dC$ZU(m zp8Qrz)g{VjxT|r*>m50pImFu?%SJ;eNYco6 zUn+itR=TNGYMN2%#8Do+lt<)LK#o%q-4qvhRJnJMcq=BjmnZEqBTa=XO>?EHb%7U~ zX|`k_j3Q?A-lY4yfVhzwl2Wv{a=3ujNrSacRWDA%?o#-LljeAgh|GitDyJ5vlQ?6o z7JIF@*Q{0^xwXAq42PjCoxcg!hMb&{vXh4Lq@xx%O+z~eR~vm+JL5{Jj#JqMj^6xA zr>>gy;+S=qoaSAfhT)Yiqm$l8b`Rs6YrvF|np&|7q`aP5t3n`uO)U z&W=;qx+=~L#Br1?CiKrXp~Zl|4Z!4s^SBwFiQTn{)0~Ox^@#JFsry{OXHBz$Je+s1 z9yq?l+I@IE7i1IAW>r*y7I+pR@fLYprheBJL7J8|&L%C+7G92&#jM7IbA;9!@1?n{ zI{L<2#Ce@)zXx2P=H?XJo~YOZ1og6rk4_VEDuT?ePvoy_4aM zlaiLx$4@~H3x@6sf&5tSIZd4D8iN@Yf1 zwC+=AQ{$^wQ(;vuVV!TnYZ}9bKZTDHgw67hp*DuB5)ky;`^0>TjB1SBBfw|=5pk7x z{NS9eZu@SYHGrEHn?Z#f_60UPF9_2Wgx&-~y#+zPh(_j(rgM#EOv3JDHdzTJf7=ja z$K&Kl5bN{i*^3R5Nn*}aA5o6xNUn}cIFHlgjW=|SH~zJUkUt0 z4al!Rg)pKi5peEatT5Q2th^)GetZ_||#!D=@O$n3HtsCEj zNCHv4h+%k<#+(G4ZAx3bO~YLTO}|JVea?E^rtZB>XXZ6fT8wr25hV8_Q}{OH{%xkK zTJT`VbMQIkgMpJgqZ8jrc4y#)ZXLAm3GBOokZrwpLQFAWwQmzUi zoTOV`P*D_d7yeR~F^PO{ZDqdoUA`S(fsK1C ziXzt~pVhHx(f>eH@6^&T9~UUF3oj$mxWtOOAFr}?`xve`zV8^}nK&QQv zzhjfAo!uxz?Y`rqQPn1UQ<8gAR0}z-pD^jBKT30F#@!d*ZU#t?F7w=K@l6r&mRf24 zZeEXWHA=r+F##E!9x%Udt%7d1QfrUSRsvmX?}whe!CVO!_dd^*22*$TCK2UiF*l@A zYObp4Jb8<_~?AFPWqo3NfL(LWqW+H(}JRbjB?Y z*U%SZYeyhXGIMh9!;Sqlz15M;;%#-a=>V zc}!4=f0@M|DiD~=^O&s4Q%c<;dl#M*4n+^h($KB9Un76jx9*2aJo!R!$Z&ZACT&8d zjrFyF>-7D&h9KY5E{P4~bC{e&U|ZAk*qX^G%!6VTXZ=l$pLRvvcnR);SDH?Ur*_rs zd`;cL@MW!B+aehILtQ{so#o*)Kk-c2Y6Fc3VrmbbGQEu3%Zv0Kl7V#ruFg+~8v{8o zh#sQ!{;)L9pJi2~Eg2IvF6RxCrVgJ84qtc1cVb=X{V!>b6a=Ej zFzJq}^^esA&TVr2P;LJ9y{{upa1*zCqTsu6!<=Oq-d2h8Ruk7&XZ@DUyDgP=C3ShI z=uAA6>@Ni5G^x4uc{1|pntp|^U#;kU_k7y&BC%9>x2s078oaF=X2r_J{MLuLn(pXte%?#YoZsfYb-r^H8qY`93kgnCD3U)6uGs$jh{; z?oE99w3jA)CSYfoF_~9L+J`G%zU}W~a-J9+qC$^Q!AHyQj&Q+L#U9Bgt81MrUppSo zZrjcwwMQ~^*1JDnl!+sq4$bC~A?jwKutd>8k#Ta>(eY6rI;JX8n10IPySI6NaIW5LUr!O=zll(4*p|~Fwu4eea#Cxf53_2T*-KY)0NNiF?fugFM z!B{G0H+AryJ(Wy6hv|~X;(3mIDyQq$6+{k`UM`+x;+Mg(2CBKz30w+yv3pa2YH^AY zvR4)wrJ89rkHws&T2;!Ok%Bt$rRsHWC(E6dxfoZ^6EsiP%3M@~~|UMl-0jTk*1Qk0$dwJRS0K>`rFO#RysRahi9A!D@M;^4A|O z)>wfR6jA?clFtb5gI~TUNKynZh#4@H0kgk_(${xphq87pd<$o7 zUOJcB%2KF<)=F%?H6PR-X&U+r-xb;7ncteds4D(zbic* zrME1r{c2%Z{%ehC>(hRTcz(UCRaGBJ*kSM*h|i*CMCickIbh0QUH5`I%=+0Z9R^!# zK(#F`D1d)#hKano^|w)u@2a&?JZwL(X%#F&K4}%Jvt(`;Ue!5izsn!4XnndyKJBYBfObsX( z!>MS?)}vf&;TM7HczCZXg>FzT$Hm|kE+?e$iA!BOCXyVc6@^iqY#?R17Xz58gRf?_ zO-HZh-npP&&%X~+xLzXt7vS~oQS+?(2xLI+Yk7!sd!`V#?Q~{%YT30$r zO$?z8omKz#k?t$rrXDZa?YC%dq1(+kX+_uVc+1G!?Q|EkyYJZ!LU%iPL5g6v{rr;1 zyM6D)Zf-~UC@cE`s^xe5M~x@t?kB*fcV|cK@EQE4WawTGqO>i@Nd`~h$ZhMsG_^Qa zGH;`BuA9s=5-+DZWNU7|MJas__D81F`|-VE{PTUeYC-$``M8p>wVFQsi}&Md<6hTK z=rh6)PZjPkCLewF6ln)_PwxSp_#O4oToHPT1khiL>keTM2gL#h zsOjYoH_$zIduZX#LexEwRgx(%f~cZCwX&xVw9*Q&;6;TE+>^iPUFc;87u$vPzK}Q4 zMrgxHwvDter9gUKn909w=l${_2=->DUj%I{D&&=s;p<>QF*G(-NgM?7oCFDhDV1oq z)GZQb^Feufj7a~G3>0C+p|dn4^C2Hp!eN3w&SX#op3Z>C?gw;zs|h@5j(I7#>>j^~ zX!;J@{zfF#u$aXu+)4gWEQ*jJ)@ru6VfF1k2N1KnabNE)54Uzz(Tm8zD%Ui755dO^j$}NY{r5L09>Ww0xIF z^;k5J@&`1~`;eNaV{aljP%WEaE7$Pdo6&F!4$~ZtNz^=qUOL}ea40#WIUvp+2m^qU zG-4?bw88XN@u#HJ74a6$2SPZP0-zuZB>^~<0ZC|ExR3?`!b2DkjFo<OO2dN-cB#b*GA5kT4@}-jgg7_o=2I&7M7&P zdlg1$B}&#{3ytx{4jI<0i!{=)K=`;bfRZvllMS_$l5i6V7T86q3WWH8#P?R(ej_ci zwZ!zGnJjFnJBEm{%sgy%@?avoX?d2+^6O#0n4gT67QX=hRUB)NceW zZ~Cb6?ZPY%zv=(*OWlI;#)5%XOJd5+?@WWjS@0o8>$xl#u^uAIEFM;%C4(qC4I+YK z33M(Tz*7Z?@ga6~E`%nvtTA3B!i(X=nAw%tSTpFZc?|KCoR`@vGNkStny`vZQ#rO( z27pVG^eGLH-5J6?p+gp2zP_)4o~y`)Pnw4)wM*AzQsr9!{_hT(X&JhiS=&(reVHsM_TF=x4FnWX_mZheg=lm@&# z@`oU!MiP)14pi%k!(eo?RGnkfXHg>yKZ!>5S-VOv)Z>p~Df1iDH;tBhHjWuYa|ijH zEu*L(ofu$~;XvC(ClMdlbshLT(Krji))-`mb*!GSzIbmqU|~6&p#f$f94M9rcUm%} zx?m6^%YBpr&_`02r63=*_$?x|$Cme)ZM#yW{ny-jDh+BoX~k0h3`#J|A_Pt6o&sq=J@&qVf*D{LZBY#7 z-DjrE1KmSGn)~to$m{BY$3qLP7A<3GQ-KE8W0!h|v_)N))-}OnXRRDv-l>n#$Y0me zj7J1ZrLsW+fv*CXbKesP{}`BenxU&`{cakwzbA5`i@xU}D=>~Z(IIh}3vS&L_qv-b zXumA{*tV~y@7C_q#Orl=4Y1M2=o-SJfG|oF&$ieLnBzOVSrBvtEZ%NP!{3hRw_g-Z zd+Z9Y-Aq*oT~$2B}8%~DT&Pj#P zlv)X|J?LH=+(|EV-l2O#Z+bn@Fu?>fnb3f-4ePz&K6ry^yde`=pa;CM8@&-5bPHm9FQ0sR2UpF5FBL|3~CIH-VKgL2#E;}iAxOecq4v_<$QbNokie- zvFn{f8=4m!idqeM2yo$OadaN%_0&f{TFxrmj)u1cOzC2BG+gmHvo~FW|7~6 zBX`UqX9ptZcO#DwqE2X|&HzytiG<(IL)y&32OFb$3Zr@vfM8l+e_{9&0QeXj4mTJD z=?X+?0z%&cQ4v8%G9W~A5UeW*Ap}IM5=CqtMS>VjN*Db~CYoZ9Z7(=_KQWr2D4KCF znt3mp6)}dLE`~EHk}4#II_cRoj1e4+5#EbDijE>G0!i)xab;qqlR&abvDi(qii@#W zba9w6aRBpJW!E@0^Emk={y2@>SnVbz5xRIGnfMRp@x~$Xrb%=hgYjH@@z#h5AL$b8 zWD*?A6Py;~Et2BhixNBs6TJ2k1YThLx+ee&0|5>38Ucb9f&psy86v?D@CYvfm6@G> z2-x(x1C?3bK^PRWser2N-Y^1oi&L?D<>fFH?TD4-`!Rox>1eOm&sWLVB zqbWQN`zwPr1>+eaen`Z!wS|*8fEaqcq1vM90_7apGz(Rz*^)Ok7OQvml=Bq^-J!&C z^;W}dQfiV;BfGDw58!>?Ta5WsbXv6+2%kDgZ@}+)5Xq2j$DS~uf13`mTO~e zEjK6Y-CQHx(@<% z;kqvh*Y3I>h7|3FKaQr^MgW0H;YQ#~=iQAUvOwBz!Ibf4-$H2f3%`ZFuHXF@#?nW- z8O||hwi&^*UAP%3aJ{=3B?3pc1(d)u-vR-si?*WWx%ReVl%?pt$Es_Ze~)`(QuIAu z*Lm-Iff+t(aIXE`9H12aUT&=BP>dkFp#?A>)=m~!0PRB$EQAJHSmYPlBwG}epvBHh z7i5ER7)pxgWDm+R>IsX>bI!GkD{{4$wwd8EErC_AujGK$(5wu=8fXy)>#7+N9qa0O zrWEU%WucU*+PT26vc{$8;j*T$*+kY22gT1DyHDeZDk?AEb1_JC&XrVr=m=gqsd|D# zIsG#DlY$Qurm}R6(yy>|kMlhzJSJszS$n}GrDt74!YgMzr1~%I`(7p-Rt=KnysjPs zN5-DCv-H2d7(s8BzZm7&S;?p=LlFrTv3__BoDfBqsGSgkj<}qZVpzR|kVHSKol#~M zbehr-Cgz;eVOMaP*K!}Nn|yH@;nn@ZRxPNKWT)nXgP&h6>mN1L^kp`?5{a~QCnTI z$bT`2t}l2pI-dS`xuhS}dbR%HMDS|EOLz(paQ~J6Zh0E-(PpK8?divAf>QgB>-i|~ z)7piX7Z@UU@IF=g3l!n0H-da76#l>$IKERKjPOht8bBwK_NgzyNG2TjKqs2psUI0i z7J@XO3oH55AK3>FsUlh^nBb!~L+cQ;!5c=xK3fLHmk9a*r*{3-Q`+Mn`clR`PUt!) zU+{PzHgqS>IjH!~LX^X^aS8yv^x9{klrrRaO<1Km3!9|LY}x3z*f%!$qZ4SDv)-4&maN4Bo`8F><(WSe{S=YAniiYnG(jbTHk zo@F)4BpviqRho_l(`w77i~ZH%U&sTEO!EID&;J_au_#J+#*N*}OLgAgE8uvnDH6#h zR4>lY>5JPhf~n#ImgJV7(U%m}WIrQM{q~YYS#^>S20h z%bE@;ozmJtRb=bRdhcS!#3Gx6qqx=249AUIR(f0jd4JVpI#h6~pFYEIYX=xY9XtKjv5QG)gLqFF(k@{C1;r*6Fy9L(RU02zV} zA{MgqKU4u>Z1z9tzv7`UfA(J=u;Rbje}Aij=l(lXSMo>yEnTcJn=by^$cti0Ya%1m@rAT`3bc~aLLIC-)<+A`l0-UWti#mV~e z<|i44CYb=8om}&i6{26zBs+B7=BBz#B^9LEl<%3QL9b5JNct(N?`C}>FD}UTpbn); zvEvQV&O(zR#LNSl@NF_DJ11+$rw7vS7v{#hX)qwv`C5n;6VA|=lwh@A7ME6`ag>zR zAvuYb7HOZy4u9l*lw(1tjUL%K|~!ge4+QdJP$k@+rB-2 z`TPm!{e&M=AfeJn0pipOjMX3HiUG zl#kgR$A6)e)+O@Klv3ASG7sg)ar^&ED5b?-UZP3yUj8p&&;0F4TkIDV<`?f5m)7s^ zmsIvWpQtLWowGP7YuqkAC~v*qKdATu$8h*;xmq4p4N#XHR*!HU9M()oF+6iNP0ORY z1(TAa`W5GcqlWdspTHh(dEB&{{|xMh^#{i-r+o}3e|Mtl*OOjZv4z67s#Jp^eSXrm zou_MC{me5eDR$a|q^s58w#gq%Lrje!SFS zlz(mI`A!x5QO$%1y0zmZpyr`wN`l?9c3P&TwRT29?Xh-NrCY#hK(=k<${)ikVsrQ) zL_uw#tj$A7>N4r*dfB$0@n*$w-uhD*!8quDujM?WqkhwJC1d0I7x5DAh^yUe z_Ngd8wcP$?m^Y&4cXWMYj>ZW;UP#(kAMf=Rrl}F%7G_y*dC*T5g}) z8%nh{F(#DFSxf1smdlaicy~D*DYD&X0F-c^|L|8WR}Ogpo0iij4*8|!jFq%M|9e`_ zEJc{)S<5*F@}}m5|EA@dql4m2=+(0E42$;)G6SD)T7-zv|5pJK3cV(R8sW#7y3b|;3@tINS#WUs` zTVF4+MUDPhc#lPzz(woyWw)E)BbP}JFynt+c(>cBF2}b!nL$i~Oy*a)=`2x@Ep`eEHQ6Nti!T=)(7uMF}efdkHVK3;y z$JTd-Qtpq}p3Y^UtCgU&txFh?FzBWq{x3ui^Z9n87i9l`Q=E@Xe;6&ly5g3!*WZeh z<_YT)^Y2DWkt&oJo51fzi<=awtjsT?1>s2ace(R7qK9-zRsT%%#PYKL7Z5%3k(+_^ z-wros$_Tc@{yf}BJc||^@rThu66?}U*%NaCllk{XOXt(@{}YUsrX(8}5HBbRD(eL( z*+Q(xMCYS6j;W-Bs(L}9-KY^L9rjEHlmQJ%56XnbK*G!l6!JII2|IRG&PLQK@DAnZfu68~nEo#{VsB@ZU5T)6YB3cc<0r3chlB zLmC5?T4vkZJ+n_vOd0e3G#FLsMAubzh@TBcbjZ%X7>o{2y8q`Ij9iZ6;)t5nsRz^pF$NL;G#HC^m_Pq>gYo|^Z17)bN~O&1Btft3CA@vL>_us!eit}q9o`S; zBd;<{Y5tJ;hYl@e2s2~j&_nY7SyQ^2ePdeopUC{O>m{p(zp+8o!zAaO)#6FFZslzQ zaiq(?Yf91-osCxBOKcOaj(l5+qKC5=JSN;1))?;GO6kf&DMZ`15(No1Uq!*{k;=Q! zdF6M9pJWw*TlJ)|_j7+`ewfe94;A{~WPZ7WptAo-7a?9C=MNV_XBzUqaS_(6$R^^} z|LWpnQ@;Mc#Kreq(udz@$xzZSYP302I1vwBE`uxUY9}#GZbz zO@;}VOBwxQezMvxDYuk}ncmI|s{VBG$pp#iT&slREa8#ZSp4 zH`jRnm#e`4;3B9VGd;Tq!ypx9VGJ58lV{2GvNDno*+cGM^V0qs=Jzia*`Jat2dwqF z>7uDSM&+MRI+bK`l{ll#J0*=ao#DkL6WJk)Gj|$PmW4+sv)OYbu8;3&Uu}ud)Fh z;C2du1gp_Q?gHRBbz3A_q-XdgI)rgN_Ih%bc-MPrz*Zqe6d4#7u%b$!OK6pG_wu>> z$hM1;kKpE;DnH@2AL7woo)>EcLKDIz^e0dE1a|1)hs*ho;Kv_3O4_n;XZj#84CJ~5 z3@rwfRF5~DKLQkUwMZDpsTaJ=x;O~{6A6vQ7o{ijdFw`2Bfegc&B5W{-dF z&?BDd^ok(vGH2AUWw|V4$N*6*VzjlRjU^fr_ z<2>@NCQYV5{?DnvGfghG-vQ`AYui1~Bmcny3g|{}s23=Q zkW>FYkIWc)YjGm2DtsTUZVN<~9R~fHM_!7my%kKL>}Rv<(tM9;^h17R*1U@)%M zB>UMsqWhq!O4lhHX8qF-jjqF#3n$q_${}HN$rVqo1LKsa)W7DoEc%;yM7z4L>hO+u z2eahMPnv8*KKvK+NX|sn@lW$e$08jsb84L90BxyjVH;k;Wl z6Lnv#nQak1BAjzsCiGS13DQLr{4sjV&`aefT2Cy;M8Y&IJMp)VQ_}>jk1SKVmi*Ck zED<2XX)QgYvm(Vuo{18ufKl88w86BQ2s30Dm)dvBU{^WOv7s%)Ov*<+Wuy!5k3x9=x5)fQJjX+-wL7L2LhQ}QLH!UwvD;j2S&J<(!9U%Cow+)3G)U|gbaWDtp$U{khB5D$J83uS9m*{fg* z9Y$I$ykHNo&9*z0CH_I~@Fh{*);GI3eJF8GI1*q>iQlS#P;wsiy{X5aU~3*htuP+5 z92me7o`qrx5Kqpm3`BQ(^%KcRvXOcCF0(MezmQBtOH|-DB%?+S=H>@rr7eKyRL??x zBAK~aFXK-n^FYDTo9box1IY&ZxSG!*>|W%+ZUFlEmd+v-nqQIJ4D<`#vC6wAQ>fHa z)Cv<;s~ZdCl9$Z#<#O1AfVB}9Kkx=+L$}nmvt`InOa~Ru<)Sn&y=kOhV4=3>`FX8S z(lxOS+6dam<*Gm5HVJBKq*wzo*?F-Hzwd8Y6iX0d!{u|~ttY^;R_o&Hhrn|`DT z_tauH_2>KM^Fx~D{&i)x5hc2YV&z8Vb;S;&2fAy;^X+$66}&K|27A655%&HSeuDGN z`N<1??~&p(9AA^1(E}snCM)CeN{uXC74mKHjDs0v%tYTuWzhSJc47|-6R=H>TY!vZ zT#ZF@3xF74AzSQJ!%|BxWB&WS`d1yC=&gxxw4hq&hP~!JQD5X35qf+kYS_U=AToQFai|K@>^{0(!)P2-_ThHxk=}@rK&$I{^OW2=n3?7k7mJ zq3i<=z)v}``?z-1O=aX8UdxYOd2QD4dD_j|u^)XrV^xtZBby}mKc3U4)xaQmqa*w3 z0f1t4bi&9MHUI6Pa%6REf&6!Ro!g-|W7Y8uBgReP^}_~eHHrQ5+iWSfBWBwJAuiuH zI9hJOqcWQVyt53Fe57ydoZt-8#qFbb4{pa`s**+@!c9f|{3kY7*;DaH&EmBFvv}?*Sl)fksOLZs6tqxI(4Hx#aw=93+|z8io2`tjD>YR(&|bcq zo1lz!UtI?2#q`WmK-L5NiLu`M^(-XtB2@7DT19cR%nv;|)sl({0Xp7HPWub?(1Ycn!Q2o?7*lU)kgtZ+iZW>>~aCVMheLc_K*hGMnge7ogNUl`wXh z&;PjBAjLDY+03_YHB$aMgAaMswbpNU#MPv^e2!?F#LLlkgW&dj;mlY$72tW)D7GuY zBOVrugLu5opeN09;oN$|U{)&9vUU&$b0#BF??Q@z|1f#e>B6uc;1TReJl-Y4b?O>> z^TxbQ5g19xbHQ%Z`#GK%Ybl=K5?hW@jBFgFQ%HO@*W542#mwsd39XvRQ}ED-Q^spS z+;5ECQoDxcdKDW~)m-4QX+CpSK?J_F{Th4;&*JIOzxawcsQtPw`0B_Ve7}wk#*ArU zemYM9KkT}&-cF-e{mznpPi;X!kV9Ym2bM&5`I9C2caX@ww2jKF2*Ca`we=4yiSnrP zIkjcL;8zN_UHT6!sjlgd)Rt_W#kiM%9&xF$Q|6o>f6LF*)=!p{alDnRc{p1C$JDs6 z9Dvw*%Xzfi@{=V!XD5b3;lXncC5fgVqC8Q5OKpA8BpGTw1Tl(ILRkhd-d?k+jTNeu zydz$y`JxIFf)d+wOW_@>Es-p>s94a$h5qrQp~A1!mT4CrLQj@uL<{V;(QKne5{Rf3 z%|mFNYZ?MAhvv7`Rxei42-Ci&2vp+NW%R=|)#y$HSZU;!LZFe`pQ)`(8B~ng5ZNc* z+%+X#pMFd)A{kNOJ48tC^OLY#xOM9?vb32P{?HGz@5T9#;Fd(NY-%?lhUxsjK%kA$KBumt(P>Ko*UHXVA=JwHj`eguQ(Lmi(Fkp3 z6CgB6t}iixKb`)VHggOYIaglgSS+7gn=` zu_%3JNtPO+A&*70wW0ll-(IzPU5T@M{PE46$~WSO+QY&es$DR;oX2 z%Mt=!8ZgjMZ+(z{(Q;WUBFnE{2heI5R-Ox(MZua>;9Lb(bcG6f&x0}bkQZQAv9?64 zN-iD5bW!|w+|VUgqw~33z((~$u)U8JU&RImzTm)sMzM;BSf65+p=WZG9k3XAaWi&C ztqJHpKq+EvnIW=3%rm*dUG#FiNXG~O;?3Miq>@lI?JyQ8-s$@1I6bd%fDUlfKqTDO zJ1l97G`7z{z$uJv!oF!yZzyn#nt+-W#JUniRK(B;owiAs{3=JdQzo31jn6$W#R_nY4Hm%Eu7=rf+oiLiZbh<~|-K~{zw zYInjQ^!?F88qMc%mEn1RvLyd+Bo2eaxrH_fZ79?Vs)=HTgfaBj{P}EN)!9dt zWPu04o(a;FFDI z`c_ea62Uhxy2sK*21Hpl=OFupH{oR_fqPtzQ+?K`$2@z8YF4ybv0@F5-W7d&DSR8G0Vm@J z;DBPUtXN89K)4u)R0q3W!=Gc8W-E9F5G)%VG3!*`*o>N^?mHGOP~@Vy_tF4=c%hFE zkN3`_)QCoIaY%cPiKMNRoV{dm%$=K_GAmQL zgX+gX_H-|M)gZ4X}PEyKdTeaDI@pmTo+u<2isKl7U1y*6!PbP{r$tPm9E2WE| zpmxt1EaZI?UO$XPRpPX?n~@!%sOaI(XtkN}3cF%NcN4*iwb}TiyHfmjlfY+|M5C}L zt8@21czX-Js`hpLn{JTqmQF#W6oE;1gLFtE9V#f&4Nf|xJEcnykS^&`Qo0*N;y)(f zQrF&VpZJ{Tc@yIvzbn4iP+WgSwr9kWoFE!Ai3~t2l3Q0!bk%a$Cs{Io{$ zhW(4l-It_)Y8eHJ&{CAoerCJib96{e?7W)f$fV}UZW4}&Z}H+NZ?n~f_X?ZZqV8MG z^wyTI+-9q3W!VTg%qj}89|-4VJ?%-B`>~6kC`H*)d~JOYTusVB5g5ZXlUh43!d+W_ zck4qS+3Kv8`}tvkuS`$k^sDv%C0p(5cjL#ym4Ex+W~=?D?|THn<#kdA-Day-CxW@h zOcidj)$8*$3t)mRq)c59xm2XPG`G~CwS0t2u#VK(p;5FFXB=6i#rIElV>KSPnn<-= zVB^GK5m^kx(WdcbywJpeqSd{uc^P4aL)%4{Xs^|w<>8Wmw<>Ju5S6H=#{@l?h9t#- z^Kh!vM^rNOs4FJ6`yzHtHFBA2RrM8y!RKu8@5)MPF{Y|(LUyKvOyapVSEiOAJ$KiU zDB+?EFr4@lU@g8-Ub1p4EtXEuCbMo*g@Wx1#D@BquG$WjsTT!TJYZOlQ)U%!0j|D7 z^xaZi@3AVIur=2gYT>zL)h!8ZB-QO2mO+xO26&4!rGnR>Q6&LW2j+o7zR4c_LWFp& zyk=M^Kg<>mxO6N{9r(W{o-&$!}j86!mQ-t z`0MkXi<7y;X}8nGSli3*t2rf?XPec4D!bdk4pC(l)YtBe8VP=h#2FC;VI=mMqsIl?J<#Kaxb& z|9Pd;FrL4txU;`2Iy@f=bM@wwTRbZZR}@$4sUL4FWmKyswx*g(NL=g12Nup(N`ZF@ zRx_0DVKJYtcRdF!5U@q81k=aQ15>Nw_v_?Bala4aJ5nQuQ0`GfN5zWFEVV;F7@&Fz zCq?)}vJ-@F&BGu(v2=P>Oeeo2|Rgv#tg;ySG(|mp*otezwm?JPBf2H7#0hMw!VkS5)HSm(y zDFt3^RTy!q&yNl(6(cm4{)&Sxs5md3upw9cbG%ZR4VNGp{F=l!BISrMToYQcHL0t3 z<(T4;bn?(VNfS%ug#3|gwl+ptv+m)9%P`9JkSdb5M?G>h>za~$Q2r0U+LpgaOm}w-r#tq<5aX680Cs-VR>9WjD~M6 z;U?z*KCbvu!EC94+6R&fsg!40hpK@8GR1j@{iZ4!>n={&m#@dNyvavJfnLlyZ_ezg z5v&O8gL`z)m~yl}lL^6^1Y>FoJ*#U&NBR{Jh5;mTjDL~DvCqwRV_W`RMd$Z3@^30S z2ZjYcg6IfaQomPpyhKud2Ib2w8;G3$iU@CttDF9e2-DT0G)y?>>eSo><#+m6ks=92 zAI=re-k5tYc7;BLUdOuj$K(j1DQGrJW0tPZNYQ&;2^wn*@p&YVijDF2PyJ(36?Z>z zltE%$iTkTabOq5GxyAR;+c_uJXUukYi*8`GxXjQhk zF3lEnW=MSx%?umf92|)MS4Bs|@RUMW}4}Soe+^tSD8cbkZd{~D;tI* z|4C-JJW6aH%yb4`0c+ls7K22lG)-<{B{^Jy-Y3r}=BNw2);x7=$%p~>Nh)n{fhKxq zxIfDhv2JS8CBGunH^T~Y^)fxK%|gOSi!Jr~Vyy@g0c#mds8l9gQ6(i!X~o*N;_HQy zG)z4abuU2=!^>x-7g6K2cqg+OIb!C!`bsLjowMQER{Ak|cfkET zKXV5P_9{=Y>jBkVi5SvTRRhVBZ6XH{x%MclD?YvCf_Ve+hyw_-fXGRV>i#pVbP}sB?PSPI#n+5Z5fG>iFd8Q{%%y<=0sHma_l1zpR$n(j);6cd! zfMl}01*Pk~RBPjQz_q!mkw$KAW2?Vi7gwa6eYSC(rv%Q(b*!u2Med62Kb#Rdr6iTL ziR&}s&wdG0pVK1qO~uSt(BU3!DtODUts4FzYp>pi8}SA#2okLG3P0e$n>gLZg-Es59rH@^8` z2R!zGGXhBBrfoj|_}E)O`#~?ZDuqcO(yfnI9f!->2(QGrNImJn(9Ss)7GkP8j5plb zKJKaX#QFmnvBrW}xlcId^Nkp3A?B-^QL4$sw<(3xV%w*Z zR0Oqj*vk76oM}dK16g2xBhCQF!+>;_RRX2g`z|x3G`=V<(gfJ8cDSXaDwmxp>iYwc z0?k>h(>(W7_;#7ozGmI?=VR90Ui52yl+F=(D~VSiC&v)|IwLQ!T$Lgd=g@L^JEZy@ zxbGXFz3L>^j*@V!J9xJuoZ#EY2j$x07`yes>=9MOl|nomj>GeojK?XA3W6LyR9B>{ zK{V=Et-iF{_=Y2sxMx{XT1x`*&9b7ZU0A`&QNkO8#&QwdTv`}HG50l}F4L`J$sQeK z^n|0DxmMi|a6(zFGS-Fd)vK|$X#cSSNq)ry>`c6vB`9}Cq-R03 zgoZ1>ch5i~C?PUs-k7w6FhGDJ{a#_6IT>tIi26tB668%|n2>Lh43U;&aG^Fj^I^saW$b0dnfKnMr7BL zIOh-f5FpY-6ecFm84>$|pOz=S>(2eMsCT3$OsKUyq!{)w9K9xYtR|baj~!x#A1&XD z{N8OY?`V9MZ+ZgH+G`D)Ympc~&Z=4Uyx-Un&vXxX?5VUBKpuNJ5!1pO#RGoDWT`ms z>c{ejDKfDMGJbpP@${|9yPXZsZ|za;paGA)vyoi+%6yH!^&3gt`2dr3gGFpey|Vv7 z23e66cQjgm1468n_f}mambSc;0QaPM(WdDvKB%8Axio`}zF0ke%2t}YiZOy%d8fUX zXfiJUMZ=cEPTi)H0fRtcVb?!V>T2 zI}y^s{VzH|#S_~G-`f7m4zBYmOA$qVvK%BDTGQ7}XU_PugZrwipm{Usrh_|Xj2IO} zdQp1>9Qdo4h!@qGl-&(HSNMV+A6|AW4W`iZ>NU6>ug#ZGOz2&@o$c*?CU~NM_4@KV zbdA0%>@oe^8#ron1Fz!;t0~@yAYgJ4SNzGm558%@ydSCyA*DZs>l1?jnlSTpFWPio zBe6nJaX+Cs3;OF0ZiXe)*V_)R?xAEtaQ~j(fpmbn6{TF#EFp!7pm)O2L|1Uk#`z$c!9q9qE}f$6OV02TOz4gLun)y* zg?9Sr1@l}1qRt)RTz_M^l z%aL{St4gHU{O#?6t~yk?ubB^37MG-<&}lh{dJ@}^uzKO>tCMqAnf?3DswXccBlGCOkK>r#TW;eaML#Gp($T$lt1>6JM-c_?ZJ}C zXpz`7cwS(95ht`2YY#R_w_?_mQEl&9Ko8xIK?o7aPt^t-QGyMoX=@H8~lPa)bpiZ z>fhHf|H61nm`^*S z^r~Au&R+ogsV!=L&I7AzBu(qLm*HwN`K9^oTbA|>yqExprFI~+*eOS5dY#U)Homgh zrTX^3w_&>^63px;oP1c7D{&p)5LqcZY1j=dd9@;=ud{zo?WnKBJqPuPNa%R<548Xt zSlKxkk_mQe;!RJ2-Z_N32xdA@vb~R(3$JXtTM*lKeN^g1J8K-Fjz!Y_cpia!k3w2g z8`6zC+|X%Y2(!1HdT z2WR~BydCOda<0`}gR0`dPn$!Z;TfHb0X28!MG08;VL;6tKkKYH4*5&X4P9K20@U1vwuD7Z_6+~ zrvGSuH_GFUS5;-T?og-LCWSS5lTqz-7fHfZoF^XrT)kCZdmn)m74>9+JAH4 zfBcw*y2GorttOVQr8L(AGSp0%zGr>+kvyF4a;fRLowU6(TT^k(bYY(T!!YWvWD*(H z%q<@S@4)p@S#=mOSj9U$o37AYwt1QR7^MA8s`WKSY;6J*4-^LGq8q+cVLzW*L|G^t z@}x>%Nd&A(xQfrw})JLfMnprSqMy`*dV@0C~(Rseg-<`GWhXuNhT< zezRm`NLgi-kv!|n6OD&3X}RCt5;k&s;68+pZGvJ#5xpx+LsvlqR)`LdcuS=uWn!x_ zCTeIZWg0~rB`c?-7%OCrOedz$Pa`a=!^MRlFK0O#9IOG4iT_YHJ|5e*x)9G7WXzA( z1;v-(v?%0hbGYOkN+vyE;)X(yqW~87X=V7j_I)J%N2MpGAtxi)S0mvVZ(cN!CQ}OJ zGIkINX1Tc1R7}7d?8Yx#VoX)URK{Wihnj)ZETtk%7jq?=5WZj+3vvd7N!abD)Y2*J z9U_Xb<(iCDX0t3QU)DJ+S_m66pibc5E9Laa!R>ZcO@T#2O~i%|9mcJCG+!{Cvfo~j zTO#XVziNWmCpkoTq3pCNHgx=AFu@0;lTe4Ebgo!hsf3F4VL8lq&kxVy(GnD?#Ij7s z`!(jsPSG}v_-?A#AFz7rUrXE>7TMrzWLo`KVbiM81t@G@{bONM zUS$XtO#nM!)n%!0G0E!4MLK4d#$+YaOl(Ke1tHpXtBWZ)Ys|ZlB>(}lO2FUgGM>kofG#N`A-IjvGgjnq;M+XdoQz3QKsDf%@_#266k|o zh$OK-fgSCm{s3m61**}L~`{oq|;Hn+gbK5N&5zXXPagQQj29RBgH zeiuMs*bOmbsAv4_I(3kI`XMObH16uN``JNE=lP0m2oI)S8GR~DQ4bbQ_kdp&qUs=v zBpaD)<1-+0N0=oSi1PMA6!Q)VIC~B7*-h_ts8sC#WHS%6UARHTWp+G-dDsQiy6)+ zBwS7I)zjj!K}A6{q74%W6%nvO^)j!Me3p;Vaa3i>i?Gsxif`S?`rG7|c&G`!L&5Wo z`u_ASXW3QVVoNNNn-17@s2d)5;1d1zz?~!b?ScDmAX9%oFy2+z?V`Lm*}aKe_EWuG zjyVcm4?Nd#ry^HBdkTkRsA)y5DS1kzu|-cstq(&hmCBE5MQ@B28dUpj@gEmVlp7Bw z$o04sX=m8!|IZ;8W}lTF|Ab6Qfu#HDDj^E?-ww=d(|u{=8zR6}mGli{3a>2qcgU16 z&kO`ImGb(#5#{2)K&J4%%>Nfg=*fl1zky5)(8npfLZLbI zdo0f+8MvB-+VZ(9Mc(qOTY<|L&XfdUA8la1o2WXpG-)JtGOs{}7Y>hcGS!}_kd!CN ztzW*mE z$r6xlK$QtY0WMDwYToO~p{D>5AlTaMYMe*^&5ppp7h701fC%t|^aVf!z@Qu>XT40H z4g-h)E)n_=Bea_P`OjiW#RH_b-bw!SLwQ*qD|dQ%Rfk!SR%R8{~Rl*yvL=VI)kEy}+KrgJZSt~D%sgu4n>duMN}7uD&YzSqvL+|4H86h&sW zQr!6(PSq`mYLq*o-8&WIsYVhK6lH9_`ug4GnhqBkX3*uCCy?(#X`z zPI{63x0rswf!U;?`EkEn^`{YvT&6w*gt}$3Sb?~bUa~`MBM|D|=%g{gxHdvxsOR;X zM);fd192tbz?dpSj8Idt*6cp~Q7hWWkpA{MK*9cbU;xe@en-@1NY10KgQl04n1&0@ zIRYnLR|=QUN`VKi`F057fEOgLM5|bU5jWuXx46>Z9=ODEZcid1ai!PkM*`8;2PRL} zjkhs=>M)zPFHin}fSB&c_U6DykE8=esH9xKR3u=8>Y3(24or^pX#TAcdbNKi*9I^` z(Kq627yu)5lwD6?V`eT-y>;ywrJ%LddJP|xdG}HAi;IAVclH}U%-Ep0A0<47{Zb<{ z{q}uc0i%(jM1>sNn7!P=3?fA^^O0OPr9~D?1XBLr<4U=5MV1;pQ)9oym7HRBG?HkM zw5=2AW)?b)8qp*BX!ggT8LFu4(b&Aty1{H{KCs>B!^R{F?W^Jzp<}FAgJs$o(+)rc z&v(YYnS@gAkx#fkt!>B$pP8Cm4bf*R1R(Lz(eM{14X0|$dWaD@m&+#~*JRlo-iR4^ z5{fpJ-&(2Hxmh^i5Rv{mM1Rr_|593i(GLH9i2kGjzCo z;r95?~3L!qG@IaJXGtxA*eLjC8-WC<=7U-Im$$5`vDcD{UcM4T1)z_a_UB^*b? z=27jz(&t2x6t)J}&5id&%!P$NX@@)J8wM}ES5UL*YupXoJa-UVQ*0X_yZ%_;D<9uU z7JPNJ4=p+S8g5x*&K>bMcJ2)-!o-{hf_Olx4~lYUsxO8S(!39;`oz31g(=~JA9)N? zdLVVWETI)k29`mYqzP9b zCZdf{Vd`3pmN!Dqicxlu%8FGt)g%>0$5mZc^g*YTauT?v9cH)cCW#cSF1&MDW}HjD zv!9oiau+5)J(YERawY8zHF0jbH>Vau+6$1Sd3qF^mPJPF;~=o86NEYT{}Gx-%Sxe^ zdyg<(Xg%QtTit>K%Fc)U#)pHo`|FFJg?mCZpy77-121U$3@FXX{EV%0)X54rA2qB6kU7gsS?eJeyt z84WKI^pvDkxKx|VttO0pBt{kLUL*DlZdT(y)CHl>c`)+>cJOfWC)Hrt0Fj=j8&c85 zk*lO~yXQj2FML|*(2i`v&qm)?m+Yew>0_R!s{3(X5YO)@j>gbOT}a&X_5yjBqORMw zlAnADIA?-s^v;!e!#hXB#%{0Kwxma-S^qQ09&mkL7gR^-s2%~ycMOiyc=3@b4F(<=o2);yb^1%5% zCq#(IOW-Pj{22s;i&&P8>H_Z%3;k`rCH<3^k6o~{JvGS1Kb&(p*Bh2WS73wzn}%O3 z1peiO@Bk8a_a29drtnnlB_W6JKse=#ia3eW)A~$nn&;VPDFjdHq%_qWB3|$I|r-X|4;LTk_QuQ1|}P3@^IW#l~m?se7e zv;~ZmYED1d@50Ve!c0X94Ll@PFL0-GN@jZ0$%HT@8QzJ*T3Np;!lQ-F9TpUa{E}Wm zV*O!)DlQ8aZJx9ojJ!{UDh-xFfQW|laQ^8o)y8`yNs2O+u=nq?g^GeCb%#`f(H`8q zbZBLQ8Dt~4NSl-#t43}Pk)%@jZ6XJ~;7Nz{bt1URpgqJ8BSes#Jx&o-Za*6bRgiV2BCF93d7MAb2T z6X-b%O;@@yqChlIg1$1c62T+;=7)MKNsLy5>F|_S{EIHhV!b3tM(kbvG0*%2Bp>o% zKdJ-oRxkG^TM!*+`M-y)9hmNNBm#kE#baY0M(ZR-bz~swjR)sF2*gE%(OMq$4TK@e zr$c}Vgho55&-<`BHzzZDmS2%aK$I!8xIwoub@CC)-L&0{WDZ7Us0m5_z1PbA4E*zu zCVt)M5BM8%kld`q;9WnS-g$MHEK!}wp2=|fg#!7Xl-1zjM zpQG5I@F^BW1<)?y^z%IaW)!W_IZ+-Y6uvn(f26D{VY>gq(hQSS=4IKj9j6l8@*p#i zn+5(~%5B!~c|B3=6{_M)DD`cFK7D@G7r$itB1#g>^XYs4i~jOtNN)DW_s<^xHaFX_ zK$WTTU|tGmtUm_G&C&<1$w91C<@>oM-3>|#Rl`LQ6?twIU)8EB%Zh<^5q%XoRlinI zv(;|VZ~~lir^|Q~26ve#>!uOOkBLtCsvNhr`iEj@~Heb;dl4_O?bVx`Q!5=6r$hb4@!>|6Z8e`8UctwVe|3`w@xfiwtiR zYP&W1_hahMm+nchjj@nBmc6WBM*LR#(cZns@qjdzULc_8ja~!mX;PY~gxQ)+vXk}q zUNbGLItD5Rl&}hs^?9RNmQowpk7)@T4Vj!1rD7jF*sV7|==2!7gdN);M^NgCbh5|I z9M@U7Hetwq6`HU)X(Xw8LGY#E8PeW2{~ZUxTLQEGv`DJ!N7CFm!^^(sir%Q=H6%XRw*+QG8C)h40~LxO zv(J7s{i9UcDnicbPoSe#)BPf7X!HZv+pE$wk6FbsM0pykzbX7UVo))L`+h*~EH z_EuWFH6A3}cuXS<#T8{7`RKbuy9$Dyg`PJ^U2RDo*|iN>O0O6%%PAwb9mBy&+8Ol; zegC9h9IKe;QZg$o*vINJDt;giW)w#$!DYT{CA}4yC{E&SzG}No$X*mBwhxuvXh4wB zIDtxl3(cyKv>ihPyLkI|oV0|;BSyj*oL5ZDPZ(`7h2#=g7u$uZ&hzkXgzP;B401R| zK1;e_XXZ;Z_2;vIO8MPJ3gEwY>lafn8st`d?Z!7Lo%UlcHtxYNHmIElJ;n2R2Q#r< zBkJj97?0`KJypNETwv?|>au*qK^ zN|=GHk3NlL)9jDx^f=o|$3<5-i&#JUax_`|fP~H+=lzIHxy!|)2QLLPj>I!ix1M6_8r!fz!BR&|_vJ zVz-q>vvc%}GEu%$W3ExYOrDsSLYA&y-!W+zh^aZzBdkJDa|Kt@LhphmFlz^o|51DY6$IUrmjyCE>6QVXK6p?ly!2+R`+l&p%cC`S5T zqj7>zigUf-gbk52Rw=O`ullluq`{lSfe3*f(k{^U z+=%ou5*}^LXKFEy2(o&Z_6Nn8p;*u~qHy0aK|_O#EvPcoTiEFg(QTgovP8ad6=M77 zoQ_;&#-QUkY)NX-=ixL74@JH5(mb%42+?TURy(keDaB9`iG0K5^SZTATJ3z#gXp4L z>hIVO#YD(p`$j~isuwZ3@t01^c?e;u!<3t*l`aNkD)N9XPw?4;!K+KONN-uV==aK{qBpd}bv9At zv_H1IMYqKLq-XZ>4EQH$H*$yF`~;12+JwYyq0z$u zG@ci!0rz*5ESf(2gD}-Yna7IcR8ej8CYUp3-Ae78(Uq@Em~AI}blV-G%h8rO-e~sf za685o6)tnTu)=r{2${3$`b#M^jRWg$-Ck|xl2uIaBVety&CX~L*_?=Sb)KS`_{ z8Ko$ckDUp3r+YTrn<$Mbqxwh}icE`VZaSEneot^(Pn7L^_p5e}PllPlLp1D~lx0XL<6a+Z!OFrfU7U~7} zK478BT=iijemFhw5A_Z+xEG<5)zv2w^|tYHeCK^hkE*^-s=Lp5C@z%h$4Rq^H!ZYH znz&eUo&(NMm=7p*62PJ<3Rsu^DY~6}y!c)S@;u^_(3e~&njF5TxY#5?8U~`-aB7A| zl-X);HL`MFM0xX!#U-&L>gEoH%2uv|p?s&yl?9y`SCd%z!$zgVw|+EiP?kYBl??GuC5~ z4ZQ7l8b6D7V>X;4Knl4X#|n9OEIieU&6+iVBTh2%41{x6bx)W;Ms}|q-!TLrr$1-e z@4zZqrjs-)UfdPd&^k;>r|n20;*)7x)okZn`5Gx0lb=Zu&RG=4>DC~<|>TeQQPc)t< zt15g(#j6_>m0Y`e*p%dmI1@Rmf%RB5&zwZGV(vHQZHLAHGP}vkwb;1RAM(Tu0GKy(8%IozWZdUiWyKa71nfbBZhf>naem)R6gVpOsML>74q+Y^fk@Kzd z^7J{IdQ_f`L6?+xs!z03=v$9%S3EfS8X`DXI(uBMSa`nuraq^8-n5@6K%IUOg`VIy z2h37Km}Q(jHLz5h4-I>jRq@i&#C$k2NgMB#w~%tO`;twj-MR8#jpqLj!$+8jg9QOF zX(0rlc&6jr&M5pdfa%lS)^thxP&=AQwW%k#y={A8K!i(THCMu(w)Cy)BV004 zaBzSQ3M@__E9qk&99ks5qQ1P;(xwNZnYdy*ZChy1oGxYI(vbia7`lCDoI-A{9vhNf^&n(T{F~67|CD z=?nu9;Tqw4_2D|gwUkx2{2s?To< z_s^=&KM4yuE7Ie2Q%A)tv|)66Cs#@?n>l_~V?!*52?*A?*i}*hk7x?>p&adx2e??ZAi3}XB zR3-Ilch;ZtIRdJcAo7M*v(!Bsv$SOIJEil zx$*7Cf~d=caKu!x5tD2okj_0-1I0ab(H;+ZvKlpS^fkn^Cz1x-DnvM%N2*=~6QmYH8J>X?F>&<@$-*nL~t)#=an|mjMGIjn_3k^&GLA^h10yO!3{DM z5;7txY3r5^Ika2LbRrLI)#TzmNUB`S{xQfti{Y^?;w%qm zE{xrfHCw;F%shbKxttl;2sKV;EH<&-%C50T>|@)6CS#)b7LFEes0CdEEfE{{!hEki z75d&_G|Jt@?)UJ4W^}4Yo1J^zq0Z)TJln4rGrfU%7|g(k*N9w!$av#v5|Jx=7?Z-9%@SkcW$~ zqVSO~dA<^&ijqb8^E8GJKK3?o67zd#^IgJ?Lhbv~nGNvWf9{EPwmOP&NU@fy5q-A) zp)!DHC|Gf72$- zjt7I1M=hF28Ny8aOIgDd-6WG{ZjSffh8rDfObnPfgLixi@6HQ3;m4h%0nR2`Xe%#v zA>lQM;ij8&`*=J3--7obxT-;WoL3p7E0Pl2?Mkno7hXqqf#}RzkH3NUZb1x?=nN3u z)!P5JAcmjOncpj(|A4FdT~NkhBXZ4-3()|-dDY`P^i^Hhyo%E8y%p4iQ@}H>xITw= zMZr~?fSum1{zEJq+OD7+p{9d=z2CP?kf1Q25Mh^o{sjO2F$A{6;9&y(wk7uKV;JL< z^)Fju-`}Gv_#-30e3!b%@cWk7U5wCQ?%H2J!Q7_U+9qOkOwQmfsTdgTtpDDY317)a z?<=O?`tH+{Gs44}zbRQZagzpHlQn-SStjXhypR4WDt@0>fK9t|N;?hdF?@>Xh9It2 zVQo;aNcE=YmUe(GvDq^#$d;IO%-gq>0@qt&9sD0H-o&qLaeuYG!gBiTjx=VX??v7f zJ?^Ch-wAXSiSbjtk!#bNbTQdR)AXtzE%gXh_tK|<=+${ug78Ww!e5})=B9$o(eH%^ z@nWkRs3GS2Qwd``9i`a_a{74CJyWE88isxpKp29Ct~n5qv1P7^sbpPE{!o?<&qyRg zM|4R>-9<_>UO$v~AkMTd6JAqA$2dv~$phCzgQSWPhuPJ}WC;dow0t5IUdk{>Sl?81 zRYCcfXfS;@ZA~!_URWw30p4Wrv#=MPYKF3m0~KZ>6!i$XPFPSoMqXZ(D5Gd4+LbY) zT6&|?iijlCOXYM*LuuuVB7~k;I#@}|z7y=kPC;9cF4@pR|#As2{^`ehs*r?~%fj7`vmIol5&p_YZ zt@72>00Ocu*I+A^9C%QQV#{e*k-doPh0xOzHZhzIEtXNGVD80nL{Dq*1bnz0coH^^ z6+AWUyLCLF_Rw+_R7gpBGCj@s@VTtOohzrxSsmw~lexFZ_f%#@rL4Y)u;FZ+A-8^ zykceM;Z7Co=fmv+eY2N)o!V9>64=HLib)t)51Wc~SyRrBD6Eyjv8kPo z+(oqOc{eagPWg~$npRAF%=>yvOkJ)}d=yJla!f3XL+ze7Lv6?CKveDU>we!f@A*|( z36YV}U0&{$$rwnm9swvfvkBRPyVe;A0En<)C!S#f2DX^E}EgjLP_5 z?Ako-1}XJfBngo@#o1kyC{0Aa5g~%bxr<9f?SPMAGp_{4Sa`^DuBXDMOQJ2g#lXjK zQQpt2d6sGr?5k=-jU3o1&NLJr@+y<&E~Bt8@G(^Tare%ffZwPz()5-?RCu`W#O1p% zWdiM>7+A7c=v5mvr-o?5pCL2LIbXYLp;AjFyzyA?iq_&Xyt>#tyJUk|9ND6sjPEPp z_xQ&Z#E2BoNu<_%8qr;hA3mHYc!ASr=OCMS47DO=xkmkX1N+?>NPW|@z62my3o9XeX+(=4RP1-?y2tQ zi;b*@KM$;=vlS?S`~)ZVwdP}R80nq>eRuLU(;c`#+zV+)-<{7N(s%zs>_R4)7F{(SSHbXs z_4YtrQ%7UZBM*!0>&y#2m!UKQeo~Q=8-Ro4dv) z!-g~68pAoo*RGQU@P|016^N^%+Yhs9qb=lZwJ5`@Dsm|RDh+)Wy0qT2e7Qc$(0ACM z-`hAQ|0p!$8P|#^0+cLk>`C1pQyyCv5AJ*aa@S(}HcbI{Z6FMA*QVpLZ6c;7T)NZC z-{H||bbk4YQC-tvy{;CiO*{9vx=xdB5vPI=G_~R(eZQ}WwqJ&E@p92Yo#KpRoc<|VrGK0b^ z8p_|A3MfE+XBp;q?wzpL2?E`tT<|SXhruqbNgrWL=|6d8$YrBKiCllIl{%T#-);up ztd+8^2BjC}QP~^)wQzIv!s(}1=3=cDP>5izrd?2UvzAt0Rw(sRc6R@UsPn7@MRgO? zQ=%PK8XYPXw{xKukt4$=qy|FN+0ioXw4pSJ$svm%!aQMbuFgWYD7a^!&!;%!p7u2 z*K4IDRGnZ0L|P80msnH`$pNG<5g}`(HPK%5CIQ%i1mqROB3$^!siv8#C*iET9PRNT zkhN0vPptoOtyEmf=zqUf`e#$p>req`N?uP(F^%Nr-%d-R5EsA>XfaD2O>|?4!=B#V zC?VDIQ3t~#lcW|m(FJFgGJWp`3-&WHTjwe>+ykbi`YY!3I!!mWq^8MZzEv+$cWv0T z#-Li&tYgf{$o3K&Th}{s)(q7iE|X+6$c8!;G~TYIZDQ6V90U#u?z#KEPdlY!fvlx% zW{aU~L#Cz7676p|=NqqOuQvlZ^(uxe_q(q*19ci?e~oDT=Y^XXDD{6G6G*~(dZaLA z1{o7j$iBD-nU>=5;YJlWnFg8)ua{=rAw(UwCAsTqshD{#*kWK>3bymbU(-^2DPguZ z3paK0?+BQc*D?tD*w$%ElYwa|l3th1iu-uhTW={W1{P~NzCPWFd0Q|R-}H3bb}yqI z5+v1T6b6Vo`ad>@{zlZfK_UDi>af!tsW9$b-f+(6z65+6-4|*7aS4T%3PB;j5QEKG zh$XKu0(ciVFrPTCjj@uOKcJyB@xtvLgSii^l@?3AA^){j`nMn{RdqAbU(YR(XQS`^ zzn@Y4#l5p^p~U`^bB?T5dY`zfQ@HF2CL4BZFf4S2P%AGKXM%mOIgpI3j|2WN_JXZH zqyx{b4*vWS?H7+E$9aNBX&uE08p5RXeQZpQxf3b{qu7xuZt{vKS~If z`i7{(>6HKKmV2kHTK%td;NPEH2k{9Tvn{E7be!&@8Wm-95AtwjgvlKe)q<9)nuus| z1>k&e)6@hyi89VkjrBIqhnW$)N}St=W!6AaJUf%xsdJ>ZPzk4!7IvHz?(0&C2ulOG z$F&7M3whktj;m2~64*h~PEr}tUqJly;=y`OLTF!*3eNZ54q3F4JBqAIG`EUH7at0E z;!4WuORJO{E@mU{F|gq<_IUi(Oh*NFB^Lj2QB3=`nf~9+Oa7KkSOsY?(T=HF{^E>6 zHd=3*VV!XB@vgV>7Ec*5L)F4m5Vm+D-UK(zaGk~VM(d8`hZlTR(MI;$Eln6$%&ME! zkY-pl0%21>9h6Tjx*qqr9j8YxL9;lyTwR4lo+JbIm=xW{`YQi8Ai0txQFNg24Hhpa;r;wU3ruS3hj>Hq(<4vm~7U=(9PCwY~0y$;Ps z5zi5{ybM`~rhjwE07tG~{dH}{?ql5HoMvyA=3p`+{OL-%$#ItwQ3xBKSc0dxrG>Aj zxB)ngQ_a;vA?p1h6YH#-x~Ebv@h|0izN zBWo3$b8Cep_3QB#bgp4NH=V-ghOu(RlgrDD1I^~utdaOglSW{B8!KdIV9IaHF3WP` zpPONjDZgRH1L0VbsF%WtI3q91{e4 z^oP8RQ^%8Ckq!Ud(M4}p1GB`-uzp6OYRi$qt~2b5aR*`zJ*iKsWoI*!bq?sE}f7K?wRr8 zfNd(c9Z$D3lr6sl>I0Gl8Zwk1tmbE^fhQ7ZOM$Wt_G%Ooi@C!1lEK7z=|cO5;v)QI z1_6(zL5s(o(lDEr2;bq!;6Zs9$Bbdp2w@rHhWlOT(^5pV{d$2?d~RJ1CY-oKmpMa$5H zo^X{Ooxx{>(GEumss3xRp5DWS@hU;i4lMgE-1L)a;|*2ur8rq!>bnM-m^(IQOST49 zi3UY==(lZE1=%JSk0@3JM3M@LY~6y`Xea&6qMIQ#{ip~797E5lOt6u~+a53qEb;Eu zv-`2{4zCyM6~H6Q`dKt~M(;DBaeNY4>s-y91zXQyN4*B{)v#y`L?j6-C>(pxN4lSl zm(oKP>pR0)3+A~9>2aRzeP+}pZIyny{6N)DX!BXB8We*TWU;-eXz&`mY23E#tUV&9EfPg>^K@3w&ogTXtLHsT@ zTv{Y#vEHcQLWELI4h^uP^o?;BB`zO0%|W42N12InZXKF{7>g``#riR|uYw-vxb%1? z99U*%wB*rRkc9{fBgJ&u0ro@|p*HrSd%NGnTJXkJgh@LOS3u(1SDJHBCN>bs9ls4( z#oMqGp5W^1Co#N|Mab3-U2v2McZ5;2T~VQHVnjD&UeqbP44FuM&{!sa;(A_`u60b` z78}u~7MK^csce}(-3C;qU}mD{Qw6|61RJCEe_G7_^PBWPTRB7@Vn@928W!RTb?On4 zB)M5RJPKCAfcrA4^Bnzwn5QeyR>i*v9*8&2x!7i?QpyHa4!zYBfPX+aMH*4I!;0xw z%vTl9XE7e2pVoMN8=aa9n8iP8l%d~#q3g@@_4HemerRNPwAoLpBEAB~^~xdtlkk+^ zze($PpZ}pu^eSoA0I-||u!p(X#-)=jCE z#CiJl){Qutk11s91|qq0aB#nxCxQF}PGK2K*FbPs_o}ShtY0~OEr9ud%zbw})%_dy zaco&x*&$>`l2XYbWM-2+vS$O4%9a(!o@H;!o*9+QtWZ`WA}c9bh3E4nf%1Uq_Zm_ zVs8%!c_05|)oL~L_6d85dI+ReHGQU(c_BHv@SX|{^O=bisUw|0t%_Q;YC~#OASTK{ zU`ua`iGcU<0iag>wU|hi!cDX}pEtzr-qkai(sY#dpUcA-Mzu3#Y0UP;8l`cem$AP< zO60oiF1SC~6K%r!`&K`P1GD)%L>mM}Clrzpe#8WPw5~^!8-f_V!}_}-%A-jdVg4KI zXzzRXk3EbfnOz%mR33hKpFfo22X4y|ErQ;acHOo(7)A(FUzU}ImPwbPj*POUROyb5 ztz$NPdG$-=1-Hv0B^K%Sm;2CWiHY!O!^3Me(HYx|jYF;uwLta&&&!XQJkYJWO(3&q zWl#jS7NlqBE8JFZ3g|MFcuuuVMixmHqPrfW=&cu!Zh1^Zcw$q%nf!3jsVJKphMR|u zpL{29>#!ikc9|?iW3SsZuX6iyapj z^Sg@9oiQ3^6k(nw5{5QR11pz0`cg#e5qp}xv7A&exm2~`vjgb(%W9$mie4~ToqDoM zq8dy^Z=(YQrr11137N(H-RSw>UBouAJ4p3)?V2IF+ThzZa=90F@6Jg&8Yw5CUpcHm zhV^(OMgfjXeyWxYm!N?|B=a_NHbxbF9d1$(#BC|4qM~G1f^{^=s@KR?NTm^) zi$^=c_s@HsF1>i=t!!`en1u-YgRzShM07Eo5kv+pewFW-Ea$40EhM}Z^s3Hd6)}!P zjws0DUv5627Wawd5pQ^8XZghv6NM_`@?y-gP+^kb;%fq`!?+X zqGrF!v|w1zw-3H1$g^#tRJ}74N7SR__Y^+Tj5!SQoCS5w53Ci7iLXoWE1tkDUV&m| zZ%7#xeI^?53nj51Bz|{Znp1fGPFTK%^rKa<<2)ELBd8c05#EJ zE11E4pK9RL|7jDrTfMpMKL`pgJv*lJhBp)O2ENgu%4@#+-2k_R;J9 zV~3=~8c9+?xEL$up`uSol=6~w&aZPAg86VB)Hl|{S4R~~PfF6JMg*TI0o)cbNufBV zx-+Xs9fk5Q-FO1*0oIAEu=b}gR7Q%Q6U7M*?AB$LI@v(moF!{MrkBdfPU0UH3`8@j zY>al#JlL*o+SpE3F$*XO(P^Z7)op4%dJD3#WvRZ9d2qAfnh@%2iDtwS#qkQB8?And zfYh5TlF!Y*+t}{mw)|)haQYVZe$D33_ZK}_&w@yvv(6xr2iOxGPh{IJxJSOQ$10sQ zyNGu;W1Nhk)2~`ALLkXUn5azAAF?N6X5y!cp>npuNbaX)msD?7A`J;U#%2w1Ta<@= zyN|hBjh{TKO6>j;a9gS_o%evaEywkEZe?oQHMb?w0~^~^MtR8tJL=7QBwe{E8(UrV zr_wK@t@3lsssdc%VqTWKwS!%<&(=Qo=~0-O)dNQ$nu$Lo<8vb=#QAvEB|a*YjqUJh zOS=8QY(6PG_qqXx5uJ=ikm_PVRBMh&WgqFC>M=G_H_JC!8pJP1>WUJN<5=)qMfNCt zDayT@YhkRV*}q`}{0FTAP3ba}JQhkAYFH#MWAkYz)25W6BOY80Y8eb*J6^hNPo%k2 z(c8LdPc%ePGz9zy8)S3|D;6J>$XQ#PwhVo#I8ZX{HRs&J`DQh(^wDxF&+ywD;eouW zH88?F-ow+x@O=a|;!}jf$47A;jA~oNl++4&H!i0l^ZH)R)Z=Jhk6FbODOIGoUVBFct732f)s~YJ7Sdflg;bg`>$EYWh;tM;qr@(#m8Tz2ssl{R#iYIh1aH8E&JhIZ5 zrAK)4GT6C?b@6ELlvE@bWt(v1kL!-HH942b^8sHSE_TPt=Ht(Zgyqi4|KFKAwqH;zlE zr$Z5=g&h^9?ZREu6HMnfQr{U~7+gItTRKcw@O=ywf> ziSK`{yzZENXiWZjZaRR1>^aF!E0uOVsI1m|RlUo@;o`g26@|jO(A$9NM1*u+FjGdE z+1pl)^nV@#X7-yoWamdV`FS&jF>w(Je5u?8!yNI`-pg_sn6p%~>K<|ba9?;lD zUN3}nz3g$A7K~j!d1M8UhXZ4e^z#0?CRF51j}?fV0bRg6bwBQg6Amh3l>87A3VLtD zXFZ~nB%+*_m=B5=#cTJ|#UD+}04~Jqo&l(_i!%6?px8d*@;i;|iu{xL^MMp1 zIuZy|;)#*@AZ)i}kurT^8b2mReT)<)y0;R_%qg1w0V(oHVd*!BF|ML3#xkFf+Q0Or z)j19_v!5hAA>nxqON2#~|GYHLkf==V_sE%7O}=DTwxzS1!F<0SyXD7>o3*;DE%oUQkMo9h0f;I~+r^MYm&(LA_2Oldnq)8`OY_bO zfqbGfi*BIU;?52!ti(Ka7Lt`H*A_zm7Ih%( zz}i*+Fl`54;s{;oXissx-goj*W=F1LYt#&z_TCI}^c0J+1DWvJrZ+H6?%jN#PGX|G z!2aI5n!w_{EE;WdaJZim8%$&(SdvbonBQX3$VeO98}OselSmgopH!ZB)XLV6fe94OR#{4B5r0zeJTi7l7`Ke;QRLd4CANb%^rjxxc`5)9-Dc5})U?ttNp; zVK2`HfR*iOy9sR@hnv~;Or`r$U0Dv~;GR=V89b7Sj)9-aj9fM-_^-k8Q4OFNC`Z=7}6zm>(}!a#BbjPQ+iG z%($**GF4mf^i)31BXDo*aj)NXZ|sDiJjx^!-W7s!>nXo2m>#$8jqfYl?;$8Zn9KbP zuG_vhG@+=n&3og{H6xEW1Ns)*}$@nr2*pNaAc1LXpC;GguFgn7piPa@D3nI%_DgT{EAndsI@mTgU* z$DZ5^@0+!&rL5=5a)`s(wNe5~_;!;>)f1Jmi&oBu1R&V8^p&iaig(PgkMyL>N(NgP z+qNieM;nej^&#lDJapMYrr7t89s%cOpV<(QrM?}SM9uu}1r%-AT46uZ_292wVPNIB z=@qs|NwvkO2WFI&OLN0dwKfP8I(iVjxFQsHDgXVx8I~rPb>$gPLKPboFwuNfj8S*sLy=sTc~rf zLxn>E3kpr@z30pa)eDC;4^S@_|8ClaMmP_;o1m+(@YKm#VUrtR<#;l!$s`<^uht$* zT`o0oFZznl#QmEu#$~*30Y<%r5upWu_gS;vCj|&_B;T{^jOrIUAY!3#Ti9UgeHyl6 zGq7m6jj1ngsAg)Ok)bp(Y2Zb8Kq@Pbeq;HtSxmjy1rTjWO-fd=c;gLsLThxF2R7sI zbUsxso-sRIMH2~clsJ7L;l(L_i{i(O2(FSVaty?IgFp@~0%J;4%^jt_k#%?4CM8F4 zHjUHPV;-(H_h@+>)Qg5^E5SA2uxPug;0LTeKE`o5fB6ai2@quu>IFpc_}lP);Zw!I zA6Jfc3Nf^~cDCAFvkSnClKac^xeHKe61s-{OKntW5@bdR&?aC;nGWg&zilgk_ZzsQ z2ChQ&A_6S{RWInGHYpyS2SAj4<_h{rk%e1gC*C5@+mzl90bXJ6h>KTGj(Z-?4Ni%> zbEKlzKWL~hKaHr`Y1=F8@6?MeMtwn$h|oZ;E(lEuxaxKa)QfhucW>w9bXT|^2JTL~ z*ow0MeVKD9YaZrz=OYKPstSU99!WpTAqGtOy_841h+N zVVChOew+^qId_1;LyX%^L7KakgHFVgg;<18NkpJCSo3CZ)p^ZN4uOwSSYHW*ULYJ3 z$3A(cu?+9kc}b9-z-g|2VQH-8bPu_bW zTcykf#fE@JVA2x97zQ_Gb_Mj$br#1tFYWmBKd^3NMR2CRdlzUwS#RyNREQdZbzeua z_cN26JZxgEn5omh$!|Z=)>={e}449022`VtVqAgPkt&fLz|R4h4RT=V~lno zNwM09(6=>d8+nbgFSNt%Whe<2 zi40|}88O*E&SQ^w1NNDL>l>Z(-UuZtw-soPZA3Cm&vq^?#VqevM0kx94vuCm5! zu4N*x22k&?&yHlMq!POM8DDhA!-y9Pa>xQc{SwTRx-OuVxtP7(%4DCbSuPBIn1(iu z@$;WR5m@S%9A50Gx;MicEm+P&S^7DhWrkZX<{*CMGGAY6UGG@w^ls#9pr6` z(k_ympZy}DVcSzIUMLuqrOxG2m0uvINA~Rgxj+KNJ|WELqJGC~;)Mvi(hX^QY2gX( zGIbM5yP_=lEP)ThG#^@fUf+Dyv@Cu{{=sFLha`4cB3HFO2#$vH3@l9m#-r-QWYTTo zvXs&ffPK~gO4FMc(B|==irt4tOCP@Gx^3JKo_d1Hb9*Iy^H+IpLJLS2R1nW*D^sl= z`*7}T_v0F#8a>{^l5gLZ2Pj>(eR4NjnPyHi%*=SS1C6y-KxFm%KB^$ze zlkn{y8NBRnB#wSJe@ls0h8EkkUO2Gb&RaHR)2IJau(3HjfHw7Yab?D%-UrX2ogyf+WfxYz()2`hP9*+~t$| zcSm63DRBUV7f5*dnE>~wNvXhMk{Lpq<56%drN%NK@`OfUa=cczK~Xnn9d%AC?~oEU z@p!i?wZ@z;Aw4Uc`E8{@JnvK!J*6;Pg)~jRp`zxF6~i;bfB`2@z<0wS zvm1Mcz8%1x&jwO2%ip~D@$1*+&kfd}dECPERxx{rZo(-pb~?b8u@l_D_^R(_v=Hg( zA}R!pubOxC;fUoWBKBrus2$C!*MpN@Sl06eT>gE82RgAK_e z^&!VV5=HjMtZ+d=gx6&#d=1m!%RwJ4NfG9FPl|rl@REdAeq>tTF3CiIq;2-F*@bT9 zgiw<#_8=cZqse=*-W(SGUq%F{GS6QvXK*_>Ng0xvu{FN>QKtX~9H&Fx2Qa>tuJN(u z)lsxiX9ETt&@^q1ua#=-FVrlp4I6bq&6gi~GFz(4)Ph$whGM`ujLUH$JP+sEsh{DQEwWZT1F=m! z1VliFXYTPl4BOc+uk^Rt(e5WEP&;Y`F^)ky`n&Pf$kc!NEk1i2U>u)^7;sQK3YMQ+ z8J-Duj-c2kV0@LCar|vNdeb4B=+7CRKQiF{@%Vb+;-f#bqfw9W3NC9cQA*a@`z#YusiH&DVmCCz9Wxo1ZFg`uSFfU#Nx3sN2p z2NBOfNVV02qQ>I{7(VPeeBu`x%R|z3y%xVP8qu^;RZQKJDeP_4ptNfZ6UU|1cWMVt z%R0&~p9L{;PklM?>fymqR?IDgf z>e9#L0S;Tc6~x2k(djpHG^@(p-!L=cdC>QtbQKP7J?teEET|gm0+(P*G$cpMe|C-3 zBqLG&i(}frOiP&{H2ayIGH7Np3Cfsz(qb7d0MlYApZJc#L1bik``~O95dUzRtz38ceP7u0!&0 z?k@!AKN*kzPCfED{9t(#PWwYW+GVBv560skGlln{ z#1no}Oa50l4GM$YV!u&A^(Z8ljGLcH-zd3`_0+s?pED`hwJmQ!)Wn(q>?y9pcWjA% zP-GvH-b$7mFxaJ+y85;zgzabD%MTN)FV42V(%B@FTHU#t_{=R&};spnR)`~Am4Ob0L+!sO= zO%IfL^%wZB>RGgvd+d9)lC7%U2cKQTTRZ*v(?~~hjdrVp{nT_;s^uHq)i>O2N?05q zf!z6+{fGBmq}5+|M3#qoUEy*%0~7*3&|6bE^eH+|{D?slmW zwYQbN6-sgDET3y8`?4H52*c%jKXS)%t?;1d-M*wjq3XD(VKRmipP`#3X!`PSe)!0c zuwu~@U-*}0HE#r78QU0ACpe_fLsB|~ib`sxUYuA=g8iLp$+ts~eblA*GqU6MzLg=? zmSs1wd6-ii>qDgLYvdWy`vMP^62LwYC)szkJzS$1JBGWm6I2T!7UUq0l;lyoP@~?b zSnOIDiZVj3pnJKXDxKhKOCr`Q9WQhN_#N}EF?sRCUSJYA%?fhNGjd8amBMZMH{31A zwD1!Wv&+W)g01qR%LXWvW?n||Q~>Ih*eybR8KEci0DQ-_FNw{`wesr_>HyWkq{(7> zws4Vn-(VU1@$zgrYH15itlLXlh`ROrYT=A2wmq@lREJ?iX9NEJKjX?;FLeG3)#B6l zWS44kEARhxwP=5MWfxcWhic((tF@g#{%?TqJ?Ci8<#|16>K<3)h9*|Zs-@06)-9JB zRMP+lWq|SLE;YcIVY>|cRmMZ+lBm6tAkCgfzH0}E@W7*s>0sS$%#i#&L3%fEwJn?c zbHJqT^Rj=wgVS0+{PB%&IF8da;BG9-JJ&;)x>A{_GlvV~!H+HR2)&n>nl&d}PlFxY zQ@xFEra{1+?0pyK!Y#{Hp1EqQkBgYE-*6|xdczstYgcV-3?Mbm^Rc-C8K$kKkN4S{{b=p*0NOVMsG+r@&ddBqkladtI{hU|3Aa6o(Ft&4!^F zyhzEsOE}Qj} zq3PLDEs+)Z^syuyjuI~{vdAW+86U$MEYf*I`s{N)HFHYIB*|$p zU&%zd)JQ)n23<_9WL^`n7`+uzRHJPbN{01<3p5Q{%n$OJ&k4CE$*Eg^ImiFmO6Iis z_1R)E7MDGk`k$Hx|JPC@dzyywE7J12hM00$dNtr9mJ)d%ls%|vaJ+LNq&^1%t}K-0 zAQ{g($JAk4jLHwS*gW5wOa7Z7=Bu3a8kE1W7r3I%yYlFC0vrOa93DCn{(TwG&lsGB z<_zpI(L`TB(|{l+au=6PB8eqqoB+TTYKVCsc1YNo;F=-JmVEvsaiH&YMSVGY|nqo z-5|Y=C^JbrqDpKd;2F{XT<)$}3eN}EW1HL!D*jiv7?&t7H6HP&+GVy3hq1zJ;H|$L zpHK}ETFnuQT@6t|N>k|X8=~T6+a13y_GbYXwkshVO|o{&ugk`&7}vG8&u7ecTjah)_U<@CF1mp$}a+xdE&U1(u-nmNzjZb_n<>)g6_#uuDYcZl- zUJr!SMGC=E__TCesToxY;X=i{5InvI#%^KY~t0Tx@$dbo}4hleiJ{WQ;U zz8qY2PV;@KcN1(EhZU!!42Z7nbMn4_gE&pS`x-XHMmV+>>Pd#KKi=WgyT-!gKy=h+ z1h5gO`SR24;-4xZv|Zd&34aIY z{O`u6rx)f$KGUeUh%AwYZ6Lnx>)t3^O^%1no1`E)%!*PDj^u3cC!)i8A3Fk1sD3MKvC*2qWj(mpb{(?MDZsw7Froe2uAL-4R!$_zD;GA*ZJ5*r1 zXm>|aY(OygPvW5;;GCaU!p*4NEx)dh3t}~Dd7{XX%w9yJ2Z-7Qa88b7&f@13tSwp; zYBK8tg(w>B$3lenEgcfo{H7(_Q;5ui8GmTWDmuqu$zrI<%$(C*G8SsdIG$%nBx|Bt zvO5|E)& zOZLQ-r@zj5A-+}5Xg~Zi+q?XUcHvvN3nzH5i6_ru^|P2!7frtsi+3=oOS^B8;p!80;BS)z5~Hh2c}*c^i(PkD?FPJ|Yi-(YQJGybtzP3^9!Aj|{)0lKu02@g^yI_7+5CwIUq5h7wm2hp zS;o}D*kB5P4fo@!dA16Em{~>NWI!S6ZopLn5K*3L)CjA73FNxh|bm z5k!LQL4hWuwBy{c@EshiZ(p54jWUy{XUnY$l@neB<07fW`m)lxW33e|ilzAtUS;b) z)l})9Hxy(IKitqfSb=e+3AQUeBPg<1xWQy2VZiFeRf0STA|3gLD{cFofR)En=ALjh7kNlJpv<_o#+ULK zo-C7rE4TZB<9@O@h~~ynf>3-(Ly}Y(Ph5`bI4RyH3TJf9PBC^7V_8qe>xM<_3q}oY zV*Y+JX4CP?>C#6-`uKqYTPaubRzN>66XM>mk_sk%d0+hjk?mAY#xXX{JBwDup{HRp z19xiHN51uZh!2anPIqL1`uc~*g>F1p#o?;yB5`h*Shp-%X2ctV4_35l6VKN+#hu#@ zk=*4jxHqNv@8)EjI4EEJ2q52o36cEqi;NmD8F7jjHb8ew8`j!wTl)gW3;uh$_gP|p zJMG8=-9FehjO6)-kG&|4fi`%au|5z;Iv-`^k2HoJ)=I=!nIDz*DOq2m=KXB^%wZ#? ztO$2r56*tfWp+#>uSXb$Zbx#9@|YVUfj^SIZgOE#Arrk3Smvv+sJU;1kg2Sy>MMJM zSa8%)tLgWkku)0KWp_)c%2pb%p+{#7l~3y#-3gi zS*=;kweW&x_d5#kW-$pLu}Hm(j3nqspXKGXtVCDyxFz>Bv44xnQabl{pQXg#eU_Uq zMS@cSHzek8pJ=wpULhT^EnyC0RNH+_;h^5E|5$HGIkdNrDKuf!%Ap=@KBSiA48fJ! zGht9|JVx=IeR6H4AjnnLT^JipDL_bX3 zuKTvh4H{4MHlFA#F`l!ZpWt>m9L%8QcX_0vFnxim@+<6}Nvp&Ly}nxI%3ZDW>_}dO z-Wg^0HA`q+3XAvJx9L&*#i@*BPmAUEDPd|mB%xnN z%vJo4_|AWVT>rpde9j(?vP?l)RPndpR6EC|Re3;{#@!s*ejJ;dKZyl%SFnL9j2YD2 z_Pv#2`#58}5QO36|9sy_&@Tf)hru;!)y$HL3D0AWT^kR}1i=RPrAUy{urX7yWJ#e< zR*?y>VfTSe(Q7mRZXOuAW?xKmv8A{(C+QilDbT07bNYv@u`lLmd0D?{J|4TsUayuy zGIY-8+JiSa#?%W8P7R`N*~(&Tj}3Q1B(iSdv6}TK!$Ie-)~&hd>np63m1Wn89JPv{ zTKX5)Mb%JVidcJ8+3Lcl>k3Iu}tjwNb0H6io>RgY3~=!56>= zK|hWA#Jli|CYdbK>sCA0X9R!_A-9bfD^y}4*f&BBKoj>IA^yY7MX*6|{hJ2YKTk}w z`QIF8Ta_H23KCBJ@Cx-vJhYp0wIw#jsfxQVs}67k&wM|EY#$H)OhJM>OVHtyf9PBw z4K^jlWasEZG+ZpC6w@c8rbxIoTAnenNs}J9Kx95X3>S(N5L!q7*gjMfBf`1rSN{26 zYs&sL_HM~A=58M}oOO!|a*h`sGIUDZH;NC*-PdW+q|Khs?)Nd>u(sDyv#85rdZQFz z$@y>yxkTT5bM*vM^gWKykIc$ZHcyh#?E>wzDGe$Ga;=J~JC0btYft#q#V^_rW<3q9 zy#MxPCH>DXt8E2I|I1gF3_YX$>T2RxeHl)UU(>xR8=Z#VF4>*2nw(c3uX zS4VkOU(y*}I#9c*W2lB1U6KX%shy=ImOzWeOkIhk%^!CkYmxZWL8M-a)!OHk&{QEU zbdsA^()I~5F#_3VwTts~#lkjH(z;LOce!ek>ab=uh2=;h4PU=~)U5WQHIH$izjay0 z`gN75G!4wyXT&q9j)7XMS&aU=Z;LX#6YjR9 ze)`SBeL5a+I%5GCR)SoZE!C{rfBSGvz?hFRtYpwle|5Rr%jdp*`qoW_LR3g$hhT%S zj$fYRILRx+!v5q?Pn(~7{_cTe-n6`*l6OP9%IkjM9LwEZ#2OoPg3d9UDG9y?2?Xu# zAID(w3d4Y%3YESWqheNxF}uE2XrIs4^H5)-zfjx)rlM4G)mx_}B9*&PtMZ1mOzDTZ zI9NqUoF&+GdmbaLV_7N9Gw?W**gxuAcI8d&#_dUa**=~j7k^B?2hTM)j2?KN_9ygL zpBV4VaA|wasd07cl_ZZTAwi{sTsAKMTyg7ZR$bg!k}=hRN=F$!&DmnjZ$bE(YPkV2 z@=_ExvJ2p*@^3!O&pymw)Vv0E-G6UB*y?Fb;h2mHcJM1AibBqJH6wlIJL5 zB$q8bL{wmsS)3*O;#jE4*(M_uRd7>DVBITu7m2Iu!~)rrY~NH&?~P;6R^k53H8Gd_cBa@MDH4QMtV}K;s`!v>iAE7FC`$p! zmJZy$M+=-1gS5#sQ@@d<8q^ufx7=Uj{Q^_Exa5#lrA#{ahWPlkK!QhQ^QoNNAH$nxj@Pmo!DCLpMCxLnaO6f*|)27fG2uBOh>DaWWeT@(_u0-K>aoZGeD=W;dKK`4Cjta6%ED}1m|Zl-}8amgAV>Z z4-6BB_ODDE97SIWzpY#Jyx+!IKL9hOG~L~OhT>s|VN)=0H{*1{uz&V5!03oj`aU}T z)M#m&YrM_YDR{)P#WkiIw%v3$2AJ@U+vapz8uy0NZi|JVvUN6Z;vHwZf3T*n>ZYH) zU!#D%Yo;KDF~DZf&i~?F*|$plu{|DKibr2omUS8m2U3C08GWTzJe1;eMA6Cow+I(3 z7x5n?!3Ym}W^w6Iie$||j^h^mp%m%C{8V=rRQC0x$c7v0#DrPCe5g|>fypV=lA$L0 zol~9lMcl6krgi=E+t=BpJa1}lqodPvT}%)Hv_v}HfL=YFa^xWthw)uW%1rdlCJhGJ z_IoEh=(#HvOuG{0NzdfosLg1BTt($71r%Ij^qT{mE?*aUgRwzCb_D4tGWytjy)gY< zVGCNVwG3n>VPCAp&xw&xXs;O+@_8?07-)TV_MU3r+2t_sSD*vLs2|0>ct zC{ovdZi!Y!U#@%-u#zlS8uabUdP=FUS4*)O7=2>210%A-`w^#af)^D|qhpxe6Ru%4 z>k!rsTONTV!E`p$R4EuFM*<^95S_t{qmU$6-6xgG=&d~mUMBOM&)h2%HlJCLqxPpy z0S@EEaWQ6*X)>d?t|=N=LpNzmz`G*-;w14+i4gTvgkvK6VQaazzOD$|E7+_Sc`W7= z@!hv54kw%xDJQ<(NN`;t>Dhh^v1HC8c%8AeJ(rZCJprfMUhKAsMC`HICWU*1kH;nu zq*hrLMph4`Lt|zzH%@iLK6qI{kydgxOea`Zg8!hbz2AxW)Z~>e?FWslTCs_EnEIs2 zPUI7DDf^sC2lLT;%4mw39j0^T9Ys%d1PeT7Hq=bN4Rkbb?!MiZDf)OIHVN5(%=^*I zcs7sNmpsvCSPUlq$6ELS*^iI0zTSCRvyl|e`vjXtV7d;yNEEO7t4Yokk#$+4e02s7 zmaC1-K~`6rbc5&TERNEZ&A0H@6m>pd@36Yodh$)qwYD>JGuPS?wq&0>#11jX2@U#D zQ;YO7P877@(7i7zLzld#-MP7hi=24Pqp;7&pnIQ?^>7~+9ZuY}_>ulE1D+L-B)CRZ zzt^BW?0S#cfjdP@Z|or#=l>M@hUf@?lm!1GH0N5I_43Og`D(e{!&W?aH!s0xz`Lmr zYS6;r-D$*bM8BpA?b%CxuR)}v!g@kG(|~-x%&AWYyVAwxL}n>>b;-0~88(WxAN)T=dT>*zW-9Fbt5|r`{@WWRp+m^OJwn5;qztn+1$$S2hdh;(HMyO%ouI_-*o5V^`?)iO&4P5UsP#wYFM)~+BZBaDrQ?z|b zTdoGU1tuc#XPtJ2CW3duHB9K~6xNh%L5UN?V95z5f0!NVVb)^}!I_HBZtFHJdg6tW@``OYijcWtym{oAl~jFq1ZwI&Eya;WS>tJ5hGV zX%rBg7*{Yr%Z>W{46rqr5cvG#Kl{e$zfI)D|1dOefBx@`vc2Ef*3c;FC-Dbj>0(k< z0mP%oRwNzxZo=v)w0g*&AAEj=ubaeDFL$E9H#FWlc68GdP^jpkB><2uAA!$rJ5UX& zv~QlAb8GO&Ccr^`baWW#6reXm9(E9X^bOD{EST~jgxzpR@p85|w^qxX2CSY34ud&E zF}cPY|1`Mi`Iw&sF)L@qMO{g#iR4v$5GPo0Kf*Ic;@zO2A8Bhmhqx~(d0<8dA0qVX zwMXrV#b~uY%V%nHT8e8I&6zB+>6M<^h~L8C%DPwc2-(0yIDA|?_lChSb-h4EKu#(J(^T8cWZQ0;E%J8Bw4W-@^AdN4KdaERkdqFZ`VG_gfjoSZtR zd|yQ2$y|wZJ@?OkHdo20Dfbr*qe8Gc%`;(ho(Z}=)^j6AqWEF+?P}>y)nvM=x_JgJ zUK@Sq^=?n&7U`LwG1=*h?&DZi@PJF4RC0$aQo4FA?j)$99_vxCr^5%2RRU_jwi~FO zg}7DYWdJmyb5eAhb?8b2Fpyq-bdnFn%sHa6(?Fw66wChcN9ISjdoyrYAHW!4QZNbd zqn%;Lz!1K>rv2?*`wxfp#5&&JML41t0|||Hm%Bvp_gp~zJ$F$r4>BRm9cLR;{lo5` zU4eFwh6Ah!NXKjLleoa`&1^Ho6D1BZ(S791>g|FIgK;InSU{E+ zF?eDuFf{OGC@@4qe<9hjCD;!URwAJCCJx&GG%1|gS9Lpu0sPAp@OGR=y&VInf4TLn z$==&0p7V&ImnLH~-^PnUO%G(izRhn&glIz23E!t>|483_hYME#<72xn9A*?U$iJdA z+URo7t(STwJH6cng75Sns-8}!ar=a!RLIs4#XfsW)|H&2-laxbNyq$Xta=j6M)OOI zA`6V+OdnHRw1TB(xng?#J;|l4Cob#VZ`ZPx#-2QIA`rl^cxdGA?Tx*$M%DeYwix$Z zQ|isounTn|1X*FLD*9s`IK?Fvn6(s{JsF_4o6Q?XL>676S<9rEnjFI1t;d1ZJvp%B z;7K+9tPn~+XWqicpR-x)Hb=!*-9@e4Ia?Zq2gTjLIifBCMX!-Sj$2NfJ$v9c_N|^> zXW24aJ?KldU+a5YL|;BAggwi)pl7#@o8GAKzX5I z+x>GBJ@}d^dz&|0I>=&+Jp&2k{MriF0UvJTrynlP@uQyjKf9OzJ!o*liluDNhudn@ zx13+My*Rc!-~Qs=^BeRE)u=;pE8o$p@jZ}=^COBkDEog@pc~5m-(!B${(pOSuG04u z@_aj~=Sl+Y&U+PoHiueOPjkSwLV0nh`1-sxn9V8c6xx^h{_Sq>p1%&YfGzjixD^zn za+Q75)H8L`L{9tB%4?ph5cn^ODVgZu2!a2nA3Me*xKdCDb9+mlH*oc2oqC^)l;D_5 z3G-u4zMqn-k!iiV56l4Pnic-+Ctv-Ds}|uu?gKv`O27a6uik6bHv3P?kt#D8i_;mm zmhd)}BjmG;y4s%)faHfm4`()zxwHW>Bg#{9SAD76c**=vAlvQD z&iB>BcXWKm>t{D;<`^psynd4H_=g~I^?z7j{)fv&r+?{?Z5nF)Ql6C2K>&IE45$IG zALZi9Pxq|4bHHt91b@5xG^FuHUf&a{@?k}g2*?SR! zaCz6^@4{5nAXv%-vUh=`{+mp(?+b+QtL`T~M)ydiegBnJchvu#)A&!MwPW{KP02Sq zbkqR8AN1K*;hn!YtW>N1phMqYEbb|tJQmbtN(rpo?3bGVf}w65R_a;C9aH|+-mBYK zvFcdFgH2_p)pG^(rYOi(Q7d3$2!1yf`CzaT@}-DU!G4l+sD_f>*g>7TC;(78XaPwH6tbQ zW|e-yO(liqnS|t92;vM@!wZ2&m^3T0$2i~x#|7Nr;1G`j$xN9UTfyVMw^fWah_A0^ z&k)&nB-Sdd@$5dcq8AYpR>fXQr^8+PN$j{wI%mrjU>8|LI=JIpzcR2}u^^CSc)r;- zk)Caw2AsC`hPIAt-_lj8Y#1q~s^2wfA>%L(TLp7tQRRGe3ev2T$|O2Ol`o>_i+TB( zT8uOCGur=7*;%YcBTx6X^e0Jpn>J}c$l%a>v4*>}^NYjjrPploMtM&ipZ2QPi#$T( zMUccU&@ntk@AW7fK~GvaF-r1@V8tnjh`$Xn#(GxJYu4(4uD0juTfrO3{3>7GuZ;Lt zxVrDFKIP_6bHuqI|FJ?Vri-l z{x(jZgpwshxz7b>LSLCLS?Z5l#fTZnW*E$eCyKX*YE+*@0$%o>?+ln901Se4!(N{6 zFT1!LI-e72xfIH_MZ${YC0O-G4VgHmZ^2^duoUtv0A+9Rl0CkB$&N&)S%s}5O(D5o z7D5{%V#0J^H}|~Fa#N}FqtjBbe4K97l|{!O9hZxi{QSW^&f>Qk<#wMn39?J)Uic;B zSgcNzepI+&i(7yEdD%n-n(b_owXD;GdUg1*H*q=T$E2RX#mTj2%8ObQ;^eXyGe{Sv zUa{&t1q&00)*B_)F2zmG9n^gdV%SP?G{H^N7`jip{3h($yN;jqNkA;{4_4c4rrPfK z{Smb=7(aN~Nm!367?M3<_CnB@oUB!+_dcnvj}y#fC{rCrsmu)z&iJc`>gLU4-tUep zXA~P;vc?(*R@<5TL-0ieW5XI1`=UaY@E5eLRbq-+thhKzYb_`UJL=EjVKf-onA01j z+K4@%fQf2ku`Bo$KbuTJ1eu@M?|rXa5_!R$gMZ>adTw-VlGiOkHw^XG}6I&%r6lq8?)%u?nHV*iXw; z7gJ%9pJ}b>Y5JhdCLr00l9RtndX6H+6tRnPPYjOhwO@+tXclQs9{qk?_rm$z8Rq&e z;k-L{llXeeE}uNMrh5{h7CGrVmcQTkm_N>rm3%at;IRKOvR$qNd%*F4`H7;DkHVFL%1N{ohH&`8;(p*grL(O-z;e}R_e5ALSTgs#o~UVY7j@36r?I(Jsp9 zHR`n(L^8eGel1KNMhF7|!wt*aEoa-}?Hr}e1cjaXA}GKSXipm<6+U<^hJxZZUyF&( zhyO2Li$+DWQ&1Im6*NXFi^74Gm}K)if5aJq56r|&@VOBU zIos}_X}@QNYc9MKxuCeAGKeTFxnbylKH`_1%NHU@9QDW$CkIi9b$V2&zB;Nlv1uv_ zQ8eFGCO)m;x1g! zW}$a~%K1>Hb0M_8S5uoKc!is}1VfEmBTvYW%VvhA$;S#`!J5S_%1}ra3*wM#4og># zluJB&SI}}&D0^B%E@SJ!8pnBRLO zDktmSs<5BzOw;qfpWAOo;+g)MThnc_U=G@OsV4s8*2pnZ2z@^r(hZ$~ z4Fw_Ti-zD6Gm7lLusrNV`FjW{?RvY&vHBf*`R_w}f$AlZ^Ax}j3k6Y+t{p>$!4+}0 zhjt2+cah2tzrrbXBjx_ePd}9s?!9Rjtx22|h=Qnp|59xwg8%^?tD*k|xk1&p_x#pW)Gt;Pp;jrxZGlphwqkrv9I?>`W9d;avL`lCPJ zzaZ$oWzXfpQ=K3Mm}LT2hy_6L-(mW zouz`6MuB>#iE3rIwR)*ud$Zi>>(;MJuD=<-D^vPVr^XR&n*4cW7BHm$p~5t|M4;ji zx0hhlX;pi!ZF(Q4@7K0%Z@SCANV;!^^Suo~slB_K-Ma+)f7;EmZdVwE&1?H_!h-*% z0_G0^7NkvQq=l>ZT}7P9I~AX zGtnzC;v+K|p1QNm`NbQA0sF=O08CjJ*A%D`m>^;vhO-Zl1u#C&y+OeK)t{(8_v*j> ziAi9XC4fO%+# zcKBl8lO}+lLJXq=KScs|3k^_EhHGzQp&3b=bsXUICO#wz_5R}SBY1uljroV_Tol=5fYXLG8lfW_5{{KQpl%Bv|Yv5YPw0U5`3v0D;gjDU{>v0E0PLYrWoK;e#l zoQ`%|a2odBc5~W}TZRPg6sNCZNEI;GbF(UEk@X<`B|(IZHx1Gp78!N&Sb<&dJL9%^ zDqA?6Unfgv@>wl4G(4+(S2lo=xRG#`fKQwy*PKQwA_$3Grw za5C9KSu>ZN|3kxVqI1V-E!9(XtI)+0XJS7aYd+bpaXd%TzSf|Q_?F0hStq8Rz!2=- zF75KqV=i~+oapHs3K3ld;-R~z?eF#J7xJivwTmU~uG_E!>KQYFXG{+sgbnmfu_=%~ zcE{eP)nJ@MBgRA+K9wbOQI)0i+gBHqMY&4Tcw|(>pWy2)ZFU8g77t@GZ!LCd?I%aD z=LBiXiH)CoQev7EzMnVF_Sk?i3uVl|Ye=Pz4IG=~A9BL8f^&ld#nJy*FR9~woKc)#~RYe z;zjT7P?Nwjj0ew88AadG2EX*%9{T4lsua0NGZ4}2g>L@*OU?Ub@PZk-ymy`$xLxmq zU#J4uSz8p7kCq8Pi2Eq>hhZ*cK(%x7TX@k2DGoi@9vLj$`1}rYm}jTp#DUQ8X!%uxKY?Jk_1?5beaZ_5R5qi=MP4O%_R* zm`s(6ZVmOCxZiVEKD+`uRp)N{mnj>~4AC-6882N*LaasxUYTCVho!{HX_cj_UAGPs zV;qc1>-ayceRWt=Tif>rW{5!nX^`$N1rZEDkq{6@q$QMYkPhia7`nT=Tco8!N;(t; zK@^Y%nQw#2IiB~N=X=ikeg8Ta``WI(*1hidMPiM6DQa^CpM)C&_UiUtFEL;pe3RO= zM!Y9lwn&}7QX&vk5WwHfRx(2I=>?f)+WRrh7P-*mEyFAV zmB=HVb^;VU0+k+|Jl0#@Vo_xz3^}tEY)T0YEnj$axZgD2JNRSh_G6B5F3<3vdPNvh zW2xd8=LD($TeJlcc4^Z zF>iLPR~&{{nB_e9^tc#QBWU{L7$2PQIpQ@BWTJ*+&d_ZzuwnuDruY*h1}!Y8&!fb6 zdWcyena^!^)HbL|@^mr`^9~5pOTwEZ84dT=s8mrzCWsjhzQ#mC;DnO#SPO*NpK`)7{_+n@P z_ssDN)4HEiP!zc?9z4j~jPF&(=a;iy6m_e=bFT#Z&1SRGr3cCM+nO(rCBJD(O$8N4 z+;ECv)bn-4`Q~bM&?)+^W{}!d7;zpg&en|%Wci(9Z>0b?EIbkOAD>i4#o{;BB+A3y zzX?y_bOq5o;&VY{aGL(GT}arY5mZ*xFD=1RAs?d|bR{WwYPP9f`$$3NP(`FuN1ZS^*l0=Jvu`4bfzc6i?WhOQ z_*8RO(AwuG)nQkCZmtYyM|$YEMTyCCFBJh9b2#m+L!gUx%?zN*4t&jRG zdv_!J)zf8kmuCG=kuMJ`l+YVCn$SQhbr$ zFvD0xX9(E8ov;6!;K7dUh*abGk;|PW#C2e}LOqMBn81A$Qp^QSk)N1*a3SjfPVlGG zY#H-3CjFKYqT^H5`P9%}w^`TyaEvq$}7i2h5u{^x-EpCk2u`@}yN0RMlU z`2XP@|L*1g!^?pePc4X^z6OYaA1d;6V+$_)5-iwAZ2^;g>22nXG>{yD3$KhVd*9(k zaWl|V(kfHRm-azEMQQ$0PYjwy>s2zEk1|pG59hX7o*CQ&h+Oq&mgHADoH1?5qjGJG z?jX)ZCjSMHXe`?e>(5omzx=O(o8~`kfq&dP|6#HI?KV7n)L-7=&zt5S-{Gt!#Rp&j z1Ar0uUH%80`Hp8X)lW6_-;@siOVY}}ltETRwt%Fa|2cs99pF{aND^JXbUJ|HVzEE# zZ5#M$Eohe6WF8Tm`L{w6iKRLOkte6|ojYUsV{oJJJ-0b*Yf5Rn6PleZ zC^WSsU$^nyw=WpE+)cCEP5TfNAKV|Y`z%CX0}HAJRIR^Tv42)6Wa!fRuWOLMq);Hu z=@0YPA0w;(O?Umb-q#;1_Q%M|ER)6J-vPj<{|Y?loeFx;^b=+D@3ZqW0Qea|bFjbj zU65~`3f@hgag{g*fsgw!w_&sCXH3nX=B<+do8A|5>>i=waw4eyl5^kw%ends*XyTg ztmvtV!u}s)rxij4jGu`7Dxty1#SgY)zM>lc{r5(bn)Li9RN3jR$G6xNz`Opm^1<$$cO%3xac3BMg5c@QlTNI!)meb;AmmDPwLa`Z>AZ zqjPt|BD?@hXP5lwb;@j~pfaL`n;uBq(-wXWo)FOO=t@hIC?SnMwp|a);F1A?41XT!noD z^3`SJ-3{&l!bz#m2S@gy--$O*A&_okWrTd043ab6O|q(o06JKWU4=#^a#~*$muAnZ z_ z2Oa1appuu*0jg52MHHd2FzZ*0+pVq3q)}xS=A(JD$@>!s zdv(n?=yrtbA%vHkcjC#_1R-%Lu3aK8+-Pkq7UF5cQ|~nqB?wKhY$q*PD-jXlOR#uN z)6l?Kf$L|=S4HmzDu*-I%w!kyV1L;9rAnzmi;&UpVfoy%xG_3_KK^AZO!_l*hIDb+au^(WO}hw+*m}IFY~0z zgn!{}8`y9BAtdlOC}bw7u!B8|-e_4go2et^OF6%e;Log>ExZp%7saqNt-8Vv%9#9N z*x0$C(_trgFo6XfKwR}qNW$SE8BA)?mk$Wdac;)r zjq6##BdA|LDzE&wBQF~i+{%|eaTsNN)&vm%O(v_S@Iuh^kmvYdcdSRtZ9Oa9h2^g}xO5}?GCGlvJf-It2GlFxkM2*=D zK47=pA3pJH57}S%=0X|g`0XOBFMEs4Xb1LP#T%P1_Lth?DX(dIH^|ESN7~Qj zzdPaZhKMD)$qs#BG2*IQE?hh8eUpnF*?gz$!Dqzcg-g%n@r(8b^54;=#S)HPU#>s= z^olv<)9ud=MRg)CNfeLn%Ty#eitYkK6F=$Q{j}EzC@yQsg=$dx?TvUKG^9*hn6FX z1Q}?Fu)0JA;D|XL-Bfh>ipn={LSow=R0`Bl$~l!sq#kFo+>z>0i06xplVNt}$BnBp2Q-ZTo+1GC9l2?#0I8E8Y`(my#Gg zqG!~bG>m)NG+*%&{;NE-F3(DakXOWP*e66=(cdjT9`0hm;$ zQ;B^O8o=$3Ndn~w$Q5|k>WTB`Kgk6MAix4v*hXLz6mbt*bPK$MJ-P+?85QDT-8TE7yf?D|biI zAw7tC?c6y7t5vKj^+HFZm2B6)vp>o&(h3&po}rAzTbXYoFo~jL6%D`X)`VUt9vnN? z3_$}Vjk2U@?f{W@2$mR7{E0nK7=r%QbnAam#Dci~T7iHW>EBc!Yp#TkbsfcpF8F(^~eim`@DtD&)q^H>4{!Hpi3WC+u>xQo%GU;U$fk}OT!ya5&t>j~&_{6DY zUkF)-dA`V9g@-KKz|33i? zvj6W8DK39_a*$#D>h8}5F$4?;9NFL@wL+yk+hM2U31z$BodUk)x>aNl?N7eWHyKTP zotBMBEq7q8C(MiX)>HGKH22qSp`E?FN$`*&vkg{1Y-Si}o(}Oy>ij5O7E!<*281Xl z6G}#NhEH}UP5nknO`Qj@t;ksI`>5boKQ(^BLHU)o|@@abng&|YkH zVF$YbsvDZGQZV+{Wk5~4@>uo9O0M-__lF0`PrM&H+SFGH29BGN7OQSeJl{@5Zu$mY z%dBF1tQhV@;(4G%XzAT1g?oZM|P2BcyZP{fTf6&4;&wEDtZq; zlcAHuTl^j?qascSOAAxE)W*EwL$DhFX9<(&0n{aVKgJklt44YtC(6~r>GMJD-y7dY z2I6*2!yu71ApPIUEM#IV6)Z(q?&C1kD|?|SI)bH0pl)hL*dN%+*Mzztjvwp>WJdpm zW2VYxk{wBYXe7FKl^mX4kJD@*dV*&Ybf=1Hn_aYnYFfVRI&ZH+DfS!27Ey$(4ZCJ0 zLnBn8}UZols~FLblh zanNtGy}u12{|t}+TM?*JMq?RU-~YDPXf>*&P6_U|NuvTKq-j|GY2ll^j;>vOt#oV| zblMKOnk2v7#F;5orgW+}5L_hr{XU(?_UCDk*QU>2X1v-PTvndMHzvSUu>p zowPp5hoddx$vFXDQ(C4o$(tTh&De_jC5QWa8$0GPJUpU@pd-rr?|O6Ehu=;eQPieT zROVgLm~ypMnj#G}P>02L2X8lVfMOF$M1mstXs2FBVXS_j*aTb0{B5{t*dzc?tcmhq ze9iLy0kn1e)Tl&9&F9MQ3jG6|L;d^0__-@{p^{A3M_#CZVuIRA-(%IgfBYSPDpEzi zZs{4Qpr|LobFQFhn0TwqA+OjgVmCydxdJ52va;k9;Cr*@$w?WH z71yC3jd0%nIlDNU0yKlIXe#zbOfSBW-Z8EPZ)7H>H*1u|Xp1bi1v*0H*^{Q* z9XJ{ZncI4!*l|p;X5`IA6KEsV=A2pP;$!@qOaNa)rP)jv%4fOe1Xi-80u)I}zN9)x zKf1-y*kjkaNMAjj_i9PE9!tNgoO)j_R~jIL&$mm{ii>+WFOsu5%g{U~`qjQxW7W4_ zCVb4;IlF|ar$L@lrdBk@E0flwfcp0Cg57RvOq%x)rMSEc%+5jCoI!IU&5bS_b6Wen zEd_!@nn9e-)w3D!{<%C8#0)C$e|kDGk*7NFPujFF+`hMw(nz7g@xvuY4a;=zz>6fI z`+FsiJnfL5;}QclV)_79WB`M>@5jCbRK{{be_l}_W$anzVCrPsTk`CJQ;u&3Mr?~ z1~|~e#z?=tRdzQ2$`sNSRnQwHcTqZ7V{A^X;mP%$@5EPYOP~&bXE$_kHKfs^ca4^O5%XV*CIt z{nDy}xcyp;_0z?8C!$V_HFZ?AnbHcPm%ssE{-f>)`iDYGUBjB}QFKUt(5-=~F9F@G zr;ikWxh3hA*XjjO9O+HMozVP9qpvBE0Jk$+(f;6g69ldzM>$Cdj03b;#M?Dht78mW zjDd`jcI*>wBKTddfkP{!@k#`#;t96zMH=j}PVUp`lz8Wu%)&C`>`Ue#*ivsEaX4t> zvwCwA;A~ioX!Vew-C*JfW0D=h#Im4^@K$V4Qt!f)c}bMvElYvx^#Rk4LodL_%`9v< zkk;6X)U1mBJ-jCxs6I}|!4{}%AKjgRiduL!5#aqB!9@L zA|-T0@LU%MiTop@{^=?6dq%DApX%~qQd$0I-T`8-Pxl%PAb180a6Q{=@(U$kU43%D z3$fUGIzK%Z*8`Dn3r&8MzgnOW(YZT6ZUWx?V5x|umUxgT1={-jYen)3Pr~|YonO=S zvo~S^gAExNY+BBDKc@N_R6)!cMe;iMMhhhX{%6)g5Q|6XkAt-R9J~1h2t!v0S*nGC z6J3le$%=XS*`hJ11Pr7T!`Xu#)ZM02TNUZvfUs>f1HGPhe>ye+L)cU~kz6iz#MSRR zC2J20F(WWv7zQa8*i|?4$qWxGg#)|8`DXhHGztY*micA~Q==lYAteLfm81KlSS2vn zW^(s*h5e02PK@79EQr_PO(ziH3HOUTY#HS4*0b>8KLm`JU4Cfrf1 zx5-7|jOfNV=AL;c0~VJvm+Zzf&$nS|DD&xq|vHD_8TDuR!wI+UYoOp~gv-sf* zUpX)5Sua+LTXRVZ)e(LmmumZ-rEtK+C)G7^-{g_9@I&W|S?%UIw?u^1Kb9G5P-{nc z+o8PcEjfPmxPU=DHHK1ivc)glX@-?a>&^yIO}r_p(X~0yA4w(c0ZgBW)|-M{ana|z zKLnOVr~6n0;67X5KWPHr-TwovlzIk0i`+MP-{N};aADn|`z0u%CyHR!sRzgZphzU= zCCqI<0{ZYX4JB9^lY-y9P&y(JX`^-}Ia&c(a$D^JrOaX_J;SdlQu)%tuu_BG%!wjY zVW*wI@rB#0O&&6FKa$Xw(@^!z2+j7RnI{2{=|@>Ta_0q;_P z744FREW+DrvDU8Uxhr9l`ygxwn@Gvi>1&D6Gs|_<=#u+5Uz%+R(xvme(->bvkRVmGvlJ`lr9@yo?NDdW7&};UiGW6*s?9)!y#a|1P66?`qhYRvcpD^n@gtOX@q!UUi z_l&ryXSNSW5?TmH3)V=EuW!@<>Mv^;76mWW7ZvOlzkkV9^|(N3=*l>ztkKOZ4Zrh? z_iS-^z{Q~fH&OjhsGukc@`UoQX)(rJ?|vx}SX)DnVNzR*+|E!U-%6kI%w|wbbE<;q zAw!o^kz@zO^`WP)BTxZC(}2yC#&|R{9R{^4qLQ&(5hoD~Thxj<>m2_G4IC{#~m*AC7iajNEO#)JYDFJ=I7L@^PV#_L1EDLij ze^l6tLDxBw9s4fpo<)J(tqif^^Hu>EbLIg7fEJ9U0Osy_%z><*XZg1jSwIr3Kk_+N zrUMw;J*b80Dv97rEpEH=Fb>tSs1_w8!-R?WGwsU(Frt&AeJgB<2zDu0B!c&;L^28- z6%*0SJd{f9ae<%Q{llGP792Ol47Y8dh2?GB}FlB%SyO@mvAx8Z44;g6@8Jr1~W2yPCyW`Us=ukRxqf z!Gpo9>gf1Ephl<2G}b6-^M{9l_GWJ)zgI38q=rW9Qaum8pDgj&AX>U8*!n&g%xo!Zw-B z$^%ac3?`yl8Pj z@#&;bINj8cdwrtb5oAaumM(HP;V$EA_NmZod+1ZAJYsqKb*2iPQ6i+5%zC*y^_nvk ziH2{$ZT!h{R*&y zEJLGE_Oz|%L3UC9Ox<3U($3N zi9CT~F1Vkxyq+`y%^amw8Z9g1O$;xlQsTikIw-w!_4ZSJi>yG2JsLaGcYc^j5)_7e zmUh^psCOgN4Y&hYGHzBMM*x7ji~yY>R`SIA&=RN=IpPkiJ0q;+lB$a6D;6w>nBYyD z)X*9-B_;gP4=f+-HPj%n0g+hk9l)^EH4zn9>F|3ksE2KKFsZcRQ&cR5F#1HQk9F^p z9k!(2r8ttSWNM)?DzF$<^DyYCc+M@Wy2b4He8{xlWu(yla#M|5Kg2FRFXyX~&~$bt zDB%*BF_n`i8jMevA(F&`OnncO;Onxc(oT)UKq9uBn2TM}u|JnO!PGg*EZyAZ zYE{p4(m8YRcG0J3Y_+rc$!ztqwSC@dWqCT0?;!Zrm^kBoh!TAXXr+tt!%BA{zF@md zW^ZP@jy|7^dhpqcz20*CCzQ0gm;7GqhrwOgeIUpQvG;|KC3bhljdQAZt*sh4Yo=|S zAKOpcEx*{CyGJ!^Qz7CuG6jDzk5ej+uWgs-AQ8r?J~?I+^>X8NHRH?j4^el`6a1ZcM)gH?;@bfLE=jv+AxDC{ zvw8n=(>`}50?gkMEM94fN?caFxf6hGYCaEsm;^YLKcs_kPX{sS9RS>P z@@U86T}cqlohOMb<+_rr)MyCMB!bpGjPt43T~^DiyK%H05J`X_XV43NVs?D+P&z!B zKOlOk`=MAk1P;koR2wz~oGE>#GMzR*G4Y{vfgv;6WQ>y_3u4weR45sbA^kv&!HV%bPQa#OmRLrk62Be>tV zx@h=?Ho*n?wdybKMPdcSGJJL-4}Bi2AGQkuP}<%#+JTrTKetNTY740rYP+QPB>a<>zwTH#uMkjb;^r<4f_(o zhBXr=dKUNbJzr<|RUX$wMRuU_-=C){8@ugUBzcoJ>Pg8(n=dQ$&j;m7lh(F3F5MCr zrhfTlf1g@_F}cZ2H2Va~qV2SI!7x=ci-JYvyw?hDje2mBIB}-C{v#KcPi;J#B{~c( zwEosYFWfiL?tJkR_95kogbCdEQS&fnSH|$235xq3Gk4IoLmr0Y1XZF^7 zZP#LrfB^WrW*Q*uV{J!`=d(%&f*x0~!5;J?wO}++GPSXQt81WHGB(szYBZyEn}&<@ z5QEM%rmFn1M{LTk)lVkz3!FbJPBkY?nc4D46)bdBoUBnaD+w>-3)sraJ!X;5ZkpQs ztlB92W*k*L?3&|TqN2N9X=8y~UiEvMi6Y68l=K#rjX$Xnz@a{nAFOVuy!noc-of;s2oLxiK%Aa^u`QAVR1z=PKi=PE~8LV8x5mO>8_X6rLwq0&T%36y9J}j?sl? zQ>@(OajUr} z+*S4U%epJegUQ0!5ZS3MPUl34Ae^FlYm?p*#?DtS>nqKsY7FM*D5rK*e5%!;)N>)V zoA0{Jh)7;()LDHTOu|m#auwWO8%r<=m1}ggUz=%ribTq}x@@mcG^UWGxVk#+t^06S zi5o|r^+l)++=$$ckO%hjZkc$7sjg7E{dpD?DnV&aTp`RfcVM?B)tgjJFcow&%w6!K z3K66Aq6jCY^JWpKP4g%5jHUCZ&nKlNTfaIgeL2oBEg(c~Y2|6?jW4xNnc^>WKV=X{ zt)mYYmTt|6kiEtFA^gS(W)`us{`IVIwY%^SVd}gDRZ@U4%}z|@3k19mq`#2qG7Ac)i? zzuJmHT^}eYPEcesEW^ECIRxwdI5Gffl(z1`pYB^LZ?S%C_O|Z%P4?SsBA-nrUfKok zP8yXI*-cwkaPCb%YcR8)u~}ZPF1=2Tj8smITVdZPjrV`zAmA6MP|Fe+L>EGu9{j{% z(Rbjm^3^0}WgyeB!1}?56h9oHbl7xP;3Q+oNa*d8(TBK0afNLlkPuBa^mai5PQy3_ z^R#m(iT&q6V5iiY|7}agi`uQOZ^gXdhGIS+eQV&-a{V^K?B=@NA_dGKVRs-Iv|N?1@4Jne|~_geMfj97k}j{ zI#a&~ggr99YpBNSCG5#a!|Xdnk9hgQr$8ppOwp=Bkj5CMf_=gCxHta|8pAZIf?Ab^ zZQmNgVR;|HmuWa=U2Wut8&AK|QHvp$_}!arxhOt8OMHL)250{uL(GT3&zgZW&}ubo=kclZB+P9f5^ zza~Em1TWuMw|(G5<*W=rM*v>AUyWJYCcYwi6jKFk^W(#3C5h=;nOZbubn7~M8p#&wdnO8ed#Cz!#5P|klB>%f_<`L*MoWKq5+dL8{L z2T5RSnJfWBhNBZNXksC)BB|Lq27*rKBYS}crsnTS%ClHy?=+s2>SKE2j<8yl?G8KY z!Su~*J@PVRY;f(y#C(@@s0tExmr#L_RTA7RbK#>k^cT4--0o}WzPUuF>psz*9M50a zJye!-RgY<2{G|e(E~Ubl@uMp2$6xdd8>TOEJ9Hk+ZaM9}e8+F$RMnvIExFo7wabL! zGRs@ia!*RMA@AGXb#G64-Zphzh~mQ-iWPod{v>IAtTeSs8=7&Y1<$bIx>ah1H*&KF8S*6=x;=N=n0kg@H`$d zy_V583?n1ZmAeu@()UpybQ0NT>iaDIgN8nT=yh!Wj>4qQ;E%TqS_c!M+bMTwS45Bp zL%!%&(=Ody5#v^S6B2SYgW$!AgtFQ&BDpgANM=PmXrdsK#$Vq>CsZNE3CI+v%2#k* zRg9@0%MIDd)stOQopz#qMLMUoD&)R6IsUfsBY!Cr^|Kbn^hDb&yV8InQ+?)!iB`?( z@-R*_L*a(0{?`H(*kYni=+T}CEPME^7iv|to`g(qEBC9N4 zLcV&>d}z4VKndTp4$`0@LQ2SVKS(x7InG#$53BC<5u?vzTngC*f(M=rd`midxh#UL z8}gFdPP^Q=B6+)hIAUNsOStiqyj%Tf29*s0H|&<{Wbfn8X|~mw(QC|$hrq69e8j%j z=M%gmPBtz(cme~rs)6*x`vIOZ``ItrEk`2T#nH82XTQ2qJI|pE61RS9-0(y?ze97g zZxepL>2Gmk3Abd=P4}fv;nv|ezm`L`=cLI z{A|E|G&ORvTRr%F9s0!9Tl@Pr-N9Z?LU(tk<9DBT7sLRyO-FbHE!L+7C<*A20RW<~ zb?qc}RPFDp^zM{3sba`IlvJO0U6fz;+=VyZmYnQXAisYJy?wmQjXWGdo`93ulf4qR zJ$vE4bbFGlR6qpJSo0bblqe`wGzJHog$uZQ%}_~8i9#AER;ffW0!Wa@ZY`6jX-1J6 zg3-l7uu89>bU8A|dOFv5+Q0E+>GI@W@nmE1;t}-Xb?_31_2RGf;#@Ifk-TMwVW*Ia zrH+79)7TN<0hsa>2Axn4zK1Ia!116vBF5Etz*BA9k_Gp+r?@72*bhZ~9IY@=cwmoJ z> z_dN!XfUxTke6GIWqlkx+`vylHfb<#QC*?d(x)#zx>as=>^1&hGt6#`RmXNjmkT0Df z$t0m0xgpyQp}T^ihms-u7#6Q`uVf;Kkqa<19-I?PY;ypzqmA7p?_R@$q9BirB9D%n zhvlx|T{VQGlIelA;h%tasb|xgf(ICl0p@bOuEvJv=7zJ>g>y}Y^K^T0vqrFd^3oH1 zVv95&&3p|VQ+5@hd67vBtVDaD0ni=o;0}ji=dgg?4RpN;Twf~}?S0oGZ4c~cB+m@| zT>Tv!R{Ydi?H+eWIj=8yeR2$}3(b>odU@TcXgOgC zGclJru|+bmku0%CHL*7?vF{*pATM-3mZVTD4!BOtT?2jb$+nFoOr#lhT|#>o3EYoh za0NEJu~H#@*ANd>T*a%P)U`<|wMht8qFc)5w_@$1C+(4?B-zXk?kM)(C3X}_pW9pVruB z`lia|JIe<;!^yK0g|d{?vQz?{zGGTpSV{0o+j1`x7+td!lgQXHN;0J-qrgbLIF-%5 zN&uN65zkL$U(K)~&$%~cd%uU|`ACk-VGiSBjt49kQkH#1I`=Yju1|h$05UMwPbe3` zhG!mtR|LcyM&kw61vwiKTj*pbOJ7cn4#Zk?s`n3SUiOTS&*#a_&#lidp2{!naV%sj zD3LBGo638sQcznTK1QaWa#+CYk?r&bPqijTL^Q{vhsQEMRc|x5nT^O-2rptPE4l|? z;IPm}$5t^zdSw^S_b|=W-g-hhW4AQx;Yb#WRJL|~@#<9Z=fmPJ?ygJK!kkDbIAlRfd*wc4x-Luhv|?kQVP9fg&ttGY&v z!YHoe6$6lOeC2AJr8*uZl{&$gG+1ULF!fTb>IGbUJkND`^mb+XVt0T#FRVi+ewEde zd@^jt;IZZeY+j=B?q&(bHM?kobPs<#jZ`3$rW`J)ieZE;Qi@gMUUOYN7fvGr4fBw4 zuLz1myz#D9(W%_tb^a0qC~VlFsl~!UfP*^_zk$tvAEvb8v&(}bC1RW-D%qprfu-#d zSs8a6Q~y1uzObRbc)GsysJ{Ft?s0FH2N5FIuO=?X2~L9|^9D9M0lSI~j4HdnW$~F= zPF4x>KS4m$EU`t^v5ULHuc|hVIyYVkXynan92btLh_&BE3O!L__9CyfGg3wuU658^ zhyW0f>)4H$JTN*3Z&O~VbTdrjzVS4MY&8N5zt#IYX{g5zWaQ}-Ld_Va&CtZ=3on}= zJHiFj@>*ev;lzFtJ;x)lja;axarv#3e|D zyw7tyn#MIPLy`8ckGbyF#+p=i`E@z_Yuy{K^MUKajX%6Vad~*1~lVP^ulC%FPipN1gF)S z_ICO>-a76mj!$p>l#$g*TpIa&#<{IV?Ll8+LGS0jYV!UDp@NaZg78A}*!b*bQYWF9 z=e;l&JL8;hhB;x*nKv*(N~$xqm_r}W418J{_=q|9l5Fs+#^AQg;J3uVt(Sv4DMp$&<>-)3mZNO?!r(lo#UCk4WsgB>RRSsWDPR;#p5!qwjOnhUXHo zB#{m2pIi_*0*OmALt(wy&Sj~W<9oRqd+TqE@FHbLD0`|c)C%KsN}&pQ>dQlzjlR(S ze$K<8JCISx>=4Gq4FCK1cbAep>FgRdWzIw7VyrXn^^8-Ei=bBB@Jt zyvcFA*(K4iXxzvw(R?;he|Fqh*3QV~nTgD(Uf|H}oVOwp!+};qTC3KgZ%0{CCgdCO z7^-tom{VW8P3=;a&~VMU&|~t{&*kVN(e)Sh&!p26DT(I~CzFcO)B1hW*C#W+`(`Cg zWj0Q|V4G?@u6E;_xN&6^*K9)OJCO)y@?PF(o$LgkXxz-9{ThqIh*3_vt6L6pnx@Ol zXVaho*Q}wWtYOO8(f+nPgJL_%30dW7__ZgFNXlfV_35i&Z(P|*N#2&&tYx+nKQoZf zZi{$++%t#1N%%%>K6tgTsAwWAe*XBy{7GZZ(f9e?^<1EM9$l_M0ABR2aUp_ijQJ=P zll+;r0Wncd8EKI5YdhRRuhf-Jq0F4{(V0FS+IO@#{bR>{^ycpv%=_5}%x>Sn(+tFW zQ;)~KJX_wsAQhJ4>{of=4tht78hMCyjl0iDs>kJ9z=|-p)BsF)I-)-pnB9v=Xtwg( zG#5<9zarPrNA9odftbIJr%nScU4o%%`-%>g=Y8lA@59Pk!}h%44j+OQ%45&6E?b9W zD<=~yVjFMec+`zI-H#=aFvWd-;wbSM*AL0%0xN}fU3005BJoyz9sc}v#cs-L~++r@c}r z77bZc2UHqiB1MD6^d|ZCq`O$q3JMQ56Yo;Id&g6Z4>u=2esV3Xo-V9T#=jwpcdMVo zIHZOmHz0ce_9+J7>-DHE#bR8+O>AB*E(YQ(`(QLs3Kq}F5W?D%AY#8%J3K(Q6id+o zTe=hqx}a!(Tt>56@uOP9N`($R$Ns2kYI5z8ht*d)g|`VIc({`d`VQE7?!eUb8y5pU zqAI{hy1rx`eK{mrgYm3Inr+?*`)Z1`lJMrekqH344goMc;0d1WUaAL1;8HKBo^`Z= zBCpPS?W^`Qj34#B@ntLMW{H==hi|ew3KlzuzB?ufJCEjfl)vt1Aa|Zn@4_~xU}43g z*Iue2o?QrVcW$@kz|LTu|5B9vEJHB6&94W*gKkgl?X2#(BlkS#ZTN1JHIuq^Qre5b z?7qa9_upALREf*SCk#F;>{7eCRXne}S((RLvp$DWEqV^ZNb4m`2kSBSA zhnu*_FHPYNAtfDJX_i8hP29%-Z}S}Bx%-@mfn_7L*&F>5v4$YtyE{IFlzfT)pu$%W z{xzr16FljXLG)KVuO5Ukbb9GdeLswm*O&1uQtNJyd$3+9 z+%ubNa6LGgy{z(8yU7!qU|=nr?LiXnbl4Wlm2!pdn=fEh`w#i_UL-t|%U&U4UKvOf zPZ3BGs$3l|cwFNvt7bRQA&D#sm!9MWNo^-C7hk@O$~I6}dryUN-QC>0jN?123)R+= zbR=U@#Y;`fBfIt4Jhv1o%@07#eKToJ!K;n(DOmgj$BZQ3T@H8F=R2D!ci&8#k&WxI z2)_S(P?R(Gj-Y^JAN_c}wBf{=ha2;gr=>$i_H^Hbyxe2`%(8ozEf^%llMdUYI(%3tnp0MAoN%&HDe>XgX)jYW$Dl00j)w5kfdZAC%FmrhH$giaFEslKZV;<4H!puK!`mj&1J8?ut;4$oBKZ;sQ zk1T5@A}aX-Aj3#gyvmS~`Xw}ZI{8(>TA*VpFLIPEU(VE^}X_b{8fK2cruo+el z^a5E@&7fGa&)JFH6~b-wR6k5%E(|FNNYMnS9WT-W>iSVnBD`xwQj^sQfz)AD0#fno zAtw!{TJP}=W9FAotMRnmaH&WapA+ai==h;11=EmPJyFQHjdsy}$R^A`H3`L>6%CW~ znsy}-lp$`62%0YGPUL28g@&ngOHLaWr>L(ee^(VM5}+uxyG#TP7onL~e~yC6e$!sB z-YCzBa$PxYsX-9=$Z}A&I+`V$63{fvLAVn_id~1Plu@V!A zpglLo1PfKrUXxRkSQ{G-Y)m9W1Of()I!OFr53Vw~qPp>Vgw>*-gmh=X!wXc* zI(n!v#BM#9p82}d6HAjQ*^)Fc2u;G6dCX%e_h6;y#*Q^_%{iOIwG>YJ0Cnkrz12|Y zkl0-JT1$+>_dRAz@m#%kBXaro5b)G~>O?&EwOWKbCy+*6vj77B(tO(bjp4%VXh0VL z8H@8kdhwyCu9?3VA0&%OxzpxAmsRQysxY#NZv=@tdf4QJohVmG@=*DD6oR*~>h5jgMupMC+1_hgqRVp? zB4{ z(V_qV4c1cxDOq}F#4_T(=J1m~&TMygyF@en;7gY)Fo$tyr^=tVNfC1yiB&pj1b93~ zZix#AR%Z#=5h!1J+9!v)LU{87ub`vMSg1K|j%t=MGiLl0_mC7j?+4jObM4E)8gYcq z!4Ithdb@Ah4$D2dq{xigZy>ge)|r_oktVM?b%zla<;o;(+!_)7YKCmc%g!d9`mtdk zRm=@U^l0Wmo}t{-5HsO-dd^#pdG~z?9>x!hX7e=W$yf!BIIoQ6@XvmF@C>FHJ5!k} zd^2Az;&3?2*C+P@KbvA0+oLShN4cU^#!3dOf+v`nM0EHnDlI}vWzkWE2K**!Z|aq* zs-uc5Y)v#4g~r`7BW0Co(O9?Yl^b`XO5Ao#v{8grT8N`d{rF9vTxwA15Qr`dwKeV5 zr4?4~hDBd}RW2=Tnx;BnK3U4}s{F!ZX80&UZQQuJvUumSi5ac>)a&u; z(vEdgi-PHy@#>m}9Zn0M%Np;h$7>7LIZW*!90M$T3I%F-&pPNY)mqwQ9F_aqlr_vQ z>Ar2488f$UIeNSqeeLD)ck`h5Uh;3xl^;=&;fS?4!VkyazS`^HR^$qbuoKE^I)GZb zLvLuKl1wyX+_Ur~dZ~?mZK4I&*V3Euh7L@5qLt*er7!1$1w71X|QEM5Oeih@Q3*umNc?jDsN$h#q!3zgk~ne@TDFOlaqt}lL=4m?G)-uh#j{|~A4AN~b-9z_gBDH6MQ zLVtCkxf`Dh)6c(p4%-B$y{RB%^Ba)jFb>JzQ1(eGJjj;c{RwxKt?D;49 zGtMYOwdn%|eb58^h=}vl=0(g_*!|3c42LM^hX*>Eo&n+uTZ_LRlN3cY<@?Gs$nKh; zab{+x+y@;{Eap^B2^w+n4~x+FXMzfgYHj@t4PTo;5AZW_AdBH$j;TZ0m-{7QZL@^) zYQ3}tpevCU1y|#W)dxxs#ld=%?%mp!rl7CXO+!Qn-&RJNZWiA%YB}@E`x|QRza6uK zywc>|K{K>cKfGYh@!zEPLmOF!xEINm2Awfx-w$zeAMnlJPB66^f~*fYAPCVW?%b16 zm(*d5KBmQDxJ$ti+5Ci@jSN4GBnl-x_UWH&UOwrt7Xf55DSSOfSs|lVOR#so?FRC>)Iz7AffdF4uzu zs!vh+CheU0DHRcpo=sS5Ez&E4Mt{+pRsLgl!k;}&D4nh(uz20W2!!#|h7#LI zBUXWIr84QFdRy)BTu2q&I@?BpYWdxf{71D_MZ;B=?|V1{#%UjV*)RWOe*Veor`IRW z43Jd_ro8<^2C>zb9gZRL`go#TWH9`){l^<*&-6xO#AB3-$gUc8JYO3Zk0tpL6O@9q zGpBPbpdTr3mF|9d?-GH?R7E&Wc)bq0?}z>HV0&%i<{?2W4Hy$nxy5^I@~!*dp6O91 zzBrR_J?9or77zXqh{7kP)M~mQpDF@nBBimL=KPHbK{tB^;S1wm8S+2{fsFnPQ*R%O z?NN~46%~mzOyk6;vPPhC4d>hy+eI+Yi3*QP&U0dvW#BM%h@3Qkk-&zoU*rC?1X9>L4#n?Rs4#RNHeeR75f{Zz#Yh(2pt53M6frlMi$c z-KHUqd=Ho$IxeSrpQ@Go785{+U?pQCcMr{}IS9ly&&VOpZu^rJ6-<#$^a)O-heYFx z)&E1wtBv!DHY-amj3%sSV)&g+ch*owulSSnG?q`NrXdbT=Ol2AqfU%F8aNh>MU zD;I1grlO1BE7QYLYu>4?sOaa68rEvHD!A(NT&%;!v@JK7d&&8wX*B_Wqi+p3J4Hn*QpF<*>1 zf1v#?c{n1+TK-eNa5$za%cV_C25%#7U(P>eGMl z#_9uZgDni3XFmsw`0j9`_CTFM7{71SCkElhPeTj*6Pavj_ezZ|{WAqD>;D3htM6~% zesP0&H!90+DjdFYsb5J?;@kL4*5ZNc7|iW$BUBftKyvz3Ij{t$8jl^;*XP%vXQ>Xl zR=44tU9~nY2^)O5i^2B%$$~X!f;#5-lgyh(eR~)qV?&%TKz@PmcN-I)fCFVvzF=rk zmNNF;Ln6N;F2VRGH{^j;#lJ~MOtlFjt$+a|H)&&}42GqFCW)IpePhm?@m4F5 zMI$|auD*FWVpJ8V> zb=`>yk3yl!m(SgZ;6fF^Vyw&GR~3CQIX3<|>hJZ;6s4g4T#WtcV_Se*7lGl%#KgY1 zRO6Bkm|M(BmCQ^W#S&&Ho9*(ZwZAcXKGjQ>J+J+6ADaHxxTyq&{KP@e|2b|HDQ*6j z6<5R=^)OGqLO>2?7c=G4HQ;+jxb~|5+v*2DF|VI02`NQPNrnf%PE68S1$XYPL2qnr z+Vck>PKgTIHn#}2NgL_A5dSoMo;|HMY?%6i;l@q_KE)8(3BD7&uQK$w`8*fvTJ+P= z2Akw-8x+~hfqGcej5;^-ABA{f9f{yfGsO66ijlgq+~a-Yrlrk6iQREW!U#f0H>tzF zY&V5V?cekMPXM7id<-iZOJ(oC?ageDH+Q5V3BRA81*Rb_TcVKo8?8Z4ZOywe6Vl@g z@3o*UFUw#Xc97Be)6+@O49jM{hFvGoJ;&w${cA~FFUufX{=jNU)#_rc=NDcL z!09mtP?P^vkb3=&0`-)C{;duAP>V$fOgh>CN~fG|KazWDUG5`GJ-$>AwZR_e}`Zl=ZZvNV(1-Os1+&&PHN27{4oUh z_vQ7!iGiLBs$%WW{$djRI+?N!D}!;MuTv?uO?{*AfOX>J#exA7B3oL@nT~59A6Qa)So6iVFs$O-jm?v0$ZDFZG^Tm(@)|<;$Ct*R3jEX%)aLJ1{xR z;_ndpY*qC^OLuDC0osmQ#YN)jd-8d^UR(_pKe@f`|i*rBq z=zmTA>#JP^gqzO49tpSmY~ngJ(P_v7*i@H&5F}i8fn=CToC|WF;N5-tL0B|895?(v ziUpoP`#U+2g8<1$X#;EU6Y*ZSE&sHzBV8nvjCdIdC8v4ajoIqo4U)%e!opa_tZ6~fw2p00x$_8$6hU!EU_i9k;HP}xpUnm#=Fct&Bs0;G^=WidG zoXwngFdh@_J7(Z!=9_{k$03I>=?%k{^!=5e(APTM&LYVdkG}huJb=Bn;JyF-$D{8& zp5~P}Lf-E0zz-RvUvBe;lAKhpkLKLuyQpoHS1-y|t>rjp&8IDm(y2dMWtZn5VLy`5 z#o&m|m=5HTL>wl9LJ~YnQ(n&x9?}u}T9qPO297Nh{1_!i2zWsq^RFPCdWYKX+2hRU zBPBOk>Uc-&c&XKD(%Uf#nQV5WK!{yt>p{^>UXd9r~_@C5@4 z+kK>%ldL7~JIs3=UET^rHv5S%Ttw0X`x|vBF(uuKIrlFhydCW0>5w}X_Ea{uU|(Pg zQK}VnXSg|g7#D-br(D1NE&)fnFme7PKM#|)=5}g(?aa@xJYOgze}3$T!~bIUwdv}ux1v5TK2#RkSWgUpy};|>-4lBWLO0E z!gPq6qepH=><;1HpcoIiR8Dw%^qXsHZzzgP;=g(PWUwT&YlI~Ki;%SxyZ?!#@t5?J zb}KjLfijtN4kiNw8yGbk_xRV**FNL_`{VzKxxRk)VLX!^8@L6M?pZ^@(5gmqP}%kv1*d~4WLh21w~xs7Ws)EnW6#7*Aa zHf{?coeD^WAq^0s`;2!=nrc2Hsm;$MW9Wgv3dVWarkG+OR-iz|O0}4jmXy8Jgi9mW zTxXxM{Uk{02L%l5o5AqyGbid~cO~@GnL?Fb)(Qe;&XiekgITNnGDeD$?G2yR%6Mn& zmDVFiq?lUpzFGy>>x%`nluMRqUey5y_NxF2^slem)ssMkphPfSjt7Q*bpB1n0OA8p z_9jMRj2V5imyjXJtICx&whAR*3f6gpo=BE@t{#ORY0oHchf$8T9432#{z>e_p0|Ts zt!h+07-A-QGaR;suFaKeR;|pbW@n<}LWH@QhnTLe!O#P`Z(U+m=0~duvY`?x&^tA1 zDqOoE;9J0gaj}K`6BFPIlP$$N0M&!ljHFJM7h5W{pYZvJc+c{pfb)nECDMM*hsyEd zZ;1hDDw`X5?BX`Wxe035nUA0A5bWrrW+Mv>pWOu1@HQF+5Eh{=P(?}Ke>#f(%zXZr zqv*+ue9KM)0P)=e?&PLrA8fz2ovZ;6-}9sG|BGi-8N;VW$*1C#^B{zNsRjnB%0(5i zOi7}O`4rHUZFZ?Ajb0F0xeZuKu-K`$%3JE zi$25|W?_=M(sHUGatj> zZkZ-&KS6l)LI43yaI{Ym4oKNo#Ulyx3iC5Ne!1*+1T z1{*sma9FFcSKVWV`Z)8#p-BK9x6t+3B|Dq0N)+MK z_n-Np%hm0X5=yjT>X|J^iZ7Z5~>}!+tw!SX(M?N#n)eU3=i_U z!ps*WhlN?bg!kEGLkTGI93i3iP-69{ylydtNj`aKim~ZUD7rNgm6I9dNnDhRv>`4o zOc8oqTvjlRb=@YUP$Mu@@o*SGiruZY_y85GBwF%hq}LG7!aPCbOrcJ_O3p@9zi zm=j;cdBEm#P~FhSm`<{K6Z31UaTAx`0t+DD%Ob4I0BStbB3p8bLnvx$cz$))V*9K)Q;P<#2&7Co3q~ zyAKy}xyinXi4>-utfqa`+!>_7u)VjDo=D3gOo?W4CSw3%=>~aKzPvGlHPIOjs<|@z zA>FWcskY67VM6?c!k+f@T?Ia~?GEqAmX|o0_BfGr@u?wU)YuT|q4}{|1Omkz zs-9NcC`EyFDgNQHREq?5S>|vH#}%*RYepyTc9pMRjb2@W@Uwue=nn9$Js)hvEHFi1 z2d2=TFEPF`6=R49F2A%lMYG{&@Kk7cS0(*S?VrLVj(2HMrD?TMt)uIpLC#M$0Q0zy9A#>artSR zxO)dLzI?V(Uo!Lt-hBHT4o}crz8NJvtiWo!hq)eM4EuGd>&>>PhCM1YGsIqv1{h^UBIxhAqN`ibQ zJ$i)!o)I(9&7w+z17kM_k3=u)#on@j$H`qup#sq1awbD!kI%jhJ?gS9UQPx2`B&S53l>gEK>>nF62h%9+f`N3S-o=Sa*jqR86o4gd^Uo%0~5ak_J( zK;fZ{0%vAJOc(jlT<2!7sMAImEM@X>n8+9VE3{2edlGW1T=XFaifh*$xm`(XJzyho zG`FnG*+z)BQ$us1hN=ZW8Ypud#%0+l@ipzrmiTyCy9=6sDZJaXx(u~LsFNKUG!HuO z-5}ZN(I*ziIOX$cn;S?quRl8qD^@u%%qwj#3)C9!pj662DPl}W>~-Q`l&OkP?c?ot zQ(oCP^#oT-a>~&nS( zl*epR@Llyrm9Jm@Flpz>GWh%NQ^vu6m{z^HoZ74#FG>qIEw|O@oLcP#v<>FUv!x+b z`EOO{pJ6SMDtH>j-9^|^h{i1vXo`S97&BY^D-Q$HqC1h)Qcj3F>3HsISw8}H)p8Y3 z!zH=F6+)WW-XBI9UNgV;l&mmf{;`v@Qt{)i@6$ld_ zlAI5fFk?e6(#7T;8eTKDbRZtX!7;8n!nYTh*mbLfsO_57s$8~FH(y=q`lO0oU0|Ty z6}vnid*v&L zcqSZi9;gEGR4${f@aCr$Ln(Lsg~IbxM?pCfH*Mtq+6tCL;8))rFF|dKS7N>)Bop>2 zn<=v@FNqkax1Vl&yp#~X&0jI!{A_!9zO?b{>@_L$Ix90NwM>PIzN2(3>OnCHyf5Gx z0}aIR+18bLbgc9~6Aq*08aa48hN%KLNK;JM2A2*RGTMY<**;)8jV+`6xqjq3SVwi9QnSb#>@7kfBtKnFWr{g9rarx*6Vn+u-0ldB75j2`uN@6> z>Dw4FdwTW*i3O&j@1}6w-dbWcR=;8fNrBb+C^DWv`1|5K#?7Cm`;$eks(>NJNiecc zf!a&KG$KK|V7S#Z9eWN6V;M;j=+_Url0yZ6ar)TA{S>N;a;0A5FAl-J12u_oDJYM$ zgfJA22#5Ev1&Ulroo2*n@Wu_tDa8Qy7_&M_T=w#D^i1I{Ib)Ex`~@213hCf1B|6j%B5awI3*?j9`JXVh9H{b;%wBLlDhG%QV&(8W3z z3^lV%-<>{XFSM979pbvWek%iM@3R!&dHt+^xTtFKUmGG_8T<#P3miYFZ3=00Ev zS+;!E7GalvSx;*4%=}RSc=keOmf55gHb;|)cVbr>U+xA5ggH|*P3zxHsdDKI5?euD zUzV`aL>lFwFwWf~tTc&+KU>mG;kgIA=7bo(b@lBp%S2#s5}r@*n>MMkc8V)fM(4?*%}510>()RAQaLmy z=h$HdY>FjPqG@umg)paE(t%^64mU@WIl^wygtDtMdw-WPxg|6K0FR99FJg^{5|A!6? zjAq8VVo%vrVA2I#S3 zZ3IpZ+gnZZvFjQE9nfh&^jlS7@c83F?{c|&x1Ase{!h=Z_&=}z_nC4nKQI00?9?(Z|M+h^%zUdwCM~#X8gdi5~1$PhKdwC+V~e8lz5A&**~KG zr>`&@$eq3d&Bbe$9}x9|D13H*Y$6WDKF93NAYwZCa5<-(ZX_kQ&AUEeI4hD~47f-E z$jw+bl@i5%=lsD09;1P9IKY}q5p>vk*Z;I|C)cz6z zp}o_@vy{esg)`iGWTepxXGndn_|W-te?qDJlXu^FE#If}StYLGMelLn^H?eHEkOMu%qs1+5VqNky%LT@ zOwW)y&!$ zKFpWztU1#g*GfhmAu|uegBYL;K4Og^0HR&a=BkpdJWt|7ev0^P)&YTr3t2R_N3hHvh@?3B^1W~p5TFJ#T;Dk`tU|}`+7@}Mp*wxjyIneYul2UdV0<5a)NS(qg^a+1=d6uo zHG>SDb_av^dkwz5V^FtZNCX6^xWr{B92fQqdRv7Q{kYKqauSd#ZVFFxQ_Q%XjQw{7 zjYjte<2nu^^;4S9xcH~cyhR#j%!AWOiXNYi?ezeKwE(WX5Vo8^rKl#Hxvhn(F{4l3 zUfa*QzhQhhSo9%{Y+4NBZai6vpr~+PjS^Nq{TyqVak3U}yYO&5t7o-wR+r9B=xt#q zn`#7->y_Rj#*_NO=W&;$_AeW_1Alyp-ZwP*+5zlyeChn5e7@hqO848rAg9suZ^L5T zA^>$kh2hEPctfGBxx$4u2RmwtWbbIP3C2?$!{V1`JC$Ew{@4q?Y&$+20`}jto;1|- zo(E4{=^BWWy|fY#9obvw#kx-qrYP#bd>!da$s&Lsg}gN%NC16sHSl^7;bU>iW95JgdWu&vPg{<$CU=REK2?=2DGO z%J3scBCHH@Z+{f*6_~si>GCd@=6gu5$XRuiF@EC4>95)twdk2FRVr|?v_ivZSOuB%9ZQ@+z1If`HFf!SB%^!m z0vJiNiDkLG`Ue$|If=dZp}b?1k!E@^$sZIg_!5iX8A!yYjMZ5@$ZS@!mid-4`wlA5 zy{TmPvNm<`_WHvYI3G^%k-e$3Smq#Mt4bEAaid35py|`=Oa}tuQ1RX z53S9=BVw(nE~FmorjfHtCJUqD7*;__6hh`Vx!IFdd@Ppf)b^xBd`nb4dcOTaFK|qF zON{fEj+?_D&q%v6)`q`&w<6VyJD7dRgoeN_zO_{JzT&k@lId!J{tSn9(}xEY4lh_9 zeVf&4J=3gopD#6D@zlW0M-?5O^g=27kuS?6NQKP<#b`N^9zJAw_4M83vLi&j(;w(o zh`WVEx1-+C#%2cI^dZ||N0hWQlvGA=*;$75mtM_cRorZCiSoo2j15%k2#smcm`%}XU=yuI+EOD7f+T6CUVIU9){WAu z>ZH>nlNDngB;3+_)|8WPDe|K_5^+B^Ol&fT?QCSFGUzQG4v;>fh|$>3CG&jWvlv^S zYT7&N4jKk+C-&Z1<8_#MXChh)pcgE7X34L(InE1R8H9;#)g4FlPjIf4Jv??c{& ztT6bU?&zds;WyPSN*VD*O&-21S&`_x=q^3uf|F6s5BCe;&D|lBuKhg(-5fC=-`&zq zq|GgIf}V{K(y=}pDmw}G%^W0D3-`O3lXX|@+@#gpfFf#6(%vLiqSL%_3q-Sq5Npj3#5I1An=^!5?cuPg#rcetx4gF^l*BA zPz`aY;E&c%R$^XuXfHoDFbafm?_!C_%p)VGJem?N>>{|%4GfJMXea8i*r!j9T3#C9 zf}>$%m*O(!+Fr9Gk-x37UY!i6Q_miDZ@yT1^~u*FCh_<_R7I9sWjI$0R5#EFWz1sg zD-qeP^1e`?A+#));R`n_*p$+jSKykpB-5jp<~00lV&KeoY$qz365npI#(H%$^tI+& zA<>I11-i2*PYUw|X4GfCek7n6`76({!QG3 zE{y_NU!@6E`V(KqBwuDW4F(-QaaTX6pdV+5A6QePIFAJ!tld;7WA5V5Z{=m2uf{Xw z&zES9rr-Jq(FnFK*Q-k zwm6pry4S$CDsu%3v44U^ks$_h0CRrr?*;!9FL!ev}~r zf+3z()b;elxH2T)d?_NXLMVaefF=&IDQBhs-%amLwrF*untxLemDa89S^3n?ufox*Zh$x-aCdV0e#vc&1Kx z*G9;I9PyjJ@ZqNL(T(u;)0`7Y;UjVpGgc8~F(G9k;hiTmEUd)K*pYo3cxy?KTTPKW z(~)0JBKIhx4g{kPb)t^kqfV?M%zP=j)FNM>gyXJ7brwAhlSBENQHKde;wGc;9}*K3 zhY(Ul6F-c`V~@TGk0$bnzLgw(+d7&iG@2GCYA7j+SvLmi5yKW59_$xc6vN}rfbxot z6l(Oi?}6e=ju9+Pjupa*)Q1rp@DStBgRptR#hYVgJmTa+qwcU1r({uN>O`7aQtud3 zm%)f-O`_)nBXo-+^g<&ZorZnfh&Oncps$-?3h)3=n=#HpkNyZ%J?=0uOpL{F*&Ki#C>5cgUgCiM~CJqM}+4%b)wYq`p);d`W_U z>_>f>Ho`!ffH=OKUc1(@EeMyIzv5AOvQ(giaMkX7yYvJhb}xV2v?CaUh#s%$o?;JV zBIi+JBgZP*OB!1XU57b?Zhz_T)cH8ObMK2x&ca@~+e5v-YiT}dn>1bsUF>QeTySglgiX|?oTH792s^BOc8IlYpH?>J?_2W2ySn|lcISvdO!wotHxJCivt7M_3r7Ngyss0Rg2|GRxt;H}7jZ-sV_b4hH+lFoh=E zjLSjiAY2?2yE^%%B6d$`-7HY7q;5_*Jd}|z5{{}4Mb8^1fs>2NJT!$K;lwSIA5G_& zia|tViH%Ha%xODn#?K*1V1GSN8zDyw3Yb})79^X>qY8?EsT1Z8r;LH&Hj}%IoITQp=?p2;(>qMDIO` zD*Fpczl66)tP-`nXP7B(_#`U)75357tFrCvNa5@2$;s9)9Y!qE6)-Gn7os=#0>3f& zfbQ<_M4Vo3bH4^_hu`bC_04v_m)dBjI*>%g?x6oBL)gK8Q~UheAocfg4ekH6?cvzV zbv)-XWq&;HzFvN9UZuTmdtlu?`B(Gm0#I*3`}xZJyz-WUR6v>_-rujhKVKQli$74( zf71l~&QJcekMuXpqeZ7GKbM7V5<6?JW6s;9`)oGG2wz$Iqd7RSWkas8R}km)nB^P2 zTqNO59!Ap24KY^`ARzU%*(|Qw_y#v)7e5|=S97R9Ynsfg&Y`M~E zsN4%{QX+-S5}1V`k=qwg_JMYVVl>>sjkh%h+zrH+EyR3EfwF~!_$=Dlp#Doaj1RvJ zXMiR`0(U@j)Jm=7MT&8E=rl)d$(en-v`r|T`pxI<3NFzT=vLfsgtN_-?(3!jnc zf6wI(&^Qq>awwN{8=c)U239#ndN{h*)%oUE?T1e8zQPX^L&dhPXBx_YnFcaFYz@t) z$=085njx^YqR?Y;C>FH}cH{dk1ME#x$#$yL$d%pM*U8Nq!U2g)xmbN zlMfeo+!ToOjiMYBaTacB8mam~iVA5%9%9RLs%&Tb4L8 z38_^HsZ0MnlwO7|G+CmBeK`5?Yim|H*8vYpaXs>8R&m$MG8wZ0{d+SF>htQ)8Pe7tXz9{I-NELaL@ss!d`z%Us4q?=cA6Fl+?Y0cje zbz_Z%Yxr=vqzR{@M3E=19bFEcKKsI>$j~WB`iisYa~-16EDW!yeAXxq9S5C$$WqkN zb?+b-3o2J*80PcI=Y1jV4{nJVY%nwPOnd%UErlEmgfg-rkau>y(ObCzuJa?L3u4E}0^SjK1mX&7j%{=ifi z2vZdi0bFAh6nIVz^T`;FOD<3h_RA$B!Cq7mhgYznB*4>t`7yX7R_2n5TTRQ{e1v9E zv3i87pA(E4*opn0$Y`jf-8el^jmKVsv&Lg>Cae2pCJ z`yWNCKX{>7Ckp>JBErQZwLD>?r;Nff6l5^75Al zeQpH{{x77>Nk41biF-wPD}Sits5Th{KXBa@9{9vD@`8G$OumXo6_Ij2v0X;#f~d`X zZ?n(Zy}+gvH-fYuaDl144SfuW=KaX`$k)i8Xs6W+6tmDC7{)c{xwt)zO#-?yR`x2j zNp0%fRYnE0C7`uG!t1I_vK;+Ubycs@@lv5(6CLL$!v$;|-R}vh>RkXGg)`vzV)d`7 z2%o`ue1H)qp8)bBnB1_~)j4km_c3s4pzoR|EnheCQDTe|CqtmC>D){*I6ewJ~gul)0*W{Hsx+U+b@Do7}C#L|(t@%e!tg zL~+SCFn0TxUc}@}LT5)K(;;#U;$fz)YzR)qmOiMJHZNHb452ln%=zqt#~MtV_SU9y z`^m$Rw5NJ!Yypp9XQ*6=F9)h9b#1jr96PQAa2=P_sg_o$k!lo(2l76&E^AujK$L^` zIn@3rZUV_s704K*4tx!+i<^JM2`R^Kz^7W$mq=0sXbk_H39;a~o@o2!#CA4e^PR!Y zxbq8+OyCv{zfO*DwM)AC`7{L6fAhZ;$5yv7oVgUv@tzF1p`6eELjD3L-V%zKk$O}< zOIlpyl*8d1=%Hx}^)@j9X!=^kDu|`JlW(#m*(%xW_J(aGn?_`HH`PDf##0*uDe3X{ z)6jQMv2g|AG?uMLIk$R)NTg1+D~;ZH%ZOjq0CZWvSb{EpYB@9on&cP%#{9wq<_E&f z!>?jZX0bIYK(NAj35zGKnGpY=Q{%t&80$bLAO!Ha0AVluH3$rf zct|^cCuB?e<`7!E0@h96MnGVGhjKM}oj>8ir;e+z#5=!F*mIf${T3Qq(D&1(B44*5 zoBNCEywV21g@M7KJ&Fnc*LU^WY(|VUybSC)1p7Gbddn?J3)0%5V z7RYesKoWn%J?am^@W0s?l8wR=`yXBKf7`Bar zX(%~N9tT9>$v_2@t5*h5_Y{EUSMBF_SpwX&N_y5!qeV~2l>x8j_LQ;7;7h9Jqn(em zoOt6Af9?xi54))!D8HQJf4UYiFPbSzuOYZSUKlpo_FL;tPj*+x6)DSI4Yr1fR=?p2)+CLVzi%)M7)o7*HgJ6_19wt(~vAK$PG4Q2M|7ew-~Ny$VcvD z=KI+|MqLNMHV)sF$Ym(YAD9_v|^fZWlnE-1YKrv^HXB~hUwbCxPZG_`CP|4a8zDI&Lon{ zQwup8PRlEp3%KB0Vxn^XB49+47gzKU>zS9;C17lW8t)!jmvjGB@0$%Yk#&cIxk$5gfG>L`~su)%X z$&%-i|86yrr=4hV^PjzmqiHtvTw0BKOZ@X^aZfZ_?LKX34*puh##>9>G&b=M#)Cqe z+>IamMqx>1*fsH*4kGXIP5#ydOhihs8_}jGA6kq>K9tnrO0M4+tr8#1P@=Xg@^2(q zyW5m%{MEM|1Cx&DmEf0^mgsL4ZO)BP7vJSV`0vhFwrx#cTRPkRv4Z;t?cDO^i?$zs z>U}q*mm2AmHI^J9AU2fGkBLTklL&Kl`WJfmJV8)A8J#Gx8_VlaToAdvAuh-%aA2xx zS{ZVJm7G*U7;~l;U}%baL_xF#Y(^jmh$m2lOpT4{h1x533Z$^#`UenTlJNmU>`aJ) zs4;L1!?Em_m}HfE3Yp_HBd2I%AUBh{$bqgti^nb;n4h_Qk-H`)6iKxp0%p%br^>^J zA-VEU;yJ0GUo@MMKHTwIn;!ngj||5m+})|8CzM9a6CZw%(-+HfuVB0>CbvI<-Y7+Crn-O(IJ+8bScVrs z%xZE3=x<~572{Rr9A!@ZIJnIXl&_rWTNZcKe9XUpAXLZMe zmMT^DSQQaJ63X?f9KU{;NY#Gwsl{b~_Pa18&!@M3kgqIdCl1S<5jVK`-%;{@s&l^w zI9-1(?MsFMpOkOhm5*^Q4+Iu7I>wKc)!%LC(Qg;mX0G*=w+ejy^ynGZvB>SFy_K$L zYLzcPvK7|zY2NPKYHRtv4MYpK`!nN@)%Fgbt|A`o9d^uq1XR7h*5XzMd!H<8LD@1)#H1pivdN~F+H-%6AyCeHPY6?`>X1{%5=BR{*5 z{_IMXGCy2hbbL}wQ#mw0PTOLJB~in#nMGgElM0$_l;cqlZ=1kgko>rYsxZ~&Lvlfy zR*GP6sijcm~{kX@#)Ju-UuY)?RfTRjQfP|lW~&~9XT+Of}=-b`+%bdTpv>dA^q2RbSK4{oiGPZfmqiKW@Q zyY%gz@AoBAZbeqG86R;y0U?O=Z-451GjX)Q`)2K!-hNOy*kR!uT3=_XAS|#>>$8{D zNZ0ZslZc>H#B4R=2ec&iK!FoYF&ceRy-z~yiAnuSRV!TVqFzq)EaFF}raIVW!JK(j zcOO11vv>3VILAZTh(8eVCuiUG3Y zGJb5_tE~6tZfW&4?e`k0h?w4sGVWb zvgG`{cR!%?EB=s)!#n8h`hF#{{_3PId{)6;0LN7)uR!=QKG16BZo~ap2}|3L6(wXt zUmXw9tZ&7N?t5GnyjY9Pyxd`hVVw>6;f`mW?L@+Aq(5Z2a{jg)ZYB9*{Km)AT)Im^ zW*MS>M40Kg+pYH-($X!6=%Bh>)(6G1T%K|tP3rO*YO!pkED*`FE_vMD#mY|y#?sH~ z3Sk$;s{Zoh*|+M8a5YP0>Pyt>IW!B;#!E#Xlp4*KXtfGy zm1)%%Ym1~X-*>uSl@ed-z{P1$DWqK;Gg0mmUuyWZB(P<9qQdEOsnL&?sSc7O_GDsN zHVFo#V*umrh!=KdwKsJ8geGeu((TLzymUXvH`FEpz#$6i8O4*ww{!XeEV+dBCR^O< zt8VVvnp1zAyqa`tXvi;r@^nytuEwo8xk-*)Lt$?P1$k4?`^xYO#SK{PNq5+HzD&sbjn$xK zI(bSMSfXHlEy!<}-LTI2=KRKn^I2yq=GVez>Mb=dz40Rc`T~`<&EF`P@$M?ux;Pc#~&X&8ncQRli!u=-e3d#gu&f7lXbDN5h<`2S3BM4!mA647v7396KjnDmYcKUTg zL+$%r$kUUqyIQ+KXTAu}VgKrtmz#d-rN}f3ZL)3R;@u4fT&KgwG)rxDLTA;;+y45m zSzfw;!C5|NQuHL39rr@ut*b%8$^CL}?p<_uokH|)_u&KR?MLsH?%F2MQa$Px(s>iv zGnzxocx8kkaw(4NJbNnC95x}w_zv@MVLw4JSviA>sY{@7)`0(*}!^SZ@3+PDcPC@ z66O?rweRhJHgbdV3?NnqykU9XlW5^G|KpCkT4vL*KkL1D0+o|)ri^{0*z+YimD7Iz z#Mz^p*!44aBH1T}KQ&fJi||rMCI(B~zHB;U>w#@MhFnhR4B3fcb`ToH>CzNxe)CuV z5tV*w2o?@I63kIPF9dX7^UAx858pqSm~3gXwk#8biTc~W9M)*1?j9(e6sT1c7})r;PpA`UlBB0DKwQ;hvDATEYiYY*gF6eu zyV&zMSH&}j5?-k~6Y4lPo_I7tacc`*4}B1;SzZ)9UNWq>^;tNOVZyRuV~(qn5H`wC z6r1ZH#iN&$0ozr$C?2g5CQ zl=!~rDxKg|*%Wp>6?WPi)?Q@#`Mc>4ZDO?`-BT9AT9EUqj05^KQHi7OcjDlp-WQiJ z2VX%oif*3=6uLix^lY_4BF*)7K(;BvM0zOcNVd=&!O&eclRH-7iIxVBdff&lTrF5} zzlVfbV0qbDMx9{?3HMlAH5xq7!DC?!TEXxLokHQCqT<)x6Ii3k*gbB}xRWPG_s3h# zBm5L7A_GpM!vcdCHeFIbhZNWQoP3Y`G97aVC(69YBS^q7??DV-v!mRV4C*cAleTG7 zv`vR^=H71v<0N$BI;`SehnQj@@E+=zw`!Z01_rgcTDle3YdnlsO^(-Tj(_bM|EM^= z@@8zA567*oS^I+?w<|B`K@?>1u^ByN~7;gXJVS2J^`Uu>9GBkahJ$>dh?Nf95Lg!5SELFxDJYz95 zV_7$2g9`Xd;)-F?#>E>$Z*4Jk@VuesnF~E#E-9i;L{r? zGFhT+3tJyblk}(EO|D%ZOBKuIFBbxC!Sx&Y1p-+{yB`~#u6+1SO{vLMyUwl zPcrlD#xwL==sDs?=S+mpv+Jfao6^`CZLXpzs=*Q|wDqh&Q-^TT z91M{n#);me>C4J+P(OYHV z$Sn^EKBpCm_q^h{C7sKD_AN?G$_8FsqO2tU0Rgu@Th@)ekM3L#8 zk42Ip&U5>n0HScI%G?_PyT}GR5;V>-o*z4^)-_YcY**8~Nb^7)TY+d=`513TtBc|kdw<8r{~QNg=Y3vr{_5wX@Sn(H z|Cu-Aug`ysQdAFq8+gU1Sl+JZvCeTF3x>?4-QZ&FjrY$Qc7{?ghGUS}FMf<9<4Y5A zaWL&pen6#=WT9{2m5-jsk?LACsE8v`Z;I{)lf@EN-WhqGoMGh!^VXvrAmi({qYfd$ z*qL@7Ug-A9#w7Vx|Ei)?l_&kC;^H`FG?G#2>&>;fNC>1do=?W6N#+}MzxK1IUz;R% z`94ppPg=IzCemv}dVG%$)WQjz^Tzn@EJWE!q>H15nqfd_T1Tlz^ipF$g<9t z#9H8&E|`x@Iee#XFE0e9GBvxG>6iQ^4|Pu!+@l~m4zQ7$t~ z?x~p#Kd5ZWH34Ui#86W!gQwnr5~)}t2jNnqgC}_1m+}A@g^GZSF`-Oy1R9fii5?@b zh`!q8UN3{4@K`L0{aR`>EeWxP{q4ZzzRKtWv_yFX$O1-(T(q0} zULUp6VuU#mv`QNr9vrrGBWP4dXB4Kd2K1a)5t!eM@OTm@ozeQ?A154xogeSVN(-9> zRVWA_4;;*jFRI2^b~`O9|jFDh`@ZvT&LncoTlvp9Hr z5h7Fl%iM{zUGaGvCMsi`6@NMWJv97S`53VZjb8t|A-vO`idj5C@Wrn)rt|Gkg7N5W zcD`1qZRZiJ*+ORQ+)$XBWi&!W-ezMY#}>q`Ey3MnozWJn+s?tIW@{->caAYB*)OZ9 z7JsG!BW6*oUMFums?-)E$+XF79O@O{;L_Ely1lk-mVb&u^eM^Npy8RtrEHcCT-1gS zQd)}N2BEY4&KjQ7LBM{|2^}u@v6l!aIOc5*38jdoCj15J$(2K*$aP@!H&8V_O(!92 zYXq`tJ$YL8W>-kE6yhjcj?>{i3K7No zHKc}RK9>XRV2*h-u!5BWcHxM>b2SjQah{>h5&bpZ^e>hq|E^%6iLj8^?tA#RNCxE{ z*w_(PFc^3vLy%ukbejzMV@RE?D{OhcWHPj*?=Nm#e+6%LkH-~%$o6%&#%V;`320QV zKAvSP`u}2^zf0RlHs#-3HU72RDT=RQ;+;$;??l9zP-#VN z>6b$2@Dv)XOA5XZQ7&XzR5C=uK${Xm!4T7dVtj2caxHt)5Bbb(h7>)6o1i?=!l>t) zdkj;tEfarSFyvW?ouBH1e&Xq{RW5+7G7o?Pw#wFk7qC^{qxy%oxRv42M|FSVHmD1S z$?!1f5AJ@BB7Dk&{~(fH#`{>8N9er5KqPR}c;mf>L%xi!$m?5wxiyJb824T|THLNO zN-PUS!F{Ih`I{8xFE(2}f6&;zpF;&O<^FvDCG0P-{kckY-_M~su3=9_APo7WM(7!8W}gUR#Z zEYD@`F%SE0r^)o5zxdUd#bbyVzxxyyz|i7*uv!67lYUhS73roS9`Xw{TlhftFPJ0t z*)2X$%w||Tx}In<^2?$xkB9Z^U_jvzhUx*MXxjbHsG|izYohruC77=z&Twx~H6m#* z|8Pcw*K;am;lP-cF>j;z8o6Yy60I1;2TcSTPszLAIUL3r7uS}H^CItGP=p?gPybx9 z?|a#;t@6SDD6N+1|5;k?zcH%&YioShPR@4(;{9PJNeeTotADrLlW_0%iF`xV`f$O2 zkyblHnJ%0D(^eThqU6#@LjA-+mVSq@@r-cxXE|_rYcR&OcMl7luRTDHP zsE>=3@DHTZk!|+NiIx;gT#CBOE1etlRJSlUR>ySGBu3knnIS<>L31V2OwA&Py@K8N zDJv5uetwW+ocU_X>+V9cROgd=vo!acb+Zg#c+0hn0AP`MW*~3Fnvr$v8dG-2%;%hx zc!AGmc``N|g}LcjpVqZ9;$XqG30Xyjg@x}LHVQLppf7b`ww?laMQc~q7t4fBx;M+4 zkN|wg)#4iPl`7>ZU zcp|!$&_x0w%a|b2Fv?bYpU5eb{43TH7!`;eK!70Iz@+3s*-|lboi5TxA>~>?@ z?^-e{;RXal7lJ!$rD!?<<@dvD`goHy0k0)n;Yhj6I0dNzIK-9kJYeBTZMC8gqcr{> z`ixo*QNHcW1L;P*osY->Z6A&!I^;_&j|ZrUgfyz1%(+}j>Yf}(832*4!d#6jW=^n& znmVQI0L`1krcjSTVCOeOptN}aSq?0+f@jBH;vHE`3Q;ZG*K7-mw1vRKa{-*H4A76sQbb^ZpS+$JhHw+`tXhMZ zYE=kEXc{IiQ(i&flTy5lsy_g&AYDms@T)lR$WawkEYz<)y*FAKJX)+H z|3Yv|5m*H*C^7PTq1At(RvR^1W?#zsd=~~e9E_H{4P(_snO1LyA1e=hP@<2{nsHdw zLHMj<5hSKH+U?={E~ui!RFH>!!r)b9#;akoeKhW998LsOh&gLjR_1`}j>nh951I~OT0&pv`M-)%yIIV2v2Xi{@T1%~*< zE#9w}dM4TvnHWmPxVovk-|#N(L6QlFk&A9E>9(|i(<09}-#sNchr~fEQ?~h9Xctg! z4grbZ425H_&%Vn6VbPrhsCG{ss&Wvs7MHWg-}718hA{St?;4BdWRLdFyPOts3mNgG zo{tMeDRieH2g}60sk(=!;G=aK%bqUFyTes!xf^P-eWN8F)g?yqo6q{E#;PT&%jk)+ z^6nDQNaW!$ryv8E!LVO9Ul5Us1Y8i1DRfsL;dL+|eUbs8&s&^yO*pIp)Gwyv)9%-G zQrO7K7SWWPk8gR-LDcLFZ8eVkL?CP3#}l~sN>RNLC6(?6+yS92HST}xYQUWVww9z|qOnRfiRd*Inu z1^fZ%llCblLW?s?L|-F+HK|m|c&fCu!kS_|rq* zpd4dMKTk7v;PFtGdrLSD%dDk}E2npB)Bf6Sp*;Z11tBMM0bZ_RIhgTKcGx7hp}~O> z4XV*f?a*4Z${(s!&arVGpwZ{NGBlVg;gvj=QkQl0^8JZxIT!u zAX#Y$H@Y}*DMtYSK?5SoAxpdwWRw>>V-$Cme(dZknc$n4=PNwo3(~-W+P$>FRkd0) zP(!`1@rhK!99wN)lZpvnSL$)z%2Nj)qN^jUgR!TJhPW#8PvJ)WllT24A3Q!F;x~2< za7qYptP42%5C98Vb)5+CJ`3=HX{Ve6{SyK`>jM2g1qMRb0;>-MS|!D1m4ZGEzML}% zN=gVysS8S*2+BAM>aXy1A0)f42D@7ZH8UrIYM6pylBqF`unFg|kwB+AUPR#K zr)0R{bLRf%_rn*Q!&lb)ujsbwBWsA9!mNym1WvA)Lb1jNC>FyQ36XHW9pC7h1RYw6q}7^DvlVGNim9 zlBqD5IWeG&DU`7gmRTFcdLG3?5`Et#ngf~`&A=S`C_3y>VVDR>4CrBu*k=mPt_Z2g z2l%KoYB7($10q_Ju_+0WffG@J593}1M#ExjO{7B>CIVi# z#N8{5wpfqjMT}DqRNEOLIG=f zDudC4sLu)3V3P3%i3y2`N%e^-lZk2TiM_`%bSZz@O&rpatE?XVam2x>@MMv;pR{Wsn8_MT;l?@jE%xn-~Ch!(o9@|Ok`3O3KPMu z#N ztcPI`JQws}2QBlPOWHVEnplG=CMlw?SE`(4&hUATyjG4fFjwJ6Y;98R+1*Sg<1F)d3IAqIR$KdC+I_JKJ>)=wP33eHFSvs?zfeC z^Nh9{&$!XBkxD$-hvEPrC@f`KA8WZ1Nrua#us{SM1AttCW=x!)GF3S9?(NfR3v&Zl z1Sldb>eIT_M=u%>u617-^0E*2!IGVEpEB@nt(Bq5eIo!s3qsC11q4vTJ%8XWHD@dq zjkxOb01q3^AuSjuzmz|zbi}pvYf)+XaCSDb>pq>ynh$_B;3*z9 zq7FXyTO+zT6c6)3zJ0t@oM@zLP=I#;p$azQTE2%0LwP={A6J_-HqZyk>`)?yFczm6%VQ$ZL|sax<)IRFFXfSPuk{!jp}c z?gOjP99y{1qLV7&MS)eHDL)OCPH&Xvgp}qcHxx8B$Q27u3gk14>d_2YJVpd$V{^Cr zm@ZZEd3IOdAb3;?B1tJ?sS(|kBvMHbMF!0ATO{+z?3K5zayuGWR0YQ*%tRjRSqJy}Ar_}GkMMSU|T18O> zzQ-ydmkNxHQZ>Q%ofiZ>i=Q@Uz%F!!H1NCu0stTr_T{1Pic{O7f7^T)p)-8rXC$My z0!TR!HDyJK_#}X_9c8%;CiMw292fHT9Pk{+cK#!9OA%Sc6UOnbkskuWWgr^20*%1( z42M|b4s<%$fWc|sxpyxt7CsdFzfi{Lgz$D6D0kv%KgqlxE^CDgBP|JzA*tb#>SaLM z;=)$Ka|Y>Sg$UYCAp^AST*%cJowT`8AxI29yqGD3{OEPj5(KKW@}zP$zCxe;t=eP? z2#uf&EYm%TuDG<9v3558#s%*rIdbi=`Cj72e@>AzbM2zTKaU5PSV=a z42Mf#`$&HNwVzGhIf{JX@xE^G77f%m-hrgdE1QU(#DrWPKj3AoI$F$NcRyk35Cw(5 z3lv9lWrAkzEaSylxWKpJY35-T>)2K0r_+OZL==>yse_>B_>|Vl*@fCKf`;e$8&$&I zPY3BN2EJcIB`QGD)|J=R3)40z)i$~wHu*NHpE_n(I%eEEW_pL%)i4B8G;+CKs5b=yRRgQMF-pnUC64^7sqPcgVAi3`>)<=Jy?7^dGrTV^vlZziRqpz~txJ7d-!$ED zhfV5}xCkNp6SWD8sEMvOU&Y4A2z zgJ7xGbNnDg=ani!Z#YC9NWZK#zI6C2v&WC|umM_%SX&=4tEu(q4VPy(UlEVKGJu+` zIeV<><*ykAtQnoI_2{ffn@E(kK6#*v3j!~`^1wH&Q67m8L3iRpm@8p*NY9ToKF z+2lups~21S^W57HD264!t&@6v^Hz3sRSFDAT2Z3rsLen;?BF`n@|<9;^$2Vtv~1ey z8_hetn|A%F!G8DUyX6wO-K$5tH_f}yvR(LD6ZXC#7+tS#F#c8a;6Pv2U>XR2Ox(IvY_WdUgdZ$*qy7#x6 zqhm+;smRutNZ;y-E=X~xo@aPOi~?MSm7&<5a!(xwXD<3?JV{DpIL|+%9boI7UkVX~ zaN;QG9lIyublpEn7(2(W7?Oe#nAlzl<484n(S51swhP~ITU^F(s^mK zeCddE)joUq0eaa?9~ADYAF5c<6CtVd7_{QWxL|*FleOm^zQXH z=ykIC-Fdy6uWxVWB5oFJZ`NmTHp_3epf@{I(5+cA1onwfsnClS=&YC@fEzT|>IKD^ zx_5>(-{y->!0Y=-aiJp!lU*_=Vc$?9l_VnBRkaqF4$My`n!YD-i z$u$p*yJOkQt(T9sO!`uV-y&0J9hnb#q{d06Y8_jSl|FCrr_esJnyS8QJ=>M4eQGn) z^akp2ISvt-Zw+fyb=NsR7wPRzX-V3$FCFyoOcF?BkyZ~BM{-3jlv)AXc$L4xk)evv;HPYV@?ug z)07?*)@l#LiAOlETmm0YPAn&y=N10)*k4acoc++fZNsWPgooDu3+rf*QIi^j`u9mQpTh^+n%H2J^5U%-=Xl3JEE)_p)5 zR-_C;^BuTc#3MpdeSRh7|1T;Ta_s~5MNu*b`ym-ff&CF)@_PnQD=-=Q(dud#`ZL-j z7zSYP;NK16N+PBWzE`9{8^Y&Nmlgi7nQ1ZNKKx{s%yW`wOJJ#*lc$2PL}7y;;==N3 zvE`U2x)!=|IyfJe0WcEDj2dlZ;omBmn7Hyglmh_>!CXiKV8GvBWTHPRiA^hc#mG$~ z;X}mwuOZq$6oUK)reFR&2}adhu>22@xg(f3P2Q7%!J2RIBoJ-tc%LK( zs2p|53-E&0!#7Igobeh!YkrMm}WtOdBQ3vQ8WQRKUVWHc{Tf z){< zB{M|4n&@84T;b8K)}}mq+f>5kxmE>K2%xuam>c$1epZ=E_rvA?d$j28Y^x9YZ{c14 za(9*ZXyg3;Hd^#gmD0b*L|v;p=6uqGzgJR2UlAjY?+>EbceJ?()*~DLm{av@W#!In z|3|x>d|-IM2iVZyUExFuq!CyJo0Tz!|6(rst{=N|bJZ5BUf z`~z(cjpu=dw!-vZu)%z*cFwG;!nf))jWN~9wm3m2-jOK;`pJJ5i}o*9R_ebvx3UZU zeiFr&ud}Fq?DR>8vg=NnD$S(MYqvSSt=bs%VOHJP;%Af54 z*zD}THlY8Ggi2V&`12_7W3nsN4r!VB!4ZkG-rb-e{*eobPRUlw3HxkYR^;7lzIbYd z(#n>}u!xE>gBkzVP`*&f{K`KKrx5+?;#NUtdeWbAJ-QAv-rY=}wfWA%W190sEE|#W zLRE;-^WI`79`we<#h(Y^g`euU{LZ{71V{l^0d9ZW)+x9CPVEI=)Si8ADm-z8g-h`p9!NPekVu_ zU#ntQm{y!Tf=L!{2@-32$?!VFK5Gu^GInk^Obm+O}-?QbYVi(`<5sR@^J1 zwle(aE4HBM+v3he$I@mKbKlYF9!{&~ImDpdw)}LecY^Ias1+SlvT)B3TLDOz1%GfG z|FW(7lRN#5AW;Cz8Lr{i^5E!VqLoPLmBMx5UE!w<75L>kt5q$!6v;jsU>w2EV65wm zKr^-!sA3AUucA3egzefe5=9>D!(RtD{Ix_lGprh%zbH39b`>F1{XYyEaA_NVeE9GF zFQdV&y8UjWpaqYKrfa#OcVf_g-G<{iX5V{2fn^gmkohniOx8zhwy={IOe?NN?NS=o z?eonr?yD(GgM7QI{22v(D^&kWi6%9ur@poNU{&$y@T>QBy}da}1v}ekB&Uhr0V#Te zR)<^~Scv)E6c>7$LL#Z2>N42-u2P(Ev_$bcohTJzQL7Bdx9jd1gm?GP?q3E&j~QVf z{%tfkD#Kq(l%Ch_rNiko5PU5WaqTP_WpstM`B{#{4ecR{&qi-xRCwBr9HOJ?k72GqY_4S z`Oi1qem9T$IG|kJo_sm{Hi_={`_b>&IlpOt|H?E{oz^n%9|L@-aL{9yF!e<2EJa2f zXUFAgL)6B_Q%`){?y1)!?TW+$03CP*XS;n6rv7}qI`z;LN;M%QeY&|AOD0G4h~@}R z7AfiUCgqJ=uq7dzag?@>kvwzAEucPMz zkR*TCZdVP3v!6UCj&!+IfIBK#OO%<$^J24SK(E8Y{@+=Pnw^L6+8H&UJ^`i{&QjZdl}J z*c376{FzZ$Qu95dknFosykSV>YO-i8yWwPGv%J-YH@gUrCPf7LAc*pws(M^Zoil47T7IJ#&NF6yB66A=1IpqtoHq7^gq3Y zDQ_!{gw)zf6?h<#>@nrH8zr)Al4xQ!&HdcxpY1DgLC)TB}ZU5g5iQQg_9FxZ0OZWc7%` z_0@VuMMs~<^I8dIgbfnt2+vDLv+8Yt_=&30`wp$uT5r=7$g_58>5YAwJFda!OavCUApN<@Wus1EpLp z`4xZqmzr9Wxv#V>&vX3@2@#3o^_|pb9Kg&V8PkyS_@xxtF$=oX*HeYYY3@5D4E9h@ z(=^c59YlJV9hvcymtHr+6Fy)`CX1XH1_pOL1D|iROzy2~4{@<8;jXlJ*F5t628Rgd-c`x>@xW?|SkI*(wJFrr8ob zTzLmFvO8T$#ZN(TNi|>M@L5ZjrnGkI+~JG0vpX>NWV4Hq1Pb3nU9`z9Gd`2qzMnY> z;cS7nHPU5LZJWZ9tSST&)NqDO?{=1mEvwCS6BKp8t z+CLe8N~G?I9?1dIeskn8f`J~+QV?@18i_R6;3@0+e(swUu_)%P*AJ&mPM_50fi}AGi+C?~*o^>+N z!Swkc>^C@$pHMiBaGKb{x0EcUgj<-Gv@TBhadfZNR;z{wo z%DIb{<%55s$^r;p9~W-mLkz{ery%wKFDS?VTKbbh15=e3geRPJ zDNvLY4@twDABo4nKF%Ao+ws12~46# z0f3|g?|2$PBL>7M&zE#d&hRg>D6tHIxH2^G9CXY1u1_`>ku<;h5Tlxm40MX}a!_n21M zacIzsVlA`Rz1|S#IcV_PJ8jgYHrV;nVCYTuj(1S3?0HM*Xyek>eZYiK zqeO)k@GFTssd)E8)Y%qE#e?2if3wvVT$`m_9RDbAQvvpoTdL)VZI+T`d2{_*0?wo4 z6KH1_oQtu{{6zD!_-AXcm$>&6T+gZX`lJ%jc~+Xd&c7ftAA&|OSnfwp`t+JA+)Ei3 zTIIDp?{n^}OgsIu`snh!U$~7v14Z6Ej;qH=bKzZ8mPDz9V8b9-Z8!laOe85QVA_2# zoXy<3uHbetoPk+g@I-z?Ir(CwK%u%wy>|m<{5=W@KQ^{w+AKwF7^~|$P9-SW)P1ot z){I#L36S41B%2=25Oz|)f9Ux;W4s<92^jzR%tW~&1O4=h{q=_br_aoszdwi^erX*U z!LR_YZTy)ecVZr~eiTtM{O92NqQeM^#R_#7_cq7Ni~{_HwRt~vp*&~) z&`ZL$JEKTI{k6o7doS{q)ulygCt-~kD^mqMqoqyU~xmzU27ctNIUdmnWz016KVM26_WzCJfi@pDQi zOX>qYNDQKSukZwp`$bx~&LVv1EY15lah-^t!R$5oLAba88c}%M1oQM@+029_cG^d4 z**-_#0*#csaq$Xs=;8e0;#I8AXKVC!cBUN4-oJi z)9-E!)XE@7SX)X-Guq;=sH4W@#y|% z^B}0n$(mxQX*W|={7}w%P6n>8X}%!4#(V%llx03BDy=@F2>HB91y3K5or%?`rA;fE zuy#zqA~0)%MMAP8>q9}AKv?jWQawkb3jFp}mTx6hte7%pol{1S08-wU{fo)5kGQS)6JtqjH(Ab;Uf z@WQ+=mHh)fF=c)x2@{wztDy$g%}_UIvXo->OFq}*EOyEoLs?vH#BOl zW5epM53DAHv_yGY%{txE-5%M0YCE7HfYo|EkG9=i(@>e6X zqe6y@3?N#LXO#EAv|P&!WGGsb(!BYwngy0*S{LA>lOXoktm;Lpj^S_+i{UZdVcBMX`C)!|txbdy0cDLP$ z5buoQJr3u5u|HM^LB=g`P)iw6{ffK7xHy#}qNMW5SpJGT?am%bfeWN433@DFm{ zXs*tQqDdZQh~mv4&HLdSnj83&+pN)u5_lJ622wk-we|@%-*Kd!%PFRNB&gM0Mp& zIO(478@VH_>BjFP|EOxrsQP}Yx}_UH!|}9dGr?M_7YdH^oHyEC4X{tJD6zgp%bpsI z7!hR*jVRfH$$S9uZ4Jny)(irf!kGr%;?=AzgmC?=!D1NyO2J~d&>vI2@F)z6CAnpa z!lfwTNCriHAQ#Nzle1THIab5;A#RA46LX~K?>*BD^QIgI*!-#&M8ECr_pr`CRd#>Y z>xmcYKl7%fBR-ge1u_4ab+;$ofAi1kRdhh52v#rr3AS-qXIjOA*(NIg1=u#8)zthW z^3QI%#s5zr;s1$jZMEdB=BR1m5g~#3m+`8lmk&BXE6rvvF*ilRE|HP&d{yOrC9+&QE^dq+& ze9K+4&aB5__RmQ1*A(-mGI`#(I$DktNmt5@%IxX2NAdqU>w0e3>Ud$_w_#KJPlJly zIK<@I^4UKk68{2e$)=?!mwnTt;U*iAt9MZEL4bON*Vi0@hT)a46nii9r-#doY~y<4 zc-zJctvk|s8=ZEi8yuiB+l^MwrU@6mL5vNzikF{{8<=yQs+LIp|Jhk8NR17terpM`aZwIH5J4)qiQHa-%Pw1<|zCz zDwzKyVLX)am3nZ*06VXigSp7NDf}~QEC;e1J##hb<+43FC0+45iFe)1RcahlLzN>Z305_VX~9E~ zuW4tjsq?rbE7i*^_0|n}!CL8MTOLg8(luRzBz1k5b`ec{Hq&e^$gXa<%>Xifn>Mbr z#=GrYWj%WV@SMKe9mx5POr6+^ag1FD7oT5#6!Zw4Z@c?M%1#t7o;s>+egiz*3f!AFnDhQ`vNqX4ZSRJ*1+Crc&XfC7){L3MFLd(J zpPg?gA7HpW&&?KUe4Z60)&;Wu>hW;Z<5D4Etv#euN4AuR6K}tJc0}f&oUi5m%usf$ z`@v}K2ltbE?4&po2on8GCnFIeW5+A`x*ivO;{DD0n=N{H7YDOBuGd^Hv*)vC<5h2< zv-W5w01faZ4n*EoaPFmXJ_wEh;zeK?v_pM{OBu%Qj&GbHvyt06g=6e_=e|C2MNLas z*dB;fXg|78p{CM8z@{Ny~G zo3j{6mSrG14h?=}L4o%du(vXK)@4Qlm~9LkywHJ{n--wYgYIdU3;SgBV2BD)Zu654a`(=R3Tm zX@18A=2Tm4r`uJho>40l7zzfQun{=wB&REdJff&Ro*IHYuk>JdtF|6u;S~9{QNj0N zmcWbXh~oX3-8^Ct6<-?pIcT{zQG}0VYy+?fUx8KSk$8EsIoIR{Eth*_(WsWAbw`m6 ze0|}yLlEyeOWAyVakjo0@fP-Ta}Kwr=Lsc{n)5XenAjAn{JjQw0)}*k>|{xlC%xlgqLCHY6(vhH=s>iKcl$D@m3$ zpI4G?#1cRI8so%BGiCYW$?&`EtmmhB-Y}bI_+na`X9iLhnP-J^Y?x<*AF=$H^X4Sd zS)j|TSp=CSq$`tb#AZLzEQ-z#j@l^Fe&=cylj#m61(v)Unp!HU9ZT9Qt!Zv3E`Pm2 z%2wX8AixHxz;!FB_BYW1uf#!O>kA1OC z-B$Q!S^aJqnQi0V7;Aac(M+*z^HtxbZEa%NGlLX6!W7eZRHMS>b{&?lTpeiQTXr9? z)aCX&@yuYtPr?^pxjzy=Nko(3SJl|fWy&tL?`A9CvhU%7y(gok^F}N>GFPlN`U(z8 ziuwgk*^c_fQRI&XB^mD=4N2S!s~VQ!V?Q2Nc_M#2Dy<$eB%W&NX3t+TvKS$9451Ac zxCzA#7J!}&JFzbXE*!HQ9q~8`7x^yA3cH*@nH8puu;%(%++DBPn*!q8Y`=u|d_7xa z8GesTV(c&eROGm%11MPS`z~B0$N12NH5)S2C$d@4pdfM$X$L+$4y2V4u68a87O9ER zZD7*1InV7-zuB?a%~jC68tg!c5bFEDSAMlWAQ)kC)a}E@_<8SJJqN2#4~Jm7RdLt} z)0<(H2!`yD;fSfN9rgnL8_2u5#UpW>x7TMMGzZeNCEj$ta zv>Nd;G|NmSD|O(RLBy2O9WBw0xzeg?Hcc07OX?CW)Cyj);zWqA;HBPRm0I)*)lYV= z-c+-|PG04bZK`Zy(E61q)=P-to7qdeNoeZ>USF`a(jne6USw=O#x}0!*X`piCl5NA zl$C-t-e(b(N|kvQ8tWU7dLkX;vs$@_<0nwhiCoM_csMHHr$s-^(h6zyJoGwbpqe2G zEJ_<2hZnMBV2dn=ec-#7hQk((t!s+7lq{e-v^hVwe{W z^($HWc9;|YK6K|O|Ir=GrvcqU8Mvx`V(ga6xj{`Q=A4Qu8)M@fqqQ25ta0)@fkG}% z27_Fyi^JLxNv0~8f!}bme0?*D#P&txh(ml^#nM=Ok^4+=5YZ4aR;a6`t4xm{_;@}r z(_a^uXaSx;d?iW@B#G2fb4m6&J}Hig8dvG)8)O&uXRQfg~d zQ=w$IQk+DJgXY)(++%%eTuSxWiY`*i(f8e!$MI%9H|#a- zh@M;&cTSDJKknSE*h!wf*->xVKDPDDUFlwqLX6NJ@Fm3mGKVBs*M{u@@uiiUN7Jrr zCys;QAFzPA9~)qlfW`20sQu8B`8&Q#V81L7G}d);m66CywFSqKD%mm9C*wG<@se-W zeH0n1hzMX?x_jvSQS^ixtoabY4i4)WhdYSOCpTu%uJ6`peiv8yWtrWrzDK{W!i!Ov zr-}M;G1|j>qV8=iZ@~o6UO9gUxnVi8hg3Oz4mGgxue+J>$A|rlk^9n9-0269`lw~@ zF9{^=F=}WDwHj?)aut7%TzcneU^83|$-Zq;o;H5F4tafYWufy$A%~q*qW~AOo zy@~ZcY@9<#D6NwyJ#wX`pm`)3*r>{3S%AJoD8uRe*sy8K$w+wps_gX;tsy~41pAhe zw(Af={>cvbji7D6!q>u`gZf&Eovb*wnf0BMrrGDauVDYhB8Pc&Ro0ya5VF(>y zZa-r71Ard~0HB`RM>F?Zrhz)6C0tQz1H{-%#Dft*y6_P;?#p;!U-p8JEXGpa>$w>T zZgudeB~n-H44~c*m%1x0SdaDsIIkA)pl4msGa}VTd(3pAo69i4t=7vlwX;SHxCtHB zn%OUEbu<7ieH7?%W{ZtBA^7mkKA158oOh^;*5!Z_}%4SAhAj_E~f zS(5>{UV1&tjf98oeUo96k^x{d!Kwu#lC5~DuOfq5F;5kd0bn7@ca~l@}RyZQnBK42kjEj2CE7?t~+G2S* z@-P7u7#wb}olZOf*>>nM5TtD+l={Z|tCYz*>n2y9qva7bhz_&Wsh`v%j%3Qoc z{H|Wm)4(?P7HE@ZU974vuK&>v)b9gbeE~s;qzyh=z z@GYce?1{*(fef-EFah}7%mHhpfHiyQQu+Zc13)}a#A~o`8Ixt>laO5So10cN)&#&^ zek3k)60}S*bt&wLI={(@u&-xf%=uyC{NczIVe@NYjf0f)gp~6u?#8v@QTpij1~E;U zuvbMRPVAhlnCzCi+#TzXPz}%lAk5}DEE6t33Lo+y3Lq8*AUy!&LG`$X*vfjoeT@w; z*2h8v0Uh~~kGbALTW!AZMJ-E4ZE8d@xkRy85U^TAv7JY8kVG@1Mc-qNUh8tdhMHrg z^W%~dQO2EMk(m?3t$3a6MQ=v}xYwdf&w@oXW5x|#BZvSXYNUlOBvEr%a3)|Y!yXNS zR5kzvWgs2zVbK$#mGfiQLI9@qZc2c-8as3yY@})cVy3yDQ;^^5LO)n)pzCD3W?(pD z8;%5;#mStzCDYp|Mnb5*zvx`xlv<1}F#zz;CgL2O+W<>n>P^`I=EOJ(`- zmz1{wDGvG8P;497eQe)aT!XH48amMkPrfF z3k$(WSFv@xl+|?7hnZ;~eas7N;9sLh71~zPN9D98@A4x_1-;20=QYL#U`u<(J@i-h zbj&?e&JM!YZ=+jJuALrei@Qv~hJB98!#?d5zwZbDW3Zk?M zV_XZT_zM#)3zKCEAKcTzz{!2VogleRVkc8H@-UYN6_7U$2Iza`kY<`*IQZ0C+jLu- zFuX<$h{n=L+&xL#h9r)x+G?4-T931(3yN+KaEF~PLW~Z=rzL#q4t=DhW5Ci0fl>!j z_op&AYmr6INXt}7ix;|caYf5?H*%|hMYS@N)NN(jD&Y=;R?;8M(Ymour<8jt$_LxZ zhgQnr;V7U}<%oh1WHLyf7X)#z6rVeF`vMZQLaE3UexOy6{mM>*$)4av7@2GZ`DFzq z*}FCKaJuQdyXfKcjTKs-Ab2>AVqRr?zzQBW2%cf_8MFvHmKV~yPO|C@dGXS;@Fm{q z6mPW`S=Gy`%E+qP%mj&^Dyhb*yoxHMMu?CbZdMTicOx#ZV5K;mBfPj59<56CZ>`Oe%k^SQ6<>35X|^4qSs$K@n_4d#RmF5ep5=o^Vo z9M5{{y;>;+`N#@DRHnx%L*hoqh7I}Rb~V@N6^1~}Ep}$yO<1EPgGICftq=3=1REze z3Ut+iQPu3O&6q}2lCI6Pan&i`$bHoffi*aZc-UXoQ?cMc{7#+cw}4=D<&lGP1qH;1 zlH^F^s0AcuJoNr-Lsvr;Uk?D#>+2u0U?7SCo@ntY08mH+(CH)zH6pw-P_`H0q#NLG z`jGVA1-V^CPF|t3BxXK{o`+S3#i!9M>M+OIh{exp(O=JwaP7`LESLqB86lc9vL_9! z59lBy>u5Y-s4xIlK+_9maGM(av{}M1bG^xgffdy_-?)Q5@_`zJF}SaJ13Pc5sei=(p$SK%g#qEtSaq2wAOVyFER16#0kFhx15_tg zOOqeN!_UkJ$C3;0m0&mB>BStyC6NS~-PW(!t5YhkGa{2PZOWqy2bV&Kr%zFgS6=&M<)zXXEomHv{JRbR~uD2Up zv_zjnaSaEMOAQ36Hd*;_q>(TNbcAGS(&w>pW#;#REQZ0H>w|g5gPD(7a)FtvMHcag;U~E5OKZR}>D-F%Aj^QBmo4#(kRSqKAh{hW7mafT3r@{9LRLf4 z?^M1(@9ER{gVKNCon!2G_a$AZ7+=b{3I3Q;$ z)Jdfi-Ghw4t@j(!NW|*uvxx{SgvYq3M$J-TSMp*Q&9ozId}t*B9D_x&qtRG}VQ+e) zfuI~HoOB|sLVRkJzM^7mYjj*{Ocsx+B;%Fqaflk!Z|}NK?c8gQGS9^f`IZaEHhowR z{CH@>(IbY}#?so!Ac zr<#M)_?ZyK5?#pcEsYPLlL=C3jslMOPIdKyS;VjN6A*ODG*)A%v0%izBn^Z;%9@|a zIh)CIdh|q+8l>hNdKx-P?_UrwjcULE)+b^WmCJDQ%2W!HI&XKUufsja}?=Y#WX(pSf8Hdd) zOok>Z#vsP~G@1B(@zLfY83~F!9Sr{F88hptMePDHD4O(2y%p}R_R!-%^_c?oob!}B zEtB)jVh=u9KrEe$$byd1*@U5HhB(utgmZ?Z$#OeUHP;Z+npfqLPf;FG3zu{RxB9~{ z_1eJH6&}J>8R=CBVJ$n~>aF$_HsgdVn@g$^NQ-ar$cTg;eMEvpZqgLV2R_fT!B|b@ zY{%iXMb>y@ttJnx1Oe}L@rd(Q zSXtv~33Xmg6x_U>waMtan*Mk*zz!8;$9(_5pW81CK@5 zrR#!|*POTO+n0@Zms`#s24#UdNGdn!D%El;Ss(2Pq(4(=+39q02_tM$H!K((-r<4l zPHOGSm+j1&>`p%}m}=jh8Qxv|xGP4xgX21Oce-%Rhx}FS&c{m7-um-i6nU{$vBaKp zrU{q|)-)^LRPe2N_UIF)5F?Oq1>pa=L)**t(MJeuaI0nGQ|!(fPYw7nZ7`i{sa8o; zR1BRoim79Z*>sQXCW@VTpCkL>nign7mTXtHN}g%&+5l@|#wR?l&^UPt@c>;8U6?-{%ky3>xvS`#O7B-}th`wW&p1 zyRWxGP)5xxf>bZnvvFXXdX<|=?MJ6ss~HPNE*CM756n2Qh0k$*+uGjAVLo711pU!% zH~|1`HXRw}{k@p!X(G1Y{eC){lQC;wK+cKgQ)-4iTio0ZEc3kVX2}aYe`2x@04R;_ zS=tg_a019~xY5rt2YWyUkSoz;1@%@F7Jqpb+5p1IH(Sd9wW?%QC6bZ@Z-SpvRXQ3Y z3qSYoo<_zfCuU^;uySTzzwHUsMRNE^`8;|Hg%99g*o6tukP|FM4rHs-2!ylRWg{F1 zw?2K|{_tD>>mc8KP$VlQ7;uVZhKm6uJnTFLh?oT+IWUQt7^(|dAlQfJrw=Ft5<7j3 z1E=YP6(fZFG0AKPr(HVRj4+E?N^ST$dHfrT6ky$Dg_r`2(rmq{y6ak5GJfaSbb1>% zMde)^*a~$ckwJyn)nED`P#OPtWc1<$?~lFx&EpF1!=v24gqdmp!8zyN=ta= zjWDKpv(X+Ww{t_O#pKQ=Sacq1>i?e|On^cz7UEMV7MBNzQ_rjt8_PHvo6N63F`Tj0n;W^>2Z2OWt zjRz{S!nx=I2m!O+wuGGD)mb8aV%5#aqi4GZa~Q~NZ3+Ym0`AK_k#iSTqs#)ZSI1W@f zf~YM_G>J=PmpN9<(Jla=Aw+LXel_@D#0cE^Y0zDYY4s>h&*^)K z6JleQnRlsXtz$Be?%0PUQoVPGi}5tFrgQ?=Wd_K^&tXu=iz*n5QT8*+5nD{L029gI z<@#dV59cu6_@>bu_g!Y6C7xmbQxZLf(zS(Pl+`t}FzUy*%_HbTo0cNji%u+}NF&8Y za#fo3q~(pQJ&JyE$f2cgkP30JvFT%&Gc#2SL2xLH99HU_>g{MSyC+J+k)0qCmtfh=H;Gv zoyZImbL*#pi6i4L!^(J>?!D^DXYLa>O#K3i{UT>`#J?Y<9hEO1Nk5!>SY`Nd-eG;- z{=I)k+wtNP30ZH{Q=!M+t8ouyeKv~y1tB@iHgw-KYm(Efv+u1v)E&5W#PmJ8ULt$N zx60>GYx=lht?zpj3$D`Cuil`$7e-PuYx;*9sq2$LYZ6Nh&sfW&eU zi@HQ&QuCt`^PqknQl3ABcKd>9e1D=6Fm>%sg^*jcZ^kMvPs{i%L`cQ5F`?;3H%+(j z1JP%!#P@A`cH!I#%bTh@*FzIjC~M%#VipC+gkDnCJp*-xC9=|EZeIP-$dMYRi*B3l zls2MA2KgUU1g~B>rBr*|GHd*`saQ$8D9+#b5d*_}8d<4I?I_P@%M5!>$}&fLv3>{H z36Jx7NkrrB>2Of6O6vF535Yrx1Y2@&Mj+Y=^{a$w1xqIirE%5B zdA`h*j~-9GGk1`c3atEH*8#Ss4F*0B*Ms18f+5%d>$5Z{ zhYuSS%lJ5p4jgd7hhW2D*_faLumoAwBLX_&du5GMo~5bC6%Jtc-2jF^RlMb!66(h7 zbdJ!zeqo-g{aP18dofjLD=r{r$CF&xVKd51Ka|DH7I+jFY-wWAdaGN5)lwzE%1r!8 z%p5jGhaayb(Nen4oE(r1=4g-0@}$37j{rdPQe}=Mt_3>MMjTv)y-E)YQc{8FT%%FH zZ^U{y*9+G%4-x7wVASCO5Nw|HQE)*iAsSC83CvWzUCI+#KC5DuW(EfKVh3x^EkXIy zC_pTj*=uzcoV3k1Z#!>KqkqO*9^&eLy(sR2nBy9i&YOF(btb8{{Y*O3*wn~?I0hMO zpbiTO;>Crud2q}Ml`%A8J1+yY$4d#=!6yXNIXo3d3@~pyh1lMv3lK2o0@Q8b+0Vk~ zfW)+>A|@3gA)-7PmSO7T0JutxC4%aC!L^DeM=vnImL--~3Vl zSV2`3i{$rJ1o$*SDP>?A`u-k@mqVfWZ>aDy{v<^C@r+*Lp3?_uFta)c2JDV+^yH0ps0BVZ{QaSp6t$0P)6! zHV1%r27}0%U0@c2|4`g3cAkO)R1nExPUutf(y9*-JelX4c0rQ|Zz|=v3kfE!Ouz() zp$Lih8+b}E;;SEF1#2*B6Mc!7||hIllDEgLyI5w>PxCQ}65BEh?q(>ew0Rj|} zLhNjtj5EH^)IO-Zd%9u=l7F;Wa>!%d<*&?W>HoajKdtDP0Dvs;FA=%8(utGX0pJJ; zvFNmR>%-3f-J~-CUO4-0s~x z!QBvK_gg?$Ca9}$w0nP4Zhx~|=ozh$W10wdk0?ja6|o*MjZ|!+&WrVk90|*G%D|qJ zv>vL0p5xk{>(AtIYZ==jx)7?FH#ey}VK+?Ui>X)WtIKm-_vv)iaz@~s!=((yI)y6Z zg|4*>8ogcgE39-Y3e*-o2k9gmv^la0_)C&dAle%ivvXy<5y>KN&+p+X9L-e zD@rJu$Vo#e%DaR;H;vGe!+I;(T1r{T=j9!D#fOf{hR8k%$NG*qDznpq^>+nT36Qi? zkn2~D)HLoyI;v7tio~+qM|3Kka%D!+tX^#CsSpYvjQveb#>KE*MywfU-$-GLEkp1@ zFJew1P9dWhbt5wX!OjLAR>9YY7PQirvMgfKxH1AjDz<}h{W(#{W5E*9|q@4-?gai6UVplPHU$F=d zO;ZHA40V;__=bnKIcWI0s7t^xIn3}HU*xBD#aIoAI6H*3@{0P}4mA=rW?*4LSVCIU z>NRpHhM>FzO%1VT;q=jJ=s#(UgtPh7)yN$VVazh4Tv8Li__HI(d;;Fi}-{ z91+*B+-?LFty;hRGnF{uRZBLVl*qN)gcS1t+H-V?z|@ zL|{yVcnleM7+K93ju|(a%Zr zeNXTy=wZoFfNxU}02K1rg#ZE#jHQ#BhW6fNQ{`k-t-%=1%(>z=t|~=_f88ODZ*a73i-y#Ph?$4P!=G_%fi0A=B6NcpF^(fBO=Vt^CAT||_0L>pE_ z6jpPbDTuI3xTcQgMfEf$i*4Bc$h*C!kX9a26`rUXL|_NL-paR|-?s8b0_t0?Mfg;M zh7c5YCACTHLVTbA&*~6Zk2YctFK`i`^*Ij2OX`?F`&6>B%QeJvB#{g@0j|kdwdd}b z3B+%TV^$aJUm;>KBNkXp&X9Y`VHV=O1ka%$r*4iLDi3?EA}Ux;5%ZlpgrUR*hsPCX z%2lAG$2JVfFzlHx(YA<*fgoUy2bMqwwast<5YnQYW>l{bCNh9sT~{HJqICL7{WbDn z5aFIe_(ioIWqwRd8mPeW>G6rcMG%hIw`xtE)`--u=fbMwm?EI7rzB-A9qM-_stHo)VsA;oK8$wCW&)L7 z$h~x#GS(oVLs-}8P?KTY^dfdTL!z1NTO9?#ZgeeTI;Ay?m<3;xhk(Vxs8))v zaaR`o$2K1FCWrwW)BrlRA)5WAnhpdKfIyzb;MV*Z#u^+++Ch~EF&!t-JNRUTA}@5Y zn-igt`YHJRWAAmUjXPQJl*^k!Z(+*ql7`TT9KFC1ZH^;)&T(ZTw$LX*2SHAd161I9 zW;-;qB76t%CjEh30c57+LQ`0M7dqUH8OTstXbO-h+DH~KyP`@9?$*VWQiVy5reX6) zSrIl;V#HC)h^yxndiEQwvd5qw>5gwXeUts88osRLyqjC?<|9-73Rrklodl#Vf+c*KarFna&0!^v*nwmuUzs z#0Qd)2lZFYd5{3c&9oU}YSkEmwJE&gh`!69GC{-vt?dPvW>3gW4btEDm~}koSj^Z! z;S$6R>4*dH%WN@$-)KrXipEr=R4-cPf;;h-%S*akUzhsP&LwApM|yqvLQHA-s{XRL^|FNiGWRg=wrV`%5y8`)2ynx)p!LFcj$-dxUi;FoktK88 zGZr)><2FZjzpbs@2bCygK4Xijug8n#LHeW2qV|`&ZCA2vmzp%=O_O*`ajn;F-*2X` z1m)bzCiD3DjJlP-WFwAbx^O5poG!wF3FtN|5(%|Jv17ISB2==t%oif| zY)L$lR&rC8=da>3()ZQ|w3mxEQXDPptyl(!n;VNaY9HaLcHzq%L`3jHGoj!hS^9#* z_2YLk@GQFZ*o`*Q!PUrFtL_b}p2f0+gN+;7HV>87EyeMl?#*YXg|A~lie@pVE%77i z3DRu|lK1iSX5xG$Ycp?G#rPy7^;eea;18FmJrQ02H3JK~)hbG-AMQP^yiSuP^;C=C zd9@1qju@b`NL+AUS~{t|fF($kT`_g2u+0sRA{R-M_fY;s*l(%6OPDBfQayaWZ!-uJ8}S;=pN^yKeKPY#d81B zOVt*6%xlko^2w|(hWv&&#Q`w+>>Hf_mB;-$K8TK5d7<9w;vd7s1 z9*!URL+SKWO!HeW6^Y)a&QH>eLn7bIZ!zXcvvPfBRKstvT=_Rk=;;5yjphCy*f;)b zX3)i-G3MWW*#AnJVX?h?%VRtMqxRsP&^eL&BCLa-XGEqQzs~Fl*0cr6OR9?l96Ir& z$y^#6-S93z3>??u zlxATRGv3ApIB{EKii~bsIVJk9bpFWHNI z9cTm=3S?0IrNcx$l+E-%5LR76#(rtp8%r_ik#+h(hS9t73w9?8J`QVjM@K9PDLw%@ z9-pEkmMPX1-4Em`8N!-sdOR?DSh0;pvX_VOHVGIGg)>?(Duf*p`CHs!w?G2->TC=J zODF#V$oSD=^3UB3ABKN+nEaS#4+hsRfkq~LUynX7qscHGvd1h(zDbc@UY*8r_2aGxqp$DW5ssIGK$aHF&(v zf+(mEQ&BQNNSDNYD7MaodI!+1FUILWEzrsb>m*rOuE9LLvQs=jOp9!w;^G6<6EI5W zJ$qLex$#HK-pAI@ulPQ_IGA+!)ONB~{;B=@5j}n5M*Qlh&TmO4{OFcFV>9Fe*F<&q zVIZNao1-W}VlTNaw#zH;&9cw0Af;=28Z3?CFQcXJx{LZ@uCL_Ba=Pl|yu4aroUOv% zlY9joS1TxSA$_OtTyCX_p7Rx6(lfy^RNTkThHOkh$$IjbF;{UP_f|pNuhy|;i(Cq07mt!qT{PuNp?rr*ne)0xd09HAlCiE zAd<0_{+|ruAFI}_rH;xUz?i+?H^;vZ;$h3>=19;(K!oFEUxW-M{Gp~AacP4CJ^zn3 z$G3J4Ew4={?YKnnS)^a<>%QnKe!<=T6T|l5HimD~^oJo+I{)^wZ+{G8^bFRbyfsRH zG2m}lA0ozU0XHD#C)$1#Y&N;dD*^|(@^rJ4N@4#zh`(WdsO(mL$NH#_Qfci!R7Wz# zs$BMD4d{FP2Gk3Mtfg2c*{wlY1*w18ajMXv{uMyYKa8DrPTT)}?C8#}ex6b+y)^Dc z*3QGKjQ{92`Wp=KZXW8R#cFY570mT97U^q_%TPZdj5UaCpZTVaE(9+GwxUPZ;7)Y8G#@iE4ZB##|66*J~u`LS;NJ;$Qpe z@}VcJpYMfIko-Azn=9zTrgk!hpKQ~#*>Yzz`D)-)p$~Iq*k007>esq_4e_n4BGJU(S*cR~#=M}SX z$2s)d{-^D?Z?n(Q7BdvyVgM%9Np`?4XSmLTak7aV`3sd|v)ej6E5pH3r$MMtan*iv z9i}{rB~^?^=;c-r!a|10^P_vR78xwZ{&6J|y4<@FABtwAv4>tgZ_-DjdeEb7K^CzR zui<>v6g}FK?_@~T>{b&A_Gm^Q4VrIqB8g=odWoh$shzzQE zHeDGP=em~$UUaI~y7u;|HYyS%_JxkVbY(wAdm|qqK4bMqC-r7ghUeC1vB|AX(#)Ks zS+>%mqOz@IwaPL?j?%4*jV(FP;lTs}u~3TO3Y^4#2e@(P@wO5HzFzq=pws?HK}@{J zGp*Oo2kTXC;`rNI^|Ix=+7-^*yN!#Yyhe?vq$s`gwIX$jW>QT;aO>9oma`V=F#V@C zva|S-HiErv2n0)GG@c9Jc4>rWb$GoTipkwe(hjPcP;*o%-X=NzSq)!e z+y)!bPy>1e>5_&vMCM77cVgGy*@10PtyD$mAG!;;u?Xy}zLA)C1`irlnuCuDmpLAc zX-MoIyn`zX9Ln$T$|Q~G^6_v@_PJ(yM5zQ>U5z)9KHGDJ`nSzYgIR~PE2JHawtLm{ z`4RNEhmrwraXFoRs$LRN`W%c&vQr*wI&mJD%vd&89Kjw7A&)Gr#0JD~xvx@t7DSP{ zH!DTo5d6APK!4!9SyEi-qcE0B|5c8raNg&UVOC|?Zeojbd|Mbh2kXc3s#71ObiB8v z%Zwe3+W$apB&*oM1q73|4di2>~Z1JEi?9ZVMSLwnv;?L z)=4{=AqglP`%Q6rXnv_U<$7IkHSb24L2D$Zn*ENFwsl`9Wy@uQC;9vCLSE|P4*v&< zO8rqaOdmSf{V^`PsLY=>k~q}iy-Ql^gZg!~;WfLx7C=`#l^JGe?0i=KECHH0#(lN$7@MHa^x=gj`V%~Q5^fQ|Tj^yMCD@L)9K{$xldp0*KTRi1j*+V!ilva7 zZ^XDD7IGVmT?o*$g5$6wZc(15a4@j;jmAq@geJ-e043oGTr>FbN$s!_ZO}c{J0GHN zz*0wrI7uMu8SayI>zQ6zH0$>q*9PKUDZkofrh~}T#@%=^*4+a(tqX+byX z&|QnwlX`c^h5voyb;{06b&34xgfpswDR-bzoKw?6O_lFUKY~Blw$LbdNFuXo_r?e zAqQa68qfu%QJ%y}(hP^N&cR_TAtth%)u1^2eG%~-G;{M*_`GctZ+cdK3w?}q~;7%oem%NoX`6L$+x~nFi5MOdg!e?^*oj%_yW`ANNKVly+ z1i64I*%MZEL>}RWCY5?Wx692;j^zq(UaayhPA!V{d!XJkQK!2A?g!@X&dIrAF+1yc z$(drtP@i2dG_!aD#NOxBx?5wlg2!yY+-x*_xo|v_;X2)4ewbww)9xp?_Yr*o zadOA(?8kZR=8^2BAf9JY`CL0VQ)`fNBk9Ix;@e}+Sgdi{K_ny~fKgg+W0o?75)KOX zc4FK}&KTR11wiBxj>NtnVu033u~MZ_G&`MGDAa3sB-9d@ZwVdmE?d1T8~UipgJ3)*e@>X3&+<%MbyY^nD!Y4a2#*XXowSY`rI zRjMdMR0xD~G{Fr>BR*34Tv9smmb2=&kxFV-X=pX|6W{S%`nZv2)gR)DcNBbp6vZ;) zbksbaDe=A(Md7%7ckE9{sw?G}^7t-MD~_MLZkCmCc6+_y)$JfmuovpNDXGD%(s9^~ zP-I-7thNK`z8>jo<5GA9cpz2qQg1i%Iw(r1FsW9VGeHcdBKb9ajEka6W4;4)N4hhI z4+TjW1zS13eZ#vtx1NUQst)ICt>p56LCF;k6o9%mH9l87{6>Vxm+Nw;*)$_ROyDH% z?x#9;2prFynkx&=y02$y_jg;<`svw+eLWMAGu>{ZkW_cNYx0VJ@AVb=U-$ANz-_<= zpyVG8Pc;_h|D(ebB9#R9O!YSy2^GavL@BfwD~C5z?GQB*Xi)wqN&bfu0CB-n>D%I& zTlL(%72K`MD6+9)b@T&d=w56FT8Du!Fl zUq-uUnq8U0vYrdz{lHs=N0aKVj_R9-P0~pMox9eJ2w; z|HQoS+ne7pE--JkjT|X=_>lGG>tRSgf!sydg48$Y7p#s4#eNQLW6k(NqT?B$wr_}W z0{d>B#S{5c%+ZJ09`tsua9`3x>nu!Ch{U3Xl?pOgc}s?8^kKtJ$f(dMrDe7PBMB%Z zgrjJUL0yeQ1rdac^APUE8H*DP#RpDQzQ^^yz|&L-+;7LKH$s5K!1P5)ca7;MB{Kjd>Pm5_fD| zh6utZ>NGP%Q4S!`T3(Q1K?c(W1)EA@k=RS@8aiyK+=tVN)dIZ4F}unz3_gdn0>|E| zEL;NmMZjmWsF7#*0$XvekJZ$*ODAgww%tf-@&r7rEPdgPk@gN0Et_TAA1#*K{&HQX zBr^1=gE4peQ@S5n0k50~CIflvqsluv`L$Axhz{UAOMV!bqW5!KJ<&>}JheR1u9E(q z-hP`i{`gY`Be7mZ1p-n9#h3IrdpvK<#ogVMst33El`xJ-&VUml7EvO>F9&&DgY0*B&vS?lrm3UV2qSeV_j}i?oOd= z2NLgiLA>JP&GCl-Ji(L2U~1-MfJwHI*Sn$6u>$y%C%XGLtBMF~gWhcF& zxL16`?2HnP#N0o6sP#B5W(o9dxG+vKg zy3UVHWmiI=<^@&+=6Ef8 zWR_1l`Vlco>|I3XsvI;L`h4F-V`K3NBpK=0T){44X@DFF01e&wT%TAp_7hgDUgFmF zg#Lh4wWqRo-eY{@&V=dg$AebLxFlvk>Tdf9R^R$LjNJ14SMXrc*qk)^?oXALg5|MB zviWu;26xB7oUgSDky<4wPvfxks!KTonwErbzT#j3{CSI42+%{rxu5;hVzvbE{qt_% z|NkoX@)i#!PduJRfPUhFwg%Rh-7=fOu<1iG}Hq@As6j| z=BHO(;X+^?R`RXelfpNsMTf_-+VN;Or-5oq-s z^=x?XQ>Gxjdn)R6fAL0J9i=C3ECm#{4oP4S9=^_PtI9N_r(6m^RiqjbFJ~WG_xe+~(c1ADv`u2v#o2{|K7e#SY|#p+WvQ-2ENBb& z=~C?{3t==r8S$d>yq4{aRk4l==TPf4m*YZkvnQkJgnJM;J$7z$W)2A}JT8=VqL@4CafLT|9u7{9q8v=^ASydn zDYz&X%R5z@18kQJDYS~UFSA8tm2H*%#6DmAc;XsN$ZS|Mj7Jh;ymBZdJuBl=Pa}Fi z#+6@WNR~@9zrG1D2I;B6p0Oz4#7vxvh139JYAusVWm>sXNv*7J*5PYzfkKzsTQ)Rz z--K^N2gNz~cMqq`!UT?{i(E5DUAI-+w99Tg zXf}lCqZ`d-8t^m8MrbjPCeuCB>x(QE#LJuGOTe40rcba5Y{v(1Mj@b{md(^F3W3ji ztrQUQ92myd1_h>CFR2cce}200 z9=VYBQY5>53ej>Qd)tfsNKk42?FDjsfYkkafX-=_-Xm@@3?(a>e)|!=Q1CC9{StIp zvigr@iT3}jEV&u_OIdRHSiLz?q>+vL2KSHq`17kh&%(PYxg}fk=pD>uUGB!KHI#_@bwq5};>sa6CMNeKV z?Je1oL3P$=zUJDFeHpV7*%iht90VTtEg2sorn=0;|_9s|DO+$C5M{M-Wj_Bjzd zKuHC@ayvj`k6PQ~m>962yvaIEX3T$g9Dxa>gl6z z`EFa6t|l4l49vT!J5yMP-%TQ5PPtK8SMYe0n8Gr#idbO@pvo1@sxGS2znUW1j2cO| z7DPgG7>H@Wj|21%a*`fO=`qq`&45F+B~1uAqp-}>$g+c-(XH7To<2Gyd9e!jwB8XT z>`R5?2Di$qUtQ3}dDZ?n3$B%ISH4(4+E#VCT`hR}MMQzO<}CHZp<1Nbut=y_iNZ-< zXVTC{$x-y%C{MqvURDs{t?~+30vFN=_9>=(#1T6)YNU?4f)}2#1?ITlMi4<*sS{;A zu--^Ptj4FRyC@B(I@O=rg?^@c0e+D!^%~wqc9vh&E4WEe?s9TVjZ1FWC;E5rXYsTB zOYrCZkZ>QvXt(Ipj&6@QcdyAXn#H}RrbZMk#3zwnx(7>#qTu=0f)1`ElUKhVX(Jz{ zzk)|1>C5*LPdk&G8bD;o_4v`)qp^2Yk*^s@R`nN1buJww2C4 zeL9;Z;P5cXBzycI)JKU(rvq0$GHyncHDGiY=qhre6!yWeVv!_94i3hhlJjUG7%j<7 z$5G4^eer+_+d_VU@}p>|n7;k8RffUgm%4))k&&|g%G+0F?~BH!bKuC7NT>`cuVgOa z#f-j}@%yGH18X*|JhPR%|LN>_F-)lamZ8Lr+Ead;*t3%zLZpmhfO_=#?AE7>k6hTN z&2G@Y?7sTw-M8%jZuh+zN8|sOgSXw=oZle&Tm5jn8pBKB&Qv(OE=cDJt+_Dak}Y^y>DMifYdv_7am_@5WE{_X!8jHH|r1m-x4>^kNev z-H`2`O8zDAd$O?it3y}u3{n4NGu$i z>%i1|4@MCHC3xI7>IwlPJ7IuFws2qlX7go(#+?o7$Jf4==tKi$QsRQK7Q+e<(lK3@ zhPE(c*B1}RdMe+jY&sS1xfdpJ~aI)03bn!~s`Ba=jm13Ak zOEdf__SwC4D0uck@l)e8d~Qv8s2;l?3*~Ga6;?stMlP-99->fS6M~5AM>Vo4I>bwk zB`WHaS;*tMA#+PPDmHXVo=IIa!NbTU%i#1TN8z1v1(9O5&&X!>H&vm4R&X&@mp%W@ zYPFhYN=FB?admI?TeEG(4a)^w2|QcTH}j!t z7`tVQFhX{}sD^1X^%l#u$uu3b7)7~z$Z>*$7257D^wi1?gDI%Sv6@6Xd5A-tz6e32 zN}ZZTGT&^uW6@t=Z&yP${k|*;6KIVJHGnHmmZF6myq3viNKRLf1|-ERNkPHhYZ(u- z-j!vA34Zl3U53E>u~g*9-xEpt309DG-6h*D3n>p6_NVOK+rY+P0)He*)GEDUFa`cx zt@>%;8+4j$=vuAEeqA$igjwutKaS2r<|u<(_G91Nah>1g?kj7eN5!x6XhC9JRz9}< z?d-|A(dx~&hwC4}#oSAuB+qo^b*GHMH3*j_`MA#mA34CnzC4ZqxqM=PxlV1Q#)vB} zD#62eoeZfRMsZQPsCC^IM6z|C{oJ=-CfJ64WWLvkpT8fAG@g@j)DdvTn!XkJyfc{t z$aazn#dc)}2he}TzmXEJ^+L@HLCTPQ&%9M7*ilZ9zY4&l>oLpl4U~J!}fsoEj;RUXP}$s=k+_xosvBemzEs-3-v3(Ek89vO_KcM#-Aq1&YBo%#^^h9Ht@UA1!mB z^%0_mp)7$-XkBHJEt|;^19B;XUkeQn$8DQlx+L6Q(p5L8esL%%{CLS1ePt4VWv~D8 zH5g4-{jG9vt2an8{_6e~V9HgOp0F&UV6DMN=f0MN8`3-*51hxcQF?&Rn#-$>)J4cS zQq|$eHIC4{1Uvz+aKZe~>z3l}LcKOrWi>?tgk&aFSFzPV!JW|bmesZVM!yM8bwG(i zshkb39&d~eTyLX9(BtCkcn(&<*8*&YJHT?e;axhteB4bs&g%BR#N2|fheCFq!)Dc- z44}s9VB>f8m+ymY6HZMlN#Ayw1SIV$ns=z^p{<0?n19V5ZGY+j;Juz|;bUcWLHOw> z3b!X*SFcvjBMJW4WzbHiU0159fkwR9z256%_9a4}0lwjEnX~nzyAAMPxQpK3l;Rj2 zByY`zt>;u9mA9}#${{cx)`Lre?^p{W0=eFr)Zb~S-2 zdy?Aj9==o@Vie$q(-K+njkJp2$%IdR?s6hGmP&9sp7&a>I9_;k6Z`b$&+Ylg!+8nX zT$Kzc`2EAU2F2_O!YAkbOaAkJXa6jH<%xx+w{HoWPn2qBqGJ+Qbd{>`yWFgJJ$DA+ zSffBa>41tm+0O5Zq8*Z)-v@hsS@Qdl|CHK2x^-Mt(Gq$<1Ek_15$^9M=_7l#+ElyR zrZ8j@+tieA-FHss`S`^9!7CR@EUzW>j*CQ!*&fV9PNXu&Ngm1g}QU1kBE9J02)D-yIT!CYLcq5U`@iL;Y26XKDgm ztjra-cnb$$YCF`>Sp2Kk02K0VN%5FGEn@fLj}#sB@)Zmo1Z>(SAr6X{hLRKtixH8hzWHwSPD0o{Ri8W2n5Cr~#W|t8TP1sU&YmUQw9v*_K>5;i>;9L4xX|MEa`-SiBGIdnG zu-*-I$Rxdp9%i&Y#7F}@mYAON@t%2&*KmVY=G(Vthq#WU-j6QMvQcN;i#B&kkndqD z#56h<0&gTnd@x}pi#NAbuU#4zRjBRG6-!WIETNalx7fod*hR)|cmU^5kTtuK@#`N; z?XMtfghD$7^!L!zkKhe@sV%SJK}6!1m%h7&HGgl_%24NY!SG0=2&!hT)JqU+$F`y- zci)X7Lz8Mgfi4-C2wBs#>Mtl(@U(840Q3}M_hvDkox*PrFh`1%udwAkZ@GH;uzh)U;~H?(yX9zB=UF?h zw2n@<8i!(yo=D`+M6pc`@V7*9{j_!YZo{1CzoBNvFzSQ_S zl#WzinQ zRaYDT@imSsLX409a9q#82_5ycsW_Z8{&Mj93i=~KUxK!Ttpd=59dy#u@9+NPKc$!C zvqSyA>luGUkHGhHFJBhbpLPJ9DL#))4E+uQ|4~|Sp4|Tx+@??rdy z3lW`Xh^*vsWEymQoyy}1S`K}9!3^^C)t#qNPnK<3xPEJkEvhy9<_C`NUu}av+;3(^ zKTy}Pa+oTeX;QQNB_!BH>4OfMnfp>%m!STQo^gW>?%wtTo=-C_gY_~cKjyk<5q*dZ zZUhqQDiC~EUW6>dT*U=-k{c_Rx1#O~;K5!2JZBYCl-GfkCeVYG$n+A~1Wp&@4Wz7| zQfL>sTY#~hFvb$?)bx~;@WoO9x1iNiT**uW-lJLg4e@Y#DV#k}E*5NWU0&Hxp+L@U zO%f7pl2#X>Tz7p-w;(Ij9#kSNDG7)zQc^I_%=^tM_uKWNeR)ahLYV`6yQZaF!Sb9A zT-r_b{$1fKE<$#>X5Q@`#ZgLl(t2z;y4u>tKUZ#z=#5!$Xmwr+L>wnPThFlY{qWqA6(wBJDbC= z*$PS^kKSzA`%T8n`ZFu-_R9NCG!9?Bm7v18&vW{*CMud5@84M1TD<?Hk5H+x=Kj}KTOh==And4^DwbbAgbVAQ0Lf zU&89rsKKfmdg9b|mzE`0CHn^ZzsL^Q9ofz|;-ciJO7#&+UsWvQr@H!AtfggA=Yw&z zOOaeUQfroS?UvrGUg|!l4Dl8w%GT&mhh%bypcYM0T4S5tNUBR^ot1ebKZi|bk17i_ zBoxxAX7cOfaS6JgU=`5%M*#p|>|SoDcp*vl-ifzaWLy zCcY{_-}n?ZQJ~s>ByTToeEtK?=C7pxQ){}WYeq|G8R}0nLLxo4dvx=2o4kx0=*QzL zb#`MVy5%Ns{zZoRA4T7P_ImXF)8Jlsa{m^!2w-i7Ek40K#mk`}VB1&>IgH~BLoV`Su6&-$%3 z*PLrgg`m)=Oho_P$pZYV*K+T9HbxvN&vRPr{e&+1Az5RZ8wN)+e32p$=NaL!8_nK` zxvH7vzZg3>_%xChtsVLqt~_OX0LUy+PM+NdIq*AJnoO;~qIp$Nmy*4IpDkY>**~=l za8D+GUfe%r4H8fC|EAF_PzGlG;d(KXL;MTP(;x>I{%%ZeGpzqRn)io=>i^_y@kwlr zcNIha(npgy^HJDfYM4SzD?|I#izUFBc@l~o;xvnxX` zfk+0GHDJ?>LNBhTmCElH^CMde^Pz-2ykUMa9_4v2VO?ZZ7%2Zi)?m&bxgT#<)0`63 zw$+>hesJmEhZc8hKqUFr(Q!ue-LAZ0RIa^>2_nL-zarZYCM%j@2?7-R^CfJ?y_Zc-}h>lelLNx zWf7Q2B+sD&gqH*K0mKjqEo3L6khdh%kbjL)ejTFmzj{9F?*|*K0;Q)r%IcjAS&ctqp2k(qR-%=zJ&gGe-TjB1NZtxVC2w85lQyKl1g6)D(Qz)op zZ)DAvPjLf@lgMcLHUE#6)x1G>kw5{DQ&kr;q{_EY;^od@%zsN6`ag^kybm;mMmP=L z`7aT-aIs@y=OPOuaQyhjx-XiI+&rwpV|t7#A+IuuBIdL_sGfAWWvZ5Q7Sw^0 zg}BB4u7H5jcAnMa%?W)%Y`o2H=47Yg`cH5t;+z!g79}ii1rjSf67|w5Ul+)O%MiKC zP!2`q8c!HCt3RiHdfS7}b}A~`xN0ZXHcxyi-9#pcof6NeK#+}a(W%ZtC8v zgc1L5v1<%9)5`rVcANgWzWld2(@4T!)pscwC?*s3O#fMZXV!}TyQ4=;k0dhZ@3D)w z<_^tpa1z*y(Jf3G8G2P(SMtz7@&C@8>Hnsx*~tL|04r3|yC;MP_3ZR(6%L+x$NNsX z`wvvh->=In4?^q-;pG!~xcR|(k!j@pg#eo22ow^GW`!SrN;yo8%ovqr!>B51yb6HN z1Hns-TxjnE)5Y_$*5!R|%k36B=Q!z+pIMKg)2HwO(I)x9{Asb z;$KeRsx@*|CV%Ay*FvqScA?sZziBm*+W-Gk%>To1;BOT3B;8uusZ5(c3f64)MX@G> zvC6lZ4!^pQn9?|f^!&A76!VtI>z&PRXa{e3>s4~ph zqUGP><+2>0~zwxYhP7>NoKasDTe0%LW|| zM4~_9%!M#MiSNg4ob?eooHE)1rqRj%K)%~mcP%$b$-O+`j>REXjA zMBX#uTdbn<;n9y`&ZrtTg%F}>28}G+RJu|{#Bh4K*4Jm7K8XG{j1mO`O9d9yi!Ux2 zoazQ>tRl-jh;u>VkMp*5PsN$ZI9!hc$E7ZDZ{{jrhzVrXBC;#wHh=!BN}(3|u-pZV z{5^#J4x>~2Usj6#k9!{dCi3en8>oXKc!GzAkKc7c1&&=G%1m+F8qaHpN3CgcX$>ip zt1=WO=eBFeH|lj)@(r|HYyXpD_CL|L-~IT{DusV3MSm};U@fu4T0x`RLGX7tYkekQ6{n!lj!*tWT=DU8#*d6-eoB0 zIr!)XPJk{EFMKIfh*T^piC?je$c$OMDoLh>G$dXWP|O zk#WRfVi|~Glv#E2C4mJt^Fyds-O|O9N^VDGV|LF(QbQ}@Qq%|mQ?8olMvC~&%&%%G z%}uSYsbfGjuwe>X#n=@aDP8@4(YMFob>54o8yo$#+3td(k86N`)$;#PrMVb0MV_N~ zj+cYYhJSz3sqOX#w;}d0{JSB8*7D#d|23);+dWnWUZ}1?@7qBj03i|Q7bR*!8x$u1 zMN-bhD`3B1Tw4E+1Mg2H<@aWrdr@q{O-glpa*gH)TFcWtJ=1CuT_{wq>JcJe5L>A- z^IeM7_bUJmb|tL_MaRex>BejVb{ zA8^RA zy7BnG!YltLkQV-bI-rrq8v*ivv#o#stNu(#lH|XS|1iCa{_cy4(CTx-TJ-nQ`!&ip z!+s;?U!^y0F;l3c?VoL<6=l#WJB4DT3>__ZJ6HMN77G1KIx=q02(JFCFDhv(MVPbW z<}WinZfjPPkH3nk&$elWYXg5ph<bu8qxj(Li7*l-+vtc{e`3X z2e?4%5gBJgYi^OJn+Ho$n4v;c_pgKm05CJaK>#q&Hvk#x1@y1sF7$)101E&RfCl}5 z1^|QnEW;tcKll&VTL}R2b9r+@Rg?B8LQX~yLBrla;GaA|=r_Lu%mJ7H=&~7P%3t4< zRWUCA4HYi`nlBa(9h3R-HBgF2zz<>!Ww8AoPQURJ0MHjB9Q3FBK3y|@wNn=i_eAmF z;Y8jaghaX?!slW<9El%*F-t$U0|*F6y5an|?0; zZE?`uk5>%}J;!aSA7Q>E_|`HJ-WyI`C$gr`KzhE-Ur~5&+Mi{nJb&|-6&%Dovq7-; z#~MLF&_VLQrfY>h=JuKjW^ThW1+EAjberm+QkgX4WfS_{$UnoWNX@bzuUOfV^aCL^ zT;jZj;3hi*VX}fDA0R~yZ}|g2?}Rre4jyxKBjFFMN>>MrC!i6NglWM6q)wDg)G&GR z=0mA5N-Reo2u@0M9H6SGlg<<(04fTym!BhJxO_|}&c1VKC@Fx0Vefkf*S%6Mk5oS61tt(B~kP01+Wl}M1!~6@2 zH{D2e66Vx_8vda?N3WUMTN`2QJ}=>Xq?Op}ItC<(TPftuVPxr;v}@V@BJbN*R?@mW z6w=nxSD?rRwH7ivsvru^)`{^AMZ?0NbA70n(-jCLnPcBbJd`xTtO~8n(AiZ(r^#Ly1vKz)*#qG)A49&rzA-)M4}G+m|vY416}BPl4$c5lK8 zrk&N5ojR-YzEFnQu}n%eh!~_};c=dJ`OX1GJs9L#_FgG(pr_|)^%g8%ut&Us8@H=_FKvk~KT=Ln0a@MLMH07@}1Z^)cC<@z)o11TnZpw5olphxxaIJ>Qv!|cF2Wk5!7EN5M5oD765Kh1a z8E|Dj*B529@~)mJu=koP6}YNUI<-!aJyt5$yQlBNl*C+a|>$J9en~Nqbh0Q(Un|2DEu@^SlsjVp&9qMa`FCW-b@Gd zVg05TfLR}iq__iH7q5wzS?6_&mTKg_@?Oz|O^xhf=g72;d6v6AoOf~;)Ax3e{3tqr zfO@wsg>Q&nxglD6au2_YkcsFrLbNnH7oG}1$&yGdUas*qf(#A4Nb6T=Kfjc7M4KVm z5BW(9hnolp{0ygIXqxBA=E=81<3h{G@lH9r1inNc5TN^v@iZ)w>!U{%c;qsDnA4DW z45tl7_@<75lGX;mn1<4Cmg z9T{2s5Ysl6W9blLu|cv%FN>I4V56YF>e+Cm<=>E2(*9;;OSNA2U<%J)rfX*3FuDll z$;k`C_wiMnYe1R!7nJmok6Qf(eN_g|U41|2%=}S1m6RMRgjUx-zPQaQz;)CZl$;8L zq@f14k$g^ix4Ean->5F${o38AZ6mn$veIz+ha|zno+;6{k(O4MAZ;NrAOxk%N*Ozq zd244f6{R!Akc>;==gzZ{TkWJ;yQoik%eVM3X$eZ6Nt-_hOd*|Ksd&_pZ5DebGQJy$ zN$nkMGmEGJH%k(rV)2{IxzO$CAC3DrrdZF;Y8SE+cDF&5F=0v^oBSTO@t!5!z87EhMo)T$_m;-z`h3& zbiCiaUyN*jJ9oc%ev{vliZy>=1A$eq<9W=5U{eui6Ljw)d;utDh{t%tcVdP|Lfm~` z`(BD8-O(k~4Y_qFTD6M(n}#lyg19(NQIEWvB+CSG8dn{@LJ zH1)5l^KDMUR*FO(41_#*?$_pl`?9LM_R8Pnop8xy7i=y;zK6pG7J~#cp@F(c_+pDL zjz26fc~SXRyfK3Dp(ZIB?AVkr+zY8@yx&x@cAvSr8fXrO5J!NDc3kPW07xgmtq9N- zou)wn$180i+Qd-IM0f}we0~MA#Ve(q0m7I=U8fFF+~vY6kkOfspv4w+S-xC8(XfD{KjVz8t=;dqt9zL?mYJu2Ag86a3Nf;+`4xnK}~26+V^_SzBF zajL4EHZYYQxaHwyf$R7z(f(TsNUJ!iqLfq=$>Y*WgjGzm56Q@q*L?RF=m6%gb(YTz z7GG<10jGJ*lwhmWWAd3XNzHTm2E`TAI|7fareJ9<%UEIi5g1Z@1j<2~bg|a}^Ia=^ zV_7^8T)>YckQo@Hw92Sk5cz%qBoM^qQiP2vn!wFRN^>luOckWR8<)uASDpfNZTEsR ziCs?(FckB+y+T`&43*f$x>lj2UqeMTp{ilSX3~H{;lO|a+9yc8>y#RHOcAcVWPmhp z2zw+!6Bkf4iu@|jsFoaHV~r(q%DnYWH7Loi$`n6rh#-?7T16CJb6NIY$^dyxLPUaQ z-~<%yjg?+(FW*n#B@9W*?4#5eu?PGUlE&hq;z zgcM}^vwk}+PJ=5z1`PtIIfLGMzDEGzRbQmi98h46PZyB* zb~*CA4?AYT0J3kN-IT%G97=7H>ztl|S-?uT8!eeg{S7jld&CELdkTCM#c}G-At8FT z(}Cwz25PMroVkV;vcVrl`EfF$4NY=nxdG?=Km`6EOmQpG3S8`b8_aL`Tt7q|tPL@~ zG1m4;Q_i8@h>ALw$PK!pfd<|w!=%t1z1!XmL2k@ScMW`If@X7ykGew(7nrohj_T@z zrEh`rxd=d|E_Xp*DBqupwGJ|t4Tk&1NGn#T$&M`wU?p--X^>@*YY@~|QCUm{_^al< zz=l`K!edw0ap7IGhz(DR-ybHtQbBam zkwpRKlZxks>o8&V$6g0=Hai<)>;^uYORzl-hl6N%W*qns-h!4-L2s_jaaU|6(?F;E zz)NeiDYeYS#0tzZ5Jd_fsx3~Yc7#QmSk<~O{G2mdC%oRQL4Y-Tsbbo zfj6xS+Ot4cYjK&vLB^nRuqkSc4>AE6v4L(uId`TTWYN#1|4ayBoTB@0! zIzewN?VgUL?PPHdbyKuc*c4$%ZyIH9ObdYpdIH$Yu)91K06+_{?sWsoxPTFLxz%L` zO|O-Ytg3H0CyMZR-Rl$wZA%MsRoQ2%t`A3b5w5dwL;ABN{Al_3YU+ zNV}+F&Xo1h9$F?$?enrU#jK(#ydQ0o<10ve$a57`u~UbnKbc|?c8ZwCfb{yxN=mV} z8M4V?_*9*X%5;hGVDh%o`D1WJEh<1BMbz$+4sZe~-0ceeu9P^0J|j1zwPk9-(yuIK zLxjS)+!_P}i&(2RNW(@!>lRs95aQgF0~u7d)CQLZwMM)b?Z=bdg{kU`0swfAx+9k>3GAXK3xK2*8eW-j zC6%(V!@-xn0pc+e`(@P0Hz=+L^~+P3O(olg@B-C~>92QCUBzR9@$IIPidEUU;J$I9 z4(2|rhcKpq2AP~2v?7i^y#Bg@*BKp!B^FGHjqP#b^Anm4C@YnodCA!`3AtEvU*pPe z24$?*3f_ViJq!f;ZKO>yEgo=tPMW$`ocYod*q3wkOw8({y=huIC&F?b)?L|0NO5Rm zeJm{#SEjKIwaP@h?6Y8_66TS&r88e1K<8134=vqhL5&|N=8%Qwi|*6eZt!-mXUBA= z^+w*{8w6fwCi#BwXMvDXGmtLCcg|N@E)aPxnA(pk^^Xu>eAszEEq-LxzUflBqUmKy zjnquYmCdB$@LoF3+gkj2CoBmA$5J{wyW!MQZV+hexur&1i@dz)?nv6^SDs|@q{D`eKUqaaUK)j(7 zG#Mqd!LFKJtF+PX;F&4Vp;4nS&%HTdu&E`z3Cx}RIPC0_zK(XWIZL`VFT8cwKl7Z! z!^U#0NXd~PlDzNCj#uhp%aL*{F;|&O~{dd{6LChk(?agcG!s~@u`-kECf@B}w z*6eS+-50?;5TD*L!r3QVw!xVg;}o0FNW^DV!e2y~ElVT)Lh3Z7G$mDj7%+9H+jD5V zeQ5G@Xli)W9eOZlfC{4`w?K^l;%<(NlngKa$X$6?hGl`?57-87{T6IXN6Fx$ut?el z9Iggs)mOklzKv~!s`ZuOjxRX;%>LjgHfbD$9}JT--xYEZNn0!-(6cWw&1mhXidM^H zY@>V3?0Kqdh=uhbEdD*yXOepVPleJH%Z=$9>kSSy^)Gby$&$AlH-`Ih36(CTd_>~U zn9>sP9yle6;9CnjFHrIoU078bo2juS7iqfXfytA_iVKs{pYTCY@8`CNJlc_5ENVs8 zyiH&J8v5x0UN?J`Wdmd&!hJApv-Qyt%gU_a)aa8%t~|j?io%u@)NC9eUwD+14Eh!& z*0#g*4pqCn&Fxe0;9*vZ+VLuoMI{z_TuUEx92J}ZjdL_W*q9rK*0r3IV4eHYVmdIo~d< zV%Ex$O+iPbv9xlyz0oPY5Bxr=C_q79bdnkrg1$!wcCY0-mM&FN$ z2PvrTfjlm8xcDg6$o1#l%oZbba8}P^wyU#~$QZu)7CU$X%yO2F;{-ePqcWcYWmT{M zyLNq|!8gcck{K!{0|Dq*jkZ!yvR^oo5r(-;ecnJUA>R5=?%5sjBpRhW$xO9F`7{>I zb#V}h*PR|0+r!z~UkrQTj9-MFChUGR;*h}v%juYm8U>*|UHP&V zegwlwzX|jE%5e}4S=IAbRIA_VfGEn~N8PTB8a)Y7z1N;Imhgo@9=Jtx?#L&7tFYCT zZ+%L?j&%McGdks_bv>H;<;`et?|!yaV>FUy@YD12Rs%t;;u{C?eaJvM^E==CJD3^< zWx_~v(XIgyLhzFT*u^Ru-h-sKy8B9T?@JZfo$kIC|&B8(*ipD2l~Ao)!a9VKg0kiaOEUHS`$U;GE4#pRgvGp~aNndbrUu4R)i zLeJ|5X&)vCz5$vP$AZO4kU3h-IWS8npZJrgnZ6X!H__FECe>0(>^rbM3@Ea+bB35V z_40fSiC+%sY@Dy9^6_wR#GQRdKTTOT4T;znk$-b zNk^9r-AGRuUM5KKtmWZrw(45F3**tVDZ3a`W^rh|rn9`#Yu-3~21`KUG?;s-?=r=b z{+f42)2q+(xnjD3?Quz)q3@SrUZb}+amj1q7O;FOsT@-YJK{(p)^Y`?2Mh}`$r4^$ z-gIg0re237P=)huONLpTAQ^#~zYJ}MxdmJg;USWyrO#HHx+lM7hLxf2QI?JWon@}u z(b`d-%jZ?|f`}Ju>&!*5@$9X{X2jHG+2Qv#6`77s5ZkJv5BIh;O-FC+>bekr+BFQ) z`r0>*(F!=UthCm)YT5IrN_B+fLcJNkv+T)-nTa&BVPL79hdd`|NJuYGT=_1zt;}}As{?fqs%Bu93uCu zoR`tz4P0D`4EW)j_e9MnhN?9iOfZyhqbK$Z;5iEkdA>LgXJ?j${p9#I?{53zwb^^z zJm)ZaE<+TH3~`)!U^s7%35G|c1j!LNLh#ZA=*uTbj`J--24sqzx(a>@nvMDin{bBM zNWDOMAOdNeJEjcH3)rL+b#zVW@^0e_-b7NzKu`2`<-xt?s(afXvwgjZEW_)G}FB8XYi5XJ3A{MLmd zPy_B3-0{?ubJ$-`71LO>|x82m7Sfj-}z!dk(>P`^b0!|Fa6&TObd{Uw(6C@wTn z0RXlUl2o*bg$m8q(oCJIv96be&zDYc6nvDD5G$g{Dy8Ix_VYthU~J$5XY^%(c$PN04XV& zTFpfmY5)K~>V7miwK1rMJPiNr8ybRjP;wh`AK|JAno1m-ZzPww;kV8e@$cM;0ZVp9 z2xvMB%#Fnnxhsmi;y~)JoRqTcXb`zZhK4aR_#8!BH0F(O32KUA^!hr?x>>kB)hLrkN)Y;INh9{^9 zv8G{plex4Ggj=VU^PTMPKYuCik~lM6=~|z1^y>d<@Xhmvpjg!Ija>ixM9SrE|6mj% z@$|w9a4BAM)rOdNR$J)hK6$GUF4OBb;3`aNw5LbVrbY*)*jO6*lgEfy(#HH2e3evm zg{6EfzYu~XOs8&5*vm#+Gz)nO)Lwc7z^ci6{pPD07~?PwJllR``GpU>(uPdM^0S~d(k=szqmtrpxcDDfi0Rg(5JZY~1Z?!e#6aCRy zd=%y~Sc|f{<&k*R-Ya|K<5N-mUAoMm>H4O37K6Ctw+8CAA%)J4YVG-4Alr{2bU5T1 zUKChe_Feoimg}!59@zlMLYg?Bx_lV4$q}gE4ugEfcPaiQ=(Whl_>O6sMe*mtl9okm zdtk%nA}P%8ap^gQJGg}^z_RU9#!VbgNRd%B#YVC)Fm^3SVyRtS8|~g7oZ}i$ z?U;MFuuJ#(!hJVyM#R!q9+iI3%BEuN*(7sqQ8QqWZf}TJ22D0U_sOHykv9d8Q-&T1 zsB)qP#Q>B-qtUZ>>;Zd1$9#4ODEg68!pVR{E$c#jmUwt!%I`c!j)nM6W)WgC+Y$&+ zoeC}8-MP#2@0%e|cU$Q4ysfa_^yIWV@jx{;Is3uX2&DmO9dVT2AA;bPf$ytwGLf{% zI2v!TikUGjS#VTvfqZF16FMTl}h1&+b&X^NP3)N(Rb9y_XW_1 zi~Rm_a-mg}IH~PNtAlzUtfD9)d>brt+itSxGZTixpHZ;UDTjR=cpZt(?3n%f`E|x+ z3CVm3P3U3K7%Sy0px5+xLj9|eafo95S3o|gpY7|qF`z68oCC3hAN^$T1J6MNP;W*G zt^rC(angf=NVFal_kj!gf=Fs(9@1Bj>fRWL^(*)1q)!31XyxstoKWcW=VWjEw%NloNQ+8}%O;tsyyCs-}AzDpLuWs%OBO0?AlK5I4w_(iF`g)?hxvJBBf_-3OJAZ<` zbE0)fVgdObOk~+Rc~}l(y30bW-js=M4aKg9i4O-8BRLbJuP1wQ6i0_9Cl(byY${He z57xj>`HD@PW;~<4k9)f)GekeNq^R_~7z_hu$pDvpB`D(|MCEn_dC(kJh1Y1884=IQs)Kh`DcBsM*nSos}z^2!(; z!bga1f@M}s{6nZ`AFjxq=+%-+B)&<{FnO$a#VhoVnM-@DpIomV&R;!V<~*QJ10H8! z4rd-OU%?~H!qKQ8NTIj8Oh6Z+)>JEhw#VEDQx`X=XspkoT&dWbkhB$5X;94JaL?gN z&4D!M@GR!=HRYRa;nc|Ch`Qx*Yg7q_=bkOiksi*GEveq?jA7x;@4~%9=bj2=pMsH_ zU#QMp1H@5XV9}?l(dMcJev4&_%A^TXqp2Zcu~2&ZNaMV+k#8Pa(+ zOF`OmA~d6*OQ5w6l#okN>ylbw$mOa)w#3b^J0DKHownejUAj%*yqjNWFN!rQq|(%2 zoGMzVPPi~xywU-S$P-CfWXLqkD_$+8t}UuOE-E7|sg@wCvMg!TL}IuuXl+G_vBW($ zDT8sD2MH}H3B-ZkQ!MC+8ImrLWMRaq(<^Qk>pzl7dn`(KlQLQ?Gde6=c`RFpE!(6n z+m)uWs0-_93TqapQmT2ZmuRjRztyVY(}EIcE4M#ev~PGhWuKBI7EdpQ6&b(JLVm6V9J~Ky2OF^(dc^UC@tP=i{DUd z__*CQ*OF&f9CM>E^tH4jD*?#CEWp?R@}{7qV4ws#)jo9%XNV~kJw#czV0(-&FsTfF z6&{Bv7DXi(xSz|g!>~Ig8*Z?Cim-mBsdd_7c;0PzwzYkJXn29}@k_3uujZzfX3UGK zuvtcwo)DUJZtk|C8j4%0=@*STKgCenkd35tulZ~xuZSA9d&!XCUX;( ze3hTv76AYbbXX6C2Lz902H#i4>1PDW-Zn)rbi^L60ugtyw{>tnujVs+lzOIAchXpt z8Cek-*yjB)Y!&{JFzR5iC&>6?Xx}dCM%;~1pgqEzqWc3OURQv=@)w$biKXB$Ifg zDl9Q9MbN1n-Y>0L7oOf1T;3Ov)~q9+BYryt6WIq^ULKYgG0SXZJ%BBeja>Pezz}#a zT8^x&g4|02ke5d3&j85DRxFmhp2*nD&Bp4R5DlJ%?aOA6{(#b)+lX1kCtB1V8Do0P zxU;weKlLNRw~{k_A3&Y4bv9HP_Gu_Ur57(57Dcp?IGh2~af3ScXebU>?Q4Ubr$v_d z!6#5GsiA;y4KY#^zAM`(DkrjBJ*98PrvGR~D6o?rT^T^H$oi>7jRct{UnxTtc3QX7 z*cEHJUN%4ggE~9fQ>B&%ytm92XY>P!{Rl*RzX#~sf`qHI#(gCvP3zrxM2fgZ(i5zM zpT(v5%4QW@v=F;5wPl!`HZP-enwDmmTB?@jZ)Nod%4`R;WG-6Z#4SNTCyXm7LxU=Jj1t}XL zKdO-NGiz~$$i8^q)e9;Fkslb(aKSB3=Z;*LV+zLv?!kTH4M$6X`da{ zNFMIaLl|!ahFWA(GY7x=gpC^gHm`hZ~eS>uiCgur!VZ6F|)D$+p2&TzR#4-s@U|0$?G%*Q<6 z;)RetVL2izgY9QW6!X}0iOAv3=yVBAnjM_1s!}HdCi7fg>P;(g6dRObVvYr^=B@4JtR;3XQWVAbJH$}o3W{jfc z(K1Hj$bbbz!me`(EGRY%*oO^C1LW3WA=q^Jn8<+MCQ^F~E$*-%yy-t!a(}SaxUmlZ z;EZz*8&Gj8^BQ0cX(wO4~HYpW*74D#u<0DcSU%X?zZyqspa}3E$6A2U%WQ@ox5CTsuHE zoMa*;c&=S%qK=DjA9%b#hBuy0C@AI3x=mKAtBK-=*S@c?yj;p*6gwF;K&I#t&L0Vb zSSNh3yh5IPyVT)jd)$O0DRawtLEgs1wE2*%+aRfaXtwt9HhYa;X(#>ec{Rzg|)0HNx0 zsW-S=F8K#@C9m$wBJRu6?<;s!$+ zg(jjz=J&q11s@_YA}Y_Q!r6War+4W)m-pRHX|>w%)$pL$2=BF1&%)C;Ju-f&K;KWZ zzK~hsap$h`podXHlD_;b*WoPsF~0}qY%Y7^@iu}Z#fQ0(pa%2R_$o1T{ znvKFL9WOjRG*+BU%KU#Vh}%@xUsE{$$@_I@AOiQDO*@}!A9R@mxBP7R%L#-c8Kcj2 zuCwR!xiJp@;GfzdJ0*^_mAPkk-<=oijEvIX`dofF?y7U@VR<^Zzxnay3*==W4Dqq5 z6c#%Tu_vCKHhBn!z%6+w(znvYKs-Hfif|&^_FYA}7TPq`R|W+5W?EvYsS$N0tC||r zS)&=+)Zr1D2JT~;RPnrL-rDg(pRM-|MqK!)6QziKsFMO%!u35%bW7LNNet+WRF=Z5 z^gOuJc!=Cy@vLp9Le7F(i7XVeh_W56mU%WDtQ#{+vu)D|Nu0!KedzLh&N}EKM7rG* zSk$NiqOfZA(4A&cv;y)>A&gnpI9fI4bh0Vm`EyFrZ95sthE-P?0@L5}WTmHU6^g>f zCUJZy(5qjN7ks}puS^mr4_n2u7Svi*+Z}ycRo)k`S6M%-=V@O*ikZ#aG$CMT-!v;S zu^5`K=gZQ%W~;v}&EQF0Y*Jf1uIhe6pO4Z(`UpEjOL}+t!bfy`WB>ijdEdJ3yZd&h z?uX@!(^eR?NxDAD7WR7ooQe-*_HFRwVZu+6UMKjt3iivwDE8ko?VnY7rCAmh9-I3j z_4qXAG*5L{jzb(8pV3XSP6*LCA#eC`PV>_pmnpQh!@$F;EjG?o0La1gIJns#YNzG! zH@Oy76@)$HGAI-*$HrPY!~lAWoPn^l>#lPi>NXEd>&BJ_wDme=7p?0~ZNfK8?yOe4 z8y=tD-fa6AX|XH?p^4n?2tn>9glho(;}uyt)i1gPpkuIwWPN`h({7V#ZS(LD{Zr{A zEMqj-tei@zw9k2ub5XXZQX6fGWHl!?gIbT{eb3)FE&cr55BJKB>cpjCAgxTK~R0CZrGfPs_CH4JDb6fa!_lsoL*WT=zi@Upm-k$r580!Q5%c4 zbND(4&(UFWs}R|_XXKciUQ&A3B6RwNLM7EXtr+cxt{U$%v?3*yIi*O;mB>G7?Wvr# zbiPR-AueZx$QjvpK+7lSny9|rm~$kw{bPO&)uYiZ_p?2n&_{j=9}y?O<$EguB;d^3 zy{2~$4`namP-lZsoAcp?tzYT~CGzGq6<{vmvya(iZCfiR;!nv+F;v#ln{pKr#F-

7IL$0L1}r$H8^T09I7W-=kIz_J zuh`?=gQE1*yl8zF200fZ_@#cTW7SDc&WVpU(VFw{^MwY)yF<(<(ygPxE}Hzjr+gpY zvU+KPe`^GV(*;FH1x86_d~VB#t_ZyNnem4v^8`0Dr6MEsCgV$HW`bWv7EfkITjsAp zPS-R};tEb%I(M7B2w?C%ei`n5IUk`lx z-a^{IQPqMZwuJYPNWJu+8`=pd{q$S9n1Y=5*mOUn_8>iI?(8Z}Z9N3mVSED5VQ%{R`-`3K-i9n3oDzZVTAx3&GNboW_OR{)N0* zh5YS>f=h+Mw}qngMPga`61`+$?b_R+X3B&$3kraTt2Ul#9Qp5Ry> z##<3;ToI#Hkv>+Qaa*1;_W9Xug*ZJTUm8(pj41X;lx88y+YyK*MAa>#hQ6{+y0Ss5 zkRl|tH7m8Py|R6&vh%jGo4%??x~k8(YQVp0D649uy=rW!YT~wPioSYAx_ZvIdfvbK zM^-hey?SY>dgZoyjlO0>x@OC`X2-v#SF3X0xbk4B=J2-Wn7;Nzy7tt#_T0brGOPBQ zUQn;S;sH@1sZQaW8y4qpC<|_~bu{vIbXavDO*(cwIy$mDI!y$-89I@79krn<+a8^_WkCa# z9X&FgeX$)=3|%uaU0r-#3xr*fcf8{rUDE+wYs;PU7{cy#lg>uV&Rssiq3q74%I+1X zuC2T7rRA=Z@y>q--4_hqS2BG1+xabHP4iinCb3m}$sIeOo`--Q6Q`bz_98j=7Oe4} zZTb#uG>KtqCAn-bZB8$JXD{PQFLO@IQ^r0v**>soANTt{?wmd*M!tseK3;U6Fk}DI z72=+y#`=H`NuqA4kKbfu`|kLg%868`#|9lw%x}mL1eK z9cjX3qdhpB-M^nbXj(OB$v9+9G-TU3xa34=Cp+Y1I%JO?f~^exBJ3O+FW%H2 zcFq}gI~;Of8UAQ0cxRG-zuyorUaqFihdk(G!A$hV@bg8R^6@i{`YjU#j<G;YxmM=SYdoYsA$d{^J=E62wIx$w(Ia0eaR(CjtlpSy8A8$pECgzMc zO^mlNj`ysL_oB!97)KqoCPog&$7CnQO((u-3noLA z91PWwG=UW`ug>DXo1$AnHS{-=Z5C5)k^nhHkvq$d^kf5{Dv?`tIof;=ER(ECJrhqB za5jI$Yxgg8;E-niSSBiaa3c(^C%wdMkT8U#ev>0>VNr-e5x1PY(t1O(tU^j!Pb%e4 zGA>81&w{T_&(|qO=0XZI0mT?M!WgV#u_tTy?1y!_iVCeJK6{8QkQondHvhxU+$7{!^vG z-`avTELfM-U5-|!gOvcs18?dFR3ua1Mxo`KKf+q{BP2?$z$@3N5dsS7`M%<9o1RFr zEfRf2f+w5#r{9U+=q~1}!e3(g-yFW$YZ1oE0y^rB2nZ}l zk}C^B#aD!sL@|o_I3a?|4fp$aG0W(fCe6zRdj8MeZ>;9gQARk|C&E}$K%wei`qk*3*a;zwV9<%Sx@NJP#)+Lq0Yr z>4>|2m6GiE@vLrBJ{b=F$t4TvGePlI1h#R{%3SBVboct-`Ntk9*aw2^?YzkPWwH`d zY}1~Pj}`uY&Fxr0({f?TzEOW%VbR`{5E_+SUy;U)$+(_1oSrHFJyTsjGa%i`jI@I&pkdmj;JOdgY&;#`y*; zShz}u<~D@I_QIGa##Zb&U%tw|9v}sN4UqZ&#MJ3ATZtFaUtBHxz~)P` zUmHY`dfk9a6~b9wz0{;fTC!Hn^J-7(eh{aJ`?(2#yer|r>J2hDm}?@uSpQ}iaBzEH zq8R(l{GrgTx`PMnJxAEp8gE2C^L(O<3EAVE#oArN*H``zcWq~@({Ep3m0w8)Q+qpW zH(H9bY6=9HVp4tYB{`z2y`PrALU}pxGYzX6)CDN=zbI5ia6s^h!?k5ZvAo;yg=5}% z@F?K?yn|3x@*PN3+ui%b5`ny}DYVrUE_~OguSf@~_-M~|r_pzJxXz7$_%;dB9C9Os zoRRJy&+R^E6HvzEg4Kx;a#WG_6Y{JGs}PH0lOcF&PVHh>ZM9qp>gBCxRcK_wMFwbW z;_3&dmnz)V860-pHJ<)MMAuav*GHt{gGh_=OvdiwQt;rfSULjNxJfEGd~OG+0F;z4 zzyYZreo7gHe>%)KeW<4){+uyh8Nr>bj1_9S35xPgcu`Bla@ZC@2)O4{*O^;*tER!Sr_-)nI`};f^Qczq-fmaWni+!KQMD1V} zwZl$a9r-g)jA*aF z=P+@Te&vhkW9*MU&u+`vvY(Zf>?@0kMmJoG2$BQAzrVuHesKjf!?)P0a_@d2y$4=P zxBc4LzEYeoFZAF#wLe(?JwzPp*m*kgtVZe$DQ#o}Yo<48-T2~-_TYzp&Mq&#<<~Qc zkAJD~Is80}5%O-Z3Hs`dvK#KYTyg!`b+vpnTP;lCOeV^~pRP;qSDJ$9@>@(ZzxDg= z9?5LGYZLjx|EMDG!T-4BN*?{IESa~vD9|CIi$kDvOk&H`@8f;ozL`hd=-h8|xzlEj zAoSih-2CeYF2#eJ+F;B$^Y4w~V8eMf{DFoD?Btmk!{QyTK#zqN5+WjNsBMf{%+|CV zr*Ko|Nem}#=OCzbs6qnRv^1$pGncfHPIoB&j5nJi=eQ;EMhANa?f~72{4C-qK-W&cY_))3dqAsyE z!zNxuGj1rMAw_M?;tf{ggRo)&jFkyq*x)|OOAY164Xni|W#)0=5aBgt5X1t9Czv+) zi7gQqS$HwnwLZiZI-`5ZqQbMcL!m-FmrCrfb!h*eEM8;pPvk7ST6+Rvg3UsN69 z@YUi08Qjmoo=eHv!ONzH%sVtV+DhU^Y@{e)M=ZgGQZa@%nRywmAzOVcNTOdN1SROO zXvbISF?G;-OK*@dMagUOO4%lg`Z*7Bs#FxmQ77zHzp#D2{0X_EJ_mMsAzM?0z=wUk z0%>U0SUHt`unEXNE6v*)njFKrgB3@S*Hr053 z+CLcjqAyu-!L??orVO7Ucw^$D>z?9doZ7J(W1 z1~&9(jIjMIm>muhqySFvF|&zcC?${bP!JJehgK9T z!@`UHuyC*I>+^dguVZKc^${iT8J6d13)j zOVyLoLN~%!oFTS#6NebFDx^M@J)sFe)CkJ2p03&v`gD*k<@7jMrrF)QdSq9g2Aqfe z6yp4`?~BTaWd)!;^K__+A#-HLs2q}C-;7c=9L4muQw>it>q{Ef))8Ri=h(T2vqo57 z8uI9z=yTq`79k~thl{`j8&5VFKS?~}2UIOY4W%5}!r#yC;+TykI_;(|GN*$s zJ@c{T?3M1)XCei~3aP%@t9v%hCYpH_vohI(k{|nHdgDR}pE+pyWPK0O&HpUqLGt=5 zwlcNISdb>DZ+5bHfoze`A#5P;RlM#L$?P_R&e1@5cAN%xm%N@HBcC73$4r^uSe$8i$%7$H*Z<%M)p={Th*)ywuWp}vkX2R3V zGv~_mxBTy$=?G@8!oMqfiVC+gDgRaA`MW<1%tv!2$6lohtNYO5+xc4E%@MtK2XC+Z zQMC^rV0<4EdL?N6ofK#ScD(eZmKn#~w2x%% zBtiqdNtNe2B((M~J`%mn@zihZ<=Sc5F#4Bxp5K(~+Sym!``>C${pS+R&MCD^`rco< zXOOA$9(qe0EHXKWU#(sSyk*K$VX}Aa!#sTdcv<>6ZL)1srS+Oj!KBD3C}1}QG1KO1 zd{(0HY5&do?a$%B%Vpw|3lHQ^X4IA+S~?^ycvTq=GZ5B9E=A zaM+*H->;-9rNTd;2p*8J9#EiERg+bPXb)%<52$^ld2y&>A2Xn}qN<%bpgvLF70PqU zu6F%wQ2!&|ttTzgYEZv1%J8Gw8*Q}&BY7I+pvl0X>HOfkok6qnj_hLx zhMo`(S-u{!LW}MGV_FUwT8$pEOC54tX*50`gv}2*?+m$|4>?mR+$atjfQQ}1hCNg@ zj8}SGt%tq6hJC_^eLwalWc1NjsXNB?7KrBWZw? z2A)T#Qasa4iF{2_fKbuRQN_GOLSCU&H3mi!4hIrDA@KQ;xc`(Z|0rB_H0gXKRaP@i zOjFfM^9$pEgge3$IqEeqnmwpMr$WV>#)b`C-5-KV~wig$k#7SkrFW$JfU8af}P5% zA>(ETecalTpHurHQq?0;$CozaS<$^o^xEtzN`2NU1KKKsvfBM%m0?Qd5$lOz{)sVd z?a=}4{{X{8r}iXFdy-KARWb4ftdqe%880?DuR6H^)?9$;{4gEONS*xtadIh6XQ@-? z=Y$SQRZ1_8v;kWeBefOZ1lIjdR~=I~w)J}Im-W=HwSq;l*2@4noik><*r@|kdPeuD zqjSQ4FLaNwr%xzf<{xU6<4v8Z(%!uONanpCE8t6mC+xeGI z4tqYP)c&KK!QzA4KUet#A2&R{)=Lk&Q^b3!Hn-d6mD9P#!mX^ zW`ccE~gdSCd-eaElU&}hnA2rufHJQHZtWM}LuIjNI z=`jyZKJA)i7oP(^(LWcFsrSKbe=rs4lJCwQSxBl~JWMQojL zMD480nkb!r5rh%Ddn$H;q%athl9@fen=`SVldb$NyYOAkx#N^lNSQ4HFDkqH6%nwP z{#%i@lPo$v|H;nBZ?W7R@jcCVSv2HcFJF9`e&0W@BiHld==C-FweH2d9u8EWYC&IZ z!GNmt^R=%0hlMw*1_Gbx7T;HLJ__atQ_pOTFa&_Z{kRd@2t!&z9@;Se)acy|js~7| z9!csOx2WBXg+oo@mN^l>Z4S{oVIT_R5ggZF-zdz}YEsTo^S&agu+C~hgG48`;E#yF z%+wEKk*0#wI_WR%(X-TDKWWltKMlSKT=*G?g9;jyo28s%d#BIAG#7d?8)kzFSDX7R zZWO78iYh^2BGQax&vo!LGh&LW4eM%RX9&RrLg796P(3w9f}-;4rUZZ>T2qapkK)IE zk?dS}!3njuB54TI+U(Zwo)XQPAuV27zD_ExIgA=Y$5u#&*dkg;=30c%b&K z{7xN^`-gI_Fya92M}&_;t=^~U?cwTJJ(v1g&F$88TTuq=MTq<(9)^%L(WOK;p<+1Z zRu@z-FqOWBw#FotS&R4Zibpf4 zqC(}`B8WH4So>#}?i)J`mnBJh-=tk+q1MfKi* zX_J(5lR{#XGNI{vGN`kn0J=K2owiB$c>2-3xM*)ob9KagQ)KuYt&HBCR3& zxQCL=UPlb`wDMFHk@uqn0&g4aIZ}=g3>BF(9d3lqSd6{UT<_Keq%R3#kAgcmkta9- zg@DpogX6qg|IQ214 za?xx`J4$2sUBuC<=9e9y>1d(&?>^7^dar9 zG-vp=SrE%36FOS3*4y{7Hu`wM-~OZ}x#OhYN9w)`Ha@}0fQp--!W$YEO^(xEf6gvI zE#iL>Si7wTqC$P87X4-ywe)`J`(-bAC~!4cr1Gp*t4(`$^Md$H=xu*{n~e+WjP27h znn+ewp+MNc2LE<)i{_IGQl|3O2o4L=-kZFhuKEhnJ=D7dlWWFvrQk!>y>&<(hMuBq z>SD{h^|u8_gn(x3v`#FTmfTx8kNv$VqwZKm#xuzTkhdF7RVYcXyZGW9$-A~3J>i{f zYLxQSAC(_}a(7!!M&g{=%zQZa3%kd5j-q~DMBX}^8=0-=<5dY7;e~Gmzforoi7rd5 zz%x-_ue`)HIKejw-VeC8$+0Q)=iarI!#DP;qIR4QcUv`MjyXybNX^&}y-v@9FRG`} zJd_-GV1eEd*y?+yW!71^Y!=tZ|K^e_`5>`B{2Atxx)9?#&S;ph4FPoXg1Dz(Bv?`{R0-6M4Hw(VDAe;6kS;DJOfaJPNqFgo@dj&r=Q z7l7sryY-JRY$Cq|dj&m6k8|63HS>kHg6rFQi07+^uZ`NO+_sj6zU){;{7{rDgoC_i zim>4c;?X1LpGPj#T`#|kT>T(Tam>>FVZB=I8g*fP`(TakcGW(1)ouQJ|9K~_gz(qo zhB;p7DV0;l3jm^@*wJj}68+2M8b>EM8!sxl+&+wRIsUhB%-m-N8{0h-W@;`EoPTP; zN>X@b@eGKDY=oQnv8bq#CXCATJj%dMAUN5N6zoaO z5-GylvSkl=J!A$;b3YtuKINNMZ@PF^bJzDXsiiY&hTvDqwteejr6J}KMasKR_U0)| zIvwMzvuPeT&$6?plsuzOEV@eGu4ZIT9o&>;K(qM0UwvdeSN=Am@=ZhKrI#w#IpN^5 zAHAoLbgy@+`|e)Nv64snzQr`_wJ9GmzA-fOq@Q|KooYV6Fldoy;510debE^%*=|qV z%AXRY+)A8TUA12!m;2#)?M18c2P}U><13Dx=nuq6F{r_k~(w1%CCo;mEem0`P<2X z+sbwS%HOxO)3#s>JFD7y^k`nA3zlUH0%tV|wQ4{b3L+P{RO@JCclfDDl%ua_vfd zj!AlcQ~dS<`Vw=78+7U#bWVb~i43|`xB;~@AO3u}cl|wy8x?f<(A2PipyCN9pb$0P zt79FABxl#pv9D(vilu+%v9edsK9b0$lFaDP03J(fUc!e-)h&F>5Vf1Daya9h%8~Xt zJ^XXVHIuI#NiN`c&OKMGl`i_kv38-STo7~La24zL+C;Q=Xh-Y&fp(pVbIg&}C2X?c z^=zOG!;d2r(rt3Aq@&rzq|^0cX!5}4?|OGIE}hNMIna)8_Mtt45aY zpG|+JfX43lTMxUjY>mhvQ{%Hg)47^qE?v^%2S01n`fKDUIDb?^t+XbW&Yz!b^!&va zazXp*mm9dVyB?#Z&iCfZ3~Fm$`~Cg$?HIZcZ&H16vZaB{rda^<=27m8q$UPnH|GP{jH$w46%UQxnwDwpcM9FC0N6<>N7JO#X z9ohVkhtaY{vmZykdvQ3~!WJvge$5sqQjoFgvhsEz=8e>4Nzpr5-CcIL48h_yT!ESn zoTN!#v7-aI{RK|d(5kRbeXZLD{sOh7qe-}fmJ~W;8lp9qVWnx&OPPoysnSeX;h)kh z=NhT9oDbcazrT79Mbjr3eONFG}sS0JyUDXFP6}uwYX&G)D0t)Q5Kyo#$pwDVS0KX@ZvU%Fqt%WXRLbAtJ9(R2D)`&Cf*I_x5T z*ELgj9KfW!D{^CMr0@8Vv!%vQt*&s4?F&(&?bXezg8Rp0W%RZsKPzde2jUC-AwdJ$jaSJMiYjl#2Su8pH8YKpd^XH0>7(fEDL5UF_2wnnzk^BV*{6QkG6&A5a26W0FZwqo>V)@0uGj76{%4@ZxYvN zSq@%<%+ydhgf0GEe!69w66UQx{0mnOhoDpDxXFG)dMCO>AWTX*1OngzKq$7@sMO(q zQf^hR@VhsUwz)1v##|?-c)i0U%;S63c*7#0EB6#_^0UZoF*_;ejH!aJ24D9+mdR{O zRh9nPbx5G(kk_nuS@Vx8?_q^YvENP$N{-BbJUL3;VwKnXtF&NfyO56#U$1P@uJEF2 zPvse}Uc9AO5%Uo@r1ICRsAS3_>jT{l)iJ#^(S{Nl8wW@{?)Oaf*QFvQ+&b@KzGvy% zygiWOeii08qh@@NizTOh!@Jw>BS-;%Btq{c3Q!Cp`iZIQMC=R zP=5)pG8eBj8b|zSbitf`SpcmnZb&Q4Iy7c^SM!;5_`T`cZK^gun#=2Xt>RttEGL4g z>iwps(IBT`Zv49{E3y~V%(>zUHEz7NnTW*+5AVhelL?Pf-lf^xS_F6Xn5CJc!PlDR zrm9cXPF94=i(@}Zsk^HGwH7UZ4@_T`^>mwV~o!W;%Q( zXR+(|Yc1d2U(|lW@NEDTt=%ROPJ1hMRBddu)qq4@7%tIf)9IT&GQpDwuAKE@h+!oB z{=`aUWz##7;8neP3Ni8b<`!2u%0s0Q*z!a&v~2}Mzq69 z*fydn-;k6Nx5L4=*d#F}l3HZS^ar6aWLPTlrMBubAsHS3J&K<_&6+|EMvyg2#x8B5Qz00vS!0y*EOAI}qg} zX2rwzL%=|K{7a2kY1&U4VbAvOKMS(7-*~|FQf`xr4M!^UJ~hWtTe2;r{j0j7e=>yx5A*Lwn{nHEWVpUV9I-f4Nv z&3)TuO5Y0coaOi|R`j&mP2-vAES|!3A5*s*^_|eGl6}e{o)UL$=Ntp3b;=R7H1~uQ z({5^MKkYF?2@HI4hv)fCgtl38h7aNw>)+8yzvQ!mLsM=!p_>46kK+Q0RZbasf$Cz$ zs@(9$?h22HVS(fy^6=t0QStckOQkreottp0D6nw;8gRzWuC1|3*}D zP9vK;doe-^H`S2#0)<1auwvz_+2OC}OKimZPl`R7UPLJjXm;#vUfxy&uj#$5>U7YP+{UVzGMuQF%EQdY6O;gRy z2_!2LRC0%8X4yxGWb%Y82(8^51%2E46~Exf_3go8S2{4x@wP3!8{<|xbBHxU4el-H zPy*Fq^MC=KDpi5HFa@OYqa+ZWeex0{L`lqIIgXy|L-xVVQ_TH3?q`cg)Ytp8jd+~Z z*YlL?tY+x?e8P5fIJ%EgRmo~a8Hfv2uwMUt{qk}Fv{$|&#N9)U-q`e=;OyBT>@z2C z#%%O`r1+s^{>$0yTy2w5xq!-+nOfeQ`T=KfG3BQXJuPTf&P|EDSeGI#6qpZFs9I5= zCA<1KwY8k6FE#-ero+AC?mzA5O7Q7ar3VvM?92ak8;D=pLI+ z5rrnmz_3V>%EXTA?LaSWur5eBMG<>bq?+(*!2kqLfJ?Hm3bOICZSf+u4(hh}+S!aq z=U)CR5U8PfxF=;kwp^H4lXC+A768Cjb6O0?n&v zpXV!hO+0qTy2?zzz5y}Ov8J^a;Z+wYC0i*MZY#5aA4?VI0beF9a;Xh>w)I%m%?i}? zchnq<3qF`l?roLCTZ7|S$*=q6RzRfoy^3C;ApUJ{?LmQ7EYdm#&r;SRmvhu^4Tc zy1omj8qe-5gvW+~ReP(vgr)x1+sDcOd8~~ClhRF@2(UQJm|qLhQ%PLf%&&lObF3Fv z`mkA)6jDPk@weOSlzAXP8xTxc*Qb!7E8IZ%B+yd)w!~H|{^f3o9X*DefO$eqYSZin zYM#dFm|N<2x{x!P8Ij59)K>~CwS~>?!nVjAJW%Rd@6}ycH6A!!{lRXA1+KfAG+So& zr^OyFoSuSQcFgN`>UL~5o3G3$b4wQ8Y`AiMEqYtp`P^pu)MR?c{Psz(%g!wOTEgX% z%oUK!m2)xw37+jW#kGF;i$>bcbC)adn2TVH>(fJ7&qsEjSA_YqnNF6dkjG0-Ym1@O z_M!CLVQlu{yyfB2d*RCE5w_gH_m4t!t=*`(+>dReyuneIrBPYj(cOoA{;YZO1Zxh zbHyxGxCQP-@BWDrU2)gq$=9#QPbf~atSD&4`yiTGD6v>5!CNGcC{pJw)j67!ZlMwIa`l-MH5bBCYXE(BNaI{)BAEOA!WASw~ORi%ikX2+@q#P+5`^y#0k z`wm}Ed25axYILc?<+Qjm)9aII8kj2^IQbd{D;p*Fd~~)Y5_p?xNXqL|4PQGY=$QyO zR<<;ZloF^mA3tsLw`fZk8NnY}EXWzg`a1Gyr6aczFAKxhH5T4lGSaeJ`O*H*r)n1R zhe~n~KZU&JHxZ&u9R5Dysy<><)yY4#myUV2hyiu}!DGk4eZ>3wiotk-;p2hnCccrt zs*xe5ktOWO(SfD<_;^|MJximNI<8Y!peuAEzx=R$2zyBYvRuI5;a&Y>s&c`w8Wm$< zCoixhtx@5>-bZjq-hH(Hn&==z*Myt6TYLmsRglsuu+GW9(wwJix!O;BJYZb4X<0Q# zUNa-V9&<}-zH7FpR&%5yxTAmkm+I-iKg_!>HM@=&7hvosHk^WMR@4BDbefjCoZIsl#rg^wlzD3g8$51eiPUJW2-%JuQ}c4 z?=BTM*V0IMT)lqjylg1Mu52~twPgtgxF)dayeFu+dzDf{C>dGaW?8;z?UN-Y2key@ z;2@fL+`ERbrFVnZy8{=;f7fd!&>x)69}9b^9{v0jwaYv5&-nP1)9s&N-6?_4uZB$l zeqfn2k}N4y2*Bc*Sfj2xR?zP497z|j7vAGe!mhODTj_tCS^(AIB$!^ojXc4UsROCF zJz91<{ULm|e}a`)4PZ`qOBgaUUty^0FQ_s9gt)Po?^PJE0ltyhyzsvYun@}Eg90!R zP-Vj7jk6d2Lm_M6mwi{9`}%asndOM*D2k(i7_`6PHBhqGMi_SJgVoU!TI2? z$1kzP)xyS&TgaX6!M}E7jd*dZ1~jFXXcOfNq5BDb_8GW=KohgnT)OxB>T+-;P`<0o z%IU~Qb8>D)<+ZJIq_om(S$R29_QRR!{9$?t4~iQ7G2rDBpx(bBC-g zsZc`tytPBf4>uGbSTZUiG^~J>o0^rI5-CbqAoX8fzPn2Ew*2pBkf3w)##!}{2&2$3 z)A#zV?s~0kWDN1a_RzDZwK^{*a>+Qb_~3omt)41;0N*@_CvNhkQkP?k@~!9p%eVmW%DoppqC$VWh3zW_Yc>T@2oSDs92{hNGugSly=Y;mii4^~3W zRvHr4FC{*T(ioacyn20BHiX#|I2@YyZGLh6aw)tSdi0oKiW%yZ3AMVkIdd{fvdtRe z`P}d)`-en?EnIQTdvd2aZz5fB>`j>20<8a!+p@R&L33bRJyY$uM~9b|!gJ3&u@~bI z=HYYOvda&4Eh|+LPF5cZ8=Ug`M?)#%DtbHI!SmBw|EEf`gA;( z%l-kq7cm57GPb2P_M2qfaBJMOWc<(TBr`tOf|i8J z=ZSw?6R#xUm{vHhR1(QiTM~^_^3%3tF27`x`R2)%j~Y^`FWXZ8kGZ!Dt8&}IhLFy4L6s0>C9n#(1NU3ypNJzKRE$e$0Slbl}bZA;Xp<(<{l9$0n|&DsJZ}>vL81fqiyKbyht`Y|D$R4vzSO7dg`$ zxjohSBh@(r9NA09kxtcxUK~YNYKrhVi?0Ods&SO)z9@NAQzFD!Dpgae$XTXYQ^vSj zWa&_B%UR)6Q$gjxeeM89L;%5oZae_~S%SNB?f^$bAr>x7Y;;4p%AnR-nDovIi%K+B zxG1^FkKm5UL~Bt>OAtAqFR@5*YO@WhOpIDvaau>@E#3B5k&^VT*KE&MC)!FfdJ?$Z z&`3l}Gy776LmAZDOS1+tq*FxWM9Z>=a+FF;Cfmz$Mhdjv)tOP2=Z=*a4PCsvU^S!1`eI@wWCFkSBqf0rqj~d~^WYP zAt2?WTPO9U8FyR-qZ!ptgry$J2f~T&AZVh^jQ5hrEr>UmA!U(NyN)yzLR z2VWAgujioNQT|_^!!J(!e{c>djBVYuH3y$RW}UTM=Y06)X!f8xN3-YNrIUkLC)85p zKRt)ckFMyf%OBma1nDl$!GpjcbH>tB8ysOY>qD2GIqQ3)e0kRIRx{n4 z|J~v9bI6R3ida>#{K@h#{SXSvdz9^Zl+WC`nw~*YDxfv3e=R=KdY(Kce1~)DR|Z2)YLM6 zoZuhzHVGeGZI3*ycNf3ASABQ(MNRPyy#3nSXveoBFM69$IOE^yZGXF_IH_}g?QLG| zFE4)g)$hFxO0Qr0qqhZ3e*WIu*j^*R0liK5h$J)7d4uV^rU=yBu!AXQJOZh`|ED!| zOUC6N)znggGZMpcqC1|+a*{Vq_Hwd6>*{g}M37-6HB7-|B`wMzdqr>G?1k>v<3Dey zlmK*l3YYc|kH5`FUh>zL%EnaJ{`1o&1HlaZi>K}X_p%#vYX0rh#-TUwTcip+ZLs5~ zGJ)dTU70`JT$V{dR(V)^GCw|Y1#rA*y>dIa+-}LVQVR{j!L{meqA}#VQ{pb!f~#MNtv@EUnIaDe3;C; zVtk-C1nPlI3qp_}_)GK<$PPO-8NPkd9cNegRk|4jNey{j9yoG6?Jy++b{uvU8+%oH z6g`9F$cvWBVXe!113=4REtOWnyc=k#XV}IB!7s;`XdRtay$qGs0@#<6jER6;6P4k% z^W!&;2t;DPIDV^ei`A8kL{Em*%+v^z)vV0)>{VcIUR}*8Y=$zd<(3YctmRcMX0PSH z*ulapI?$7Y^_XM+xRv3O7ciN9>Lf4(E^mcCK&O##;Ejmr6m z>l#cHO@^PU*UQ&F)oeC1S}OQTzMqZR8|M66ce?KvlM;8#xY>Xpm2Sz8W)fM*i;Ta% z`3{RQ{p0%xL9?wU0>j*`W@6j*trl{x8{4hmNVDxWx{TcI_8S%J+a0%BZtQg49WmSK zVq41H>3(pqzSF~v%(UCfk8i%)Crq2S+b@29V|PGWh-q(7PSJdCNXam7Z&=NCV{b&u zi)nvUFVcK}%qSyof84BMWB!psZ<1d>MuppPF2H32%t^ckItw^ z$(kaY*D@hosFZ_fE?9z5p>Q|~t;%lkPqir=Qqi5YwYb&xK1$-48R_tj#VscZ9nj$> z`rZTBSZOwtc%QAe*&~ijSU*pMat={ZzG_p7W!qKEK%= zHvL?CxR?Vgsi;*Z(to)6 z-&UnNP!c%{2>bT0s}gYaN#m|UaUVh6aPPqP=4fgV*78Vvoa?Z4ka|$#^7?Kd;bD%h z>k(+1)mL_Q?|y^RC7MhvfvYbO8(gur=cU}u3591oGPw>Ta0qOcwWULi=BK>C5yIhc zH0ha?5(jFy4ZgRs>6*lIiNW0dY>VGUbp0y0U@q<-BYNFko&RD)|KqFwl=5T$D+p|y zNH41ld4^|mcg8;I=l8_KFed-}J+c1ltDm!;EyeubUVY>no39fv%{CiRXmeFd(CYE9 zek_X|AY{-yT=74FYw;KQRO_a1wyja?QZNk7!e5Is!v9#+STl{8e*FF>d z%ccEq-bC2aK4r7T?SSOOgTLGpslL>Cu~2lZz(eh!$QX`q?4w6f)5$6|v`#L4o+EpC zvwxcVWNBxO`AW<~E$A^KY-yiDB5@kTAfM7inblW!!7}hj5Z$i2Kkd<{tt9Pnz3#5I zJ9+Yc5EC*r)~pbYa7e%VJ|wf(jkbAo+&zZasz(}B{I*X=RXR1&2b_un8B`2x8*WJM1i~M&V)( z!6npzt|C(L`f10QcwT}v;WUy7$UAhQ8(Z%)!e4yk)zd+~-9&t~>}d;miQd+8v{%I6 zCma8qHuR^<+y6%=o6^5O*(@b`F&{6dMp_)NWMGpmXZRzX(^rFDMmh)GlvmD* zM}su;4i}#zPo-SOHj$29u|!Kh8SZg+JZ%|rdsGJh`7;0;p(lcng&W|AHl0zxWb1Hn zKMENH{Go!c{a(n@9}8U1(YGfvwJui>1&MDJC0(Fzc3WgTLGavY2=pxTtwFTNA^br8 zVtW|1Vzn7+sD5W8lVyLWamkW+9QUi?Q~EI4z7)PtB6)^T`tEeG6yCVw(pAZ9#XKYd z26Vh_2a2b=IWehTZAtYt4(1~idv)}yqRolHJZ?kBA=e)tl%Vkve#RM zh{pGSx1wYwE8P-gp1ZcAey8LguP8O1`6+}pO#7xcgMbx<$6@#0ILNbWU(2)}wxTeS z*!J7rS+$vbc>p~xu45s>h@%?6@@Iqj<=3rztYU~GuJ3j;?aOz&l!uJ{XmQo zxX}b;=Z|ggh&nNz_WDGPtpi(+mCP)LR-r}}2iwMBO>wD9086^Vw-+I8Y8Ijy%D8K< zQKI?2kh^P#xmL47s`A7nTel@yAWG_Ut)QkRba@|NK1gXhG1^k*m0i{GmlMPQzI?Cf zq=XMQJ4STtx%Y5)IZn}iVt1?WJ40vq)v&HdAMd+zfcgXA17uwVw%sBTCA}P@jS~eB zJ~j;Vpx9B5PjgGY^Kk)Ry1m{on2e<5i&+h^Sa(Q5zr@ci91fZdogXjiOB?u9w@v?p2UH>#ry)BLLFfa|8j^x zsfUc;=+h5yS>Da8)ms5i{O7bs=~_6(w*u`t=L83%u!F;7f}GJ)$&str9^!06yv0)~ z$M){=F>eP${8PbD!4{G8{6%nguK;(joNQC2gJj@iPw76WtR>kdwq2zso6zNQ3tI(eRAWE?xv-DHYnYDUBmt~$u(ZMZ%< zK_L|q*$GLx_}iMEpG5j2T+{ve!-O9?1@pON>!sWJEO76vL^-*4WN4jcNxO;4v0x5m z3Vdmm36GHrM;S;{bzqRo$j+`;>P{!w5@WFx#)_BS%P9|LP-;0QD|pru<6P9j(^(x! zx*C%EWGF!CDgH>cLU4XUbdLIgC}HjPUV$@4t`@S`=*UD@fdh}3Hh#xwGsk`rBp_Fh zR&12o@&1_o(oBgw6UC14;p+Xe9ezeLL$MFz(DD89 z%C3!my_^qI$NLox82Qe)jB3qoC6%pZew-m46N?-NRlNcERvBWGt11W8qh0wn6&;hG zUK|t{@=p-dcf9vf>Z3xe6|-9@)(9+(d_(Z+=3#S(#_`*Oy2GvlM>hkFH>~azC;F;z z_xJ8$tu|?2Vl`*Pp6x{#38=)wnb9U8RzZ|Ld`s|J66n63z0$%hL!J-~Y$5Xo zWL-YA%l$~MW~1+K1s3@miq8=-%GSLq{Ve#zY>xEgu!S457~&;9PkH^QRamk(B(ig! zhV!URIyh*JaLLW`6Fh_QEtJ+8|EKsCks&Ud#VlI6eVJXq$XB1} zjnub}W*;Z&4-JGp(l6GgNkRKUn96k7gKof)DS!=|*3D)W0>{lZ7^@>nOuYh{i9^cD z&|?ryb?T%nz2#JzD?P<8VdqL`WUz=eS06t3WrGJz>T$sajMLSEau8GC-(ZG z9;w74pjB0`m2bt3FVLV^7eSadq($X&A67NyIcn$o1}BMeT*fU0x8Efct;qeLSBIy3 zf?v!>pYyo^;n7_avA0YM7LDl0S$SHEXZ)7$WF*yMn;xQxZ8f_ZcYb|&Y3;?nj?kPs zo#)`-b7#_?KX`dBt33Y|9K6A2T9&JH)2eJ(nX$BNM4fiGY*g+!y5$8pD8qDPsL!lL zJ*9*AEz|wJv*YENN$!VGPwaBkjW5z*IP)ZF->ZAb!EG<^f4VjYKhG8ZMhQnRckTf% zbCqap3_pQFm@e}%uPgEbtH7L6Oy3G&kR#QkgU9Oex;n{(-1~g4H`s-x2c*I4a2C6> zOa|U}8^uqX85-Ggg;LjeeIMynejY5z=^Hx@K{)cdPV#Dxr%UnXnQdW^<(bT@ajyPH z`}R4vQx+0#LQi*XtFyU22;n+?In_;d1hUX&58+@V^b^Gs&O|u;R&M4z6M3j& zBkiQ6(zVV+r2DOnm@hWn$kCHfgoNMX#B93Li6@~cw!X!y-t@TTpM-8G{EldR)03?; z3DdUq9qI9=7dLt`)`6GsdrG1$Z(;Fd9P^L{>eWIkN&jTr4B;jQl`UT&vgoY1wTbz~ zmY)`S3PFo-GX%ZR-$*=#Xr#57)y9Wh0{r^AGRhm{d+sXFW3`sZU0WVVLaYsSyTF8{#eP$HB?51CF#q+K@V;^kFr zYgee=4lndiyJ0BOp)$T5QQ4WsY}*F(^6kh5^z>U^BAq%!CDefr(w8aIJ2Uo*qG|l8 z?k3Q58RzH545wKA|pK*G12c=64zZ~|Ju z7=)fL138H(j03U?%26UQFwZVy94U~h^+dcbZ>C)QxGP;iRo+~+Tye75qsBUSvcz^| z@l}nj#dNhD{Mxn7$U@C`&d7|+Zw{Z#z4xc$jL0qhmID7n1Mn-H&}AfSZvp_ejC6b` z>dFQ{jDa>YKDU~^N%RQ%?1BUEcvvY#R9nxv=d3>5yS3gS!Ms1X=d*dKf5$xoz}Bau z9$rMm-|%D@Uk=E=@?`OM^#M46VcrbU^`wR<9LiEslwk9RC)ifToHznC1qL2Uunh&o4Kn zQF4AAwD&S6tPCDw87mlxT1%R9Q9*Q>2hQJB+H3vE^}fQiy;d14hG6W1Sir|^kuqW@#BTTXCwJ_VI@w3e*qFab9s|xwx3XMbs^p_1; z_zxz~NNV6O#cp>~2qbDY6B=t1_I5~gKF`X~$RHL$v}eR&-!XUCO(9Q--W^m5HIW)3 ze;W6dC^7C9KPO7clQ#4Jh$y+(LcS9v4y#rdL`kU#+IOPlAy#{g?ZfF*zmoYqP_n0F z-w;XCr=!(~=!e*D)LGrf>t4)p!DFRMfrD=uRlz<&ObX2&pWf@TzOZk>FE}->6`KFN z-MhAk#D}6cY_&T|6}2Yx#v1RlEGgz}i1hB+T! zk=P8TF_?PzKoP{!P8N*?xizQHUWaS!xS z-1Z(mBjMM|_D?#~`SV`56V)o7&Jx+yX~3})-RqxzH$$Y$MCGx2an0g(d`1@@Z}IDo z=u2*O^xfS7#j(rc862OZ+O1izP>_$BaKje5XJ_)`4?8m+9<*ikI3DjLfUe=$A`#KM zvgj$G+*{_sQR($0l}jRXTdpOpmiEDPPP&q2#D9;Y&;LbfGI4FDz-_etAdA6N5~eIs zsp|f)Vps}%mN1{FY*hDP>b#!TRpr#scvig(?mc=w*W<@Yr0$t~_p*5)FXYlN-Lu53 z8KnF~hf)>FvJ?YM6cQNZGoM-KJTA*tD&kPci`dIC#9&k&F;OT_9s=Gx5sAx@1DZ$( zKQJWNBufcj{~beuB-USGNZ%D)PiG6<@v#kVR0eCcxR4=w65lEYH-{3*Jd;}qrWTH* z)D8(VW=ZP`zpuLZvg(dOPxK?xS>o(aI;oV0!Eo{nrI`aMQlWzC9A)%_IkH8vLnilf zM)EWn(af3{w3Ukh1=k-dhcxT+&d^97u-)Q)=l+v|OVG~_=-yaj0TN1t-xXXxckdL& z1ds0uuDp?JpQo>IT0ZQoV%wTS^tdA3Jz@833E?$W5az4I-KBv%MY6zJ&b{@Cdf*!# zn2tv_I|~JVno^E05BJxnJA^*RJH9;G-04v)AcLOmoPLQUbzZus*Zc~x3u)q;a;SCK z1&6m>fUkW>@vF)q`Dii9z>eY;woaMzxpL@G*-#DrBZy!3E?$!+h@8J&l^wG|Qs5H$ zE)~B>r4dXyk?&w3`8FZa_JdOMj?BkAsEl&TB3lK@kZkhtmBpN{w{% zFVn(k z?vb3EA(twKpS(Y(xx2DEZr9^G0W^1?r}%bTjAX1{6CI4^PK!q0=_ELjHC5DF@Zaga z+r|&0x$~&=`wYN4nxrY|#k?Yy^-6enNA4NF4X)c08z85=RmLwS~8}R`W8Lz-Z(NUWZDu2qXKyQg-RkgxA{rs|z ziS~wPT*+mmW3So)jp}9JsbuNT7?CF@rry&ERhvvgy@6rc$1xR}3kHKd+>LWXr#f@E zdJhC*$V(sWqBs>S1SnLb*`G`Yu5la-vykSeEDaPu&(PyeuGC4n5kZl@g26!djxKLN z;(#y@^ZD;h^dt47rfRS9Nt}_kHk#=d0+Z~F+am47Bs(Yzx>U~ld~d-m`A8G(e3C76 z1HZYLWSLPs9|Du?x9w$1B@5?05yXd++Y?!^Qi1qc^>6`rL&b zWSc8Ws!u4E_XJ1NMb3K;ub->jJx@@ieV)i`Oi(9ACNz>i{gz)_r)u)1JqE=Dw@NF6 zH$e!~h*df(RWj&0lio`N?Mc>_Biad!hA<0u#ha)sWgQa96cl{(s>RU-%FmkOHSMXH zw8x;r&v4dtK3aLRk3I97Oj;1NR?c{YFG^%m+>~S?)60}EmtOiLIEetUn+^-7rYej_ z7J=tF)(tv*56XF2LWz|Jlf}1QEK)~0x@3tOiVnm)6i>%;S=M5Ws`ne;&EUq!Zhff& z!9d%~6qd-Ajcf-#>#>(59gr=TAv%<;vX`yYm90?GK9v7rFGmX_N2x`0xHx7n*GM8q zWu$$$ym~M1NkER;lITeF_+GwUSB}O(`$*k!cs>vpt~KV$*d?G<=q-_}W9v511Yk&9 zV3Uw1NXp2f<;CIFSz%zGUooWeBacowKLA6*E32ehF}?j^bPPIPP9a#Er&CZRIw`nb z>=Tw}31y#{9UiDO=fa=sR#crA%&jtpBN3$zQC-qm*NIV=vA*07_9*0K3mwn5ZZzrN zqA9Ofl*o~CiJq$7Z?%S3_qO}sP_X_mE5#$VK#83k`((93vv)yOuvZl#pGjQ^oiuqz zM-Gt$A2wnI7P?X;=_EvHRrp+}uYQ@E(g9oTnLAoN|bG*4pU7?#*S9Ceqe=*Mk!E&-2v zmm_9rVrc0S&-LS8Rk*v!_5>GH>N%;80KA^W@P*%B&%e??>+-5@oKcIA>pOF)!k^jy zqPsoUvpmkIMF2ivM$C<--}77j^9x8=D*{#8Y4TV7GYkh>7nh|k$_`I14j=oWe^wA$ zrLHRLngsOE_na(OfCJQ9=UfpA{G7YZOhF2QrQ0 zb(9#(#8UEgfe&9*me)E}T6RozeMqM7wV<80VuXl^QP+m9l`>E_(y++3mQwAgRc^11 zKE)Br6VYO{K~CX^>J5!M?C;#`W0>0RiO0<|%1cQI8XdCnP<^Pt-#heKf;zinKzBRRz^M01lpq_}Cc917=1c8db|mpU`STFm^NlPkI&$QJOeF&!Ul4nvsQL6$yE? zK5SYbbil@clLu`A(6eYO+w~-Y@XcGPzn|b5mmvmhiA%ktgkL>VFX2 z$FGa<6cCB2_cBRFu04b4S;_=hHP1z2OrHid&P8HE7&d<;68mNM`5_YHyv98rW=Leb z5Cx5TvKZ?iVp$KTKY6sQrh;;BC9^}=@GF)2E{s(-8o`R3_n z?WO6^&+lmqPPbW(d9Q7E3PB-Ty6Vhd_9SV2zwA%ge*SXs(QBH0cQ(@U>}WY7A!l#3 z;`7&-(6eDD>JG!Vw7edP1l~UyNMBH^QR5z3GDG58yz{!EG{| zt_1%c2devN_lf+@1p{bu(`)vB8n1{j!Nr{|sC%V@lXTvIY;2Rt&o z;LVo$q5_E8V{*zGBxjF9UAUy@dVHA`!Zt&06rrZ6{5R+z4-|?`T-CfOF`l(bO?8H* zmyUyE2-{rPZc>7XKrSdD?s9nI5Ad%C@er}otFnlP;!$|6YAgYx%!hj z1hx>6{LPj|^-go&@e4e=*1WSO>2Kub&y#av&Rg1Z-JAq&#Itpg-Zmcw&cn+*PB z>Ci7H>TSo9F3~mj_-P?19~w-sZ3#?+Svp*D5vFiYD}a`!?ZSX5iucXZVXrgQ;m>F~ zg^mwWqlbrkPAU&5TVh zjcW&XC6y|^9aJHNN;&DS5&7e&rQz4B6lJ07V^GQk`OmY7eYH8z*L4PPK4k%cDumqR zHDMJaPG4vnNtHU~%QB{&!|gp~Y%fbZowUI;rwB%n3Pv74K+r)X1*sa*CMmoaq8^m$ zkq4{I62 zB!Gys(#r&)eo+d$&cU-XFLnbn+8y_dFg5P6CMI|yTyK9tOOzcCVMZ|5-DsR|NFXf+ z3~!#PVyVB4KpL!Kzy=CY+R(@Ix9`3d7miBuA~+eZN|`W`Bw8u+1!K99F^-@lun@%B z_(nlwE2H=kqDaTIW85?oNN>{T{YN0QB0}IoEaNTm7@P)KgiI$DfM2r&R8dZbOtH>#UajZ>La zkA+C>2Z~`5J*1PM;M~y?M5Dd=bKPsUI+sB-byGCrePAKDmaXq+H~xyV;XM{i_nKNZ zm+*e=8BF(D@1ejM7y;A0dg=SMF#Waewd8Uvj~M>oT^^|`xMkdrBdw%|!Y#yEZ!m*@-S$YFrI6G^bJyPt!yq%;a!7js9$HRT(BNpz! z_LgBbz1#v;f_-e`1h&~>sxX6-O?S0iI?3zEGaE7c`CsY5Qw-rLa-c?dx{-=&M@we{(DoCq z8!!J1+P+u_ZmV8?kc3~`3mPu zT);UPncT>ty{<&Ni6|18y!h?Co*cVLSOJ;*w4!~!D!a)9U73RS+xr4v0H7g8mavd$ ze@M)3DxE}@sA7A6MD=dkt$-|X*g`N4AnILNlD6#w@yF*2fwY(CU^0<>*oOzeLhyoF zP$M+!{$Pqwa6$UB zeK>sRuk|GVrg%1YK07MnthEmci?BK(OPt$;JbB_%+$Y1kBWQI(1@J{)hgg@f>F*7D ztJRt%{j4HF1{yvA{BPxeP^9teQPLmZx?vGAge~7X_wWhs>h~rz2O(W|g?aeCY|^&_Ez{m93U$oy_YqYGHnYR z2YfC~)P-i6*I3vO6+9k$nUDY;K2wj#t9o-qVDeWYNAoeM6_>6~YKtr4M!yL6RvlgP7zqmrgbn@NZ zxltiLN=$5UiA{XGn1!>FdEWA3@pDp}yFG++aup-sLSLs`$pC zx1t4akI;tVi}6g&WC}@h!ZJi&5-}9x|5%l<&^rQk&9I`$Gn(WSS#ZRo4 zHyhwjlM5vc&US*D;LRp(r(?p54t!s5Cg00~wGCPXNIIVdf?*AxeeA71jvj>a5<0MkuE$+}B<~E(Dulm-L>6ycDJI;AXUi869f$ zN|-hZzXaiKQ^)KBMu$m?59H%8qXRw^A+`1uGBevqYU%At4`s4^HW~eQBZsqJjSiR} z=k!zoqXVsa>?9W=Q<&X&{PPPr;0rYbA=cwnm8s{K-=&4_a;z5$`J6Z`r7@H75M)bI z2_}B-mfvW8{a$9V?cmM{Xcyc=P~We67jeDpdFBEgVgOgk0X&9gF9R}HLiMMJP|H4& zAz+3zibf}YnA4hKYF8C9$t*p4nm`x=MO>MNx)#4VAcQdXB%vN)8dZJNPJIAB8W`M* zOumDi>Wtn=F7VK`(X~{>O>XQOijdN6oNae>ge)?tV!gM6D+M0Z^rSE@b6vX7GpdpJ z2bW1H0kxugPx&dpTd|J;4QbzskJD15qwB+#!JCP8^WmX3p zrM;fLX!y6)jow_~_c{wY&jv-vzX-ST5^Y2H3H2lswSuoxZU-N>QR!4VCkgOuhp4T! zfRg70#9y#*4pNEIqRd_qaNG_XZ6i9=fkTjkahbU~aDM$9iNY-BTqee7jruW*+vPzK z1V<*jns!Eq-qJ zp+<`@Gadj9f0A$~8Yu^c-$VbP;a^S3>h&~ewZ#0|@b|mKrc2KoezR3!3i&l(cmS!7 zohVMF%WJ#$_-{4*|0x3WT}AYkXut6Jp0|#&C!iu?HAqxl5he3$3RQVu97dAjT=)3u z2>D0KoX&L$Wj1FO-*W#(D<4E2hw=N}&p-(qXq&|HS;NAs!6ig}{wT=YDjz&=i^`7i zTLP*E7p49RGjUf%6`u)3$zk#i2aD%>D2;x%Y^&qJhwk={BHD(oW za?nuD>4kHE1c*Nak;DJF;fLSO@(&E+u*U`OH0^f=ai8KLP{IQ@G_KLW<=$@q$>VT= zgr5xJXjbP2aTq{iChK7EXY>MK5T6rd$^>5+#Opo`CAv2K{E2XlSiN(4!D|Y9{)zCb zp+uuf&(;QkPlU&F9zM%aC^Li^#1Fbh^2{bNVG`BSpvR)d)oRH(E~2`!V}hVXhK&c2g&tvz5soDDXSv>$tEg-jtf2|%$UrOPKJZJDJ1P& ziQ%Q`dv|zL+T&T-VyJ70F$%Ze0IHQL)0(p3T(GdtJzZ%r$>H{!B4(q>OhfX7y3X)- zqvv79Urf~an61da7lvaDd+bi9-2s-aUf%tc2|ALE{agL0Q7 z23{CSw3eGW{DLH11Dj#mLl#_!N+=82N|3rCK(q`>9nS^;5z2B3b!e z1`b5|<8`HE-mir}4kWnv`kGZNr>oLO)uS7V;Y=N^WXG%yo8Al<2cr=Z*{-&Y2YbS1EKu`#wJoS41;=530e~02v0203RqI;_b94b~R#IS9`@phoi zU9w)ICaedG*p7~;Ddfn})!bhts`xN+7$#BG6GW%~`iby)GWx7G$rsx&i7GZb{a2w3 zHIm51Hc{xW4^pNFgfcj{<4kpVtVFOhFyBXV)DSg!(s$N?LW63-i_GECojS||(OqUJ zOqMWmcqaz-xKsc_nHM_%ISf25BHcoyJF%Uo`W$XYoi>6yajQ2jb0iT;*$!WgUw==_ z^0^JE=cURW@}G1wh(KloCmh3n!j2Kg+keW=(5i9eMk-{u$j;!2Cmvi8ybFI;ynmu*3ClTez^`svU@%M{btLkCd8BQLw)D(@T zA}9zk+^t_SfXs$s@1!nGMAXk8xzpcm;7%N9V$n_iv|ZcmbIW z$=X{Yg+AOkW{T=hC#Vl+fy@TsA(0^Kau3|Nq>SVsAhQ81#?fr(XO<^ig!p)L%U~u1 zU|y*Op`|-v(tIq|vyW9_nGHx36*5}zhzk0iMu5TCj{`GIEAIVX_($L8`zwYKD_`h; z_LsYD0S4plBY41H?pY>q?l1odI~JP?k&aUf2Ig+6Ms^S=xB135L)hhEpFc7f!?0sc z$T_AYi0tLgp`r`|PWXki$;VUBE>nP8PM!Ufvk37kA;$;JntE)Ld`Gd9+ z+ILY8zlE=$ieP}MWiIvmi6^+;pe|c|tCDAi>TmMR$8{2x(;BB&Uk>lfdLcrkUN*51 zOuHo(Q+7Q}{=I@THRePI45@>KuiO|S6K^mjJYU@O1FUa4Q1A7`54+yJVwrXi2;BE6|T4_~=y;iGl=?Z`fdE#9FNfYbp#t|j9&O;<1u(&)DMsp6*7u+ufN z%_|PppFTvM3$Na6MRDVRH(%YVJeis3f`zY~EiCpVh|xz)YB;UI*BVU2!dDVi;KAfP zI6XzQSWn*8(tdP-g|B!}&a`~=tTW!5wuV3Snt_FW=S`sPsoy_ptp6n>@dFU+(s>K^9f`Uhs(=jpE}U=H;WMzik@bt{)O(*N3_ zF8$y7xX$0!`m^U7$TR^psz2LyFM+T?;cyARDKf+|ay8*X3?ShMgTwzk;Rv3l_}x!k z`a3#8%`1y=wK8@LyP<{Y?oa6}zezZH>?@1(QLn9CD=$NdUZbnM_!=zX=tAioq0s}= z$1sVgT1ce_)Rcx#R$0Lkj%?{P(w(6DOk>@joNe4L^f9`@`$(fF2bDmVzViiRFn4E! zy9bHK0XM)t)v%JxY3yXLXQzHR4H#f0YHWo138N3ORA(dZu`p`I6+o~(D1B5@$C4ndqRiapH&s8z;( z9!SbJPj5D3K?&9VozJzVHeTNx>$YIc zZ$&2l_zfBi4*#XdZX^v;{ZC>b${zQr|5*&gheMMOPYRlz{3ZtC4;Vhjo-SAn#MwYY z2rLGIi9PTl1_CfkY6QoS`2pyN@8dwgEJ>Sh|80OJy}MEl46tL_pT7;TXDTC{zyLeF z<6XcA46rQMuY4O|ub%B2BAW+k9*nJxzdXFdA_a`ahA&?pdnBx$@qE6H`{>Q)$j$mM zyVFv=hwE;Y4+UpX$q&Z`8eCBdoe|g*FCkYpoHcGZVZs=`O7@+-4hP)Mk2^3p`~{XG zacS%6zSkq1)tgRqceT-wS$Odxux>D|_g?<;{B7X-O}7iBH{W$U1T`)|ALAInPk4p_ zD7|x~P(lH8#K6!8ru5d;eNPW4y(3%zbmXhLF;!yat+3!jrv&L4e)5MS_)7+BAp!Ml<=<17!ik*o1aSYI{iE@F7>XQ3T z-Ct}L2T?=Np#?Falr|exH91l%tN7MiWqG{o4ng-n%^!@cL5+GM8;4+{m?+XW4wk-vR4Nd~VVZUEe=1Y^t_h33$FV}Jd)3`@6!i^0yyThY}IfLPj zW`p?T!*4eb-0q4}_j$mJFat_E)zQYm0n5BbczjAFV2?61q9~sacAnPT+cTo(%N;C9 zhT~&Mj8uajrbP426W<*RH)7b;rH5iwq0);$c-rw&D=A6%jxb7zc&O6H=KSgN=^AO^ zM979e7Yo$M-I=jSA|nR zN0%9M!=N@jxH7G!t9g{czOz=u7}6b}tXYO!;f+$Ate5X-RI%+@0;oO{3eU=M_EMPq8j)8H(7+=JX!c>Vjbm6b)iU%MPS&PQQn+kC*L9`Eondf5ISr!dAQ#z@2)FbW-W#Tu&z9@$1u@Jj<8L zZ++NVvUFY?th|24uy@6IjcGp>1W9g7n44(5GHyP=A>s;7RyD^_5-Zr6A4QHhMx3ug zAa8IggUa4&IK%^&mFU_IoZ7oyQaziTMR1C?)z7Z0tZEO{8C5diBFiStY!v z@YXVx=ujdTp9%3W3@xdMJR{?D*E`CG20EO0a^w2Xzh>ZN$XaK!Lo~eFj$q^PALn(Y z$7)!sWT;KT{ec$8``bSCCxK0WLyPktvt|C%IBd!YLcWk$!!%+yra=!tmw>+@6a)|y z$jDLLI29)4>f#Y+l4cyu1iAZ8S`^8`)H#zH>mW03o9y{ZLL z;c?e_%A5nU!GayPD;VCS1`g{Y5$Q41Dvg_M3t>6q)VE*s4J>62>Ud4nDrD_2ZItMV z7|cnCgc1u{!~pg;G%&dfF8n&}d2*w+T%pWC&np7bC}%MI6PEMjMjf$(Q`sORWK4)V zf-weU(EB{O5li1a9QR@hMDInT&num~ta=v@NNyw_*X?*DYxXo47rne>`lc`}xp8xH z?y}SURU|g6%0KB$s)z# zoo8zv=$027GJ-(y@cxZtPUzIwWKZFgTSy$wb5p&?N+OI%n&yKQfi}kf5}6+Hy!w(K zU;m<`VsUo(7TX#MhPeBwZbp&|QJv?eX3HfBRc#$gaYEljf&2&U!vT5%z~FfH!{{_a z9~hL%7&9vvlUw)cSDn)n9|N_X&CBE9yb(6QQMH5RrXr0HX{5Iuq*|wiuO!DA8L(@< z269s~bZ+%2Q3#2~DH~Wg!K%+Aj%GZiuPh4T>-$yOhxYU`3oMU}2Bd1WePtzv znLx;2w%9N>R8GZT)SSXYwj67J6$YV%$Zm`l8#BtL8mATjA%E+9X=6CK+_J)n3xL>3 z)tvEh`$%B^u+3UtL0HHZ5b{^vJ_nkJ_?AaDV~zG_5Xu`P@Yg)D-*0!smSgnvBr=k(|2E_=Qcrd2r7FWc0W5&~KKyt;T>&!V4%2To zQ9Oin`NKl~?Aa|KHerSuS6gE^iGPwm;{c}~59jnt`TS-4v(Fa(&yUydlxhE*auid>gxU{(6jqvmY@k_HG71(k!ip@WH+FTRZKG@4HU@xS6Cb{2)lVV z!5M^xpy9$z5Ty=KWq^4Iu?z{@9r^}8#eG-VC<#G!bo(`TY9Y+}$*`;K4DVvA4ae$x zAIojR= zqwJ|H5w@sRf$||7hrq!dsD8!IOZ!EWpTWS9BoTTn(`WtkJQ45&Y_zFBoZncK&Re8- zyLxj9fuQ*GY!hAI^4nO1P=2Ujv!$$AW10+SK9G?~Qni>9kuwITY;m|{vR-5#4PMuM z%jyTj`K34M+iWb;nU#(j)C?Dn1Lfn?z;XnX4-K`&PjP!uJ^SwFJI`Z}6R<^Mg0OAQwI)q5(!J5&8G?5j(`AaY z-dVa|Kx?-a7qK92iOOG zkD!&I+>Fp%Lp6u9dzB$Jn7pZo68j+XHV_XwgdZ2%W|=|&%+uP3aBGrJ7Vbb8%g39n zyfT=E83(M%Bif1pVy_2n2H|r1c#`5anLoUsW3u8#jMSqaVqH$8@FzyXb)@N^cgnCNV=x@51W%v?NpPs}O z(R^0dRxF7yCdq-O`a=YY3(`_7yt5#!L(`tSx~(ijHvN-&wS$bHBo`!iD?WXW#q`Y8 z#pOqdXYW)(g41E4wRmlWanZSp)nuSx78ClM=c^o8Nu_uW*NrwtL)N(Sz}z?D$4IQQ zi~c|AzB``EKK}c1>=81fviE3_s9TPik(p$ay=TLU%#4hztYq&!$}XcpsL(Q!5i%>3 z(BM4Za~(vX?(zFQ&-1$fyiX3-^&Owj`|}4TRD$DRJT*)pUutJ$l@=4 zE?qVK;3j?WzT07H`6Y3kgLy^B^ugORO>wz9C(GHg;<@UvBdszkcpm0whE^kv6g?KM zJ9gp8`;m8_{5wlrKeb6+9-U~H=3LwvNyz(t)^+A6+O+ml$2m#aQw3#4ivDj$I`oTh z2Tp4F+mvf$#23u@tA46NLj$5SROgpXYn_axKcLr`C5wcpW7Spi3P)pz8al3s}C+tfBtlfS$ZvWv+ zaf$PF-1mLA?oloKQXIVONvFZDFBI8*p(z~prAU)xASYecBj{N$QGE|{V6|pkR#qTnI$VPSY)$U^+wI8ndD0m)Qg3aFr{AN9m!5p zy|(x<6h~-DAPvd=0SJCYaVrACP^AJYzOpjh>`HZE5lH7xia_wYzgPHrFiQR5+gRh= z;k3QSy){9}YpQM#D^U&vzdN5iOy{4=mIF}%-p1{hKF@%$Grn5~k@H}cp!8{on_#awuxt2ZUuz*j>5`^CA|%@VF+Y&(DDQj2r%F~f zrtB_kxe6}2lLf9^?9=ZnRYhZ^#q_wv(Sl!Mn(PmaysLNi?Zl+7um$hGZ#d)kWeEML zueDQ$%@1Ge>X#wQzSa*PVeA?To|Ug05olj))~y=OtAoeCD6bs^9)*}76GYh0`)1d) z-BwX2f4FaWg^sTUYSu-a1oDsB!BHocHBKLsdh|%Tb7AZ12nB~FR&1X)^?q|7K&>mB ze>&tMZnUDavoSBEv&6mw$SQYHWK#xGc7MIecWMxI!uGa7L(9vTc851Q zVngcU!Sp`Q21RtOOQD|P_F1$GOxq=#-<(S{&;XWCh7WJ}&qXIeJ56Z@K={osW%@eLrT8T>6i=L#yt!m`BK|Kje^xG#fUi3%HS~M1?4ECy`BP&@c}sNFKA5kY0quPT zE|AUrety)LJqMesP%g0F&$(2B9VqSbJpI>0tC>IcF*{!fc181E%f!(K8)1pd)60>l zgQv~ix~}=NN}r{2o%@TEb6_LT=`UygXtiyFGk;d|NGxY{e5llDPh+xX-kt$@+*@bO zaP(eY$(nKDkPefwY*d1?W-jCIS;?9a+I=zHQ99w++vt5y9;&b}M%HK#_YE+U4TBM^_tUOy zgbN17<`)H2*W!L;5I4kt@Z53@OMB1l`4x3PypEQvc%9B}s}brC%}Yzvo4P`n)e$}1 z=~YJml^4!Sl5C^LfqppWP93juUqRhha;wtcvy5DNOf`*sgxF8k{`iZ&+2tf+zs&4z zoAE{)SykO9m_Dg3o+P~d9h_UWI3tM8tLLha<`A+`m9z4eyN=GD}~C98W2G;+%hoD`7&FJz$5=BY540Sf)vb ziULiY`oEo*gg(rPUYU9WTC%gAxHFvXlC9P*$}@B^0+a3XmBT%5O%4HO4X=iKuy4JF zU8y-+IH=Y@UZeo>!of1xYUK<*(4+Y&@ocpWP`Co5Ro6uHM;@UQ&w|HzO&=$K#IqVL zQ}i^%Q?{E8tG*p1o;g|z=pR2qi2D9=XS-4^-~;V$w5CS3h-IZ)19|M+WHuJcox5p} ztiDdi=F^1RS35*R^}%@}hD)D1Be|9+NK_OmON_3~b4bw-yvQ6%3Kei7*~c*h1zS-I z*r!$5OS2P|YxF&8Eu9RE#V@~~9XkV9o7AnRYiR91^poy?#xOu!In#d|n^8}feyGlo z@Lhwc(xO$~<^36CVf8O8K2N#oludmB)dTPN^SgN{%Ql)Ejp^s^y2^~XHG1=(hO)Ha z#IplF*X_n}*Pni%41g2Qz{-(r7j3W@W0tIS<6=Ruz)4${=2|k8>0E|hd+3FI5hT** zRA~1joZFCgTBRpL{@bLj)iPkk?To6hX)Nu92+??Yl>r`W20t@?ipD!4! zy#Wb9Daeel+iDG@N?)max2@F7s=g>_IrVOJ4g92-t5Qi5M~fPkIbpnrGu8W7QtznW z)LmxWW?Hc9`VeQ#L!RA*PQ5!bIcwz2W*osb-Bb=6=xfX#n(p(=J8FY9CS0H2hbCU) zxqeQr(ZC*wIB*Be35&fTU-G%=!f2f@K17fJ6E77x=mw?)%qy@7vS8TLtB@j?sJFYQ z@oA(TxB+)f@w01>31uE}vYG)=4*tG4E??}PJp%^%A7&@ccipUliI*ID^(kI4=+i?^ ztp)#{TMt=hQ+%h^74wAWVovyRo2t_-8iih`l+k<>Yh5n# z;yh}23_Y_0t`9>Q0qaY_l{K&~8H(E|2EGC1M~P$-mZKbUbGQ<7Cp@sdhdXnN%WvaL z=akw0d%J{oANncbhJnEbsKDtI~%JK1_U8t7dv$%R{|AOGb3nLzI@ zK})>`5+DHUnI7x%mg~8}4~4h%h->pm&UpT5LVVV1=|L(Pi-=#ZQdsAD|PzQTj zta!_x-5Tw!oQZk(IDXLrb!gX3LFd>evI;t~Th;Xw>7Dig zV?rE$f55i_< z4i7jGQo)EwBMD0tCm05;4NqfMm{=`2aD!5y2uQiA^pDd6e>v0Et!GTsRc1WVVM9#R z75+<^TtzV=oVPjomiW>j>WUw}4e3u^E8jTk3an>c6U$q~76k8+Ynx*<$ASJA(+K+S zoM9>V{E4Q-MZ43Fgw06v%j{--?G2xZ0#5nT?L`3O;v^Zc&WjYkODApx*HZ-= z3|}vEd+{9cIzf`_4&%;;#upzy*-j|Yc8C%}vt%z^O_%yGSCwOA9~iMe!WGVSl96^o z@kJ$9i!%`xU54wa7PUS=Mc12*@KU_j@rjFjc=j^tCCGKc`7kVn_5fX)F0)Q50bnpx1X^CsF7GfzPNqzLz+dK+8m zyQ9fR7e7Adw|F9R9eHazoR#-A6+tvI{!%!?RGTvOV|UteSQ?^34(oxTl(qxAFmkNc5M=a<2`PL>zt z{|5I)(&9rZ;c`!~|1{;l&UMNHDJ&o?O|U_E^p5@dT&F(_OLN-_R9YXFw#gu=Gn%lm=M%WS0ecBcE1l8xiNG=*`g5gN42%j2Evr-vM5qB(8KVm1{WL)vb0$x2V$ zF0Acv0M!U$_^~6$fGh7GB=aus$d4&`(d&|V18#1h>i;pCUA1uuD!AnSBN3MP+HOoT zuj@XFZbiCqa%u%&;{u$iPT=St2$ZN`|3U;O^A=I>sD5((tuDId_oQp?o+EzM7=zLs;Q?1cO6v!gR1wX^jiAHn zt0sVxdE2zZY;vw5cYH-L5cqtV14(O?WlpYv;y8{kw@T*yX-EFs4yW&d?s6jR*9zlE z^@-Ua_tuj+89^;34sWCNzs{418$?@}`s8<=2QY67m6TM(r3~Z^xJEgutkjbPpIyLtf2kkA&lhPgLdhRH(mg57?}szh{J6q!UaQ>2!onsY z2oY2CRc-WcHU8JMvS7elmvZnwT>PdWgzJ3a=-TkC_511$`+CQ>onHgHrWv-p=@4h` z{*rjzY8?XtqgDjX>-QD4MXA}TD7}gm^y|5jNyZ9aZ!+?XOj`OFoOrF5vJLM}Tu-je zn>rXdh&9yA%uqXOOOOsb|64VR(52+vSGTc2PgpIoB>TC-ohh*viq) z|E{Hz{t1#Hlvk2r(bc#7GS!jD@B_>ds<7KNafUF?wriAgAdQz1MfP}h-=~CdRd6=c z*0?6p;0lRc)qn8~Bwn9bG}{?~uKj-`UjN7YilQkAslc&%F!aXIIAQ?L29s z7j41eX%nB5sW!hb6soKp{Ml5Th)r-b4wJO(xS)VZg_V^zq=9@ma=BzKf>`Y|(gJ); zDy)u^F4$M^Oc52A9;kv}L2cWy zCPw~^xE}tZh&|WYRocRj82Od*@oj@1wry4X^>FH+V&o@oQY)uPt&3Vd$^0x#Xj{kE z*fKPzvMjQK8){5^IkhA8#e>T+^28Ok>io=Czw(RV?(2t@jPJ_TTkg_&Nk!FT%E!rc z>xeV0LfFh!@TO{%<})?q*3RI4NIObzTvlc<`5d;8Kf(n?Q^Jt4@Jl>V=AF?LYU0fr zI>-=uuI@_oWo4BA@%bn1riwDSp}ustKc6l_y!pG4{f%-w94;EbWtBj&O?af#$^<{C)(L|Fpbgm@4aj?-Y(+4p3F@)1pf-6+0XMZ-8uRP&ek@=WQ2 zh3n(X3%O6AcsHZNe5Vbk^>> zn+sl z(-IA{%|uokX6*+3xU7DcwYy3A2)hL6niQ3{DcA#-0NsufO@Y$eQ>i1Cs`d{!du}=5 zG9%lkn|Xu2alMvFDopM$E2_~hu+_7oqH)k8pY1cs9Y;3Cp!AmaCmivx9mMt?$5PlB zAVBnNqBI8k^O%wxMykHb^AnSQ4AYAKlEYdjf?R*;^)3TmtC!v;CgJE}k{IUsOOWpC)Nszk#_0sFr_fBfa{;ZExetBS7yF~xPCHt6=$yVrVM#w-hn3&dO~0?^@aM^nTSoo5y@_*EukV|o zI6ps1-1}*)jWeY0ujy>8IlO2ZVMhDA3wR2h{d?=g+)#6ioXKuqKbw*9z8`-Zgq$Zx zmv$o*&1x6>Bqw}LERJm zW8J;xOCa6Nu6u|^Dlc_Iu0$Bhq|8HklmOwjl@l2Red zMH5T;!tR2ktuoC;36^Yv>w!ba#&XxN+bXTHwx=!bnJeESa?l*`_(nuH5GGDf_2G^Y z|BYsFDtf?$xf&H`Nd*9nXR}tes_zXws zPV_xu{-DpuM8~}BP%6a2d!$ak+2?N8ZF$+Rq<9I_LPv-mSiZ)7EE?8(zQ4e!?^35~ zO+~-k(ABvCA4&}&i7I*#^+Df5AB6RJcT!yxzecGpa(u7Yau)Vh`xAEYAf*|qTGoib zyNnvZaDQR#2fM5f!YA0Z<`!JXFxa{DXhmu))nxe}4pwzNQh?N0|9Ux0-kTq&sdh$7 zjVp@uV&+!ZwB}l0P6So%SM>;CT{dF-X3QTKIwiJ+!;_Jp-1? zfR>gtS_E!sm3v0?oi6ti`z43US>FBvhlj&MI}kL3mSQi0(i_b-78563f^%zW(4!ZY zQH7PLf*+$7Gy?+!&HQHY{3Aj6&qgmMT8$PKXJXdk5V#NvbO+(J(MtpRc~<#fOe!e8 zb8hY~cs-2mS9ig`b#=UUb;K;{A6LiPm)5g*u)QDI!m?ih%@*i`hVf!q#u|ak39yr; z$QD5}Qo9GQ0=9rnd;zUxqcz#Bwx0US#1&Q-(UVsERwaN8ehREhQeb4LvE#k`65n`l zwcEE@&@aKI9h^}LCap_v?WT_1u1Hc&;`;t|O=)M|;efZDYm?G$Nx~Nu0InKJFuGg?#v9YV z+<}OJvo{ohsc_z}>p<3>y<49x7oYY+H#V_(P-kt;RQU!7|lM(MJ#po|f;?g3p$*UOzH$)&_9F%d|XO&3{j0(-~1kaps|` z;A}CHROK5ElquLnJscwCH>w>j>yDeI$^p0a^qOZdAy!O_hTSp>hU05UEx=0!Ed(lG z-+?TPM}Le!%)PXBp~a)G*pX>`Ycp?f!OLzz$Zvfn`7hy_3RcdfKKxZcAF~!4{cFJv zsq8(Ehu8a)#r5jTW?g#RQpVd_pkK36&N?i8$4B1d;D+$J6wtDjTmxKEYL|+=y&iR! z$`#sM&45xE_VhTX;88AHvUsee<8@UCU@-BWp&J30g86HKSNuzG6_{!UAsvT|=6AUxh5`GdD|EE}-QfjxcnfpLt!ANNSCF|ll;De=MxI4`-J@

hB(buMO^y>@vYd!j^Q4-{$*;YBMwF(? z?de4Rj%b$l?9!2m(HQJ=5n-N6QMr@Fj<(2mC6CVpzPoAvN}jy%vCI(*U0|F898Vc& zU)Va>Jg_Q;)yC+cT{6%qG{GI%;4iE*$N_UPgeP~jfz_Hy8|_(|cgD^v_phW_yJ6PLpo7R1-cH3VE{RsoP|T-IPwJnnQqCel>^ zWRLSBBcu@b+ejKUiwrkTTbu@Y+j{#qQSgcsm2N%-8E1;bI6mJNRWGS*8kG@ekD!rO zNNu>jor3zh7UuZTbi~^CGy$P_Q~k(gA$eL}MuV7Zi6I)fo$=Jv=Hr=fqwbDpiFDwH zXUc~YVK{ZNEHoBTNqLPpE-Gu0F+2zd#B=5Syf8K(Tdwp37<1y72*^)?M2z@U->o(ItFAU*hz5d~>@Vx}6CJISQGiLa5eHktzOxoP|um{I5Q-Tg|YZN zm3nvhar9Busx@jPenP_Ht+RwK`ly1DvB8J&$JIz9O=97r>gkL**^RS}fUR$}cwt1r zj@~}Y1^>MqdSSdWNyOdGGq#1P0lIu*pD{lZk&I^RhtLP2$2ecPata&Kf}S%=5@4`8 zGI68ec*2~DaW!6#8lB#D?sp|dGvKJY`lb2ZElLsM_oXj1dbsjCOfeo`f9&;vM#hR2 zpOIRhl}Vk;DNZDw>e?qxD8N^8pHlMDbkg<{`6Uh1H@*}<+)W(0|KZNdmu8xOftye3 z-u+{?{)Wid`@OA}74OU4YirRF@5_Q7G+SR{Gi2;rgX6G)l9EVjm#$LQO#nB4(Wbc6 zI!1+WvZp$(gZmt?ABr(?nbcnEy09I%dWm5r{@7OfcQtUac5J?_Y>nCBuH*>IaR6vF zN9_TCmc@1s#gIbVKjeR|Sm!B}!({&70$LlKx8iB~D;#FB4whFYbxrf~dAe@1jA)&l zf9a`dK_d_BGmrXqhf|^XpBN5vKy3)GUMt<9Pw=+FWS0KeR`;8f_!(|x!~9RN0orf# zSKW$En(q_2R4=qMq&g}3FR6L#r;Yud3F9&wlzSU(E3_>wrrcZER^Yrfa(e$ddxgUc zbaE>d03h?j+e&3~z5-nuzv*(hXDZcNlN0WFUTB!i(*a%XNxyvvwpFH7meJbFlnNq* z$g#IHg4uAIa9Sz%U!Iww%Sw&hGkK0gjZD_KGFM<#vbDmSlbXC~1vM~Q8Ebj_-U_+* z;i~6w^cjPdmm9Pqf`muk8;Ky7U+xOI7nFCa1a+9)yIjk!oS87WcX8I^!_XrS5|34! z;MZFI8u#6vy(BW(u^c$uOn}@QG0b#!&Uh6kc&4ENUT*AbQJ!*V>YzQ1T&#AVw?RX} zYjFY*ovRXXc}L-7^xK!aQr=12ybqI6M&s?}@eIUwcYv3BsntTbAEYQ3saJ0&rg54t5ytW&Rgg8)n7iA`E~Y?%FsO^K!Up#$#70K+Z#;h zZoVYb^>3~DW-#8jilq3XQZStL>7j~J&Sm(^tjK+3S;ss*_HWKCxJ6xiX5BV1qz{+9 zM}UktZtHA(O+}`=XD_ZQ_uD8Y(Ev~in3|fz=|4ECwz7z<&?zPNW zM>9I&4w+^pzoM327VZfNw}_{k`yz9Tt5H!2;<67c(WO8xuYHp3=eJPgT=hD;&tI0c zO=2DCivnanDfx#={BWzVs*}L0qH5B1^26=vHNw43mNnjq7T`q4Ie9jj@))qvre8GF zuiWAEt|WcH4Hnz4EbEKiEGiA&=O2H3j8`H5cWl21E-VZ8j@)+WGKK|6Sp{=w0n%Jg z!qZOD*Y+2L9DA#qgXayLrUZL4``kVFtzm8Nz2RNy&j$SSnw^JEAxNv@-INoDBcja; zzi5Wq?Ro0}n0Xm{Q?u66UAF@P(>CnWKQ8}Ys8Q`5^%~gxL=U)BhM*Aazr3lghZ{DB za7t$GvQSHX7{e`>`nvMw$m39kxnS{(Zth& z=TEnYF`w#-rxP%2O*(Q}ZezG~ckWHEYbY7*lIxeD z&Y?qg9!qXtQMhCMo?kwn(sv~I7_*+N_{W$3FB@sO{a=6i_w9&9o^sSw2BCc$VLc)y z(OO4$WMQaLXh`yU-8(q6j|Uhpv)H$Z`%^@61uhAW1qE7A^H_*qP--#E!0AqF$BA}y zVdg~Kp&m_54B63@k{+Eq5lWE%DkifF3uQo&zteDHqCmiQkVyPQyag|qHoF>-?^wzW zlV+mJ8w+b8dSskyfY3J&!Xn`CMP`)pwC^Ugn0!~!e()Q4fpnnGAg_BIF;KvAyvP=R zSr|O_f^9@NyEPqRoQkAHiAacy-#lhFs*{Lyhl*Kcyd! zVTv!wO@VCds8&ubSXOOj0UC#`$EpAh{ zjrjtNnto$WQmXknb{tz!Yqe>84w}~QrlaknsmH!q>AQXcU@AVZLG5DQ_>&$TcUU6> zI8u_I-9D4qPK6&(5nb3eHgI_a3xa&83Zp%}ao(R&aR(NCo?5#!xKhu>bE&k`$e#9n zV?ZClCM{7e+aN7L5NytRjvzQfz<%;D^8L<3;mHLoz2bkdjEC)1lDYUw z^p1_H3XYoG0myGkZrsE~(Zz%;s>)X`B9s_+`fXgn#Zp7dgE!$!X`qiF8AnTHwL1(k zn7;^CwxwP&+W#G^s;z_aYX11Dff^dF;E zf20J3y^%3p)Y?Lu617vfcR;kJv*J|{3{K!56hTpup}`52TSF&9SHKCzy06f;ckf5C zfZGV#yN*lWbi#(V%N-lT`p(wDAw6(Pe_0DNMo|$PkZSUDb~(^(CHX zhNqBpAn>kBL+<_hau8i;cXJ({8#4+%NXmBi2v^Km9-2E99i zZ|qz)G7US7NA!xi;q!Ftn0uGBBXdp$o(eE!=Q_#TQN&8Af&0k8O8wTcrxNV0(Kgx@ zRy8gB#1*`~v5o?{zOje0*8;WDuM~bagXT#}T@j9=?Z9Ereb}yX6*ySCyGS*W2nm<{Ik0+#^4-gmwXltMLc5!vUv0gE|s& z1I2v7<=Vjjihl9NFYxV)6z^bW2n`&>(ghH>Wdl5J!agX7W|5Ui_E2Lst4iUe2ZJGr zQ3wDW2sx4ImtArWlG339c-)SI0nb9OD~gjtDyBIZQe+cS>~?jRE|N#+}y#9wp?EL01!i>{Y#hc0450fjdo1hYw3rQ zdd~}%-))G03Q+&=-2oeIh`oO}I2|!*^Qa?PCAI)_SWfJ^RdZM@oE39e`0X%36c96b zJC^XVHr`DG)B8=|BX;5EcQ>^i)3*T88G(60uGGQf!Ei2RaQ!Kx*J0RzT|+!2fCh zw(2Cfxx31*bB;e+M!|wuVE#^x-}JcZlkO>EY{asqFHCAmf%3pT0TJkew??J^i}Z$T zhIUJd0D8PkN7-EO4Y&mHO(t0zQC_6at^ ze92iUE@e*xLMO&_7<~K|`1m%61bmzU{c+)TM)>1Y^_D4;zI6=pm&VYy82RcSg$41I zLfOBp(Jfvnc-LF31vKA#!?ge(DFn~~h-I0Ju>}tf!^Jq}Ge_ztD11|2&YKfIldAGO z@=*-qD%*6k$c?{689Eby`T%n=8t?pM&ahv#{vYw+ezXrD*9HT0{pimDI8VCk00>69 zA7t}~N6Lm=j6dwp`-XdwhdL@(pho!B{PgPdr#e@+@z$@75b*g*A+(?FmtQH28AN@q zTT%4Rr`CJm8{GU^9m7rTax|IDvM{-F)L zVU)D3Kr{i*dusJy;EoVhi}&3HQ1oOPqXn!SW$j_rncWAzYC*%t>59LB-i6H{Hy%<_ z3fV5Q272GQe`gu(%H;|UH81cqjzaq2X}p8vw(Ss}#%!~nr%dehyT+6a9tN-a1mGVc zT@XgHx5Vt*S!(9apd(NoMr`G70-nig_~G)Dsb@My zGSOQ3-Wiur{a!DJZMG*T=H8r6Dj+~G$FfbzoYL4vQ`qvU@Hsy&K28Y{Q=u9^@jS~( ziG59xSYG^V2N7`-{pk|#%a4vbm-pvKaguWI_!^ksFE^<5%e^VoQhSn`O_1S|Va~O+ zlbB>k4q||0zyr7eFNZMwNbhxalw8vroP=^=b4u=|*}#s{hwo6|&S^V+d9Ooz8+Yxy z#s-CzAIN-HMVYqOTa@@~Q0%~{EH^g$c0QtTb%d8VvZF^ca3DKojjqGHAg7#PCYSJ9 zHG7`)z%!o&`WA;uUpvXl9X(Ip%E~Yw@msx~zzd^*bfE%B8vMR@e_g)hWPL$fE#FP; zGyfUGlzL^_-uvj3b#JX_NeI#L9o9wn_8ws#k+b|2V#oN|hJ16ffAB1mcP-rsy$r=6 z1MpYXLkj3+h`AhoUWNiJg2K~D5~1{~j(^nWcR}atTO#)vNnDZ(%Y1x8c;_qo>wrVx zbHr)s=ViEBMW8q3`ei7+B+q++A0q|Dxb*&@U{2bIv?mSJ`^CJv5WA4Wn`KO@K-GTs z+({*@2OWX0Vv}jSZI39FH|0*7M+mLnN8nW<0b}MVbQ1hgs105f;FSs&_lpNntq}Hz z4q5~VB2S3RVISDWM7Zu%AyE9Y{%B&vJ_q{mxTV=o)5zarkvE+fgItxvrtg|rCiUq=rleOdSnGOS+IB0E zKWehBgCq}eQ(DYW!O>Mb1u&)~R-<>W zyWab(RD0)Q0sd&>ym?!v#Qfw?(J2p&+6UuAsHYWeN#EVQP@nx(JP|aSofdd3FI&Wk zIRM6lwqsMx+ot};2WHG1th$%tL~Hq=m7j5mI#p_0^uj6o6JA-M5n~aQKQ7DlAOv}E zf@bJATSiA~2vR~2xKM2-8NzV5HUx232z%0sOyoiK=n1ZVA{Qu3*0vK;P!XgDUhC{n zua#NCmGmdNu(S@wosvyXjpM|c*{#SxpX?Ph5A%R0i5x^7KDJ91eJrGz?lv*_F zG24kGyn0IY-$F{4cJPd%`7S@rZV6F$|DeBq)DZAm;FBljLBM2pBqRkHLj2%C#J~^Y zY<-Ovis;wIOujU$Wa!>y2HXhw9XHeEuGKMQ?y8?j2V{3vd2qs;Ho6P#j%aEAlwOxe z+>Di=X_qavM`kzCL6;!;XIb=*kZT;O)^FM^oqUDpnV6Q#Nw62i;k{_I`CjBIVO%MA zhot!brKKqDqCxM(0m{xImiJ!hkYAO8)ybrS8=)~S;8Wfvd^(60F02JbFd1n>55qc_ z4lmdl`uJB=l1Cn?XEdt`Kd7X8k#|=c@qzcQJG$+JOkV^)0imOE)~Aa8Kl{3*(o z7&f?W>MXTJ-T<7X{xf-lRTwMFcso?8|oM zN{ZZS9kNNQfeqRjK2j`ZND`t4&s+s!$KA1+nGc6j&KNk%%g0$J5X{|iX@R|LWE7YTJi(N6Iim_l1|^~Fw4WqCr_p>*7|rX4bKKw|8v);1`V}x>sJxgCnXYZ zXg4dRCNm(SGnrFOYkVUmuARwX!wQp9sL}JiAZE>O5j2?B z*o~K1>U-vuYQIl<9esF1&n_XVPH&>yBl3&8{;==N+sS?+ZKlCRNc)%;;Fj-5wj%=g z5~g7V?+Jk=01-i;_aGpHutCGR59{t_tR?1Mt0)S1%s5zFK&FUpYB4=91T8yWOfzx& z;8Dv+jqNp9^H#91ctK#)Ht_M?Ft$Rz^6};94|{X6!8-rdRRmXuT+lbj6@HJK^reG$ z*I2)a^byPb3UvvvHO6haK~E%UC$5gQ=4KCt<%zp$|5*OM!LqsfZk&y*zL@Wt4U#w0bm z6*o<-}D;{+lu!a6H!||WZ zU^fO)R&EpOHMfawRm~iuz&$d$HC;M7#Dom%Hz6jM>xfM6tWvDC_9Mh0Hq0HM5HLrQ zdI`h5r;9i&EC9oG=V#4=21LC?eL=}7$VH*H--xA`LcroVaLT#KN3V~(j-&lu>!m#4 zf?f&#UdGaeCtH(vtPNlmPWsoqD&8?O9V!QLil?fqOFt76vPiNak8Y|alL>H}R9z+( zi`5@(e$#Z>?zO1CQ)63m+PBZA!qf}8uvOK}_SAec{D3XwvPSx&=bonSTidlxR=D-O z`-gDT5AOXOS`G5|xS%U^!QV=M;3=lL_yB)Pb{fgri-Z)552A#zSuXTNB3nFAueW*^ zqvePMPy3`iK->6uOo6GbxwGZ4$7=7zvHxUxJ#dwF4 zG6W|V8{BmyMJ=+f6~m&BA5t)lfe4r(kLBZsfRcXpSbO5VwNgoq*;SAUT#ehX_`$y- z0{@C0;>7u>guwwUDct>rm}_rYM9T>gVO`qlTo{!6_f;kj4pUj~$)L2twO~NUK+#RK zcjbzp;E#aztwpr|f*dQj=3Lmi%1oBrv0JlUi-={_2zKk648H09$1kj3e}}a=?bZwS zKm6r>!iv|9d^UX!TmN!D{lv9@)z&|e4s0MiFffA%z;-0~&RLu+3M~;)@DU6!-Pa?* z;=>7(POaBKOiBARogG9%yLQ?J%c`VFg|aZp*soTSo0Jq=fAdej@*h2fzx5OU=pk(V z6aUsbhkw)-f7KRm5U!LVNC+!!i$i96N&!~gyEFN#SLz0p@^V}CcU#$acQwqOfJ5dy z>&A#9#xGp^wiI~|#o(CsAunqDOci#s6Po*BJ$HuPS z=5>w<>KpqmXUpDVgPtCn@0C+}wfmQBm%e=VT57<(%jKnwCxPlr?2huDntv50 zCTi+=11kHz_)6H#?X4Qo;m!(=s^gH}$M+8zO)_wj`#rBS@2}^_3S(jPj*dFe&c6$~ z8|d@2>;b)x$rqM(F&&)ndJcw0He7$h62~@M)GS_)=w8ArEE?_XhfdoF936Qjwp3iX z%evz&Fckea;2dl|hcU@Q`}ugTTEuT2#k#5JyOHPjEQ!{aH*O9cTqPyI%ZD7I!M?V| z@+sL+z=81Cw&1@G+ufkiVl0>6a2R~bkFRb;pZg!(QC_IUZzfZnmacqSsN18&j*}hO z#yxqvcRGIPC_?o*7Th>^uBY*GQES2Jj0+$mMj`3w3ynOD^kS>FR=3;p9|r1zP-M#P zcP@S?d!-7P?rz7U%3p~lCEY%{_-*dfP=Ar02k%ReiJHtmSBX|bx|C9h8x#yPDUctn zRJlw=s-A+RJX zSXQb93*vFJSuznlFqGlxm?h(u1iUf}A;Sko;&d80tbV7yW|IdiI|3i4WAssM;ymZR zyuEI&Mw1~)xKP@RoP(|de`OY$5eZ`^!4UC7E`p}qmkwx+Ci@VTXG*cz(p|gmD>T8S z>vUL9Ueb+4E+;z}MU&G)YF`t@xe~hdtTU$Z>8IH-K0<6(Nl{ zcFDgG#1U0@-9aiNvR9;`6r{rNAb_4Y~aBXAjWNG_ko-6^0y=(d72WdAozT@u+sd+s90- z#+J>(qt@Gl>5jd)b?iRw`}q5ZX>IJq3%UkBLJH4Mzj?ODKjWs)iBpQ7Uy`u9&33Te zif_MyC`;>g=nhEO-Q9WhNlUj)yr^T3#jW?{ug~e>A9_{rdQqrH4uyLBxnH=4JqCEJ9V_|k#xXhx z;;BgzCGH~=rEn&yWa-5*$&?%4rt0zcexH6oi_S#-lN2kvr7vSyMN41bRe%($>4$qk zidCl_YH?w-XeGspBpJe&tw+%RtrROCuHz|0r<(53ET>qR$=;`bHSH(-IEB=y2~M#> zlBANmFQ-_^9#5r+X?nnMcqTw4IF%|(wt+``CQ$QnDosUG!ycEJAbpaw9S>z255&y` zn;%c3?`&!ms-C%eHaKn9sO-bTuVzA=AEz(1zfwWyw{EERIF)NXvap%di*t)(_xYnc;8MfKZE+==R~yO=d63^o^rMb4v^T^^=G@Vgfd-Vbt?K%ynY#Qc^K8 zz@jOtZFrk`vf)QJrvY!3<&F;qdq07h%}KZhHGpA7^ee+&1dc|liNffG zLhG^n#g!7+%JA^=a}+&KReS)QjM?ii)ZzJG_U@i@Er@@HI~DccdWFR+z)){Ks?j0 zVCFw8(f*&phnP0$1Fz0~VEvxqVX&@w=7RA!B0ACvUW>)Jn!KH7xvzR{qIeC450F4887epx;$;kCF?p8>ZEGti#ZwTN1~ zNU;DxfeZ#^4uHOG*8)tKTf{PFZD&9O9|*2kmDC15S^*8J?65Q$h*Zoy-MN?*y2c_Y zL9*ru+m1yB&4U&YBKWwv_13XX*048TiigsO(@@EU4m5z;e9 z^q<#Z89)BP!NQfB=&Y->5whtXjtOq7S(QKI`jZyR`@LxJuw$28kw5$A-!VC08X70P zJf_fqNn0@HD7y zJqRcf63TFy zusk18xLewO!#Lgt`4Ohu@het*z+z$#v(dPp20V0tG{Xp|&=%{8+C)qwKSIu8 z=^l9E@fR0#3Jb?P!cZAWk$;5j5Jq)|pp-((LwnOyzb?ySddf*n-Y36?C_ER$+-c4hRZl`rdO^Mo<548IN&m!A4uh4(|8bP zoNiw!7g%0;3T>6Lpc{y?E@^gQV3G0*I)KLUOG-@JLX62v<^2Cb09j|k;<2!6EaKg9 za%yTj-pcJ0Qh)AgL?8rnlgv%uOgNVJ|%o!Cm}`*WpmBeYe@vGAv@Vt-KtuqB{P zgyr7bXd3aRTc`LY-&@Q97G9S2sh5qvQ;zRN)OU|%#P0cO;BMhyZjlMrJty~Q_s39v zMxykDY>+|0#$9fWd=r#c+VSd)KVR9$oPs-lcgYy#~X#=Y;tOD(-z-FFI{@CqywLc+Qh@LXFTtU+l z=|6no@)}>iYSG9kpwuy0y;FL-%Eq4+$ak(Rsw3rJ&GI--6<%C+zKzLu?`0h-??pcJ z$CSlq)LbjNtfVb7HRG}EwK04ot}}9MpZ5m%JTVkYgZW6^H*wwjZa|)kl z=R3=dWVTw|xXkR#S3_pG<0Fiw`EvPB^`!I*xCfGRM{@Hny?SaHl!V6EdN+7We2pvc}0Os?`}9~aZOrFlXnyNuMmClS*-iR(c?qgo#VHV5TUl(7Qt+B9;GQk= z_I=n4<)RTcu4wzFp2Lw=&bKbA^Nc2hiVQd-Yx6NT2!-;7LyP zQa%+Ue0->W?;ODkj`&M+Uvx#WA(gBoADW3iHA1%i*(t$7mamNn*{ZYCA~mYx`0aUe zvlE<6EkIsDYl9j^ag?Q5c6O!-PKHZ6>H5b3c++4 z3vmE*L4k+)-#|ovkFvhA49@upv0+DZFQv!P+{?YP8aQXft>4N|A<O~9ne`N->C0lHI$XtXWx&g_;ilvJ!yuMg zNBnl?nYdYtfu?JFdwZ+VxJ_tBqV19D&yyn8KRJeg3+np4#cq_P;=a$N_@o^qs9i^rnt#*0=H*7w_VvgLSW=3pFEZp_~B~i zP*{Hrr#J->6#F2YmtuU_MIm#6!Q%6mkHb;zbRrPl4cYzjybumDOjk2{yodk8cUI|3 z<+99PqDIAPe%I}n=5#N`*o6D&FOdt%CwLCZ$WxV>A4meiK@Dc$*Zmx@9JO7~AFK}*5hn^J<<7bg4ndaIK)0?K@0ZvpCEL%eInREw)S_7R-p zVfz~N=K5->fp*y_^&+cSB8d5W(qKz@+t&)+A2YB{zC7Z&cMMGB_TKRq-fP%^vzU{p z_^ouTC*5kYZ?UV>vz#dXPRIATB!j-DYgsn@CP8AIRZ$8_x*Fv*t^rs*w@vKo&jFK3 zBa}mdR7)NIToZ{b6Ns+KDMHDSC;EWOXQF?yKUDB$1UHHcs;9wa-$&{}z|nQ$v>E{| z5+QrsKvR@R!<<>M@NNb~F2`2VAW9j09$W>rvkDZ1$*~V`=1QOSO4eOEH5e?&BPB1c z262faxOu`LmxF-lB0~`wErs(rC)?K=r$%`An#uv=pi9R%n58KwoOb{NAr@l=3$^sv z4F0zFWtuVOM}g&uu{DeDmGshQEio1yBEw=&z8D2jQGEZzp5Tagcqmevq`d_?&2}z3 zIXK#!*mth$fZ35x2QA01oG3Scgxp3tFr1P6f%bV4wl$G?c6O~(X8QTe2_A2IcXHr~ z_a;GZvS8r4-(;cXT3oOg&|^Me9fB7L&@BBEM(m#~l2wx9O1-d_vQCM{RsG)t9N)sh!%bOS9h=6!HCkoW7 z940u7*}_lrrgy2a7Ctyioq%&=$Mx}OJetXOCv2s=S|Zhse|uM^ByFZ}Fx1Sr?mJJPNe;nBvdHd@evAX9H-X+zw-4+Fe13iI~ zFelWn2?&R+**7Ux52~SU8GlQGr+@Ym!byvj@71zG(y?L7izNJjuIADT{vA2VtOW=P z>8Gb|DRXBAE!~W9;j(&G;NYiQbGWqLqsXYU)NCp#vNOYB=$$CiyXMxtbFW-#*qzSD zmEzMMTl$N`Rwu)YM7I6Ak2KO{@|44T+&^jX_Ga-V zNJ-4Fsj-##B3s7~MK~|A??+N}Ee<7naW4+)fYoyV;w}&K?l;G#B1kz_xyU*oRt^c* zpWo%Ksb+^g64Q?y%30WcuDnzLd4$5+d#CvR7W3$<>2hA${zv1C+svEFZk-P2IOn{} zy&%2GSXPa}X*iPaqAXkVZj0s>LyX8uQpA~N_B8Hs8{Yn?YJz+j~fa@=ff$j58S z>(>RWV(-LLUKl4_47_6^&W>;+oE^Oh1}nQ2*z1AwhH{9S8`4jF zv$vdNRBMgE%1eCmQSY{g+Hs@ICp~O*Icn}@RxfiE^SmDV&+F9U{_-wi0yYLkm;hojF6w!aM(UKuS@}#`RQHHh`1k`>_`zUAE@v}lBE*R z`Ekt2M7ck-VaDZFZ5Y$DDknJIDhg^ltrg^==RI%cbrRxAK|f*y?FeR zp|deqfbj)in7z@{Z01nigt%mj=f-8{7frqhm^O!Auyb5!yJgmxqDHu7=>ApC zV@j8*K8+O9%1nK6$+LS^%8T#xMBBmY?dv*L6xmeGorZCFl+8?UPx*8Y{Zld=Z&mjP zdWrb5#m9CYZN5(%B_764j)niq3r|Ky2La`G_SxNLzcS!Mp&|Rmm&WwU8{dZiL)u$7 zMAfx@+d~X8Lk-GLzop{(r6zl96P4wNx z(hME%xYI|mc*;9;5)Yzp&_y?WM;*37Otpp*ZxE+>aT*V;%@bL45y+=vGTY1&R@MkY zzw1h?ViNmv^4Bc1^xOad`Xv*T6LeXa471rI%ZxH$UMR%m6k$(@6&fjhk{3=_ZWSZD z=&4JB+4@)|uBd0g(j_s@nkDj<13gj?%OiZR)F+-QuPh%$dMndLzro}!E^+O~S`f+t z+O3iY>{~}6rWPymx^6Gh5nOJK63|3wo3HtckLcfP5@U)lbnKJp zDh=$DO(MB0B}FPX$gbz(4*-~ppON-pOU1N70xhcNFY!EYxeVXT8FLM?Vzk`0YXHRbMB? zWyjqm>xoD_rdh4c6**tfu!NA;9LoUP*ZYCg9XFsP#^7u?;O8|QL8xqN!$Iu*c_m~Y>BFA)uA zs-_C|Ok5oP93;UtLA1NIpWcrveA3ReS8@aIL8vE#)cpr~ao6Xx z`f2+$XnKd2Bl^v*kD+Q(3AdFN8m1aRfZ!`xpXavadK1N+Twh%eF<}<6F?JbuduAUH zGsy#dpq87;Nt`JV{rc{=lW~hgEgkKjms9KSI5d8Jq(B7PnRX;xJvQ=r=X}@5@{Y!B z?_)DT`FXQQjS9`B*PbNo?*dpuFsybeb9x@-SO4dHeTji@Yeb-t?Y~n$n(Gug~o3P)LOL+hxR0903F7_XXdi=AJ ze+(u3wRirvUxK=3Y^d*GI=}zx4*AKIUjLIT&^vFZQkBqq2(T0tf7w*PwI7f+_Y3<> zu5uNABEw_Wm*qG~3TO&~l{#rJuwxo`lFFykK>#Lgy;&Rd0R8t13}<8(s9+2Fbe00Y zJo?Mf)+Sp?WTG-i9(p4gDs8;j8^*`l1aAE@lP9`#$=88UBH}&Kjk9_4!9`i`x=@1- z`pxKGPW6rDpw_!5a7_$Bd4R*$RYP73JLZKA^|D8uKGr+q2I}RVJ9GA8S{!d&_B|FG z$w+bUbbar6zdcQE*Jar0d-`lOCHCg8FvuT2PhkLjv?u?$WBm4{q{FNJ9*g*2#%45j zYV!ZfVs*Y6{rd!p3WEfkO#J6~{PuY1KclSE3_rEWf3u^1#Aa~aIR9Jz7^QdpU*wM! zQRqTcJLPwFG}WJf_))r|pX2eX95Ifc*`6i+zObTEnY_n zVIi|K`;czj4Ttm&GzmH-j#Thl`yrHJmDaFyjwje z3MM?gWF6){Dmux&|K7HO)apPA_^9#C!!^h9lgg45#X#?!IbWRs8B#wC!9P;?e-HpI z{;A};a3j$C{Yl55p0w1@t5F-^#?1ehJ|FS(|K)tvKHNz2|L~;kC43!z_VI7)wfybT zGTFdWYH^zE3H_0=K4Y5w^Ira!pa``v?_J&d<23(sOezNTUkwA0k6JkVs9B9O)WU)3 z{mS8(ywv=e^H=Q_3ncv&yzTS<6&W`h@?}vEJ!buDMDFJi4*-|~bpKj`xJQ4jK(C{m z2Z0!L_)gfW4AKE)%rZ<~&YM!vP|k=xp{aslB$ImfErd(aNHRC&j}^GBq={}z*(VIM z6wkg7M1Px>P&%0-7t2B0onWn2qL`uZOhka=O@*R8s$by_Yp*tLM1j!AOcsJH@rt=x zG>w^$+8eFs|J|?Pewim9B=I;(n|(7M5qMlB8n^2fO$7@ zsoYLKAIzV-paFc~)WI-q&g(>OC|n$RtNCFI=SpyKr46OwN)x2^;K&GX0Z0Kk(1#0YPNsw?Xds!?_C_$PSxWVjTCTAvBCG>@@goiSqcZq76 z^6!!~El^Z!U60{+iMj#vH(d*(BxKSGqIkg67Rlbr0Gn#wk<7v<$$?CdV(abL$~EEt z95tu&vCyhQs)aJ?$<;|SJ(0@`AxkqXM-*kqL;RA!lCW3`oN+6sEgCF<9MQ?nk`MVEr}^EIUdxNZ-!CZeNBYx z#D+#t>C}V68g=vn_d#WCA0dW5PanQsCeHx6ddH_eDo>i{Y;=)hJj0ABQJ;r7_;8(B z3Z*!*l`8c!sye@J|5Q_seR*~N#xuvRnb|EcXIy+>T_3h3@koE3D2+gux}}=H&^7O~ zqgfr-&d+nYo?L?ShGEJl^A;rrCyQ3~&jjDVo|7}^3#J@!b>GFIz1;#kMPW=<{chlU zHA^|ZQy-&fe%m+=l%Cp8TJVmB$$P-HKq9rtbm z4ykO!l()ZcGh4$)gLan2>6m*T8VPQneeAkH(9wQ&pTku7)T^jr?%;Sj_Q6D?M-qJ|35|s|!ImQUeGKq}s%x?0+r3csF;jG6_dzBL-soXrbHRkPoXFyDBiaf6*nQzTYo^U$FR{H( z1!Uj97?Bit)^n^V)5Pm<2r3Uxs5kK$kQ5dxPY4M@BC3mq~)Wd@_`d#56q7QkeqO-u@|??t3XM^*K+3JIpa&$E@J%F`L+;Jb?*o zM2bm#do9^l-)U|GiOOk?p?A!vQAfbBAoPiK8i)jF_fg) zqV|NYVEKbo9zs>Av0OVVQGCvMm!Xy6f$YO0!zC9gn>pdR*(rf2U*APF9df$A< zlauBSyblgx2YTydDJ|X7)y@g+b&Z0-^!EMRFFe|&6V;kaImGtenR& zR9yMAlBnDgNr)wE!^>pgA>l5C_(=Ve&-%gsl00TAtH)z(b!7bgG z_iF?3#?~d)puv&Q~C!dP*um)d`naxH3cPdSImb@oC zJ@~TU9GZxHYkdX3s?Ysqw=FvD%|JSBay`*jsE16r|-M72S z-xj9hllc?)tRSk7L}p4J3M8mU?`zgyys0Lu6VQ3KDSzi{HJ>$*bIs0@mil6@%fhu5 zXM6_{)jBa4iYJV^a2BWA;zV}r5Nv~ z`pd%*IQ1N#GmzacPE@->WSYzHtnh{*M3wy6MES9B+s!O9ExzxQQvN+Zvvb2+)rE4rXc6C!>(ERz*?eK)T4!STCCwKH_Zu7O7oP+SU23GrVOh5ohY_-tpAanAJ@zX zVgj8Bh>@73&0@{9pjlb57u-PAZm+AOXES_0dxNf9CjqLH@FPAf7^|6-pd0tRSssg% zQVB%9*-bCZT_n~0{;pe1lZ~OQjG!vP?OE_7k3G6GK@$M;>lzr$4R$)lkyl~YU4w$V z1Jt|-NV=an6fr^@{5H8m(0Tmi)(G&iY0{7EY{SIuv@L8;^(nOA^G#-cvSB=0u5UHX z!Ksj0DM)0W6%a-8;s$DY;Xti|Pmq9gV;s;mH<=z1vpE-#zD5wP?UQu_kOB2}g!#Zw zkKQRHBo)9vi?0U&Sekf+kUimj?eKUz?Dni%qJ@**wl!|pQ&o@15znVmcAmywIuX9Z*!`!yl`PHSmFsJ0an z(`A#=Gd0GmB?e1~`0k+QoD|myfRJ-f(B5ISpxbH&8clTUI6>0&F_M zfpvrN+2YPyIFg0XEL(#0;Fy=!fDkn+$Yu(rl^2d2oN+F|)88WOwPx7iP>emf%d;U! zfE<{79n!1<#_q-!oCVWO;e%>#R@H)V%1vbF}_Ho{p zsouqNKKeQ+M7_@?A;K!v^zK3`H*Y%s>qIc2!Dnq>5*{6a4 zI=e-HA3#GU>@2fqUx-MRY9W0A4L1?b=t;}$GD$bGkizRB^s|b?a5fDVibc0{oz^kW z*KsQcnfahSsilm3dtFA_i%sFNm({D2?e&#xUq0KdEc2+0d<^9D37cZb8gi-=@Vqrq z^_0A8AqPN}bAvGcdl_VaJr^6y_~qPU+afhs*jo!LFQhC5KRpm`okvWS8oZD~Ba-TW zo<~ZRPa={}13zD})QepwA+fb7K=3YZE@1YXZj+^ zFlG5Iikr`hh%BuYnu!zfM-hO#fpoC1svshy5*%l z<>dL-s0f7Xn#Z<`^dM8PuI|QyCI48AY zbQZ-699s#2k>p4 z49>-lC=~*z!F%yg2*$kC7N!QH(<}CqkH-{U2gBBg-z=7wfh*LhD<1nc zDsgzy?37|S;fNHwY7|$c zz}PC{FW|+mBdV6$N@mNeJak)vs9OY!oovBT4FZo`PYIePgEL@>Y+eocy+Ena;2bZX zJS%aZ3BV3CugV9u5>+g@h7 z7WT}RnTXyMF#A-U<%>1^tu|n!O!Ade!&iW;z0&TzuKzJjxpqf?b7a9+_DU^TEO`|l5Fia&ff?T{r)C_jZS9lg zS*_09QKCiA1O?t2d9Fbjbu-OEzr;rTY;XZ*$d6_ySac|~BPhJ1J?z?!VB;RK;J2JM zg{S9~{n+{e?4hBuGV)|wPc>+|vz59rXht+`yZP1|@#E9o_uH>TAmJIcwu`RG+m%au zFW4$uZY_^+KJDe8X^G*?!u>?nsgvEcO#04SbTTFP<9et*XND23)qJE|&MZ7nYl!|< zFrL-8aEpaz*!bkw_)6u_YRCAR=){Kp#9O6_o#mlck9w8GLhbK4A1liTiRmyYb8~Ku zoZjlbs4OfLRmJnkhg?)J>*mGVm{Tm~9ct3Ve|y=moyQ@q0)9;roliuY&tW4| zMv>v7O<^7ffJToMw2qaQWm$MGEbEe}of}IdmgGfuN5_Z9Hc*awdvx70* ztS`cCh!tYC^_1!9)ArKHh_~}mm-7QR7W}vtS}7I=JWVL=J?U@?gxP9?EavC>hO_Z% z3&j?rb>}L!G;xQX^UHv-YdZ{l3C6(5Xxvy|yZ!RWear#gSCEvZ+@zPI-m|6EX)PfB zv$@pJo|X3Hw@b_Mvu|+f42eAn9*z>Pvw?=dmCre_GKXwV7Aq@Nehfq z!$}BV**?8r1YZ0U^(wdH)t9VSdXbAD6Dh83xJ7wQ10G;>bf}}M24kI|olD*vf;q6* z2&x5Ih#+*iy=#@`7n;`cbw{~6Mk)P9DPl%DqGtH=#J8Kx@Wb24f|yQ-!(YuJ$A)i(+8wtw^gq`~n{BiT!^?^^ft*eLbS&dIB+f31x?^4= zT7s#!w#eBYo^e!h?X-4@T*L9hLC*!I?!dvhK;z~0%IbBxuJyLD_3973X=0BUbs(?3 z8j`$l%vC~!(ssnVfiklo^huda$S$8DVt8d*Pb@tq#<`6%BX7qfQ^kiupXtfuYDT!( zjhIw`)4S*1I0}$;J;MQW@A%ne%WWE~tgH_^l^@c{J|5ow_*(SiiQ&gH{Ew31t2YRz z!6rC42NruAA)J(lqPzf2;gx$G!9gpH%Ay@|ONRyC=1f&4p2|dWSm7m_whbW}(lT$n z?SmXy#sWtNDZM|t%6?{Z{LKF1v-QYl?(5IE*K?zsR2$xdIhTW3M0ciNby>WQaqAgz zo&G*{TQH-tYD74^SZr{t*kJMD>M_^FHfa4L>)@eE$@yUyB{+SjL(UuV8rCkn+R zN@x!6g8Du4&U89lSn)DrR?pCM-$;)SDOHhb5S*pQlIuQ7kz0va8%Ey9IH59uBpx@r z`k#2dxbR-RDF1k2P4I1B_?zRaiyB8?=>1268|1*YbM(b?m)%TYxp)$;J73QsZot_M zv>6Vuu-HcxiH~$&-^`6<`U*mub;-JP>bzXMUcFqtzFfI^<-l^5^XMGE#qqc_r`{R@ z5ho@UuXLK3YZ$IPmG32I@t_UJ6zBTXc)ttq+NK*82*e}%?yj=l9gIUu)^R$y))|V$ zsnD0Ix+xPwdjt9W&8JnEUZJ2&)b7VsG5;&9+^51vWMgQIpf=H=_}rR+Q?J|l)(LAP zIT(Hyhu-|#5Ax`;?uY0imD-VXOKBQx(!D)QAiz_++Pwm;T6tZxBNT2C9iT?HvV>l! zDgMxq5D*vW4ku~^#M{xQ)@o=0h-w$nyGQacn^kEatYA-V4#i&|;?cG+4?oHT6*izN zyTj4|_S%g$tPuAMfbM)A9o*GiT+8a3`CQGrM#*jr_k$hcdn`GFn-5P((NpR9~-{4NFEHyv7s=4Z_upxVTEM~aa7OSrI_ z-}#Ox>H9ba1nDb9VWp?NT@|a5sY2s7GpR|&{JnQfoU^W<-1G4UzCM6gI(ce<@>wk zqbD?Lyj5p3yoj1Eg*9Ha3yIO|!cm_wM=0#uVLdL>VXO3%&+SbnxX<^xFkGk%B@u$_ zu&yKtge=`5{Vw$0byWQ_E|%0^C=GT$pjc(CP1Z9cQOn2|c%o$z#OyKWFLzv8XhiL&SB0Pj8<~#VesbD zm%#Js90rY@6X}MJWQCTY?hW)#VQ$BI76gXc>v)uY^Xp%jLQ~f)iLWd#T;J#@|a@)0yu^7vlw&*>MvT-uWk=NOn{FL)Im#G^1i|9i-n9;aqWu{kx zn^a5}J>+crZ%(CmNP{(;slSo?Yj2*C-v&T$D0xyPeof{gN<|+vS_I()csLcfJ{;%U zdFm>h^Y#0~lH>2m&?-4JJbs);q4)d%0s-N5G|hMQYrYQhfleC7A;L+c#f(~mE&S5&KV_S=jFHmNj( z>((FN4SX0h6vwjM+>IEdZ)O4p_*gt0=CYVAV=5fyHG`oylGGy7y5+#uobs4(B!Ia# zP$mVWO(gfGL=XVK#-(6d?QgK;4vVh!Wx6#FdTiB8Xi-T^Jc``{tMB|I#^H;TCuav% z;|bT_3KbeQk*?K(JUpK?y~oec;!z4=4s=A^u-?GS5|WP1s$twwP2QQp6zKt4%h+G! zBQ^Sn8oz?zC%l_6Sout$rFd}LO$|lZjY`^9%xL$_g7nWqJYpwtvHr`%&{GOI3H&Lf z0}-uEa4%1(&OqErtx^shrM#SGe0)N%nKB20BDoBxv4LR@mehVp6#x8b0WLGgBWs1n zHm@Rv8Gz~<$J{#j!z?&Yz<~N-hR-H-wADkJF`Dwdyw#9kil>|PV@*wW$kc;LgDlvK z*hj3?T+?4&S0V;7pNlG{zlu-$p3LaU_AuCLibeG}oG>r{Az>piZ_O5VGzoA>$oZ3r zJp;wf8nRo@$au}#_busCfGUBX>vOO9tt1HBCIdM5>8bp~a5B|q_j{V~1LrIkjJ$Q$H+vpAh#`mDZ|R)hSolv|DTb+s}tkKR12 zg7A_)hP-qkQiZJ4os}%4rh~<~g)Nw$s%R1zq_>+~p7I-*bC|TTwmWQb zP+EsOK0((bj81NcGgnGY)OS233Vvo4*Q<{OD>`T?Bq7q)BJy*?(V{4Wrq}g5VhOOR zkrY8i*ELCY`5>UD=7Aa5^6rb4smWt~WPFmNOzHgaG_OLAp0(Zp>5_Qb&! zHI=bJOL9#cx4(T=R2_mnfCz-BfzKe#_xT}v!G)xXUHHDQrlIfc=m7#Qhk#`m{dHZd zwA~gGu5D*ht*1S|7$a`)BV#X;{GMXCBDwo3HW5n#CV_incb(=g?@dHv{;ZNDdVn?y z(D1;53!oDDflcXipxdsbVv{s=yc2;M8+2#d;{8kE&*swcQg@zH!Yx!1oYhl${Mj5o z!T{VcxJz>}XYPoVR5RJ-`MzeLjOPZ{8l|yMaZkHR7-zbta22P8@#6{Vl|m$wLsHL> z1c9o1o#INR9rH`6rTB98ccG66x5!}7{)zy|fevvnapQ+u@({^Tiy*A~UC{R@W2diHJY|D#f-~ z0`W!xadfWIMAD!_kl77t>kxMB$V}@Svgt4t@dT!!q)rC$PTn3OsUBjDp4jfD=-u?Y zpC|=D1uZ7Y2A@F!7x|6eprxhqv9z8``2=p$aIse4I3l`sosfqY%)H*fa@@dLNUUNj z9tI$vq9psuUUAE;qRxhsONm(%{pB5!m%9v-J5-YL5uH&g$>#g{*EYQ@w&|Q-*?ZB> z1l>4ECd&vzoQtU>^6nnL%yE%~b+Cvx6ia-6d7ngzJUt4nR-)Wls^U`;bwZ!Tbh2zF z)$P8%`gqPeW2l>ngmP4cG3XAWHqD#2_m#KA?Zr&rz+O$aUM;tN?aGpe)AzzAZ%>_P z3t>tdvcKd$?B_d{=KJ1nLNcIA)gLk>QYpehJ5s145*z1KW^tTd8OUkM)Tb)ZXUAVG zJ|ja0?sNDqLmrqHg&M{`i*ndcD%#+bFK2Ml?GbZsW{e-)_7VF~&c&Z85jKeqpbXbG zm44h;68?!%f{O7mrkn;zVSs2MR7cKVVJOUPDBNxcp)nMpA9t-waz~8~!;L>Dh6EP# zU9Pm3E!K>AH+?XnLzc}nKS^Ua`IsH$n@q{9eu5eCT8NM*KAMM`j~)??SRYOrVb-Gx zPdbtx{G3dz%VNRAVh+C9*u(C)HDJ%*XIrS?6r~`i+Bc&Bk0z0KZ(u`;iaWZL`!J0{ z@`n4lLD|bRJQAR1Hj4a2@pAd$RYVfON(v>xgJP5vo%$7Ubk2a!C84IJ-Aqc|{9`W; z8Ka(tQ*(yIb+CDmz+9imwV z*5w{wWPA(d2niy3X)#`4QT(0_XlwzLNs&4X=J^=-;yTsz#VO;&EO=sEWP*TtFxo1F zw{*kB<W=eQuNA0~=rG&i5t`xZzC+DsMSiwWw{#G^Bhs)ArRRhn}#)2rgyMkn0 z?V?7t)8<~2jJAZZQ8YUgQKz$ry$)l0%mtGE>(gnoO-^;I4LUP2O7IJ4n(;5al~FhlrR87LXv50vZiCma5Unz z!efmf?WwO|fca=*DncNn7I;9DNc1HPe<4^G0y#}Y2U;~%x8NsYT(u?+ZdLhj4nSk8xkFH)QuYok!1#plucIP%cCb)Wfu}5l~sHE zVcJCopdR%F0&zODZ(;06I2cn9=K{z$8mT5k11b&kZ=u|ogv#ksLa~R79xsuYEj79? zHJOVC0jN>mq>z^8GxXGy`HX|Ls`r63MJhUKPUt8NakVGI^ z^>Dd1b+M`9XqQXHoL=8Xu8LHr&*QI!U{^#Kl#M7XiiNwp#bzWTX`mp%5MJ4Hk65UZ z$4+ZObaQPj8e)TrXVzr-#}OaiV~4!a-v3(aOv~{~diCTT??KhfVn6nmx7A@sHKRpF z8}BRE-mPwQ>Ys)PK@_>tFxJpLxXwau9WonyC<1-{8ov6@FnY-7lfW8aLKb1X3Z7ky zl|bS6{v^|&hLkc;Skg%Jx_?X+VlDg|3iYq~OQvC60==|YJKj~h6SwME@A@baLVZiZ0N>_TD?Jkxg*LU~H$De-~&HjO8 zxdf=Dfi0+oRy!}houNY5{}5#4YIxF?qO74)BoBYeYJQB#naF_*QDbss5xwhS(4T0E zA3#GCMPMW1R@3eeGzAK1$p3$hnATgFn!Iyj*9R2WakkzLJvH8ng~?~`u>?_fuvB0LZSeS4_S! zyjMbs4&E=t^SKyJFDx$KFR#QhXA{qEy8fA6hz! z#??%@KPUoGi!JEnc1Jzftf&z7H?C0>&`?$>{w0wX$~aD~ItJ;X@I2({qw>G?d1x_T z;qx%tgIkUx6e$anW;a^LK9BJ~;_Q*+oU8mYahTu7H*EU-Y4xy#WTxvsLfBki|Hlxv zV03)-`;#T7LA>k~7iwR{CHI^6ELNVLK7D^WM}N(AwiZn8aJC-KTK)eogl)Mo%=1x< z1MofW2>%5m>i}zwsARK}@ubx#&YtV>%olsbuk(zCSdsyj{yMN6dg{x`@=Iil!iFyucJjc#QX#eZTw3aT(!TK*_V@Y^Y5)O`KVg4Cq1 zKr5t)vH7LMDzbSU-~7=a*bjpMQy?@Wy4|uuM)mt0i*D<)QHrRk!3_8JfjXpDimBfk{&yN*ZqJ|}1^HchYgs&We58%?O{LT=t4>>rwiXCWJm0@I0Q#$YB;` zC`SQmS;NKfkGHaa0&4FJ%l`_R$=KcA-$iMB{}<-!@`XG8Z9fZAliaqdqK6ypO8bYa$Y`K^0`v!H4#v z2oaf%<5}B}Kd>GjyS|_3(Z*eI;5c<-{#B5;cMpFQSjcFpevOLxJA zF3XOO*u>w`b%mUUIKQW$-KF&l8ZuuabcvgcM=w)63vjpqUQC6?|J=QLm{4M(nIQ)h(hyrOfJR3JZ8(9AI$nNQ%`_vl5If#>m~Nh4Hq=ekz1BgH1$!VjiAqvIDg5~_FlK5Lp6no~|dFuON^WTC56J_I6 zvk9OkE&PvSDb;hXO){ObrUjlP1W{agr0M-W)t!mzglhmg|M6&V=>7B2{$b8?&P$F# z1vC1vjSEqaR$W0U_qlmb{Ou=T4Yqms~%a4NrYO4EhrOf9QUyLi~*Vx2868?hM^bMYIyNN-$1}so9c;kQ`)`5;p zr#gSn47vH8L|fwUZV-meW0I9wKH1h6GR+M|PoW=rJ94N8Mei|=mA&$|R5GN!{rSV% z%?BF9KUV;5A`}nWbOi zR+jwDc+4JQQWcE4=lL)bIw_hbCk?L+vo{(WEzCvCG1*KuY18M!9EhYA;jw}o>@vtE zO-O<5?;-mPloX->@cbXI9mC+izV=^`(0`;%%;nUGWm_}lr*qi?;{_GUep%!REpUEv zB*h)U8W9a;3dIi#ii0_Rk{B*QGZ8=JZd&~Tw0cK3#mmip#wP6Ll@;GM32-*w?s4|` zB7xhFtPy_!L?b2E^(SQ$<2$rl@PtGArUwGX|0rqf_O zRq(2qu7#3*(W#2>zo$&t;33zCq_Wn6-QpY=dU%EH-x*Q@^nq8pEu9x*Tx4aw*Rr5K z^yc9EtTsR`sjZ9i0v2z6B^-Hl|-H_r+4E(1;p3-^0cf(uxC zEv;lI1?6_4`A+1@6jL`WER@}z*=)wC#JG&?RRVe0IZ@kBTUnyB zd9YdhF4I4^A1=ve!;1Ij3xe8(QmYP2#^eCqCes#;+v#jtdHM4Xn+baEWfyU_62>91 z?4c0-jliOACZag!%BuEHRB;^y9^R(Ef7nw{!~3QGT83D*|HCp2WMcf20lN@aD657p zTlXV70pLm>nEwSgW9CEqKgDBlL)6AXe>n!H5{Fgtv}<*7LPdVKKms;cil5oKy@#pd zUkc!cO;#@k`GK(LgtU#<(ZYx^4DD2$p9~NXOlK)ARG0;&(r6j_P%;_@<=}*}2wi;W znL<}3P#M2yu$`=t9$ZmsZ<<$0<=$u-{|7L0D8aYmhFXnF_-z3Or|>P|0WSGUM;2e? zIc#S!?BW{y%2`3Oo}@mZCKbli9=J9anF;l`3BC|5Vf-FuWd8jMK(s?E@dB6I5RQGK zxdy=a)1moidWQ`uMsYcn8w#B;GYn^X*l7GeTuU^)aHMHYP?-LvV~Q=nC9W_;=@_>g z5s$*BzJp0WY=!t}q9WDe4;=QGV`Pbr*Hc74%WlV9XR$MRS)*uV8APGh8YvFxWm#E* zF$fiRh39ooAZl5=$(dA*>_mA^8)0n9k%nx{5+B_)%=5Rei;}4u_R3;{&MC0LD(&n zk8r?(QcUju&|VTIBT$KLWi=Y-jfUX_OO}{8EV+fL`hSN-*=)++q(83tfgj=QaW_Qa zNA&phr0Q{B$CKW(sQP)jmh9 zbd2AjrJ#b^c1Tz8SD51JD~Bz|0A~zUNnA^jy;rlp|@2LzoZ*SOi8-}Tz@GBW&a9G{K713qi50r~q$ zADw)$42w1Vw~PrY{^oJ>S`d>w+WH?$vTH^y6tC`|H)Z@uL)1-Ko5AnK0t3YDb`18D zXxyYJ22b`YHL$l3mJWnfg08R|ad_)E9l=M6+7MY!ELEPVXj;Du(=bGAJh*EEGEFv& z!DdnB3_Z_H#L1I?V%jX!|3r$~qPbX>P)MUV%}cX%(+?vmjWt9{TtiXD>T1VQ+413A zG0fm9ZOxs3;=BljE3+x{jyEjdE6)63j-Z&u*bmN+5n0D9{&7=Q7#`fOs2$Mxb4lK$ zjj+}BRM23PiH=Dv3xBb=lO^9TAzb++K!&8U7JXsr03g+R@w#Eaq@6f~H?+Y{^3?~0 zSrURCtxWM!wFWEe`S?OxnfDQ#j*`yh;l{sT1LINNBr^aC9QvC?7>gPDFIYFKFSC{V z$3E;t|nvWV0h*{2A96Vv80MqRcfl#gVW({OQ(T(7rV*vIq)UQ=XBk8~fAld+*Q!}f(!Kr( z$NTg6#iI-$SRf2OJfjEp7vL@ur=G7rsBZ*cxp<8l2L=`3EPiWj{S3H^mlSGV^gQce ziJ-(-iZ_@4LqLQ715q*LX*XVrIl=MUi@66zPu}}Yr0TX<9$;2HS-qXy{?j!7;~FU1 zv%B5HDgP_&$^LTnw*OD)Iir2m4{_Q*WmW@1IDK2q`@m*=v{MQ z4|IL=$-vMBtd-#MXM@9%U+FdJ1M!^0Ga^FR?{>Qp{MMHdf^!kowWt830_12Tus@Z~ zhG0NSHet7QnY!a|pancmu#gr)CP^pFulU%5KvM|YXdsIuokS~fQaT>Lg$L336DDz6 zFbS(7EdAFta3`A|yvz89rzBA0l^1rRr&XQ?>Chk7z#Hsg#de0FThv9t78hBLG5Fl9 ziUop9I%V2fax_|u&h#Z-?u&PV%)~3f{mfDB|15e;Ex?y*(rVfMQJi^9YYkO!r*?nFkBQfGXI@eKP3}C%HChD0Ma+ zjH2f8+oFhHmy2V*k;$Ki3Lr*Pk)i^Kd?uU$cW-QuA?iyW=G^zjUz0y(oy?bw#(x~) zhU)D-ED$8+n0!2r(#P4nRj7R{UW3&`MzZv^VxiV@u$XJKu}Y}|Yn?1n5%~eu{`l?w zZ}MA;gNK1((O_j75+0S3$eVnjhe90Y{Yi{^*<%WY}BHSxzCF(adXgwPbW@~po zB;_XA?JczcS?9|s^D2f>`na37RU#yo`Vu&01KU1#^JaiKR3CQwEIES>viuy7j|~pi zUbbJG3p_IheA=yuC2F~k0xa@1%9XcD=M@K>t{)JLIiS|i`6cU`|2pn(tpun~5e?Hw z(2w3;ATj>ds}LHOHwr8m=F{upI+qx6;*{|}dVA=_aa@?BY{)3C*;17V!EGT(491&+ zpGSD&Xo+oX(>OU6d4@OzUF;_bD)>;-L=j$808zV*Ts;}vXYd!7#LzxbXgkfSxNJM! z%3*lhPoqPAQ4AezGRL?X+blLym+mqfz0I3gCkb$B;?N11~{ zD&EGOO(H|LjXcl6e80>qE5^nq*)4lNrLrPGsfcw)4yfMdW0|$aRIvOJ{OSuLf0ytff1_SBy5oWW!rAT}dkmJ1|CK%)O~S z8?Fzq1meY}UXE!4uF|LeA}V`tBJLx%Et)@E9F*DOd^>FLEf*RrFdr4z=f8Y;58*fG z2RZP)q)YwO>$|T~&bo)=(F#1TBxTh|`o#4a9nG#&BKYA1^Cyg_hV$=0X|KtbQ4~#2 zqks?0UHPxnwQ?k;!fGrQc>}J~)*DRq&yOq>i6`3Jk@pC<48HRX73WWrA6^c5ofX_P zsU1XK9Lms_7a(f{fzMChFg*qxrYb$$f*B@36f#6iK5L#;oe5MKQJUpd`bc--=>{;(q1`4AHDy{rqLg%Ww~_n7^vl>`RY1qNbv3fzRJlGY#na{E*u}oh6aVfu9r_9RGze<0Dw@y@}u5SP06Au)MhrQO#N{-bU(f|-$wPhC@!W&_Nk zuyR=3C-sN{A}uWOX56gAJDk%EJdURg`jb-Zx0PNibKh$)^}qD-aGKS(9dezMK+oly zH*;ijUr>~RpDa>MRjP~_)ju z^gy6;q0VwN-=LzY9Ce5AZ;C)Q_vJk>hq09c<7f2S;Xjz&6wI7~ValZMeCumB3$d{p z=)>ojGE!psY+2-N>UVNCv7(5CsCG-I(C_&h8mQGsa)J5qqI%n!ejty3{%!lw+@Bj@ z`m1{WB|w-CDee68RCiNs3HD_R)!bjbB>&Oe|Epj5@kEPz>k;6B`Q55~Gp1asFLrcq zPJozv&sxx;yI`(LBW^a@mLmYdhpgRK2C4`KS zR>t0po_rm?8KY5V^$PHSfwb_BXjjn_)Q}{?lew%U| zz>D=5nkYCyqG4{-be_oNFz{F=6PP5=lm#j~LBdYFyeK3zH`sS`W9a2}^VEwFyZQb0 zCMvnXG3-5n1YVoHqM$u*vLAN{_D2y!ZaaWbKO2+)q3iLZh%#MW4%H`r{B5&2sCpnC zf%@C_*R?j2N`ynAhK`@mpV+&Uvu=_|cRN0gxuIO54j+P+sROjhKr_aZ6&DX`lg6QFm#7>H=@!G%+TFPcQ;6bz|ajtH`0xC8#G8L-5?++pr|w` zGVh3o2fSvF8y!Yt_@M)h) zGLX04lhXI_w+S?5>S!(tru{0=go@VbrC@n?U`^thKUaN$alzTA&iPHGTt+>${o^rX_`NcNK7%BQkGfXtLc)=KHD z=1t@B|IsZ-tGEqMRzSGbOea(q!-llO3%pRT*)NWe!LLd|#WrkI>}ac9DK8=5gs9&h zUFr74h^K^lgSny%SXJpS7Hafrq8eG}yRsZD`?cx95|k2X4uWfaFQ+LOL5Q7CQ6dDEgEnL z&Yxt1>4)UC;%Q@3-oieV`6fZ?3GLT;6xRnRAvL(+(kcq~6lOv(F0-c69(Y$Vr<%xW zzl9LdawKP%ms6U=QZ|YZL^}*&+bpZ@;;L7H2`bgMJO`N1m>ToPf@O2$JH z_u?YxMX2 zWT*1(QRZSCRj$@d%pIpx?;M&p#6atpEok|6YT2kd;(#rb zh0?D9tpx>yVkV~HZJOn&QDu^v7t(Q-6cfg8-XpW%rX2!ZRtZq(_L; z4(5Tl0iPtN@Oz#H1d!hgl%2yyb2(dZmq=c|x9LLs4T)DteMlIM+@=p@>G5P740*W& zGrhH|F)5fLwl8tIk7|czAaLqsM#l5ZF1=ISz;3DNXd_#?uar??n}>y!(?Wds$&-eR zPbttsntDT8ZmV1vF1b3fHLquL`3RR5;mK)t(Y)&&nl)^yxO< zuNn&+aoCc1!p6gDFdmF?X)NVpj_&v@)Qp_psCqyT5*Mgwfx<9%$!H;k%W%lZ!Auqr zzDscDtGbNzRZ)ydJCEq}M{=(5A{jI9VbKX*mEWslLf}Eu$Nd}4qn}{lf9q9kOivZ8zdn9x{p^+XXVSc4Gc)^1$2Wxt zXZF%}^Y$^oQou^>vt>uZjkae9FfgGVpjmG|am41ugciOj1IEx4>aLUG@&}(d$5=7;_ zYpzNX6rB>mymp5m1`|P`(Wj(zt8ty%aS}4)c;A zS*oR?Gz^VW1ZI6Z4UkA^BOM9h9L?GWG#OuNWz9Q3)D~NAwM*u~oJ}@o zPZNbv$PMS;^C0%a*VQRJ)~URYGWnc@B#Dkq@n_x62YD zMk`W_n*`oj+{+20A}g$OsD7W+K3~oCu=CUYhx*M^#XW%b^T^_co}de=s+WRe`RUB9 zVYP7%>+&Cxp!1dL#J5=?b$LQP zt;p#gxV;!$s*;}~f8W}bY#IG(_>7T1Z_W2A=Vf*IlZL9we#q|$W)5Osx&ZzTQlppr z1shV2IQ-@`6xt>p`*E>)ZX}gmh*jZb6U(Ru@4xrd_y>`=f83X1XS6F3?dV`XC30&h z5`3Qwp)R%&8F~E`NPBfi{sT62^sM=-YWt_r7)$7IEB(rcTEY6BsnUsJ)xQejxeUr7 z@ff;!P8W6~%ak7HxVTS+`__kkJkNgZOWO;+Pn&a=C=#=(R6S;&(R|dNd_T|>);uC^ zR9kIH`wW?3R|uiO4W>V;0aH9YuL|mt`Cu7x4)YUbAutSNT+@Z|;hknq+2P&s$_z$8 zK8V|pwcRw5+WW>~Yj-Y^kyX|#Mvx==hR$W7io+|t6~{d&|5gE0(AN^;%*}>mz=gF< ztMo0Vo!Fnfv&m8xu6WE2cPC;A(U>fsJNY8C@C&8le){@A1F@+0@dc*nQ5`!IE5S9JZ4tJv z%E)JxP!*kp{erQwjg`$27Ce>pFXS#iU)ayOylS}xOn-(J&de~=H=K{2%BZG1&ix~y z2_xZqA+B>EefVbXb2iO}!V`w%Id=|HavfWAG<8x%;DL0k%9Vxn2rW89e z=;0p<&Uo?-{6(Xgw-LuCTLybv9_3C<_J4Yp{hK-eODyn*mlCh0p|=2|URFDwGF}kZ zGLEwFZharAD}(s1Ya_y+FLybP`tbG+(mA>^?e2%B-{!pX#)_uZVGQ{jXq7sv9yJ`^Lw7Jn6S*G4+k0h_qB%K4*++Yv(ROG^s5cHlM z6~E%asO-NhZf;9O+)(k37!d+~mQ7A9cS^={g+-;jzlNFMnU3Rx4SWGVBOEhRlyYIi6i*8%;7gN?Ph z2B|g|gjf8?LYoKEqndj~pWaXfG@)Yu@me=Y6F&Z7Jo`TtH@p5-ar3X&`iD30FXV9e zEDhStC2yvTOzW$43rMwX6vo2>_@mj)6Vb}tv2Fw^=q%4Pdxe#s3;ex+n~duHaID9sbd> zm{7)ib>ya`h7k$0hFKx*Mnuk*eVh7E=u#!V?oVbVi;ZL@zu}LZjf%Rg<;HJn=pIL_ z!-W4|I+ezuDvIgVBVkg*Hv+1X&A2mNKMuJ{!e2U-zYNp*qY>rK4&fh%{HI~s?>d!# z1lC`N{9nmpe{u@kaSpQ-61mizT|0kY&Z76L2YlT=xf3tqG&8Zxp891cysp7ma{b{x z`TKJIjq3c*%t{g#=%(4Z)9xk|DQ{>tsEz&i2YCvB6me>zZ%&QUe`V8w)9G+S9K#!# z)kympOA&t5y-w6CxR}<>KTnMgg$triPOX5;j$jaJMV{So@~Y=*^!Sg)ZwRam`i$1V z2mA9)cGj^fKd2l3$jSR(IMLpQ7hPBRpQ;5vvBXd0?7qRclp^YGra6}tQ}yYEmElmT zX?o$$6eQ|7%bz;6G#1Z3AsFS7|LN5Hk7?e$SkJlV}UosEW&RL z#)!0F$^Z>6@-rCeHGjpa_`!%FyBmVQIX;4Q5C!2mPH)7tD*N^QObZ}8TOdWP&nC@F zc<6${9cJdCQ5dXb9lqeV!=X&X8BSSEeQhXL*K6aQcWuW}A^0RbuoJ*cC4RYJN0-@$ z$!g1h3@k6iv`U*MWgO%PIn6)!L7`jEz4#oSmHK!nLHn);%;<5F)6KL>AY7>tZc2!P zaL6)TOj!IWf{#c1Q0?)du3zYBkk7K`N7#&!h0GnCH}nV8r~e`^)qEMa)6~?+6dc zUj^acf%pH!3#N?#Bjj}UH8`qMP{D{|9>ER$ASXGyjkCq%3E{6za>IvBLMYb;Ae-E5 z635p6ixltw_w@h&aP}7P#&0b3{>&Z!-$L9UH`X8N|Np$PE`L9JfffPSn@nlJu;-9( zXotkJ63`d$aQFmyvIHrb9vu`DSh*2`y`E{Ne--2TS_WNo(JTnxV1!=&MaO#vRckky zji@e}ky$?Cn~Lv$)y<(9MLcC&7^C=uv{_zuF)4xh{Vrp=(e=Q#l&SYG(&o>K@Bd+w z@ST5=Tvbe@Xn<4UI^qH@m_4zly|vWVL^WjQ=cw z{qw^6kA_MAhu!eM^90X)#`a@37{D1!3p7N2zwny>04e(8%zo~MrWkzfq#MQX|K)}E zd&pRPEJ4x8wiQEjy_FKn?med(m-2g@PC}G;0+4P0B~AmcPF>CWk#J}f!!K?#4#tq( zeIR|&U?vwzhY?94{1E&y6+?qcyQ<;ecnSb%Vw>jxC9-IYAW=7a&2pu5NoP?VhuJE% ze9dQwxU5wr{ku!mt>Y@)P~A5!JQVHwMjfV~_tVD~T;6m+k3+4M{@_iI?KjkgCE?2Q z3TK<`gk+LC{^4=`>-qM#BWT>Q23|pkB~DI!Yx}(V!Uv<`r^j__{Y350>kl855lvXR z9d%9q=kx70DJGmeellID{ax=5nRd{_15^d9)oCJtG8V8Af5=f?;_|!psShj|70<2^ ziaG677>d>P9^ra7#0-FdcQe<)B{%?S2tAxQxVr2H)$)D^i26aneQ_LLdqWVJs)d!cQ=~A+OI~flU zs?V7wk%$7RMFt{H+my$=%W+^t#OazCHg%4(E3NnW-tS^;^G`3D-}9YaRJ|_@Aaby~ zG4?2q=iRp}fr)e4m-_bE@0FGCbiyQ{*T+eGKFFi$6=$CN_?6zp{`l2p8C?$fc^UAp zY8B0+iZzw3{;?nG+UE5?R6hSiGyX~dU@Vg%{?+nrF1aH zJG^={&b{#TXyWy9-tj2)`9}{GHFNHkL1}zv^;+LLMCPA-Shp07k)4d32j3G`vu zCY;V2_)MHG7~DnlZ=kVs$shyhVLfDZi%UR&TYo+{UjY>WMwWM)!kd;mhfkcpd7Hv> zF`X1+tSOp&!ahAJK1hPc`v*r)phui*VTU|w)7M5FMjmc2^LlENp?I zifaoKp@ zAB5Cu0*o_J|2B8IzB^<=bey%DY3$NX?-vH&vWV3e+U ze}s(8QGA6Y@p5IDsHY%4H8|478Wtc+!g{S2EraoJD$4()M7ohsUQTg(ZdJ>VMWsq{ zYI-WY>!d8Yv$8_^p-j$`QWhTPb$J`$OaX5>oj7i_`k)0}NDGAiLCY}s)1JC#BPugT z%)Uy+K4H~^^lJ5p7)|>l?Oc=78hx}H-5;vY-ceN+OAabsibORTt#x{>RR(Ki#A$e^ zPY8>-OwPZm7aX0|Lvd@(Fq9VisLmRqRcbBB#}f0%1K=DuPnjOUea|;*tuZ9R@T3swfEqD za`od{-J&}07*TohFmr5mtI504Y9yTXUJ=@!jU@K$GZ*HThBbLR$?nyiPd@!CYlq&t zPd9j6{il>n&I%T~KSa0&?0hphPFZ-qpU)Sx7VzfcQ|9yUbM?W!*z51nTggyHLfIt= z@zBLOdI^FW!kLseu?#!*eN0Fp%&4`N3i z#u;v4k zEyk3~kQ?723g{d&yKc(rSANH5%QOnIMvGgZe(TgC0w>|~_Q>1h28t|Xzw&;CUhsz6 zR(xUUwcq-2-naX^66B(j;mmkrCvXZ5vZFst)&<-c+ixbi(@4y<~QG-(fY*x*$1Ozgz9t9of;+o*PN#M zV+Qlh88ZApjc5pQF~M-C9Dl5Bm;uSFNWnJ!JZGmkZyX;l^PQ+ zTHOHyUbJV5bK`FXYAk5J?`nbed$+u{z28jZMQ}PO83xO*yy?j20m(8X2GvRpq1eh4 zFF3hTbT7@{wrR{?dg>mxaBG?x?mH~NdzA7yYnu&@(K)Q8YENZru+BLl-I>e-^uH*f ztM^l6n+K zuhCu9v5!uJ0@@;=`rhR2*Tcl5`wa|ltk`n{ONXvKgO1^PNN0eTwj?5H%Q?W zQ=oK0>iy^1eM!HY4X(%$0==%nsP&@0%=5gDvkCitZh0Jl%azy(l!a_9@AF zlW&-&w^LKb3_FX zEy1t9zFs^U#IPr`Q9YRy5+-SA2j;lRcAVm0Hvq9&@nkB1TRl*m2iQsr(CITz6sYqR z82hbT0C`)00t}F{fj?31)F%|$L+)VJ?r?doZZ~WhB5AoJ<=i|BJpF?2o~gmB>v0XX z9Lvz)X~R4H;#~*BN+7pPxeajWSD0(`O(SFml^H|#U*e4Wm&Fpavc5yAfajhM3OVH3TU-dga<|nre zTS)!4ZpY_G#RGQ@Pw4U777f2cT?jj@b%gM8GOek7W4(7n{1Eb27YQu8=FczUKD2}$ zMmd)hVmbLlYeo6&T_l!ZCf!DN7AsHW5lXs-p%TGRH4Bq`Dt(VJB2v%8RfSpAtN;S66bg|PM*S2bzZ8a;6y|IP z+j1DXb#yIz&^}u#nXN_hqHR2!Ev{DnVJSOWE*PC`7HB|#HYXFzpB*P36Q}qxPT^&m zQdL}our05G3LRm5$gazW@&Kw%EL;X8-wv#|-(eFC?9Id2;~ z7ykLERKILPo5*zgRNG32lo)42Tl{Sp+J{M?CYWyh%z~KRzgoc?cA3MEo?9o9TdSYj zWS`rZo!jD<`?M;zqtiFOO0^V*l?}xzGRqsWw-~O<8{!C`=*)Z7nfE$7Z{}s*09O96 zU;Z>HnnnehIt&e^5RDFQVLZB*x9pdnN5R@cEf-BTDn2C{S&-OV{3~;JC7&1 zlx!VwX;_Z;IhAZRO$_qvHL5i{;A*~K{ry7U>+;FHFbVWH`@ELxnw0b0zHZ}t0&&@% zs5fjAi$u}>`^8&RND)q2Ar!8kX2!mmb(TbO4P%sL#U5Iqmz%~V7=;#Hq=HG{>_UYQ zN|$I2VS>MVaCbDg@Kr}*i8X#&bV1q7Lh zxd==|B)yg716~)=fYC;xtn(pHEZL&wT-=R~lDuPADLLcZz9vD0Gg*Q9>FRA#C7fHY zO1A><)T|igxr2Dv%+Sd(o?7Np|L28C+>4k)T`^Q^nC{wAN@4NM0l{ ze~-3^V7R`j=>kW2I4h_D+ADxFOkAUk=qWS(oe!>Qf8dC{-Rnr%1rnndv=EZ1-h zIbzfMG`@HbaJJa@%4bEU(go7Z`UuvC&L97!k3c9d50XMSXptCeLA?Xm>iMwVf2P8H zI6|MP4C`l;Gdl8Mz>dI*=Ch>m2wh%#f9SYaU2_Z(yES{)OZ@nLqtiKK)JiY-y9IuU zGWmxV@N*mz0SKI6`!%4%glBS2AAg{=(!>(?Y~I2#!D|U28r!yP+x)$C>G~q&bk^O+ zSxxKgD)qdKh9BfV2@2BXnOw6vR!M$?#$ZCeiIwe~vVqBA!ruenQYCncs^XIV4#izu zog-4$x>E|KMe}v9vZ6q5&+B&xFd2Y@sB-B1{X`L_D31L9aH0_K`wau&LvO&3HZ`TT zTK(pKvWfe>>EjRl;g7!U$VFGELa7U{$01L1|!?hA2MH|rfa@bV5 zD4a==^^C>sF{t`>`+ekF$e2!$*P@%C=uO#g5yZf7g-60gL2TYF#;nCw z$7bwj%*oQI^70*nKFE|5Omev56y|aATehn(QhRyz(4q@s2$9CeMMfftP&QbqvTWK` zEF3c}993iS=(WW4#f(~nu}O=u;KxmN8H7PH(I9K9bdd~mvDvhZtPBy`Alca>5n7N1 zyD(X%OiZ77n!%z}B*>6?YE%>xuV?o$URjo%O|@AcP>iTWHW!9&yqI1rl7PXMaMl73 zjbYEZV2U6?Y<>=1>gNk-vDuSvO$Cc;wUoqKCWoqWyTAHSH?;5$(0W=oekFG65vZ(- z#lw?+Q?48GVKz)CQu34Eyei8Re+B0cPhi!&A6TLiUF>=D(EB=F^uE1AeUeHgy7<}u zkSuStw~EmS){BKLeamfhAN^1xh-#aS^^Kq>tuvw8YNHFC$9UezWU_MpOWLGb!;b}!~r0We)#8gyx_@yvB@+=7V;?xx(HvGHn z(aGY^A{7D})hq?Y^Pvq<-)?3d4-qu{L9+N&+T~QYm-qOy1YkW_?}Q9CCf7e{XNHMB_1Ue$J_bM!D9oILNT| z<9vhrf_LDz(@(3|T@JSOzPxt1UE!*+(zny+uZFhuY zNUR6=9BsYGRSOos?{~WUrk#&2_}Qbg#R^L*Jy#Bo)gma_hAm30=0*rIt9)T7`km;F zPy#`U&9EE$T|67%qDZob(VLN|wCzg}M9^Q4IV!5Oh~<8=YY}(*IlE>2y;pXYtXG8L zST6OXzBx%a*O(hH5K%T2j1Z{5ogzn7WtFNd&S4D$##T}qu~-);BnbS4(#6JZQUG(^{Mp%}o#!dp@_m*?Dhf(tC$evR$*mGZvrzD!uF59X+cE8%{osW%_7!aPV!v5jJQjMp!@vRyt zO0z-{1dsP%2k|BJDT1z}Egd92a(C^rXA^wjZWu-8$Y~{Qiacm*cULlO>-3Au=~(u5 zba7gGnp4gb(qyXyib-s;7H++Gi_bMZVadmp6MiQNl&dZjTbvU;{TfhVP{CJ%K6AIe znxL7}eSph9l90o(+5(@W|vVxDb>{0tG zRiN5Ox9GcYC9f|!+)WMrw$qe?F1L3aKKZ>X^idTtChOJljCm{LT>lK-LL4j1_TqU> zkK=DjuV! zW=aJhyHNUuiO%$2((w+R$$G>%^SM`-ocM@^82VG6#8qs_F zhp9gqzFsO)p8^+UlCmNtQbfSOD4q3x)u+&ToJ)u~jzjfBdv zXo;h_Yr|UIsp{5sH}7*i+x_<(ul)^(nTB&{n$D`=uY-<`A7A6JgE2VOLzesLu-Gd= zk06tgWV1yCftAusic>LX%?uxpWTXYZVkf$s(9s^S%Zq)*4u++bu;SV)su^fz_~?@F3F;AeH6R50LjB7F5`i-}GvW!LOv{YSN7qODcxfz{e2igQ&4 zt<~DCgAxuoP=Io;iQcn6z1i$QHCkxMst4STgEe*K3&swyxw)WYX|w&BLfy{Ke#e-55UwM^QQI6+1 z883u z-XXSBYF`gaekf5}9!bDcMt~Cx8F^pB89*;O5JbwYrP3rDnmuVr3mV zDD>>}#OFun-CQVkGTN^0*z``w)r>4&YR0{2^ez3g74P^7S|(@cyE}#s5Z+^`V4x{8 z1iP)n3sjJ|5Vc?cdW(0mmYo9!Q6U!xdm(9? zyd)9SD@kj{YPP|pnu`RmACQIwu<8+TWMR~bZZ9UYv+dk4t@ zAdC0z8UFRRaExZSvRRN(fExprm@1Uy;j&}R`K7TW?NNYxfd^m~Wv`C@3!gmy*FBf- zaD8$pKp4u)Vsgh^r{DTPZo6T81h;b8!%d7JB8rd)GNdTx0Vw5u?Q#Z}0tOiKA*qAL z39TWwA_H3G0>~mmS+hdBhC|sFL%ArznB@td%7q-Fg%D?j3GP08>l2c}>M5}k%%c+o z>Ch9Gfy%Q(6|=$(Y@x0dVd@=W8p08z{G>87nuLcTT~Q$l{Gs}bp-l7se8Q2udXabZ zLhn|F+GB<}%0~ju!!;?Qw1uO@E*`oR5nGy*_^}gn4@Ob%L@}d96EZ~mFGk%nk7kgG zj=j(#PL9S6n!4{p5tFh=s53=^%uhNs!0X;f7#T&V;2xuB?rY4?VYC@TsS%SoLR!)h zTa7^J24m}YW3`dunnwr?`C~e=;+V|+Z@H6obr3z5Cl*2??6)HulqcxTiuY!Z=hGmg zJBgd5NT4?-?Y$s%?I4_Lxj&6b#_t}ta*@zMLGT;zHvvEgum(u|k&@mxq1WPZ{!)Cv zWsQ;lH!TIAWu=!*2q*;jx%Y?*6s{xqZ4D$K@-6cs+L8gfGEk7?T1 zScO*Vp~>#}^XI^q8JU26exR`To3Z?@Q% zJ(y!GPAPas^j_2R9!h)SVBo`z1IHJ1;Hyl(Q!5;BB&aTJI##T`LufL{4=Ktxa9-ii zPz*~jjZPmK97CZ!{>|8`8z7)$RGH^f_XG_ zM+<)kz$yR~0C@oD=c)tfg$mc8VSmxO{)bIDFa%1i&`9z(TGu~uG^({oBug-o@zlTG zB~~w&ixC`W6|iL0*g_9itZb7&Jv@)~ z&{IvJS9sSO{cX9F3Sp!gjA_tLJF#EuT2RFP?N(1$2iZh~eQ5flTUhQ`@{G)sfx7OM z(*gnvv!y$9?t5JoE6>^6(nWGH$Rn{Ftx?}fSPYx{s!4m6eY1wbVABG3~&%y5@tjck;y4rDd|NlAiB!n9YUR@_hw8ZFPPv=?!hT z5+DZP1R$(rFl7K3nAA51852A5zd~Rr-DAPQG@px@Phn#KQ*PaBCCZ<#)*E_PCEzwd z2*8B+WwpP4nV6O2|A>}qSrcW#{fSmX@6z9po^Qq|LXe&{Zo*L2k1>S5koW$%A;Zz> z6!ZQHLxh$CNOWR<6M*|)AhMjzWPjjC=B)K9QeHGQr(8?TBHvlG4+}y z7}jDAH3ih1@V{s|>u=`12yh1=fe54kOz%Hu z2u%i8J-UImFN%OkF>S=9crff#)_8S<&~g~Tk_^IOLo`^!swJB^?OZpiQxQb|s}Z+% z$|-^#M72Lyk}>y#f&ZWz7W?H5GytVmbM5OSoi5Da1sSfA_r?q8Z}Gesu~@t}pJM#u zQ%3%kZY;fs_>>=dQPPX92yIFVT`Zg(H`|ndLIXK%4+t#4MZt z8VC}0b5*GqRYqcbfZXg6r03kzU3#~P5wnctk0av7tPp$bl;1+(fEWlJ)J7sq%&L@& zVwf}Va>jb1;7`$L!2=pxgkk9q(P%Q2FZce~naBX{1O%N874R4_st5oL(}|_wPyV)f zpEn*8;}zRq7o??3EUnbfof&qHkVK-qQw9k@{(Z83kmFDQ9f)7M4RHKta-4;9075zx z!3JllN+jbCon?Pm`ZE3u`R9z^Ohh7r?1g&Me5?b&z`6MGNl0yf-r2X>V%aBYf0i#W zrx*tVFd%nMMh+PjA{epDxnDL}52O<6;z9SC7$)L{^i^Ay?ywC93vhf*qijKNon;Sx zhjo99G>uT+xS{{zeEI9oe=(7a!epRLvx8Yc;*k0ACPxm7hNJ1&B5Q>;H~8Y&C=r0w zQDIFuAK{QER&%*>?mgH2@s~3j%8!LZK9MXpmrecIaF||)C!62^N%Zwri zmb4HQ^;4syMbsCC-b4}w`MFr4qt>H>sJcQurUb!v2;~5Q{Y9oEp=)+4nDkdYW|%B% z%yxeQj-$K{j5Nv>_2V(k;nxJ;Su+ z@|fp%pYQ%ofvq55-@fAUqwA&jg`s3ryG2ms>RGab4vpAIXD1|pm}CkOBV}oWUJ2@v z9|fJ5Gjnnes}*dyk_0n;Ydcx3ZFIk;W(YpYT-!XlUtQPVng(S)eS{J2YXq3GOnTz< zLtO&E@R;i`#5_Tja}%HUY^;YiR<{eewrgrtJ?K zB3TvLi|GPZ-A9;{obHUU#obTmk(EI!9XOolJg&Ptqj)?a_@4UiE3x+uX>IcgwLIfH zU6LH_WW<4=rj>;bPG-~>vUtZZH9)tbzI@_x?YE&ut#hCT7ns? z($xjHNZt!^5JLa zOD!mV&)F)Lvy1whG*>*KRg5WP^|j0jUh-Xe>rZVPtUTh-k4^Z1?t}RECh9xY=j;9( zijCJIE51oCU3=Y3pT8Z+W4)f12tF2X->&h8_DP ziFY4)ge9KuZ4Eyr_zG0`+@*j<^CaK^eJ$zR_Z}|e_vm`!$iN0D=KVrs+$|Aws>u+n z@D1e6bBR}!5kY}>3((_+#V`H7(4Sb!pKiB_96P%PIF1zn@hkc;c=4f)E5gbOmgdVR%RI>K5&Fw9&?OvYH{YOJP)Z)GcIn?2xZaZcprXMN52Apalc& zaJM{gaHC}SGE;W{iQH)q`}B)ILigTnJH?19O|v$V_!si58*TIvJWin{oPn(L2?*mq zH#g50ZV||W=GfjBB{)C|wBRcSv^(6ND&QN^2#7?zOW@S`s??AJ)l9o%O%ge0!;EY4 z1YegL8wniU$6DP5d3#9`kFfa!NN&gRDPm)(e%~TVY>gnHJ+2>Ot^nC7E~-2_ED1cp zySqo$8DOMcXrzuzhuekra=D*;|EZHD()na6;0X>6Zl2|Vc~TfFi95cR3;@+pgT;=a zu+xy8>#As(9}XSWQ>=`z6C3N8LdGkd?4Ko+LVYHPYKC(PIACWSMnjE9snTcPQ$kWQ ze( z_Rr!jo+jWR31^VB7{&tVL+Zahi!vevK>2$nYR8--kmWb=hZQNFhgrKC!Vl;BgWQP} z^;Srj>8A~q>47aO`x2j~(CI&($DLQYc%^olKVUth5ABvgbXQjQ=r|!mCV9w1CmF<3 z?BX7!g^FY3qH;BERlxzyQlwGBs_xoA9S00M+wMt?29%ciXA#IP>Pa!2ugH+hWI)>A ztb8&U;9~8Ij-a!cxg@+9S}aV*G!(N*LuT{NA#2tR0&wD9qGwsOH-{0v^R$!%aWdCl z6nLN(t8H4PuX!gN`K()T*G%VmTLT(E@ld;CFS8vEs|QJ|#I|C2QF93H^Neg*5bG}c z5|le5XLPq2b|7KaunTC5UCC&yw3oIo0tnjZ-+a%on3?;Q9$#@Vj{71ZPvK=FKz0g0 zaXl1!7zob!-W$PeM&^dFLrFg{-vK_;3w~^Ew~d3M|X z`#jKcV(vt|2O3}~L~E)qps6pVdSY4ZiSZKgG0LcpQkaGb`Zq`iza%@!XB(Dca<4sz*5 zqHmDAk6->(PrzLopj2362u8M#!X3w+V@JYT{G4s@{iFQF+m&|Xv2)U z&1D94R<0ViZ9kH!<@D&IpIa3~aev-1gA&_bp1XY|b|25+wt4^>x}%$;t~=R`h9rok zC=W$j)a)EKK9G)RZzl4#6n1-SsL$?H+6pO=xo?Q6<29s+bsIqHjqNz1o3A?sZ;2cct{U2`S3tMx6(nSwxC<=BDW&M;PmSJaA^(Lh-6kV z&zYBt1)In@*qS85k6b`qn=BG}F4|L2l5jz@+)lZ|E}#WNiyI+&u&C-N6#+ZD?=BzN zRw?3Wcb`*OSF=Y>(>BheGNNY$;z6P8xDeeJ9>p~ug+>t-x=55rnouxj2+k6l^G%r7 zvt1lfo2it*_rkVpaiDE=S;-P}xAY&+N;HzQ{cX%PC(@VPO5cJek ze&nk>T$wmh>gCBOJ)J67v7@o37rllOhr0lynR8=8O(r3YtshZtY*vjgfzgsCZ(bO# zBJ&ANqc?2vt|6z0NT$%~r}Q(XP;`>qij1R1P37wpr?Qed?|>}BNde}%_w~I}FBelU zDbmF4?@thm?f9lGMW-odr^Q(&E6^js`_mLVW0dsMHT}{bEWsvA1tpi#rLvRI+#^jz zGEDR{tQ16m<}l1o4JwZ0l8adCPMAw)a{ZzknI8cKWhPEG=sR;J{$*xRCyeP{7L80+ zsD74Pj3qZDBi=qEvc%X{_dvOEFjE|v3Hmoz9%Pb-xZEmd+T1v?mXq><3+ zD6O@q5CbJht4s7pML5|Q$r~+%yGo2i%lQ<`?flDc8>F>`CEh_Vb(Sv07L{YsDI9De zV7^z_YgOUFS>dl(*f&rSN>v%&RndQvsLfe)%fF-tZd+~_T~0Y#ln9hwj>t$bD9_3% zPpz)X78QD3NrZkWpX7m0WviZZj6Kn6`oJGMAL^QuYBEB^m{;M(oW*Uz%+UzsNoXr| zk5y=xsmvge3md2zh%J4_SxYQhJ7iD`@vn8cC;u$7@~*!qPn#oxe!46t#DjtQ5dbos z2DXBMDVo^lUx=)FfQI3wrkan`?eR$nOK^&WAGZ+E?$dnt6MY#Df>)plT8Bm-V+TZ_ z))9!nZ-;Leif9$0k_iCph_nH>)e^16&}tf5t?;Rc6x=!Gn9>{jmX$U38x?>}55G1t z-)dqJYmzjOR!VD}_X5egCl+Wa(Q6jGv-Ks0t80BZ6+$xOsXN0rEf#45JDONwJ7nHB zWfW2u0+hHZ@gUWoDaebJiDJlWiI<2x=9H`;*6J5U(}W5eb&CM$(NADBmHuj)Jy`Bx zHOz~;c!o7801$B@Dz!DXmfJ1Q(sH^Sg(3g)N8MF{D^(hC43o)JONjjpOiGz$R%l8&Y7PhLo}H8WZ4dvOE7cu`{Y9-AyWh6K7|(NR|7MlkM? zViUtJ!AK1)*eq!BJ<5|I4M0cD@p4wHZf|MiHTTH9%A1na(Kr^$nV`^!;V&> z)D@T9Ws}y*3$e48#&EAsnF!nnh+=&Jd^BxU zLZn^K!U>_u>!n^Tp`mW2GwRhLREiU!2ILm9RL~^4 z@g!#8Bu$gJ5`SUVY(+QFo|dbc)x6ZFv?39;jKo$$+SKGs zO5{_;QN<#^?lQO8QiD;Id+@+ALE{}qeJdf3Q=3wE2!H#o5xpUC&xr_gYwzrI{vfIMF7u|?R2uO%@i*$o@D1rjg zAl)K@fRrL2-QC?K-69Rr-Q7qx!h0`5F`j4decp3E`@tXUo@0(N$GFDzA8w=SOB4%t z*C5Gr6YeiR>NB>e@Cq!(PcQz8n`wwYz|+!iK|5f^Jz!Z`JovteI%{Avj3@qK?An8v z7x*y~vV#g=`{XMJ6{7~djq!Q#^D~>=2{|PN?1l=g^4kpaBeN>PzYj%K4n^Y+I~*m% zX2xzn^%-&BeXGsdnE&OT8x0iSJM_uk4^o39JA+d(b2Zt-#^wrs50=Ta?EOM%>K-7Y9~77P;kqJ)O&9Ryv78y3I<3U}mIVe7{unQ-TyAhJmJYBRI@|_Ouz7BC;e}Ldv63O^v)PU*tu_2UM-u5v8f^plmcIgvQJvSbpEuR|@LBfJzB-ajC+U3x z@x{E>FE{68$A$d7grdKg5THV%qlv$f%hKRfY~_E=_+~3KXmz8%@Ai z6^WK?T0~wE-i%Ej6RXH>>SpZ_Ee|F5EHO&czWY8Ue`_F z+AvS2L2ak~!1TE`E-y|E>Tvum{4;3av#u44C#W+Yxut2%F+ z3UAxMLhB2)Hf5hy-IzVg_C1}PJ+q0u7i!U6r}-%36>#FIFzyu}S}bWKByDr%^?42k z>+XKZ#*nXyU8C#we9UDa#qZUjXFz)xCS~haogwmQ_Myov|M;QMx0OyeiLZ(hn1&PE z2qM;l59QJ&pAY-k8w@(`?l%e^6wn`hpkG-xk-QN#nUr-b{QbBl#ygXzr5P%|gtkxb z&5^46;GMBdS(Ia5@#&{1$C4;9>CwxBIejHDypPVPCWB26am1H%&W>mv9nL%S2X*L; zJM8mR9j^JzMz5cW+3#c%oTlf*MJ6~XcAA#;qPE^}M!ri&!hBj6G9t9g$xvBGR z-A8mx84JDpGj$%A?3zZY_h&`?@L5syv~y+~-Jx(yAkZE(2U|k5Lc8HS`21P!CJ0)T zv0)q_PC3r@_EIg#P{KRhx4?NeS(AdU^60xfbB08g0*Zjtn`cG}`RZS7@NHRWhx3j4 ziYkYfLn_s1xCwSx`Q|EV#T36w`N#HwWDrFA473f+GN5G?{oZj+Mnh5-ikE7J$iJi} zQW70XPcvU{^2U-1NPbhsWYCxPyjm511km>to;^%f)*qPaQIm~7c%esLL*c+`JjeW| zC%U=}7SppigX1$KCzbW28R0*Eh`z%3c6mASAgeNz~}tM+C(K_#APBat-*qX@Cjoh>Sv zH=m@Fl-LvyKi+~{BnHW0WC%4tEE|yKN+Bmo-dAG$V)&V!Uhshw^MF=Bk^^I;S!(8D zI5C2yvLA87`zFw234|kOYV7+Gx6R=1AX2Y0VFU@qB@Xzz=7C(^#LV>fgz2L&dV(3} z3X%>e>~gCBf;|iZE$Y^d8a}+TdX!r?NPH7u@QgmmDVf&y-DRUbA*G+tI%)I*$>I2U zTAqrhdC{Iy34MfKW|u~^RMdA3veY^07Fjcz-D5I#y0fH2Sh>bBYFQ z$zUsneEr2@FoN%*>#ayM3O`I45)h!#NmhrGy#2~O{_cZU+9evUq@%C9*zb;sR{7fB zw1}HGACa2!Fn?e?Q+8+WfG(x?)4>aWx#&Rc079X)t^>NK`c?k?Hf*|4R{gZoaHQeX zI=wVlVvj2AzungLWZ|)q_%Ml&u$*G`$?Z%pM1w_aF|$~%tm|WN8}3vb2aO5ezSH0fK$wKn#e`v(45VmzqW-}fJ{e|lw{vJt_Xjn zrPYK39M8e1(uB-1+bi2Bi*9nr%D4ephv<7fPgwD7I-=C74j1KfUfY%nJQ|Xzg5y0| zn%^Qjd0laL8qcI6=SBC%Iw~C3x<^+EZ`=|89KqMv`e5ayY;rURo*Zi$%Gj-Ra@=`J zX>0Kn!tjdy()TBi#X=|G>9yPl>F>9$9t=#6ZuH z@IS0Y9D1zm&)z}#%$m-uur(;ld9I|tF#B7kze?UtJGFLNt1@EUYta+Y9AflDMICaH z`b@8Th4IbHz6*h?);E}ju%z}Sd%~s8Ds*g8OQizeZoJ`fZ>RaJ?`w9HN|Y~{qD6*~ zZBY~uwQixyHO2nex<4Q~OESWwVgJUYvW)-f+gaZGIO6ZHdSl^)DEL$$i{?cs=$~4A zWmmiP=!3ItJO;Cypgt7d>Yz>n;TnYqH?EAY_m0#p3u!MB4zz@+B(D6rPao<870DHqs4DU@b>AjpJ=c3#2E+&j!JOi87y&wc&@6=$n^F)|Ev+Bg#XV2qI--hKQ^YSJNtkAw5Y#mJzKf zgk`|bDS?E5xd#Jc`V1>)Hl^sI4R^*%+7lvPR-bS9nMRrE7^_{?@>BGhkxs`}w#%bb z3<#onkfZOgi;(~%Tv)9k=?jlOMqM)0(t27+3m+7c&xF>Lq9zZaM!>Gx38wxRB^Pe!>{FF#IaWfE_iwndqp@aBZyPY?YLFYEqR|0qGys7AQf;jL2|wCFc?06g&iN9ZAsN%0(1hBVvsgBkxJ30EdPq?uDg6|!sT`wo z0s2wL5}Mx4#^-de_b2ybIE=Z^Qk~i-nrD=2<8-+p#b;f=2;+%Yv$92wcbFY8r_=KY zZ!)}l>Hhk?9!B%P%LEyl?htR2Bw2fN$ezq6uw2voZx&18IC5PP-m=xbk~1n-V9<7Z za2HAJBj1f$=?~afsGizqVwq-o#s6KmV+59MfgpO}l*-pk)`Wqmt+ zv-(Xvo~qySL$TR~nXg}yq&4s?#$hDz9->)BF9{KHOt2l)CSaDVmuj+pkXB^u;S_a4 z--lnJXT%tcIh89UN0=*2uFfPhF*Y^2fg?1IT2L9*rC(WG`K3bt$bWKtwnxH#XK3~W zsl9Or2Fqq;DIs}9!arUnpA z>5_6u?>&N+<>ibdhDb8c>Bc88>3ihF*R5bzp1h-KNha6;eM{G;wUl;Z1#-aZk)ci1 z_rUopGA$^%F#4^-&D)m_R1Z;ZhrWe%$JB5}mea<0iwSnx{@sC!$5}&-gSr2SJAjH# zu-~PCt?>k$O|FQL-xOjrG5i6qZXPi!5^;$#X96vjyN5EGhf6}yn(d@P+E1#uEVNzk zJ`swLmfEV5_b|Ow51i{1d;wcn6;R60PeRb$Hxq% z`Di}pXi3Le2S{@fX1`MK0qQTAB*CFL9Z z>8wadOL8?*Okj>bweB%A(4i>_OG!QvuT^}!M65Muc3<0R_0&GPMSn86A{=KJvb-cN zCtV5NJ6vz*B|mggofL0eW6|v63Q|j&UFLUcS<(DSl=1bncxRF z96_9Hh7bxSpeXn`LP@*CN_|49gL!loRsZ}Q60KghGYq$A06jdFLVzM9gp;qh)$@{0 z6Zwy#Ptat;n$)2EPqZ|}IuS7HovGY0?`q6LFeeCISNr(_RIlqHbRl8Mm$&dhXx35zeznr@5RPb<1BB zxxa550fsqxOyGwF;jjK&4jta7JJ`D`gV!9H_yI>IuER0_?i_++UHOLPI)jrW#P%#py2itLxeHLzoLG z51_OHP_=;16$wAxxlbqKOfcZn*^@v8Sd zFmx3q^>LUV@l2au)yym1xliZ%=COwMyAY)O9`3Qb7Vku1pLVZPR31CO*F+VdXsVn( z_=YEPQ>&5z^!a6v_7`$IZ3l@tuo?H`2o!*G)llgQFzi_tiIib@D6V`uuU$-R&z*^J zq5lmQd5)@04uaY9Or5rd@3ZK{z#;A=jJ^~9d`8bjF?7-8x~>u|Z*hdo{c(w11P{SU zac&&H%ME-iXSOHA{O;JasC6Yz68O9cxluvvGI9S=DtncGFo(0%dy=7JIPgKQV|!Dd zrpRHw=`)baRQlwy*0P&1kf#HNrxeomC;bif{9hPL+PR=el@%=Yq#74-lyaQIp7AV6 z&y6LYn1&B=6ocU@=cI=V&-Lu*wJlxxVSpVgx2fp|K82)6^KQA_b^6M4GCJUZSQnRY zWsH1=^*Fch_2Gp{Z?!{Z0e~~RAfq1-y+8lVfU}nH-#+tC2Sm0(Zd$*mXdYA-NIZCK zPqrz&%ltz(mHNU18U6>U<)VGpA@+S!1mSzN_ssXGXQN>7>+ zwCe1K_d%{~z(j;HPX-5yEnGSV%8?4qco!%YZh&MxE6>DJy##MwNDi*PBfgjlHvVlwdMCiIw7LGeawd&{wvF%Da_{3<*pYqC?or%R-n>Hk-(EPPW=u*H5-PMd-ip z^vaul-yPJ=`Mx)5wQe_C=@6sQG(B?L{%}#&9&pympnH3~A%7+jy3%-KbahWw$>9_- zxTV_X_;}(?-77)}cM2Ig{bwMQgD4orPPXgUHn=Ex51DyAo-JYjUX)z(eh_Or2Ysb z!B4_CTl{1L*pK%_I_Yy`;QwY%crBiPnpH;SW-VV&hG&EwzO8(=P)uPJ%r!AW`;cd1 z0Hl%U@HqL_P9Vlj(CJx5-Zq-ejn4yq^w5Y;CHPkGYdp^=MBoXot6jIE1ve5F)comSc`O?EAxy|@|)u8bA1zaI~ zz4^$7hOsEHp0)@fQBjgwp#Uf`OA^(zxnN~WO2uGRm;Yc^8SH5D)6vvlL?aHs6H<6> z(JudRG))h*3BE9^947UPcEMFihz|zCkibCI%%Wv5Q1$Q%s9J&*bW6u^Gkhhd2G$Tb zs#pMOx``}fHUA4^d1g+#F!kECcm_)v#pqGdW{PKn4ZoGnIDIt9tjk^jqr_}AL0e@u zdX)$B8S7Oidn@bJAUK+h8fa{zjn6)J@CzV*x4=0qz@8M}Uq?c3gg zKQ4e88@zyZ8e(6MhLZb|pS^#&Q%k6(m;Mm=g0tI&1^qv|Q~z2T{>^M0415K$+w|I# z-49iE2Oy|36w#XQz<05cV=LISXR*9B{uG51jzf2A{5Z+S9!|asm(qB~i!3a9$Ib=9 z7Y!R-ha&6)+IMVqvBPIO6QE*erg#?$&13@gwZui@7cwV1tsYEeZ`8oPku%=4QB44> z)1X)F(t`dP8Vs;*eG1@(!T!GBXt=PTPgcH3RM!%E4(mL(ZWX6uL$fvO4^!|s2kUX5 zHvjbZ)qD29`{iQ1;mdR2>rqOKKcm=Poj|!Oyl|`w)p9C8y#6&Bj(b zbnY%Nk5&HqWCek2{;2k-PON<6_+4S{q6f11#`AeVF&G#%ZE9Qz-v6oEvlv=dfBc>o z36_-2Lj8%82poyZ@+V5^6oEMOAcMf=_Ddg=pHJ4GMSVaKY6CM{vAW7TE4X>g5-Yxm zYICR_OrsD6)h{+Tt5vRiOrj;h7z_Y3S(G05peH3Z!6llb%s@XeS~lieMd^99*BUK# zUhSzs5ww+?t$(S$1-FnfXu3I86#yk4U0%AqP#hp|@nr3S>#uD;_q)!4JcB=vheZID z2LOUO@@3zEGxHL=KW1@ zQNKh=6s~^<;Oe*;=nHgGPy6Xro1y*uqe-_>+WmwL!e(UWU$@t&34cYpvd z2=-AGWg%0Mz#;>1+tNCPT37LKI76>^84u^6$#cJJvJlw3wBP-%9Zb-BQ{+yOG4!O~ zqe?IGIebf7jQ3>uksabg7C|A?PZ#4Djj5!QgU;h2eMv%U55BBBjVehIoE^@n3_UZm z-F!1(`d)RCF&{Eg2t$t54)Yhb8?5@yBG;|twXxU+;L-4x2VuBy7#bUkRwTwty~r&v zR)|!k{^mB8UC^R1=biCQi$VbFo8o#lwW$(B!JY~4_PniXxd-K>9QqOL=xsY_X3B2+ z_uX*IQWN%txix4DtQvI~uKQ*gltE868=f^#qh&Lwv~4!+!ifFM4qL4X?#SD11N`6ydJI&1?hal6*UReL;X4xN$0iU-&XD(#;YaN00PG7rLsH_jCle!+ zx))paz63uFZtn|kzT|@!zJkM6_k=mI0P5x&l;+uh*X#)AsWr)+TO6=t22yL1nj)jc zl*n^?0FnG7wOXzrW9WV~{nI+%MFZ79&j5xX9ekCD`zv}2ABFLXU|D!10x@ze3d@|8@alwVA z?VUUr9L^^xEq@l8#gi`7=esk%rPdskR4}vlfDS{q>cjxrxEjRCG)cb;3obOP*?egc zz=b9vJJMzyhP=^c{Y9Z^wYvFlskI{VQ#Yp3b|%L<@Nj&(hip+2gnE9Jj1A+XN0AqF zJC462?(J1Qpzmuef~5VTK#j*YpzazKkFJ@cxWktecyX0n7Mj%~Y>6|pHe(p|K2^k&YB zU3*x>-WhMcbKVl8UbH|FM%t_lJk8SVlO67hVwcpM0eJdJ$pA15QOmcK$&#x^1|D&nmHH4(ZZ6NytXJPUJ;0;-q5xA$Y&cpAY_`qSCYG>C!?e8p|$ zglO~2t#N7al#A;%&~Qm655<_CZ`el>F?|Lh($oB>h|H;NHMfAQrrB=3f6L-=(S!3= z&djoTM;mFUGzhm4$-?j^Q{sRC?+uayK5PPfympyZIJ3T%F(v6r_}3qIjgsJ@YlLn( zR4RYfS;4yIJ?0NW0y#lu{4eP!Ef@1&`Tt2tV-_TyhkF7cw%l|bKvi3gj{i_Jh=#+%EARKtf)n7N*Re-wSz zPio9<)?bnZT-gfi6N8B2$mfFavmQ9wL3)Y$ktw*8%6dY*r2LVN*u%n}mHi)*TsUq= z0+5csy!7V&;qW{8ivj6~U{4|+eE89BtSuTjDoaKXhwZ{cFJSdst{6Xi@^(ane3~lN znSYfw(75!}kI|R6A-^>y1g-F{sRIW5?0DsW)%R#atHfO|G7{Rf%)~2(jSCSJjCHTT zgS;u0!T6HDVik`XNoo?Uk&znPyuBnzvJ+!r>&}?3z$;cUeqO|aS6%V6+-O}0YppxR zbT71KduziG(mNEueGhe4fDk~%N&D)0j{`hG{;lKpp9-<&+~2SLU&oMGQvQ;lznpxk zCONn~#fy&L?-OJtcY%rj%O@Z1Y-;>s4Eb^x=@PTY+Dq$Ox^)gzqqAZAb^LYN;t#udhk}5=QWO zk0Z;vX(2|r5MeQveoAZ+==ha|#v-9C5GA+^+n^=-%N+#<1nY3fhKE}&FQxpw$8qL< zFB!UvY9*^A+#rLmJYQHpy9O5TdCt#{UmMFxrge2P*4n4@4n7l(JJ92pPBp$P#K@S8 z|LAcLTblgnajaMOqa&Sn{1`;`34o5Dmz{*~7i1Bdm%0#=k+Y6a3RWKV)aJE$o;Tm# zNoqt0y1V5n8aa9o4azUm+{2upE}Gw{;^b}}6iEHo4*s<_9k9eK0=((CktCTd*yIaH zgI}md#q>pzuD+IhuFG9yq{BI@H2{woxHklJ{5rAB6N+Ds4N>x=L85+^5bHGKn8uGH zLwiQUX69*M{;~bm&84tGSHnQTk2E5H<{$R^(H?(?d$M>cxu z1J^cvv($`Obx;DGAz2(y)WirNFcB|XVa9rWC#sK3ST&@y|>b6ocrs_Ico86*Lx;F zS;cSQbNI`b2w`{J^cVJ=m?D~tmFir&aD3KfmrS2ds_(jzYIdJCS=fFuHg6* z#k8Pn5cQ)*5+lDTtGv0|XP^08lvU?FlWRRh{b*+yIqMi&q(_OGp6btm_&N}SAagUG zx+LaZsxyc{g@65Q7p-5e3xxf-6~&MF^*J%`zu`3X@1y|l(-?TvBlD)Glhr8-C}k}z zn2Eef=xeXJDYW&Teb9u9#BY_GRP@FiX^CoOUgIl=-0a5B0K6Rlb;fT6fomp#M6~3g z&O}S-148=@aO)T5mLrc%&fHvE3T6X7`)i8^MJ+f!O1HYgwYEspUQ zvUB`~tLo+Z)bchFCjq$C^(Wfxp7b8=?4;*(A8;*xf!LV*z@;ev#JcOU@px{4;|Cb* zH=M13|PnRt0>GZ$k#TV1zR8Hc?pZ1dpXG zQ$sYgz4*u;zs=0`(1{3v6FfYTieGm{OEu)F9!rb z(fTXr5V*rAHnIOZM|jMa$pxub&b+@jYsA+|wShZKMoHt>8o`aL15D{O?zRs>T=3HnFL`MwRRRfvr>4-*{bM09VQfY5wu{Xg zKJRJ8QJ30YZckA=cbdi0*q2*pg?iMsdy`yg9%_USIQASShgusEsw*se4;EHT)8r9P z&NkPuRm~rWZAx$&`*w?SX6g0C%E2R2+!X_nOiozAL?w?q-?0p=0bv>JcevfN)YBA+ zMUmEk#4=zT{m5Vw$cO%*=(e&an@Jt97Y*+0v z2uT=FiA}R|@(rPNpektX8>$b4!yGN@NSFF)si*qU0wa9=p>e(y#H(|vYU}GfyZ=(B zGXzRBS1br!`jFJ0FI->8p$&!T1IAY|9SZrzC+xoHP@*p6oKR>iGB!w?`VyRTg~US7 z=1^u+6J*6?e4~7(ov~GwjLwFZGvO+6Rjji%|f8A;^rS?&+ItCwr`Cka$XYZ>Nc z+PO*Rw+SnaipyhBtrZT2r|AN75L>MDVry`-h9fYRez)a1-3D z`NU~jo9WcbVAPy{v{8rgisa>g)2vxx2l~F#!=B(80r@5*5AU-UjiOxiKc|9!neuCe z*mc+Icodj{`@TT4#)@2jlypgQe@v8rgdFJmB6)>%*~iRwVBET-*q$c~bih<<4fOh7 z;-d@YkNB7sg1(^=_SZQf`Bw*?f1H|wbG!1&mi4H9|AAD z(#-|?b-X&dU;t#?ALQq0^Lu@M=f+wp2j%xQ!>bEAM@YtQ}FWJ88i(@D){b6#C%dg1#^@WeRj6{*iJdx{-h|`bQL&sDu=JoHV`3MJi=0)xpcC{g{%i4!oWd>;nUkz{-GNyGixKozJSNPU4hca@@ zAvnqMwP8wVJ~bYOO26-vGX&z}f1DHkcT@ArW~R9?xwm9QGxqgV8VH=#ik~j)7fyI! zg-0jmZ&-COaoH0@JbWYyxUv17O35S~Sgy^qf3*3o8t>v!Wjh4t^(a1{0bd4-3Q`eH zQ;T{zgf>bMt{KaVj6#@+^bZo!Cdy?{YyI`q(x$3asu0I(NVk(JJn6(YicTJ-t zOU(tFgC7{SzYUF_t&7FK@s_KM=|xZch@vYvd2rY+wy?DcyYQg^bksX1PA z1D2IdId5a8&JXW#`&(=C~oHX7T-aZ+m7Ur<(Wd>=XuGT`#3CCF&LA;r8Pfce7YJv0#`((VUUHEJr@% zY3OOV+%Z{#a5msg&uXn5qqL)b4Qq!(2dXle#R3>rMQ~1qKv*6AN5&bt#n_? zbh<-&@h5r!3*2|!M5E*)yh9ixj^i5@B7qQ|rAa36!Z*ix5yE0mIWG{yPvU64L7S#* z2h$)N>uBb`M;7tDkTNCW%{YRRi8kX7qCj6zNhk&srDI}qlN>EkI$(D!rU+ zg>}3N*GK334QjN?_FGMYeV+!G0cv>L&46zhS_q>pN9$F15nXvw>0+yLASS|4`IcK4 z6VDJxx=z|KtRCZ_A!w;p90qt{oF2>QVRIkLkluCrzPByvAotB7RSaclaDf5;$JgwT{F6b2l0VKAzu7rk_!|y;G=dnrow8|^PLg)g64LCW|!6y z^M{m57G&qsmI$U(dGuE=+{+eecqhRx4_TSlRKA7+4sf3>`^3TX0W^mtunFZzF?%H< zhOP9sI$N{t4uag$2MZn1 z58o5emN6~$B+DkKW`)Ntela`4Q9e1G3Uqct87Je)&0Qa_fjPw@cw1vOQ}09lxIMDu z)oh2u2s*q>f@yFrN{@Y$koxR9)isW@@6jbJ2W5*W!D=x;g}9eJr5h8oQ6A_dj&-cf z>WBn6aI3-?TCBfgyXVWWKS8q*ESzNwf1hk!Ezu6cIiwh)antrr5}zD?g{`q=ojg9w&j4 z;!k!u9c7Gig3`O|8yXe7G@g;&aHbfaiQhduomtW!zLHg@ikrZ#j_5j&TYI?ekykUm z?IGV{VzruI>$Q($?M~Z@mD`}v`rKz&)6iIcR27e|WXN5Ku5`l0HoI)eW@N2owW>V3 zd>YatDo2)fnaaH=UNkEa^nl7N5lU9ktmeR=p2kg`a^!BII_;g!LgoCDoX^m@o|_F2 zoZ>HY5U4$)-yqqE<~!cKwX4}8L)to*H&S-zK47q3Zv3Sa9ci^a{P_q@0T&#~PN(-x z{Ov9Q>@22kVe+p#-H$}Zc6x(Y+^D8&ygMi~CIN_HZavezECRvO zu)HkpPF}+^sH}0AsWX*;3A+*6o0HHtAMH5JR&Ml1a}g^m>mhuP?cNb_#AD#nl$o_v+9g#@5bsI z&S#t}0eH@Dr{HKEthTGqP&v_L7Nt(;Kb1#Su5=&;TJ4Y8-Z!7v%*5MQKDk4E>>ntszJ-4O?RaA8(l(so)S;{ueT7Oq|F+wji^oE$4Y_CoW z{5|9lmKOk8b)apYp;-UxNtaMC)JM-0#wJN4)K^|&MD=7O(thoJ0(4`ZDeQA$ErOPt z(W-SRJloA@9d<{zymmf~4A(J~e%}p<8GkShGP(;RM~e{+_dP}Mp1U+tuzB?DJ~Hmo zuqWQ*KA4_3AW=-41ZShCp$&&{4D|UQNVFQL$=CEGnTIRGY<7}azNSe&RPente`e_{w5qYv zBG=HqYa&=E^2At!tDXfb$D3J2^MT<|qvqbH2$(fZUfU1n)fyMU*5&{ABrQ<-DG z);e*r$693tfL}KyCcmQ&0{1fgJM7F!SVFeSr<5?xuQk&UdYWr*x97UBwoReh9(*A} z&2tlp1W1*2bt=s8?(%QZurf;O8SL{sk)}0q8wVTE`R{+UYMUY8Y;SDlqW0-RnkB|N zY!ZEx?;p}OOU8NFEbW~im?AkxrF7V$(4HS$+%`wI@Q6nh^;2l05}1FerQer}f*r_s^m=uK_qjyBCvNe`xY#X_7@zI_N==O&H6enQqsc() zI@v@R+h@>pVT#Dax302%Ddp0M!?6}7et!rt5{v=5DsG|ejQ}*>CHrr*$>`lF3!Wua z4n9kMz)MSOut%6WOMP$R-A&^}0{O$d#z|**F%1doY9nHPY79$wKkn+2S8=p!1;q7O zh&HLy{QN_jKD1CqckA7m=%5q$7-~h;ytohx!hH6K7Bzh?RCCulz!!t{-&CZRsyRb3 zxB2jM6{%Unf0!*&C>ziXKTYr!rdmqWg5;xA)KX4g@(+BOe>q{1)e&D#6Z%%7a(&+B z2f7JT2Sr^gqxgwnRS-Ni&D1ko&V^4e)yv(_DOX+Uv|cyhD46sz5}E^0=;N{zcPyG{!P-^Bcpwrjr9k*^wUJ5; zHIDfWdZqO=eNdUVO;6@RogmOofGGx2F%zplG~wwR$OH!G83tl{*y_6O?p9&8x_5>$FZ- zeugx@H3|(ie=F1U&F1CV5>dzbcar@?zqBi7VJ zfZ~ZgetN2Yf}5q>L!WTD7QO2OpdjFbE1z3rpIsSqzsvgJM}0m3(iBwsu?YvI>~x3n z{@sTGBtOIdkKXmQ=FqO5Pb|HIM8dZd@?5&7i+$TrQLfDLzRqyYBGdsUR~f(eK8GZvJS zj`5tXI5^QT6a~mthwP;-*xV1S{4*AIH{iXon?Tb|$5;yyv6DMBO7=a>wEXJm2x8eY zUQ!!&j-2zRibM+yK5Ux2Nf%4x%XTP!Q%eg)0{z^=xDdcXtcm7+)L#zT zz2R^sny19CYn>EMD>d}~rUN8|YY6T3vyuUq%$vJNPNd0AH(#~-&BudRbOC8W|D~=5 z7_cq^BJy)x&G`VR)D@5xQ1z<^#O4hS1Xy2}H3tA+h#M3Jgk;r^FO-CeWdyeHhgc&( z_oM)un4{xpUQHKl5-I-D5&?U(|I!k9B_XXO7(lg_vNKKZbebq?ApVTFC;j(L+@G@M zKQHJ%XFZMJrI#yN^SI|erEbfaGvuN2ZT%j{Ynuz`05PEI{7%d0$fbIN?48V5&(wCj^F*xUt)+zp6YNbTi3i_1t*pKqcb05*+?$0idc%i|=B-nqN z>R;{g&`CI0ZZ9W!SeZT}!7e?BvM~jrIVGaj-l+(_HPZ;S!aqK2l|OC|ba{YVW?NYe zihpHCvW%(O0jdBO!x+4Nnfu~Osr_oje$XX_FPh(qFpH+*jjnCOtMo_X1&rqNLLm=3 z4&NTNsnwxS<$8bO*bnOnG64LX#!~jT=r)fU6crGU_KoYm6n_klJ-*t@J39mYMbC1+ zmj|cAuOYag@|V5vQvmnVK_93Npp=||McF_5aeo}XEB!@yZ(oa|;3J`@o>_gpCo<)Z;0&Uo6T#gxg)nn5?c(5jrNVFO3rZ2q~KpEfrzt50Sm?o&Ggq zGZ-S*7U^t>?(@b>Q^4PpM;DrUKz8RtXIo*t1=SjJxj{(_`SC&syS*}y1|Dtw{8Dy> z*M+do!Z0GfA24+Eo;g67r2_hk)A~5qyP6imA4!V@HQfotoQXZivu@*g;sI%do3UGO z8YGh#oZyW;q<6!G&!%_AQ^icp3MiI z#1zqL%sRyccrg+g>NC;LvjFdw7%e6cYj%k*$`Y4Ku&AJ?B|Sxz$shxzo*Q8$^R|@u zia@M?`bt*C9#{wqOTC(VU3Ry!`l<6*AuMwh*7p8Y(16e4E^UemdYfyB_ z3qOkSAK`{hS`O@`3)7JPwfus}_WqxK9AJ`+9amj;KcGd(abvPhO%fA1w=qy%mgvnb zYRlW&8t;7Euw|Lr%vw7_{QvWUV{o7;Fv`5x_NOOPW+D2iwf6)5W>3&l;BQ_Bh!`6S z5Vwf z*wyvT9tAs1JTtVK9Iw_}gODpH&7O>caS(bInYY+k^>Heq=t4o#09Zr~_zjLg z4k)+TY6!1gv;Vkn@W2FU+Y*7>i0j-PwJ;5VuKS`%1Mac$4{+&AWW z$#a=?Jc?FKnZCI0OJ=BkYgAN)KL*YAk!bJgFYpJMOw{c)L7dz6dK#`^jW zGTrOHP$Y0*@&JPt5d6&fMRDP5@QXc*I=90f6_`bH^=kidQ2@?5f4N2f<(>AgMIlus zIam>_jsTX!(?6+1l{m!zxe5J`zYxKNv%z12MmJeP{=(TnZE&Qxy6M+$1ubYA^zP4- z@q<;q8CQMrKK+0FcmGWfn%SpX>)?EgI{9O0FYrD!1#-pZj^A(Z)4yF7+iZv*(@=fNCfO(1D%kG=P7Xxxc%o5wt`RaJ_7Jvo;j3x-+zj*@j*FQQz8}h^D>au=RZrN>5F*DHQ6GcCIpgc+bxax%`Xek_#N?u0VOe_6X0stA zi_;@Qr-<7jO5cdK8V(~pW+Va1 zdMW8srJTfC;XS#zw9L_V_vbhi;u@`SGIa;tw2-B^Iso+GII4IfI7B+B<{8IgCBl3w zW!3SrVNUhQ>BxEwB=((+&!A(xKC@z9^cu3Fl5!o>4~Qg~wa_n&OcOkYGSV7|$RqQb zU;{GqbVnL8%!|DcdJWPaWDOgn<{}0PW>PO?%4Q9+WMmZb?ju_mKid^+2@r>85U-Q* z?QRLkl&0Y$YePk0Du5I<`^49Cgtark;~J&dLbGC2B)KN)=*WkFrtez@*>*xTq?qIINtF#GJvpv999)n4&=UeVPQ*b>xKG zjiL>V;hUZ>B&Yd$-RhXZm?FtGurYf1*-dHHEa7{n+d~CehuDc-QiIMvv{G_jgfFd4hhsae(=(YVMeM7A z;&%8T;AdFe{ME!}J7N+!g{@Jn-8_6da#1pcW1zX+vTQqQgX<&tj97=w@OJb;TMEy9 zvwnyD(RK_7C6y0Oyz?FIPAt4sssMINrwhkU9GX|EAh~##yW&p#?XRiAtSw#MHaiJK zC~2Z1;@$q?ObOduOCqxA-N9u$Neo_TlDgtO;ln%0Y+utJS+(>;AMK>@p`=T@miel2 z+$Xx~!~nN1EYR(hgm`>@`#K=p{#j}L_m}+dud)BrI^u8n6sRLK!p~3v>FVvA%5z7R zAI+t!O6#BNh#wD*|FBk9zP~>C#RK)C(pp?6<0;|M;rsbMfdDfZp}<$^-!?ZHZVWN~3S1ISB%F`c;_ko>LxcAW0{|LiBa zTtWF;$?B^0C` zxYEs&B`qBITNH`yZx_Nfp^coL1&&|`dKD-&2xb>;1W^3V+HaP9HK9`vSYOx z8JS*j5@v~T&^KDv4c#fsseEc%RNew%E-I{;5GabtUt6#&&Dm+B zE6ciqQmG42?d;3?5L4_c27$Zw`AH<&TBTB2DYUV(dQI82bB-x{b<2*sOm*u4i+c?l zL1Cp0+oeVO;Bn^9)OqpWFdGA#O)M?F$GdE4NAz_$*$@Kz@)UL8GbnTh`l4;CYP8+$ z0%{u+b>kQnyY!H$FYOS((XzJ@oZSGA`(ZIcE7i%(zEp&rbrHD^lD67c4f4%~A9eQB zOzw|*7tu<94E_2KkUmtnA(>keg~;pv7hccRvw^1BGkDt+DK zU3@3F|6ugSGdu?!&_z(vO!NvweeY_N6?Qy@>!35aSZJtGr1koA#;SGmONTeB$K3L3 z<+Jmxt4=pS2I+&4frrWW5#O)9G<+hu^5&k%Y~ZPV9u*pkvl97*IQ|c(b$gjrB@r&{TY^e~6pgswa2?L<@r8J&P& zgOYOX*VLWr>4%<^LqY;y-<=IHG^}VtXkM(jMxw1Qh@|n4IS;GzE}G|v={Jl8ah_yg zMleD*s6r>Xlg!+%bTJ9p@kprI4+X}$sOx0r)8yFnD+wm{GQ8f{0JfwJAsbP{P*$P> z`)t1Vp$}aL)Vmap2w#x)O`6K!NhrG5!SWZXqEt?a)5R4iyW8^T6i(%%W*2DJFsu0t zOqV{zm*_{|745Rct_*roY|Uz?S9djC+jv?+%E6*BEjL>=<6i19%<}l0S@Zo_T$#Oq z3^JS@xSgl8JV4Q28hucw+ZMY5{Jhv4Wn!*RiJ&xbxY!b_Qa!-UgE9?Y#u|xzVdBYI zH6n+Dt*SoubnO{sI~Ve#xes{0kf5s;zI_km#)7@g)%%ai}Gqj%moH(csbH~3*6ieFp7DD&!-Up`JgZ{AWYdpbL~eAamW{xG8K z*=PBWR}1GY7sF*Q&IdoUzlyj1%MPCgRSf=3hyR6&^R00H_u`blEEW1k+t>G8OZ}wC&xP}UO7Q)|{Qhq!iQp8+Y`z^0N;E`iyk@|i4`Wnb{wf1=_sPrgO)y%bE0 zHr7sj+z`rrQDdo7iRp`>!hWbF$_Yn@_m&bn#GnoaaRF#On$T8)2t$ac06qkD`eIR2 zl-F0RRcQSdElVj>)X`cIsSZcF+kM;cBY;}sWTuMJ5uf^X3t3NETRhQ->x}W+!nyN{*+W7Ob*R zZxRgUfYJHxA8}WE^#sl7zr#v)w){4eEWRC3l4C_`g>2Sy<)7?i=OueE@8o3#K@}Xixu`pZ zPMM7PIp4TPEGofI3Ud7G2omkyAnyyLmkCiIe<^=Yz*1aMPhC`0*-Wu(Upe}K)S+sO z(|WTQs_!q6vcKDAP5&5#wqL&%FTdaLvG&Pc?U&l!2V%jGn7?trcJqVCTA)-sY!gjz z>y-txd;l&>ue=Z*%f`6_jW@i!Q-olfxfKd40kc4DEhOOgkWU7M_2HxZ@M{2nlHn=2MHqnoP%{X&1n;6})S=lp02Tm`?FXw~ztV$70RUG| zz%(BsPROya`%gZ^U91`6{&?SGq*+Nex!c-m5tX>4I$8pj{{yEeu(X;Q26(qLiHMy& z2Z``}2Ajgd*XS4R)k%yF00TmuXj??X4Wa7bakfJRDHL^DN`DNeL;!%;JQnAvU$U!e z4*}}^M;AM+oTu|kSRt5S`GQeII6tAqk2qglDwP;Ej{NW0l{D}$55l|G`5T(!n#DK8?nCFfl@{1($a320n1V#Yv z$~X!D1PhCaZA$-TYImtuOgyKT0tzaE6`%)eh19n&qM(_3**YDfEci$(T2I848?SGg>cI0SgnA(J$qXiuchhS6-3@xD)(4iQ(#1J z7ft0+ge~o2qaO4^dD}r=8Y~7Ya2Cc%>yMWd(*-by0%)O2ps4ADdo@lsN>w^4Iczup5ALlmOcD6@q~=#0N5WOuO#Lg(TdImMwCS{=6x)4zh}MDb zLlzk?GW|~H*rf?^iUc~wNCyRGvi6`UUM(ki zHcCCD?9bhs7{N9;Z(&jT+We>DU~GkO4N*9+5Qjg2#PDU>w8Q46YB^6!dO1nuKVMNz zF)5*x0>W9Np>a?dKXMLY$pLzh_yv1(e6agE8f+U(rwbS!gVjH>nujt+(E;|If`t(r zxH^*F7>=$oAD&Equ&Yuj$4!y-S@2E;7prS(L?eEAG@pDCr2VWG(=^T2bN5{pf)xEF z&YY~Go=R-ARuO{`H=47`Yy==H{L+KWxWK!V)8bRIhy3V<}UCF@J{%4fj337+<*Uvl9Nv-=yc!2bR%g?tT1#m^9Z%45%f))X&FMih9&vY) zEv>kt=94@bZs{CnmY1Pb*D+oGqNdnPaaVV-ai+edrqp$K*YLV=w(YK_{H5X-6VjB~ zJ--^#{qirCT-Wm>kv!FTtb4ZV*9$WvJhgQtdycNxi_4h2^}Ve7Phzey86Vd)&JH_< z8_e_VMbzmIYtj4j|N++45w_7sGjS~qYC%J;R+bVAwr}C6e3-xbzbVeIz>PAjW zeQtN%zwpoXDxFoP+-{qSG%X}i{8Vl606+jI`p=IXz#E3jY}q&Gf99k8q)BqidY>s1 z<7oe_{`?1e^j~5k(2D2(Iwtblk>fw-sedH#{}rtLw`rKL*1tPc!uw)eSSX7?{BMcz zj78yq8kBxlIEm^0Xw;0xFJZ}vs9wRHc;dapvdm8pB68d^c}*z*t+t@NB3$vkfTF8a zN{YAsh~@ZO0nbuY*I)9}6O8{Yh__EQ`18AWf7F>F1C#*|VX6Mnn11r}rTB9dyJ1Vn z&!`pXMPUQ^n5NHHCW1mS)U7~0Mx;GbE zC|3+E6D`2}e+(J=OR0~%W8M$u9myZZRCqZP>NJoyV%zdO@{gzPOn@375rzWVUCq!8 zEZM(_oLV2HwR@2Lxx4=EUiJTg$wYfA`nxP|s3B*4Bz^WNx}u)_AL5*PFcJVq02cIt zWdHSn!~^6ger6s@N5Ve(MU?l)eBbYJ&Y=sZypiA1d~ksKNB~X%DcqxfG`s$ou*TfW z_$N`+KV3tApu7LwHT0-(=sUXmAExwwx`x`7$Ugq>Q~E*nf|i~!CwWq|A#Mg-&;>`J?Il080}k5 z-F5Nqojj7_P1@=1bcMchsc@6W{>LVtnqJIz%@@bB<4z)@ch@KXFhY<^m1pn-TdPmY zjo=5qB0~}P1*54JRirhwCf&Py>X)*Ba%y+@ny*mU<&3p%D9<;Jw9hJ(Bh7t@ybgYd zBKvJB~Y~9Z!dFtDXDi*&9{gL6F9}*Hp%ks{ohjd&_#v- z9Z6C+*MB~em~ISX32i>q-^ARnL|{|ksjtIz#68PP8U|T|Va7HJ0`KA7yj?QL2Jcl#y6t1;Cd2@KK%h$Ht76ga&$c+z_ z*%6FIWl5$3&T0=N<-Qw`aaorLr-59C$*9uGhBL4Xkd>>^cSh2)jgTEG=Sn7UxWZ0* zADVUeo{RklMWX$*FB{6&?;sDG&rhBf!>bf=cv@B+6W`&N24dw1%UNfSvwFeSlq_0f!%)(ssNy0h|sWfHpMBbP)hBmw5Z46+;5`N$vdt zJa6yI+zqu_swhSiY>@7eFGEsE4LVu1#G8NUK3OpRjWsb{}Un~~} zG_6mkAe{`fx-x2SHR>?^NZpF@7%W+Hhy-+4i_v}7Uch^YDDKfQ^QpFyrGV2UIL)rrN?ybfMd(ps?yOTt)m((z3o_7xbh4Q zSOl!~oGC1CSybY;>k8Vi8eALp?ImOp$KUE|J=7ajPxi$R%-xjbsV+T=Ks54@8ny^j z8o@-;V}ex8d1A%lvbZM*Q2>Xmi=?Q0(#!qI^YV=v-T$KVsMB z23>L#9V}}CV5V1%@;$Ku6+ujxk9A~WHxqfWiB&PpHb~oA0HAiQYH=76yFgMP zs0_vr-3Cq-fUwaEg=&L^-R8U4mN^0R_FcF_{i}lyy6Md^XtkA|2A@HCs-x0jeuf9$NJfJMnSq4@mw2<5Bz&=AZeNp!?Ul`sCuTq{EpmN`9J{M0TD=<@q+Yg2B zOQ3Uj7MZSDm{xwiqew^E@mVmvkHxwZmJ7`(B6UN{LpsH5N(8~;-pCx6RlVygdFzgI zya5XrW_fYH^@Z`E8HX+mgTWaPb$=|^@KJ2O!iM?bX6(Ba$;Y=a+Ohj<4?n4}vdJ%y zn__=Pjj$;sFh!*}Ld+3FrL*^hlZCamd!pZ(Pc z_=8Zm%h+6n$|H%;LUU5LvrjEgL(3ga|%W>Lv(T3RcNngA5gzZ~2j4szjil z#gYUf2RysUJDlSi!_c+h`2fpEinTrRO`f5jgsG7YN_fE&lVlG+V#8S##qg->k=_(_ zP_;(tT|@vLtU$W$?@Vc$$5RBqNDl90)ECAxIw}HfplhObS|H^1-*CaK&>D)$xL>mAeD>^*c9lS zz25M-+tIV(`c2(i&BlS@D34kBj~Ag9EdoPj&ljskZ@*=~Hqlu0C)3aI_&UKk`TRDLIi2eL{pbxW8w0^}UCPAe zG24Qc%%xIRl09LVc`P?$ZgY;+?Pw^$b`$DCq?XTTHWr z1A##*nOp(Z;w%f}YW^IJD+&a%MLiSvh_0R^JJZaA^UOMt%31t3V3kp;@#IprEY*@7 z4Tio+4S)AU-C-Wxn4X#SN;hTp+ifcS%fR}_=w+fM`07R*qTKDrai8tJ6hB-X_lexk zHT$q@t9>$mzt$tWAoEk=#nax8XFT77OS|i|w*5|OWI%iJRpNmC=Tu6M{ZG z;%#{CFq30lL)SdQs~z;g@$f`@1>hSTmSFnkrCrw&R+_tyb+CgbvHqakc6kri$Pw6n z=@a>^RUg-rqo{<1b#@32f1h^gaeU0pddUknW#*RHw{1_Sih?|czBap}PZ|i02hk8S z3daXdCUdZIkS*pKOH$Yh_TcyiOF1doy?vRtLZvI~dmDw_h}=!JS%aiUdF+@MEAg38 zH`MzchHF_f;U^l7J`p0ZrXb$FsZ($Ot;X|}5|M@`tY}$fU_j!rW!JrUOd&12GTU=0 zsckzSG;sJ|m?8t5%3{8YM$P3QXyVrq|f`h`2T zcZwwDmY2xq*~_+L;q6N$%#kOJg@}P`SjIMZY4_h7-eJpgKWDki4+$@&+cNTcxadTx z`;u{c69%r3-V2Q!LJX~1qdi1VRal++db+nSGd=VE40LluL+Q~xy?)2VAyC6r>F>?d z^E_Od|D_9-zqWDT4E8NAcFegmLXRBFDt2+Thy{Ykd#sRpaa(I3>()^?)EqKf4kr{}O*}0}FwNOM{A$ z1YMc~jG)yX{1TFx2hX16b%uFYvEw4A=E1Iks@VVE^`VKFyIU>SA*3sNu7;^)Mc6`OGv`K(aR7hc0N{jP8k*I2f5B z3jPkEo@i*;`2L6l(ebz=*7gap8UfUXOySt6uFcDEGo9eWC>j&~ z((L_Mh>2~nhCfzs%%g1w5pPG)`52IHtk|~0L=Eu#(0e`pmCHpevUZFTaU3X@O58h6 zN;X!yAx>{T4xi6svc}Q+U)yjqn00ak%Yy?IX)D&HgE)EuoMNs2q`?>a zn1H+D;c7Koos4y;bdc&e@P-dnh#Q+m43~VCQp^jhUJ3`rm=!CEfvf6~(zrLyyt;;} zaRvtrHwO%ho7$d^4R$XNe8?L`|D;xG?p3@uyyAo*raGT9;jw@SITue(`>^9-JtDlk zRH$skWAWGhT(ph|ZoAAkt3AZ4l6)BuNGySo)RBo>luXt-t9^;2qEQs8+HL*M^eQ5v zARHtmdC7#9)YZ5^Pb=Q`xp%8I?@&L#3nnrXgGu9Q;KCC1!4qdz%6lAX?JlhC4vXr5 z!{L8k|2SL1yq=0pA4HLINKjFaZ+=NhBkuFH7Ow$?IHit}UKCZc66Z8ML{{{nTt#B? zqz?xQ{!TsKuowPS5)RPj-4o8VuAV2_qFKf+SQ#E#fCe6J7>+EeV7Q}aY9O<@^i0 zd-9g(v*K0@9mH@>38eMUu-%ZnculfYjzCF0PlB!Aj(QcB6*|*!h`&!Z3f*#<*sz+X zD@;lR3Or4qkJW&MdAv{nT$GFH(+iSGw0^aXcMWe;BvYh9g>A0OxmSpH5K6;jL$o31 z&~Sx!IzUwWln)LE0kxq_S2Y4X$!H|MblKz?qCV-i01l?K3BU@7+VA{!fP^%tu!_L{ zaWD>Hg9CG2OrDM5j)~1ZV1)o|xuX~kn+hjW*n=b_(hGNQSTy`fW-T0^LIlX5K3ACe zgG1~G&Tw!QRa7w5aFo?zDL5>G)pDxUTWY2&{kQ-<3;K3hQ|jVTlb1KqIPWBCOe%^< zj|?;FtWFE^jAtlSf=rg_3Xg0`uclRWfF#I+{JbyeQco00*z43d2|WY>Pe|*$Sm-HE zvNugDT`DUdkpcsoa9*e2gj{2X31UYG0^X1|$Wb)}2{y#*HzbDDCloa#71gKgHlz;L zr|sf}$XE8qmF@dCqJ)u4H#G`oHqPzfquMkM<>T|C5m&R+Mn*N2E;h9+8kaBH)m=B~ zMp;UGHcxHXn4KAnKQ-E)ukqt8{lwk;1*LvXfT1Mx$!cMWVpvw!E`AB*`aK*@iyM8* zrk(1lPYYH><;FEha})UiT8x(H`_dITjI%P21sk%kbXjnQr^% zQifCv_2+Jco#&F+U(|8n9`G>Adk*3`U~^xi5r6=U&l%Y$>|MYqlx&BHSQ!Ysl-1~f zMiwD#1{DRBRan6keiX`gaM6{`IL-56oPcEUuVY#!5xUt$R_G zOm-c_6;)Q{I82K$q*445#dxgjfd#r&7BGgGi)JCHWB(@wV>KPrqML?0;_GZ5z~WN7TdIl}7-atpwKMAmFw! zsWiWLKCVZ8(oaeSgY^n(uU5|n2B;Y$F=zH2j<+ax$Doikfr6Y0(cLi^<5XmaHFR62 z70j`Do9-<#KcB>{;FCb5qAwg+M%n)6? zKGzgmO&7Ni*mL1}A%n26T)?eVj3|>m9MAFHX%V2<812e%nwW`s4q&4_CDUSuf@*cV z8m!`Yh+{fHt-SK6PqU8f9^d`l+$j8SH{t$z3|1Eugl<33{QaS|}8i zw^W1>%D~uKPN+zo2gi}a(Zj@&;qNGnE#E05X5IN5f&(y1_o9^*A5rUpGhQMdS4K`x zij8?ES23|cE$_WL_H?sJ`nrBwzCY$medeGTJr$u?Js}Ei*?i$}A4b`&^s_8>Dpn3Z zn=3}rqZH*RNjEA&xAr%RE>+Q$1TxQrpT|5jx3QucFP(57R!kb6vtL`ZA3n&6iqz^8 ztel*WY6;oxf;0Za)Kn!HwkS`vbag{PPhKeNuK)u=9UQuHmr@c2{U;j=p^u)$MyDvNAm$Pll8 z_8`NpGJ^8t!vqiY(!tRuUO@MYM}RlvKn09O1PJWMQ2NaS+vm#Tu>53tP1v|qV^&X+^&pv;e@QQJ%`AyRiEgZ zFr~gwLgB{_PQw>2wM4Fg;@lZ>wu^R^#dh^c{%Udj zEJNfxXY?x1>FP=Av1LN>X&fG#Zt8>(+z!iKNnBLYfkK`WZH}aHsw=Yht z0(CfX#OxOz&TdY^iVr$mEV$b*6hiD6VudNs_ZPDq-XKsITsW_F^NRC?t2K0die+I_ z9wEDO-JZ@e%8MlT_Sj#1F9>;8Yhjx_9QKm8jPv%gv|+yW^*y7zXIH0tAA8e`TKlvf zd_ZfKFKZXOQho>nqkzmYE+b!_0YFj#XT!}l=5Yr?!7wFAB5Eq4h%9(c>AjYXcAf2a z?PKXPLQ7@cV0wd5Nn)$)3Mo=2vLX>O&-DuFd%p0TGS{Yfm3@@DUHwAmQ&(1%$CYLZ zoH$H&$AW{wUmRfoK%!5%zW8!Wa z*07n({bk!_rsl(w|#d56c>r`ov)NbB*B zy*_lGKYqS3obd7a=TqL5#F;%p`{1b$eUAd3wg5E%1`Q(VE7L z=P4yERrvX8E`HF$YCe@?BE&Wi?cLROcHL&9bamGTiB)GG`EW%NT&vjx+dsTvHpdW_ADwCc9mefH%H3k+aDgVFEm@!pO52Tusjmr~heSO8N! zSsQ`RWAWz}OI}tjmui~Q=k-v#uzgX449`bCd+Ocqw#Mk?r_L)HKejyk>a9IEJQR=! zYj*+U6M1p@dDI7Rff2gqHF!hSO4o8P#|VIMQ5LseYUw~4wa_Kr98@6r%C9*#zUT_WSu-fgrW>3))_sh^vL??8a({uBaGG)R?rZv+ro-+<$ix$OZn**6= zGv!PpIAccwEUHa)iEW0DS!>oc%)DYMBTs=m%{Lpzeg$+UjuVN!5|*6pUT-tFtEfhX zCb@Em6>SIXlV>2smT9F0!}cU{&I9nD52~g5UE*=0H)&UB$91_&SXm`MyQST;=y$L{9rfcHHMYNO(LX-r9!Yx$3^4ZuRSfKE)CMkuexuv3gwUUA( zy1%Y+WJQ8tBV!g9o#Sq9!+>uirx}_R`^wRmCD2B}yNfznh|wRO94x)TE$kH)tHB*k z1hODedVk`o&5Dmq2voy*!>&mQDo>Rb+lqRwHCuXu0*jQcsKBkSvI)A;6=gp)&W53AzD0D2S(a+o?ue|gw|pBGG^jF< zY4Gbi6OzuV>u&Lp1jItGlj1At5lXw^&GlWWYN(2ckXdvx5;@V+8{jTX-?>RN@0N7E zqM0(mRIWF~Y1vI_M{sgMat=dzs6|;+@l0{@Ebk&}9p6;;}p13!IIL z_Vw8k<|C(P2ZF{hg!L^~IZl39Lyt2#=i0G?4ja@+O;EMxI`r4AQJfMDF*2MeaB*oiqd1@I6+wIgzP3ynKqY=6 zCG{ja4$^E+&)XoyzQ7)m)w~9Ti>lT3coL7MY3^j<#b+>68Gb9kO8(Ve-b*$l23)Ak z9MW44k<6E29vBIkn9p?Yu}%!L-XI|9ZM0Y%@;nvVS^+75*y!9c$F)>yoI}itR2d;V zk_#v-dV>~0amg3~%X65Z5>-w^F+X;{4eHzo1)BbRqjekQ~RW z>9`$au6OXO@dnt*U%6bN_F3O2M5;gRX#}*G%PD6lD&&Y zfrKMxQ=p?~sE@K_j*O3e#A48k1p;mTC1B<##KP1Pc2Ii<)L6H;ag@i3XzZ>P=CPeB zSr;;>{J~ILn)p5K4bpL;tfkFOPD7xTAW`*%K4lA_PBfR9LR+R*>`jHjIDW_OtL3Hb zN7rd9eN*>d-S-6KUx)8uP95ZlB<_mfy$Qf`wl$2&#>*9NBaB+^S`U)igcm(HLUi8Y zv2vzlIJkPF2yeBWpEGU0?7fUqLSud{m!{!BXH8IS9M3p+bYocVe=p6rkMQv!F`U;( z%ZtnVXn3P%gnV-FL%>A;(S|Fjv^tzg_ zn{od(q)5nOMLp@F^ZfbYMu<lC4=F=*p=li%s*ORl4E}HH= z-|_Li-Xs*cQn&P8^n_2IdnLmA$@ko0qBX^}P~`5QEcfQCFXSMh6;R!JIVl2rA_52B z27}iIYtRN~-v)0ELWpfc&ITd91)&v#kh|J2rrI#=kr#YIro!Hf+SQzKwd0=fZpOSH z7H=nTYbRV{nR?kyoZU_$#EM@nnt<{LOIJ1kF5ojPRQK{v%Q%0LH^F582g%~EB&+`+ zQv}Mn{AVhcf;%)QF~g=ROBu=(X|&y$`6F}e?u*k;l10)MrIF^#?TwKv`H$$&8-H;U zQ>wlaJy_}ti}Cz&FatG^>nr#T2l(9i&M)5F|(5LAD-2PWZ<4-g) zkIjKGYX4DY^#6nU*Cz99>FT$~f|5|Wpmp%Sl28tQQ^rC+5C$;*_Q6kx6b87~-#&nW zhyNj|gMQ<$KKM>Mc>?V^GXM#+>vRD>SL3a=>;L4pR)2W!2W|JCYwapu<)4`SD(Qp{ zlneCNW&!u0zZUU_UjwdZ{#5(-owN88Er-GP|4ek5dgWB2|BCr{_r#~SKa9-azR_PY z08rmx02#D}PXMg-x&DuaZmX{15}E|2A>Q7%xJ~`Rxk=}ny)rb{gUBQN6Op z0ZG4x+|6GzbZ1EbAi&t6e0Ewne@JwGSG|jIUlfTty^2lcMp+8Le86BHmtM|?2DfiX zc4|{3mdK1bl{t`JA&QyV6y_b4e7@fqghLQim3;tCs9L0r7^y}g2`{?LFy$ET3A01;+ zeHd(#AEN_zQ)#vPQQ}oAwJjN=q;XFK4h#KOBDQ&#FF@+f4&msdSOOvry$mO37OM}b z3E~(NHUk(QB)Hb)4cu(a5|ke?V0JTA^^w7#j{4(d>D^S<@vA4An z1o8^wI5oF4Ut5k+oXTki%;o845jl@Gl?7QJz?eR+^3Pd|)o8 zk!MmvCVkb6yQf=%?@-e;FE>CCA|b*lB+$UU7OfxMJiV1vq|}S&TBOwI{Y5Fi4T3<( z*BI9kB=E`OkwU{~mu8oU2hC^+{I1LN7_iEyalBRwsTgUb!%FPl=Bw-a$%>=jOM!g` zzu9>{e{=fBa~U#pHp{^LGMoRdh@;&Xi{o+iU%vO{{YlX71c+jchZBBcD<@-TvA*UF z`KE5&?n?SaFl|z#1t)VGb6iGFT#T^@E`++q=*HLH(SfP4cjlom(#W^l1eVb?ux|(y zn7>^LP$ub#hCD!qZNa#`x90~5!aXW`81+60CGWFdFETF=%@?f0NKG#z_{}C4%Al-QHD0t$F z50=Vqsu4A58fX2120pF!HG!ZOjIl^zj0aELbE(VUPH~1bDe^|ZW=-RyM#r{*CDYdS zP2sy_)1snW$iPl9V}~tEN!c2+T?zM7ev^ne*zKM2hGSd%ioStHJD)Psdgh8ciYB|t zQMKK|w{A(fy0we8b|iHlpQe=Pf4W0)Z1@mO>e#p$+T>Wj^X|H|5p6yOAR34069%y9 z*)44bKv>FK*@-KSQv3{LY zl1{DcEyT>ODy&;yIGG}6Inl{dab-Q58Q>Y(pSR45C|&qkOJ3gUTt~{gU^lzB2cowV z1@|X^fB^lLH+smuI$shh)h{kE50$Ql-&?-;1UFccK4t#ekbfiI>ILn`9NMk{z-2^9 z!1LQ-3|FWeA{g2NUhC!xbWEVl7j z=E@oFBen#>_uEtAY`3S=_sX6fciZ`-n|$=C)4NbVV|sD96mc)10Z;A5QhDBp*Z7tvSr9x&uL=3F@+9 znfv0f-I@!>@%2MF4?Oz^A733Ow4vv+zm^>`CHb1zr;y8;(EnHPF;(Kc;NR{f(BhCd zfH0EooJfwA~YEHo)vJ{Mz2e?lblrLA%ri8p9J7pz&xMcy-$gO`oUl}sUW zv7JJ3%~MYJ1q5Q=1FhMFzUxjt`#n{J7KboDS!>OLb0oKqD^D!}LJZ<^yL!CTiINDfFu#YqyScDl;U~#!Q_xAH_ChyzjFHhU{Mq7AC zTOK{DCj6isOIvxcks?Ry76luldH&Xaf=cFtKRPE*q6@X?rlI3rbu_7%5k`8KrU(Aq zN&w1>{FPv8o@@gPcpEKUpdND92;f{Od!Bw71C%bRXTzWZNH(CA#e2C|tKw9IPn;b! zM_#ZFC^k3+>nQEu)9I=|>ZgiR60k9d)qOml6Q^rBm6K><3!f7glFF2uWUR$cpW+yQ zNtfi(xEsh;FCg6+tzFqz=A0sb~=fWP zt*QxiDoORQMQcW7a5nKGO?b-^g|lE5CJbTxQi%sCzL}1rpS5?@ykCS~3IAZ!=j&+W zj>IuYTzm>F+*YY(OT*1dT(*c~Ou@aFYZUG4P}Qi;>*rq$Wy@|=OlYL)Ts3GT$0YK_v?3<^3e(BBPrNjsigTa+Y?<^r}(y$mr-Si)Rs} zRe8Jao-W`{d&RHl^i*5imphR1`5A)WJuhWp##Hr2O>3%Gn5&;xf^Nu9rh+Nst=B@n z7jlh9C8nrDt0m23NJUtRu3IE_g3iv{N^SUBS`W1;t zDA}caR%|pTd8C2v_;Q&qN_P2MZ&ey_BC+Pgk}Nn&DiRKNDVB+yR{0$WatRNn6`hQE z0J9||hnugFC`&6uZXLTL7YTWMS9M-ip!-(!eJDDLmQ9bZUaD;z=;0?&xh-2Q23mUY zWUC@?#?WFOad+cT3ucnOF*)D)TUxiGnHLSO=~5h>{ZA zYMBX67gm`GNo-HNE6E>?8*O2EVY=1wyq^I5V~eTWT&ZuZlAe*E=cU#uZ!G;E~X*#6Gxa}4{9MX zk=_^0DEJPZ@`=Sj0ult{hE5H2*ofVgx%xGiKVB*bX@Is5H&{8I@8t_O??ZFgED`-m zjjN+Hg(5A4P=#o}BE@$aqIxw6n!9DbhIC#S^2fF_6_EM?Vbu7NUSD(NXw5<1kXLDX zdzR0_+^v^NgBu((nY`E^7kiJM#Zf=8Hj99a=uIok9ME&h_RZOe7vfL8ibu)a^m@wd z*K6Lpk8pFIQ8JilM3{SdVAZJz)SI`BAf+;>2UsrvF;xfR+qzjBhu>=Q`z`8cO0^>E zQ$BuK=foiSLFuS)f9Qcttu61{XP4U*+BAWVQPrZ?0>tr-lF26GffqPjXi4VwynVY~VlayXF_9GZLuW$Cwyz->!LRG=#6DP%?}%s7 zdD#+9x-Qsu&{|pY#UToK+R)}Rf!m?F+^k#g%w*sBx#w!oX}xS~F}_6@++yLs{t=ja zbyE5CXj)T~++?qMBGMB=B|&bquBr|8MFCC`8tw5DnK+(mTCE1I@yk%XB%{zydk**G z-1I$U8xLRuG(y9a-(Cnmhit$36Cf;y{XBos@csVM0)<}uFD!}S_fRfge`j5YF36G8 zFb^2P=IDF~otSBb*F#X)kUOIRlv{|_+FCd}=+`2A==o+zYzVa^-prAg1AHixZ8LSx z*EU|QmQG@}WTq5_rL>NdlTy&lFs+DyLyA9^x3P$LhZdA;>wE&5gjGdTDbb@;_X&@Y z0l)V?6`iRQA-(NAnQbjVu|`TL@2_-{Sz@#&`&ID0@R}}H3R{~duf>OXLUYu6C_DJxoVQ!!{8!kmfV{r;C8xLMqGzm)7y z5d0v8tu21h`;#L%XUf&;Ngl0!=xFxs zD6W}TsyvDvA9gM)kzG1BAmtoiaQS}Te7=4D^VaIvLe44dP)JVU{rZAjLYCx#cnI$8 z0p**f(kc}0(sfo*vK()-%Ab-3KMa3%D&=8C?}p*xY2QJ5r-~ju#x>jN z1;WbYg8a8r-B*h6ittk!wyGPhD0n7IVv6y1I4~52TINQKuV|<;K*(($N`4S#UZd%~ z>K;HR`{_x_?FmKAvL?een`FHU92w^z*((ky!4Rz|p=O9yhcHMlRR&}D@y>+Kb=tY- zaI2Erbu%f?p?4RO_FdzhB6u_|xh8554VXv0R%xmnRN-~19M#KpyHSmDxcAZiqVLzL z5hF&|k9HO@y&os+YKlsp+?S}~9bmdDQ1--qSn%e|t=!D~*Mr9RS89e$G`I#H+g1=t zO@v79*DPETy6-yAs(wX!G4_mS;ed~Lw#$q)chHcnx|a3*H>j7swL|AF-|QF8%Oz-- zC=7M-7^%4&_+`ERbMe-@I-LH7gB)@1{Zrb0kEC=-ubLMUUr6No?w)A)f&TF}8b zlf{EVCExq+lp1;8&vAq0t3YRg7HL7XjLA~={p1K0sTD;xd7*?DsCI;d{Xo@;jPeY>B2PY%!6n(Lt^kLm6a*+N;XJLyW z$I*`?a1}zB5v?{9B`3)kwvZyhg3)9i(OebC?t{8w6@|3O`tumQ>b;6r6qn9c;K=wi z%G`Jp&m~SqR5=<^;g?P9FlGO-uz)JVoE_`&Oq^#a(UvlVM8^2NW}wR%QZ6RRclM1* zL=j;mb&G8;=)Tvq4qGboK)31&i1%;&6}!S=FN1IJg?uO#`MyT2C@^UQ*NYHNsAmO? zb0D)+t`p1Az{qo9)Isgs?Fmu{Qpbe!bJ}2LZ&Kpj&0N8t6UfQy^p*KKnJO2jDiY1@ zd!n_Wm%@RJv?KX^o#LxxJ!?og;l&IsyLYT0utgb#)9A?3R197JJQE7@?qY~36#cbs z^xexaY+tnOGrGm|wH{cfSlLNutH4`k#)}R+MD`xSmTe!dl}|Ryg0Dj zNO^Ui<+0kpDGxzs{(+7aNlac0C5%wb6H zO?)M8R%1ig?WONctxw6;jqGadhW*m`2?30jDzpBjBy^Vk{r3`M^vO+w?g5N$QbRhz zV?l=Bk7V3~@;D2a3up}-G?MZTv~K(A4>Fs9^d=A)Bf}oGt|i)wFdBo5PPc6H`UIPT zSoT<=4T~ULQj-zDk7e@$qqj9I6uj9*jr|BkL2wMotu{?(aoheR7N-CMyA4*AG&%Yg zlt#`u%JZ#hS=k0qsvubug3hS zoF<8wj?eez2)XFp;eXG6zJMntfcfX@F$HH+5XLLp5xU*+KCQ`&3wyytO$^=Z#eP*{FF{-$ z5=Y<>y~sDj+wY@#+1_NO+)mYli_(@#?ZmQL@u$imrh-j2P_WgRWXCu$PBB zpXFTqy)U%CgqnwGlOCIj&nLVG0syaER}96)?$j<(ZV+J#7l^Jj8c3U9*ssYG5xMPV z@-fF$>_SJH?`1m*-b;4PEAk@r)0M>F%2sf0u{N_Yn&o5{IJ+ViC?KPAhi0bN8%dK z#LkY(OmMY8Lj3c}xVL$QqG@9c9%3r}RlG3_wJ7s<&s%)|qxl!2|BE3r@cd6^KkG0P zSO7$NI0%Rh4yCvzNBjd507Us`!S+X8L)1~%@E>|_xS)Ud;IPHS z4;BaUfTRE$(gsoD(j8@B-}>-YWb{4p zh7xS^>Y$r_@yJ=W5-@XZ0dQ8KRHLhzD*pHgmem@atd5}lJKO?l<)aS-lXdK)vbl2} z#3N8wEOzvwAH*KFs`u;CBYKuB!fDr)t+K3~ygB5Mjifx=b8@q)S`bzJa3YFIN*yid>kbtgK{;Q2(d_xPk2!4IV(#%BN>;Z{ z_1O{+jw%8ksYJ24o8li7 z5OQ}AvK`EJ>96{FzSg<9#0pN!x6f8v zfo)!|zg}-@GJOj@vE$Hm(&OgmwiqIJ0iBK8?*MY~>8mc`mrQu4sHxJ?kIE#@U*C$8 zoVG{8tH*talU3P}8y8=9+Z*4DpEIA0%4S7Iiw0$=aXHl(TQODJ!tX%n)r=r*P@{SD zeL_sCx$#H^10>l(%JS0J0Y3S_7dtAcp-IrO@z^^^=?Mn`npn%oRU5<5n>rNnT+ShK zm#uxD(7R0rL&G^1qiE(olevG|(jPY|EWJK{-|b`9Qko|oj4vHRa%?%{CbhazCL|2P ziEOSEd!iA$Z*7;8Xj)+RAoa?MU9PY+?EY!$xD`x3HN9VfMRs-l3P2-|g1s#$coJfi z%B4p*5ldQT`>NPiWjS3w{sKKuYUicxG^;S0>@o8mQruUkbxswURzwV*(Q|O&dAn9K zdpozNcrN~}sf=HSOk%xDnMQO2w6*X8;_bZsdXv|YbpZYTcR;`20=QTF4G%(Pezv8_ z8;XC_fIiaoV|(21)1LtB%jzRs8*%sfQ+TBNQ`^Fj-00sLo?OdA^j^X}J_Uiq}v^zDpbW||~ zc8zBwsa&hi{|Gq%8KdryAtyY0cKANF7}MAqAQ#hNHq~PLQ}PNn;}j% z=ba`iT)zZpd7Les1A8~DP}kDgShmZOY20V3df#G(1NjEjI`ln!V0IvMI>6`XAGNok zRceX{zQ=o?Mg2J4wagChheGy_M%RGgiA;u+31?&BfDQZ9YVHBA7B056vh(_PA~ya~ z>i#saGK5*3>U9_B=c0%_m<`zVgMAl0tTO4OH~SEP9qH9zEzN##PS_p3vP>24WFh;? z+Ths|A1cWZraDnBq#qCBXD-EPK;VzQmsWl|@05T707oV7_w#O~(?07=q;cgPK;T>o zAv}lsX`>J%WbwrHpa9^5)p<=-JG@wuBJZ2LCpl~8!(|=K#TKHMH=IjoQ~zw|U78?U zbqMJ;VO8PzWM$~?m+^wQ<{TU3m7VVDB85z8FYt1HRN-_3sW|im15JrpJXOkAHq37w z;8J94ySS_246tE&>D_xvSN^I!^o!|>u*6b}zI57^s-z2Vt$H&WG9xr5uOP?stq{Zx zk?%kudZ%AM;nS07yY9R(L4AkhDi8!Z0yin34YrtK7F2*#YgUVDm#TUE#34P zh_hFN?-YCnR~zL}3+wI)ejUGE%3&(LS_qhN9|HX8)9RBP7!Kh0~r_p+Vp74+#{onD3jQiXl?!WF&R|@@Qa2>!^J5wzqB~!gN zjr()fKny4(H|SuT;o$cwhk_T*8vQ{nNkI_8K@z)In%Qw1B4SzDDVhQDgOK~I+I|>s z#zl5=A=z5EkfAW>1jM}OB&8AbQl^J+gZ7gq|dA5|7jmwduw=EJBb%t=h}VE zPP2g2No6!-G()iv8{)>DIJ`KNZ$;wild8mJkIRMv%3+4ggLk{BhjsJOw||5}tb;MCl=L>$>@ZFPa)4S-!O}-JSURK-1g!x>*vy zXu}%=*{RKPV={qQ3oH-{`mMX%0BR^u)`jUETCpoK!%~4OZz70M4>ECy7^pG~u8rZ?D|8NHnr)g5{Ts^P`{pgS%MR{4f zgCGdu0i$9-^9^LFov+sXcF!P^AzZ!c*pKA*u=HR7gp&9mB0vUoARIMA+?20X4byD!MTj;(=M2(m^Al?1_R67%meD<9`l;yoc`K$6HO951j0!Ivx^1;t# zK8&E?@(tg%TxYg5K$roDWy$50{f?YJurt31Ncl)W2ZWYQ0R;3ETSo!{zW%@vp@-W@ z3w-@IL&Sdv=JPL2Zwnx0KlyX+OM@cn>%@cb+{OE;4cYC z4){?rAn+c}4|M_pf*-WZ*DMmRbko2*!VreD+ zp7i#uu!oiWPeLmPu>;LfAz=5a|JXh6=-c+B~_C6F9 zTKX%m{v{}I_+K0;NDTJi>Y5(MkD%Z|`)#_l$>&|eb4@;{p$}G(m3dDxz6S-0_m0N; zLM~X$Obr1Q!J`4u2d3Ndy(so~0iNSgUjMf!S>Q;!2$9+r27+V$%M1^Lf!j-wCyA!M zAS;(U(wp&kPIOoDD~c(B_ZmKz*lXR_uCQlj8!Z?wGEdrld$I*FR%&ZC#V|3tI#lUw zcBSm|S^JK1!-W<9$xrs9O=x}XV6jiarjK#fp{APUYjYK0oW84H;?i-u5{0i&sO{Ll z?q~8nMngbf`6ft#@R3~a?%cEFn?2oEv>Fzcr)u%rd5lg1SLYrC1~ih~5jC8vN4{j~ zZme|)sPQ=cGIVcy>n-HG)%O4|Tpfq@DCz+0vIbBwd!RcEBKX6lDGB~d|DFEp-(9cC zf6sd0An^S8VsrX470*fR`B!EQJvd~B9L;PhU`?aAQ$SsK{{9(!zpns#c(Otdm2t!j z`D)po4P8h2j>I7Jyu}PaQ@*)~sC}=(9YB5L(t!9L43sy{0=o$!usP~wvz26b~ zYpDLm^&`77>fTuF6(57VVT-=_)4F(Tw+2}bht@;uzw_>iv=Qdua?JMiQ2-lCB)|eXVEw_elfx)DG6lyav|UCd<(X zLXcJ8LAtP`lOWD3OhFYq-H8yd53z43b4t7rSpJL26?TKkdKjU51zY)}Dd)ZlGV`Mm z=L@;Odzl3Wd`4+TRboz)o2y7RtFG!B9u(eFsrqk*{0d|8O%n)W3wpnN=6%uVLgYa# z8@r~{!FU7T$ZY=EqLquraXWTh!k@2X|^;53is#JSn=fKNV8BzkYSt+Zk9 z&~N27%sM2Ss?>AcZP>o#(-c1Js1ki^`6!SCqJe*u*x!BdFBSEF{3<{n>Hu8B`NIN| z!w(sMD+ubKeGbXD-JM|v`asc`E8=}ne*9zRKjl8k_Q0|QrC}rdXx_7_|4RSr6PtO$ z@|$P*GiLqQkPKL?9dQ3B{V+E&{dKY5A`%8y?%$5VeWE{(!Dj%dv^RxVWA0nbit7N> z<|^}aF^Z7~V0}BCTpiKx_Hq~mfxyy0Tn7ep5C-HIbZT(QIG-G z@UX$uH{yZt4#;AYo%0lfA*+++aq?7s;q)X|kd|)|?Ow)6Ij5Y#`yCRjl5xy-*Q~S) zaruuuOFaMX$uG4x8s|z2tDx`R?obe5usqO0J4lb=hv_l=ARqn8&a`|KzyntK^Fs$o z^5H{RcBbv0AHoN|>4yd$J|tgwq=7(aKn6YzNa!H-VESIKZt?o*Dw?_g(Ee`!{tt&D zB?CkX2hjol5DSR(F!cuE;nQgHf!H5=5HqUovXn=u0%r< zi0y~KL34%B&pgT&(u3*Iae`1b@=_fTEp&}bESnFl?~|@54x7kC&$PtLfCu~Z3$2&sn! z4Vs^cWPRtv)G2Bq=R+kU2$sxz_WiwEo2c|3Rnz#R7j@&wo?Cf7sXG*x=#o|4vi>QH2hT zfDSN%Z*2qagF^*mKHK7hN62H42+vRm#HUq!_!O?t9zY@f!XuG9>*>+?1;li8U^d_| zk^qjQLvXFsz>AjKP%;V=KAli5a5AoJ7$1h?aVQ}PLwoH&8YmKbigc^TwVfb5<40D7k{ZH^}r8p5LGaI>FdLC`GX_?wnZqrku*i^t27R7bY zcj0_diz%Cb`pA}nXXmQeT!THU!|RCvs>c$<`9j$%M&g6L#2S)GnsqhvkjxOiPhO{OU$Ml7+dkR-_PM5 zJ^g8K*v#v_N@AK4+gE&Zm1M%LP+ulRcMC`5-j3NInu2U*)sMtf?TYfVs#I_a*N^=H zq`OPNPNtGvfF&Y^i4+5c%^Vx(evve-TsngJtE2|UZ zX8TdmxX&ia#q)C|T~6kIkZdK9s0=}>U7NIFcB{RV>~35GkF+7R9Rne4Z3n1`UJ(r4 zYGxxhyKnpAjcpdDd@@TAE1M(_(T$j3%Zk3fOKy!*cDw}_=kB=~ZHQAVgYMNw((lJMuC zBRXkhi&~$$Dd*!NMTl)1l~1UxwG;5V@~IJUwU3zW=P_JFu#mmaNr3R{TJaN5IoP%d z=-(;LC6i=Ye#m6#=yE@owB;>Gaxm7928XXDqK|pT+MxiaSz|yD#~cCNscTe;4UEt| zrb1yo!EoNB2$aOrYQAvnlYG&Ltxd07rk2a2t)yPJd;587Y122VotB>4kB3Xn+#KIX zDtTd`Ue$Q`zB}ofu5Ypp26L*ax%wK)6?2}G0BtuWpAk!r* zrvzW#S-l64!qjIYnmy0HZKj*555M$c-3?v;IpV>)yJ8dFk!xzD!OG?HrtI%~uq}-Nj~B?DMV1!q~4L z_3Q3w>|t%QzV19`1>xr#-|!jE56w@k>6*NFJq+W7{$DHXWggp3kF&40w2Nn z5D!bM_Z?Sjqe%8MuwZf%)WQW)XT>WcV>?in{zn_3|N*0aAZ3ugG7o`Q?Ppaekv`m!GNKDFbS9^#8Z(keJzJ2ra$x$*4 zM!CYvduk4!@(vPHhJ<8KD5@jY2;3x8Sx!hCsY)>EHN((smhKV>420koO?`P9kI*TDR8%vg zsMaRD9C{&D-0~q!X198xM|&zbK>QHU!bRDHQmwK(lw1nLMk3Pvj=a*k#=CzzG13deWk-h-e&da9r0k?mk`gV@gA7Z8jqTtG*}R0Qhi;I zVpdJ%b|sUv2&JO!N7WzBw&BD$s*;;)$nKQ6Eo?Y$3QN#?pt39No;Jmeq-jl0+EY+tA-PBm#9Z)ZhfKe824QqeEL%FORGPX5qKRpPWMRhfnX2@mIqM-%^VQH z_F=veELaGy^yY{2 z8u27K#3pq^3tgaU2p47}^!4c!1}8CGG1u3p?@L{zAWmlM8psqt9n-QMEr`uE_u$E% z`dFZw4LNHJWm8xlk9EGh&V@SRJ)J2LRS;)>0%S&LmczrfN#;CSecP)_uU0BJR?9jX zQ$8MIfJlZpQNJ*tdasX4v}q$A5JGGFp|VZfq;H$+_Et|-MGM-5swP{CBL;t_CF2XuN>E3 zR!pL``$U|K;qUWOzIOZhh0XI?$!x*){vp>c562i5ntsfO+kqYP$1muYi+i$3vTkt|s z@JSHtyu3V|L%*Q~;!=P#i{)!Xi7W3lE>g+!GsujpKdQo=spZB25yUEz<(sm*P5-FiM_)>VlJHDS|BV5 zRa5MK(O!U~t3I*OZ~C;HgUobqbR`p4&k&kfIa(Zdp5I!x&+*J?d=qf#mgnooe&Hz$ zJ}-l6s<@z40pth-_78=Ue~kS9C0794Svt@cDLKTG1s~?czX4fT{-JsL_iVC%y0eSj zRP!a@dLvaoA2#N3yF?yw^NP3W9q5m1R2QMb^l_DMF;assW*vD1V08yo&3A_|&jb)u z8U8oT?SoP>-dl^GkHSAded6;65%J2=>PYOb0uk}SEQFIAJPKZ#e-UK@Y_#X>Qi?BR z_%Lf2u9TG99vy{I_rrna;7lcWeFe(zb}$Sw=>?4GINM?8A60 zg1*zUZp=3wLW1~9seUxhmwFSvLxKj=&K%5b0HSxWe46?_^#e(=O)2k#(|2p3o|$n2$v=@@SA?<}N3$SB(% zO-^9dSRgv$07(K?t97($DE5EZ8vE(|z0`1@iCXcfv;(}M5|D`#Nd7Pl`{{%~Y~y=> z{=1I!-(DpB7Jq${3)eJ8jF0NO(tSe)WvS=bzB3=qKah+4hP^_G$v4bRrx_Ec_D9&5 zfRcwTwB?3|Zg;DfE9Ddgre*zk?Ja7^vP`Mdthdq*&l`tA=K06?lw3vvP+@ETP=2E4 z9(CpvU?i8V+w&ds*SOK31Ux|nwC$kYYB9}3a&?ne?FZxa)PozL5Vb0fO^@ogTG&-& zo@38`Xzbb;YPG6dORVa7WvYzF-8|jm3m)F*^~H$4MAo&uv^;lGAZ@^-$M2$ro8Y_2 zto9Ad8n3-$m?qCKVIGn7NRCxtTK-trW=5Wq-eHd^n)Ip0?z zT4IuutDv$16nSiE@H3FuTBqZbm`=4lKWcw6hU1l4Lu~<3fzxM)7(c^s!nQ|_Z?`{i zHL}KBawwr*@Jic(>85%nmdHK4`=ws{6liV2t^BUbzQ!@nyL#J`WK>_?jh`;tZwkP; zMQD9|=~cqqndV6tk;`_ASRLQOk81rqaMM|fk1c@7Es@-tMK32KfZ{uJ^3b0@1m^H0 z9iBaIM~>#NOBn3?zuhOt<@Na=-N0WxSK$zrddE_3o__(uwkg^{h z>$qSepl)~2rXo7P(ABDRw|E~Z1P~8Ezz#C1O6Z!1YkgPW#zT*-~Hn=}=Ow z+m&yI^3E1&_uj60JC-UJ&7oAFncwT`;NY2>QhjwM>&ak5YAtcTXqG1;t@lpd=Ienp zjYw@^p7Y8?i9>%x)AEz4Px~|2FVv43-8Zn$3bB{po|p6bJk&#WdjIS0m(9(EmnF@o zvDkem!7Lg=)5&_3vF!1Rz~35Ey^oF?EbVTmotJGqUkIH zxij54g0Od_GD8HD={UoL9&}oUBObYDg-KPbF`kJi(_^`fOJg_tt*E6g(PiyTU_V0Y z#B)+=F3xb@(jp#Z`Nk&REP(KJ;^FAFOAmryC)-zd@!UFXx~R^NWA}RT-r4#5%lGfB z2QOVZuR8*Z!)`}g#ho;jUdWV_=w8S=u2^rC9jk4hACWkf_$DK@uhTr0?p&M^!t;}z zeSY5kf|ax~n-LgeHU>K}8%Vjk5bC!dB>lp@^3j{uC6DlkR!iGxre8;zSZrw^+QTK$ zf+#LPV+b8H^bo^(8b$I*wGRhu~W;u=&(*zkGF%QVMA zK#0w1pAtDjHBn)DBuG9&7{``>z;`iPL$#ctS7tz%QiI)J{_}H4JKyJ6uzWowzUVk; z0U0HK?(^}7VpeQsi|Z8xyW;3)IGP#lMO>WeNK1kdPK;nRDW-)7w~oAp4=<$`JADpmPBgSD}^-UQ9-bThDs{$X!Lr;QgmU|+a zkAXF}>RoxU=_+mNF(wj5S~&E}!g_oI>VoQg?@gb|YsNZLaPqEp4_NEVN*P_YvhL}z zXSLp}tLB;=LxHwsy_%sXp6I(AY9Q(!B5YlE9Hf)o}E&dc#PeD zyV(#a^Y!zz7xq@6WNm##C}cK3fJ#1uy3}i#+#I6cocR0bcX8^yq8;`xqCnlU}t|V*UgV zL~mNavEF$i92)~HHKBC(L?)u%6J)dN7$i_-sdexhmxUNLX3|s`-4|59c7x^FZ2Oo> z2u)e!CEkau#7Mf+du6)ePL(eiH*20y_m$mU7h?-hQ@!thqFvFG>bcS`ff_wb48za3 z$lA=;q5P;P>MT`u_^^F*vI~RDd%~(=+|~^@ zjm^q@pT{SEOfUM%@hsjoTXm)Sq3F!5EMaClO)Z#y+*oXmvC4Kh{?3V<_4zxSA7&F#@*1kXcNX?cP*qdNuj{qxFxuccH6hI2yn##IcefYDY^VhjC|) zDvnRKzLFguM!HR7i<~UhH>RQP7I#*6pyHyaJ8p%=sK)P3`==(t^6wV>8`+1CB}(Z_owcQ->{ ze%(Fa%y~lSOtj48yAU6ieY%cw7Y4};9owq3Z2V6fDNNoVXlMPJ2bDRVL2_;@OGRw+ zsg$y4BqOlaQe6Hxgq_G9o1v(X;sr4n|U)uA z)c0{&2%du#70IRIbDTxyd6%{arAVv7&j_yQ#q5qe2smaRnSu!#Ky=O-*hv{g(dlkm zG1J+cky{=li;yrHggrPT*O+8YE`GjU>q$jv3R8%u!RzL)Q0L0r-k0`DsL}|V8;Ts%u1mBL3TxVT`gfce^afLk3nF)M{$aEQ3rauecjlXc5m%U zq|Ec2dV4lL0&FU(PF98GEeDH?A|NM`kmpl%R#(%=ZN0O8Y7Zl>^9WqAA52-J;~nmBU$qpl%@nG3=dM)~XtWh*FjCT4WDD@)e#{qkS2^sdZCI-mdq-zj*K$~oyG&;` zT*p`I9fekyb$C=|_@sOI44uk^ZTM`S%G|clf|1Ir#E8Y(h~>@*!|aH)Agyd%FT67K zJ1%Ovi)x?D`4%nsR^}t;Y`NdL6B)RMy>nN=yA`1yi+Ncay51Q+wHyJHjw0cYptg(9 z+ae>pd=pNnMR62=XZ9H{mLiQOx-mwaIXeTd|ruu>dQvs&t$dGEPT266b+taJIC# zD^XuGf_NA%c$q9%Rcum;gYI$UTQMc`BvEU6q?kUUmM+2KLW1k91ec_Q>vaik`3ZNs z65I(BJ?Rs@E+qQhN`P09ce|==v_gAhK(Ul8gVBPh0aC0pQ8fsc00c^TBO62siWU{r zeNR>-a(r_RhND9S4OSrzjv?wwE)B*k*<#L)Bv;d?6!NFkC#8^i$I*X)3neL$TuahR z7q3yki$R~#$KX1)z-)93+J(C1aXG^apwrhY3noS?K9LSS>bO|Xe}Zm$m8!=lOfp%m#tJQ zEX8XSSx$G~OW7XM>(|IkDzUmNc0JN{7y|L(}V$(s#&; z*+AK|L`XJh%`8k_hs@hIgJn0DoKT7=D}#9@H{f>oMn=Y@awH*^Jhj#6WC|P0{2WYO zhgu(WDsd2A%%#JDkg0M)DFIq#^TPAx zP<8Xd&*pr^pb~L_@(%>UwgDFu;6$ht_+)AAcIkAU6C9N>VNgbgD4R?yV`M}coy?=j zkPf9+CtM)yt$^mt!t~|oaav^FeUOoVPnVQWA0a9ngv|o&>A{{2r4!1--hU8)4HV%g zQ6-FI;93N$uY{j@3)e)!ISR;IkqPJ9pimrKuocng*-Q!!DAJs00)jhR0sZ8hKO1ur zr=fTusz7y)`@~Kdgr3K#A?zvw6Tc-euv{&5AoV%9`~)pOjpW1sMYX*H{q1WeaTIdDSllbbhgl#8QGx2TL1p05EG)I_Dg-;+tLbDiji?8vV%58rZLGwAq&;0p3-<4?A3yx zPJ1gI*_vW9k10&4X|0W`4GFD1S<|D|)W6&`gLP<{Effkn`Dotb(aX?Bb19GBXrPfN zYEv8Px>G7&b=Q5Ewm%!(_&l$9Yr0u?r?K-D-TiWYoG?DTRQ4)MzRAatxT}0|LoKqF zM5@Nl8`UgSamu1X==n}Cb>Njf#w%+R zQ;;ddmFp{%?((VB`~VkoBu`0CV>EceWc_5rLi2Ltll>^VR~~T0L$w=kN=53*P{^k( z(lP6t@pqLI0v1aJ>B_u`!}DZ1Tk;x$o;5UJ5uE`JonFs6gP(QAxCV+POY%)7r^i0x ztLx(L>bn2DD_t`Jq)ARinTk?`$tj7NUWk7~32@m;23$wjz(GM0Jrn|hlaT6*p*@pg zFyWP$mS-_-Owa5no=|7pQ!U7KyGCZhMp(y@wQrYeiQfkAWN^9UC zlsV!}7RY#jtV?ZRxTZ6=uruoUK*5)R8pI$&&j96GgLasSp+#4XYc7cb42H%Wnk%q{Y(-f;eE%kMSX8f`c8yrtUiRxHHL~HtCl&TDe@xAF`#I3 zzM<=-_%ec3d;RceQHb+^@pYmhNVQ=@B%Gt_dBf;f#C(d*NrmLy}>P-Az#)L2_S zOF19@!UzU4*L*mmLN(o&ZqOrPa$%_-xP7@M$Czf`f zoC{;KenYlQIbbaU(;XnINykN@y9)~>1vC5e-;nJ;Ox70!STPWlM}AR8m2p7vk*eST;c`cz?=3WV%+5D>+C$OUR)20hiLKp0ng$d38-) zN(u7i9O`9b@XOt%M|)0>R;OPs6^;=pJTA5-a+p#Xj4rxy_c=s?SM^%&8k_jw+PKg? z!IWEdBVQ>n4l_j$B(6z|7ceUyi&o-~5pCcI^X7^tM?JNyn<@&Q7WSMLGaaO2UN{~x zc!5Dwr?K)advUO_0{tT@roP7-3{7~*0aycfcmsmByTEX3ZfCnokEPq-)GIFOmj+z3 zu(CvWD;M#H1%*@8O6!$!T5xM$PES`(JzREK+4f;AcrW9Uyyl|3>5{AGlJlvhTUVAm zB9*=(78%6Fi6jyRJtI9NgCVG6Lw>jZ{We0A+ z*@ee}+HJw4OV)ny>wQbM$3>N76%p1ew;z$`z928_Bd^$BqTXtd=V;8(p2<3O+TKNx zoc_%;T_?YvIL%;NF_lJxkdkpR-1^y*fruxAr`GPyKf!t37ww^eGbdCya*Ertw$On5 z!n0HSl$ML@;XKv~^BJeuw9n*6)cIyjLu(ggzmlu(t$d8At0H|zr`+*~bfwF5eO@>I zB@6320V%=DuZxu>3aO+fT`U&&#a?+RVWdoiWw~Sp~bThm37>7_UtXthm*o)U}aDW5g1_$#WUu)7#Gn; zXk1Rtj6N4KYqlbi4@4;g6;IS#Pc;ieu1QaZAeH**{2)9gL_CBdgaJOM%EMkPB3a(9 zWtARdCy<9(aE>x7^$?KAAkibqIuG4&CMYcV%KD)S&WK{?Ts^iPpyR@I>e;~AXKkGy z@LR_gjEaI#BB;l78dxpCL840WUZf)$_l-WDnhqId8zETdMBHiE7lNG?Js4$a?hvy| zlh$*7L5oxoDE|x$^uZy-?=}wc6eC*4LNS1dnZdF1y?J{eHMgE0KT7>f_=>8}79R7oxJ| zAp(iVMG218cp{6K&E9k35E$0mJHhzpU3fv-a1i3u?jli%GR4{BqAFD94a!t#E*LmA zc-3;|GwbDLX~PKBfa&p*mF78dY#tmo6-!jx4>M!0AbrAuO%#S$wJGwRrg=CjC=xxs zB)-fdgcf;A%f0I0A1er&XiG;u2eEk<5HpGsz9w)9)0W99rb2g8O)S#vQeZfW zQEKd3h*wwm1;EnOZFa35Id>V_*(-IaBmDP{pQub$=!?>vacr2>sFm zwb=!irL@3Px0j?P?>O8p>NDnFJJa#?~rV8D-Cd5$n^fyp1Y&Gq#NHd$$MJy>*ya8O54T6!I5@1-DtT(sX=0vA=dHSk8JDTY66F znRKD(jO8;(Yptq8brcsom8l6*amqC3s`)Cv(Qc(mv?;w`=#q~b>z5$-c$u*Ivi*x* zwv7`$(2dBq*UvYMNp?A&yB?wDJECnMAZ!?N)GRbSo@Wuumufg< zw!ri--eNVi{{D)YSvJ*e)M>`O{DaBU` z*{J#MP@irMsHV61(xhLDX9mC9UM5j_YQJuDQVM)0lLe;ZBWwgl7rgM*LW26KqSIMC z_(zMJ{NJKJFSK>Vy}5@=-YtyA6nHSa(m*q{2s(oO42cb3?8rCjj4niCrMQM`od|3~ z{3IUHOlHZ&WDvz(t3PfjPH?hahxr+WSZ}EjwrHDt95Z_AJcX5XzY3GlFjF;B$5Upclu{jy||q1`P57)Qc=Nj_e@ex(@OgOiT$2 z4bP&;8?lt=ivc+jw?n#89nL`dhcKC$+l~IXiw4nLsn(^k1^x^-zL!fkMl3&}*+9y?sNk7tZM4*pQv<#pwMJ61XrpGp<@w<=)-ccL#~at zQ_rh2;&S!l_kU z%#TLQWWzs`SS-0etd7MBsYn5XaL@R05eDA71~FckL^;b7Qkd(+D>0pT3>9TJ@hhT` z*F)uEAcZ)IAW)@zh=i^BlLoG*l`I|-6bFrDj^^sDBUFuD!dP%_lnzV6|PpCu=4gFJ_imi>4Ut1h&qrch;%IQu&Qj5eSY9XjzMjy<3V&A3x_^W#D$%k^v z<5xGZ=e#uZ*jwf}2ER`3GTuqhdiJEDKfYxtSM0}%hk$S(T8gZ=s>XU6muucgi%D&K z^TxA?Zvqx){PK;7I%-YfmCfY2&s}c2qmZcPw_C5SZQa-2>)Sk-schbSek*Re47;w$ zG2&AkVtd9oW_{;7dH=g}QaeoU@#K;dKko1Ghm9fND!vu>v9cKJd4R$Z`yzC=b&mLx z$^A$g=#RV5XjogM#6>XiWWtCUCdx69B9qSoO$&x^-J62MQ1R68X{@gWPCj~iTgi&l?brBQvt0$1r62!cSpjRaLmh~cj{1sJa(m)n%kqMnmPiZX)#*^dR zNV80~q==?oF8x9-&CVLl(AQe?A{J{R)ZbhBZ2azcb_%Tp4sNrl^+4DM1rujTVx387 z^*NB{e9IERX)utK0*8;W-)#g>CLU%V>&gzAVhQpb$?s4X-4x(K%RDCR3a>zTg|4FG zcPGIcff#w9Bhhsm9{~Ln(erNW1aKLL$t2)Z<3)9?-Ye(9udchJ;*5UiME@w#TV@&m z>?SDk^|J?IF->o>9z>Ww2%r{@$`6SBdZ&Z03q*}~<90ApcS$DoZDeZX$%$*K*4J5a z(Uy}!qc|#Eowyh!sMN~E)fAXATzW)5usy@4w==+0Txn2iEK$KFx?6V-?2J8D#~#O% z895E6cZv-q_f+jh$DQ#m8up&P6PQX0La(Hilfb!;22xl?m5cPYH3)gR%#~wK-CCI( zZB9%Nt>RbmG|0yDK%?fD%A!6(>*J{;xqmam*bh|qCV#$5$Rt2B!SfiB4Ji*oKMMPt zAQ948%Q_@Qsn^?mI}lGOvnLS4XY6LFCjebzB0+)%w{P8qU-!UaDF}qH-wyQd3qGUM z@oQ5APmNv6WRh~3#>N@sh!*!mfLExxWDLz`NJm9VRz^BP-Y(;T+6|C9Z@klo+|z}4 z9#{6r7$d*05VukG91yHwu_>QRj$j@r4zp!q7LR_V=f{r5v1*X@A%;l$0rAebH}z2& zI~07>T`q&sZ%vC_X@bfPdfV2E-oYg05Ez0k@10ZD^UYe;hnzRO0be`c&s?%5XUy~K zfbRx~&Gg&r$9u1dUyG3V4U$w3`s?Ps_2Quw@{Z=YjxZF;l2I2w;|)TrYpIY3iwZM1 z3Gm|J?o|xePGG8L@~h}98j}Z?9MyUdUvnT+3_<*Gi{JwXy^^n5$qrLc7gPC22RcIu zNYa%S>%lD6-ZX6{^&MF>M!$wyYU`-4fus-p!kim&ZW~v>%qT5IE2iu27TD>hB$e3g ze$P3SA?Ka>$N=*-X=V(RR@y?D15YSjQ^^wcigceae?CsHf_4})TlpI1*Yc2Cv}v*< z8O&95c$`^Fuo|jQvg!*XeaFMO((hz#DO0C|&eTGmh>Z52rz-9A8Q7~Ro{Vs|cdj^> zI7TL|OlGrrKf3-&X?3#Bx)c}UM_Ym%<3}U%?~++q=$_fD`lyXI;Eg)ws8R@i zL_kCP+kPbia9VQ)T;Z-NU9ik^{&Hfv@I7F?V;+C88Gy=x`M2-Ejvf*-qBwyxwIa1A zf+dPL&Buy75o)9?I$;iK&;G3IQjsKpvH2@|h*+4AWOY`v_I@E{bB{v$!xEj_cP8n| zl*a%)C1v$%$&ybYvZz{aQXi+g8=MF}+aIxRjW@d^o_*sR_~^-uGL9_ZYV}pq^$hd# zuA!Aql=llu-h*+XnOg}cRt*vq<=xKrDw(^UOYl*bXDSkts4>?pqlWuSC=qz&=`{(8HIp9R`l zPR~FnOzFbDUWQ4!U>Y8fH!{|;j<+8_6Adgyr0a<(4sI;Sc+5f}%4L8icUp{BA}>)$ z)0!s(%2~n#^}(8&pAF?4HU1g7Y4VsW%a668YYu*f?wrLh`u>O_QkrXJK3e`fxm;Pr zWFc0~s9+&Z%VA|9UdNw#F~K0tWHHe=w_q{Jyk=$bg>@J6QnKBs$x@2bV!=}C^I6pS zC^r;7YIrKTDU+w~4w|uh5asH!Z-@ZPN;dc&iw^Ws(s*I27y)b*CxX-e_~?I2ul`d; zMcz~P=#2-N2d*&h08tOHv-h``?j*_Av|g`Mr{5%vCquEK(Z4B_3F&e!`2= z*?ab1eDrV4jORNGW0ilKDxUo>tjy6E@~6Eqxt6DWa73AAeDPI`fz%u$AeoZfVR9D9z%{JHQ4SUPeMP!#5QxG(^9g)6zq4y!A9>HaLM`Pp%%s|ESFg{y_dHLI&dWnJ4W zYsFQgrfVg2i-kan}i;) zIpUOXKo}P7CGbOeW_b17W=OprL*BK2Qdr4P?uu@rMs!MWj?0t}AxOUG=QO;t2 zL@h$iepJh`d0_NOfXw!Q`V4E0#esk4-Z(~ZAJ?L?paGS)o<7WXkb~6WKxgBV~CfB+5 z?w*h);Ku&T_$*+Ltr76vb^0{@*U4uk?ppVCuDhT{>U~rFF0i;GmG;Z{?80~|ND>Ep zwtd*#avpqlg*1q(&UU3%v-!;MJl2iys7t`EtC*OmA2^;>$lkZ-$ z6P`0-5c*=GWUSxMlW#u~eJPozo}Mzrsa-h&247ftDs6kpyqxYEY-p4b7-bNGk2p4` z>2jcU5Rw(7vN~uRXH>`>i*CMZA`<2PTN9Wntdv|d!5NFGO~v0$K)NKy+{_THais~? z)++}@SvRVNRm?W3$Bc?LY9<}d-PrwEH|yr(%r@(nbBi_`)@#-_8@Ibyx0?0{krP44 z3N8Z-;7BhV!~Mb|41I)$#LMC*QBech$o4GogcCxxS$1>^>7q`=Cl54Xl6w-Goj_K$ zUJ=+t+7`wblAP88ibvvbj)Ogy??kLFu5ibiGuVB%>sGAX`v8@lQ=AjqVsG%7$>j9` z=nbF=a0#yM4=bylH^I}AeV_?8_CM+bupf*W#9P$Vg{GDqOaObP2cN9pupds^eY7~7 za#||kmPOsd**N^-iTd8~i!5(p)wJ_pR;+*!HXLY@B(VD*O#-R|#{*RQ&>p^pFQ zLUvR0noc0#&i0r0X%x$aEfUZq@>zr<%)d5mBsrM@o5J(80z$TtpSvs@;-96fKj6& z@W9=VXY$g#;?eEWz0nsxPJ3fv`KJ3~DiY7Q5$HM1fUcXO%>-ck8_ztav-H;nvI2=! zT#!=&a6%B-8Ri0SQ6gnQxv}7L;amsCI1vv|>eApy2)qVx7KR|z`(Dhzc%V0aDDPbI zLog?hQm;qXU(<3-H=bI9*eFiV^mrjrD|5v#NlWlzJV;FDzqx9h2hFB&o=+9QBgsnR z0lP4!d904-W%%KdGG&Ia@Z~4NMS=04^7dW?zsl)sMC_Tbe?eY~5u`A$HI#)VFFWak zxiD|y`f6b*kYUVH{4$QOsHD6`qo}ZM(}neA+bN5AX;rHDO1UKR;%Y@aSKoT&dr=G^ z2u($5qk7aRWTR%np>L!1vp)uV#XKGXF)Ku`&@wl{vSG7vy$fTjX=hYwtNCCtWUJ-m zpl_@76s6d*9tp#bgn62QZL=N1{dT(pOAOPd8d>#wG}-agTu9Mo%Sk_fL$9RyOWJRI zwq=aiW;?y~wd6Z}uiK?7-ZE{OetpMNeVaWG@9;r+KlF^vZeVWKyh^%g1Y>9DM-*iH z16T}b5=B*+{b8}E*OW+vu{Z2L>Ugko)oH{}4c($HG7D*_rGpFeKX`@%Wq)z=od~FE z?->RW8t4ol9~7%9YgiG!Tkza>MVxlT^E#W`e0y6A>v;ZNBb)OAXOTH?kCCJM(EHN3 z3=mEh$9)ly!qMC+e=QPD8{g?A0VX3_553N{Vc3~K#RC1aDPv_xm&U?z51aI)z z47Mtr4ybT0W<3h0-IWP?y-+h1^5RXqIl{Idfr-q}DU6?Q{DwPDDAh@EjHgT;4XFKw z5Z;+(28g}W5)yoOlHvJGgev}~6?6ccn~Q^BZ-D>;lw^w>j=b*-ZyM?tj1#?f;w4V{ zN;_;S0v5-;&kf2TOaOyPHg9_|5ySCo6QFc@Z@lP++Z|q@wK4FG-TzdbNqHtd`DN0f z8^2~dk~MUmgmD~4b2@|xoV;m$va=I^mYL0QT`{b;4G%NjD?$_l*9P=khsEG zp^EvdD88l{e7v@B6}TV105g}p>g-1n}1>B3%WOg2^KG|1)@Qh89 zp0(q$H1AWZKc7QLOHe5FN&DXh>G|@l4V7 z-jC&g)v8*}jg`^brXM8_eWfO+Nr~#ZDK>3lUrf$&Io7{7EVav$dc3T0SU;AsX`iEs zy>`%16T>FLz?p&0E-rXIYCw>VGZLLWw6=N6{+8d*Cvit4)V*4TvFu+33^JbFX)-q)8g5nTbF7hkm0Ix6z{ zJpKLp9(fhpm_)V(7Nz4}xfRiIk9#wS@9eRCNRke`an?Z> zz8n6S?J4O8=lAw4l_|S#pFa5J-0v}3nf?uPSrGfAUr^;PW{B3jIn(%HsH|-^Bm0V^ z(#cTVd(K?$k`>u!Cm&L=?&XV7n2LwA4@b*ZW~O~iVxv}nV~u6wul`_7=p)}~Rm*OP zA;sL|ZyF!l;&xy9QLH~9y8p4f#XeK@N0S34^^mgvLHxT18+TQ|P3U)VRad^-uyFk} z5fffhm{?LhI>vaN{j`i}lpP}DD@aa2=)*M69?b2dkC|o6-8f!?EK~OB%l4DQ7x%Pu zpO7UD1PB}@%UxT3%=&!>J;Eua61I6}<3drtkIKL7We~bnL%HwC%`l9hHPue$Fm*P< z&M!(6?q2LOl_4*}uQs?WFHbrm(dC?Vx8#}sm!@_u?j08Csa^5I@5>M5PWm0+?@2z@ zA18RIk%|=MNBc5?@-+Vq%P0)PB{|8mi1-alnQXY@w=4=>>~9UbaSk?^kMVyTiQQji zheSowjyH7yaSZPdoAc_ZimV;Kpl&&~leKI+aoY~3F>cUygi~Y<2v3VC7+{q)b|2)6 zF({WO&}u)yUtfN+#Glr#ApeBmH2pZB@!F=92k&xX_X*1#TsyJa(}RgFw*-?`rz{ya z#{QOPqe8IfP65Q>c0{kYU(*~an78lcz5hh~{jqf&wx`drk^4AyzgwrHcE>CS?HSUI zFWXzLXWzf5KHusag=CSbFYX5(6bQY7(S>+Z9vDAdqKLQmP!{lGP_;Vcz{(nUoKXfj zNOu{Rca4a9cCGH2xTqa=w>9pvCjqeu6TXPXM*}=3FZ|_aRAXM$#;!Mbyy%#`Lb)v0 z;_oe^Je{?6pp3gVUkRCoVl>$^Bg*UE3UpY5`jClYXe>E&J$1`Uhx~wI%yD>j8@Wpd zx{Jnu#5vr(1KgFze5X+DS)J~_A9czsdqisFaSF1^;D#K}W2Y@)SL2uv`P*mJTK<4~ zqN-t&XS;O1ajAC>nLyL zBj?jaD=oCB4MJx+bptB(C_O?*64cpiEUJM!jENJ33lGNgMAF~@*_}BB_#8zUs05O# zb8HcZsi?W51(=mN#eA;S6~#vYM3Ezlyr?EgP8N52eQebj zlw4D9S!I%36=blmfUU@hvR{U*sB^!&C%LB}rO!EeQX=_XLGtujeaZ<#VktWF*6Sy0 z`Kepg;hTx6Tf9#a%2GFbQnyG@zSf89!PCCIesZ#q_TyL^B&iM3NZ&Fvn7;?QON3rL z08vawKC@2W?sMaRSHa(_L^fGzzl|^WF%exOtHjH_#{OVwAvh^7)FuG)3$zIH{{R zqImd^Djp?x7expbt>s;p(Ib9GTim^h#|y^qODcYUQanIfGQ?LhtWh%RQZklQGSN^n zIZ^WYq-2`3be6AlUZZr;rF1!|bhV*$eWG;pq;#9~#AU%1iHGeBiHQf|X1C=`<{8G7aZ1y924|JVFBO}Leq0huy8pulxuZ4>*A&N zKf(l`{0}g}e}Y3a(+NNSD;zRvW>sqaS@ZEv7#b0D0WRPG;6ln@C1-k>XG(6}KmGE; zmFOS0Y|qUnjJ`jG=bT%|{RTt#TsL@?`uDQ(rI*96mGCPz9+#d4f5OmzA#nd*a_b}X z?Ex`BE)x0J9iZfd4u3HJDmj@ks^6{S{wo;zzb!e}h=ecyiNFyjKL!6@a?}#n`2Q1z zUKc^TfT8t7X@Pj@U^aJgoeKocxAdaqE@0?`Bh4^@-(YCowh+mG;vT|L4FK*zf-+j~ zFYci+vgbd!hyQcQu?T7wUm$S0CyzkCA#nc)L;q*VWy*p;wP+LIo8B#<|A4@anr$^7 zEjGr#I8pg4dHws5UUfCgvmvP&DCf9u{$vo>Wz{XuML45tVgR0N+AUHfZFD_F|@D(y2CDlvhT>;3C z+IeyGH)LCq^P&dHCs=(2aBtn50yvHW1DZkLR(U`ZpXaaWZi)y#%5!#7}&YhxoP2LWB!wqxVVJjfFnW+sOYZ~ z5imCL#zTr@NtjQ+ns!E)paUdCo?GUlmt%@3B8o=-%}JPir8>9c2_DWqhg%6hA^h|j zc^ZXleD?xw{dEava1k7twGsLVqJp|5YnD_(pY|1w9KB=}twsD%l0tTueX5b)XL{;> z)n_R6b3`9sAoSs#CblLCP@CodLCpPCo0pgHW|MMu+=v=tTNev=cD{RM9*cD#9k*gC z)f)3Ih`FOdvsFXIM^*ztciTJ& zPhw;gGjL+$1DW))bstsx#p{Vu*l_Eqzgu7khEd`nO@g>dhxK6(@$l!NLJ;L_;Vu!o z`6$%eEBev-Kb#D#`u6n=@ob3Pu`0RBfA+#(UJKQ*5A;~4U`Zr zF2j={ovB6napNZJb5IhQ>#Fy#asgNU$jv%HzBaPy+kjdRbnLbW>4h^{m;~t|Yy;U*Aw~<=AvHg-hSb)lGR&)Zf!5Bnu6BOar^f)EShI9FfAa`Ty^4QD&t0UMRIe&=sZ_2STr$qs z6Btr8^Q{%e_fks$8-GAQHn&R7%FQ==1le^GxbE!a{U#aT@Wt&C)rlm`@VUF$t$A)@odCkyYXmu z_y_Oj_c(6G`C`3`1zatx`GojKL!@ZGji^F{oVaxK? zh#XA1e&|MZ>HgOQ4Ygr4BemitmpMp+#g+*cd)JRmx;&t)9&_kX*O`#y#J&c@j!&P}NtFQW6G4Ezuy2b&QDMiN?%Ap3_a#69Y8AU97&(i~OtsvFy7;EEICdOiO%DrXF&$Jc@XG!-Lw&%Lh zPi5WhdH;dueP7&q_pG0jLvz}CHg@r5J~Mx(bta0hE%yEwmlNDU?fKv|L)W@R6GCl| zSb7+o5Xpg4+xs?i+q94VF<4g=148Eq#loWQ@g>LNPM0T;6i$WRAXKJ>F=EB&1rwL^ zc!qFL;@=38t>=P=fnUYVLHSy`<|6K+tYpE<2uvdRMOOo}BP1D^2ckr=KnrjsuAX@~ zw9qKRdVK17WITmGbCfSiq&hqiDFb-ZAWv~ezObgm&x1V+{!8KVTj~AF!{$Z(F-5$b zY-fRA!mQ&E6pHC9EaJgTlw!;;$hiv5Vz9Etd68iom?c)mtNMr7!5pSTc_DVVoH8x4 z3uMgLtxKL1u|FNRT-z`r5lkx1oZEb~S-UKoZPoy;w^b-a9_M0iLNrdA%6n>Bb+a+0 z`h$h=(GJE$J(7exZb`_`3~=7_1|e!{TSck^BSyJ5CYu< zUOFpq%|UbA1i6CcXunt2mYuuf{%Z|h&YXJ+bimB1;$)@6AEcqO)f77zYo4!Y zX=RvypJ^k&)0OcD`*YT}xvvY_r3I?*?Ji}aV}D1z5ZurolGQ!dIYjtU8FCgtzN&Nl zb@@Y)w$=V~*x~w|4*|W0Tkha2WbtKM*;9Rq*C?fl~ z!V3j?n<{q+lQ7^<5+fhI<`IsJY?i;y2#IXiTP)fN(inFg zZ2GnuY}JND1k9Y4UaMwgXx!`D=QHQmPJC7Kudj)p7MI)C4;ER!q_Q$M1;3(Y1Ozv0 zYg=g)9x;AU);uEH-qIA}-B(eRzM%W)Q*WuP2>Ra^^jrRMrlNtmK(&9>GY;sgch{wW z3{mr^#U){n*Kamsiu5=k<{H3tepk03;1(4vF;05!Pgy`rW;1Z6j_&0EXR6QH-(ZnZ z*rh*~+bKkf&?KtDSSCEB=U$0sgcy3Mh}u@ke!3&_-;&Aq>@=ZiVDAHP81H(5Z1pViuD8QWW1jiqdhr!tfKOS9e4Vh_Tt z%WVs4kZKH1oA`FxJ4(#H2vC0$+nS_OJj0f2X>v}t*mYNa=-K>j7vl}%Fj8yobH7Zy zMWVVh9gpuP_x8U)5k~_iwNdn9dtl>q!_|S_u8XuAu zlX7tNf@+8d58t>lPwvdvK;X#;Pn&j$4RLDFbs6T!M4TYH*k>sSJx_$SM3D?-#4Nic zL&!%&vL)1L4I)wzi#y0C3sreNRBOMJ1#t>&mrO^VHQqe;LL)i z;0Z57vrrP{3-|>Ln1u6dTvm(F>d!P7MPCFT$(KMzNLN9P2d1p~tthT=Iz$l!g_3TD z7&gJa1FiurgV}2NDrVUIHa9he5EF%oB!h^Wu_XM>8hwW065*w&B1^Fj8P%b>nOBXa zV$;kqn@!kLdpHKD%>_8=NAEdB+b|`d+tTKe*=;rTE3Vd(^*!Ipq*J7u1_=q5UVN4C znQFvQLY;ah)l3$@9^b>1SG?29R=a*7AbZw_*AEEDZUlMlzQ-4Nvn!18O_TH)b=L5Q z{#}>nxK4)RbarneXxaCN*_dVa`|fG~($1hpV{#3lg8f3yjZFoH^iWGm`)%}ogQR$i`#Ap5JNg1kIf@&i>c+< ztNL&th%YRd7*D7*ZSz=QVCe@#r-)z>Yo3cpURF;e86v2uq#tYit{-&ko?S>kdev?j zh^Rbsc^Q%C{XknQ>#%dyA)C9xiqnk|mB!Fr2fmf5ywD%EHu1L}A64+m>HUtZozFa7 zf8IC9HUBpAfU`V*>(4U$b1*lKE;b5NCh?~Qt>~R!wywzs;g`0q!4em?uB#vNuSM%s z_wE}vmg*>gyO&vu$CIm3%=!CN^u}wfwMRpw;upq3)y_uF^H7ysTfQGtu$8?9sUT|M z0`JJL-P(U+92be>&jh=F3Or3B98s%yFGD@$TEi|ej)3>?&sDu$W*)$}J-OOEt71i~ z{n-_`Z_0dxsQ5qX?606!mko2m8=+fcA6(8b?com&c7gk5%d|zu)qAU;i-^ag+082p z)Bie?5%kpmo0lUMYl3hUmH0S0Jp`5*lbh_05@bvL{P3P|I27X!U8=||CS1o4ONME{ z{#r9?Di@}q6Qv%Cdlgn7_6VcG^Fm=J$V2>g@j)gkmEmbn6-TV6F%RipRygUtQe?0= z7y76N;_a1eg*&n)^p77sSyAv26OEylt5F;M9FI2gQ9t~)ePCpg{fOgyya5(IqbzL+ z>I4)%#VntS{8a*;=H!t5G~E@CuPr5zG|4z4l+x7LYGe6co2oT?%#aOO!gL@VQKvUX zN8@C1MJ(Chltnfj@UJUusqb7BCu{k{vZg%r?p)v*Wu#V$#orB#+gyt#C70v&rNHwq zWNnC0xVpxVS)sT<@BR=zK^%*GEiwI9IG#|FWNGc0@j^7-=g+m4Vx3(@3z|uzW-lvG zHl<2(0qx28eS>M_WL8gQp13Q!*9ke0-q+@O`Mg{aPG*nfJD;x}rIk>hKC6q(7%n=O zsgaeZbe2BpDYQt0rjJ)!yS1>_-7S5b3f%-|{CKNIO*cfVNj&KJeDxA6YRw7kL4bEf zg})tbzU&3GoG22`zvCvNx3Yd|IWI6hi?KrBKAQTmJGCmM_ijg*&2F9%7 zE3)Vx8H=dpp99r2a+Z(Rp>8=GrTQ{74AFsg^M8^T5%i8YnKAz)XjU;&^6S$zWzpv@O)tPLifCXl zN%G7I&Q3v8Hz|U(u9Bt|w*$}1z(QQtb4>4|-WwI1hLR*KGL^{hBV>=O09wvrb;uuD z&X`-+SSNXnFOkU#no;U$a9)mgvBCo=nAcKUPq8%0gr(S+wxw%hVEXu9-16vzo1UEH z=I)-V+!jtIR~`c~&!V>6u(IhUBoCH+xyg0a$` zhuCIG(Wk&RUa9(nLOG;{eHe71t#r&l@~K^2m07WWshwnf21)I9DANr!LTA89I4qkB zYC#zr96Kyu@KL&HcA>5O2}J+JxY@r;DZNZyzF^#BucdEq*6h1CUORmR2#~S+sI}iG z(@6V7zEIj{Z*JJ^MJ&_&QhNWkKo?h8D|3gx7}{ylX8 z=FeAm)^b)^jfNi%`yr!D4MRN@Q(!{Z8&3B|HHinL_)!M<-iQj_R9`zV7GdRaJ(j(X*$ZjlHX@RVX8cY=t&cJ{vU}_gobWYXAoa`4(qad7ZgjGo?C2=9r>}ZCS&< zN{rhiFJYpQ&RZ?+=xw+3aGLLLD$R3LjkOXChHSS>?B{S?c@#8_caS=+my45ouAKzXkr8kQ=(HDe8^a`Hza+_ z!s3Ix7%)WDJTkg@DL|f;K)BbSb?e8IHxksopkaOe(5j&ce>Zy}x$%yhFLa9@JNjA4 z&98lS3~_97_|m#??Won;XFjCO=Y#)|^een7r&*hOSjQ?nOAJ)vCLyk6P_ zOD1-(*W(hAOjTuwg`Y<@s2bH~8|U3Si6?`svb@>k)F(gqGKYj4eNg=S*g|YB2 zAN=2R&i*Br1Jl1#k>*mG;H|{ReQ_HP{aPn_Q$FppYXBQDMqy^~m!Dfb<3}MsmjQl0 z(9LjL7I=P>+*GU14fdU;sCTs0+`jE^8CGHdPJi_cLam=) z6=`qT)vr~9aQ&iH?PJJ_w%W^(Z)9E|+V2=_!d5KH$wMF^bsLIKxl3uR#9(7da$o}rvA#`>Y$?-R0w@69e} zg+Dw%n}-YP(Mt-7fnVzdlaW@@1B+f%s6~`6hG)fH&3C*{YZz4WdKO5v)Yu=YN3A6o7E!0f-}A+8rORG;3Z`@ea%WM zb883K(SKAF72K)rU==Z-v->F2((?La*&9)*p*-YcmW^tZA6%Z&RImL~p#vIAtHND+ zeUD2P`Hb_uETelezVh*)M zPt|a^UU#+A5+t}=JYJ54k!?{hP7i$#rE*lhlhZ?JCs!w-PN&p2YGGq0d56{fE)0x= z`mv=AFPr>TxP{;#A!8$8Gbbh&V_;G{kt6+YoG3QTr2}% zy2%`j8R?hlK@4B@og5;A{VMY7 z9||LGeirvtUtA}!DG1aiYMSZH${pHVq1FDb-;2@oeRtsFrzY{{5AUDD6xEbV<3?}M zO^OOWGpM$oisn3o;&q1b;1OA{Sqwdm5cpB9MaStS*i5!40IQw1!u?(n_;~NV*e$UC zO~+9Eo?c4Bn&Xk1F5h;jkjjzEOJvHP;0;Ut?Czhm8Z*cP6#lEbIerQaF2WH4{?RrZ zcn%q~t3b}fsqWAuo90apz`7gZ(kE z#lWM>-w}vQd2?Oi1N04;1{=<%u9Mw^dh2d3i7E7{Ps&4V{A&%gEAR4^UOXsi*w-9Q zz25G>(eS6X<+Hr9V3E{aT&u^&nYLd2@qo}ErF?u9*mrxl9P;g8>rR+Au>gR8Y=`2 z_**_Ej(kW9F~D~3pqZWtUN|=E%L5M~Lr#YiTFx*j1aNtY4-wKJ9LGf5 zZGO`WL%>`7;&k%Pa2_T;)IA&u9V$;I?1sD^#z#5 z13{ChX!zZK)EB8R^?zumoChe+Zx5^^M>*j30P1URO!33p^YF7tW;`^xD2RN`3HnZ2 zpF3V8jvMdrOi7NskZ3-!VcW}mwaP`#)uHTBU`vK&&!sG9tdjU;rk}(?#zeLCTyL2A zE#0YlylS*i1Nkjb3yK9T{sYgl886?j0+_Mz+oEp}sijn;>uu+|;_jL)qMbiKB4FpM zWS5g1VGgMgLt@6J!2E>9T-^lY%FN{|87;l|Ta*VmH2@s;^Z9YUN_MKrvmavg(u{H3 zq4DrsJGFB~JLURSwDIXj0gr}OghS(}>+YnWb`bcu3Ww-RwO2Ablf@9+9UHltQ1Ld5 z2k!IvD{7KDq>HmlM1oqG%92oJI7SWMbU{*(riJK30Ltw^#UPaO{IOei3KJB=z%$0c zKIP9~M&}O0pMMZ?1u4%l0shT5U{5Y^+A29hES% zpdnq9ndJ(DAw%`?Vsgx}2(UyO>}Zs_)Kj10p*}J@M7Stp8yStbZh{l~TyYWN^*n0) zlM*_vII|jf(brfA-W%Jdc-@JS*(s~*XExJMJrgGI1Fx|62o^w6$bYj@_&<*&x@4Mu zvG5f3{ObVR{ z4j3KYH+ugS$C+6q)Z21ct7_@GUQr}gr!Hn7gV03Lhu7DjP@cPF@w8LVzq zEKQbW8*E&M&}|c%#_y_?{Jnm^A)M9Bs?JGg-{;HAkTas^w~jou z)3PFfjl#Kg@2!$9MluO0Q}6w)>s1e_hfar2R~V?p`n`{lRUE&xxixo<4uC2>`LdV~z9PS-9uO7?fv~V1E!1z%8+28eg z7R0TWEQghl^`=Nl0fwdURt3>5AEqd|d(D$-+dB#XvYm{wiI*xvg%w&IqFrJQ{kb(n?Xkf6ydqL^1L zG@^YlPn0Tlj5|yv4?fxZ=)Hp+t0O7DfkY#C9V>=Lf=qOI%!e}9PB)OzkDE4#3Clqz zn9YSyIE3aN@gM`ox&HxHN#G3;zRfyC55^NFU=_ZL(BR4{{J9#8a$hButlFF2LUX^4 z{;3!^R>M!*(pNnZO+8>SiO;zw*V_v4Kaf83<30C37{^US{Gp$h>b!%V@9cqPx-4VR z5Hyn!s;9iH`?#cv!1+*`Mw$5|Gs}RxLPI+oPY%~^L==pf4S$v(*l8lH;hxPLtVg3= z2G0o#7giOm-K!pswZ0R>B1$2s>@V?@fq_XQ!kvIk@(mP}xG}qwJ^n zs);)%*tJuD>^1#3D0ZU`*aE&8UA20=+CZHG0k(ig`-bZeRD!mmu8s?LfNUB6D>a8A z_6P9emwEHbQZ3yZO$Ou>sf*2XWVdmjUuj^z`G!9qn=Cs-KNX1ERR8|i{Iz+0o|Q^> z_tjLL?ZxJKTuITT?lmulwXRGzKU0w6i8&Y9T$wKrnT)CQb;KHxTuIi{`Ps;O@C_nP zQ)L~Ky4E9=l$Cm2*1{IdG)n-Tml>^8kA7U_*| ztq6a22XEt(Mr96pSX8ZuwA$U2Om%zj@1I?+^lz^QBbJEn;o!Tt@m(Wc3tzOu-!xFY8Fpk>~3;*03$>h$0Cv zWypeLjWdLBpZx8ik?`0bJ8}$u3rxdEYw!_$c-DWBBwr6l^L1UkEwYWxAl(T9=mP^` zB9lDW5}h}iY;tPu35c9o2Paq-GB0VI1sx7{rLmux!p9CXyy3V(*SR3{s3yi&UsTk0 zA)pwilRo_Pho0Qy$5TqWg4#*hMD`}7W7=u%f9T~Q5aVBQP#5pVNDvjM8I*M8TO;LM zy(C2ZHLo`8@3B)?h3bE+*Z$s(xNO+q7%3r50yhP>V1i7~5`bQqIx;I(j{&_GpwFw> z=z1wW+54#A{98Ni0`x-dt#=jfwP38D=n(2VJ9xPsyMz!$jCs@!s1NBj>*q<;N@#zw zPzV;f3ozdkuoqFPxfq%ar)y^&u&N)J`x`VCVvdi;q z7+v;0)vDUcUh`gZunQ%p^8UMw(ycR0ZqEn8yA*?2j)`HkhCAD+g%5ePb)Neq2wZ>b zk?0|DcKU9QLeTyioXRsC!70icjLa0N0*3K;`qC+MPx(p1mLvQS&6(g2U9XA40~sTk z;6W}Kf$(6&^6u*aXycXe(5Ll*Ghs-t0_Vb8kHNGN+z1HS(rCj<0}(fv=7*k}i92t_w&Qbh)y+;vo58cogeNcMD=Ms!h?2Lfjh~pPwmR-zGwawn2ONe&V zo~Ba2>UpZ{e!8-l>P>iJ0P^QD$d1!vXuyvS_eNTQK6D^3N%F1P!w4f!>e0%LCtb)3 z&p7u>d59bg_@!iy=f`l<6pS;eJ5>*{2vu?+ttCGFtc3Rx*~?|^S$41Tx`l(pCB{6ify8RU?7t#)r)rhPw^4zxmd%7mf0_d zFIZXJ@}hbfzUN0xx5hDOx1XaQ?_O|gpSF)HF!V{OK4*Wkv^8(`|>^qW+m|2 zd5e)X_iAM3*cL$$^=xecd9X*}lHZgX0c+B&nqNc-u+wi6(SG6)~RAdJH}b zRH;%nG2Xg-|bBzYvv>t$TuKv}yKY4eg$1rm=1KL-9 z8*IPb?1}JeJ<;G;98AwUbOpbFrVAJusUDu*jBx0n@tt{3Uk*vc+iY0=*%OJEzR*6{;HIF&lOTpF4V+RT6_hi3gAm14PfabP)23=&2Ia=v zR6a47$1DAPht*lN6pg!|W+E?vsX0UO& zcCE=-D03swOk}gVWOog%0Hd^!0)R{I`#=!SNG?;_FGh-U^*;SN8DS7MYaBm+e3GUv~+{0NXHC0fTVPHhXMiyDcwW2bayu> zUD6!_(jlM-iURKf-Fvg$`<(Cj)%E_*HO#E_19!L~;6MH~FkHYZUvVFr% z38aIJI}M2cR<8ajt0an9Tktlw41(267n=jP?R2 z4ONQ>+SH5DYd>&Qpd&!<&M~g~R>C(?u`|1-CkH%TQ73FtqtyyQ#lE228eZ>9{(`Qd zdXK=as~zQgg>6oqv4Qs`a=iEK!KY4U41#KkP}K@(WiHBBAGzmDb5q2^8voiOWWID2 z&^r)jH3FsGoTBN#1JDNv0}o*R>Hz@PV#tf%^I;vHNO;;n!73dDL?s@q+nYNHil%$? z95eH0lN5e2(|@+LPJXl5@hWU(Hm>eh%j+&RG?F6GtXZb_XAYagF94fPy-*rp#WbvW z*o%f^rC!aZRJxFA_w+2JmtoD&&l`oJ_1mq?>?|AMCHP{q)wm$7r(^6n)$DKk=(Zbt z2cA^)mTAb~sJ7reotZAbk(>S#j&)n1Ig{~ydhE?}eLCnRuz(8!zr5+{m-B(~|5@7j z)&OBo>t?C$|KO~rx+WTQflS5GAG17`tCT3xr6rqAm_EI&--mQ z>H$oz3BUaf2ZF5;L-GUWhCpjQbxJSrvPQJYto`8k!!jU<_g|LkM(m4de3biT_`Y6L zGC?nZHz@}Eo_XN+G&B9?O8*yS>Wxyco9%AbvFWQSgU}NX^mC@eX(uryvke*)T}UzK)mzMDg&p|;;R4$hE_+KykO1VT&fOB zbJ+Yn<0Z{sg7E9JdL76ZbPGfT{9eeMgLgXKd7mXx&Knv+Z zXX;BwB*3Id#DnyE{o$_$zEL=c0E7r~0RG=S5W)=lm5$zL|7KJ=|L}HK@U8pSp_a;- zEn%ddziM^K4~TvV#t}f*A43a#%vGR_4}^eP{kL)C+XncX-5gfm1QMKUEifz7{cKGG zK%p`rh>BO6wpnk?pUVs2)D8ze5fM}me3%sA@wH_rH!Sf%MPd9Ib;HtwJ%{3Ec7>2! zt*-zrH1v}AVh8GI0u4CDpJThRzOM8E?La#V&+bwG1vCY+e4w#^s(T5){;uxL-m=b; z_NBz~XXlGD?DJ+q%B3i;T!+Nd8uSCXytRkP4@7qcXFeJ#z7lo4W?PEsNV&f4?3-AV z&*N7Xi6v88S1nT0(w|IvP;gBwJFj=NeVe0{tfCeY%b`(cIh~uzR%fr%=sLtm4;bx% zd%0itkla@e{SFtrTU5pMcR%##T!y3nz1;&z%bQ9*DLuJrUmMFd=Q%ie3Q?7Li( zHgh&IBFE5o$08mCshU-l#~4N0$@HD24CS#!Q-c`rMryL(ywqz{ZQ9QXKX;cZr}Ruyw3qc$2?S{6QLznFh@UO{IEFfn3J&O*o+ps;WO2fssbi zx){PtZ9^ahB=Je~^E3P?)VGZMDSf`K_|y4AGXt5^@{I$jV#m-yrkE&RUc-|r=%gT} z>0mIOdz=obFi?Z4Zkdw-C7Q|P|m zf?9QQz$mi3aXpLneEH}qtzGHZCg_!zV4H!gZl`5qIDh#cPFiHaY5+blzW{hlsW=3-ipir4OB~kbh}`&Ewup ztDVsk59e8XMQ7h29csW`zlwmm)UfpWpyeAl1t+o&5^GQ@AeLtn^9&Nv!`ZNg;Ma1t zPt@WuDjIz2LQ&l9^Sc^Rze_!yBX~T~T2WKFOTpQCX~mJ*QfX87z0`4$$dedXj`Pz- zo7Cqk8Mh+pwtb@8o~>^WxSyVm)}<+bjaKCReqPm4=6OOD%Za;aY!dkCBBR*=^}zKR zIrZn0fY!N|;m26M)SFYA?Wisvy>CevyrmGs9p-rVLVunL;qEH^?L=I4W}yu9N4;-} z8q58-Ueeg;yOpJll+j+uEkRW3aH$I45jSb+uw8mcchchH1%67_$AR#@4QtP(QNlDL z%wz6iRXGY)AEYI|4WEpAPa?RsJ_FJ#-B>ZZPwhQ|VteM9t= zR&_>XkD}Cz*T9%&GHT}cXuRnR-)@)-G`%SytPukX+Q0GBmNW$6M|MJ{_`Gx$I&Qzl z%;NxQL>eq~V8P{g!Jpsd(dZ>$F{Nnd4|2W40bx^zy;g872XWZa8e#S2NJB^EVwjgR_YS2=MUv<}xB8sXS0v!)j{2g-%BXX2!B8|u z3^dDC>Jli}UKb`$En!3erx(a24n;?skww4oGG_4tdC^b62aC#r@Vk{Bno>na4aB@9 zu5Lv0sa{P)4I*C@LF3z)eT69tMpvngobo(FU}*(2P<$y!cbmep+oK3v9O;V!4JwBX zKJp>{YMlfse|x(WwVed9CJ2$4MqraWklE^+;JpMcMMQRS++HOd&d$#zG9(CWLV}uF zN$PP<*&}H4kWSr=M@~9mF?g@^B$msWeo^=%b`Z!5F&f#hPUcV=-;xfOf}yyF>}Z^5aQ_fiG`8!G4LD{~Yed15*Mt zGB5o4kw^fUhwl7f9Wgypwdm|LSWhDGzF-n=J(3{?!aYhG&AUizfW;kN+rrZ;kdP(N zDN`m8k4;6xe|T))0fZk&=;f7_b}|R1PDE#LcWNCo0{qOA z5EgpFhJ2gw+xwOghzri3+wQ%DnUSgj=u<5?W|p@p1=b)Uc)o?%X_99&k;DjUwEV*C zOoX5{xWho_jv7A>%Mjf4dl8o}J1D(4K+7x|%!U+!YG9}X1eto`12Msfgwits^iGeu z0ejF}RwY(dws-t+4{PTM2}cOPbeU~fD?Vv=&)+K)Rni(TJQlOh&=j1@6anW?8Z|^t zRVqNx>%cmJa^7Cge{hDq+ASB_Bzp%JnK^apmS^<6aaRSjJnW-q4>^Y$?wFgQ2ayCY z$n@d%Q^5$)QA`eAO;n3iA*`Bb6N1Zf8>=#iMZfu@pOX8!(9Db2U031iKMzOj@0w zGmlXh-+xRU=W|CwJh*LkhRW{i9*1Sv-W#z9dmgF1@-J2)^b&7EeV^t*kdsD=$6=~y zSx*%wgxCEWTlS0km^JDe{lu(es53uS!b=>P-<~E{ly@k;b-K^<$^p(nWrU^pEh>NP z8I)T;#D{o~M)!NQF?#C>3Xk~nhS{SXE?R_f#PYRWzvzguhI&*q+w&EBdTH=i~*E9!}KY zH!f@A`7VCsfm>E>ycD*Dxq(Q&l$Vt6PT+Cjq9KCdco#RTnl8>q@H>0Vx(o2?A`u;I zjP`@fOlyw??{C;G^=NO#c>%R1f-0`)>ozjg68c$kPfbJ?Kk!vY^O$|$iFCqQ9EX^X zQ=mO|3{}_vVCr+G%IA|~2swtgxdS)u3q?QV0-b%irj}wG_#)X4;LC^4|Opb4HXi9!05_8XY^kSA_4|v4C1zwl5 z^B5O7$O=r07V*6t7cn64#nUuI@eXWqqC`&!O5&4C=Ly0v;ywQ0|Cl-0;DbN)SH47V z`i|oOZjwOF8eFJKpj$kz#hR0wiI23VZ%bB)SZ|25r8Jb!w+R*M<*j&f$To71yMKlz zJSudsJ`{YPy9`e%IR-Z;P~aO~z=DZrHlKHPpm$|2)XwRpNvFsiKY^}s1xjbgM-xa^ zNBHY1(zRY5oRuIOz6d+I@GLx$vH;h&A0mqB@MKUU;S(Wik0OxFgkwe{jJ?e$5bqtYv& zW$__k-%!5GZMJtLVZ$@gLf@hVNn`kD*~AK>#b-mM(ZVEUVp@&mCTGOK)j=x!v8r0J z>d#_xyB_SfyM2Bngc=xYNE&C%A7?s?-BvHxP$eq~jkBGNv;P(+wdP3b4Q_`@Aa}~T zT1h<9l6YYiUosJox)$%vpU_N~;3t#tEHS~qAR(|JA$&F=@>xPuUqbY^gn&f3yR-aL z$nhz&iD@jcjs(*W<#xIBy7GVm69g6AtYC^BwsFj*CZxKW+hiQ zB)85cw_7E@=}UgAmD2evrOhg(?^#Ml5S~n6!c4bnh99r4p%>htF`|Sua=p&pAx3SN zY7+xe+a;F;g``9&F5)NEB$!O%o>k(0L)u5u*N6PCqx#}~p1GEaYstjA>44ZwA3v&V zhl7HcMNe>CYSHB10#ay1G;55`+rUUG$WCxdmiJvWgBncFBNK!q*=$f0KOrXE>d*As&dQg$U*Zcz z=!*=il9fTSgpHWmJi~#PRpiP8S({q8sVBqD=`=jUxG(0$USZW{lF`wSVk(epJ}2D! zEZ3?qrG3_`EPO*5y@s)Yv?L#AVc*!c4`r zICArvP0$6WGG#`vUA(9V?q|vSgXN@zT&yqzPXx`WLGDvoqGz(Ovp})u83UYlU+(}8Yw~(8wt9#lZZ#zAi&cW(e0}Kmdf(Z4sppX-PeN^yYI|o(zCKE(;uCVx zsY@RyazRx&Z44jHo;W6U>UXM!S7-3$a&arRol%sPke9A=1X>y!)rT?jh&5;(W(!-Bx@*J zYpT&{oj%2>pVz$g^v;{lO&@JqkAk!Fqv@L)n}Jc*H_+ge+!krlHf~c_o>&V%Sfsrz z+{9K_@Vx2GU<^TM3_%K+OH_|Bz#1$)+AVeei z786CgAug%gX?WC`?UWsxoOo~65oeU3m`I{!rC3x`x}BuE3MA&MIt4T#3v|#{OjwL4}gbOPFhP;=AWP1-_)%4+VUyy7efcH!jD;1*@YH zvReFKhMRKt!5((T>PCs%MtRucZCgf$@(3g>^hxjemE7-#hlt;e>CbQOFI?y^{?T7b zF;FfvP^mk>z4pReSHk{>kjRdcUZ7IrOF7dHm%8HtTVDTOcC)^hgP1wpMyRd>6lQ}$ zLt~-R6PEq76Mm(ZYP+>VOAEovKZaH*WH8^vlEH$6l1q1*-{lguslAl8nU#`E5N>FY z?kvm=wCx^>8UFDScJ^cVym|P7Vgw{Sg3K|ZAKikn;*=|{Phm;j|)&vfb~Z7vqzkD2jfTwOFQd!fWEC>+3nB?`H~6TMOkI{N%ho8rIJat zmPviA(IWv-2VLoEWws}B6}6Q*m7DICb{?PE$9rT(9NkAG^roGJ$6f8Fox^&&r$xp0 z6?(dmOAMKjW0*eROBFvML;j=|!#_ILJjxa7v&e^h?nXsh!3jU$MIjpE;WqX8aK{S8+{~^AY3vVX*ZjC{{CWrG@5c55qr7b zd2C7#Z-$%niGS~jmAe_q3 z3tDrfS25JQcwC`-4>yBMl|Y}2h!gLE0FQ3o6Ffo(ugtcD0>b0stK-sjClRx@>^9kt z1Tu~I6|iKXb+^H3b%k{Ws&yp~N<}T0`k)N22S5LkLhQJ*mv11FnUo6mlv~TR{nEzc z(&;B@)6N$gq-y<5pXZD&giTt7^+Y-~zw)Yf7~e^b+HvDvXiU7li#|YTDpVaEn(}1S52{7E3{jw zzgz9GTbs7a5<~yP>0M0gmUp<2vt)m!M1zj~9wy}i7Kc~?0UqYi27%EY-SMVWN@83% ztXO{^E_I85s&~SkFLRuCpAV8pw_o)&TuO7p!wF`_`LWlY@3MD4J8eHt;XoyPlQ=`T zoPd93yqWo2VCKWz8RwxzZ$!xuOkY>vokCs*dnnfaVM8GJ4FU}NJ?`85koMjX{I(;S ziu3w&eV;U_L56zuz6>~`u!86kFzLdaWi{kwiEhlm)lJ&V#vDzLTqAOmgU{L z#k~SwG(|I88^%Qz$AjO06-yn8Q2Y}0e)9xVPPyg1!sW5S(7P1TxQ{=AY7q9xilkm# zN^mUKNZ<@q5AG9V(8H_X6;!mk{YkLIO0vZP%St5cIdtTvvIpS zrzj%J4tGvdwS`$WPaRap5f%f?{l1SH^l%St+X;=)Tq=I1HTZNwbwQ6~PFyhH2(OEJ zB1p-zRb8MUOT434FdMH&KmQHMl*v_i6CH+2_i}dB>(rVtN1> zL5So-ZdhML(%6GVt*P~{bko}Qvy?cFWc6j~N7EmY3@yjsd%{5K+tR=b4=RX#J~!hN zsxGSxUr#t|l|!jMH+vxA*QouVx>9>RRPEB-J$CAyZETIYp2Ok;jWXJWQZZ~tf~`2T z$gRBSV_c;JMHPAwH5@405JeIRWT@W4EbDVu*`W=ou3NII$o6fWzYVHhF|^S}fMZlm zgT0o7%)Y87|5dzB3G^*Ho6{TX`^&5-E_H@1Xy#BJ(x)jEBad(U^R4c7PnIs0ldR$y zg_56XES0gRo$A*~$zrTU^%b6$M5+;!md5IFV$8(4IBUuUIqZEkPsPgl+C+u4I;{_5 zy$_`iACM$7i1RQ%V@nS)=i5#Xuz!AORamxhWS!sDJj0%hb#Z1`-a^$*>_0~;Fe9dA z+{9Y<)K<{GPCjYZuF1xR+@xuJ=K`UoYcD`eAtY{L}5JkguC&fOX54>)7ZJ1 zB-6reyXWuS{pti1o71WCUDvug8^7gv-f4A_2tyYB(stf$?L1+D z_k2l*hq=A9&-<;fE3O6}-?no+J)-G26z8HWm^V-m`M!evh4bDnW8xUnto;rVy z|JqB-iz@cmy(}wzkDibG&}!uJ1^SOEq^!?XtQ?BgPH(g!xu+tTHC!Ar-v=jZyPLL= zaIDgtRt{SUd8ndFY($Sqa4F+>NMW?h(%i=QuzCpwo>9h!zQzPue3C5cuwad9W8#W> zNe&lS$ir%+LJ3WB-bwL7TzNw{mL3Dp<3Zmx?1!CEaP zjZ%1WO}}o90B52y!k}JFhA3F(GgBIdAU0|BN?5!Q#hK+JX@u17`=~n+pM=nQ2C|=k zi@uGq&=^;;eZhE8{%nZNEJ#+fu{*AYF!1fgRwlhtW>!6?4_y%N~bVOy2Gpu^kWGq}$F1Z<~WUP9GUB;8&BUq*H7jv>|twbR2-#KY#jGu!7v2SSvS^0L2=!p{f{4%0vQz#DxxGkY$$|9~{Tm ziM8Akr9i^$@;qvvk^Fmwv!W$gAch1iCfsLeVs+`h2{90KG;pk`sv52ab-H#o$cu5N z9i211uxJk&B^UMhA%E>tI{W=zopmyeM#s+5$1S_MG;2M3KQajwkwCI?m1t;Ors#eg z!5m)T;9Ffi^mX-Jm#;roc+-E);$jZo^DlMOd}TEjAW1Yc{W;Ak4rkuqRW%>Uk8~<$ar`jxWuG`RFS6WS} zh)Q4PN-pRMFVk%~c1F<^sFx*9yzIo^6=pw=G-AxR4)B)iB0!^ejhxjjEyAr#6ec+Qe(17tV@=*DBxbs3%>|-zmZ3-luB0jE$Y~p>n&7cv4weNzJMSD?B%hBCJE5%EY?Y%p z!kry_z+6i|mlbIbF-a*ye;r<<@t|=l;m+z>m0_30yklC$3jys9vKUXG;-xtQ?^*U> z#|q5O*}Qu1?94wWXJBuRjjcaEWz%tK{>pd9BH96?Z2sS6{TJiz(f5c9Im zJfD}a`UpO;RfO20v~%|eZ=iJ3ljK{H)4}IFX~OMY4L2{^5vgM7^T>b_$}R%dlRD9u zokR^fXChX2PtbYNmSn{D)KRU&PU%*6H3RUBO~5OxV&%`#WmWZ$EH}q{TI*g?-KhMD z1k(Ib@D)I2`l^-hs_^Bi{Nwjx$?MGYwGZ>B6;39)_BSh>eB#9m;TnZ1q3Kpi@5BG(hIZxFj?HTp?HF90SiKeeutG*Ja%v4qxHl;7}`4wVhx2 zFqgezzX7y0#Gh)!{1{PeDP|gZw1<{D^A`GtIi5J-ES!2e@b>DSdz-j82DL^5f(t^Qfe0RXkH z*sclirN2#?%Ky{}0jv3K%KV+3pqFU+=aktV$}C24k&Ve^IB1KtL*ISXV+%l zk&0`D?6Mc%x%l7A0aU&3745m{Uwh-3CoHIC2VEB zBB3Ju5W?+$E6el2HBh@T*Z9A%iC(o({jV!z|KCg*M$2LMe}zr`i%3yp75Yo0cnN!J zA1~Sph!id4p$F0QOE#v0W?L`l;V+Qc4}Zc9QLkZB|9~4Fm2FV1Y4(tJ@R|TNQ6bz4 z#*WQ+Foyu5dcR~i=4U6J6vBhSK1rnVo=3~Yuk{fg!l@6igqxNPPiN>x4q|zSaz6$O zIde-X3#Tp&@ktp*HGI;-S{Oo*P<}eWbUs!!-HRuTdyCaO?BvO#w*Ay`#8HlGk>csn zOADmFpBfrX=Zf+)FwX&(d3Z4HD9MHq*PWasH8wtH( zPyDkX*t+D~b&t^hw&39JwMaKGiGM0a|9jLtMOoX%NLC&eHGuuh(Zh>tc-L~(7ykXz zB_@DL1bT$}!exhB-DQvfd*bGdIiMKjkQrL@X}jFoyW3!_B#f^d;N^+x@2cp7`R;VU z2kU?6+5JCJjQ&sL%KzsxWAvY!i5v_LXyw4pl>t1vyBhBO{WA(zicz~v8LZ>I>i?h^ zJvr5FCJ}>P2@Z-JT6Ol=UK8RRZ636*t4QMsVxTeOGGW3&4{gzL0AoASmynT)6A{cb zQ37Tfm;ydr@sVvCwZwAo+A|>~_^5PD{cd=9Fn$;2o4rp~3>ePK;1kW5Dv8fax=9_k z&7`YGpx1;S-hDc+5W{7Zgc|07u# zr0RhR(?1-c%)KeUvAwU$)}L4Z-!;el%_g06Tn5*Q=xF!5P+>TXgX^Ts^KJAE`T^hw zo#Q~*)q4LfHNVZfjA80>N1^qH(pn`_l#J4krf;W*Hnf3&NLL<&!!!eQ!eyUafRLdC zE?5kvAzrAAy(5h1JX?kmU-h`jB~1}WVDLER`848lPs&#U$QtWLd{I`UsRNl+T!%Rj z&oyv^Sh`85pWnMyh^tGR{7FCf7n}6|kL!OX*E{R{z}lNO>0&jmDFMJHy-K402Yl^c zk4*ND2UJu)0xh)UbKyI+yPSq)se*X82hS5Fu19$jad-v5&N(o%ZI^Qt1B42niHzQ2 z{&W4m2^*AVb?DOzhGqrUX96(L?KhYyFZReJQUm*CMBf*aH3>Zb7@k4=BjBIF`WaciGnwPnTKclhNY!P8@q00B3RD1Jb#EBhEjQbmOo zoro{CKrL1mwN`enJjUmmS!ff(c5T0Lw~8~Gta<#bR*;XkR4@7Ridp!31L-fPf7O^EDLqbW|Sxfs=FU$u0=QqK1$wJfbhRDD*7e z!)ktcJ~*4wT1#$Xh0sSP##+Q4x2}5wo_~LzsdfY>zl*dd3^e62g zUpu^si+gXnj##}T>^K*u+iTA#370`jVe~07m3RH$KYQ_p*US0>Z7oKzS&O%w1QR%zTkOpfoX6~Gajuo9Azg9>;^k~9F}(ndbM1N#o(At5*dkW>GV zuoq;;kjQ{Xf>g(jb>jjgA-GRTF90IZcvF8Fn-l$yk+(e+4o8~91O7;6^^ z9rdSIo5Pa^R7)9k?6dJyf1eorOb+?(EtwDz)@_5Q^3Mq}^itwDX;#kCL`;3WX<5h=Gyz&)XtXXGR#_on)Y?n*CFR6L9X zAs%#1>W=TIjcL7^QxjmNv-XwgMV9)CVKs3##c4Np@8nCrjspSLN$QBB&U`b00TcFc&Eua;4EN3~vk_;0q z<8@(;b&-?GLy{W-lqev8(g4c;bAVh2P_V3J{-rPeu5l62+!stCGe+ZeO||^1v_Bf- z#%=KaJT9Wx2+>Fu6sd7^h7&;DJA*Wzd8*-8W!{aVj=x~SwqVTQ1A~ljG@I}AMs+C^Hl<&JdvS~QBAvr zB=x$5WCfJvi~Xz&@#xRRJ&j8e{qt)Z?vzWL~p_XQNSK(BN|{Ky0g3K|7Qy zsZ+ByRSUqcQbWdw9;Lhb5ih=oaZqWKgZn-xr^%)7hl&WF4v=SlUjLh;DAxxP?%&ca z1|nv?aX7W#9yU5ZYy#W{9{pxO#EeBo#vP-{Wpb1`E3kIx`+bRtmRBaZlqvwLx>K%E z7U-#Xyg5QM9juVb-BC1H^cM&LfU8|!a;|z_TU-8m;gcsHci*?2zc)3Ag6ngfZ08PTK?mkErYfe?{R%z?ysx)Wv4z_l~ch>Wu_v5XI% zeSqAv-(HW$zG}EI4Gu8=gJuE1)gJ%$!o?WPU)MZEV^+<;o5&KAvF2x%@u^)K_6?y8 zo_!6Idaw@RS4UUF<@ypspYzhXZZHfyGBAKpCv#oJy-%qnHiR|W4h z9R?3LG@^ZPa;!jk-L%~O?a7v1$SLvjs!ARlyW>nr1hN~e*i|d;(2Z@b-0+S1@BNQm zKH2~0#D^QLxVuvZ@CW;ZyEOo!g}E;ipnEXSq*+harpncEiZ{4?-U<8WKpXFUf^3-- z=-RI1<9?g*q9LKEq~#F~4zup3r54X9n(>ERpp1>|Fu~_M-*~utJzfW~%GeR^5qHqZ zSGg2Wf9PkaGU`WSW2ifbtVN0Zp8Dy1iw?IpZUm_t0F>r68}L`q%V^t~(Yh0tc71d2 zAo#w{nYMZS2?zskKKHmWsK0;xyo=J}X|Zv!_yu{1QHcfxh-tY@QbDsG5Q2SJ;6O(5 zn;d*bVncQkq-OADZY#?3?j(2t*I{534nHM9mde0YKuu_w>G$(a^HUNRm>S>}B%Ky< zeK@li4P1+Q_?MaxzrZvW$g!`->AC=e`q#}JjVef0f15tZ&~YjkQd)1dkz%4RZ4m=q z=!;Bx{*Rk`KKLc)Pa9@|e%S16jw6;r;dbuw`8ac4y7}pLObxTDY;2YS(5WPR^VkCe zVw{7&?P?|e@s4|g4|_!bVYv%;V^{m%QdJhzF7>Cfjo-db3ox*;Fh`cRN}W~q98QU8 z*b>MVOOI?U1wyqiKKF*x#Ag;!*-SwloO%b-5;?Ezs8(4Zg`bg}R9}PtK9bY?Y}DW# zK=@N=d9Ky1TAW-hc$9W>KyLD?%eBBwNb_hkgH6>zWNqyPOi+1Go2vDEeCuG`R59`r zdw01C7j>OgvdYNNmH zYCu|m`}&Uib3AA+1X8r#g88wWnaqF+zG(KlNw-3?Bb220(@c2Y^%yg$m>2wgJXmcc zTEZil0tAqtsc1H2*earIJ^vD+0He{So9Q5`1q=Z&j{N1ljRbU%-Jl!Mi)AqNKW6&R zR>T`Iy5HXHA26nc8_|nDqt}0IU;ol{&kivl;cbwxskKu8A?$sTh&+6~5PY$)vuN|_ zb+7u%Q`v9muEs4{b>&MOFZjxV?d$GTaPd93tL^Kb{jtECC1WXo^FnJ4Ulgc*KUZ(U z$yhH~cksUb6#!!r+T8c<2`T&WpuNm#{eHB#Yu}IeZ3bg`W!0z67B1uXdq$TI7w(qN z`gQ6FgcKiCfHw>~?%$3OxTENcFvetY8Qb=VPPB zhPWYH*TE1GSQ7MgiF0GX_z3hg5d7^o0or~nHFP6^uZ*M()r&DzWyS6rtA0=@!=is< zm<&CfW7LThlM1Kwr@s{>-OZ4$%ScR$?`1brC5d0c?w=WrUqC`_SOUFE5=X0LF(6u- zKl4sh#TUg~h83Hd+7_X@fe`>hshYFxH}f+|SMUGky(L?S1Fv?aRN>x(Z7Sh+bqpVA&x?Tkm4acUGRatXuLA znXg(EK{qH_&y|}KzKUL`KF7YvhKvMZfkr@ue;tdL+d2N94zs7*7&&d;26ewIWR^x3 za-=Tc`Rd0X1Zp&*O55ukKkvAsr)QUy+Yl|0jmX|9@QE^wn|nd9@+O`f9oalIcC!C2 z!FTvnA=Rok&!J5!-Kfvg87tkS3D{e>(8Q5~)b0~Kcq}W%$wyS)9IxR6ZmL}2#1=WZ zb@btHh)^I%_60bW|9MLKaEW+*Z@S7W0;i-Gekmy3WzS}4zMX#k9Gxm;;5kqOxG|S(yj#5+?Q4ivA%u8d;noVsZ7P{E7dgS z>5x0DPjBO*IiszG@!;1_8kMkXDj8wJw3OU&DrCk*(dh92{7&^aGD}JIIC_#oxauaz z5ql&j3W1x?=rzMEd|pcEn9PWOpihi1Vzl~>jur=T3=1R~d!hjR`a()cBcq?5HU}RH z1L!zEdmC!4s3&Ju6!&f?YkXl77vv@&#{XCFml{kH~*Pe zoH^>dHs)OC6+aL0Z5DriC$#xMb{LE@1XTB*7vIN~V4_q8$-bUF{t0_m)v){W6ZWp_ zy8mSw08G0m&$J4h%pxUGR#{pOH23+*^Ul}yJ`mX_Sx~Y_JnlsLgvkdOb5J<>)KQpj zP7oNNtQr2z5Q(UVX8XG#Qr0y8w{_SNt=-z|ZOqjU%MbeiLAp|;@vF$bxrZ>1YT9$< zAIGbsCt)~b82fpR_?LC~CKT`L8XYal?UgNQX6ZxMlp3ZEJ@o@wcQ;SA5xgl)PPo=mrtD|1#YNspfgP2o74 z8XxrYdx3P0zGCwpk=I>BjiPEPbkp$D_LP-r18xrE=M`jUb?%Wkq&wR*}$@C$d zWR@8zye++VH3C&6Zw(?xMxVfONl)D+D!ju-8%h1-SPmcI;j99Ab~WvWn5GY+8T_ie z6;8ND9O;;-E;@I%aBZhsW-?hSngsmILM^5=DjF0EYqZDP1gSRgbIPgss4)`O`1yUg znMA^9vsnqmtPGa5N`)|Ce0sb>M4n7by0A1A)2#gDNEjmNN#OU{;J^YYiA_G@018o%wXjqJ{|jXxmJ}MmTL8`_(wWz}Lw`&IfLZ=1i=5%X)qF^wB79YXKDR3K z-xZ=<@df{xI}EyL+Hx>ltatmYT?23o4CQ?FYv4G-0<}!WD(rzer zO$%~VpG*ia8+J4j&x5x`YpY+GvZ>f+WE+O@IIn@k?O+lqLt-!J4W_XfY-{#spf*|+ zD>chCh(nTgHCtkcG*9<(=a*`wAh%{3KK_)W14aT$<*ftAB`4ZpJNzwOrFIm8l=3$} zc=pP*QQ7j!J27zxE4m0wbSuEOoKh-!$VK-i(otZcW_`@Bi!0+;s+#Y`b9DTu?By1( zA??N3d|2_0>~rYnci>Zs<6*H|^3FqlS7e3gK_p7fa@LT3QIgwSc@v^u{J+J<<@%LWL2l%0_O3^8~VF_4u9s0&huV z>UUV@sK6E_Jkc+M^pf%S+d+8qsJ3}ktn*Ee9B7LfmK+th>N$kzFJ z9@7LG`UgoSw1WuAP*w&OX}YH7QC ztciPaIQI9X(-ARiZ&}zO0A;@~JB54RzjUruVM=<@&kIfuI{BjiD3FJ>K(kEVdOPPo z6@AJ5El=OY(YIS>^X*Cre{CoJOP5wDOOZ8tUBR+JZ~IFLPh3RFv=V0nRIuoO*DSqR z2XZyO8Udi#Uqyuw?_z9LRj4(%hzAQpjAG`{s1uHe34PEFMkg6ScGstwkIPgh3SK@} zf*))q7sn~Ct_yW)ZvlcoXXNGg^B}L0yr(Fr2{+$l!o%=|`;RTg(-qNJQ^_XtCo*mT z@9bL=RrA#HxeMa-nqoLc>MT|oOZra=$D1ra&)E%Vl+LtyT~$cAWvKXpU8jV^JsL+~l*a%nB2Lir}-8H_cC!JTF`5cyirk*Yt%r!6`cVf(LH z{$wh3B#!l1ex0ClEG`pBb?k|$#>M*S>sZZCt~qg9>eu>LnP4S7%=U0GIrQu-2r9lQ zg@!n?Om>QMw^d%Gn|7~87(&gfDP{ya*a+xVl!gMN{i!+`DCi`{A~j-(KQB8{!J5bw z5ZO)m$Sta=u`lYNM`%!*Xr5 z8)IvA?3;u)=Hl*ja!wN1@$&b7Z2AF&UE9tX=QMTC^voB7QIm;xi+dPe*!m9g6x%pr z-``6ryU=a2?f4+}y}XCmb>OInHu{H6FH_#aVLxM4XypKF-Co6OkVBwB+xMxI&+jfj zr5p~6OHOn{;6qfaN0EjkBFAo14joHjGf+N&NF!Vy{!^38wSOM|^+-xezfGjgR%Ph9 zcvw&OpUnSw!r@}qbAI1z(P?wPMhSoB(j;WT38D1V5&&)}vaw@*OkNc|J!e}Al@2ct z_nSB2U5m14%_O{J|318)6hNg7pM-A8w~?90nUtG?64qrvD2dKd*EA7{U4v2m>}JZ_>smKENw`=KfZ9!rae0FFgb9SSD_GTCzh%9 zA)I}G=YaQd33SEy>=5NNf@6Q=GJ-H1gZt%=uJMO$9BLm7Ac*Nrb)a&hF9hlEr&aC9 z0*BtXq3MWB&^PGXhdv~O>BzjjZ?K;qzM{s=K$V8R#ZNl)Wqz1}uF?CJxbe`BD>MVs z0@^_~cj(VIn1Suu+d*}97y!nko#9YjC!%%f3Vb{liW}eC$tZ9Xq!gM-mZtvr`h+tIs;@@UXm z+R5Blj@KznR40juRm&4Z8MT#llAxjKa)!Ao$*Newd?Xlhuic3Hgo~u749qL3zS9Lh zWX|W~OXK0KeeD`??bJ-gkBfI$m9Z7m=)PV>v;Ur=`FWQ7ukKdpj;>U`gzEX!+GjAM z6`-hj%SegLgKyS%@=y3H@RU)3rwoPT{^wKv>%?x{Wq@+`ikX=8Cn4?sQY3M2_*ZJ& zZph$-yD?SnmQj&<_Rh{C8;EYsz>*D_lP|$=#XA6r@uI%|2-1U0L*Vg{-*LS!?*9Kr z+g}Dmy|w$}@Gx`;Ln{r^DX4&i42Y7_l9GaSBOxH&(kb03NOzYAND0#2DP1D-|ANKd z+kNi){GR8$o)@sztaZ)0u1`IiGL{CZI=T^}1u(;^f1eg20AB8O1(S-!>OPzrp>~v>64eb!7Nc;D1dCC6ff8PDE=Efs-Jp$; z@gI#3G{C&K6ss4;Koe(Pj;bFkJKzu!#)-+@9%nW-niXr+nKKfA3XKs4$Gv^@EWx$? zO@em5Cy@9O(L*d zU!aKT1b}M1KhFu|hY3Bx(H*&%BiZ|vo8^7tUi@ep_vmI+CXCB;h0n99Mn*6K<*pEMR{R#!b#%ajHy>!9i;3P% zus3k#J>Bc!+B=H}!7<~x=@2pGS@(*%(DoJ782QEa-jh(%_Kf? zAD;ANus~ujck{CW+sf)_VvY!vv4syo#e^jjXT{`;iiD#Hn-*9g;GhQIb2M!}O=>^u zNPPcz)_m&0?2Oq>R{I6pb@h{lsEUM>c`NfR4gI9DfglzQ+k$&b*@RmsYdLo3SRG$U zSsVvthNV`AP3RuiY+XCd;QZX6d3d{L>O|GSrrkK`%<4l!pz>bdZMJW_gXo0L2fgII zi2`{3hIN}IgjnZWd#1)rVw&@2n7quG|0LeipXdoEebx}xTgX>TFB=GS$ z=qZR8L;`$V4uU&_zwl=Scwj(r2FiweI$*3g(x=hnhQ`9$$_=^M7C?FzjgNjHCBlUO z=5Qvuo!$|N>jnzhWulSvM}1l>X}_D4AIc3!eLdHDSumEyg8(lG>tqomU8hVlhcHm<)OBG#c9ZE{Fm593DEb&=|w0f@Wig zo!%J3<2G1oFaOLn5*1~4P!u~uCW8}~>RO0`miuG2K!P)sC+>~ZIO!&js|Jigg@@-k z>gadGTp#O(g%l6_D=>K;cABx@ILu)2W>xz(PW7-*(VfY(40lAlQzOY9p7}nJtA)Jh z4H&_ok+^oBdas9-Gi>Cu@$yE-gy&R_0F{PrIaO?8!i}d*Tdf zVpyW4L>Un-ap>nprZ|mJgBgZ#6JWKntuQepYEh8q(U+)Nnx*?a?DkFL-4e8rL~6mX z@djm)FEPT+Yc8-2w}dZilesTA(s4qHhjN`wa$j6ywR<_4m_Kuf+&y)U{UQ$zX!87R z&ny>4UGhb-DdhHwhJu6}M0Zr(ZjR2Y@LrQ!=`;B{IxNMsxnZZ^O>`*;%FLegXD(m4 zK!X2<`~fsQC=$b8`7Emo-vvQ{x`9TVN&`UtoI^YG{LtkHu3-0XKpY@fkTdX&Enksv zU0$dMZgRkd`Xe9t`|t3L;%k>_YzhYEfZzQ;&6`DmT;0w~iWsZ}`r>`bE$CliTl4E;cYl7aYB|?Xyq!Df4Qk z@MLG%pQnbGQ*^WLV1T#q>$GylXcf+S+hZw7zOBs5Z)d&{P=wey5izs%@;Ds!mbR1N| z8{>bJ?E&k41ao^4tHnI<0-z;Mj+lSHrID((1(TIW-c!HUP4+v#RXJm-9gywSGui%g z-8N&vnW6Wkz6aj_i(fU6rThzCt5kaMJplZ6M$5II&;3h6{w+}LA4}GEA9>FaqyM{- z^;akbO_Jg&l=6Mt@ZDd3_#0tVkxqONxdbP%1F#t!H1tdsd2CSI>SJ=njAsT%7%@lGX1Ih>LX7i2wVqJL7|P{*dEk zj(COHh|ASGf93205oS^LLR;ar5)(V<+wHIYRTB(%DW9 z9Ub4fDSw5Q0|+m_?%}?&@RxOqwO@}aKQz6YJhOrR?u0{u@0Jbdg+VCU-#cNgCWhZI zJo4D>&9U)qI-Y6N+_zsKN2X5#LMiah;iVxHvY*rUVPAsV4 zhtNh7e2(fm8kX7h{fBKYUD8d!@t^-ZK?HYS=HndY8>bICSChlu;&!=`2HXXWmRt)r z5xYvA0i29LVsMuKa`3RjuKw8k^`bm7Y2(nzcPm%8jMe=Z2d{c@QGN-3{u}DdU+c`@ zAlqMcCgU7u?B)v7&g^@cb-~2$1M*=QR8Wi0bE9;l*Jo04X8U`p&qcadymjU_L^b^~6yGCYl7#eP_LiYyqk- znK#OuFIAN2oF6R#eF%R8^++l|YO`JcyW;LoP)(oWf$2}568>l`J0n9h*8g3PDqH^XRG#_UlieD&#B4YaG_f2++1CgT9f}0cR8qK4_Hr|b*PKDOmjkT6 z(knboZzK6|FTS+*5gTdgr^5-I04Dg5)MSw3%r<{po$625L{q_@A%3z}qUl&MRmt141bPcc z;l&b`5iie#5w!JU>o%JwU;MqAy1l&~5g=!K@PR}ADKUU<7NX`I={dWydT>i7Q3HL|Cm8lGO2p>6T}WW_emX}6 zii8*Lm8U&AP;F~K@<6qn{^t`HVl4RkiOXF?dO2QHFbKdGQA3su`kR>ee`;&eev66! z__UvCD7U~h^CKRj{ux5|x4^+4da;`liT^t>@pxX{RO7>Q%*0z)!W^yvzj$nL%76Za z!GJfw78Oq>_C-)*AZcN|*&ci;Ci(HK$Ge^}*m)7G4MdmGiU$HoQ5R3K4%Pd-rzF3h z^>`UF-rU#F0>?^!1G5(-2*xwIZKcPWI)88FBF~YQ@GI@0(_zlADbnB1`k&f@KdrfV zW*}QWPh&H>%s3$n*~;NDF--`28Su2ZR!#PUocW)BVHE!HlI=D$|fHvW1fQ?=S!CgfN ze$TG2v2GykW<_3K@fHc1-_o|13<pHIsBmeEhvAg`~r8FR5s z*S&&2BE^W=o^EkRXL@A9%|7q-BAPYoURBXzXDI$yi{Bed{rAai^DlTQ^dvrU$=5s$ zj6GN#&Q+_(WFRhIA1OB`{O0xKXmh&WWBCP>eLm1VMq-Y{->celIV|LG89j4&GQjas zb-KqnM|^WK5FHkQQ?x(2EidLmK>D)Iv3Gm?y}opVMGXr)4oKyk$*&Os{zYVx(q0|i zv|E%Z!6dYgUvb6*<<*iRZ}aSPN{cEzdu^`+q=nv(t8qAU zy9x}w@Y4;~A|PDSLT90eyt>A@m=X4@;KPE284Uv2OB?T_0De@-S@ehor%FGS1{4ak z2+g6Y2v>aqy{UL_stk<~q|eAH>DW?4hI(RIpAp(}_Myt6& zZ^UM7-pIii^Kz3}=oEr(FEP#+RPKsDW0FTmri%_k(39ZB*r7#A;^E9&f4H_YvR+EG zyAmxsQp}TAUTUV6$-#C*B|dj%j)MbZ$0%4+vFV5Zb&E_v6QbXmN}e2 zJ({v|gnc}kwmu5XFJ6Ci?Fx#=ju70zk84D-a=_8b=CqE>G{xHxLv_LQNd6y zqs9_S)|2IU;&X#x`igU_PV9FT)MJi5;}z>gErbdDC~U}IzaWP_-y0CbGUxl$c2kc*!)fM{Xn8xuzjAjfK}AO!>za%NJSdGY|7vsg1Wp>%1$XPR zhWrI%Elhdf2K&?0apSrrz}F*^z;UA7Zihy*T;vYPgCyf_TYj$na9h7O0bT{u>84CJ zG!^{1fG_(F{iiJY$DDzN=sMqpv1>w5B{%gJOuVl{d85U;?-QRe5p1Ydm<~tX<-W@> z=>B4FN?qLU-KTojol}--i>=Qs$T!c`n6-*@+JlH6B%W0k>vp}yCO^O17exHgSDh4( zCCui*Cj?n61(uL9&~TxMM`C`_kl=W!wPvenU(nWf9YO7JyXL0-#%Pg;$lelPyht<| zDbKd;QiH}T=hH7=)_Z%WUw!2-LspnekbG zbMcyXz_oVYb$^$0#OEW;<;Surrlo^Y z=mjCXJWM#bSSiL^j}G6i=_fff*DTlUw@a`&F+?fp2cGsAe`z>JnxHjbCySOX@gy+8 zwwmEQ+iaQh7T2(T!#cX=JkCS1(>_}-lG_|RdOM_=LTRC(s5SHTZf8gFTjN5;VdC3) zkg*kxZmw~Rw>^L_+p{W~VcLgakZ3=qe#6L3LONWFexV3;&2qDqtIv6AnjTc$qT3}919y2jN(!2Fw%MAj1;C> zrHh8fM_DG_(gATCF<+Bl1ch*pGElfgzyG2vibe1oZ5LB@cN#ni9TLcZqW$^}-Q=0; zuSzH%A%U`?Ef^pZb|m6wZ&Q*9ioO(p$!(ynt|(+=n$?ZzT;|n&2p;v@(0l}l){W0t z%4pz&J4_%#l>M9h5B=o2*@ssI&gPKH^gEHQpC?5_!I)IHyq$KiRN%qb6p&_;9zjV&g`S>LZ~fFPTRu zA<%?!NCgTF1^9O3B${m-JV9r&rVSK|q(%6Ej6w_HD^Ut6>|saA8`Mzb{`F+x4Z%_b zgf#-V5qE)CvS^^fc|)+lLkMfOu#fIXS1o3Wvb8L)y*^h=-WX!g3N(PH@D>7}vfKDt z6x?y$HB-u%rgNb}kG*FSNI`fVmNs=xK+PmKbhPNiX(OMoD2?6hj2WV{s| z6)NJg%!0wm8YtZfzrw>q9GdSK%=O= zXpxKiT+kLg9^BEvwzd`W$CN-r5f${*qVrH??1+YpG%-2T-6Vcx5bbnKI_AmH?;o}8 zi|cHN9l0pu72<{$q^8Q0X&A1J z1I>7!+`M^1=@wFM4>V9guZc+4wZehN2dVw*xcqRZv<0PH4$7!7Zg`=5uUN7{+I3Or z^b)6{6J`MxX(l`3S22(g2y7AFc+C`rbS4L6_kx$0O~qaWAv+lp8zktt0)+<^md1D@ z>KTNhj(FRfQ)cBGo{W7^%qkx$D|`}hUz2wn0Ty*wPIW?otxhBxP;OJv_$}YUS>oxN zU4l%&=FKcR06TM_ysRW}Gqjy%a=HHVJ#)PRTb2Q_{+EQM)1)T$574J}{VSx>CktMZ zhkabBCIkpY5fxL$>ZVBa+Up<9g(&J-+eyplimHyP_JB z`R?;;VRcls7=cmKLT}VL*1fQ!T8i^R-}e$a+nIJP#AYJoMzY8}`ze8}-a7$meDl{o zDYtXi7X_Ji&l7#+e$S7z8*In7K!K~$A$q?!EUH8J6!~9?DhIyy3zat(gWTCD*`jnYy)n9YT@jZhn@(?all2W%)9F_pHM2OWAQb)}V-gc}=TYy7=ppwEJQyBL}3e~1v! ztHwi%Sm{f?6-fKgsFeOwGCN|mDEE-okh>DLSwo%TliOVGU5mxQ#I#=HFYd;!Vy9r7Qn7U&Z{vA!$ zbwwe~`Kc=g8%qD^gD=xk(Li#bDDVXtEi#+cS>dKhj_GZ4e)^b}Sby zc3HtcoBB&1{5DqlQs--2cm!$q9{fu$KR@+x4F4|!hXz)8@eAmToYD8M-_J}-z_rVP zLvD3%o~Ak1m66QF4we6RJ9Np1U^!>v=J;s<^B)lAzxT?2i#SK$8GcZrdpVNXeB$yQ zZ36fZ7n6b-0#+bj^D4RyObVWP;vk)pLQaa*5D@j1r@9@U=k(a#^|&~}0GAmU$^1lG zIeAo)^G7exrjIohU*4BpfQy$SnE9Kb=D7glt{kABbP8Q@=6f)vG zL;`-25B}>x3hUEU+v%;2->y!_bMKn3#0TrQGQC;VaEnIY&Hj0Smc&nz^ZGBg=dEjU zlzWDf-8IUZ^2P% zPy}uUUtFa(Iq!ZcUIR$~G`n-**aK`qzh1@dQ-K|O1ttb|?C=j0-hZ4O(rMQ}kQl1A z5q}U@J}ovRLXoS{eos5Udn^5M!h6Vs<$2VZ3z$yik0;&+Oa}fUfdsCW2Y*1{XID-4 zKSobK4ZC&KdzfbIK?mzk?_tNaz8^dGQ;Pm`+9|caEbY<_;AtANXb0;9@ZjI7d_-U? z62avE{oz47qX7oL#I*m@H9~V$JjVVR)?wuQ|Ka=JwRnEOA zY4dTa<1bYQ>p^+XroU4dT*mR9k^DB5`SyTiYyRlhnL)T1U4lRq@HLkkh5B=Fi*-(A z@FfcBh(t(>XWvWM=7&xyHIZGI-0Dt%=uHw6+SuShchBmKyD#bIg#4d_TLa-VJ~eEM z7vcCK8KTdG?snQFf6BfhExFK@n>5=(`==D*BJ)Qt=xN{2jBFOpAaBS!C_pYnt7TMX z8&vfCddU1@o6#+=43qBM5mLC=DT6pa`Lo_!EypGKZjzeAgRfO6OygaVKaY(t-tM2s zzpyW;t+cFslBMy;SMg+O8DUbq?Xec#UXocR$@h)Q)tiT5Y}-?~2hO!&k(7;Veep;~ zF`2He{Y=A(bIdeV>r4z{$L^K@3fqfj+%{XIjtu69fgHOBWIi=wptyibqmpJ*HxMrZAS8!Vq%C!GAW^TR6v~gl zhPr?eA;N;9BzLl)WK;^;$q1q0OOj}Z$gU}jrh-dpA&(dtjO@wMQ3Z9W5%3uvHV;1c z13$Kq$)t}uoruS#ZS6EWRe!=D5Mf!GcBn73; zU*^VQjshAu7NgTZP#!x#CW)k|Dbo*yf5pJXdP*^*5R90z3GF=3-KyRwSBoo(n6%B2 zm5-tVR7#$reG%}Jx#N$LKkE>p04A#t^WqGV^|)@c0lz zA?m%SGST9KcM+exZ!cXFK9NE!^9J+B@A@Fj=%+X$ba>x_dkx3#F9#~L!jD4ZSyFZq ze~3d9@^IMnXi|feAFqmS6?P3*bzzY~hB$eR@e={s)I`}6#!&f`G;p9OeK#qgWC#;a zaIRvUz1`NyvQS1un24a5BxE_(43C@83%751M2f&>-21T_t4!PzDMOZB%rbolw|M(%!T4CGdwn8U6q;#AgS${V+v@m6@4ZYp>k-1Iyn0SWi%%u#+y(j% zCgaxXH#b|}T_4%EHg`E2pVu5cKUklJogKj^!@$S&XQ$20f_Unc&LbUM7h*fz3D)|M>fATN zrHfDPOmRo^xH6;uA=yBPetZYX(Qy-x;%-n>>rL`9ln$wv1H80nV)O!HopP~O^l5`) zjIzbp(b>8YIV7aah*T0vv7S-ocnQpg4#94|J>)nyQp6M;I(3NlVniuvIif#wKet7q z>Uo`cCrj+3k?LOTh;D|uiJ^q&Mp#rm1|9c%hb}*-+i@$BSv##F>BA{$&Xxr5I%Ot?f0iF`s2CoDb?5<5siQ`aHPvxZ}Th?7pwZzw3oBmai#P9}H0p_F;#Y^ zis;27v3H_qgX<*J_;CkY3ha7}((9TQ*7$3b$sJf_j3ANd^;T&j5%eX{%iW(IOk)ICG4YLY}AI<69!T zYD?fwii42m&$&kfuZYs)O3!En39N8@HXc#UcrA%MMV(44jRqAwWqN!pcYEe^4If;D z>8#a7)zO5YR;<@A7+LJ4n9Lv_FBH8631f5$l!4#3{E`f38rL+KiN4{}@BTMJZ0kCivDG3zJtd5doEi ziFusb-ToTveQx+#oJcF7XXFas>7uWtmp{avw3VFhMnY1?Q%U>P1s~>@)@*M?Ae7h? zX#7Ix41CmcD+RO$wc#*0hmvs9NRzqT@kAq?iDkBCQkdQU|?1VQ;d9{9Rw z<`|>tV8R$JTt}ot_9jo1?3>}?iF~&hcTbQg?-O(fc%hf*;oVbSIqbBcI@w&(KnN6! zE7xarFuAy7x|wto63Ao-w-ERZqu$JUHSb$WC5|lt9i1P9w}%w3(PnU}Q9Zv+q-TUB zpmqTT=H@GE&Ibv+Lo!#d6Df|myZcSW_+ek`JHe3$5U(buDX`^!JzGyECvGDK0wk<~ zlLPa0Nx!&{b0Ga0rCd-NuYV%zm}qICjt?kCxIukQRq!0&ikO-@O+Jc+-xl2v*CZ7| zphL9d>$~8mD}=7A&sCWQ47}(L%6c`{1bg-)Jv0*A^v6Ik08n$r|6~S~w>X;VaO0$_I#&6Rw?59Oes|3$%Hypc>8ozMP@Ahhr%T-w0 zgaq5g_q`qmwuFc_wn+Pv%>yi<=QxuOaqtbKe1;?#gh3vkv2lED-z`d~g;ddGH*2w!yiQWW3TQv_quyl8Nz3x-E9l#3jUTT%re2ws+-v!oP!$ThNMAcO<@T z!(s91sYMBm@FS3EAGw9R587umdtZl_20p^YK3|7?T-*pyvc0_ReecWq`d0e#uGnzF z*uC>pJay>_q&j?~?ERWkd}Av8bW)ziX5*CDx@|=}uxNX}ELagODTi0!>g<*I6;;B<^&N zq6{8CriuzZSL#3vgsX~+&jWc<6@U)8!%y%$4PPFjtx}*8>}&95bRnEAIq?1}cx)wc z&mjeAHdU@X2?{6Ocn7;)1s7|MUH%3GB-D7}9tF8}YIj76Oin7#J?tB?DYqCO$8kMH z?w8QCBZDiX+)IA|o=rKpjg}!3T`8LWkvffE1u{I6jzF1-EE{D|Erm^lpFt6~(TI0i z1c~jJaQ2FxUljik{Uk>e$JswCKil7JE$c0Pwzqh8K0P)d%-eD3_IiJ>hmgmZ>TM+^N361G3LL zEO!aXCE1awU_8k8FtY3MczzU;-v8q<%vh$(oP?%e7om|+sBiSESQg^osa02 ze=Z8C7`Z1pLs?d#f<1?$ArAVAnpp8Eubq+BfG1_^CFF|{WJf%A7ww(7c5d=);#lSD zNF%(UQ``7|VTyI$Nvu$JahJHYQf^0OvPm5(&RP8j9sMu&xB3zN*ZsL6hA15hCM4mg)1qAOW@)y;pL^~ zS1Y;ATPmbhD(G0MDO8%Gjjn-03p?eD78Z-eE8DwUrWhxt93ZA@{2)jeWLH?wFo*SU z#AW4)5DR{Ct9agP9&4={D&9tS^EfH2v2q<9Axkxgodm>z7vjhSah3qN5LY5oRw4;j z+VfWWs#W@-S5~f|v-V4TX|tn<3qv4$<=ckCh^)F#`!rrc$%cu*{A)SiHmM6QZkjP9 ztE=KxXf;ApHT-Nf7_J6^qNdalQcPS^(j~?7xjf~x>RHpftr$ohFVQB2&kiN2-ErLO z5<;i&*G$w5J-&)+w$W(Z6d7?uj(rt&jum{63cI+vTv$zo3vYEs4RYoVQOR1(aD+s@ zg1?IG;U2zx2@E0;6%-Oh+_NkNvyMSS!J!z-GArBs9#~4Ms zzND)QUJ%)CqYLCj6DHhTIMT`I)@@J8Gw97TAegq6-e&R|qFh^{YSR8@f^?u(vXf5- ztZ0GI#BMfDnri$WEQnk!3F4sWK?(&s${>R+JBS6lT6aq8IXs0$s-TNiJ*_H|*msQF zY?MY!-VJ=za%;-KuJCh$Jbwgog7$(b;nhg;B2@U3!7{~8-UvEuN}yg-AE}EV>lmB zioghP-Bke)%>*KnK#GD}j+CERJZOm028V=i^Yk%8?Np>c^9ph(r zkiR=Jw>+3bIi8O{j6{Vv^Ms0F7N^|vX?X%}eC>N^|0rT=>$SHyQnkK&x-=%(2n(_W zPf&=gsd!HJ$DhHC`{++H>)3w5eO~}G(Zstp{33iJi}I5(dT08#Al6XEnW22!qMZ1Y z$>utIB`1>9O_3}U>fMBHY9a!p?BQeK2?U)96xo^u=Qot799=b?_OoooMbrK8GkfZ| zp{86OQR26K8)gw^tB%{n=VxKyIhFZ#2?Aa!vpJf2V!DDk2B|snsX3;tIZDj=JLhwp z_vg9p&#~9f-wm3-Uog*K|JnH#L7yVoS=x!hX&c@scei>08=a97*%#JIiaz%L~HGc4o_9 zuVu%AWvBDyS7a*=_g9>yR$Qf4p2C>PM97GUa69uRr-R5=(=b-UgMwF_S94ibW29E& z%vRrMtY)08CXlVgv##ZuHh*&#->SPY`*^8a(n1(9a$x$u1Coz^X99|3u_#U`#Wl9GHL0E z#S;eb{Rvo<*e<*2klw8toLwpyR(Z&{6$wS4#BJ*HWW0zqj+giM`Uxq~r>0~FIlzT4bZ{O2Fv|N(FO_LD3^msy1Wra^E5lgdCScRwrd<3UAAf7+->S%new(leV?9rNcBXU}_ZxC{xc%B% zQosi6#zsew(bP5}<=_#_6eKu94(E=DNF*H7m(1^lfy*O|VyXSWAB*WxEqDLiBQH|^ zR|q%c7DU5tzAiW|!5PjF+uEq+Q;@qi7M({x0!xK-(HPPN4; zebK0Q{)RRrbVLpcd;1n=0!N9G4v{nmC&nsfW~f1cL8(1n1#s6%s5#yBacz|H5<_Fe z{(z~S=U(tKj4TjRuAd$aGn{TuP&+cKgQeo2KpUfVJPuGq+3mY1LLMWz;4Zidb0{j7 zXSwfxQ2T1THCY$jeXhO=-6J~?}J{_Wc`<`;n! zqT4|rITZigd-EYT8|xl}nd$F)PB4kyb9YbM=7Hl{D13k=aK?t_g*4Yp@oCM{D;&dd z*RRmyI!8XKJLGyB1(IMZy9lY>!Vc@g*v^NPB?x0*@~A6xg#bPO>q-?_k|&2aLskSs zEr>?En{eD+A)67!k-SY~$(}91KY8B=xiF+ys_2o$@kdYOkiR7(- z*0H5buQ8TAQPR{yd!k&#fm86+)+*r6sjdWmt=xLNsiL+|nV6zZ@Iy`&y=c9175yYH zPF2IKjB-_g#fh(GTCoTyK~^_7pIW|uh$~~&`;bfh#jsw5x}71%p}NCzMumnW@C1^v z-diLraRvQQo&j(e8;BZI1b6=zq7gFF@UIRofLIC@%l#_2qbC^3`Uha}pW>~b;Er8$ z_oXrysR{wd`7gTmKb>yFZewS2sMtUv4 zL3)M61@(vD%B3>@K8OL70(b9nN55UW{v)dMx9;%|Q0ouPuTX8){|<>ZdQ78OVpPVU z_djTz{{Mi*z-4v>QLt z)qc3z#LrK6B{kH2ZM=H^zV8+juv^<8*#By`{zo|WpWq^o0@^R!Udb2SZ~+wk8IHZ8 z4F8Kt^eV&uPv?)o!T2Y*_yd@}#O z8z2)efV&B7!Zhd`>OYPQX9Pvj6`4aY#my-+F}b;h-{B-=k&Pw{*1yrR7RUR4lz(2a z_5VLUGSY}IL&}95Q7pTDY{GIPA2;83!Uh5W4l<{LZUg2c7xp6vpv|j(Mf@OokUj_< z_<$D#`{!o-iK_57%{(eC>QC7@@Q2y}--Vxli00Qt1wKdtvH$wu+tvR-4){7eK#stF zF!)ch1e*Dz$N#Lf{tMgYM+DZN**3X*1i#MYA3aWgf|oy3C;#M<{HHVdi%aqy<&}n| zVEo(~;M`dO-@)fgTZX?Ga1~NEYhwNb*}tk|`k%NE|Ga#EICli}trx|AQdIA|yyoul zg^9@j(?aX?ztf7=hYSA;dxAeIWxvykfK=hVvf+C_PbsiNmLM_EAV?cH3S0kn7^#{V z2yPqw!944YCHjAV6#lS7|9>t|e>)04X+=Ni^H;RQ1xKtus6+4|U<>4d`%?>g32Xrj z6pr%u;)Ead?{ez@WrhC#VGGD%lv9T0Mf2r>OBI80GRDHeyJZ82)#8H{SJ zg+6LvvN&>bXDuue5hNA@b&VK6QEzBpQ7LP5%SSwGspHkfL4^;VX4M#|Xc|9!g{@y- zv}5VsVJe-a(Qhrd45l8*BbL(OUfG;rAe#mT;5oMWqGbaK_tWxSa5%pe(@|E|eO(z+ z>etIZyXl38h?bS?N@Pe2<;B!E#B#-Wz7We2X&Txpu>ZuM-x(}?lmyyypiS^02}IUr zqD&p>x5yOBQg&s%k}>fgoM!$ldRisI11d6d&;|8t3vfTe*zTHYbOTgm zfXiMo)B_X#>>1!9E69L|t2mL}rv+w!qmo)s?$-(nro<1Telwuai~y3kA0ZmP2n|P- z(y=*tw=5o44i*K4CDV&K!Z6Nt{r1v((i@yUGv65a+>nYBrW;8?V>pn5f0y&)o7WahAnkivN3!=~t?{(3l9Q%48of{FP)uft$qQ%I-A=WWs{3&-x zIgs;)Tsm4Z>5xl)z3thXBQ1G`aFuM-MOFZa%F9wfO48}s%_V-c}WZxKZHYIA);bNxZAC+y{QPvAPp>tLE{KLANSxgOH`S-<04yVG{&XfWu6RxBxMwzddsCW*k%tr%dMo;p?w&R=eEeU91iz z)ZCxD#aE#Xl7806``pMIWG1<7tMRT$kNkChsVz<^%$_dkenLJ1gD$5Sg47+6IGN6S&} zTGb+n?#rPJnXb>hRcK>Pf<|dy8YWg{#@RHV&Q8%WzBryCVQe?9 zqdvXW^z}ykHuN#4Sidn^_#IYDEpV0So4J0lY1vT(> zT~^hUdCVp4-Tg+^@3@u$*KVGp?!Dgo$k+D!XwVd}gsPE}+X{ua_)T+V8a7y?VaY~! zKMCt^+LUrR#_tZZdu+bwW~0pV1f`*XTJgY?S!pA;OPF4a*aVw$Iaw^L+fCTDz?@|e zAghx{Q|^1F_RhF4$L%@v+liG8AxBJA&B4;IWD|pQB&y~D?d})oK3ViXiAwh=SXr%1 zxL>`N8J$?YzEO0}vsToiak^ICrNO&dQPESgRo5Hj;0jl)Tf0Se-m|*a6*uLy*885U zZl#CGoPTdvDfrvrm>t%)FICT8anCMbnVlb>raZlWxIC0gBk`OxK! zO8vT77AM#s>{mYq6p2XC13=Et{FfpD*!~G0f6;p2frb8vn%h$Ap&KEh?!-#rP2phl zi=4zC(stlUs3#so{!AP}EHv|B+;vN%K~!tNJcaeL6C-Ws#+;m? zJPBgX2r4K}vnnz?M(L257EZV-U~pDtt3O_fJ)8TDA(}$3cu@a>(I_b7rG2ao^1%p+cwSS*T3$dH zY&GL;c&E62X35yvqISug;nKV6G1UnH)VGI*g_^YMOn@&l`dgq#jBl9vs3NbF70SNE zD}Nc58v_F2#VI?;bDYLki7O)IiJ5vT$<#2=ga{YGNS1VuY>i0Q zm@OK?*W+(BuQ&6UgXhSGw_EWvX}+|zU*ugp_=t|siu1O8r-M4rW~cV)=rfWunu@pV z24bS2o(Q*lCvv;Em-#{vz|e{>FQ1T#UH$wbYe4%d@-bg zuGPzCeQ0_tfjFA>gtz>ya{rW%NFv0^5W9e42C->5cOgC?J$Ww4E+}dR-oe%(Ix4)N zT1*v|RyhY2tbe%>_W&H$*&8GDyxYVr;z*O%O#X+EP2i zZ#{d3&}fwo_2kl9o45hhbEm$`rok*Kd$Tu<%#B)^5hv?omS`G}&B>Rnp(us~@yTjz zN||I-YTpI%!&w2p^4wQ-JXQvy6=0gFvuI(V$#*(QMqZA^*BHF>MMFdFx!meX8hXmn z`~2U{+uG2WP=$L+g5=UwS!}zbb9DoB80r_g31_t#V5(vf12LuZE()e)Mtbj_gt1tm z61{L9v@udssi5}j`kLSMmeGx=S0&zfX8BDT%v9t5WA82FqU^f%;h7<128E$Rr5qXr zQ3(+lx+GOnrBg};1QF>Py1R!4=@KcC5DX-w1PMVzQ52*E=6}u*>UHTA_j5n*@BQ%n z{Kz2Z>~rt6*E-fZjze>57-T-fmh)`j%*v;Brsr7`(8aGCPmn@5=1`^MC>0DRgY!}eei`0#hU4!jv-%1Z(Ac$& zZqP*QDx_{+|IF8hc_=u}azXM*U6#UyZ6OLCPOu*ORrRZjg58huDMmNU3&);mYG{Ak z)}cGCFn#&@fsYNZ(3btV`Q5J`i#dG_uWWs8Xl)v_xf;t!m8O|iD`Z{!mWZV}p2YHC9ygf+d9h9=B5l-vDLZux-(`hJ#G z{>%Y$%0p3s2w8$lsM8tknd)&T_HC1ZYorp8GqVJMP;Alo)2f#mwz}>h3x;stCaxdr z=H7`P5UuZoCC-s?%!FoKdLL#M~dlvJclnG)IWSwJoi7jQXxI@6KiFOM^VnVeejq$e-DLC-~SxJ{EW<_W{i7&+h~f5G29uEA?pLXR2lXq*_D2oQDOb zk8QO8sx{wHMnHtqaOAM?DS*6ia5Q{l@ZKT7%8Gd7%NlpVrBog$NeoNR%YhPcn=Peg zs-od&Ox|{3;w29)utF!SbhUbJxSk0^Wi#q%4XJ|^OdTyMn=i@qBHj)Qu^#O;BYo0Y)h2sZL6?;@R zvMN?;U6Lf9?yMuJ>aJh!dfn{ndL&U~=|l4~bpiI<_Vvh5H|uX2H%OnEKELsbdG4wg zq0!nEi9o8@F|QZvvg6hZSgC7P7AG}-yfTjPAc)b|!!DL5gra$iha|Pg^)3fo41<6; zk#I=mg$Qov7v^bhuiwoLc>B{ihJh4`)Tm{u;69HeN7ZXH;wC*6GOifkU^k05Ym^hV= zYcb^KxiuJ?9L8|lGBeGHW*%_H(ddCto1L0LLeVJBRH}!V4Xc!j_AWNlYnqzxljwT6 z-j{&e71g2%i*>_AN!ML^crU>w{6Lk+Y_#;(tyr~EHigU#)3O^Ta5h+0p&N)F+l3TZ+bh#gTZQS2(d+lvp*!ISJjq178+LQ;b^$pK3uAkNluT;-Jj8fUez=sck4#+n{ z=odYR&QB<^%Ugo~*8jq3Pt)s3v+~T8FaPttl?K{$SqoV;jcKY5ahJX^)HyTx@T)NkqPwH#0kFDOl zLY=o%3lKxGdR$-99NPv<0)y^FbbKkJbn{(#^H=W1@MRPT)^?92De;ySqW<5GVCk1R(B;@y>+t$#W8T;G+?s zS7x-a7DlS@5sFDikgPKx1O4pHXz)so zE;rqe%Suu?=FEJ4UQPkvdtW_|b-C8~$s!2wG<#ptOvwFbiy&Fx8}#EWg0L>v*FQHe z)J*tsf2@5Id+lE4cxoY*XY>AJ{lPE$Nfgi}egt9%e1bTDZT8}43ZPnggCCAQ8Zps? z0`y6FoK+1xLYSm%`%f)qc1Cd=V)?vUI^7!0FR{JxR&}B&h|PHZQ9Khg9|3iOwK?}u z!}Ub`xom_{12V3~y1Xg(7YAFJ@IGAG%=Rf5^r}{zjsAl5ohH!Fydt_tGg_iB)|jHC zl{<3ZbY|)(%HdOQCMcZkYtR>cRRQFIIo3O0X2o4k(scwYT7mNOyjkrkyXXLZc)C>3 zk94k`E}d+W3vvOxpM3-0vK_y_y1~ZX8x%l&_({Gtlqxz*?-!a`H9cG$28pG zGyl2q0Ei`j?;>LfbhpOggwJ@^Rd7s0S7Z4d`+DxMusw-6{|CnVzLOeNQpg_$8#;mP z(;Y+!yiC)dUnUmqgnZ9-_A^jf%3UDiOf)Xr!DgWEZYWB)V~sl>-$W*ORo~tpY#=wu z-({^*bw$7HPu|}~0NOnLLtl{!e}{yP3@RF8|q7 z@xR@0{C$@Rc-ibl9AkDe^8*z^GY{{F%;}A^UV|$$r5@MrE3$e_=s_(IMA1LhmFZ5qi*#CSY7GFB;X&`g}TI&B&XcEW0-Jz8J zpr!uD69LRsv<9?iZ1@oG%DUi$g}NhRLFA9L<5cozw1Ng&jMcO?`D(i+d1DR zJG``fo8mm1|2Fl`${!rD3+6I|e|E%PjqrJwV{X;;&U*J);rfs{K>6YVk_6s=%pXch z;6NAuO3Ca;Wb(&U=fC~_%bPyV?315?bIy*}w13XQy8!^Vg(Cp7tRRThKi|RtxLO9@ zyI}q|zrvqHD*k4$fPMRPc-8!``|WaWg-i*PfE@tl!)=kpSwIr~E!1E~5?!Ad5M#q` z;i3Ppw(zt5E1_psu&vbCYU6NeYRf-vVLvGnk$<^`nb?4f=I$5Hx%Bm6skw{*HtZG_ zFtx~HAl!@gK)DSEvjf);E%35yaQjtlq5+t!qu$K5XY%mcre}G@G7;AtKu)l|wEBrj z%9YLzDj)81J`$hmr0u%tb83(tL_$#-dGCpMw8@AmW%I|h26xaMSa^PEZj(L+vgyrv zA`+BR>_MX32{-J)S7Ihv=3tt7?k|0ETZ+DaN(Fq*6DC%_Z1ysRG24%-$I9S}mq~vl zb6fRHYXLr()JLHgp_y~Yeft{?Rk38yL7S>;r|YOp<9VpIUp-j)fNX*6>K@>-5er}< z<_bgtw{bCK|J7{73ljF%vDe9p+snLrM*`wIoqu;wL_bUcr#}O@VE-T=^52QQ4S2gg z7DE;6arYW_Hm=_Hjf-(1{I&G7AO^f6kCW(Nd{I*G6PChe32~Mlu7@)C#(anf(qLQC-oz`sJ6QQLIY5r*Dn~ z=Tn%gCJQMc1VM<%55!BLCq#gc~*l4Dncwaaumg6Y2XT@>z{ z=!_SKbUvxOY1j;zx8y9!PBVX&q*}Ogw(iT!fZ2t{ft`BWMhOsksSL(g7jyCM4M?&;T<9F+(9H^LJ)L&V)&I9$Fo z1i~l}t~YE=6+hK&e6H{45cV>`F^qa7LWqQpiE2pSIAF$~;bx&kt%3Px&x`c#eN-!q z*C%CWC*-~vR*(B^5(v|JGAWY{yCB9_Gm!79h9+F?3_Fsj8{-LH$$gcno|Joy%4><7 z;UP@J!m!xUDuH$t=auMO<@yuow`r~rE)J!elG6Ei&TBGP4*BZ6K;Luj3Qoa^+8eV-OeMPX;17hI1$T(SGb_U?Z^@DC@4y7E?d#ttA7Z%-_t0O2Kh1c)c+V3o|!bM}AKfwEkDjZA`EhxI4`fJl<~ zk2TyzBzs>jbPJI8InC1Qil?MG)6ZgPGk2qyjT`@n!g|BD zI4R!r;6$CzROEqj&*PMs=G!z6lqL4-h8Id`5blR_+%qtPw19>B2??$uQsV$xu|F^F zPnM8j+bRW5)~;oDqgL=AC9m_(Duo}!KzlgTvyo{+sw#mjAde@RGbZL zFQ!PF#Zwo^ho+$e2pWO~hwTdUpo{8Yw6z$(M)@%8zHJR9VnQC*i_$ufL)q!TG+58L z1ncJ%lDN{$Ho7i0LNj^w5&Z%kD^D}OS|>B(``}^PoAN19q5&qDRF_OjT;rOS~HE0_DpoU}-+OEA8+C^tqx<{UYxIwX&>+h0uBxhw45hB=QeR^xoIZ|gbt4cF-&sNI^=l8jyHG}0*Z3sBiA$$YaMbq7 z{MUlZ1z=lchlC2mSc8oVVIJ4ez3xhP8O0gVm*!Uv-GOokN7UU;W1Up#S1Z*pJJ z9scHDdR5;2t6JfBV&$cJP4xNtD)u!Ro0s4_`A43LvbVc(ZVfmEts^e`UTqjZT>Gka zNf4$7-5)3g`j<>#1hB2JgI4dcPJ0}SjNd(qyqh4>n~u*jnm~kn^cS^1Pqu`>@euNo zYzmOTLx;BY>d2>&t`Hk=DJz^!Du#!cWYe@HrW0f{BJw1V!sIC+?%G^gr^c$7CF(A_ zJV!bI0)5{9ekJM)Lb*VX^tepHvf-sTqGPGaR)Rc|@!Dd3Gm3rhTY`vA-=|U%yw+D| z!Mc$Z$mGH2Zf$qJ-*q|dNeO=)xryaKoO~o31`&48IU;ZS@n)(}V-=hx%EXX`aO+ zsWQX5Y)Y7apS}{uyxaaJ{fgQn=)bZ5@4b6Cm*~gWt zm=)ctHd*BbTq>rX5uGM3B1U+=uZM6kE+-5uBXihW%De6?@*DP|vpa3$-%U?PLN-sd z<&Q9%Jj}X6vpraFt7n$trs(Os`=)bq&BU0Pa-k!WT%!=i!j5G4w;Xo`#G^F67XFRE z#L73XRU@K3UVLFy8+DVo!lov+s89-}QwZ->;YL^9IO56VIS|i_;owknn;w>A@YNW* zltNjmOk^a7VTzeTc3d~@_Fk!EX`?Pn(T)j%SV!Qya;<-j4aA@1c;hdq`BjMNZB07M-XMeVbPgqRq^CWOBg0Tpa!xQjNfNdkp-6|$s3aqaw<-CTbJ@TG z1etf@PtCPtVs^^x0TpRZKANW0Pl@Nh@wV9K?`(?UR1JJCYnxY7xaZg^0iI)0|o0V@%J{yC{iP-JeS(oaZdh%y2Of z+mxm7Y{sSo60tZdkqgZAsRzGZe*}yt;GDl4*RJJX@RLr%@vok_t0d{N<~tT@g|9ZE zsMh$HzUNKY=a9iYhZ*)cEPi+n58lYV=h$-~3&lBY^cuc2C*0%oY)HW$ zWDIxfa9774tBHS2kU2WU0O&mu?;}&da**Q*0GkfWusVu!)qx}HcMhD|M2jCEJrHxq zkU)a^w+r;!?GK>!0>EB<_wV+qLb=If{l8YqJo=BQMSmvF2z?CMbME@H&TT32L5mhPf;DR~AX}DQ+tw z9L$FMuK-w32(X}Zc>n6~rq zZvAIJ2^>d90n(#m4jx#6W7+Qz-19~^iG`2Ag6=j12YpKZ+H=abEe%PdnP;fCyR<+| z_%&XSi{ZbD3phNK2;f9f<6-NZe;kQ%F9WLgAHIx+yc>TaY_3d&RPW21{vs~SG%EkW zm+Dun)qg+>JGPbm)5`!@(-`Y(03MpYuZ{a(iz>fe_uU2x0)&F>aI61(10LA^Jr|7{ zKmBKJwO#p>A1N#kQ*hJixTdZWOUND$ExEv6M zB7iW2`gd`Ceeu7agFO51<{*E11Aj7CeQkMT-_=+2>HK(W5MaCWiyY+KtwsFLqp!u! z?Bv#ev7LbQI z<9EOGT~_?lS+V_O7FTv504qpru7tvsU08o=JTMdGqFn~am+0_uA7?cdDKAQQg;N0b z)8vZzuyt*yClyHol`FXTE(8vl?f_~!nN*)r$CT&)gF{kcb$!7a8 zJpDSB|J&$~yDvz=-z(42{X7#`0wSQ2p#?DmOVEg20^uIU7Ow*oupYFG2emRD9n6R5 zdd5R+C39r$+H|u!?E<)#sCQc4msKd0(juHy(sPyk9_3=8iK3Sf0pVIlMJ_TNNg5l? z0z#^~i@DgIS6fbfie}7Wz*k!`e;x`gBR{qA+@Lp^)^o9F{Ss)%hsfiu*x@B6c(KXT z+dTJIa$f~E{|4=CVp3g6B8-z}?;DI(VF{y4KTY_(rf0gD9# za%((X7D@_GtKl5!xXPCWvA?GPJP`^^%p3p_0Siiv#S_<5Td>5O_LZ z)9xC(VZd3Dc=vpTKp1L;KYQ%I4P5jU0EIxff#?3md57iq3AKMdK)`BnW4BbsskH!S z?DU4wU-SjdhjI7cKQkWvgUiL=PKC8%B=)VX8F_XG2!3T=P;%c@;@k4lYmyy_ga0JA z12#4_9zTcxw~^a0P4S?Mj_=3w0eE8=g6Ik z0#eGsbnIaW4V72&T-kJU1im}-rj{LXIKF}|RGRMdYiiCSZ3QBuZboGkz8--A>qPFu zNE=B17ZJ6Y7s1<`tdmAP7Lx8;*0B2w;X1CswrYD!a~Z>>0;RO0=ilfeQs(Kq7YX z*P(zwZ=cPvKi{}V)I2(_^cOxR|DeF$TDSX)Q1A!grd^q#tj2&}c@Y2GQ1HufIH8?H z>~(jh{%(QIsLA)cakyC-MhRlJxrx2n`acO0z!n05nLrE>Yymif-9o~pJE!*YE^_w^ zks6ach4k16j^7!9s0MEn5^gE%!nXUy#HJz+$brHOKaJrSlQ(B63N^;h*|yWkP7aY6!S22p^hfN#zTVznek?zgypR1pZk z9JhK^%YO_2tXXgGHwb|^K?bZF9QX$!V*CN||KkuRWb?0TLDHo+(w+hpu>^lmmKCnkaZSMK3NZr~$p{uP8st#h?pbP7pU)D&fzZ^`2aqquIJJ z3DJo22gWs+@~?91Y4?4pqyl+dssGw*h0n!rrs-weL4LlQip4N!XZYxIvpxqwy3bku z^65tE{p1t)+B=KJ1bhV%&}mCDV9_MJ6R;W_dyD4W!?^3ORyN)0L~CP+@1lc&7dy%FT9iX#JZr_ z5Qg*d1ry(0q>hr3MsEu5m0|yvJXKu#|4H)nV}ga*>v~YI+}TaAep@pC_6NJr(0`B` zQ~mqq$S+dk+s1!!AO7#A#_s=FYK#LhBLEQd|B4ChH1a3@Br{@DNA%jABSOW-(se`=KgZhd>~kG-PqA4(uDf(rhQ z*pN6KZcA;>=nF-j8V!$H&qOv7g_Yfg%jN*DL84Y;RLm@ivf9iR)Eq9>SW;aTp#0 z+8ZM6uE1zKuCfh(xM$1fY3C962VBvyt#z-x@wdqCuP2PB0y%aK!(wh6Z{Kww_23`R z1Bi^c(Rf16AAHIqDQ4r3MX8~v_UhgLyE^~f)%n{{@!KEZ&dlG23gGzs_?drmb^b+K z_n*Gq|GPT>4~P3_SLa`BzTe&mf7t84xH|uIX8z52_=}VHf9K)fM!Ubgy|@12_EzkT z{-?Kh)A!pO(z%<$Y`ogPz2$eO?g>VmcDR{s+B+)ZO$*$(;e;e|6qHY`r}x$H!)_-6)TfU zN3FU$oFMgq7ckX*kL`zlGuq(?`Rw1`X`^ocvM>AF+gpWI55-eG2gne#b4;KFeytIT z_Bll!{U+jk>h8t;7keByT|Z`M-{qHq8vlDX`T&3`=>E5|(Y-|MCuHk4b0&K=KDj%X z;kkUGJo?AchLj~)ah$PW+Y_9{nB3Ibqy}Wvd)f=$+zoW&NJ|J8ho!Fe?lb0J2`7(XQx<(S<&G zT#=`q%C1^nF1G~8cksIt7Ryrs{Tvp|`UR`!n#x56twzx!1yr0Bl5GW7>iOUGyW3Bb zn<{DX>eSgEcv9TGI$u(}V!Qotw1$7E-sLO()q`L4dz+o71yV0lmR)X(KH1%Gb)m%M zX}WP{zw3oB<2?vDnu|{di>JEtj4O_~tyc~Rq7P2JOsSu+ecb@vre?ToQ12z#_vI={ z@_MsoD*>1Pob$xQ^YV(4NB0^;}i=zQn20njQm3_Uw#krg4o5}*@# zp5fgaSt5=%&%H3r(Le+1?`-PyRz~)7l~vANke?5*59TEc;)A%>FB;AQ)f&O%s}eG@qLi$8x041;*U3$UhV&%|{bR_Y3BvJAVBjN#RKT%nLteLNy%cy5l>^C4skbNli%Y4k8 z)xaj27Dj&BSBE=+1l|T>BKg`CcZr0u*yCpLJDa450%%@*R;=h0^)poA@krHsNwblm zf?Re5c-Jl92b^?;!i(}*-hV3dANlgU^x?BYp5{iDadLlnpiMT;C076yjQ8cumovYOGGxwvfUCK|?x30}S_s~9tq zTDGM#Z0p)kJ%UsgYi1*_oWAtRs%kBwowILCQjt@q6U~CeX`wyJkN(ij#4OJTueZBQ{Tn{7mmBBES zqAA>11-_yGrLg`(C&R_lgTi*j+%Gwk@-W+*tDi6!(7|-jo+Qty7ag?ZdleFJ#3jKh z0GogSILSwU#aE-JTq|MmKBdUIgbNYkR^; zxy)q|cs6AeuN)hzRf#Et6XPN4DAI3uAsU&wZFRrTv?~)#4st%@m?K*Vjzp+&n_lbA z7J=SSM#kBwMoY914sECwzs?2Mez{}8?csy)r;s9mom?2{2oUhnUsmgLJd1;a0dZF_BZ!QcVm|_A-D=bNlwyRQqAriMOZRNhqXTTW z#L5<5KJ+{^g38xma@boUTza<%tOOkn`5y=ARY8EesCj=f+#h}vhy3GUb8BJs=_Y;9 z8LLVyHH1tgK6_%(+NU(JI9AT>+nlDed@)oDW9OOLSf50bDL^JgDoi_L4(hXkAn9+F zqTxYo3dqtNl^A)ltIEw(Ak{Rr3i3N5R2i4Dj5@ZJ!lfl8pc!cu;yF94JvV+F!Au-msddAk%ZE+w+-664PPZ=)-sVQll1aBO zw5*(9jo@pQ2SXe$q~4GYv2ndq%h+DVLv8rpldjDpjg z58t}}y7QRO8xA+eA1>`*P3z#c1QBqX?;%U0`{F9V!eI%cRDeVTh^QHaA@~Or^{bm- zKWWLhQrK)oeR-}4@+8H8!;PN5QSw{4$R;n@$9mpR;6U#k`B{C47mr>9%Mi@4-dzD^ zo1d_ltM09*%eDFS6qjZ+FkZXK4mQ+`6C$qm((M^n_2uf0WRCHO=GCy#%{Y`~Qc#?? zl6d^0NL5S&ug1ZqLrFIcxH);~3LGrI#8EiSO9#5G)) zK+OP53nI$iJ;)=(=+8wkM2hqUk;%!e(za>oYquH zVX^aylCXQGVlVvmQ)AU(48E7M5&3f)BF9;|u+_h78kL|IKoNKW_=d~Q#-$t^RR0L`iArMd+dJ55SI58>$bp5|N$ z^I_2FWRzpeG=1*DJ1b-yT#@qirHgHucGg`!+c#quhD~b>{lzs_!#s&>FHT7;URowb z!AO_@*)7)mtKs;pYGk2iPxG>GND1bX#nTPUyjIZ(RX7?)XH#pIc!>EOoBUzwH}p|b z*C}VN5pF@X((#lz86^nEoy;8{%y3=}4fpe(MH(Hyo#48%uCP8BQ{)bkEjN+76hRt$ARz|F9p014A zb{txLbz@L@bLxZR}!Ds zu97T&YFtef9co{?v$-hF{rc?3=V6B)EH}zEJy`0~Cv{tS3Fr;3^uM=;FT5GNy1hP| z8@4@vJ4(exET_ZH+0vIibnV-h`ZUbDZ>#Q2n2m2~AUt{GHr;VYtI?EU%J_3*DK@w8 zJkmDUYR|!ROKoeUMyU}X5I(|?I4e;SbcV=>w=~nD7~}!dl83p<8~Sjce|VidJuuU) zm>}AGXYp4Vq!^cgvy4Vzw~=R!$Xx@ZSqLKnm8_>EsPpha@?HngLtd1P zg1(4SFDesx5M=0j5T&gom&Rl!O_V9AP_R9ve!UE5yLQW&tBawI#|Wrbp;As=EhSwe9l*t&tp9hdCCyQQW-H@Lt=ajh@{)uQG9C`L7_-V3L*>tBj9Ed z(K8fbJ*N)Sk&A!?N*A2))C{2S%f$4UG$4!D+NhIrC-aZC#k4T#a{#;3G4o|w;<+T8w@!fP9W&v_&=DO$f|}Bl^f%F$ zcl|2w@h*rNE9nhkMx3gvHVTHT!||!ukgzIy<`Ye91bWpFKkj}>nWs>E&>R;i4gWCb z;{CyEPBA3|ZYkq;m|G$rm1V_N_^Q(gjc0xdNs4#yhxA2`>lp|nRj)-qc_2DaXf@zb z4Z3t!$+)R_B(7jpEc=OB;21^LvR6Krq zNPnnh8L!NrX2Wn;mNhp2=&JzU4+hlr&Tah1uLtWrP=lDSwvQYof*S=+Gptf69wNT1 zt0;ML@Su4!9>N~lL0=|Qc}%&c5ht#4MN8%%jN`ba({`DpV)5KDGd{ib z$8}->UF3L52GnQ;p2LUble)cFylM{`4|vk1uAa@g!)&6$30sz1K9VfCwBBP&o|a3S zGbefCj9Kb>TLV4eoE-D{o$;(Q*qtsOTR~ww?6~|+^(S@5U3ZpUvanV!9~`+ zIUJ6jtCIdi%nZ>M;YJcchZwDbYp)x1pcwi5o^+OChuD;=0oLSSje@FYa_>{q63Xc( zxOPWD&p6C<6%e&BP+kkSmZ*Td&`{2+<{hmuoD7Z8i#_>?zCM+WVi&i4AhPuKS(a4V$9U7j-sti;=F?XF#u{lA z#2Cc%{j=)=$?_4$+~IdtzRpfZrSUc4+&rdVmo$lEFxvz~OzwD<)8x)8o5s)izH-b> zctK^?lzd3WAEt}1Ze9ozhi@BC`ce9=O$4yS%1;HdT6@!Q!qZ!j&^3vYD;;5!-YM|7_sf)Y~hM-=^IqR5Vs3BtbHS!&wR} zaB99;;pez4(a|bamf7)F3oLVzRbb{4z6=*F934qObNQZ`1y%(`_fQ4S(b<@OLQbuh ziFrwKPPORh^O6c?aW<*>Z1*0Pi&&R6GaUX<-X(bLLq%G(iFslFecgqsmu5=EcI>`f zaL&Y)PIS(+lhwzZo!j-E5~u5UX1`()p-lv^zYwJ|8iG@yv9^Q7FT%J_IlJ(}5SqP>t}_!7KokVM)y zvY_#!4ywH-H26yok5`?%3H&eo9^&`x!P49{%OChap<9xr5;YtcxI(|_fvY{e>@qw( zKBR}wfx;j*o&d9gqXi{?>E?&)8msm;^ABqf=`v!$q>ImoypFl8C}p!OcT>VjHG;@t z)}0m44{Uk)^!V2cuuo*iDGMuBJI|FGqiL3(<0~RFciIvPMAACZh=(?b+vlXvkO{0Q>Bg0j-*c=9CL=pK2uD-jW82(`e?_`NV5 zbmuj4#gh!)`;MUC)(k^URaN-r2k0hScsj)*d8AoLpqcU*2l7WsE+wp1*D{nnEDG3Q zp958bStxTk+PE~-12VmhWW9us(U(7R7kX!C&QmMQB-;~gdiIr9ueL11)kh(RJhSrO z)V4z#Uid4XVNue(ew4NM4NCJMf|@`<9(nGCz266xz9YwE(@#ZmE}+o$$4_^hkyH#j zU2b^M#DY?ax*VmqiDu8uOD81}kl2(8^dhgR)s$4d{=BPq@|atVriWq~#bXn3^C`BNh&LamdHPw~2RXdSNzbM+&WZIL`5XdE@vr5e{&ZeD$q%6gjNtb$1a zS;~^kstF*wpwlH)5S6-A`3@d2tl=hr0FxyS5DZ2a38cW|)$eDA$y;=2Zx<-iBDjvb z1}fRUv`sYDI7Uk5(mtn7kqF%?IMsT)-74`!5+N^CdM!Z3?*2_Qm*YFB^DwQbDNYu4 z`g~zW4)Ua_3%MR``37~`!fD45P>G@_UQ|Ff!wJR0S4T$0-JE-jMj|r9dM&i8Him># zHJIVq(Pr%V$2qUQ42+M~Iy|Dt+|gB4yh_Qg`W4pgjH$jT>s(cAtsE(T{NYmd*{AOe zJcBx-=rxNg=*K2EKdY0nPFmG)96JEAti9n(p9biOdCS@^v=#B1)T-}4|Dp`f4{yNO1U#C{kx3&z$w75pe4{6o<@N%+e z+BisyzSbR#D$nKr}wqca)1iF~ z{=MXzYu!g?$wOLrxwTUi7DOWlns_hC^H&6x$1bY-e3Wl~BY(&zYuMKOa)1|~?#&>m zyw^ho`!sIEiCof~#ncP-zMi%%1a}Sr;->K^E*HqO3eBAyHg&Yp2XOn;mAD6U1kL?u z^G}?#3)C6`lH!WSbWlYw^y?aZ%t-`1sHXLh2Bvo8UWk!SZz^4uXh^^+gA1IRL0W&o zH4PC7YO4Dx4>d6UNOwi3_{pFZ!rpV zyt|SuqPLoR?2#o;6A6c!NA#8z5eJ1 zc&iIMw(bEJU&^KacJWIE;q25EC=-sw%zKnXI+eYoES?c#q|Aet&NLlM^>|6-(@O51 z+ye>8@Ut;ox@(Qfli-8%YoJHlrIIFFZ_OuVA50z-JTfCcuAXiGY0c`0ktCF%&9`(I zp%C1#Y%1V7aN>@d?863b;!g-qX=Mqn=?08|_pn}WfJyc5%#Lr^kNI}LRfgQ(|R$jdGfD$3Cww(oFhFU?=5WM zecIXkOuYBmHE&T`pK}~OVjKqR#^jEX(1diTE*zSe4$WNjN$BypIOlVL7J4ZUs-^9# zTk5MF;Cofx*D%0Wz1i2q!cSMtPhZ~Gs?*n|*3Yif&w|$9yw=Zg&hKWtzf-*5?ErrR zd0(12w<KYHNe;4+T9~3u>ed&NK+B zat?YV9NZos+*TXh*%{oi7Th%y+)EVlj5efSIOJt~$UruguO0X?FK~eoMh4iK@NsF4P4O@#3JmC^57#J#yafv#U5Ovlvs-#mLpE?K~9{!vb)@Bh7&kt8{2~kRj zP!5b92?!bGh`IPUTHP|{LSW1#mzc{sL7X~wh{-|~I7s3wf~M?){D^!f(+T`IU|H$0 zW5O^?PMCSZAtNT3Q93lsK32^+)-NESS~xgqD9WcU%1gqz5K*t&XDr; z#6pE66_=#az@)N-qzY(~{xCUQomk2xmS2HXuom_nNxEzwP^Cs%$WKz}k&K4JrY1-i z(vx4f1XT8rzQ~77rNbsMAX7{;NvlQ5wpvPHU8?_Z>WB5z;I$}&$M7bmpcl0ycs)le zghMm=4gKPwh0XRE=`cpYAk1)DC}&7!GczWgq%x0WyBVf49HS?aL9LrXTM$D(5;JBI z+%il~ArMgxW{Px*DQ>HjBukBS1r95O zXK*A$6AWii1m;lX1H!*K8i`^g;X_)I z%^uRP{3P$yEIQ8^KB7%8X3E)CBYw+8k~5sP%>;{?kK6JnBINRtRzUH#<$}dcZ9uTd*`YkZN*=+09Z7Iu;g3>fQXx59oINQQF2iG7q zBHy-v8YfX0jbg~r`@!zqMc*vFxs@^wkJR`j)jpdm-ZUp=puUGuM4`FR!gK|u#DP^g z=5`8kn2pF(z*&U&KHs}YsH+dxWNGtU#nE@=b_IzZfx%;QMPj4T<$CqU?xz9s$atWX zu!Q>!-|8C=KWG+x5d2NXC!i_-T97FkAMae3$3eL50g`8e+bLAPBu1MPM}zCCM>}%| zX^TBEha)=j0!|UvRu)F1>cbP^4R!VPCkt~_0~^&un!e~YeRgfCQ)p5h4r$XPhe#*u zrq`HrmduU>+)c)p-HT zXIqZ(l&}W3umnFuyb54@@{sG!L(V&~1dro4+2JdJ&;*axGetgUU$vfl)hheARrpDW z*x5%CMLx2ZA4xuVB>&`*Tym@8+M_c^9tnEmD=@+37e%r>pc&0=m!E{_zsfb>X?LS< zmwwe|a<<*PsNKZ6-E_0v`bfKQQ6zeaU%gcnrcEwa+X21qQzNIt(b{pO41QrzewF>g zu@;I_Oeg$>mglo}_={}m*R+z#Q69!}@H1YI+xy%~A3aVz(wTneaptCA#`&&st*)84 zuDpX{=q!4I4E+8jl?MOwk%HY(gyed+x}`35*I9QX5C(Ztgp@-b29ttSZ`~cv2H-hS z=6s`=qyXdb6DGmIhEZ@5n(oH9r`P6kOPtv_2L=P1XikHY8VU z`c`Do#wTA2X~Jz@ymWeDRP|zu%Eok=ZN#UO#>rkc*GxyQH?{v6b4V}ySnox|8Bdh( zL^;!W%nf3+{b@1>((SX%DJKa_sNBvk*mXCJwPCYLOotCX~0;dk{7c;>h^}m4%qn_lvo1>_DHsBU`FMD-oJ;tRW$k@9rNcM(ppvTRUYe89vN{Pt3T2= zh&h0O#`kP5o?2ld$jHDCVkL-#3xuD%3i1$3YB(l*45XWGB7Bn%9mheqrA;;P`sz!L z12H4Uv#&R|UK3uOAUZd3ppj#?2yWFXeVB#4$bk54hvBE2=RQ;5UnnKdo`A^;8YaU< zLsnj?_X(*_oLh?>d(|+-H9j@8H8r|0g&uP}?Lb!VM4Vnsmy~W*la8;4gwakPgYrYQ z%7<4xhLalvQlAQ>7lXdK={h59$`6fJ@Xl0<&1m19(Y2kq%rJBHx zOyKu=LJ}1&xBNsQo-TwBq2Tmac*v=sKB0u3C!v=qPu(3=_BI7Az>}Mi$YLaDqK_GK zQY=pS3LgCRwLy`uHe4yk2yP1T5qg;go9bS0&`sEuPPXk$AyG>@H=lTQK2>Ete&Ag| z?*#Nkr_nKU4JPIl0YhT)Q-q!_kLafyY~MQG1Lfc1qilGa(*G7(BXY9!jeNQAq}Z8_ z584?^f)fpwK}Y2#uV|*p%nYT@XfjOeZO@dAEf{PsT(%trE6g4-)T_&uvgH17Ug87$ zbvG5txs4~X3@!zc4Qdsg z;AORWqf1zJtjpvv%(wen?wLpZpO0WZqiDX6&U|LEyTl~^g*|Mfr!}6`XEE3OW5-J8 z|D)|J+@f5&zCCnG42?9yFq9zDiVQuZbgOi?NQrdk(5<9&cStuXs5FR_N_T_IH|XB( z{XBa=@xJfz{Racb@w?Y`U2CoL3_xV;W>oEhtEK`j*T_3{79qo&1j}M0TN3n#Qa)2Y zpNI;U_j8#1_;!2*+HH65tA?E@a#;|G`V37Q9L>refnxSqUb;V`KL#U?W?7F7#g5G% zAG0hn^VDqPzOPhzaPWXzBB1eU4cU_+EGgUwuRD*CpE=(ZuS0kG1h)sLUfimo+^4|^ zA`+%u?AY-mnzOZgXK{~5PFfuWSXD**-!7zxr+E>h*3L{szP;y+XVT5982y%m;=Y3g zh%$CikQsW#`jxox_&fyIjqiDr{v_t*)S=)#Ht}~d&V(gCk`tU4Rgc|4C*qXct~RXD zYB7O5if7RdM5!YJeVm1;cOHF2Ftf%407wJIPJx>fn?iJ2MAlqRPzDS>RF_X*zTQyB zo#jRuH^KujIO4qbxPe`(A_4*I*>rSp$$8y4{o-JVDpy8RU&EiJ2oNaMLt@YujMD*n zJoPt)b|+uM(G0H5iplLhK$J>jZ5dpE8s5!%=6D9&u4ih#wv5s;^1e!K>nu}wyV^yd zBg}bR9vLIKV$HHgy=j^oTBWFiwIlS8(+Wqq2 z4A5AA0E0N-oZ2@5Kzfe=3iy^b1jQSMcD>N&DV60{M&0EQW4OG)2&>z)GD8Kedjxd> zo~gfo*{ZV_5|6V#WQmKBK|Rm~_u5pIKnY6VfuTil#tks~Y3%odx6W8=M=&e%!9f}= z)mbxL)gjptdPN2G2UEV-AQT5VLt#J@=_>h+#Hl6zG<0@mq-L3>yXe*qI=~O4w^o+x zDMJlyWXmeVLKNTLj5Us58Q2YB^eMlL9hMK+eE&i5_QQDf@q6R7A3d`*G{89ETiitJBad?1fTH^~27niI$EqA#g&VF3rnO#Hs4W3VIv$TfwWhgy* z;(%AHY7PLV%5SY)a!gi$&&FTmx}MoHV)%J(KJp5OY%(&3&OxyJ6K~Oe5k$_NzO@l& z;d3MDsA9#aypfH_CDoWzc>a7)MJ`eFSV2LQtn_U#Xm~3Q$sH|51eOdzm-sm}7*;|q zA2Ku!l^5GKj*@$OD*H5qd#qP+-+#8#g7tX&omz>r(lP3zotM6E+fQCZL_FIv_QrXQ zbuoX6d7A**-fjN?8xkmr@ZexPH+g9NrlI44U&W6Ae-w>{QXH4p(Vx7O0sS^+ ztlusxf&&^i18FKoxLHc*4VJd6C$?B zNaQ5MzUT2u9szw@pf>O#sbhx^YkHwJL=X-SVr|W( z#S&J~oA{9A!f9$@sU8oiFGxmB`(&ji)cZBI*n=^af%lX9n{~1g&m3cOJ_pvfX38Ja z#t}VWJ_YBrihJ=KWtQFSTSEPt`5)N5GU5asnv`8VUxj8&vtVw-!;;9@;<3Hd?mN{z zc)s+}{ridq6h%bEFMJqw>lvek%9^~>tLp3$d>oNkVbyT8!%Snw$4ceAtq|~bkkKK; zp?FCtF3FUgDL))b!T&>9VXeKTFxx)+On;mVspiY7G_A3sH?G?*uf)EuNeimCZP-2V z31rTaAnlUO(F_W?H#QG7)zc^$7%LT>#W~6eNtHGUfw()k)QGapu+pm7Oq9r&NJlZ+jg0{BjVy z+Ng;Te0C7fcNENIOnZ0HOszpBt&*HC>=1i67oATIzzdwT(+jG*ceD%>j=%fTINwb( zRsxk%BD`y6na-?|T->EAJnL|sTwxdn!RI!)p$u6O zxYOW>1^{*7Y=QweYRr<3MSOmF_<`JvaW-7p3By%(@c@GUC#(mi#J!4nR@D#JO7VN1gI(C9E^H%4HZN1rycz=?J%N=Iv|`6{Hr~ zisKSj^@92EbqZkF)v{z(97G+g7*rro;>Dc2Pjbc%CcqXADlerMt6#87WdeW?k)x`l z2h{f5h+g}k+bl(ZW9u)E4ULxld~YD#^J~4vAXgx)vyS1j1nOggL3bVTeB!zsa`Q*! zaa0M3YCLD;2B+0kg|8Uc0M;$ofR2D*0f5mS1eD(qDdv3FR{*p~m#5;(RlPYmQ|`&P z4#e{bEnf9EkU~{bg&6~bHv5$@0Lwf$#cqWx`CwZgPAhiv@8-7=FojOCpcY8 zhEb+hDFfvPA(YIL26bvW1R6u|hfhB9mZhVl$~bZO`87(Qe3*gPbtrTj#1sz5(m^Y+ zs!dPlxh8Le0#a$0%pVKc0j6Fl3~k)5dqw(ImnAGx4%kt3`?EiqJlq!~Vm~ZY^ECNX z0_Jd79QYP>f{%(WK@7r-@qv%vGjZ^e=;?F#P;5(y8wmjgjbL1WBO}23DW#=PRZy(1 zg$n0(sKkB_`h|qY5FK)*pQ&oPtJRdff-KC2gubWms7j3Z8XaP{hRc8R z%wF=DZLt0f2M(V^UZPUaWt?w~jOD)Sp%=-fxIekti}ZvVL^pYxWiRP@UXm-E=LA?*x<%ad0RcW-9^BkqWu!c`e|^rIY;*2{64WxZE?M$SlZ7z76` zZ1g>&=EcU_s6S3!9W@Y2JW-q=^4~DnprWv6On$Q0j!FYXBke#ByorI|f#K4D83+yF zr9k9zl&942TV*PT^E>iO1 zvkNXhN?gu%-CF75=FDFo#-&?trxAfN?q@Tobu$`wBlv73`2xH7UApi3OO*QNxEsd+ znt@lNZAq0?qLqo<9TLKD|y}uV$?@epj!~Sg+n2X`L~# za>KC43_-k>**eWV+Dxn>{)IYfY`Q>>N`IN${o=xNcB|4pD=!(Fygs`;$=jq6ybKs( zJwTFmmazpKj2Qy-Vgd*b^SC9`(I7`GOxD7>zvYZvbcLKSvPUYgM(`d%>bdvK{}DBQnb~FCp;q zC7|ji8fw0hv7DT(AlBs7o`XCA=i6v^b8apS%s9q60_A)Ye^rHvaEX}p_tE>7Dx@Uq#X)h4iPqWE52 zYiq5`@PPhsgB12;n$(D65bx@s4@?BogztKaWvfoag)JNE&j`@L1AZX0yjfA1;*aH5 z&o!FbWrb0N;tR5@NMRP9w#H!Q7!tfYw2A`X-+Ot21at{WM?+Hp3;`)A{wS0|>Rt>- zO+kJ5sMJnT@swz;mS{>GxX(h9wG1&3kejIz(;U^aLL=EUhww->6S1b;M6i?uGmXSr zr1END2hV0!Ss~VyWsn*q0u%tWMGMn4YKL?T-lN8DV!&X_ilA@~vXuA3G^6=a0mzE=c-xCpo4aKJOH=5YL(R48ojUMioXV&Tp6~4oBCS(?38e=^qc=b8hn&m>>Mh`@-z37|xl_CsVL~$M zo9fTq666%`U)LD)W*QaDF_u-_U0PX^RvA_Np~Ne!yHSa`eq-L2;L#Vad%R)sM8|gQq(oz+`G(*}6C@4O(+{ZD9 zfs&dFhWhk<#Yhnl2MPyK2K2(Q4Ii?9ZXET23~Of=KAwxrz*RF_N|R{97+b?%lA}w% zlTlhI9G|21g)OXzOfP&$r!s zc3n?1W3-YCr%ZnCo#w}pFFKuM58E>5o(|p94ruzI`6;@@falZHDNw)i;V13qa}G>% z)4iWwT7UBWxpM!5A`p!vTuTCwlLgn)wzdDiC<0cfY(nrM004#HeCW)^cN`@jbAMBw zr?d06fUK~F%I;@CH8_?NJx+6Y*1vtz4uxmovsPj~^$fMU!?15DT3o1-$Hrp2&%>Lt z3_?K+bMXyAQeo~fc#;hwTVzuBq%Ky&sz&zwc4?LynOQqrN7^cfs;Wg#Lh>GtY9i;2 zoHlM*JTI+uNUSeSzn8o&*QR+>u2cGo;D-?3lXz| z0sP%99fd!MnCDzK{tz*5H?6+-;rQc$`-#M!X9Kg`q5 zdGLmB()Qr3(6`cqclT^Abw{9BT!*7l6n2O2VXS3`9~1?*4nL~May@m(gYndPlrkJ0 zj6ZqkLBwX@MzIkFzD;v%8*^McIPLvuxlfr`5PfUH_Mo>|5%Z>$+o$KBB%+98JoHT~ zKYNKKyDoYY+s7@jrbW5ytMk576OF->Ihm*PgPcjEYj2;WiG@5O`pWk7>TIpBpj^Z$ z2XE|rz2q1B3%OVvja=MJL#_T9s~?onYdRvZH2-&S*1w1qM*ly9wr}Y!&iw&=Ce0uE z!;CBW^cQi;A3f`b-@H5gXz1y0R3E%*(w`vQn-lW``Yu1WQQ!JpUE*GYIzRXj5a0Yk zxhp9nVE6tPlsiV|-2Vc!{U_>qvwnr7`fO{PwY=~1{Cn#~9%3xlYg3`0YWghoZtFfXtY@i3U}Yl>--)z?(ZS8Nl> zkBk3<^wrWnwa|Gr$2d%K6cTwItJ=jNI3&Rw8LKL@?(10TO>^5NHRKc`{pQ6c#~FI- z#g)~F1k=*m3G0or#;?U2<%MlSfA2TX&&2(+-~4|XtKANC3ft>gmF{+t%yjK$)Hfbf zW=<&mk7ISRdGN1dbu`xV!kT&fRLQr_OVobrXwvYd1zr@o6|sO9ftdU841!k*fQmYu z%a0OQ`S69lYXIvPs4E+8?8#@6$2S`Fe(ezc7LO>@+JBBm?SF_z%!=|aj_uH2WpYTv z(?4=-e^edKpi;euzgfb4s&RjEY+uJw>$3m!Q#?F(__GuF`Sr5)|4a&Sq~UW-&H0HT zeDYh>!QMilSN5uzSQ?1GGm-NfhyF90`!5>zU*gez2k;L@kn5sfz=7Iu$hzQZhHtsx zjt$kA^urer8UTkk6GjOd&92C*V_x(n z$Tcl!x`qCVMN!b!PJ-=5SwIF2G@x^4nt~%C*rrvbL5Zy&0 zjc+->SDm$dN`85*91JIUcmbMU_*x-fofW(gJxhMQnBFRUG`F-5*=sK%e9yj7mh-*F zFuc*;(x##VlcQ93I!|P?Y5-iaS^Y*}W3y&dhGVOCXHR~sZpvIC))DOt0&keH=I9ll z3obE=*9aQOXwuay(SUFMQFWH|?0;3AKgR?Aq{X3|=z7KGKUAHI1k+)s`F)-@PR`;r z-cRO{Rp$lm+BWQI_VB^qRGp(S4Q;!laUF}YqX`4I>v)849Z#7i+Z|6^7L*;&*fwk( z&pP&Voy@sR+MRrI|5kP~?{%UgT7>S6b?bCtdK~6%BX;02jE)iY?9^76uyz}E`~JI` zjKq+Y2&jPmHnk-Br%>Wmw1;Qa->Rkkn%(0ckP4@kG?062F1=O0*t*FYePQxT4}lCB z99e@>Q0xCGWVkN>A!PAr)Bjw9{-b!By;BR-Pv^Ig{j;6D7%@MTsqn+RfviEZ6ZAip z@Cb%R7b-gc5Axetm)G+h0dD3j*JvuFwfUdS8%Vgtzp6pQ*z?y%yZg^U?OWF&6Fa^X zMqz-HUy(J^Vqk)G^o%fQzp9}gLy$FyRI5-c5c7;|krXVK4S!4?OsUUB&dB%!O_gJa zUcS2Yh?3d`4`uJQrHNgGBNPxS_%~=OMS-=I_|!V=-^Jtd`Ep4H^P2L>hQVxL&s0j# zP>N+5nev~+;}Ss&2{LaX5vjREVMVQpVVG)}kvI4y3F#e1*OAHKu+E zqyq>ot{l+HvlMDigZYLG$|$IUQz+Ae#Bk6VM#<4LJd0`<$XAA;_1LBls+xmKZb=+Z zIme))cPIdW=;STi&BvD?2ug85x8bi(if3%f%-j^yUpzx3eZk0lHCz*ghuP` zYczVrJ}}T$0>D-VSKIDgRQ4(-)xR`RAO#YsY!9G+dIEm~s#v%0Dx0d22I`D^Idmfo zE%CI{g;r~t>lGt4IS{bL?Dw+FcH0BEvd^2B|+Q%>`Tgl+#Q7(^X;>5Ss}_Q-*S@e z&##Ym=j){n+vgjV{kJYQYbWh5wi>^cUu?IYY+vkjU~ymW_E0!n?hUY3T<*US+_^j$ zmF50^IHv9J{b1hTZme_k0jfn*Xo=e{J0U8;s;XVU>fYp8hb5{4iacMa%pk*&q!g$a@?e z66|XQI94oq^p<)}OTP?RQSC?oTeCoqeq_Txy*>2P#Wmv|^jXi441n zOp`iTO-ooWUhBG|8n|9p)awIhjH=xAffIR;vn3#t|8bAYaG6L=P9rwX{=` z-uw`t;c8Lk6@oOH{0hVnB$mrZy-|MODo!1>Bxz`)Qsg~5ye!9DezTf8$X^Z;duei$ zsH1vlvkqhjgGLL_e9%FSTM6B2WczM1A|?)k`l8BB$#1tXeKCz`=tml?XWP_&H1lXzDT*&H;3zQSH)C;czs;^|a-c zAXV7IV?*FyK5k>(IVJRCQJ3aMDXaY$PO4ATVfY3r=4EevFjEsmN`yswC*Y>*Y0U=} zyo8T7s@h6KZ?yhr6}9na*xj9J34VnAzRuh5pJ6X|v6fRnhJ9Bv`s{0l+mEo{I$zEE zKZSiKk`QL8RoT*Nn6?f`u2FI z^ty8Qr2NI1HC6MOEB|$iTXtM~1cJWe@WpVe+5j@lyk~)agE*%q588$Ocllo9O8Hhk z{*C|yCqRACQ7z_`^gsz&&~viYEa&n8($4{;}}xJrIn@cCF?YH5y{E+nj&wGiFZqzH0U zijZIdqem94m#Ioq%NHP~Op5axF=rFX(9D>^#q@gERbF-p%xdK2nC=q-)u!$Y6}>aR zOIl(~hb+*8L&aN-GF#MJwdf$#Er_uiGR${XQwLiQFm|`dhr;DJS}*5KBcR85>?%OK zW1C&&`p`lsP@iU#M+xiL6OM|;(y`l3IcyrkRU{8b?_Cqf*c;&d4&)J+ySxkU05#kL z_OAge!_d<=rJ)?`Eu{ytK!vJavHHSv>n;Hjmj&^=tX!%c`cognMfE{dxgTu6XJew^ z6VDp1tUdQ3N=M^3juQTvs;`RW@CqC2yJCu4UPzn`)E=n{wA-)yI)Ec$(!CWc1 z_)uU`0OBl5c8-S#O~4dY9ukTz?oLar92%6Wo2}3$gGm`I6Uf^dDjFV4j5ot`M{ZqT ziVuFw?4P%8b6;bCJN&d8EO1Lwg$5gowoA%S<2|FCOAdL%K<_Pc_HaPFu}rzUG&d8N z;dh?xk7Zk0Ks6xq$A{z^_wP&gL(=gFzx|JAC{>g6pPa7WjS>HT+4hf9K>^Yj@!x>Y zMKAv0o_*~d`+3hM3zp|pCtXgNCNGiDo7`LqSd==tnID#AqB>2N{AQ(Mp4~4MGmxB% zS3_u0?_6%LfBMcwU^Ma9`;^vB)_$@4-zAxP`Cbi|I5@a`dKTG^E?zrz^GJWe>`Mn0 z`1Ab*-hGr*DJ#T276S^9>rmNE`xE@x@yX_5OUwhGHoeK5E-Q~0AaUSYolygg`_kD* zdZ22Cg&ug)s9`n$O&mgCiDpVZ5W1R`aUV5ZYx5@#hy$boVYj2f$t z6CdhF7L5xLfzfCv!o<*|d;@*%yPg_F7P2JZ#4a#;fFu;?#_}RzdS4VI+woN<6WXRs zhQ)C47ha;vLEt^)Xo_qMGEcv&KX|By5BMr-MbN?Qs)?)d4d6B}tnv`Ky!#+YUmht^ z%mYEgx$@xe!?}(#Jl-QOE+3U2A`?~!J+93u$OV471AVD?rEbM>Y|DsIgvK|toL@xH z!(Max-jYmVXsx9N|!=ok7 zqVY=Gkvm+tdi~_TW0uG*mp=Np$^W@H+ED ztpymp!wUMRu2VdcQ&sXuFn$_rF=iD0+V;S9Vno^?t^s!ce}aK^9Iv3gV9t+F0&902i3Yn1;r7n&Q7S$`%fJTbKHo zT&+@V8DJ*BmuU*;A6m^#5T<6!dl06@n(1L&%wU*dp40nS_4FeFn<^!H5b2dv7sN~Y z(Yem!@@ND(M`_fDX7*RA)62tvEBxAx^4F+$eJfv+Z@dz#uQiDfZC7OM6h#K3MEv8` zozhxV-4>3D=|{s`fEi=F@`mwf{;h`A8Iw6NFgp#TNwyRt0kC{754{8 zOX^fwHtRF0REX7As#FnDkvrVV$3vT9r(n{Wp8Fi8Wy7CPzZ1WM-K706Dz85FWK>DE z>|-msDw6TSo*8j8A*dV0`|lp0$~0?Tziq*h?Ucu5C!d{?TLb{U|MG79=L#$G4Lb&T zH-?=>c|NE!U6GfT5G$!>}5X>9PTJS=#bcOdM%8)vgyf~qNC&uQc<3G zavvPf^i39PU&x2Jh%Nz2`FJsqTwcQ4v?l{}?f%s6NRL^Tc5G>!IV(H3%5TqqGC(A5Xj9_5wB{v0$)4 zW5XafSQbYT(Rd1I67FD74Bg8%C6O1Z9nJlkYDn*$v?*c{XbHuyx77UiM9KaZENn@Bnz&sv3ezx=}$8 z8weMRy`eE$$6|C5Av!x#mm>Osj`UV7?UDI5Ac|^is(HoQr5svDP&?a%aT`3!ePTNs z-+TG z$E$UosVT5;(JZ5^Js_?oyYn4BXo*uy zmJj5Kg7Pt8MA(K|q5V;& zoacl`K@t@>oz#~N)x{G?)2!YmTYbq4(!lAuaz0Eq=ws+Wz^Rk`?X^Ez>(vr&T@kb< zG?!d!D8*{IH=0@Ug_n-gmtpLJp-*p`4rJo|2vz1C7-I$#0&_d%K>`P$N z2hY@-A-~M}ZuXxVpJ9C#r4e#i>W@Oa$jms~pM9Gx#=ULe?y~-&>_Pjx=XYQEVWUSQ z!nxSv3vIuQMBpaQ-}5~F`l-U9g3kN=swP|2rW`T^KO z83J(Vgbcm2N2T5Y(#FZJf1Mnh|k*CYEHNSvaoF#QO!g1 zOsnQ2ZKBrkvIlc8B6f9XLU?zh=mTNHRl;3m z$bqfCJy&jM9A}YWT+v$SPP8?5t3b3>@gr0tAfxBf%*P?`%~SOe$X=1!h}bfNVvOj= z>gr15lNFO)Pp%N>uKUrcYcyh*VJcH4XS1p{BST;9oF)Cv<7!9ZFGsS=E#yszWGa% zeheh7RJpt}@51?9sLVj0dx|TVDOjwnR@7pu=g!M-Q#hilw?@W_mkBvm$JG_Ufg85B zmz*E8$agxnyjAYWQAytx`+oW){*d>8Ld^T1pC-#A?UXra89ZBI_Qq)#V1>{ztlLmC;L}>6Ilqe;{3%NgHJgTbOtD8L8tyfBI)n(ia{{H>#ArrAz*p zLFyz3U|?XtMa$BeVZx#xa=QJbE6td++r0~As{09=5P7c@h`_?C*s8QKYxF)JA<$_w zV1*Kc!&e4RiSLF$sUa5IJAT4^KN#7iW$y=b%3Q@#9uyd?<7$Tgo{V0#`nkv;RHurb zfaQkW+IuN6jY;@vZ$VfPDEXZ!YxJ>Gggyyqj%`bvD^_kN=_L2T6#(uF00AQOX!HO^ za?1`5sn}#|W z9|ZSrfCZb1aP&l6GI)nT5>vYcu{Rub{EAWXHdASw-~JjGr~Kmlz!51F}Lk}(lWoLAhEePwI6rV`c;YBbFyUqxccPv zb`-bQx0|0`Ewx+pVg6nx3ZJj`Puj0oc8vV*0<>3G=$}q&`4cNX^5GQfBmi>w|zVhMeA{Z%yt0K}{%l1Wt2Cqi#o6_(N?8Dr7n6xG{Cu!!M zZF;;5O{&Rx@WzsbRiw)s?3k50w<@LW`98X@Hvi7^HRUHFjI~kR6rhe_kgZ>u(6x!)@~Sm>k?5xV|>4D z-?4MH`BkH=XFdbUzBvVUE}{~n^sddL$MB5T&j2N9x0H5YSG$GWUm8Ua?Qx(o%%YDmuYd1r4!N!9O5l^S zsX@N$!1!=YDE;9(`wE`9S!Flbe%hYER2xr+Ym^~s8#f|^qaF~5Qb>bcjp<81z!8K# zAcEX{Z3Vy^f~0ni+AR>CmM?S_9XX7TR+6{npRl z?YHKi0j`idoq-MqpU=xPIStjjWLIB46J%Y}bGiZ^Tz)2D_(?VQy1l83T{xRt?+*yau$xhfW;c1P2$V1eYK= zDA)!zu*VLoVYR1Wb+CwJMjkB8P>U14aBMg46vIwSqXc)qcFV}f(8$=r$ljDtmjXGf zo+k~K5lFU5W+QXZqCRCO_Y?j{^Dr{0Sdt}ouN9$ab8+HjOBuy%inW30mBQ#R5TflV zk^@LgN+VmZg5O1${is%Ax;#u ziYvu07Q2c>qBGXSDTdA}mR>j(Wjgl6lIW}S-=9`Qnm zBI0kMM9=++nIXhsjIrWpl%p^T;=OoSDv?}Mth}(lSZcfqRic`3qK0mwmPevaYNB3K zqQP|Hqq9Uqsw89KBvaiabB`p;)FkVsB-`mE`?DlRs$^&3WEb6JSC3@()MU@5WUuLD z@3UlIsuX|WltA5-V2_m0)Rge1l*s9nXpi{3-ISZeBym*0+(oKYt<>{IU|LgLp%alD zoLpc!6}Xp>7Z!hajrhf#w1T3T(&@DP*tAOF^jh8YdXMzR)b!@2^w#P0wzKpOs*En- zj2_*LK97un)Qq8~j5pI6@6IwtsWLwZXO8J+PIzQarDl>krOr%e&Yxv+4rVSGPN!7M z#Y+gj=s!!NReg~+_;eNdr;cV+jT8H-60e7)h^7*~v?6ka3g8f@E#pw*GGYwKVe)qp zFUJy@RAy`n6Ce3Te_j(7OMNMI_G0=h{=_Pqx;dL>h&VSjI~WN}{!LZ!W1I^W5Q|#! zvtL!q^xwHRK(hM(`+n8`&;(bxcs)e?o70#1NAnpuMEqy>#y?qQ|1!>n)Tq!a|C}`W z+-7n7So|A$HVM4E_0Qv6@;;e}MCB{t(}UGt&1XS%L>ikyr)rwSIClz5{42#hj6xb; z^rLQEKP*Pbg8#soI-xgaSl2>eHyg}XRBx;XSAtw^mC-(%W`&T5syrtQGDAeV6vDYp zZVW+ypiH7S$rIj&bA5H!2O~hS0HEG!z)J{l-4bMX{_u1;hN{|mCBEkMlnLs6F!IHY zC>ZTaQt={XZVZl;Zx1=O>%f=P+^{Z_L=816P@rWWl^$5`Di?bF)F7S$wT3}su~68* zW${d_YeB59a-?1mgN%m7uB6su*aNjZseBnxPanK6wPosr)JtVcgD_I9)`}vLqmAUp zf$VfTvFsFWyd@AQo|h6g9oW4mCQll?>)s|Do4Tf#*nMA zxG>1|S(ud2ToU>UJ%xI!(aTId2CN&%gn74aO!9&E;zB5M)8TghV@MTKaTqu~(wQqK zWrD-;F*g(SPTf*qj$`Wx!KUM*;$pVFx@p*^UFiJ%(kcVSaA0(QHV@4{vYOgD>yba= zyxoCY!D*Sr+Has$nr5kb@K#{Bw8r2_X!Xg+U97hg+{Z+AF7KuB%3So0g}&8hE6CoM z5JQB@){SdENai1ZFN*caOD%*;^P^IPUA@jynA`EpV?QJ@SxNjvVd7){mcX35`j_KR z9w&(BBv0N@p*Ma;PMWxzK29#+mv}~hJ!vvbb}Ak(dp&7_hQYs_iuV*P$V-7#L^{vK zdj=0DI~u-@Rb>y~!01$lZ=#PXCv1so+MoY-lP2`FGc(*f^723;K9!T-`c*#jU)Qll zp8vI9^^ZD;%a63E6ayVQtrdPmky+@huufdPU4Kd!B~spjPJ(lD7drfGY*|=W_*_mP zL@^szI|Ytay&J?6nT>A&>!zOB4HkNnP2e`rO?SQ<0>#fE5)Fa%Fj4P?!W46W$pbxL zk-adL$Q;rFSTDQYUbxPipZzM&y$D16T*`h}A8*=T{nkc)Q8i5 zjI;dcfKxi*YRD(7eMl#85(yH~wALuRQE>lxA=!pzIZ;da4F&R2-8{>ms`Gb#r3<*F z7>8w&EjRWE#?nccKBM@cUC>^tI2v`i5r4BA{-ru^x?W58^+kzUDqF9~l>A7j`ZBn% z*=WPB0;7+Pr$u06w#cdC-P>nwt4L4v1*c|})*On9+l*Rkvd8D{Q4-n5NJYrew+}Vy zllBiAk@M45@(7}Vcg7p-i`QS2t0%8RGZ?CQ@1F=g?>N1<^?9bP9jW&y)_kD`>*3S) z#ReBH_*2C069EWNP}E6%mEcm^_~wO+!2l*6=uPsvPI+{+#M`6f;_k>DH8scU4mhSZ zE){BQb+2Tu)R?>w0Fyb(OF&h{`I4ZcmHH)7 z&vo!ivSJ_PYYL<)b{Sw2DKP{wEfszTu`WLQDpVRNiJ7sC&ojiHo7eO;Gq)Az+x39x zYIZ2N___nWzM2bXm;aiVpq4jCu6F$ZscPwD^(rkiC#*mZwzLL`wagBBm23aLh}E zdYKbgv(+#kJj>NM8=k|}uo#!V-Mn5uyxp?hhqu$ZKcTSm`uOX`cH^8m(^floQjRa! zDbYU+k{ucs1xde^vD*m*TFMQxA^A&|V*|!lu&ztp#WGAdAnv>OPK_ zrMyE7HTX}4+2Uzxh6QRixjXK4r{FZN?{hdbNJK>Jygvs=9e$7(e0%s2|Ae#7Upbc7 zc~IwZM%^3Qkhr5)k6+RpPw6G!sGl~@MS|FE3qBpsAQ|j#Q_L2?p)q&XDcmTrWQ0xa zXYt%&hxfi{-)ldH(wDn0MONHBedi&2MbCjHYv49b-eBu7kgi`^^^MX8U!*su`<}=* z;q-FPwbFw5^KT_B_D{fY1^Z{7rK2g*T`~$Z)`d&qOfrQzDf+F2{m;IiEWHuj_Bt4y zy?L}XR$#$DvvIf_Bli7}nV@UhVdV8m&S>syv7=G-dz(*6wytJ(hG~5+b|<;pzaRG7 zxgA{w^bv`>tfennzmL%jH6c4Z#bT4lCh(~=A=}_FZ17Sg#Ae#1--PQN3Y@kQIIB3t zY`nx4J7`DIATZtBmEGgb#(g%$M6RBm^cON)Og`%>yQu98j_-2zZrOvkU1&~rD^Tyc3c z?X*WgEtpZeMF+Q2CdNO|nC|Md|F|!ulG;98KYJBRR3^4v;@uAXRC47zxz&JFeVM)6 zlUxwJdY7MRiDMnnOFHdE>8B7C|Ic_KTr;;Dy~nyDtQA?PwVOJLl=llDbqY zb7&C@#zJ3>Vm72pgULyl@5*EgPj_xV&AwyK8&jnCfuH2*o5-)c1#5~{u8~odZ@#K} z8^s{DZbdGpFugxDicm6*B?aQKoJ)WS^iNGlvrY5wY05q5Gg41Km6E3sltvKxxZ9E) zTlUhTd3N}R=g=Js8J<>RR6plci;eOsWM+|nANqkS?(7XjuUeYV<$VCX6iL6VCb8t6 zQw$lC=wq?qBCdHdd&l8`H3bv-k6ld)uZ|R17V#;x?T!=l|CD~O~ zwcor-+jLHSw*D3_q%rzbxtK4#SgU48vq+CDjS{0+$4w3HC*}0Q($0*^F70FOS3DAv zD2@k0K-u!O%Cu~i)Jf8M?H19}if3;z4G}Z^UA&x?0bgt;+fHDi%_HS-C4JKdbE!f) zt@4!2Fqxz$gSm??26*}}^eHHCec;{d3v(N7S~nXfM55~|o^Dz6J{@_3WU#a7ihj~| z!>dl?KW-30D|h%<|N4k)JbOS|-#O^+*doD+^V5Rm<5^=jgBH)$cC0UCWw(>yeq}gg zhB0|dN+*Z?Ubs=DF~vw@AJ?m@Xx2GHlnY8G5-RM6-g|`hz|?e4KIho2y%-ky)IsG( z&hd$nD-i9}A(g)Ugcde44vW-bO}Z~)alQby%Urtp%Kl@oY;zyWGX$MO^qrJc{BOdD z+;4`Od)MYME3L_iQD-BNyEO6{ zmiFh}9})@p3uU?1)gE|`7J7%qB3jqAYR<>YqxnlMxHj}Yo==o3AEc1LksV#XbSv|k zGM`0r9g3Fme)Ff*QLUTy0_js#-mW$3nd?4C*FoO9`l5!iEqlSVK^$xeRA3h1&a;cT zIc34-qPN>ztY^de?`o2lKbdijT+AQ8Yskzk-FS2{I~k^YztjI*LIP=qOw$`+Lpe5`@IpgG;~N%GQGJP!Y`$z-TW@Iq0P5DNhUa%fmas16k<2hjFB3jZN9A(Q5+5d#Z88a{K9Muu<<0tl#HXf52|!eGZ>^NboUlJ#6xXb z-l&o~9N<%r0qwx;m2pUE@JOFDZ6;T_J;l^f|J?M{%v{IASts}jcF0qh!#&tT+g;0> zLIhWigyjJAx=|&Vq2;CpUXVK;2^^=YA4LwKf>$@`m%cz)<{JpN#5>yc1NZ`5+!(Es z0(_3Wkg!S-o$#zxVh-LQ{B-IEJcaAVMWj zPKD53h0A0h2-ZPhp9R2CA=FLwO1Nlg`E;rkrZAZL=uw((1!-_VLR6w z;sK5E+OyD6DsgxlQNZA5;6BraN)!%ve{Rai8j5EP0CauJ@L2)CTiNgeAvj_n%2-qG z&=oJ=7qAI`j-tu6wZK?5g`1vbE=`GHIvKP%ikX*%0p-Emp#bQ2;EutfP9`JKv@ubj zxW2L>x2!_URtcxS5jML8Oqo!m}9BVfm4Q(tq0{*-c+d>T-FXR!dhG~%_=+N&<*yS2> zk1FK;nd4oL_~hw$Vc}Hg(_|A2&rmH3FI_8;VA^x5wA{5+6U`($E5fqVqDiD z#}+kbNfpOwRl3Rd8`53Q(p#INig7fuz@8ymY3d;vGa+dO(;3+U8Pq`}vy#qM1GWTg zw&flfDgyCy)8M&KP_&o$>-b06=q|JWblxt}|(IM3e|yRMaylAOG9 z8as5VO5Bn5c{A-mEBsTkJgzG$ES4#UUpUlYbV&*F-~_<{!N=}d$SGMsW*ig|ECgb# zu6!#f4I2^56z&lSZvQ@UN;XJYny}c4j5vpqKj;2Q<|R`SnM2O*6o|zthv_T_l{ohf ze{QE=_}Bi-^G(p#%@m*rh>1;Q=RqUp#{Oo7nD7dTAkKd~xs z1{Mev7r1#8Je4W%oX+>#D)65!aMv#MEzTdUfiPUbW@BY%h7%Wc_<_~7tSJTx@g2PG z_(9T`bLeDp(1(j+JTkSbDE2vu3kN6#v{?m*A&iT~LDQg0{t}Q#38qnroOVgGM@dUc zNoz{6;wZH=Y-zhleiv~*236^8ztXPh(zj=-qRd>k0a)+PKx12=iD}RjKWK&-G|LZ| zCoX@-U%sMUzUEQBky5_ZT>fzys;eyDBd++&UvZ#aapX~Pl2UQjT=8`ps*$V!Z0A)H zSHkO5A_@RNj+H=JB8=)vjPptmNfow06|PPdzGoF-Y87!y73oYB`FRy3Nj0@VHLXrH zy=OIJYBh69^{tue+vnBnBsF&gYM`@gz$w}_ys0((Ej9OMYJ|>fgd;LV1Zu@nwM;-* z!`ihE254l?OA-8X<*gxdBy~mnm1>@KnyGc#Ep@sxb^7OZh9vdI0`;ak_2!=S7OC}C zE%i1t^>*j=k4YLF1sa@m8eBXZ+)^7nS{k0tGwgG3p57mGzNP%hNd=#w=_PR zX^c8=1d}wGSl7kqG$nX8B~YOxy{7!L>kbQmfi3^mb+0A)-vuy*TXg?-ITcS)Yr7reE$0=p5m@j@NU9wft$C{!wOmxI1CZ@@WkYZ;}y5 zb%K?Ve~zOK{7~$yBrz~>GBoSCRDJw{ zFoJYeAZyyim)G~-(^;-+t6VF|;2s;JGL?d1m*PzmoFfF_ZTB(3SGC4VY-|Zk>lzJc zl|h1bcF}>Uci(P4(kL+seI!s{OXHV9G5zJ8pbvL*JZl;5z?A#5@QsZ;wGMaL9CG8W z&4=$hw9Hr_+Gm?ZGN-xAY{kKSn*e_DtFWz7DRH8uviy;txsJeBTXw#a}L{tma_c}Mo zZ%v@0h&%&#At~E{yAh1!z&&t}KUOJ}vj1-vJ<^Qz?{;7NmB&9_^#AB*toOXf9d|TU zfY5&AfYthkpV8>KhS5;NQ>0y|M*n{$C;LbDg@8TOzNgO8d`xbF+jflmZ9E?ow|s4m zfCYeI%f1zxK^Fg#Ska^X|6Z}#;X@9Po&mfG1%?QxKFCziD>w*-BBp+GIw`ibo?aK5 z?bD$%yVtLfN1vQ*zqmL*`EqS*gqDW9yLl*l;qfgN{BBA^Xxt}CPcbBJY>gI+L4@X^ zv1~>cu-UDpRDrU>+XAaG2>;8jSAq3O@_tyFw z?=bYN?bJoMhm{38*qu|0z|$`5T%R>NQQ@>3Vg(6;C|o_1SYhql0)BC@R>G!!vZMok zd5(DN5AX0lYMQ?jE2{e;`R+Hw3ddR|RNODGzY{CuCf@L0%g91t(45>#L7?rS%zYcB zW+@%~A3Gab^t>Kj)C*|*uHC{tfe!12LL;EVy8i|mvE1bXCk({htomDlB!~3UUy7bm zvCL2p-{zn?&J6DlwZ3s2fS9x;_N{ADNXMbuF^t>3zGvRcLXmc6k5NCEo0@?uM2 zY`^l0NbFpuO2*-q_%l{yK;z~MurY({7EAWFKm3k-CNq^tAf*bn)D_s@%Tv|h5X4-` zx;g>Sfvrn@#7uSh^89$5PN?>@)di=2$*L@c)tLy#_^x5zPQXfXR z?9_dJO;6QvEbEV=Zh`x>zE*|$sm_On^!vCfd9(Lbr2Nz);5H_dh_>CG7XjC^wVv^YAG%W7Fnqa(drDBcL8Wjh#NI z?MFsU$r*N-=!aqV=-T#EUSyWV8YJ~c(erP1wkb+KD8bC%YD>%|V{6F1cy2@KepwHc z#Ud;7_6Ibg^=Rw+&UPo3Db3HZgUrW29s|D5Vi0M`ti@2C0h!?wZG+-dXFn^!vT9i? z<5E}qs{qh9aj_ZR`!J(*2q&i%ww@;DB$x8!lf;s?7f4y7a{5L*c*igR;!mX@!UZ|=;? zJb|)UK5pFKtAB=7_hF7S`kiM+>!V&=lrpS3iR};S?}5sNtRsvfdWp}F++QoZ!;%C( z7L#EhJ`y$|5py<`@*$0#W|`ft&B3Io6;Cwl69C}Ba>*%(K57XStIYt`G#AXG?2<%} znG$v_7H(TLJGS9qm{x`cC)kY4gPL@XW&*SZn?f^uzIpigHT^T^n50s1BAT`yM?H(4 zP3%EGm#shoro6FpizAN?>ns4Xkkn-`LX{g-U@};(%OONfhLns&B(Fhm6J|WMQlFbb z%+L~Wunauz8yp4RS3-op>2bmXpobF-Km#}fs=gmi=zwGB;Y5N%`{4icaAIY5h7;bk z`Y;K`y>SfC5?cQ4;ryR&`tNh=pgm5F@XNLvPhOX&IkY2ju8boJZ^OVGDtpWTZg%^! z5oe1^cg&72*DhiZ2SAxzt@?wQvv@n(KcUY#Tm7I}$Bl^WJA@FIlQ$DwPj6 z4pefPr9v*So5j}Ub&L+;8_=cNaQdHKi3x$fw!_~Vd~Gukb1Jcy3%p$J8_06bY2ZZ^ zai3qAEkxZLotLOXYfp4T&TjZ1G9IrQ=K_bGlqrWp+yzqpk`5X2g`HA~_E2nUPzmNX zS_g;GJA@3gkx~cd*s}o{uAiO8ju6isq>rB~LTS|z9mAJ>8jFjC6*e05u;;);#$@*d?9uk2 z!2J2so5P97Jgpm1#iW&<=3bjb65U-igR75+JnW6Iv=`IDa&ke%^2qIT$={Sk1pEnXi{PuD+Q9(ZwTUoKAP^5uv&w}DMT#r^{5LS*)> z^{r0gw*Rg<>bKT+d7s%Ik-sX`cYPiC89WAm~zmg`D}`-7Z7ksU&p2uXsiQ4%pYj7meXBeKb{kXv*o zN&yO9p-W;c*eelXa0@(Yo;Z=Nvyr@OH@@por3kKmLTs?tup7=Zv*-;KNwz6ud;tlf ze$^0Whw33#yGkAF>xvKRWV6O`*fgWMJo5%z~OGZEaAFCc(DgEOOSjWsfP1=J)AdE9lZ3{k+O^vLXbQAC0ifSvQfRx9)Wt&A0e_Ze zh>aRUI7hNR%X9|7;?YPXjp%5q=uYlONDzs(xUnSs(IRl}(S6Z4cnSU(HFCSq_=YfH z4th1x7`VxeIk0h^Nm3k~FcXM{pQ}kJx<(pr*dORVg{6*OH%XMB$v>JeZcZ$gFPcW0 zkfV%AzartWjh^-XK@1^$yO<$tA-$n}vD1dI%I#usZV279N?4wB^KxF&);KLB*=39A z@w{FwbpgU@tgcy5bCOk_1O7>oWj3%07v5iKjY-9&7TKx55*w}3TJ+Y%^hhzD_};iL zVz)L3i79%EC=ZRPqfp#OG-cg`qxlX17MCwIu?)e|J+?YJy%6lwFRG>$n-Hv~+fq^Q zEE~zBoJ`crP{v>Q;9P$Ss}+8K+)8{3i=;vq;7LNKa_+Jqr_tI8Nb(Z<29&v<$x z&_dK=wHw*{%@8jBcAVwC)Tny& zdo?2l0A(Bl8h-9(r7ZvdWk0vXk`kdMiUsTbVbqC&x?!6C)_$%USoRNh+E13mj;b=; zA}~(Cw|utIZGEk*<+yzArCo@*3@@S4qJIbqJ;s~H{lRWnDon6ka^-To6N>p<3E!f5 zdpeeP8(MX>(dz~bE^GvrbuZ_O-tNY(jSPTVI33d5E(HoKc7me zqdmbWEqIc}y3Oe`brrxkx5&09L?{0>vTft^=w1O%DaOmTi*xQzB5}`s7_TmAE|3=f z$gnmR{<50^CN@y}`Cl?D!Oh;KpieItmu1r4KxP5Asgsta>OS1@#l?oQ~)?jO_xH-^p=NF@w;Cw@OLklK>I)cJ z_C?+7UNDHtR)~MX;+rivUm{6ufqOBr4LA-bs?@w9d^YBukHNkhD0~}Dw-XhH9T!Z< z({sB6`0yP3c%y2@L0m`bYc&3jINeAGa-M*p(>~n_4J?M=$LTH%@msO!{2^vltn5Aq z5w8&*hJhT=Wd>9VWz^h0r=!fa00g)K>VBSqO3Hsc0~}Pz*Uo9$zVO9Dzh%k{(*Ek)Bq>&tzafR=hMgeK;-v z>rN?TbxFs;KOITMlPe(4mN>e?RC=z8XU0}8ooQsg|9!ExFDFS*1E1%Wn_jr|0 zSvqu%b`yXie6S{lHJ7NSpL_dYCONwqYhW}WkO^q61V2}7ZCc>{XY_{*Z~@f(+9lAW z0AYseuhAccj8P%`b@ca}jTj=uyj&c_sxk14Q96q-B-#8o>dt=wb^N37k^3Q-BlJTH z?Dk;mu{v9a0VW?VB%)#O0S|6;T%CBdgLtATac+1SY~aH}=CZZ3@Cpj* z_|)tvwey|2qjs<>Yfd4!Cm?+emxX!|G^GD(anEm+LgVbBYaRe&g|BJ{Fyu6RDo@rZ z{on*051@n&jO&uj+Z&Z(C4Wd5Ll24+U6dghpv@86bB4)Q_r_DF6uFBrG!UVg9I_nM zT-LYzTo|#5#6SpmQ;Q->Wr3qBq*djxOEj`o2wqk6;J=-?8ryWLL7QlZfh(S*^{^=> z83X;8E}0yrKL5emY>n9y3*bS%oW3#Vx?BCQXygg%c>LjtIKiRuCDJ1|<3HZj|h0+;rQc8F)bT!SP zc{aZz(C=QoeM1&?vfp-(Zoea?lpmWlS?ySL{&&oa>hkLh;ecHmn%ctQc#i8)=qfPp z3k3QDZ4gxH$F$XqL}#aCbY)z0U%}FG-5F4*Gwd#N41#si1#Xi^XfVO+f!Oz?@ zJAFf7tL~OZI+W?81lJKy-_6=;gl&ln}K>dnN3Ln#Z0kh zA0@?!8(||RV27|vLc!EoO;OzVBeHNoCLe;@eI!ej1+kc%;Q35Cgtmm)b)r2u zv@pP$Y+^H90iR6ZD=b05xo^clK-(>{7M@OB9d!9I&5H%ey*_n&8U<>I^^bm`^ZN@71|UGA z&_4?<$T%1l{|jHpsQO1{z1G7Du-W=R6cf=!doKW(-e}ccm@O3)LzQG{3<*q$`J2po zmDuWM6#9)3dW|ofsCK!@so3zvGc*`AWHKI`^E#*w&8^Jtn5_v~E2tPgLau{d2weyp92l!5bnIfhCbh z3LA_I+L9@_i&>dQuPpy9`YIf#wxekK^LW>VUxhST_Q~Pia_>E#412HB2R=rLQS+r| zmvDOw?`^NTdqKXUb;l#tK3E%yIfYAK0xKdOBiIey z1K(I01-UC+*ba1{|CGf;jgkZoKnJ!U@^>|qKMdssS+Q?2tVDBOsP>2*AMz^MOL;KR zJVPHNG!tvnJ&ljo&OuVPJ#?5_g(7sNwZhHwnebAq>cisfZJL=FR2<$~K9a`bcVEwV zdW4dgQ+9lv9DrkLHk7$z-%ZrXx_z$rmK0|8i7pWH#rl18;2>le zN~Sgn;$|958dbjBs?F}nlZ_eIaNTj1(e;5cLc{mh-#2AB5dT(IiiW0OeSmKSuxoG+ z2C7s|wdg(X6>7S(x;P^Bpte)q+93i{0@$XkhW9$z||dNWimYasKrqCdW+!!nHUkYJTV=#n2YdI$)c4T|$qf}JbGvf~#u z)e9B`!izzhTzs*f67)Q zDmcrp2rFqtmmbUaG+SDQwQXO*JW{S%l0h;wzUoncHk!7Xn=d5sYc1jZMzG2zR14N$9WY^RES;#bO^mu8P}*fEle5pU()45&R#d)#nDL1 zX$y~(0U8xnSwxthb+hYgM~Tcu)iV6x!oDWh5WEd%B?$j`$ZYx!$o^1I>X@FiRX}$O-PA7O>Jalb;r2Z zlWp?rptYbDiPpdy3SX{hbEIc;vv0PWldoDA8)|*1w!@f9awP{IYF0^R*1}8sdXH-F zNO}I1Mxpm*=jh%b>H)ez>qYZ|2!6Ep72dA~Dy?on#XizvpkuZqm4W}@I*IEm>Flhh z1OwuR-y5jAhlb%OQGGeqFl~$`5+qt(i*lXryd&X!@?FZ<6hUKgK`d1~CVHyKD`Zlb z3M;wNE2aqg7V?XautQ;^dT1nwR36GaFo;E^8Ur;(Evjhk7UR39aADtAeK~a&{ zbUEz9HBnE;RpSiiXcP+ty)9F7nOKlGqNEJ3*kqP;m2@-<7x^KBWQfpccr-05a5IoY zrIyy#i=TE~(=w`?q$sm~YpbNP2lu9d8m>`Pf6XRuZA-8;|6T{W8O?EB+kOFn{E^)t zqt{FST|bhhTbcYiKE=*W@Ml1h5KY3)hWIDT{Fwv4N)ieH{$mcD4m_!wFPv-gs z=BSU9b=U>8IDNtBVo9jbukl8=gI+@HS_r{7ED{l>P^PFJjW85LcvICRsSN?Y5;jN) zfo<0^2lxkPJV;#89m<5pr}8D{TR<9Ie-!g~Hgyiq?8>uzGR;`itYZ8c!gW^5o>~$3 zOG|MbOOr0X3@8myoNv3B@Li~Cf?h)R7sxxdq1g?^!i%S$50PeGWnSqBc|lrt=Ed&& zzPvg`on?U5f&9DY-4V8M_5I;kEpPxMRouiLV;oXAEcnctLk>iUbmAdAr%MaM1%4Je zDl)a)BYq6^7PwDv9&Ri>6T6^Z7P}(iq>jAj(Ut5jh?xA)jb;n_0!z{JkwwE26JKPXSR$fRk+S#q!0P1UF43Fpgd= zr;|?IX*bld!@4$MY{k3l6GKfHq-FgZxdi(tn-DAnsZC)XeVHNp6na`FiDWARUFQX} zu9T;RcQ#fEh;~nsOJKX-^(={8nOZHDqIXPLiq#~zQ4o=iQDbEmbTFH_)nh{#B=4L_ zXH>Lc0G0tgh-Re;!`R%#3WP2Y>-xL9p(W23f`eIIlIR0%(opHGhZl|=%vNq0Q zte7|6J-v$%***uqA5CQNhOq?UV*B$O&i8$$(0-&GY`){bt z7PlXjd+A>!dY!t0#;OU=C=*fcN#<&^vU+%R`V;$s)uaq0h0D@A0H|{7NB`zpx%D%H zf1$$;&ER8Gus7Hmdxm?E;#4&6H9d(G$?*B=%HDjijZS1@pXBZ-u?64aSpa=#?}@Lh z{j@Ir!~ByR$p!UkGAToUVvfQr+qPlEIk8f-Kw;fBUc%8JRHFk*4V89WBk{pHu5b~Y zb_kUN0t~xS7-BLv!825*VVp<`|GFT#3pCSQW0n|PQypG>PO1pFXN+J!GA^E+Sh&!{ z4k3L-Xyf2&?uW67poHPzW?4N{6Y2oxrBUtuQEd2 z>vtL;$m1%Ed1JPr$bi@SeF=+Ylc=&~kb5f9UCOs?^GbPY>cuzFa%R zS5*)KoPOb|zHu0DBu|SX${2q+!aui_v|sXn9R%{15QD`}_=n^P!?qxP0y^GoO; zkdF^N4F>PD7Syw<*Te3hf8`l3(~EwLI`HDPtEqmV->jVW8(dk z9+_cjMth5JSY*l#^GzlMVyg2F8NtF3k_QPHZ4iaT_)W%y5SPdK1~IC@=Y*D2F;1Gn z)@6gS;o=LEBJ+HM$V8CISB)QtjMmdU=%6wjeU4};8UxQe+nErF4g-!3@y$bC1+aS` zkgBUGxP6f6qY6{{voJ#r{b#Aa_VLgBfvQvKAOG3^xORbL;VPZJ25`~XW|r31S3x4P zpiJ~&N0IXNRWQah4$-@&Q@d_0aLNn8Ym@4`sEc~0Y&N$4>mHR3GKy0_ml zU4nsc&d#HEuJlbI84rNB-QN44VDhs5 z5%l1T5e*)w8jfNr0h~e!7#J@Y;>ZyDC6yzP;~8V`>prFxejeG4U@9)_fxjrnFY$Xz zA{xLBumgnu_&dCNzhBhAJT!JjFm+eNwN8m~i2T=ydWNr9%xTGy*U8OdGN8NR0DTk* ze7;E${899NT-0~BNHy;=DP-fM%UmEk|I#V_5zv@_$f-)7PJcM>-|GB0{6mZJ_Ts-P zD$8L5ehvb-324lxcy_IVgpqH1$&(aROjiiHcKy1jZ&(at%?g(ZvnwiaAMa#(-vJzU zy-WetI}6&fwBG*YEaG!+@8bGp`TcX<^0pWDN4wB~#(sq2qQvR>5vnKKmHr9wR0H@v zj%Elx0WBRE3(4Z)s*Li+?6FQD_8g>3|M!-76m(VHf8E`Tdjx+xe;9iVzm3V03^jv> z8q(F-9WmdEk&uc6b`xeBx|%;i4MowfNYGM!?u|4PH(M!45lO;!+F=V&qUNmKodOkj zq>H|if!^KM&!3J;X$shSy1{aWL+ml$Zf_ly^^_Se70RnZ9OP+FY4(n}XQkX$e5I9< zi-BQCL#Dd8pE`8n9!|d|jm7H@RPe zZ@*}k*c$(Bmdcw7DW`9uW2hg!-YhEcwd9AdZ7=#doRRFtHLn)D&(-=TaEv7Ds>Pj5 z(ZsU6rC8l!;W@_OQUZ{bCx`tArebgaQimb9A^h?#nL&X30}2ONW2Yqmi^PGBIC&3l zE)-=oF|R$D&TSHQPl!kTy3wN+E^1zH5=~U+Mk~j4v_=r~h>Iwiz7nPbWDYWNSB)aj z>IVm+QALx4;l+Iq0pbq&-iZ)h9f>RwHZ5jF2g#opB9DsTS5dlmEv+o-&m4T({i_eT*Dl}SSE zx7>(cDjwcp`iCC*Y?KLHIP`7Pe~bD4rUFkUi%-|`>J%OtvO(kBIOw-K-hBJ+U%uT)lnL(g z=eLvB7X0z;bbo$({-8fI%3AAB4NUXn0^wY-8%5Vmy!+R07oPF^UVsg|l$qH}5Qo?- z*SD?@&5QXtt!~ZA#?kzTqU+Z@mEQpr{}HVH$_qIkcKQ*XG-pi`&=IM(CY)vjkt-#5pN%e*5=nv;e>ewC!{=jTUW>ZYWdO z?JG z9SVnF#4w3j!w(p{A#$1OfyGY64~sO@ts<>d*8mk9m>zWqs)keAW=Ls+mL3SUEqR&ss3Dls2Mv!;23R1B!^)?unYIM( z=a09fe43x|Gr~-WOsTh;A)YmaX9q|fw7EUT|b1Z&B zeaz&}%QAHv@x=iq|0{~C7p-nzaQZV1GRZHTj)RM^<%Od^h|MF-pn=%|erwAB#0^bH zoIC_Emb|zQ6aqX47iC<+Ncw4QoNz?qAh^JU#UOn3#_SMm^U&;Is+hjT5Neks>Tr60 zH{&pxoI4>jb17XveF)?MRdyvKSOJj7>{r39lkGErG3F8OtPB`nX4dL`JIP zZECFXL@@+9m~N}MwDPT$by;H@6rb8MH*H+JT+Gkiow z1c-xz^;N`D0&z9jS>FsR%+KX#qU{~^z>xaYP(-oR` zicn}PQHWR?mVrY9eB*hzWf8lMC)Lt<-a{RT|rdZv8><9s0rS{dK*DIg#V5$m2QB z23LLE3?mKRju3`R^QF()NcAje4LOaA5gH1ot1&tmd~31xyYA~**5v%qnOO>Fo0&f5 zIP*T|gJ;{mE##itwXf!Q6xeOs%14nUg=$*1f@e>rzt7B~aB(B1b7uKaHG=L{Q9h}E z{&D=#^NXYEmVu}8M_+L+PnHrDFHc^k*|(i+R#aS`@AhI|ef>P4cy)2K{`~6l>^L*_ z{^mIXU}rzV2Y$#GUToq1u0#6~bfON-Q%YE>r1m3uB|m~%L%3IoA{cgi6lCy=NDrhs zu~I7i$;GmfA8Lx?XYA2m@k(EH@&LZnJ@?^F%f@)p_loSSGDKK6Q{f6$s+}5pKU6}F z8auJDi~i1jn8Gt^+ycgKW|jSL^*2j+4ok0yquA)~qnUtu8GG);>_1!0?H9G06a|j& z1>))&kl@nfCt-;2MnY7DSBl>FkCP-JD~NE- zT~D^YWFggw3&3hdb7^-agS_$u=ct3u>T;frj4~i$4Gc$l9OP0S77E@DABx*$BQF~G)2diBhb!(h5sAA=GlD~%DzcJ}V6V{HKvg4KNiW;HDA!@@IKOJ%QSC0KHm z93^oxP6lq@aD}^1A;?AQ4FhB4mjMu>9SatVq*w!Xa2~vvHDFAp9f>%)%v_J<-Xc)A zZahAWF&$Yj0$IJ{?65+6r{p9jY)G9QmjO%OOrQ@i+(7Fm^ia=09n(t1Yc4l85uwx^ zQ)XnpN-md@)LO>&Gp2!CAm!!*DH+)gPWakod>un=_$?|Zcc7LwxS=uRKAIzVdb*PW zB+@7N0pzQ_H%>w75ackkq%=DoPsw3}Y|mOPk>L-H%sP-{Y$(xF^8eh-b+6C4BSP#<+ESMRB3**Kn@Kpp6!3LJ~5)4bU7KWujn??4%Y|9r* zG+G7O@FjLr5IpBT+1c%aI^obxdhA`N=PL9PUy z_0zL3i#5aB%JY^Z%Ju8RbtujC{+yWGOHuWdlXaE`-ZJ4)_o;x#A}F?&uko|)fqZJa z2@sXn0d6I$cW_<%8DPrAMw@0<;f3irZq;DdDw&6Y60h*C(VIPwi}RR_ID|lj#TFb&%}9 zV5>RB2M&n}E{TG4;C=B9!FT1}ctqT>DJ_0@6=VaJ2v3hDKWI6U@}-v{8VDePZ?$gY z8*FI#@~Jv{{r>T(#(R>3A>wNK*18~{f)+4EM=}nuQ2aq<9$0;*6JHn^N8H>N98{~# z26zl+!DWx)Wifo&KnVxha)>~&@P9=>E}j<63f5_aK`sGH<@jSmDnki->n&0mCEv6I z9xtvfu69nn8$59o5Sra&a^#;E1Zraf>hG8n%Qb=n=YjBj*jjE(03}QiqAP%VzFOEy z));hdj56F5WC`p1%iOn023ru}h&N}|bEMyN`g_kzeM&F;2TfG^qQoJZnz#=BS#>dSW>M5v&JWD{d1Z zeuDW}AJuVMm4)LbbYgu8q}vgXgb~wu6t8?)LA4Yyd#L3g7w%DYGZ6esGi_M0J8b|Q z2&FLfBg`%{-3BFKd5D9}IOtdyMBVH8_{dipgz(iB3nd!l6{KfA9?177NKDg@lR;mP z(P`r_Xf}YeD4IWg=Ho91S!-5 z%)E8+BVqNGFEW;DLW$x+G#x@5(SVP8whaJt_d+w29^v8;FprTJk2y%I$1SwLufff0 z{tI3!BYv9{PK6VeYpnwH6~zB`o+Q7PNR|`R_^@$Dx6T#V2Sw{atC>2;FAyo(P*szB zjV^eh`-ut^pUNAo?-sv|7h5qLKpLn?D=kwBFU_MS%!qJ+3a z$o;yvB=6p(;d%FfWl~wefF|wkgS0q&?w%&z*G|a^r&t@1BB)hWP`zpeDO1MFCD9$8~+*rSNpuBS?# z?$`@V8NI{VNFq5n;aHoSS#K14tryxU=jFwXyM^d?%xos)aR%>&6iRkWy zlL-;0i4sGE&vG9$%S*~YWQ!rv)43975bXkH3Hm5S4R0b`6qm;o~E_hEhoy{XX=8WuuIp`rT!jic=< zhbvGl7+(j|Qiu1tPH??0`>ak+px#)g-pI4wFtvWHOa8+dreI$|Xnc8MFHAv?>>VD! zZioUQ&y&R`s15D6mbhZqbHVpLGn!9K(nX(6^5dkYlp`9|`ZXDsRo0@j1V~tb#Nz<5 zkL#|&>MV7tYdlIQP@C(TtEgq0b3B`kt57DF@R~fFcto&|+YtclHrZ=<>@5QJRnYlx zLLz&WdRs#GSj2*?8^f%zB1$A+P8*dgnV%!b==bQ(o}m&Qm$4%Qaw&zdUMothDxTKn zTU`;iEeN!=X+PLQDAso`$K)b97H;SZa>fg2fK&2VdDY_80<+zlJS};@d*)^TOgbJ+ zL)HPRDim!STFI`AXw|`C;*5Gw#Z3N$5~!St-6)FxvQM{X#zFPayg2h-LXBo)m0tSFxi4aiu;?sl1dmmojKYvNQk7~GxCEla} za#Cj{)F7ctMITjUJjf*V6Fx4kIOXqFZ>@Ovteb}P!KOeVMv7fH1nUDzE(KaN(blVO z)GjuZtV@|>)M&HZ)$*y;ZWdyFfKH)XTCaX-Z)j7m_lI6zv`+eaodLR?OL-;Et!?C2 z_c|;-^o3{lFs9(TTIS3nwvTc5pqclRZ1vsO0bf|+;FzVP-5Us{;(MS|SOHO@{*v3} zpQ}Cqc@>scjmF(y1gVmHUGwyHvu;|`o7atBUpL&!lb^;o?2=>3YlEb{!A*{zjK7=yzOeYcR{wj$$@c#*{8bvsUs` z1|H6fmutTm(-kZac7B@^SV)5KWTLK1Sz0R#Pn|GGIiF?FF1`D)e7B=lcgWYF1)^Y9 zK{eJ3MXj>BV!Gm|=w-H%%>iW1L3+)(){|k8lQxi&6#hxm!!lHO2|VfeEOB)s1PL0F z2`9k``<e*`RX8i|KN~nM(PYYQ338uNlFR&QS3| z*(1!I1;!!dRybiRIXHl*dL)jj6*ef9<;A!G%Jj(W)ab?3SbAZuyq+6+Dr*lS?^O#5 z0zB=L_p+1OB-wY=wNt0ZWvau=nx75MeUhJyNN?WT>F;^gi!)|99VBEBGU&_$z%`G) zcWVJ>Fk?#oX%=xM2M>Z~y_tF59WAdXWLg}8hfmT=>e5peh{^LwFN?_ROh|SYsWFx) zc1LN2mJ}}P`&x&n_A&F?E1^&@)C1H}!dI^d7B)D?Us+EeU=ShArO%(w2tEpid2D=1 zIp+{yl9)QJMl`vqGan*9|9NLlWo}MMs5xqOhA=v&6oJfur&l%~a5=FY^>vxzLz6;! zpw?PDChDR=kzxZSz$UmJMQBXLYuzPdUDsxK&=RYDk8|R)!zBnlT@+vRiM#O?2DAy< zXntFt&?EjlI!c%lhT7!=w*shPXkJ*OBj8rw(~p}&t$o=FeVMnn{GN6aXuoB(BaF4} zi}22gEC*3y)#hvWLxg6>)3>u zsa@8CO+!0Rtq ze&XtVbv%%J&*Ag2|NWCd#W#LTUx*wM?dOUECzO?SRcu>Ip^W$U8d|sIPdOi*+FUsL z>y>2~lx96I&3;#!>yu(x;cqLTrXM<;f%?9RSj|JQn5|&?5&HRkgc;4#_syB-t%^=B zp1*HkHn{7M$Vrg0cvx1PIMrdL(rfUZpMHwpZbm!)?EUlg@yvBG^@EZt4ZN$bO*7MD z3lx`*)7_l?$%)!R=jr3qsZ(=!7d~5;=4In!rQ`dUv-%{n6SLcA6h%Gd{(yb^b~ZnR ztBZ5zPm~=#mxR>!kR5zG{ID3vTP>89e4k+oN_=eutw==^O5>*`#n4E^6KFU(O~vH3 z$8%ctwDRHPzfEDYu0J#TL@$>k9tM1oh@JNmMw*Y`7I>HGeKvd0*{$LsM%lcFp4fGo zqt>$VCWFLuEjT+Mv!tQA_AO76(Byt|&{Ui@5E?@J#x=nJN(4H=MLp-#{Z;BF?+ zmOW*V9)LiOd_{OFhyn3@eX?1ouX=cvVZ4w1ViRr ztH;6iY(t2Tcfp6MMkDO6Ty)|0{aj(6eMVx}DTG4SL)4qa{WuDV+5F`3v8`y{O1*zZ zootf>y8E7fgq;EHL4ZsSfyKe@MP~%VaO~U zhiJd3Y|GT5PX&IF=euhiE6TMD!FeaJ{^5Pj)W@Po>1?}2-#fI`q*+&}Fq(XC@yU>g zv(OhLh$uyvY%II+w|O0rL*>)pxzv;;>FUaTvP`kFJM*Rd$uuDBu{3aA{^6+b(=d*V zoD}dS`O}&#uUX2~aAh@38u;rqO%os1YgNX0C3K&C3{dXzv=b3UjpFTh=n2eO+Q8@W zHAIlA4Zd|})Kb>0LC=*>G``;;Y2=d}&*e4}JNL9@(7aRwV{W`kTs8sryvU?*#*sFP4>cEN2K0Dq!k}WScT5RL06Q-SIn>BlJx_Mi_ z>5_OZE3Hd=yK;gKZ%27-x5>8ITiwxy_O*31eUmDXuPi(YBaSudtnCbn+Pv_v@)K3y z-)kb6XmNP?D)^~I|9!h^o90OufiFE=6Qp)DRHf)!FCRLmyz0d0W$P@#p+Hs|dD#8w z!)sB*7hBT-oqf(99&*hdOa`od)zjg%LOLGUKHtq;iEWT~Ur(giDqb(>jXW(W2odu9 z*pRs`P?Cn}z3yUD^+9U>t>k^L!{O)FUdQtx_q|Wo3toDkf9j>U+}Ai=9ZA9i%> z(Tg=Qgs0BKb7IX6FV;lf`Mz$+IJhJba*+q|w2}ZvMUR`Sj2>S(hqUMga$DTXIf&%0 zAW275oan&WeS4c)H+##800&sVZ6|w{2_S03CNqxoWizHc4%}$}#Gx3PT9RFOD>Rh^ z7{%@DzqFO*_Nq#JUnnrv7{@lYn`v$>%-|z6VaZ7YdxEl^sw{PpMQkzY2qc7$$`~dh zw3UW@FEWTKi!3CxiE|13+>nY&!KPP)P?XVCcX7cCm+02ArBZY-EiJ7pk2Ka>g}a8a zq|4-q(!FDJU^(ibCt^f0Dp4bGd19-N6`Ew!sz>6>0#{kgh-9_jjwIA|t+Fakkpc3V zsb9jIvj_3X8RNfC>V-F#05{2*bH7i1M{DjnUf780{Z5|kN;>@iqwO!_qFmede|Q+W zyOHh`6+sahnxR2LK)PExrMtVkyQGy;8dN}}ltxmN4i)Bq0>aX@)^*?4{d+#o>v?m| z%()-2@7wm>g4iA21h@JN;o!e}-EvRPI`O&Q@`Iv#-6d~%>Tjoi{e*gQ_E>lX;XOn9 zOA`TuS1J66do=AoQEK*CBykDH%#ks1g%MkZ33v#^==Edbj^o}G-wY5UFc=nlBs>yc z=nrXMekXKifIHTyJfDfjOiD4drindF(nLsjD)~~5=5s*8_EIFo$LTp z!?lun!#JwDs97E(F+wBK8Q=8u%bF9#Wgd{3*xG++=?mwUBB2CRD&x!^zoL3%D#t%S z9e}`W3Bq_D%z@Jpxgc7InZGs&dg24JqjscyS@KB00G@os`~%NBtxEem^qCcQCd7dNMT!4C8REYv6+*#-p-SoszE; z?ca^C&9oeP=P)W#VnRH z{;8c9|KraZ`G+O)crR{iFd45398Jl2s(#Hvys-u`P=ju5BPzB0(CT3I?mdhMC5Y7x zqpj%{E`BGcyN7)a@H!bWB8q!J4CrAMhn9BYvq4UzLM zN8d&7CTbK_s}`m>hN+(^_50tlv(4CAHp#o8F>KsWnI(gl9V?v9ToJs7o;q*2VBfdqv=ZFC}lVPHE_}XOFVE-pyFm#xX$oIG9-=@8|FsPx&o;#9Av@ zGEH`M(Gu7Yj~ek7M6ufK13GEqqbEuo?A)5g$U*Pig*l^!O-U>lFbpR6$98xhZi;db zs9?!I4NdsW!tF3ytU?$)(q$Uj5G05)5uLVO;d*c!G(z?m=NpHDuV|DmLde%1_%r?x zIKd>5YSr-!`W7dhg_=y(DOE>S02X+Zy$JQ2&loBbP)2D*MfS zzlqoWCHbkVl-E4vX@&FKoo8$}EK|2MnEKnLE23i%PBxiN4mLa6QloW#ESJf;_Q$=l z36~u(dSZ9aLkmymxLe}kPC}N)3U*df@k6yuVz2JA1x3lnT}#9z?*unYyh1DBU(R{S zf8Xxpd?AslJF8U(IeNm$F{0V5#Evz6!aWG?8HTX`cU z5y68!v=?!=PHsb#O4`4q)-c|C+4elt(!B#?KfhERZ|Hpo_RkKKeZpz=R6L3dx)T;j zy>z_T8#F8soH0^MX$VPvCkBB~ds#MmdFKs`1hZW_N`zNler?{D0X-LLhDd;!`09#g zP)GK^^GW~z7I*#IDF43_h5g-WoOM{#Qa^-P`Mb*fFD1usYKFblE6LvGxh{s##CnKjcwDGV<+gqR;ENed z&^{MH0%EXuskfzC7Ndl04NnbPYWgA#$U~MEHx8hz2J!y)kI*O|K+r_1{qfV{@5j{i zGusgUuW?5aFzw$w16RMM+83Lqoh7L-I-R#aO@q3?E`~-0uL)C!1#s`5lphgh6zGIgdd< zMzXd?D^}+26@k+52J~}+gnGy&r!Pr2kYxpMrUINkQEtG$k6LMl=VcvPV)V;EwNi5K zOg-oHA+fGy`%5(&o`;h#JJkR;VUP=%DwF@ljh3}I2&66ml4v)DDqO#<76?hpp32VC zBSSDr_nBe9@pf4B;6-#z8vi?|ue=(`ETlB47i-Wkz@kUBG+A*h0jIp5^~GZ84M!>Z z3Y1PVlX_I2AGvaio-A6;+S98UDH{9E(aN(<{t$VIaq^f}oE!@dCD@w9aw}-{#W&;Q zK=SHNFjM&UD-^;{+Z{L}Lzcgb*CK%#+vrt!10aFn35XxUe*j1R?iMXaDx^@@%>UCZ zdM?zG&#G5#_zA5mmUBY?ND3%*3xc~SRpv+(Z*z-BU6Q&2Sh63M@>MipHEDSiVFcGYWbz3PvzXv z7Z_lcdD}_iNs8I5#%4rg=J(C&uF!EL5IdHxyr;WUW51ZE>g9M;7uC_pcNPTC=?3j?W;FUVL{Lr z8(EZq#5Pwn6o(tDJb7nPJc5kF?&lh}p+pR|KrVa9ZoYIZ5&55%!0Qb6VO97TtZJiw zmjphtVlhHH*TI56=4cH%u_+b6OVwvcPq4peahYgQ>J!WUe1C1 z>I6WXTXQN$Ae=6hzVLs`;Ma?hF_KTpP4@M6Av0pv2B15d7f$^Qv- zhSaAb0|wx`&k!hqTqcaWYma}knAbD91HQJNjdx>1~;XueVM z`vM zpU>aEWbh@F3H28+1qGkzr(<-EP!Kw~lm{O-ZFd;aZ9M;`8hwdyDjwFqoXfunQvXn4 z{||=LYZKD1jTZ%w_pl9M6`n2=iP))Ud>e!&(mFza!c!cKL6DH12*Z^pU^eR>6mGCfl;`iBwX zASUO|gNtJf=P=dz+b0kE%=`=etn(k=zJDHL{(;#8);S?rA^=R*$5{5|?{D9vaT$PF zce-@N1DJKUY2)U#!VC2C`8wAFpr7~0ExxrLuatcQfGL{*5@OTYx&wh20H&;C0vj*J z|Av0v?Po43zd%3l4&Ll#-y8acelFj8tIr6De)RyEV}JNngUJ4fB-;n^QPJrW;`a&? z9RCrsemG@XbYm*aMi5(I3L}SIgjW4Ey@t!jKw?g zQUiKB|m&X6A@h7v*y<=w&;gnmPBnYFRh~8h7stLGK^p)+>$sU!i(`925S9>vzBf zZYMt6l6`qR>vf2L#ryVU^PJA1C7iQd>wT?dz{H?N{se7*u06>HSiB#W5qv@DN&?EK z^eY+5U* z;gK5VdVNBNo7OP7gbvr(^nRcuxln4(CKGEcGQYG3mYP=h3UmLRKpq~5svNcdf-k+P zUWS0vK2s#03-9#-1lah^YS@a zNq7EwvYH)q$(R1VUR+f9eWSebD{!9b<#aa>e`oz;t4Vs$=_@O1hkHO0*M3@hJF(8s zuRUsO?z?ws2R#Dn1;6RpjY!Mq6e>QRntw`|0YlMsXKO9Hyn* zBVI{@kPv`XV2T4qj!1+!E+5Z7gI6r_3@qaa}EdK7f|kMe4V7`=%v+E<(^wlqxNZ zYQ2}tv4uh1oss_?)~{m=Pe5k=$Wtl?fiz9BCWHf!uA@aYdUl%@qA$8)`!!5zus`yA zcrro+oj+iITwK5d;m5Pw8O)z>;z<>#XkZn~TnOZui9D>HwrtV0o%mWk{tA8k#bM%S z%Qnr3eqet?{(H1RTq%H&Rc*z)C{XkR+$PeC0{wx$+ee>d`A31`iyK|;Z-F7&WAh5t`5Y=oy^e!p;+-eVcxD?Gfekw83sI|VetpM! zcK7ogovh%J;gx8psg8pgL1CEHL zdj%aS63Da+7fb+!AkGM>`VBEB)#v6sO$FJ$6}rx`c8^*0)8KSomu{iz>Z%3ZoEQ)z zJ<^+McCl?R*HoLIfh$Ll>I1+@3$L-YX#Tq>>S>zSz*YEHZ>IDc%}?HFUNLw0I}7_o zBUC$ZZI76oAFr6|6qR-VQ^|e@969hG`>-!z|MaYjdJqb_4 z4Ve%;W8Qxk2}w1HiZ<9WHjEQK)qlqYt6QYCQ+|8A99J=U%P2{Z#=jupPDAZzs^Kk$ zzE*ghX=IoYA=Q~<cpIqG{fF6Z{2+ahGq}u za#X$zu;jpchWO2B-8v2EyZZ)|iy(7$YqkYW*;}_Dv^z2ww*{zu)qqMus$a8G-s`Bw z$K;#pSi2uy*_n_tX>9V&->zt_&+A`DC(ttYNOgJJFv>*#k#*zVBe-VXj|3j>d&IK zPx-m6`MbkHYVGWC0F_BE-_s0H(V7iZ+_NQ!nE-h+X}?^&-eTZ}+|T_nHJj6eNt3G6 z!%xoNPLF=u;|$REm*Miio&9LYA!+X3p0I(P9#fRJzf zV^kTJ>uiNTon~~jq!89irx`-_1wLJ|B@`%H+3>UhjP!eufj3zYKQzmO=wgVHc))q^ z$-kQIbpLU$yLOskdM$i5wb7k}Yd`yXL&l|2*WC>ng>&fGT)!iNPTKlKayC~%5|hR3 zgPS#iUVt62>1PwoAlwr)Yd6=hytSE9v|bAfP$XTs-TJeS+WD93>7m@8aDm4zHV4au|AIQ%Qqd{(B`5ZYgz4V z-`E4hvq-^ctuq)1>Gyk`_X-EIs^3LdK}QIM28i?l8mcb!dJ1fmL}M8u3=zRPY;0No3Ab0GJ<4hj}iq8hKO_@fjzOj|qqk*c>0gc|+Ynne zmiwN#oS^Wqq#!~4&@{?j?7s46h`~ls0W>OwmqAmYzh#=;w>d9kcy>zQ6>dqx?$O83``58r7(ju*7N`)}?6A=j!&zXUJ0%wKL zlhv&o-@1ML*8Uz#H>@7@N!euQ6T7nNb~yfN^F)Ll1l;In_kS`MldzTA_E1>J6q%yZ z+g4O=I$7@aF#EMw+eQ~YW)`EkGx%)?9bTqFKqv6Yc761%C%4}`?ES7lP!k}DlZ!}0 z<})P7d*e>WYA8F;I~hUDx;MhSU0)za9h*^dg&7SRxh9O3hvg=M;dh1LrK9~nKK&tj zx67i;iuZ-H&QxKV%`R+)DeA|m*2aMM(J60LklGi<#V|HGm&J_P@9)MQ4Qkaa1@cn5 zu0&aA^Hq7WWiF1}V@GQ?tMW%2Y?L=-_!HP1C4B!<&gOw*>K$cn@wHG>=EsK)t_MYZ zX~2++^e}sJ=36N;?3R$`936ek4^N(I0y_gP4LcopOrdchYkIl|nBIN}a0?JoW*j`vVL!(75y5GpK)C1yD!e`wWXxD$g6Zf$O68D% z<=mv1pT3@8^hHfrtUXEiJ|ef6Xs!+celi0qE}x8yK7P(|m!HZAWdkIaV|oOQQ=2cpM!wMY0&9hu2F~t0a;T z>ypR?R4CSuWL!+Zbrl_+PtOGHm(tjcO&-c;oO80tCLn!l~2Oq{=nvg6UR)A7weXr zeUnQm$_!6beSBY%`}v8~7IP%6hZecNc=@!9|+Gnz?#by7Pbf5IcYq6e$ccW%>r zna4v#50CoU-g$oC%K~8*Ly)D0eaZH-QQjDHS==Lcn|dFE8c{6DBsCJMv7h^?P7Lzf zc<=nsGyE5@|JdS!$U#KVG@RWE_`ey_FNuCv7kgr@dNA}Neo#J=f+hNMrxVLBT4Xq< z`n1&AM&Wf=_JU5(eGi9GmRCAYD&xMwYG;fXSFCvj3gkP{vw~qJh+TdShtCDM3I86K+!aYdx;()GqcYY>CBv3KhVwXq*zKLrcjQ3{}-&7T*C*#=BP(ry~2(GvzFkJ|f) zHH`=y{oKpqLUxi=RE6{(W+zuXXnBw%xbYG?#1)#D<1FO{>J{QCTW@u+o?|C!=Vv9;Nc2`deFHr97e-r7*~|nB`D#>e#MP0pd(; zKBRvgb`O*dwpEM~@HmT|Eh{rd=#prUKQfOkwPKEQ+~hVjQNmVD#mOOJ2*pV-edvmv z(a5o%_q>b8B*Su?hnxzKN6_n3H(B*?*j7VdeAOCkyXcF#E51DZ9$<6P7km06b4W^-GcRdxtUi zj@=S(jAo}5K7$&631qD*SMhXUc>wBSXiZhD->&qS9jvSochD}Mnyk}c@$6m|?9Vvb zG$fziiyD_F_pg)KhC6*fK>}N>o8p5N?r4xdZaDa;L3QH^fXfKL$;z7AjY2p~hFLYd zHC%N>M@EGk7~sHv5}`g0167NC(%hslwSvWz-8CZL;J}${$>liFStlGj0ky~t>PYC{ zF6Y5P<>OS?XyJI1yaHusfm@gR##rfFU3K6DMjgxS@b_8zoMw|~a27S&$(z;XFE}T@ z?^jC>gp@-+Q9jsje&)OlLf|rf$_C@3dWrDv=&O29Uj3f@AyhI3VY=JBVfJ(fRn-&E z(2^F8rD0o+ZP%Xopc$F*9i7%sB;7D4lIq)EEEFxX7%=Ij70UIX5M?!M*1dN>Y>9 zgzbtLHe46FkmX|`!qJ^b7gRdRqrTpU-*=+CG4iRAp?$(+qxy^Y4Q0O+_tj`s#@y

4DTII`-MSW=Ot&!ct zrlA5(=l((M@4HDI7=<^3phNm(d&$I0^tTMA28{08GxvuS+T+!7-;7igm@t&Td!zQv zPrbdgX@sJWky8}M%+IwsmJ}R*=7`@i&rKO71rcvMWr^qyCf>+Vp{w~&&VTz%G655> zi1#&A!5VGfaYl4aD6dh$MJ}JoGFe5~sWyOH0H4P63j;f`A+ATNzqf}aB9<7@kkeOW z8pX6e0(4YzImKm#Cw9tUZaf6xGZEVI1p?4rbDU>#ada9ehJzGtBVohq#df*sO1SmP ze$*-@3P$G28Pj9Au|27nvdkjr_Z9r?RC07?O4WL&RmxgcN|a>TREngcOG|?*Y*Z{X z7tF_7>=2xOKLE#qP(g1&CBGej0lbW6J=wgJF5aJt0#ik_YiN%@oFU^~_KVIe`;_e` zgo|4%n|S{@Z6ec}FP4l1xF_aGVuJgNhv#4A{~zfizepQaFiZlBtF(zvvD={Da3DX( z-6p%WKlwIQK)K?3?*a0A20z6{l8h5kk;cgQkP5-EXL6bd9MLixaA*41;WyIi#HR@z zEj*aX7e)u+K^QJlIM6{B!X&hpDi17h%5yavrqX73g_pst&tVSQtt*bf8c4}^gR^N} zUQEqdHwXU|kWA4FNNOzeYKQICB<$*F`ABmf9YCemOW@*0RTMz5T2Iuaa)T1{H!#!0#F?V56zU%-Ajbp~ zVD&Jlu$|Q|>R9d?$%m@Vx)PW%6HOPXSywihhz5-wtY*=mr4pF6|2&DxjF8fZC4fCh zEh$V>EoCaq@*Rk=OLrqHDG`M3gb7!p!S2wN-DHRc;h^T<_fDy6i-+JftD1)iKo2)8 z@R&YNo0arv>~B7Ym#juLYq(>9Uppxk?N30dz8P!q4s2nTGyAG;i_wstn}Ad^U)fsv zgVfC|0lcU8JF34mIHX9RThVk1C+(ziiGP?Lm18@sqwV(S#`=kC_geLZSR+=F^3x97 zkB_ztlS2B5T#``7LpkVzp43RcLc@5R=vCse8_3!I61V%-gooYGGgnKX@zd+5=^_v` z_H>vUQ+9vErH!9$RE9jj{;D(EYx&`^NyWkV6X&giKd}Sjpi=Jx^XOy`|KKrQ{L2qoUoO6kh)LakZpbwl(EH z`#|RzM#XJ^CUU3-8YkBf4C zB=VG@Hlj}RG4uznln$>TkurHwH>$1w0|x82SqA{nzL<5KE1qWEk>QGdt~OTdmH47F za+-asUg}jO#*TjwTMZeEzHL!>Qf9pL#=X(oc>UcXM`|0A1LdhL&nu2flt}#<@of1D zg>F`o?G#5b)Tc8il#=FpLqXjfj0{umO(H`bUWravyN8|Y@M&RVastH`e#tMwU{&ki ze{{TG`j|-S@}PCn4H2%X$dr=#=)`t&=`tmjnQ(#<$S`6aeul(on(c|E-K~3>VFd3l zu@I1bU`!K8Vcnp2o~=MDx*O5=-htwdau|dug*o0rqp5gQzW}uw$LZDzGm#O)-GUaN(2L|T#wvB*2Mk5 zkm8&Gxl*G5F4X*0P}E_`x`-b*1_H*rgNDxnKYCE4smBP5@h-2$LRc@xdULO%9FKlv z6C`%;uvFcF^ZsT{?cGwgN{oQ1&F5OGeVW>@YY8pDz*R|9$)Z8uDM`uuVeGJYV@h_m zkIje!oDsLS#`<917?RQMVdg7Yx6j_55x918Bud-EY}S5$X{QIrG1WZuzSq5_--<06 z%irlXyVQ@p&+F~Ae5#hgn}q=Ncft{dLE}@@+Z`RreGH?|4|dVQ$sEMZv6MnWC8)LhnfM}*qV6tRVz?(S=5iIuEOXXEoQ4zq$~xxLxA$BA&WBgMZD3+PLk{~oFg=sL`w z2vR~7O3-(bRDJU*RkY(OYGAB5<<1AerJ80V(`3SN+-l}JEs>6F#0cwCI>IPl)YYmH z6KFxql)(Ee8Tds&|HYrSl5u!9xE=SlEbws`^RKmdZant z2zfhk3G-!qB9aX>u^cf$6DJOYW}y&><@XohI&Uzlukrc zJjE)0F+rW`QF)dFh1IRE>g9KveTL8yN@@7Pa5yI2N=Cvlxn#E;20>J_1$qPUvWd0o zs1VucKzvDtLP1GE_F*DoEsq2)!SCR55mQFdFA&?=a%Dr=+jW&9<@<%}J*pv_u8-$o~^ve8k z@HzeY6lq0#3Awc?l4F*{1E`Q45J<0bno&on{zYyVd`OFg$Xdrdl7||^$RqWLMW_fq z2QB{l^NYRZVMORI<)aGS*R}Z@?+YdY8H%S0P%KilVCfu76IE*OI8B6c$HAj7T=7B~ z4`n713r9Pi;L6{~POe#c9fi-Y{fUHoc_4;GKGHJfxyhR(Ugz0q*M0AHhHi{<27E{1 z2?Ratc#i19_235krCCfxXPen7ABj(<9}RtDm2GUb!W}I3K1*laj*^>kbzB>NZZPK= zTRs8TYt#b6U@fUSsgBJDWe)jJ$JT5Xi6mk_Yg_w%yuR7qKGz2O`O_+p!l7Y``=c`s zi}R>X3pd|KtIB&MH2&E4ACm_VYe+8mlSw^Zup;$sS_q;DU0VoX*5?EHa&6TUE5Qzs zb;IFCO_##?28sjI9n2(8jaD??ni3jW3#NiXL{2uqQrH!rgzb7Q^2D#m|0)j^#fDp7?ws! zb`)CaR{bZXj}`T^f#_eGK89*?HqT|2S+{&i{m9vp@zt3%-3E>POZ6eR%%21^QT6O*!2z6FC zq2-}udhNi?Frz4rDWz%KAwGkHD4~1`2ZgurlcQL}YAmdF-JJMV?+2x@^R)*#=(cKJ z%c^DIy)mF=JpfT^ZaK;b!QEUDREV27m@uvKcf^C2%sJp9p-Vsfgc^d`HCf0l%R6I1 z<)6fpsrik=MHEWG)H$O>FAzQJ=Pq#DB|sw6o8F6imTv|s8GW*n8x);&N4({iC#f0HyPnIuYiHIec&X^TizDh7^H5o08Ziv`;h>S-@_; z1cz0qOzydPJ!=wAYpNhrErxxPvq$UpbzuE?=|&9Wt?fe5gfBPGnm9Y?QD=q!uxT=CBa``-ki5fmnZ#Y)K`m~J%ApfGKxWA6PKlXXw>DbLV}j&rlQR`v zWDt~TmD(^32g)CM=5fL!K2`5m)F3eByu3u%ibaL#o@cl^>?J|m#3zJ@dT-U3;8Sz+ z{~lBFm=MXGPhXBF@ia`0c`S> z<}=HJl{EFTltW#cZm6lAKZ$Cxo)Ny2OHN?i$?78uvJ)np5cps|Z%=BwJkCnK!z7Q_U$zl|*{IDcip37`M45W{u zRuJ__BP8GE14GQL59-@)^<-U7REESM%yBeZ2RHRqI~Q=$YKB{n@h8yMO=m`tfrI|l zoK7uXZ%4c}J`$VYuV$I+_Aq5!m{)OUarR-HG3^d)2z1F>7>e`fkkVj0O zC2uuMI}L6%UKHk{8=I2Z={`aV1kC}Jym>p3oXg}8hgk^k*G4}&kY3u)_VlHt8^Y6i z6!;gGuh75U$LRpq2;;a{vRYcb&iHWOTi`8Lc6K+0&J)c(dOyosJ+w)yI9l*2$-Di; z_{ExRFiV>5bcdR7yZ)fI>5_L@4~aM43CEG`7i0if6u|+^H2uN8hX@YPhxG>1Y--Xz zy1ImP&-RCP*aRMHDOovJP8p@i5=~o_2{e2(E#lbvXx}^IG-LVx+1*dBA7K^FQw~uA zB%x;LZ;w7&&{-c(h01sH%|^t@68SVdex{oj%#X#loG$qFWW^obny>5T-p}2)1;iYw z?=zae)UH=cwAS?IdlB<*SY$d`Eaq=T$SK= z+p;%aXRwcRKML2o5@M$Sxg-_Z56X;j<8!Bs9=m0U`z#uMrSD3dXh#uz10H(a;Bt+NpeCK)-3Lwf^NERk z{AbeoPY2s|pb4}x1J7BQ)FlO%OXmPtC*I3sB&Uc_f0V6 zV;_BfQyM=I^F8Hg$aSX+1Y&1`ZwJ0C9PllHFO6^|+yFj+gHr;@gLHro3V@HRkEGAn zZd6)|$2av}0|E@r@TN=H?7t;mU9`X$w>tkMZ=TP9{|5kX_q4*wc-8+f1HKO8_(S`I zv9}=9D|F4U2c8@ZrwbwnVFORj1w8rjxoXP~9+y%1kC>d$Lr(B-8J){U#U>M90wP2K_zG*sIgcv~^V1C=@k?*~dHkoKq zuv`Tv3<{!NFzNF$E%M!B_8}kz8GflZ`@p)X5lL$mGvhF_Dc0(&C`2*5y zaU-EON0_{EeS%}yNFM_nx}}6GgK^~H11ihzsjsWSv>&e%4}f1r8P4wd&-VKD0Rk|q zVpjw{00Wp^5DE%t3yuV3UJddWgEbn+KI{2S4S)msgSCClV7+(~#GEc-hc2dBzX$&{ z*Ao27r`lU4^117dc4MH12xx}#G}tH9l{^ZP$vQ{xvW^y4XsFLf)!q1mVE)HllylMx zerNj9tVaJ0lYm`;Yd$9slS+FinSG%%f{xeY=i}WD9ijr9F81i>MwJH-!+4%F1Lgq@ zvFFS23L#S6rS^#_C}|(O)li__#^gK(-l5f>-JHza8~Z)cy^yP#ylEGP38ncPEvxL! zmneMb%PZ|E4y#|chkefCRQP@zWaOJU(L`bL<3Qrg>#V5gThE?ve3+Yi2g^A<10fYh zdw_{hsC|$ai*+^gIo3wqFVp~hG?F=TINHTDPe`rTXmlGqm;seHR&65qyEpo*{d!+2D_gN;)ojl z@)-PSuexxvFaohd7b@?I>@!VPCx(LL)C2k7FIF)?8$9r;4US>T@Km?c5B1M5o(tf# z`KP9v9iUs-sCF0n{(yX1DL!BgkoEx~6h0u?D|nNJSI_M52q(Xbna>Z6@Ub~)wEd`wu+0Pz;zl6FWG z^6~COQ;uXwLV!|(I^UioJtpt%{dIM^^{^soi7v~=71?g~f~WgGRQJU{A`U)I-%dau z)4{hbd)wy*(eo;r+b|xe;z!3ytjGTwELw4QP%dE zyb*lvE+HYp`Qr&;R*E)5Q?xLdlq?|Jy%*9;bU3nZgmxllW?H z0uI(OK+y(*f`NL4fsj!Mj)A?&_ixc9mw$}%q%}mshl=;g@%UFsl3}1KUABkPne~d^ z#npSBFV1VCaN_3&>oKFULUt{o42>9NmeR+BE&YE_0{f#RE49Lph*nw$dB4p1d!0;^ z>wZ(yX?MeBDu_Mt<~$_l6JI-;SPN6RNZbbfB?21@FuA^2HL+HFVOseZmQts zJW!I?0v)0vopamI9|p6wW$Y){D?jklMuCt)k)ZNlKka1*Fc5QUc@=ZYURr;~-OV0N-fE zP{nDrzuSt5aM`1p=&f5UvYjtW2fYzUaXUAXnXi5;+fn-P1*QYRw=@ASbf(~`vMQfm z)H8~=FLifn`m=Z?*q>c`TCgo#UO1O!w>vjm*+;*G>1e#r{c+$$r5YsfW$5C+ zw~6logsgc+&73mL%YIqro%cau4E~@c!t&=&d;ZQ}diMhRCZEw>zVm=6|5pfbvaX9J zaQqM7pYmOb9FMt(kiJ;$E+V8;;*6xO&7}V^fa-j;i#n@mEYwGiVFsEBWOtbU_&3vm zNU9c4)ZhNii#Rb6KN#hod)L(cYrW|^qWb?zr zzyTtuGK8zlXYSu*Q}g}u(i8FCTl4%HiUJaZTizRQSxlGQ2>3h71e-~{Fvp~a31{0e z*TIw?JCr(|{`hRar)4ws(|E*B29ZGLo zUmVR;wuc#0$!Ff2+5Y^$#fbs_IN;v|{BcEMV`zRGJBSPZ1ggLw??TB&;WT-}jWV!_ zESQ#6g4P}NC$d_|XiS`fs7y^Skr$`<^%?~Rv3CN*er1q5@YC0V5U_YjFq3WN7^j~`1)5j=35Awr%C+PG1Mxbv1v4i+Qp1{{g z1D4vW^?;S)*y6Vy#(91VJG0TXmv^}@@SktcZ-I1D`%KqKBmZYDPbNhxP;0V39m2*(yP$3aaQP7kjO>9=y0z7Yl zhU(TVU@F4r2qUf(e&vhLCfD4Qv(QtHHf!}OBoh11kotd0aMHd3q*?)KK%27}6PUk( z!Tuv!0DH^%(h+J#MfIHjWN+=ie&heXHC(S>8!5ce!5?X;bv4g&`gFi>ay?Wbh@FyD z`qbt{xwgN4{fmP%9$YnWW;(x4p@Cp)HBJ;Vo(t94%cV-staH*xFw zwUG!Kvn1CVb|rIJ97-Rk@%N?(*~rP<-`9b&oho%2bgSPSukK%bChJabo}g5}GCSbj zXj9(m17l3RlOq7f_HAmf-u>(Le2b5ln81yegVo8L+{!ls4M$&rVHQjjD)90o;Inkp z-8Y`C?jzeDdTqQK6A0iy2&N}!2#%g`X&nJnjvxC?sGlLUt z%WS}6Mp8WJG)5^Kq*OO5MNUa6Aw>!&$}Pv1WpsSQ6+z#0)~X?2RYi_>G2TF$A8*Vc zLg19yFj~}3g+5YZBbh$x_RMY~D1S09okMxFi9)8m$yY;AglwH5R)>|;IGP8K+1pRX z5p^Y1zqWrliMNm`FU)>)C4r!ROe6smC+Z*#(pZD8h8YjsV|G~|F(M7XzZ*KAhbMeL zD;uh~LIcu>UX0>sR5;QRIP)kh03F~o6z9dX@n(RalDftbvAM7TW?v#obBm1G1Rtu* z1MjtjVANA6Yo$f~>+F=+F{yHmJ3S|i(GMSPTGovTTWr-$NR?UDPddG@YWU>2Ss^?$ zv$(+6fFP71kU?oOSlp;sX4 zG4$0;ln8m}{UqMje~d%7c1bA_dRD)Zu7jBu^x3HG9yDk0r+sg6R%J^*wmGJi?iRbb zvr3Gjio#YIJm#ELaY$cjyT)Al_c!dQGbcNFbn+(r4yWHscMTManC<*^v;~&Oi6c)B zC!DKVkEVj&ogOWRVYf|Wys}z4UP*d)_G2dLB*lA+{9)_FkzWSP_QxX~7Z@o2EhJU~ zvPL@0Qz8`d4UGiv`@t6uoh^DkxSWz3cQeb_tm8reV04Lm|lT;;=^;H z-AaYP@;q8u$t1D!hS-oE6&(}`zU~A73sE}A6hsKz>p>`Vmz%S0=iSQ-gr0~yh854x zgqz;4!%(+`;)4}+FM9z9=L=XK$PDBHkez^ncq8|EI3d|J$bi^}EGF)$a>$HSpZw7th@RLi}mRkbU0G`j>gSIl-`8 zN5wBE-*S)6^)8NF&;cAqas^U&>^GhS+x!KwQyP%~Y;19Vk`Wq_Fia-> z_{WOpy9t$bKJ%^tG?M;C=@7|oE;NZlJu@9Ou5c)o&t^kZ9Y2S|9gHsbD+Ba$ymFoa z3N&U2H$a+TUhH@?}IBsRuF> z)v~?T9GZoY=_a*_w*qOj8m-2F%sBF~Ro5ac{D;w+lZ$eN`qo`%IVaHYI(>=7+*g7n z$*+c9S}@|{8y+fkiMPw5!c$Ja?|)r-{cY2H&>I2%3rw08$4g(*N1HO$xTQyEd zE!!JofOpdP#d?pXf2)e*LI8fD)35;i_5_-%4Rle8zrtfpJ_Ja@LF6A-PtNhbX$NRv z)>_x}!$~rUsO|Cf8lPxA5MN%379e8DkHN-uU583C;041-_zi)MLM6v+W8+RbB-3)z*G4sPqUfQB^nBr|90rE54bt6oawj zTZy$t|zqYviy^$KyUy1D0@R_*3cIao7g(D^V~uQDnUQ?e81t@_4HAy;c|A zD%jc2qi--62qPPWEZNZ{ge8D1Dh+;K3kkz5^?~=MK3h}kK+`ziO{iV({A0YrER%z# z*7u62Wjo+z_GJfqQM#3q0aebou`4~ddqPYY`lHIHtJO96oSL7daDP#UWk5}?N z^hX|$T=lJhK65pYU#9><0#>YB7j5A!m9 ze>Bnm>4W|IBe%uV{(599v#5>BYuVuTgkUZ3$j>ItD>NhOutsZv7`3XP!`Y1){suYW zb`&@&0?X*9La)KNA__ytRZAUF$P%0nPM&`5N+LF~#vs+>Xv-Gya&*oH!rQLHhOd3F z&(}j|-;i$zY9doM5oMHI?62XPm`(q&w=rKu4CB>p z(fYQx7IS7E^d05vFXEf0M~lh(&AB=Jrqf@RI?CZtwx0~e*|PbB7i}fUZ0jS4!h$b} zad4~`p3|D1+43`HT5~HiQ+?=(Uf-_ax4jJJnyH7M%?+GRsA3cgn-$oU z=s}_cE2zq$2q60E5WzFZd?*0~fjWT0b)!Bv1s4s+8x)MD2!X>Q!0E^dMpH=5i9s8N z;QC7)=clHVjiHfN)WwQ|U7Kk;fvmGwZ$=_HYB9EaW>~anw#|C7nNJW_2PhZejyVK` zhEeTZx%_#c1Jp;Puu^e&V{-jDYCT?u3DW5;F@iebZFDA-vFB>BLwLc=!AK}K{oxQ% zs{PG4A}vyLkl4vNBZkK{hq;twV$`(3Gq-){mF;}|1=R`*3X=DxnL5DBgo96;F}zKu zb2?*!OyOo2JPKRQ3Xj7CP{&ADxu%67NO%r0>zO?ovZ_V#Y<>`a zNwX%|yB%7&xl!jVNegY)*<5c%*F?Ck4~SD>2#fZMgo3Wb2_pJxB6RQnkGZc5sA}ul z-E7!M2?!gcL_j(P6p)ZcT0o?`8|hFaq)WQHySr5y=@g`-yF*mC3(VuubIyCd@4ff( zm;Ga{xyGDxjAxAJd3N4i`7lP%QlU<3zE+$ZT^+0&riC2KGxYBHlG2d2A4eIMKL|%!_9c)N&HgN%B+fG@Hp@pR5n_V z)F2#`vJ-%6!jkE&B9WH&5BoQzsNyHl=YH@v`~j8>mYOt~x- zJJVi}-Y&aKZFe`a0fqdg7u9PmjJ>EpoQ{924Md(J{^T7l;VtsTlK!G&?Au3t!FoGq4YxX<#(lNu z6ghP?xRv|+KH>Kf?+ZDb3?qiGs2*?;#e$!JARyqe5iSGI3P+@o^uiSl<(u0k@QYtH z#xJxxqkxnA7R>ovKs@N|GEf5ju9Wy$(clM2*~I>{4d)kt4aFShFB;=Nl|V$0l<%d) z+HT^wo9#+ZU2f%tYR~-zv7jQ2KpE_BuL2Zp7%+Aq2AC_r6MKL}fTB&xrO6EzjYL)< zh?v(4;diF)e`^r_^W7sFzij@emPSOj>-pXD?TH1AiGKJD4KPoEb_*DIG8B+A0G9L^c$C z4m*M4KZEW%__-Ssp34nWN&0OR;xdR90@4PhfXRS|I0NA$lwAxI{IYobi!XkTWVbq> za~Hlss_8yfU(Kff2mz~Cbbao&VPc@*?-O368=n-d0hzOlbYoPyzGz*w zfOAi(7;C{3pe2-~tUcZ1bT|p$hj#b=W=}s4?B4v~g0oFc)VaCr_YujY4Q7DVWA2b@Xm5OU%igKuW&P^-3xU1V6O~Gvmr&#jqHU1%`qwBDkl~SjWu*@SX!cumvKq|4(B`%Pz72Js! zQVuF?s&sfhP~Im>q}qtBf+hL(h*GQBeXG;dM7DUo%a!rQHO`7Z!q&_SCS}`Nt)8J3 zew@l0ro9D?i-#vCw}+;ZoN@^zzrog=*^hFcUla3^tlreBb5z7_P;=U{PWOYkcUFNa z|5$7DQRCxL&O1(fUlnnkvaQ7|jFeUzfJ)*^M^nQJo$=tU0kWsAnmn3}uG%y8HyE?7 zUm7)(51p~c9t3#{$JFFGSs;6=x}vTCO8jP^uiIM@v}{#a0|;2PL27b1Atz z=RCzG4~Va$bYJRyADOT$;b3M$u$Tn;l5}M^i$?(jl9VoeyG9xvBw|obAv5OIr7f~$ ziTtoubVDfwj%-rTG_dVLO3v#*3sd4v>4fx_5PF_WEbVX+WQcHhN!DZ*Ih-y5yWBX@ zMo2LVEK(nBYz(QU?j!FS$rcdV$G&C3y8?e9CAY4aCI)fs>k^LsAd4>ZrVENMnorx; z4z7<~FA*=NwHA4NR~3qTNP^BFBfUK_(hs?8bZ+!|t%6^ojwC$d{-`%~)hbpvPr);; zwp+41&quKvOiNUPBA}LMJkjL$qAN`sFn0a&>yOo_4&V8+O47b~sB%D2DDCuE7Q^?! zLm`onv4F4$0i-he1qrUU&S9{`BU$`3lQ`KJGO8j=nnhcc)NzO)W8hrf(PnKjX~h0a z_`cEPlyuXEuC>S<`|Ts?cL$LIiLuI$bi)g3Re}~=4t=%pow4DYayLa(rJQk(YNA%h z$v%Aeu-%51_<;MqeGTfxehG8VQiXLZ3Hqq-4H#j+>M~~7$ z(GOI1O18OlG0Q2%kI$APUz{VOD%l|qHIBnHJo>;ioyyWOr2MG@#gvzB5Uj|B2~xg8 zppuD8nmj&8Ve0Ji)sNG{E6)E{mf+C-lW zgm_M+gS<#}u3dW5cAg*kSnH4yD+&w9$pm}WrIFqi=@69M4UL1-z4q*CI31-0S9I}2 zum&vS-WZrmx(1o{j&`I3QFnNx8(E_pC4t(=f<4)+I9-hnp++%NRNn)2hX|1bb&{Rv zK7aCu?{)=Hlci$DUT3h(-V^P0=%eb;UNBy6W9XrMO}S_x$POum*7QC1CiT;|MIG^N z31W7L+ZlFCd38p3l!g%w+6d(Nge&ESIuw1zNy&|A)aOZ3mW1}uV1l4V%3Dr0<&!_9 zAVp4ppqh0m?x(DKcc=$KLiW>$1*!P&#SBCg?1xDs&dI1ja|fLIGM?s96}k)x&RSpL zY!4;Ht`w53_1Miy5HKPS?Ho#H9}bc5Sbe}qHJl@JkQ3`qEyr8Hba+Jd>)E8pYB6(8h33ZSv_9th6vJD_eP@>O;!3A>yEC*yKCPt^b2NDa0j89wI& z5h%@QEBj%wB^|8}h1i=;C0pXi?mRu#t~Wi7hown^zUm^d&=PC-;(NHJ2J&6wBQ=NR zMFAVSwNzNGXRYBC%_aFJc3l%wCx?~&VR;Hj%1X1?x`kXXO+`#(NEbbqDXRkLtsyDn z3wT$n#<~k^`C$j0UFQov@zHC-K33VKAFboKvt_R-1FcCwB!#1*cYKpOwOcUSaGYQG zbg)bPWOtNsk}JjXo`6Ow${5cjdeQAPj)*n-mi(N6M@AGTP(=Btmx9HQJQGti2i1;W z;lmeu@r%E^5_?=ovT1JraDAqON#VudZD1_*-3Z(>i8@XyIt3*a=2kbmTIv1`t;fdN z+1m=V2-QAf1SPx#UgZ#_ii$G9sgcZ%W`S*W96QK);oetgus^|)U~Q=~PQcBKf47p4-ao~RT}kTNt)7o6<{ zC5JJEGLVf5j&E}dH%I7Ps;N&$w0X#W)Mtc;{5BW0U&B(+SB~Lv@8JmTj5oM9vmKWj z7Q5eO>lV*EHOPAl{6?8HnR-^np@9_YP2Tju?}f|NDFwsZJ@)W;2?ss{I~9s?P-Lb( zE?rCPGX=Hw^4&+s^PMj?j6BLyH=aMipQj|!M2J}+Fnm3({k9>A#^(ud3LQFR+vXQ8-Iw_Q0^Lp*}6Ewp5q6{Z!2f>S!%*aY$$*dGq6bd1h3N z$q|cJ9N}gLTMSi8glL?CCh~B0AC)a*A`+|t3={OeHktIb3itdlUn??1EwfTxE3Uop zNdN6{TT#=oe8r&YI%*vT=CXMFoh7$+OY8VEd@*zI*!(~CeRl+L^CVZT;RnY!F2oI@AXA(FdGrs%OB5CZq+LnXiZ zec!Wu_EaMxcY52I6ONwf00SR}mQ`#QI~7}xQb`0N(kO-w_P4U=OdwZ*Xcs8EHT15P zoj43AbJw8(orfE69i@ z;BN1LWh%}{PvnMfr-6<&L{D_XDQ%wlw1|6>#UMmTTga82Ra+-Mi7cJ>mtqg zR8Je4N<=7*sV>&k{&z(0v6N&hWRR^f~Hr-3r{pkmL_r`+TZujdx_J?Kk#J*;fQ z&qhUFH-rMaO!v7C6C>h?L{Vx$xh+)L9!ix(57(xb_6oM~nrC2As z-An8}E%OBXW)S5enk@{51<8{)6^2hjT)3j3gt*v~0=jhav{fFMtxWh6!Uj*ygxshz zl=pFnSVfFPl9k+}LIvLV2Q!6A;SJu6aR~g=_}|(JxnH!Z8NQxrTWNV=2A4 zp(;WSSNsgN7=s}hgM3-8_XwZ+jlJa(R>c8wsIY3!f+>vxNlhds8*HSz4O*Wq+U)_N z%UKqa8JPAWs``8?#ohqs6Hai8Srn=PPZ9w?VDylZ=(GyU_>IOrcmv^1Ee@P#$xMZBgfv+jxt&zW?j(URZt zBD5_Vt8@o1hlJq9s|2Zi9zo(nsl7-0Z{iPeLz%SWahT%GgJQ`nVDDXtk5nXrFBDjv1daIM5cg0LtAU30em|7|I?nx?7jU@qInx=I0+heB`Uf)#Ls}0HV ze*O5wviHZ_V{fOzA&Za?;*v6qvw>@HxH{#SMbi{_@c74x6^)2`sWN1*#H#TczRt>c z#7=~RlgYcRwQZGjNhZTO#w@M;xn^?W<4$7DP6GWJHZpWlwi9s=A+O3ap&%^;&mh3! z)zM5s0kGuF?n@(k=BV42Ma;^s$XD$rjF;5`6O!hb6NBrJ6+@8phS+g6)!vu*lqmX< z9Q4MX_O_>`+EGp}dqxpO4zElW<9K?w67wfLBcWNU%1TV$=4bVL=^!ibI!B_HzB#eJ z1Z@b;BvCwV{OI9c=nLK<=JLL#nYN2DQA_Lvsd6|js`U$XDfYMoMJB#oju+ z5o@|RqRAi;8JsIKmLkX!cRsk_(Wo$c@yQ#(P)BQ8VVEfJUbQlYnL?<*1~CyJV~vew z+v?l+j6sn=Y{s<`9*#wj*{U7~Xpk{XsB(44<7y$sY7gIHvEpi2N5A`2hAkroJ`d4T zvaK?ZwP(l(w1reVE1z*y^5$i0ajcpXr$mBT4R0Q**+A3|`zk)Hpwk`I-r=od@*@^G ztnG}gW16UI>8k6+ukYcgZ$-|}f~jxw69-ERz7=zsGKNl`Ava7bLx~lzX2lxj#ITl> zG1l<;SJoQdA(K8%DfUxlUV=-VnkU{D%k*f8%(XWh3Xf=VjJd*FHwkOUUySMKq0ru{ zWBn$=&LM#WuL8>x(_rVypqIx@*V^RB0y6j)^GGiVRSK4sUe4haa!R37siZzG!eQ;g z;_resaS$-8G-{N>-gA8=l>AEY#VfMeR}h$HFmW?BPqUCe0kagk$XntMAD}2NLdz~; z-X~~zDwK=p=8FLno3c>Il&61(;uRcl98|_Kn!M7oYUYT0Wfa$H^7fVSdaHQxOF`l` zS>874k2l!XUyT^IKH>Cs^4Dy;=PeYYedVVgdKIw>~#UdrCO*c`r^(W3Xfyqa~vi#Ut@T3hK{L(?C z`B7XK_s7=Sx2^SgUA%Ff*J6_3R47AGlt09#U}d}xkEqw-6(!Gl@}yPAyt<7bL+uX7 z3vAL92I*I)yxwhj1dp58N}hCG8+d6*{JKY8{^c76G1?4?j~NY=y}17BX+G*3alOgn z?d$2ipXz#xGkVCW_?Bd7OE}4CZerU$>Ejwe&F?E%jU$jyA(uU5lI97O&wvq3=IMj> zcv>bA(vcE(6Xc|Ov5R#!_!CDH^t%}`A6*R-sDUYe;!<_CPE5(={`~fUh*%Na%f5Ne zw$_wEjRAuv8OnU!Nt+sl>W?Y!sS=@s$TvrZJl=J)tjqfvLuc)2=S-Mc=}0+v8b>&p zvvJMPll5p-F_1wlTjFV$P9tU;xOXL(mGhw%@nuxU$nT#K%Ut8OT4lQQek8jNr}PDS zX);KM=6W#SuuHv!suK~7s$MLj@fyV=#Fq+n#$|q&!|TV#z%Sq2i;>udXF}aEkDlbP zk)RcLGEN&$vd>QRUVc2acr*@cI1meji0FNqJXSz9k;yo^JvV{BJN)3qM0rPSMa!+t z^dTO^fLIf#6WGMP3qvyiYw((-@dihNDv@b@_x*lGk+WpbGrqU?H5ui|r#5rOTSLa{ zUUv+ILGSUU?^yUReiGliJQ0^p2M(?XkRO4u3{EtiR_#Z%kwS;1M~6sWf|$WvN|-^G zoB_Mepqjy;o6Vs0%wQ4DViwF?m7K*$n1KY(Uf-O>SHmE>`;Itp7JF)zvf&*;!tCX# zcT}72Zk)a&-JC7o#+Fo^B3UI;OBx^u@rvM; z6(P-)aLE-i*Ol0U708Q~#LX2j%xWtADt6OKSm0{<-IZK=^z4F_!k*Pkv(>b_Ymt&` zRZrJy5>{%bR!W|N3R(t_V9ePYv>&gc-`if{R>HBVejE01{Uas*nd!2I<|;&MW9%vP zjTv+#ka%L#tgk?~8~!D2@`QH3mDAmnp`H$+%E`t(A8w}QVzTv1mgJLniHhjgu!FYV z7HmyS5d(Iw1uaXi37te63{8aOi0aUeyUc#lt!q6>fo1~8joU{BP~_`7cxN0Q4LgKe zs)?NXf*ksoXn0u8L@>Qj3Uw%&#wuD78~F)V_t~e{T_{UW@xoq<@8L%5QNGwKP~PJ} z+h^zA=Q4kCw|8wlp;u*1s);t%5Gtk4Z$f6J;~sPZ~ovhIkd=dIn{CHHAV zJJg%nCNR-6Xy{i8nnQMu3$~KYV4i8O!f)?Fh(U&?P+u7+%-Q=>!jl5}6EOElhWbes z+DT^Ou4ki?I_paklb6>CUKAG=l%TP|a&3k=zeGYKZ=#2j>jw$!yx%W0}AG`OBsyd8$*NttWBL{6utjH^nfiQ%~3@Q@&y>|PiNuO-|{FIX=&_OeWc zi;R_Ia1dEyLwoMNgfIuczXg>9Lehq{E* zA=?>~GcHHC9pif!k11sfW&{ek74lwUaP(vMpk`jKzjRw`>t!Nd=S@nFwAG>{Sbr_w zW>=y8J}~q?XTJcJs)}?A_5=T7fy?HyB4r*=aE0$8W1s{O%@gevGZQ=)7@$QC1&m&i zTXK6u4mjUw5KBU(4BCB!f=k308r^9G0P6`cPNwT0{fO!5W^|J15U3eo_5ch>oPDdA z`99Z?fN8C36@m*C%pH@B;^C5)d6q%;UZ+f&z{3%gCtPkBCS5|U+nss>AF@YBG(Fb^ zrgO~8Zm+;;F3S^KDl;Qnk(00~xS^G9lYHaRN!yUpN=`_U#G8HQbVggU3WXN>+Z75N zH)L)p28a)?6Y?W#d0-(oGl%(ukc}Xt?ow{UrS2)vBWBs|Ye#S0+I8h8A%h-QCynFN zS(EqiaDB9ldD%o=}w-^VU21=SHvki7V9RNlA1#H3o9C zoJz}SK5FC3?s2DgjIuK`YR-&u3tQQZ^D7r?j0+p#IZTS%$ZJhXdq>9g%0~5SO)IB8 zIn1h;GHT6gw}ehsGLA-S&7UPjux;0!0lqqo5P87#?~1{oE_MdWR*f*tqJY%*+J)#MD$n?LmPMhL`J)QDk0(3g{_rtoGi!o~ka# zERml+=*4~7&1<<%+)W?K?ffZMPi=m8YPa9$Nm}kFEOe(&%41mwl$maC7gfzmc*;-) z$dPY8B6{VM1j%rz^C9Rxv+I0t4Z&xLcNVwLeS=ZG3o3`MZlH&09E}J^N5qdz`GUBM zSh$h^oU|3+=fy2P!Yz(LNk~O1Tds-l30^B-&2^rRR7C;Fm93@cy*9a75eT0aoz`s| z!EJbFiszU=(3LI7U^Yanen41|MM)>%&LA9b5tKS!K?4(erV9z6#3GZrdZN+HRp>nn znpiFl@Dk8T&||LYsUs(8EJ`uK2yut=HtMxJUHPu9Pypv9inO_8xb|{1<_I5_}#*^{N9yBh^NhTsIlxB z4ZpbFRlyUz7=_5ge74hXDm)tur-60ZTqbHjHsf}@p`=C4VCf z3#(S4b@6^y07Mly^Dicy;DGitEhjLeyAIa9Xp4Qdi22rfM0~^hlalN=HV2>s1$~o) z<*J0NTJST8=8h=JkFDDW?o1cl+t01rayIL4J@xe$S>G&TRAxKl0UapSz_U$90gk?i zb2bNZMQ3DEsOu5DpGjs_@myQbvs1ohh7!R>c*d(k;z3r^&k`V>Ee}RZo6Ai` zA1no2~q zUU042ZUwBWct-g5{$AgRet*$={38SNI~(oXVdHc za-6VK5R_#&bSWvK;|@H(i*Gq3$>GzD7IHXJIT^6K9JRWx+NT?ae6dQaE6yq`M>tFAhtD*>l_h4IIPu#~9l;8Uj#<3LC-G%0)b9 zcmyL&CnIayKU>5gv%LOd5ku=J{s#w&-^-?T=X40kf0+V=JrC*!07a%7tpAIko^6st z{a>6%5dFjW9+|2uFt-eh@8MlTsq?@lZoaTp5xcrR@wuP=d4d9&Q2eX9=I3GT|Je7a z7O+Qb`YeyU1K1<}6|MM}rghhMxxlJGb^W;D zcqkD?5oisFElzo|f;=hS&-Ho`kw>b3r4|1o+6xY;jE>(IXiHD0G?LFqS!!bOmv zfri27`V(iMKb?F(dhh%&bP8O>{4I~|NACHr zf`n4eiTwxFf%B8^rOo{i@xyfWa}P~j&HFjwgQ4=+VPw1y^@bP1zMH!K+S%}LRR=DD zgh9lW>N|-J`1At6`7rhCOOGF%XT&NS&+Kw-?$_H@_hJ}?7&yj?!W%@S*aoj z>&tV`sfJ4-N!%=YO4P9?Q8+2 z$^<|Rphy@};B1)yZJo22{$hl0j=@v$n_=`1BYfvs)eAZnP4bR0@(VUl!9IoTTw}^t zj{j%k%pWeG|5)4RUtBU#93Th(dQkRG=8p`DCWdzZ+RZOKl<$SxgF1 zX9fn?6wNbxBM+Y1;zub znvP@rwUqC3us|j0vro5810KY*!f?My8c{!eE*=5A2a_r`1r$6 z-hb;2znXXbdGPVC6E*68;4X}V{Q%4k{mOO$md^^I>djBya;Ff{B68F$&uFUr(n07qY?sLFk6sKI@bC8hRJ>Iz<5JJ?D9& z0`$5#;`2KbTnhch;RXmlBtV`32kUhaopj%Iwa$~xzhVmpsg-OX7E_?xbB7}ASq$*mm0(4kUj&8Bvyu^KySkE@1RrIX^{38; z-VY$pT0!06XOL(8oba<=+)kdmUhFPc zIvXR#TlIaazFQX_c@K_)@P4Svz(84x0DI1d9Qf~50QivavZj}DHNG{~{+WD0PyrG7 z-KsH-Ik)GCLWFGZix#?~n2m)fZT`qL%T?>Hx#07quG5|$jK<&OVg9rU-+tbN%-=U5 z@RLZe3{VT5%auVvs^@ZL05kMUdy!B6o30tKTM>YJ_bMy^_5exnKi{n#A&sbizgzz` zVpd*lc|m&pWy?l!&aV?#vZ>eK94&uU8h%!l`|WP!-=wMktcp2(uA_LK1pf+>y*}K{ z`vHFE>d^h5GoCXrjDf4mK9<3Z^`-B9NVoD=yqH43ZcUW-`lgEchr8s9D&{}itpFOo z5cd0)4WNn{V{)-uTmJ(M;D6Mzk^aqY%{3ARcB@`=NO8x-ZoS(sSQc2pyOC6>a-@!?@Ha}+-@DyEH3miIpD7uA(f7On zm8C#3AgK#h^zqMV(XTIXC2OmowD!ubye290g%w%ZtU?sm(X5Xp2(SY z{*r_zJ)A(4C6ZS}$(j*>FX_Q{> zEYlbTyrF!*L)f*CE`8zdU-Tr3Z6{-YK2jp0HO~iVeu>_g9$Y`iG?8!BJGvN-r&K z${e`32#vQU`q8u)dK;V`Otc1L#=h?gGO8$_4`I#9FBgJkGWi)I*+; zpWJu`u3&1ymML>1iSdNGlz-+X*^%`pFz`aI2yRY+=e`zBKbJ$I0h0U>;W{HXq}Ho50zhU$5X ztwck_jp9Wphb_|bg_Xi*!X8@ifYq8*%^cc1&=+pDvl z9_4(#UPK|g=#TOr8N7Q89m>>lrY6_%Zmp9 z80ZAkQSZOw76DPs1xXE*-*|TUeG~{JDU_|NDtuZ>!Y9V^MkfgFedR*5!H#fHI3npy z@|Z`5f=HoeBUCL68_n7Jibe$#L2x1W79S%C*BP{wgsO321r4OYXPGNYCRXhm3+4_y9hg|)(m z-J&bp)#rAtA|^2FCCXUUGyb_1j)bK{^kjKl3@irg{&**f8~F~r5OfH@eF}#Cj5Ggj(0%I`3CUlQ#*oKt~x;^4Sq=qXxA|ih=uNWOBv^sdunme0;7I1ISV-Pfh{Y?anCstE|EU(zKlEnoR9oXYKS0{&wPj! zxpl8o%j5uQu)tl1g$N~ET%9mAz4v61+MW(N(FVQ_b1~{Za*46m%n&l;ENs~_<85BP zCr_~6bjVD=J?)@Kc)ECpGRX;ENuO`(4Qyt340?`1a+su%VM>%}3{^^uZRbj+muJmv zmS4!r#cb8;Olrrxic#t(g#~A;tB!Cm8bN^KC*E2?>C5rlyasq=6H7P;uhruAO;Qiu z{L9wQ?K^~M^6$OcrOqoKKK0$G5Qw3cLRSvc*DanfGTtm-3VCc+u`Ib(@E{3^x-fZ9 zuEsFyKy8((VgJyWA+Z;4=y@sP6ow1-sVLI&OC;9U+pkdXq3kqc$cyhZPc`K3NUz(f znAH*%elTjneNco1;SuL`rO9ByPiVjS?4w0HQ=7?pE8CgCUJvt;$zIzbgn;lF!>Gxv zUTzAfTh@12O^3Rr_?63Q9x$8Q*vRTT+1M&+e+qiuNKkp*R@JKBW(Yo6wS3ehc9NwC zC3|E4EqCzZ@}zC;3Znyjv40oDL4Rl7 z9&L)v*$)4xD=h5NCZ)Z-{9T9n^riUf<;=na_UQurK!>%mUbEWOSi7ej>y1_7M_Vk! z^<@JuubvsbX~o>y+kXA(^2a^0EBcj7qY{PH`@{N$@dwop8tV_ooEe@T&p&=%&#(}A zkNwCycI)(D%MR`AD6-A_joy{D%$=9fR64S@kQNADPdSyZcPWM%MWgjxtYx+^+o z5*$7bFOsB`HCkNKI+QX()lc;B z$;bHsv#c8`Il`^6K0E$*W@lpkTX;Vf^|Kh0KEyxJ7V>%>Yz6Cf#PY!OD15aLP#1d?-wF#27h>M-G(R83;8(9ozR@eC<m8A?r-HWA6Vd70ooP93l;RX11oI!YrH$=TS%Q{pTi_foBStaI(>Gh*hPD2ohN=KJNt<(kzpX;4=9rMElk0Ekh2A z-tnYM^$E!BrxHn!vaT2kJ~VSf5g~##7R~Mrs@ac!WlhSMUIZZ*)l}TbniI1_dSH#m z9CvHn4NgfDIevFPYr71BIicw%Lr$zB9FW6jB|F40wI3+cZA52tBZg0A#!vlLj$GS` zFyCo6_J)C=Qb(uUQ^)fBN8wuH>2eiSr(fmIU;zk)_BxC`2nxahGW`i~J*& zOY%!EbhOhFikl=aoDZKqEMqIe$_^la{RoS@Gc6DV7Ewb9k|qNA-B8StWg8%DfrG`I zd14Tv#rGJ2(J1WZO&_>a8H~e^k#PEM84{u3dhh;`##99=vp8x?!$Aq1kRZgq91|dc z5fpvnCM`N(tJ2T(kzzqUS3Q=rtOUz0U069Efm}1!dXwj|9GURL_Pz+-HYa3~yC%7+ zZ<>f<%dAvx5`F1G0|_$%=n3H2NdAk0<;R2>$@$ZV+b%a+KO1#lbXXv#rI}3U{sG!0 zcx=powG5K-WrLQ|Ov$)&->*koNsYc%Z|<#N>X zJzHXilI|6$0TT5za;C}^IPU1%7SwAziak>XK^r9 zouT2=`$LgejZXK~>mPqOc*8nrt}w^Yw>LXFY6yoRJ0#O)K`af04ciS?O~+au7WG6V z^>D|@fNJWQeoASgG}ASZd4M;p+r^D2Y!M;6(62XXeG?F>^t%NwKW9GGVt+%f3o(tz z?lMW5i!0(a8v-i21BJ;zvGHZnK=!*U_#PjM;RJlaEVv3`QazOE5&a9xx{>0(h|0WC zbnf#YZOVCEFI`LAj5v)E!^H<5v23-#@@fWX_w=Wtr=3o8MV6DFksD>D5MTiA^{^Hs zJQA?ijt2QtZ~88$#9^;eCC58?YJou-*&|7?EIHIcxqNJLxrHTXfM783%Wtzkf(WPYLSh?U?n+s_*$Gwo=(t_qbNFDUdC)yXYXaVN zbSS-|F?`fU%}7OV_QP8&u`Z=GBp;|Am0pS1GCrvpF;Do=b6~CsE044N;&eB+s0o?l zC=4G~ik*i86SG;A!xW_~h0p7a!gkwbir3ri2(Yx49dNlLiCnMQC-M^QLui>QHs!?j zx>@k4N2=l|!(56i0&-P)*59ez%1j_5b{!CpRkD&l!TYp7BqJ|zYgk^{X@5k4;Y07h zb2AvCQL*v|c}4p7{8)-jj$$hE5bEjdCStlbSSDLhyQDB=OwRa(FoY}kI@9AA529w_ z`QgLgdEdJX;ELP{mhVEC?^e%wsS`RZM%bynUy6Gs>9Cyk+>CuO(>#HFKF@f{afw2- zs6!V+xHyb%J0g&M%6NL?@nl^tUENgESwiJx3x)HOZ7(E&9S?R>V#w^F8y>T{pL(PG zp?E+W*NZ8y=k>=Ep@pB`Pd+bv`hG1H?dgY=QijG4(t~GCpLQn9pPs5sXx*pTFz|p@ z@FaY|l@dS@PXa^SINpkwUr5wn;qzq~dxj#+htWkJRe%V1HX@sN(Ak3liF$Nb+O>AX zucE>zK2NlMDN#?j6_P=Wx8sGs8owJ>#W}~g<8xg=4KtFBlPZuD7<(gr4+puxIAQ>M zlv2=nzZ!6(D#PP>MD%BIbwT$t`X8+VWweDnC@?dch5M&@BguX#3O~-A+W(9y6hpN$ zEVZ^$)y4_lTWJl`s;c-l*zAa0Qt=IlZCV2U7^VGc&747I4Ox=f%@ z8-}#1&L(eV6rGt#GKlmADF1oAucxWf`Z5fULE)lA9r1MjOJns4eLw4+CB0DLtauH! z{df6F!F+19A6C^j;7zO=Q90`N_Xf#?iPhhZxa`ZAB;I=6Q09Ob+fGV6DET;d`yjd% z=P6t^;6%PzeRalo?J}tcG=IH9!w`|g;69Cv38RY}X2jur8Xa_aRh1qdj&0IF(nv8_N$h-V_@QhU}jd=8soCVs&hBU;*YYQ6^7~ zy08I|9)7|NB0jcN2xEG*%cW3RG?)Gi=xbkUdPeXwqQXEXhAW^dy{BPj-mG6^pG zU}V~rR&a^X#d{|m*9|?;9n%G<1Kp)7adBonNd+lhkcVAi>w8KNQFTQUf=c88#fw=c zx#uOQ?`H~_A-7-;)MshmTf7V!#}){#nhUz@ihWI2=umh*wi~aMOPk{CRlbSDy-;eNr3Gn_^Tjd-b{FA}n zH^7@^naCoKlXBLb@Du+xdny3%9#=F7@+SIhHntqZm0oNR4h>Jf;FL1!N^GNMgL7T?8~ zwj$zC5Zw)^o zT2zDGg_R{j8k7f3B<##8?vq?t$rcfwSi=~(3 z{X-Ksk;00b!(>c$+HMseuQ9|5_xa{exaI9i8jTP5(ruK5G-HERt9QFu4-^fOl}&v2 zdO6-O1@&>jnp(F*(ebP}JP0>#N%C>i9Sq6Jn;xjLj6ShZ`*u13v3?1Nby(QXgr0vK z>+}EL;2ZysWBpu3wWX8iyoKm|`r5kJgMbi-;p=!%E#4a#vhR2(kitkHG!+Q%{77C3 zr}&f8FKGF*^+ah0aHI&QKIh6gP7S)Iq~EK9kF?**BgQ_YBZw<%s}o!o%tsoo(8Edw zQN|cr;8D+sAcbfNmPu`H`FGR`Yc=^XT`d*`^8*SLt3SJ;edoL5w~E1YAVN^Ps-`M@&iL1~xVno=~f zpidti*hF)q@=ksAN>zfI(q`J?(;Ty!^^~=O^esYax-6)IgA^#4(0z$=z5t&g^YkUn zqYN0#x0_9%SmXlJ`h@Y^Ahb+8i&u9gX#vR%r96vP0*<$gtuK`3O?g4fu{T=Ko#RT{ zXrHa`b~32HWqN(9%ikivh#qAk>zz`}Qt#bMlY4zOV2QGRLFD-Te$i=UINoCtS$GHn zXBpz40z>}o0TtE_n-SG#pKJ!$ms(3ZQc_g=-WXQaSB$@Jl{kFMv&2D$0j)}L=Pg$_ z3nQ*DX#_?XYz8IFXT7f%*w45#s2!SV-D@}))4Wgbun_gwsjm*+0>h>k!RgLIyREXB z<6`840>{-nZo-LH)CtTF>sVcC92@8p2^^akYf~Isbtirz7?q;%c_!9_i>;pT2#wT9SI%ZT0X***;w74qCUi54C45rvOVutL@F=KHV zq3~MBNY)RcZhmYFZAE;oF|`}#T}%d1;zhEpDfM6Wr_imT@=){LOE?N!GL6VS>o!p< zO$2?)6qW)}Z4U-X^(y%e629~IzH>SA zK6L<;X;K`7o;E{i;medpOs6ZN>o8DhBAb4ILLtmsla|o4pXnuHh=CCV7tsJsd=Hl+ zbIB?#ncW7NSdZ zvc5sWo(VUo5^=4xV?{}lpcsdV#h9FMasuMze52X{31$C7;mm+_BYm+5Iie?7fE{VR zS?{}Xxp~_Zthf1(f(N=4P>-s_rD-g$WB$;-LjXz(VVFC=NolWE;IT3OF{QQqNb%=+ z&%LBZSJrD&xnHHX|GC)uuO)~mOQ1xR?bJxa8aMzy(Rq@V2f-z<9-eluj!cV^L+)iM>vo=^t(bjN{ z*bp(1d+n?uq3FaIunNByrgplf1Cn`k)H+7+!n zk_W6jHaGKRF1lGw6Vn%}`E*_vC&F3ev=4cP_d8$e3Sfqjz7=84 zpQ(bfPlAknUImO4zy?BxUDrVmghdyb3%*T~trGyI8zX*JEtoxFFGe4&X`--cmmYCs zx&lmz>Ag>n(zFy=jMmHOkOHSRw?g=KhGEJ1(h+2@@U9!MX2j@juIMMaq)?%IogtP% zT;GLL8YDf@8kYz*%GK*=+dNK=Q!6cTNY=^wnNGfX( z_>2wo{BjR#lW9g1jgpkdY(6D?kY6lGakdB2@z4t&E<%8nb5J2zvaX zunA^@jVEvC4bwuHs*!QgD|EkDb@My6xtq-s(s_n01m^3-twj1LdZp;5(&$AIBte;W zaPMozJy5i1_gZc}<|ysHt<1R$!XV{sCC3QTLZ-?uOD%fEMv>2)>P)|SEAc+-<%1y^ z{S#WVHW7>#9bx|`e#4idRc;UJ+*4&4hLz@Up%W2iR17nS{S^DwVw8(z(r%)AxfVzA zj3+2_1xqY1mHIlgIlt{BgLO)ODSy@uwoD5s6lHHsx%fTk&Mk1XOjye;u%vd(RTr%p zl;BJ8ALL8H(CHe@UoR7xN8Gs8!t>DytrJWub7?q^raGSOc2P+rTGAJ@u(#OIIlB21>GsAS zOn*9^SenK=`lLKD?mrR;BTUQ#0TZ1jwE?E!o37DTDs$xRRg2B=HZFWwBd10GjEj~|h74SA;k>WrP z(;yY0?7)`W4GDWaPfGDVPa?zT7WN(~xnQ=4ScGL*25CC=gN{!68cVYFwX`k0j#>pr z$%yha-CdLFTGdsI$cESHH?LrP9XSN(FIAv8kj(`+eD)JpaQ3A-?Aa%)&r~q{ip~qF z1DFUYjtv8#R^f^uNm2EwHHY6sED->xk$jIyG*3g=1~YmS=^&yOE0!epqqtnDA@93% zF%XGU32)bwQFq28f=q}F%#CDnHRx<5LS_uR;xYO?RsH(YT}l)yk(S48jKnMKF`GFJw3~$Rbz*1B;S)y+DC8av6f2v0U~ACKH#W7h+D+D2h=l~C zlhu%A{U7$eIxNbq>w6fw5eez;QV}F1MY@qj1f&}TL_tbvgaPRmknR?wlx{(~k#11w z_-;^9&(Wivc%Jt=@B5e6<;>j7?7jBhYp?YSQvP?jLh41V1wGO)LK`9woeg~Zd+Y7M zNhn0BcPebWikGH4STM@&x356abUWXjwo!9}!=xp;MtRyK1;!BqiUq}h@J`NyuS|tc zP{Xi?pD14b!ei9%Bk1KAtoRMUk)8u}5R+8Eg~@@6rngnB za84AYuG<`Z&MNg)ip(8qQF5rcs(9(M!Y<7r3?ih65c;-zvc4eY8{POJk(90=Iwj{e zN(V^DU^)9)QBm^q^HonTts_ad^k(tXDQ9&NwU$zeqMdeed-fkRA-m+BJa z#&io!EF@hff~G+S?qb=rG@?8(eEi~|G^OS6;!&mzD|vOXq-dN2ERaP5w|fa@E|nNV zhAY8YKFwFX8znF36vmvaW@Xfu55<`0#T1yg-s0SL-W*s6lYh5HX1#CP!Daq-{q5yw z7K}?r^SiJoWSn!D&M2otcv9f^1Q9?neL7MN0q^*4TOod*LP5?*dxA*f>}owdQq|t# zp4zm0bPfD9@-xe;7$-h_RLRn{PG=81H0djO@xeDYoerY>!tj|vLxd}z^NN}vCL&ypv#VWY4BM1*Ijq}iTeS7gL`22y6-m{iwJi@KiGCsB z_zES^z0CmK?L7S!K6%qu5ml+gt$p zXaW8eIJ_f(!)OZp3QhNkJALXg@~epsQ|)8(Z@Xpp&-lLh=j1M&MhIVO zar)^Xv3Dn%X5;KV=;q>2{4cze^s4!NkzS|522j(_Cw&311>?{q#(2=vC)fmuK_XMp zu;x-TKWH8teFtFs^Kkg`Ga56@hBAUjDxKzK;1{;?g5pQJeoj5Upn=$8 zJ)njnjF7E+DQj=NPmx9nqg~@N^;);GRK?ptbu7pC9qM63DhvwO?yvUAQ_9I#th}&g z#2B+?(J$a%lC{mL{+vkJ3<+9~2i7eI_n8d^3Dx3I60uIN4NzFtX7v|b!?ZafvTllR zFpvPMuH^1mTS~*b4&bW8GFW*RM$0javC+}8Wt&6frL6d&lC`%LqvGqWA}sgibkVO@ zEOc+3vhRSE2!=WjBKn1uctnJS`1>ozpG0h$Dg>QMZhb|<^<6{#%PIzc#7g`Y-}BGZ zWXB&sURgsP;>f8$+%ZlK)PKJc0mLBJooWHrdO&jPkBKQi2X&{Gs?vDa84_72cemI;z;P2VDh512(ZzB^NuO%ISxa{<5lltjmE=3BZ-6O3oJRXJq*vbn4AM1r zeG&yXm}U}2?UDvt4Dm@#OUbV2o#R7%jZ}-{5maWB`9KZwFg;y-y@REoo^GDsY9lf- z26KNm1Ge-q(Ilz4I5fQgY_=|w;a#bgmFdMkl$qK&!-er=jCnDmRIH!es3eG59rAqM zN#7T?Ehx_$CaPahoFQpg0yFcyn|=z`pxW{MI)8z_26kw#0|%!NY=)UNMQ>J{eug`p zY598VYW>TV<~+lPgNW93NWSS8ifA6|r|@L;4ohd`2oe?;CLt6ywddp8tX8;yQPucA z_2<3=PCh{`PXP1}y5G=0J{g03qJKai!c_LT5AjjB-W5uq( zglb+?D6PzoOkLh#udlG)u&A`b-XCEGCr?BIK|sP#h`HXW`M>U=s?;!S$-zS!*gqh=+B z&3^gCtl}A;#q6@p=EWQUUbmF{0!IS4+*A85SR-HDsB6_KgH{X}U3YSP|jPq4fr0Pn3;D@-RS2k2=NFx88Q7IV+3h z_TonC`EJJBZ5(5nw_C3a4c~6(TU~nF$$vJhAbS{Wn!&=7GPwL|6SO4ry1aMcUF$jA ztfEeJ_~oKkH;20XbG2`q*$o&Hv|YSGTavXgWZrGcpxl1cC{nsqdPC-0(iOJcqdlc zPckU9-l8}M8=BV z87RbUzUx=cDPq7x33kE4vXJX|T_PzUz*8A61Mtpd`F;2%!52ESvP*9+;(*CqU>G(5 zJ5h%BqLEm%Et1~%4c*ppOOUEz{O-;Q@ZA5rZzFWDxB9jx{S$;RWn=dY%= zap%KG55UHf1%vvveM9ONak4f zBqkR^y@aT{q`jqJMqV;2SBX+Gc_yk1P!lULye)!unl;fr$TvhLHJ#92DRpO(4SI7{|hVxw?x7%}2&2VXU4V1I{ViR<89H>3TmiMVY&o*YokBi@3rLg;1bdsh;p+ z+cozj`4OK*zCbe5dpXK!3zhJ#NFQf5EHU%bOHeq$^B`7|zYY%*BvE zEG>%NS}Isr$CYHZI=XqKP-$12fG5g5^h!o*9O3D8PYs!9g|RzDZ{%SESOB;Le z_^PVd;p9i5W*M+?57w*Ugev-JOo!_u%fpZ&CXEYjff{=(kL0Tzbq%#Kk{~ZF%U(F| z54qu}1YQM+#^dA~PsjzR7qkZA6ednD-KHWKX_Z$dLxqX4DPd5XyBAh=q_L!msouY_ z$qc22K`boxs)rKg74Z`o5IBh6L*1^26g(}Y>)yOK*!}!9CW~5r zvsS+U`x+gok!e#aUy$(fBT49f7RIHlkb_q*EMvM_{KShmdlzt)5r}58)%f8>`n^4= zMA2#%xNt9X*dejExSVL|? z-MmzMUTQ)9fqt7YFG9MzAw;oUttZ#qHWPWnSam3}w}4tS%j&+#joEunRnoROt~{pN zxV3W0(#82D@26hsQ*%H!X2Lf?^!ErvWI&Kg2!!W6{BR2oDyB3?l|^K+qLzy*V!nK4)g#$>D@E z*vW!X^f={-ANvBWioo#BToTE=*q5TD#$@TQ_~Jv2)9)w5rZ4cHh9nSqL7-$nzW@mc z2OLn#N4+AjF`0&aC(cV(G}u#3l9QTbI*18y69yrWf3EGKQ)6IIog!w*>p(cHXxI5q zfwsWMkb$5t0G$OsX8!qOUr3o;F*NzQwe_{iiv&bYvl-xfB;|Zi+ftx*i{*d7JWO8r zm3&-)lAk!+^y_q$0%N9owi(LaU;ao~pqhFFRG&ZyZlI&nk=Ji6TUK{EPx(vnx+!A|^hWaGttfX4Yrf8gDJEhLU_Z{G-sKPd@&QBQ)w zojQFk!H*q@kgk~HxI8-JW%x8)KYiY}#1v2q2`++OxSQaAPvx|h0R+OaGSq#r%P$1N z()Q}#UMJ5|_oW&8Qq<@(pVzYYvd2Fy3;kUoiobSDlV2?)3{JSlfb)7%(N+b6Lf`_x zw|c}rAWCtp9iFHPPlz=Y03as+-az;@?QpJXtP^cutwC7m49C*~50FI0gR+1M6&Q#N z1kf^|WpbXM|06^lI8tB$MlT##?dOgZ5s&Quk&NDNNL&88vV`@2aR2b#T%y%HUA-6} z#zc@Mhyx7#4{)-R{eW2g<|-GwfEt!6B&p$R&4_>UWVaNAhCf4~`6q;ze^K;F^iNC! zsqpeK-uXk4J!mK4L6~p~CI=RP9#EvU1EB$fD-AOGEavk?k@lzH|6is}B5*GUO#!r>y6N3{)@Oe-(NC^1S!{3zo4+f6$I`5xJ z7*2D&vn=2*`<`^QxYCK@U!|aZIbZ2BoTQ*%bz53K@8>_MiWV|Ycs(o7R-jK^aqF&> z7W+bAG4f1h+fb_OgQ_q%n2$RVpmFo#AH4dPfAHo1#1A$i`uKwvF(6X1>}IdYE&A%) zxaYt6!M_QG@5RiobtAqE^lx_~em&4pX)k>l=wJSczke;A{9GF7s?(we)aiW^7_e`@ z@Kd4l?^!E9xjFpH*2=f19*Btw(4*5}Y4{i{Fd*PWtpZL|LNE!ie~$j>L_I?u^MHiO zgOMXY@yA#Aud4`ua{nA+vxMZ1|HX?@?vWERF7X$KP#VY^sI~xILun9y=H#ycKQ4txLq>!d>4GP@K1tozPw$g|B1BZ zAFTZeZD}--)2J02%7mTYWtHXD%5M~ppbd3R{#?carcV#ZA<96~KtS|;Q=AYBxB>o3 z4ngz6_eh(Nf=nyo5%AB2UkH_8D{Sf^MuB=lOzQ$w)to_ODR;RG)C<0=2O zqwsfAuJeyi`R(sbIsWG`zVkzaqSUaw-42!~2ip{&O(?PYmxr{_fviv;TX-`+w8!{bx41|4UB3^fmeZo$UXT zlRtU?{H8GYv#%wae=hg_GaKFC9p1l5cm6Lq`LiY4#iXCfy-#+uDgc1=37NEdS~37; z_U9_$Kt~)N06L37(EyjzW9HvJ)%StU{l?#LVfiy)25hn#SHvTCB41fk)qME2u}P_I~J^#>+dfN30ok7X;OBP)Mv8ndF_A4SY*E ze>aZF;Vx4{{gpjyvw=tp?)EnB0`t5IBlr>?!jjd=@&E?h%4qxBZ(0+%!_e-Ryg;~h$H;s8ZtE;d3W-JR^S#ZrS5;voHxC^5d^>VFIu7Fw5085KNSxkb zi;lZOQ#Z!BAmgXTJ8wbF^;={q0?PSGJGUY{?v7AIdUUvNqkB;p3zK`$CWq_Xpf8>y z_knUNCV3dwwmtcXBfF8@a^fk;q@?^XQQL`R z7)hqjyg|z5M`RdaeuU~~K4NNtdL7L{un>c<6}c=}tk4==H|rsyiT8821=XkEMx^9| z%w^H#qWHrE7c6k8pbuDldr}5mWJTsunvc}!50WSCY-b5hpY;JP?F+(zBMZqo%ireT z9>5XTV!(fTSCu~3$SUvdOe8Wxbn;6SKGT_yErfW)?4w|v3>Glt#ROk|?=76V5}T!) zm{E*MdQBzfq#&=nkYOJWW$8S|T8_(^tTp_W+-B{V@D<5Xkve5YucFDb-o28P*v9tC zhN-SEosM1Xz>(jd>|ly2WrzjQUEN03o!Wolowk2pG0j;yhv;Uv7^{?JVTeBBR+q4d zan>D2lB0o`u>q*jEsKW~G}{vjPR~`EBDZe^Fo@I22JjKx+3ui5(olt@Y0ZWS-KZG6 zhb~Z?FPIOk8w~!mC1Zc93Gx?}F+p&FQTH^}rNgGi@)xC(LDkmmZ`RK2?vSpd^m@my zw=x{X-$OcwRaYJyYrtFvek~usV9+;m*FKw6Hph7r5-0>-MY<%;v{?Ky>rwmVfaec3 z)Wv!e-ZkVL?YA(6{8e0Wd)2{10eZ!QNn$z3 z!``D@>g=4XWe2sry64UH?CX|f2$iYspvD>!7w;AiwpQ|Jc|(Z3QJ}|#rPl$QZUh%s z>iwz(DDWCY%h~hSAL-fLBAl=nrjp7P!tQ(TOXkcZKG^d&>NXPSOCsyMnaV_F@~Ilvvp-FKe3wUQ}ZdSFYEV zNFk{@iNQ>R%Ch_3kE4bhhcx(`niUhe(&K8=@e9;?vNd}$G!D{LUW)f-MTVr`;#s6? z@lncG^Og@Y^%Z#K-MNYYx_FIeL1rtxuX5&nj;JlxO7(nSwa0AsW3fyf+?M`&>4(0^ zu9>=LFAhY>hmxIQ5P;1d2{t)(3&In{9fe&+W>M?0n+h9`Vb zH%geLNcoWkALxYio(+dF9ekpYbm=3w75W(58V?}qjDJOEOwh&_k|gjLRu1zzC**14 zzXws5_FpY<-yP)>XFo>NVbTf!_APW1SW5b7PakfgOvwn|G^d*hpK}*WhKNQFXq}=a zfT&6UVv6_#i^>Q@6&9`D31gewG$nVU#trag#R6&RT)l$>_yMM3Ae=-M);W;&r=l_N zfHdF%xF-*wIDWwP7nJX-9-GAC(T3*{kDZEnuY*2)4*D3)7k~PPFC2%nsO5P0u{{u0 zxYiRv2Q&)d>*RR}*SrxZ!KEq?A`#Cm4EcT0{3Mr~)VQY|@1MHu|0@bSCn)kFV4*4g zEY1j+D$ai`bk+aAy3ju36cKS4Yb$tkKZVXEYNbIQk$t&^R0L`Qr^moQ<~WHA;DiIeg;t=N%XAgoF2~4-W{Qrvj$~ z>dC2c4g?LH4zi>!pUmR`11Q`e>(f;Syg35^hNFUx`M$Ux-mDez`OPQ?oTpSA;J}Ci z+VKy;&L<)BbM1ISqlrF&$CO{|*nSCQ`{qLYAtnq??nR8m@4()YrMcR&}BQWRD{n4kxXh<>Qd)IPpySyF-S;(}wVR;@`+SD;__R^;>cD$T33`2K zjAfAIgBPys5z6&(7lhCLg}=h?@+1;H6?G_$VmjK_3E*enHB1tzB23d2<`?I8Ws(p! zlHox*GCNG;irZ?d|Zr@HXV+904)So0>tDZ;RWWOhRMr9bc0NL#RM=dsI91A zbp|<;qwL}6-FXCeBc>r&CnH>7ZZ3GIK9QqFG>p|W7f6kUh!4;vR$)aL1xo>CmQNaN zXJ=A`eRgCp!2>BlLeUw#&FKOBXoEgH>Xdm5F(vdn=wX0*j}MmBCLUw<(L*B%z&UDy zGPh-S8@*5ia|n{slh2XD^O84;9`?v`X!#K=8h0jSCf4^>SxhK_1!TEwPv_bAj5R+EosNmh%mnS`8QbzO*od1~d?*zN>*q_InLPkB=INY=`usU0M>M@Ha7o zIU&jXQP7qPeoftaGU2=rlHZjo%(cdeJn9uHyFM?KEE7Xr%UPJN_?YDY_4UHqXitt- zPFJQV+t+rb_X=rBR+{qd-Y(qV&bMfHC~ zuZ`E9p|PcP$a(9gDRz&jdfN2eEPzfTX;PkGflVy-J(@*}WHoB75{Xj^h^*LqxAv-~ zDpOUUuHk-d$HagsK{YZx(FPq>b~*gKcv-tB-CX{ zD0mI(>6Eo(Wv{NW%q0BN$JeEeo(88+8~S3w?YK?xzn65s86+2^N)>uNt8gkpUvq#u z6b02t7jmtOGbK8g$~I2mDJ3aHN%K7|1~-fqTc?dKg8OWOExF-rqJ1_(xBd}|l96^8 zT&R&w6jHB|bexj$d}?@5dRkg^!oBWf=yO~k2AHCwTNr=`?gdDs_zimFwCAydCh1l8 z27`ExEIHG%t9R2)fszY>skcvW(_9RoT(BG{ffxyiL#>z^D}*$2REr~?BUmX4U=E`! zT~c#cDPK+?V0qqyi7fO?ygg&pEI$+xJMyTK&axUtf-ScOHfLV{g`ATrMjj%_CFlBJ z5#>U5yyo-tdc0eXR>>sl`|I_@0mBy>sXZkxHWOwz<~K5>Fy3yx6sE!2!anQww*CB& zqXH&}v_^Mpyt#%=y~t{_bywM@-|c9W0=)Mx5R|jdS1avB6}?thh_SGIbNHAaj0rN! z?o}q)FY04em5dt7$cDSqb+yIp@~ztsG%k zOL_bvym^uLSSvY3LJjFvfE@R{*ttE@_14R)&-ttPnW5-(DFY1&k_rX;-VWcXDqBxR z#&TjPwzoLk849_%1j^daN8FohU^&v99unl;<3!8l*)1HqCwtVn7Y9NGS6iXxlEO-k zLm?*cgPA*>(fmlkB%)^44T%?5mm1GIxf7n&dxvNQ*(fuu3W{Nsbw2h(X03=#BnB2jeM+ z5IxQ-9}&j{oW#;PI=eg{lsu7lS3<8bN51kkfJs!u_j!+FsKaBjYbVPIH{5whAZWWv&gSuZbszrb~uINQPBQk}-MD zrn_UY`eEf=v^6T0d@Ib@Yu&eVmtwnzls{)Pv&?j)@~J95IuJ# zg{!-%-8M8Y3Kgmv`6?#}My1Qk!CI7iYyL>u$%EC)jZ6tXajwG&zc3!PCPeUZY3EsX zn}_I+Xs^;N$odGrPQc7cy=qwm`;Zn2lzRyQkKY(02$K@AxOMItTUl2qb1ERZNAk>}?G%r8L6$akmly`QJNoi9n@aVeFj zEuEG1_8GIC7wPJB2)Lrgw8|*!8Q^tTWlQf+ljiH^J@$wB+U{OU?0TPlyDfubaksr< zvM1+WQHCZJqRfLePZ2GAmpsvQZwffF5U_yY8o#kT8(eXY8*HXN>tdaY(uIQfx=h1~ zrh!UL+k^vkF=NHlLB#CMqU=Y@u-e?}14p|7#U&deCa{99A3aBR%}&qcFTDowLE#5O z%PtC95%AC8cRnj;8dSf9KQc4eTUOMzVwS_r{3anUHyM@1zQJT*1GD$}Wl(yIO+Jbre<1taInhR`0zf(4<@5s#-wJb@HXxIt1HSBd}Y#q7RQ<6_8=@L^WZ1 z6{TT>St|hz<>rVxNdo6!UqdRr=6OwHeAU=CNS^*%9q#$YPlt7>)OU)n`;UgiJ)fq% z8DY1z?apUDL36=lM`j04)PD|hcptUzr~z4E0n{j0Pf2^HDXYi&OiCv86@#6Q8#An- z&^M+92qIfNH#h7uOmr~0)oKEWFC@_%O!B#wyku5N%t#2k=B#zkHwewvi;l-wj;8cg zlD|!wa@K-U%5G1x2U~{T@`8#(X@|;idiI?di36*_CY>q$IA=h)V0ECsQrIr{{(Vz@ znxTOfIQG0KCNn*my@4K&&7#B`re^AUL!)SSir)Jzn;Yy6&q#0OH4&NGncN*-V=gWq zs#vkVOb~HRKQHht&(!@r^)b-uo$4GUUAMUY-U4BJ(TWU9HSXsV7&4``COqq&%2y^+ zriUCgC+{PdrvB1L&v>=33Pv*!zm}^wOFfiO1}v~=>vBEU;_U*}-HTA5GMIrC zBFXIq7fM8olsfg&yjvdPZPcQq0(q}mTuDquP1nLIoV~7gGntf--fB;M@09IWdQq!2 z?G`RC-mc{&Oq5p3sFbbNRrRAJ$~4C5q}8P7j|1MLsJ)=R2;JCkaxFbXYq~!R97Z}F z$CES4N&KusI@Y-FX4auuP-k;*=lb*;RyLE2`{hc|#g5EKH!F{#llHsO@RCGJ+_9>z z_aQmKUf3Rcz=m2B$F$sk(Z!)mAaz12_HHq$6VYbLgcr-*St5aRPQsHu7mcO{^z;Jj zC;h093gf)NuTtNL9~r)r2>|bGQV5W*7$#loVN)TZ6Jd|&3XsK_p9(&QDmERW@&k6P zQAn`$AWX30X~hJnx&{JR|2)vK16SZl)%B~{gkS!y3-qjId=wVz;$g!$?JXhMNMf zgZ-9a2I)D1Q$DCJ7;jK_r%*mQp}Z+(@SWwVIQK5SFGoV+bS!}j@l)VJtOx!eto~DF zIp$;c?tf!P=vRxK(#4FQe5oHDT-A0vrJewznhcDpE?5kh+MiRdxJv)OtIY5XKcDSa zd}l{kvE1M;7>+-1IC$&(07Gdzh)H_j)`W+Zm?)ViX~O#e9uf~ja-}NTcL7XPv2zK^ z6vf+nfRr^op&Ai)Uv^UK#IJ`%v;R16TNM#K(;6(g7R5f?_p3c?bFJPeT+ zC7TZAMct7BD=UdX1zeGjCkrzi#kvLfya~d=Cdqap(Pc$P%*0&EqphLVmnVgFJ2y#} zDtX~hteH<<6oW><4sC%}Bny(4z@JqpScCJ3H=Rxd;jmjee$#Y)HaW?zRwo{-UkBYI zHFRM?IHVY*YaydhzLqqjDEnjO3I?c50Xi05pm3lNdd$&nfccdzOdKZud(P6Bg{Q?a zpn6&YR8I}T_9rp;bJbI!e?TE&?t4-h`x~hLDXEOnKikIm#IgQDzqAyG2|my;&>Qv% z?W7N5@f@IE`WsKF&(+gr+iC$3oX;(&V^1k1qaP;&bSDM(*%E7@GI?okALfCp71wLIqjquX|vp zi+&>oQrS~2@J0+8{4wtY4hASd*qZob59DVK2Bv*(j*CFv`4{gMpXS$-sw4fz@1+(b zw*DDm>kc5ZdL}Rn`{ZmeFQjbaD-EThzhjrU1?XIR;<&0nya@kzmxu*)u0NR#ezUFi zOoQMJqGvyLvrgJvP*9P8)XlM8B0L~<16pJFupmxe zLxKwWb_)y&kibC%ivl0|ncURV{QoxzoXf^s@UH4unviYf@%ugsqATThjb>n7JNQsX35A>+6FWD=34w(_kv&Xo_4Nu;0K z8z9v`X1Lk@{Mp;t&Tlmzum2q*e{JB!geR#-V>AzWsNwZfpd63~B>{PmK3MT5Lmcof zzxe;*^=pff>UrrpK&Sqrfe!jR2Ksj){)0S-(zyx+5C>zz@tz8jJb^jlc<~F0%ggEo z!+%U&U_jWPn(-f8ZyA1|0(G(;)c(IqSFfdjfb{@OQ}QC&AFPLhzc5WRwleO36#Elf zDAV8UL_e6O@8df@9Yo$e)G%UJoqU?1M*6O}v4|8HaNcS9{<@U|H&2%vP{;}e8G+7# zt^&(V7N z=wASA9IK;Fi75XYospfl#)KTEK45^9-@#4b2FpMW`S-x<3Y{HCT1VT5un6NWWb+2G zf=AC%PUQNvjAjnVU%4X4ZI2(v$b?6tn5e5ev}@yp7bV;^ac|mWuVBv)r`72#7XE-D z!5?m21rh)Qg*WLhw5c)`AOaUL1rcTr9@nWF$9;NLLB5*Y|D>d?SG3XT4d;p%5e65i z3Wy*RotPOvp z$n{rcvbHhw-P(w*9Dbh96S&b@z`|R#(4L+ztXh!9Nx)S2T298ywnt^vv8b2MlQ7zy z$n#*mUnfjzb3i}k(Pq9T?pAsc5&`3#VVlcWN=9s1_BS&M506aHEBbwqwuiPWpOL`s z4W6|~66lLu9l3XPbfqac3ict0#J4$e@> zy|xIhldhr0>X(-7O7vZESbb&3tI>P?wwdF4qeaY>^=26+hKl0Sd;v@>2zfG-1`NMA z!%)Gb3>_4u_QCRDJQnQMaNi`-E=V+whmN0b?8@7BInnpHv67su7aBUooDb^G##*{; zm4i1|aKK`b1hnz)_bgq(MdL9%#G+7$qXHn*R%|e(Ky@x^(gQfhD3B{_y4wwNizzPc zBF2UnSjD;O^nMe_ A4t6T;Ti3zRbI=3}xq%06!QVSFUC+4);{rZ_^zdj3xRNOO zTl5SHqH1%ztX4eZe*JatAzVTg_9(nmye(il|FTM9D0^18l(~;p)CkJ#AwOKp246y*O>tbv@E|qun!{(LLc_ZC>Bu=N)5)G1?lci@ zz9vY_o~RZb7Z-1_8)C`6Nj4S0QJADZ6S%jwE? zleRg|?@ew};H$hq+q87Qwxm6c)L&6RZ}{Vf`KEYjN;OY2(vp;>V2Cy#Z@6@mPQ#v6QjkY zjqlB@UCW23Ba}$9wrOsMNQ}&@DVN^R8!$Gb7+gv2Ehm-~<>o>hRei>2KlBvUx7UGV zGohhE6I(QGasst=fQouMVQU`R@9Fr;%I z;4x~0hrrI-lZ*~qEfe57_AiOiE_n6r4ZkZEmh5_w?t`8`c`;(UE?t1u&ww$;yKB3i zqdm|6PU{=uz3m3@b4-Y*K}7bek28Euf3b%nPVCXZmwOOsG`k*>c>76Ih?4W2gb zoRJliHCs?B-|Z36X3G$`Xrf|5Lkjxbo(cgu1MNpHU=5W2rakpR&YW@E;*WI6e@|Gg zRX zh)M%EoiY{@CfO`#$`*3k;6oxa*$;glWy_7414vn2Bd-gKQdL8C1$-H_TgQdLcEJdV^#;`y)4F>o; zYe*AZo`x(PL&I=>E9^5#NE`G7BcvT?ZHcw*GIR`U(~F|pj4$BM4l8s?1|(gQm%6%a z^IAq(>V1!b0n__lC6f`hK9vW{wy$L^Zfy1$dd6(_oBA$q4q9X|-5IiUzOgwXcJ^S9 zMSSb1?amm?5o+nU6Etz@#1Tez;iM-4ApY#d$9#7xm|K%`>d~$2XXB66{kJFM4Mumy z!*EwP=To98@6KiTwsXzqG>n#xk~y32Etk$_@2x!FTG?BL8B-|Yt3J!(*j-D2zP|wg z>-OK4cE=8OMP9Wyc;Bynv^_iYmiOM~xF-wmYFB~M*05Fgqr;trlDNaY8$+zm_iT|_ ziuPgNWU@jX9 zpee0Az(siif33d;({0V=37&X&eZvbJHyP6n3gW(C_>9UJRJwz!J}5i0f^$8&p8P@+ zhDRK*wdD9`?p2My;0GwQ_s#)CySxS#H8Lnt1YNAd&d1m}hETNlln+GS5sj7M)-NKS zVOwH|$M0?w1{ce@TzT$^$<&DyjOUJpsO8S2rtNFDpNNg<-1=>lYD+RlhJKYZf{g!jAs;d}ZC82P@zCgfPwsA`c0o0l7`98qvBG&r zZI<`C}WB zDqlV=gozsD>_~vM(r7QFE-Gnzp6SgNDLuZ#AXaeLyCmuEJ~3NsEm9~^K?birMA*5& z0BNjP9@$WkAU#v6!7` zVbs;$M-VEen+>oquU~@8TXo<9#1!*)-)F)MB*=B`Di=~?WX9*wOFwJwuggaFl)jq6 ziE1Q!xAJjVpe?@MKwi7dBNJnL@(0R91pJaz)nGTCIYVqf8-biX6W=dQNR?)2;po+7 zaY0*_ne86W@XBV1y^kOt!i-0(yAQUoi3r0AeUn{d7x?|QJ2 zrD!McR(90EQAVvh4}d$>O((Ge!s}T=*B{;XdxQ6OyMY&N!>d3X12NaQflc~iP*~;^ zHS5k35@D1(3bQxfg8Q1MpKb)-QrBa;Inbgyvk_{-UA9IIQ+O8VZCHd(8t@q5ElATM4ZZC zZ8nlsa)8G?rNwSn zY2O&^tJ-Btag|zfKS+!SuJj{%+_t389hEHWR9u)MWmYLvKG@&R?lwi0ru?jKXoS7D zq>jj3=h4ux>ID1s?5t(G^1YEYV*fINi>ubILuBtYMJuuMS6RonM?vVN)$r15ZUp<| z2r{KFaNE~Bxc4V80!nLXq}P4a_b1PFl-6Hvx2nNV%^(Vs_*l$1ks(6>+U9uBABs{x z(;d0WwSVUeKn#Bvj#e|)-z-gzRG9M1Lew9V0h8`S_If9&@?x_=P}1;dTY1UqSoKMf z_J_5@A14DKxD#jTznBdC$o4aBOp+!J-Dgkz0S%q+p&8FT@%rE}A+GksUznaw{k#-ce`F}&Fp(T>2RKZ` zdmJYNp~s{nb{`{vbhNOLkz0S}D+AtZJ0E@APt?4EfRr%+{L?Ap*;QA^Ig20k(2x)J zu>TXK{M((*u~&VGPpE080*SvZ<^OETSW&*U3Q>IUABd77Z;?|T(YI2@yO?s)!e4_c zX7q0XHq8UK#K8CIPN-?gUI&>cDdT_^ShNv{5)3q3j0pSRx=4NjuK3EP`8QGWftq#_ zC1}S{l5CU=ThiP7xd{Pu^^ZdY^3lEM_ZIbEb@eYKR=6I)IbofX9~Xt9f{m7ZCQm6E zMyZ_;+_dquCYXq1^0UAC?`XsTN^zm)Cd?hREHBm?0a&DE?GR9{i2x}K^rc#3h?zhM z%mi9610)+%ZlAL-()@8F@i&&qsBt)282~KmPuPnFml*Hrh&RKdj!_u4=#I3-GJFh? zPq&I>-$k$DXkRzYtKHFk{81k`IP2JM*ts=+&+_S2g z*@ldp0S8H2fRWe(A>J6LjopTIg1(#4d{zM0jCTBf+r(v3d-xfV`1>gI{o_u^T(sI^ z;Y|h;?)iBs6CNi`h&F8ij8W=pI0;lPQ+2E;i|2HV8BQvff?I&#k5cc=hZwx2i2+CJ z+ixCT-4xY@@Watk28qx|=(-6Dt4;+=u3T0CDwjLTj{x=}m5-VSoxbADWA@_sqqJoI znkUC0LOwehX+sQ4CUz}hO4q%F=~+s!qWn%uye#H|!4p?%uG9oC<^{t<$i_Lfm|&!k z=-5VW<6%21y9J|&5D(*7+h`|XBVq7KUy#AdKbMefmT>IkO`L7aAk)xx`AO_k-g|R7 zGT-2=h;~oSf#Zyiqgvs{i zNDP*f#f#a|)AcQ~qOHQ`a4j0~%Q7n)R$2@zk9IRmt6=(C62v#Cqg9h5W23TPDo^gM z)GpJTS}8@0h_2UkN@Nv>8I~N34qD!xXP2|;Gus*=?8v&@a?|%Hi>=pb3w3)O41Y-5;XreUKk65i zy8Y%pJM)eQM0s>@Dm=%acshg&m1IJLfSGIVR)8kQ{N2L>&RLd~hpL@bddv>?nSJJi zOQnyE9YVwOGBK9$W|;R&%exWxD=4Cfxfa~wR`xeK!klid8+S#$S?jM7=UIKmp2;&d z;F+_ssiJ9ISxDiVbGR@S5RU1xn5@1$_Np8G;GnB-?8@O?@?oc)S?ivfIosTKX)KOM z<(gZ;XCJS-uDT3JX!&ZC&@I*!id4-gPGT~7?3sl!!HXSgg~74T1b%4?>tAf zYjDN3!M<~mmKV3oPy7BaY)Z+L1v+B{6=WIra5eq%cE1>f~H+sp!{d zQoL%(kOF*EF8N^J4X-j3bOE~8MuA_-ue<&?<3$Mps7>dl?&+-!PIRo4VE@^## zo5Dn5IyaF4>s8BBdF?5S8{PbxzVHV!A6P zbq|xw?t#l_+|c zJ?6pXQmoY29;g1I8TMT-><6hR;B6(fF% z6`)c31o&c@Ctr;AxTMR`NpdVpg|`3n6ll0UQRRaOtCe|9D^bKXllV)ZVGBS%Hae-F zl7ZAe+6sNL^6^AGBOHwIDqhGJi$%#4`-3>dA4|bD0_EjTk30IK$L*gYT!CnR0W3A^ z6Jag;<03A=aH@8LgC|F^wA8-(5dAE(ZYqY(HE%Q)Oute&iaKvXny<|=e_xdDi2Ist z0x+CXJ}3|8!2l<`Cuh;&M9Yi1~K&8p#MCOTJNCh(S!gUi<*wN5(Qo!NMHU8~C20ZFp zFZ}VeeCre6{XzftsMD?Wht56!3&skF?hSwq#ttF?V)y6-I}91G0>LAHpk}$kpXH4f z4NMU7#%47ZqFp1Y2XYnRDZ}%L6(E|cfVT-TbB|;WpO^PN)o~d1cuS6a& z5PEsk>#yji3VxG)>+VWhgsOPZ69JOqNTT?V>VaZ2Wy)(aaq~=3l#u))L=HUpTOtd3 z2k(?I>7YDb;LsJkdEF@peZ@@A!WV0$o0Xbpc&~RN#|~^(B+o)+x!^96b6C*hf5=CN znJ_!df>F`Bn^l_<LcCNf+JxaD5hVP!Vj5(84~&cmgAe1LX}e0393q9FHi< zTEKWUuxEcFyOH2TpF1(Rx`2aKdg1smp}^UHpK}W^+2FHdY`XBYB@CP9kV3VKvNehW zc`#!DGestx(WrfDry#W@M$`=d#yu;_nkQ85^m^jhPugOr^30>v-W#?CvblFH?Y<4G z@D;m*bVUM(W(Z_KP#k$If>X@W1_#mER2C{a0uj_k1!axF$dB{BTfCgk6Xb;W@(MCc zo~DN@XL5++V>2+w3%h}*e=E?RFDhXSOe++Tx<-Ng$oQKWvS8?%jwn>ebrvH zXX_Uh-(YH@TeK*Zyrpcq%aW45Wxu!>#VirG(!F{cF;V2U%+@nCFx^ElfbV%V9eZj0 zS`j1`SKLQ)os*v2?t0H&P$QsYKqOAr8H!m_viT>@8_Di^c~N8R)6otA=|Ovpt)ddLDO zLnXynF&uk_$Ait6{or0$ViStXt<@RqEMob=Kja9ioe-y7a=pHpqKle#! zXeVc+IUIhwJp5U~Y)3p$&1ri*-_xxq!>Yu@HgDXQC0F3YL;xsj@4>V8b4kapvIna#R~cB{j%Fn_9kpSLxR6^GHUNfHp5@ z()DUQvB}4>!gRO}aIVT!*OaY8rv=qDjh^1UVeL&7uIpqp6MoZUN?I(s_1*RGvv<8` zqSZphQo;>-BWPmpG^fpm)78;U$3MhD3if8F_L)nNq#vYBloDJpObSpEPvh66OS&bG zWPaU)KkEGJcBRLm^z&(4TiMLWsoE#TQ-217yH6RtsSFbio|VAaBl-0@ zB!kx6dbHcE(>zu|Y|WyXg&S%7B^a;8MM)Kw@@iSipRczPb)#6d;=J+8YlCts%&*~x zC(^DKS~a;;EpilPn9K<^uGn>rf~lxWPJt=AQ^g?b#!J6}^x!^4*ZU#;8qP#?1BP)~ zc4kHe6?T1~#|MT(iZ7QpN9<A>>uAxIf7(xj}8tDd6lrHH|;tb$ot>w|Z_St*wALm@>_gvR^ec$`e z^StkKKlgnrqi7{jhlHKceS~*WJ9~|4>_3`Kb4HiUB&)T1Oft zKX!fdGBYRHG)|}h@C|Xo8kjr%BY-_uGL2FimsBbp-yA4KFf`441>aCH8r6@>y(CZ^ zKZEEPFHnknag7xdBu)(XOJWdG=0@6SkV2fK$cxuP8EF6j=zQbc-Ssd7d}DB^#ar^# zx8!I_8N~4xVRWJEPaMLHOlbTm2+bOY)=0B2KgYgb!j4oc_E zP~?nn(Ms5mrF@um&G(Z){1!KBJ$~1;x1fRnxhgDU=Cc)Rpd~+nP@^Y1K6=3^y2KjYzx;B-sSL= za!tt!0APfPlMySyNJ$gXY1t*$%M|QV909j&AfgC*jF64Z49Xc3Dd(!j{-n($cqA(R zgZSR)ge`CsI7dvvDT{Ab0nYX$Pa#M{R@1Ea)^>SQE>NgHEIQR&H%cl_HG`L`nv9pf?-`}D~39d%|e zVQNOwx2Y!tBBv!Ij@d(X+M?5&{p+b+6-LXl??SW{t|Wm}XWpeUtQ?{-vNUvnMO6FH z+ew+)&;d@EJ(@T2R8sH0;GTdnOGGCjSTRd#?iXmr?WC~+7zfi@^wlljh|2G#)#~eR z&Wcbw+UR5%FX6IsFo34ssJKL9gg z-{>`xhg0oc|J-MW!^ZFe^oCU%u2sQZU3JqY`%;z-j)8nAx))+KK#yjx(#%U`d1W%% zgkK`vUsm6x_`xUL=~itJ&*)n>kNK2|7t!T|c2)q6-X@ia6urX%81<;N$&+%I!&Fub z3;C?ny@ zV!k^}_t@J;h}*0I$B!A<<5_N(4DoVaU9LoIa#cs{4irxCf9OT9h*Wa=u(^z4>`oTi zBJV9L?V(g|&)Z(s>{a_!bPy)Pw>^^vFm_UC{pwt`ch{#UwL2|kn^{#NH}E)$$~VFs zQ4nuomZe-RG!`+Vj1Y8`5mZC)jdj+@M_;B)H3N5SqNJ}*_ybiRwXd5;aIN$p1;dNg zlt%7T{_3B!GCe58g;9VEO+i9syPsV`J%E{!pxJU0y$K&Rrf6leh3Ftbs|6PMIK%y! z-~IFSZCJlg@)2_o zE_p4@eiG*L1@m@KITV0w@{k{W8MYfLw#5KCOdyvCH zB+ThY9h0xu12uVued@g2>2WsHDG2KwJZ8JvhO|7FiYoPek3#t9e4fY0e(=NrI?x9^ zK5U`)>?g~;?6s<_F%>X78V5#aie+c;z5Es9qw_?v41EZWMx2oWdBX4~^Xw;8I8>m> zUd5~Ma>mc$UW4va)_tH7kQXsxjydWM`PPJMV|DC=V+@Glj;WMn8%0>Ppj+ZYM7eR8 zXc4gV4xrB??~?~Zm)dx|xm^@`s2!>++!`x+^l~!oY#y5ge{}4GxEaDJJ1x9@ThFon z)|CYvT}7*fELc9TRyy{%I09L^%Om%`2j#?9;~0Q)fcBTcixq$*zW+ss@nKuah>h*a^DT4l?jq$iL^5LfqM9x#p$DE_ll+A664=SR{jKp z6|*h+r6dfC?%t#P-<@TC0bcz-6m|YT`b)&=f8AOk;{kyDJa)9I(|ABu;=q6A%5swR z$aF8<5BYUGoHfnOW95Dx4{^J7p|tXdADR;H1+9wTpH|}9(PU?pxJ?|*_jnk%eijcR zW!FyQVQAU?v=aBS;ZGw|=D=?WIptLZRA7$185J~K8AdkEXRk^a0Q~K!5spI%QU13)vzgGMOz zi!-C%?dGehH}DNOZgW*a;zt60{@4V$^uBmshw1$Yaa%uv2~@DtA;fCAQ;xk`V9mx%y!Ot5xq(SaQ&TFK+$#6}ga?Ez3X{XqBohlGR4LJ$J2Vm=@icECD#{gi zA?JZ7^_AS1*qVjh+ytw<{H&1ne0WLCvFBnzS+USk5n^`iN?z4!g4OfVjeP5pdIIf& z=jFIzoFy&9i8iGj)CGkvIu*y4b(IxC*_LonC=pbZnAsFDdD|o*dd}(!OJ#@3Rj%?? znXC4%w)Cu5YS+dRuh(_&Xs^@(zI`ih*j$u%s69CHDtV2|FH+Ko!R9^xmQ>y5rg}XM zv{d#I#ekz^2p@F5g@I(cTY^QuaHE~Ga(M&k&w8L7$31Mb`A%T2aI;G@yK}Q!9E)qK zN19@V?41l-(N>=V|H@Xs{k}+p7@aor_8>bQn0G+OZDo7dAc%Hz$SAIsdPrOD$+Iyt zF&RXUeWj1epwsX>iubOK1E#GubH~XQ8a~b(Rc&a=H009$Bw$w=$Ch_WpA-dGD-|N| z)e%j?tP86p;+^ZNTY{Zib!RS2JyDvY;v$Gz@Q*4U{Zw4Pl{^zb6};7kxh|^oFV8^FkE>y>!vrbx}bBPsw@bw`3yym?tqSVCeZW|_Cwd%;_EEp9k{3>O;}KX;=gu-usT%qh zMjb!G!JS(aRQY4qzWxqr@gzm7LSkS})A1l0O*YzflXiby#@4Ut^696Qo=HQ19 zIxwsISdx-Q!%AWVA=w{n-_oJ_yNDI+iaV#rR2fb3?8r4<_5~F&^Z30$WYbk0LE22>H zw;AZKbFG~~J+P1$ne-PdC134#ghUR|(~tq>?v&k&swqzq3tx~o_l%vJx@LNbXNE!0 zTy>_YD3O%+gJhRF(6VnU*T~XR5h@q+A^m<7h9-wf&LXsAg2@!?!ezJEy;o{=(pD;m z^HM{W&D|Hlg)A7!ScC0DFA^#WtzE2j@~*U)A*5Nh(px9z+lM>R?H~&9SwOxq(ZnID zB|a%|51m++udmSRvB_sQNrZI7VYzXo0E?k~Lc4#slS6&gf+)1QG*O7zL|okH>(}1K;*yP!y!h=#fjxREYv6p|6(X)u0Xokx-%S+ZkF}UjyL)LmvTKDQkBK+YyJ}5fD z&nPt`xst-ol-wC5SsPlll^7T+Xn|r!y;&tTPaeL&(Hx9z8K_NLqPG+&?jM=SLKz?z z#VNgGk4Zlgw6>EWxu{DvrFC)kzAQ_~$`?r?20%FQK^@U7Ob*LHqHUk^RsJn~DV&W_ zl<;&0gn*_IhEtV1E;E9FiZsMcEAm6(8ePl-hD#w{M2qb=-tb#rzkJc?6PWUOBRa=p zT|Dj%X&*I!ijXNMS=p_6e2rjqWrr}XH=o8r$yzj6L$1>#L@IY;q9kG%ktcRU&Q0;> z;$7GT4CE*rK^c#|byXa*@i#`%%%p=}gT%3f!}{Ns^LIG$+_@7w5hX}y0386|q)3sE z-nfuPLNM9@M!CBXaX+G?RxU#aPvz1F6%Qrw5Rh3zBnnGT4p$|=JYUMm^a>ex0EYpB zlcg}t6DNI(!H_vq{hf8L(EdA@l+ByHNps@6)s>;UhSg#mxO1;@!KU4waZvcPC?p7 zJ5epQE6&~D-hZ21ukB9wl)l(L`uP1?T$H_hmFcYkI{Xmhja6_aj#%ln8pj%6&jRSw&><_}xNB_~?p&^d_C9>j<;&;;Ajz#`B% zIMCERaH5%Zy#nk&8MF@9lXIsmrqI1E;KNlFk#}Og0-K{_Ku*M13QHD1Ngk#?c4`m8(f`zwOgad+H%0|c` zd*OW=WYNU>_5vhBRV1U>x)T}~$2EvP0Ewmqh(2rRzh{5C7V~rt_>@rjX}>$Ao~+9* zxgQ(F{qj8`fJVfToAie*-)ajA^u4FHj#4==a`+1o6(;Q~?v%akk;WGzh%ZKd14bOp zhm-94L!603XNYnJL^)nStY;%PnL|UABQZFl89~-G9uRh_dlxt;eVn7YMuFUIWO}AH zO2;yM6uU$LSrCnRKAwGw>va(-M76mDyVr3I zf=LQHE?JZDF8vb>?B9;)O%!Q=tWg0*)B;(QKk5noB#~w+a zG*dJJlV|tYJmXVzjU{hYg{+N+tnY_xE(D_ni=hIIfYSC zS{YCX_lf`>SsHe`)>25KzNQ9Y%_H6y`hIW4>jCJin;&m8h z|I7?=AzzZO_Jsz7VcU2i0iK$laig8AWwJB)V~>;+@S3trK%!K}A_i*qpHyJz{uzToIWV`Jy8bO%Q8OY@ z3zd#$kI)(((qT>2DoNHMQNr@D3eCJFbvW5;3)y%g6~EjxtGo^FY|WcuXdf>R$8e87 z28i#_-dT*rO@G8dZTfOLu^gJO*RK+oW79y*8-N{*=TX>B9ZaE|)|pV)jr+LuN>K-H z(U4qGlP8H`LXiw*h_+?wBz18bd&m|?>TEmFC#}?J+~Ut)i>iW%3fqe|a8uS3$Z9~u zy8_SeR2F^p3|{aoUd}IG6)K@$f9^S0jCrX9@Uj>`G4*iKfbdeOp5t?-sOQ9qEa!|B zWSu7hzy>U%X8gR)!x{ZY-nOKp`GbC1c)GxPrXl1#ibPj4-3wq zX?eu*>s+(`@3;q6#f@d$v(YZsURAE8P9|7jVUi2Di%&J0lU$O1rQs;i96?J07SSv- z=m6imG^DWa^tn4qLY;g?uzaC6M?O=psK&*t@40G=ndtbo*+`}7Tz2ia>)cp_7uGS? zD}nWosLA-#-zv|naQOGa((4zfL#*dIX?I<}ym#?Erl3pNb>E!v$)T&8bpN)w__~8l zjLzq9Z)tOZC{ z1-_-_7d#%wBAcE%lAxOOKVo{*#6=ZbbGy>|sxkk}>GwY`sE3cJ0jV76kUqbdLD-sec! zYx~nsbvtBxz`S^WHp%Uz;~I4B>pVOYhHM<1_j!=Pq>3bqz58h}O*NIz#uB?&olY2dQ{U5zO1VG;TB5<@{h0MH8Tr18{GBh$C{p4C}UGd<@WC* zwR*;`m?;#sanQzV(Vu=VOh#1bmgQiU;tR>aD=}9eJXd>d^j;2OJ^I|dF`L#J!KGDc zHC5&#&%fG!irAea*a~}0?Qa6+#&ip-O8Z*W8Ny;-#g^%GxX{W@io`pccE?GWH+RCy zXS;I6atLZY%NrYm{}F=ykG!^u|0gu!e{G`Dsd)aEnH>AbsEUBBNm!bae5eA zRj_>rT_ForMdOtxgWSW`>CQk`>+rea-e%XZhyYt7{oHZ%*oy{dWP5XM^y2`?s zx4vhGvC~$Vge%MZNAnA}|F7f^+y7wxcwUTH{(czC9TF(~mPAem%t`~U13XSe4E%sE zI6vB9``+wC{X=U`HcD-zn+B{{=J@jVk~E From 4d65335025b01416d53ccf7033458fe58393eef0 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Tue, 17 May 2022 08:37:29 +0900 Subject: [PATCH 28/55] fix(accel_brake_map_calibrator): rviz panel type (#895) * fixed panel type Signed-off-by: Mamoru Sobue * modified instruction for rosbag replay case Signed-off-by: Mamoru Sobue * modified update_map_dir service name Signed-off-by: Mamoru Sobue --- .../src/accel_brake_map_calibrator_button_panel.cpp | 2 +- .../accel_brake_map_calibrator/README.md | 4 ++-- .../accel_brake_map_calibrator/rviz/occupancy.rviz | 4 ++-- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/common/tier4_calibration_rviz_plugin/src/accel_brake_map_calibrator_button_panel.cpp b/common/tier4_calibration_rviz_plugin/src/accel_brake_map_calibrator_button_panel.cpp index 542ce6f7bded..545bdac7b630 100644 --- a/common/tier4_calibration_rviz_plugin/src/accel_brake_map_calibrator_button_panel.cpp +++ b/common/tier4_calibration_rviz_plugin/src/accel_brake_map_calibrator_button_panel.cpp @@ -75,7 +75,7 @@ void AccelBrakeMapCalibratorButtonPanel::onInitialize() &AccelBrakeMapCalibratorButtonPanel::callbackUpdateSuggest, this, std::placeholders::_1)); client_ = raw_node->create_client( - "/vehicle/calibration/accel_brake_map_calibrator/update_map_dir"); + "/accel_brake_map_calibrator/update_map_dir"); } void AccelBrakeMapCalibratorButtonPanel::callbackUpdateSuggest( diff --git a/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/README.md b/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/README.md index d7de93030841..0d30686bbe5e 100644 --- a/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/README.md +++ b/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/README.md @@ -17,7 +17,7 @@ ros2 launch accel_brake_map_calibrator accel_brake_map_calibrator.launch.xml rvi Or if you want to use rosbag files, run the following commands. ```sh -ros2 param set /use_sim_time true +ros2 launch accel_brake_map_calibrator accel_brake_map_calibrator.launch.xml rviz:=true use_sim_time:=true ros2 bag play --clock ``` @@ -110,7 +110,7 @@ ros2 run accel_brake_map_calibrator view_statistics.py You can save accel and brake map anytime with the following command. ```sh -ros2 service call /accel_brake_map_calibrator/update_map_dir "path: ''" +ros2 service call /accel_brake_map_calibrator/update_map_dir tier4_vehicle_msgs/srv/UpdateAccelBrakeMap "path: ''" ``` You can also save accel and brake map in the default directory where Autoware reads accel_map.csv/brake_map.csv using the RViz plugin (AccelBrakeMapCalibratorButtonPanel) as following. diff --git a/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/rviz/occupancy.rviz b/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/rviz/occupancy.rviz index ca51dc4ee75f..c430c21562f3 100644 --- a/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/rviz/occupancy.rviz +++ b/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/rviz/occupancy.rviz @@ -17,9 +17,9 @@ Panels: - /Current View1 Name: Views Splitter Ratio: 0.5 - - Class: autoware_localization_rviz_plugin/InitialPoseButtonPanel + - Class: tier4_localization_rviz_plugin/InitialPoseButtonPanel Name: InitialPoseButtonPanel - - Class: autoware_localization_rviz_plugin/InitialPoseButtonPanel + - Class: tier4_localization_rviz_plugin/InitialPoseButtonPanel Name: InitialPoseButtonPanel Preferences: PromptSaveOnExit: true From c32361fdaba7f4b39c688a3063ab1af3790bb077 Mon Sep 17 00:00:00 2001 From: TakumiKozaka-T4 <70260442+TakumiKozaka-T4@users.noreply.github.com> Date: Tue, 17 May 2022 14:35:38 +0900 Subject: [PATCH 29/55] fix(behavior velocity planner): skipping emplace back stop reason if it is empty (#898) * skipping emplace back stop reason if it is empty Signed-off-by: TakumiKozaka-T4 * add braces Signed-off-by: TakumiKozaka-T4 * ci(pre-commit): autofix Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Takagi, Isamu <43976882+isamu-takagi@users.noreply.github.com> --- .../include/scene_module/scene_module_interface.hpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/planning/behavior_velocity_planner/include/scene_module/scene_module_interface.hpp b/planning/behavior_velocity_planner/include/scene_module/scene_module_interface.hpp index 50261de15f5c..398994b4cde2 100644 --- a/planning/behavior_velocity_planner/include/scene_module/scene_module_interface.hpp +++ b/planning/behavior_velocity_planner/include/scene_module/scene_module_interface.hpp @@ -123,7 +123,10 @@ class SceneModuleManagerInterface tier4_planning_msgs::msg::StopReason stop_reason; scene_module->setPlannerData(planner_data_); scene_module->modifyPathVelocity(path, &stop_reason); - stop_reason_array.stop_reasons.emplace_back(stop_reason); + + if (stop_reason.reason != "") { + stop_reason_array.stop_reasons.emplace_back(stop_reason); + } if (const auto command = scene_module->getInfrastructureCommand()) { infrastructure_command_array.commands.push_back(*command); From 49d1764a5cb02924910cc5fab0f055cc337ca8ac Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 17 May 2022 22:54:46 +0900 Subject: [PATCH 30/55] feat(behavior_path_planner): weakened noise filtering of drivable area (#838) * feat(behavior_path_planner): Weakened noise filtering of drivable area Signed-off-by: Takayuki Murooka * fix lanelet's longitudinal disconnection Signed-off-by: Takayuki Murooka * add comments of erode/dilate process Signed-off-by: Takayuki Murooka --- map/lanelet2_extension/lib/utilities.cpp | 34 +++++++++++++++++-- .../behavior_path_planner/src/utilities.cpp | 5 ++- 2 files changed, 36 insertions(+), 3 deletions(-) diff --git a/map/lanelet2_extension/lib/utilities.cpp b/map/lanelet2_extension/lib/utilities.cpp index 072f079028db..8983d9d4f367 100644 --- a/map/lanelet2_extension/lib/utilities.cpp +++ b/map/lanelet2_extension/lib/utilities.cpp @@ -315,8 +315,38 @@ lanelet::ConstLanelet getExpandedLanelet( // Note: The lanelet::geometry::offset throws exception when the undesired inversion is found. // Use offsetNoThrow until the logic is updated to handle the inversion. // TODO(Horibe) update - const auto & expanded_left_bound_2d = offsetNoThrow(orig_left_bound_2d, left_offset); - const auto & expanded_right_bound_2d = offsetNoThrow(orig_right_bound_2d, right_offset); + auto expanded_left_bound_2d = offsetNoThrow(orig_left_bound_2d, left_offset); + auto expanded_right_bound_2d = offsetNoThrow(orig_right_bound_2d, right_offset); + + // Note: modify front and back points so that the successive lanelets will not have any + // longitudinal space between them. + { // front + const double diff_x = orig_right_bound_2d.front().x() - orig_left_bound_2d.front().x(); + const double diff_y = orig_right_bound_2d.front().y() - orig_left_bound_2d.front().y(); + const double theta = std::atan2(diff_y, diff_x); + expanded_right_bound_2d.front().x() = + orig_right_bound_2d.front().x() - right_offset * std::cos(theta); + expanded_right_bound_2d.front().y() = + orig_right_bound_2d.front().y() - right_offset * std::sin(theta); + expanded_left_bound_2d.front().x() = + orig_left_bound_2d.front().x() - left_offset * std::cos(theta); + expanded_left_bound_2d.front().y() = + orig_left_bound_2d.front().y() - left_offset * std::sin(theta); + } + { // back + const double diff_x = orig_right_bound_2d.back().x() - orig_left_bound_2d.back().x(); + const double diff_y = orig_right_bound_2d.back().y() - orig_left_bound_2d.back().y(); + const double theta = std::atan2(diff_y, diff_x); + expanded_right_bound_2d.back().x() = + orig_right_bound_2d.back().x() - right_offset * std::cos(theta); + expanded_right_bound_2d.back().y() = + orig_right_bound_2d.back().y() - right_offset * std::sin(theta); + expanded_left_bound_2d.back().x() = + orig_left_bound_2d.back().x() - left_offset * std::cos(theta); + expanded_left_bound_2d.back().y() = + orig_left_bound_2d.back().y() - left_offset * std::sin(theta); + } + rclcpp::Clock clock{RCL_ROS_TIME}; try { checkForInversion(orig_left_bound_2d, expanded_left_bound_2d, left_offset); diff --git a/planning/behavior_path_planner/src/utilities.cpp b/planning/behavior_path_planner/src/utilities.cpp index a2c3545d65c7..ca29304a65b2 100644 --- a/planning/behavior_path_planner/src/utilities.cpp +++ b/planning/behavior_path_planner/src/utilities.cpp @@ -1227,7 +1227,10 @@ OccupancyGrid generateDrivableArea( } // Closing - constexpr int num_iter = 10; // TODO(Horibe) Think later. + // NOTE: Because of the discretization error, there may be some discontinuity between two + // successive lanelets in the drivable area. This issue is dealt with by the erode/dilate + // process. + constexpr int num_iter = 1; cv::Mat cv_erode, cv_dilate; cv::erode(cv_image, cv_erode, cv::Mat(), cv::Point(-1, -1), num_iter); cv::dilate(cv_erode, cv_dilate, cv::Mat(), cv::Point(-1, -1), num_iter); From 56f83861c291b4cae0f56d65ce1d23e138aa1f91 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Wed, 18 May 2022 12:13:30 +0900 Subject: [PATCH 31/55] refactor(vehicle-cmd-gate): using namespace for msgs (#913) * refactor(vehicle-cmd-gate): using namespace for msgs Signed-off-by: Takamasa Horibe * for clang Signed-off-by: Takamasa Horibe --- control/vehicle_cmd_gate/CMakeLists.txt | 2 +- .../vehicle_cmd_gate/vehicle_cmd_gate.hpp | 160 +++++++------ .../vehicle_cmd_gate/src/vehicle_cmd_gate.cpp | 215 ++++++++---------- 3 files changed, 167 insertions(+), 210 deletions(-) diff --git a/control/vehicle_cmd_gate/CMakeLists.txt b/control/vehicle_cmd_gate/CMakeLists.txt index 309a296acc9d..a6f33e0591f4 100644 --- a/control/vehicle_cmd_gate/CMakeLists.txt +++ b/control/vehicle_cmd_gate/CMakeLists.txt @@ -10,7 +10,7 @@ ament_auto_add_library(vehicle_cmd_gate_node SHARED ) rclcpp_components_register_node(vehicle_cmd_gate_node - PLUGIN "VehicleCmdGate" + PLUGIN "vehicle_cmd_gate::VehicleCmdGate" EXECUTABLE vehicle_cmd_gate ) diff --git a/control/vehicle_cmd_gate/include/vehicle_cmd_gate/vehicle_cmd_gate.hpp b/control/vehicle_cmd_gate/include/vehicle_cmd_gate/vehicle_cmd_gate.hpp index a014b6d3f666..84c41475e00b 100644 --- a/control/vehicle_cmd_gate/include/vehicle_cmd_gate/vehicle_cmd_gate.hpp +++ b/control/vehicle_cmd_gate/include/vehicle_cmd_gate/vehicle_cmd_gate.hpp @@ -40,14 +40,34 @@ #include +namespace vehicle_cmd_gate +{ + +using autoware_auto_control_msgs::msg::AckermannControlCommand; +using autoware_auto_system_msgs::msg::EmergencyState; +using autoware_auto_vehicle_msgs::msg::GearCommand; +using autoware_auto_vehicle_msgs::msg::HazardLightsCommand; +using autoware_auto_vehicle_msgs::msg::SteeringReport; +using autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand; +using tier4_control_msgs::msg::GateMode; +using tier4_external_api_msgs::msg::Emergency; +using tier4_external_api_msgs::msg::Heartbeat; +using tier4_external_api_msgs::srv::SetEmergency; +using tier4_vehicle_msgs::msg::VehicleEmergencyStamped; + +using diagnostic_msgs::msg::DiagnosticStatus; +using nav_msgs::msg::Odometry; + +using EngageMsg = autoware_auto_vehicle_msgs::msg::Engage; +using EngageSrv = tier4_external_api_msgs::srv::Engage; + struct Commands { - autoware_auto_control_msgs::msg::AckermannControlCommand control; - autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand turn_indicator; - autoware_auto_vehicle_msgs::msg::HazardLightsCommand hazard_light; - autoware_auto_vehicle_msgs::msg::GearCommand gear; - explicit Commands( - const uint8_t & default_gear = autoware_auto_vehicle_msgs::msg::GearCommand::PARK) + AckermannControlCommand control; + TurnIndicatorsCommand turn_indicator; + HazardLightsCommand hazard_light; + GearCommand gear; + explicit Commands(const uint8_t & default_gear = GearCommand::PARK) { gear.command = default_gear; } @@ -55,43 +75,35 @@ struct Commands class VehicleCmdGate : public rclcpp::Node { - using VehicleEmergencyStamped = tier4_vehicle_msgs::msg::VehicleEmergencyStamped; - public: explicit VehicleCmdGate(const rclcpp::NodeOptions & node_options); private: // Publisher rclcpp::Publisher::SharedPtr vehicle_cmd_emergency_pub_; - rclcpp::Publisher::SharedPtr - control_cmd_pub_; - rclcpp::Publisher::SharedPtr gear_cmd_pub_; - rclcpp::Publisher::SharedPtr - turn_indicator_cmd_pub_; - rclcpp::Publisher::SharedPtr - hazard_light_cmd_pub_; - rclcpp::Publisher::SharedPtr gate_mode_pub_; - rclcpp::Publisher::SharedPtr engage_pub_; + rclcpp::Publisher::SharedPtr control_cmd_pub_; + rclcpp::Publisher::SharedPtr gear_cmd_pub_; + rclcpp::Publisher::SharedPtr turn_indicator_cmd_pub_; + rclcpp::Publisher::SharedPtr hazard_light_cmd_pub_; + rclcpp::Publisher::SharedPtr gate_mode_pub_; + rclcpp::Publisher::SharedPtr engage_pub_; // Subscription - rclcpp::Subscription::SharedPtr - emergency_state_sub_; - rclcpp::Subscription::SharedPtr - external_emergency_stop_heartbeat_sub_; - rclcpp::Subscription::SharedPtr gate_mode_sub_; - rclcpp::Subscription::SharedPtr steer_sub_; - - void onGateMode(tier4_control_msgs::msg::GateMode::ConstSharedPtr msg); - void onEmergencyState(autoware_auto_system_msgs::msg::EmergencyState::ConstSharedPtr msg); - void onExternalEmergencyStopHeartbeat( - tier4_external_api_msgs::msg::Heartbeat::ConstSharedPtr msg); - void onSteering(autoware_auto_vehicle_msgs::msg::SteeringReport::ConstSharedPtr msg); + rclcpp::Subscription::SharedPtr emergency_state_sub_; + rclcpp::Subscription::SharedPtr external_emergency_stop_heartbeat_sub_; + rclcpp::Subscription::SharedPtr gate_mode_sub_; + rclcpp::Subscription::SharedPtr steer_sub_; + + void onGateMode(GateMode::ConstSharedPtr msg); + void onEmergencyState(EmergencyState::ConstSharedPtr msg); + void onExternalEmergencyStopHeartbeat(Heartbeat::ConstSharedPtr msg); + void onSteering(SteeringReport::ConstSharedPtr msg); bool is_engaged_; bool is_system_emergency_ = false; bool is_external_emergency_stop_ = false; double current_steer_ = 0; - tier4_control_msgs::msg::GateMode current_gate_mode_; + GateMode current_gate_mode_; // Heartbeat std::shared_ptr emergency_state_heartbeat_received_time_; @@ -103,53 +115,35 @@ class VehicleCmdGate : public rclcpp::Node // Subscriber for auto Commands auto_commands_; - rclcpp::Subscription::SharedPtr - auto_control_cmd_sub_; - rclcpp::Subscription::SharedPtr - auto_turn_indicator_cmd_sub_; - rclcpp::Subscription::SharedPtr - auto_hazard_light_cmd_sub_; - rclcpp::Subscription::SharedPtr auto_gear_cmd_sub_; - void onAutoCtrlCmd(autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr msg); - void onAutoTurnIndicatorsCmd( - autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand::ConstSharedPtr msg); - void onAutoHazardLightsCmd( - autoware_auto_vehicle_msgs::msg::HazardLightsCommand::ConstSharedPtr msg); - void onAutoShiftCmd(autoware_auto_vehicle_msgs::msg::GearCommand::ConstSharedPtr msg); + rclcpp::Subscription::SharedPtr auto_control_cmd_sub_; + rclcpp::Subscription::SharedPtr auto_turn_indicator_cmd_sub_; + rclcpp::Subscription::SharedPtr auto_hazard_light_cmd_sub_; + rclcpp::Subscription::SharedPtr auto_gear_cmd_sub_; + void onAutoCtrlCmd(AckermannControlCommand::ConstSharedPtr msg); + void onAutoTurnIndicatorsCmd(TurnIndicatorsCommand::ConstSharedPtr msg); + void onAutoHazardLightsCmd(HazardLightsCommand::ConstSharedPtr msg); + void onAutoShiftCmd(GearCommand::ConstSharedPtr msg); // Subscription for external Commands remote_commands_; - rclcpp::Subscription::SharedPtr - remote_control_cmd_sub_; - rclcpp::Subscription::SharedPtr - remote_turn_indicator_cmd_sub_; - rclcpp::Subscription::SharedPtr - remote_hazard_light_cmd_sub_; - rclcpp::Subscription::SharedPtr - remote_gear_cmd_sub_; - void onRemoteCtrlCmd( - autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr msg); - void onRemoteTurnIndicatorsCmd( - autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand::ConstSharedPtr msg); - void onRemoteHazardLightsCmd( - autoware_auto_vehicle_msgs::msg::HazardLightsCommand::ConstSharedPtr msg); - void onRemoteShiftCmd(autoware_auto_vehicle_msgs::msg::GearCommand::ConstSharedPtr msg); + rclcpp::Subscription::SharedPtr remote_control_cmd_sub_; + rclcpp::Subscription::SharedPtr remote_turn_indicator_cmd_sub_; + rclcpp::Subscription::SharedPtr remote_hazard_light_cmd_sub_; + rclcpp::Subscription::SharedPtr remote_gear_cmd_sub_; + void onRemoteCtrlCmd(AckermannControlCommand::ConstSharedPtr msg); + void onRemoteTurnIndicatorsCmd(TurnIndicatorsCommand::ConstSharedPtr msg); + void onRemoteHazardLightsCmd(HazardLightsCommand::ConstSharedPtr msg); + void onRemoteShiftCmd(GearCommand::ConstSharedPtr msg); // Subscription for emergency Commands emergency_commands_; - rclcpp::Subscription::SharedPtr - emergency_control_cmd_sub_; - rclcpp::Subscription::SharedPtr - emergency_hazard_light_cmd_sub_; - rclcpp::Subscription::SharedPtr - emergency_gear_cmd_sub_; - void onEmergencyCtrlCmd( - autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr msg); - void onEmergencyTurnIndicatorsCmd( - autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand::ConstSharedPtr msg); - void onEmergencyHazardLightsCmd( - autoware_auto_vehicle_msgs::msg::HazardLightsCommand::ConstSharedPtr msg); - void onEmergencyShiftCmd(autoware_auto_vehicle_msgs::msg::GearCommand::ConstSharedPtr msg); + rclcpp::Subscription::SharedPtr emergency_control_cmd_sub_; + rclcpp::Subscription::SharedPtr emergency_hazard_light_cmd_sub_; + rclcpp::Subscription::SharedPtr emergency_gear_cmd_sub_; + void onEmergencyCtrlCmd(AckermannControlCommand::ConstSharedPtr msg); + void onEmergencyTurnIndicatorsCmd(TurnIndicatorsCommand::ConstSharedPtr msg); + void onEmergencyHazardLightsCmd(HazardLightsCommand::ConstSharedPtr msg); + void onEmergencyShiftCmd(GearCommand::ConstSharedPtr msg); // Parameter double update_period_; @@ -163,7 +157,7 @@ class VehicleCmdGate : public rclcpp::Node // Service rclcpp::Service::SharedPtr srv_engage_; rclcpp::Service::SharedPtr srv_external_emergency_; - rclcpp::Publisher::SharedPtr pub_external_emergency_; + rclcpp::Publisher::SharedPtr pub_external_emergency_; void onEngageService( const tier4_external_api_msgs::srv::Engage::Request::SharedPtr request, const tier4_external_api_msgs::srv::Engage::Response::SharedPtr response); @@ -173,10 +167,10 @@ class VehicleCmdGate : public rclcpp::Node const std::shared_ptr response); // TODO(Takagi, Isamu): deprecated - rclcpp::Subscription::SharedPtr engage_sub_; + rclcpp::Subscription::SharedPtr engage_sub_; rclcpp::Service::SharedPtr srv_external_emergency_stop_; rclcpp::Service::SharedPtr srv_clear_external_emergency_stop_; - void onEngage(autoware_auto_vehicle_msgs::msg::Engage::ConstSharedPtr msg); + void onEngage(EngageMsg::ConstSharedPtr msg); bool onSetExternalEmergencyStopService( const std::shared_ptr req_header, const std::shared_ptr req, @@ -199,23 +193,22 @@ class VehicleCmdGate : public rclcpp::Node void checkExternalEmergencyStop(diagnostic_updater::DiagnosticStatusWrapper & stat); // Algorithm - autoware_auto_control_msgs::msg::AckermannControlCommand prev_control_cmd_; - autoware_auto_control_msgs::msg::AckermannControlCommand createStopControlCmd() const; - autoware_auto_control_msgs::msg::AckermannControlCommand createEmergencyStopControlCmd() const; + AckermannControlCommand prev_control_cmd_; + AckermannControlCommand createStopControlCmd() const; + AckermannControlCommand createEmergencyStopControlCmd() const; std::shared_ptr prev_time_; double getDt(); VehicleCmdFilter filter_; - autoware_auto_control_msgs::msg::AckermannControlCommand filterControlCommand( - const autoware_auto_control_msgs::msg::AckermannControlCommand & msg); + AckermannControlCommand filterControlCommand(const AckermannControlCommand & msg); // Start request service struct StartRequest { private: static constexpr double eps = 1e-3; - using ControlCommandStamped = autoware_auto_control_msgs::msg::AckermannControlCommand; + using ControlCommandStamped = AckermannControlCommand; public: StartRequest( @@ -230,7 +223,7 @@ class VehicleCmdGate : public rclcpp::Node bool is_start_requesting_; bool is_start_accepted_; bool is_start_cancelled_; - nav_msgs::msg::Odometry current_twist_; + Odometry current_twist_; std::shared_ptr last_running_time_; double stopped_state_entry_duration_time_; @@ -238,11 +231,12 @@ class VehicleCmdGate : public rclcpp::Node rclcpp::Node * node_; rclcpp::Client::SharedPtr request_start_cli_; rclcpp::Publisher::SharedPtr request_start_pub_; - rclcpp::Subscription::SharedPtr current_twist_sub_; - void onCurrentTwist(nav_msgs::msg::Odometry::ConstSharedPtr msg); + rclcpp::Subscription::SharedPtr current_twist_sub_; + void onCurrentTwist(Odometry::ConstSharedPtr msg); }; std::unique_ptr start_request_; }; +} // namespace vehicle_cmd_gate #endif // VEHICLE_CMD_GATE__VEHICLE_CMD_GATE_HPP_ diff --git a/control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp b/control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp index 9bd4bc94efcf..622a5c694591 100644 --- a/control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp +++ b/control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp @@ -23,12 +23,13 @@ #include #include +namespace vehicle_cmd_gate +{ + namespace { -const char * getGateModeName(const tier4_control_msgs::msg::GateMode::_data_type & gate_mode) +const char * getGateModeName(const GateMode::_data_type & gate_mode) { - using tier4_control_msgs::msg::GateMode; - if (gate_mode == GateMode::AUTO) { return "AUTO"; } @@ -54,85 +55,69 @@ VehicleCmdGate::VehicleCmdGate(const rclcpp::NodeOptions & node_options) vehicle_cmd_emergency_pub_ = this->create_publisher("output/vehicle_cmd_emergency", durable_qos); control_cmd_pub_ = - this->create_publisher( - "output/control_cmd", durable_qos); - gear_cmd_pub_ = this->create_publisher( - "output/gear_cmd", durable_qos); + this->create_publisher("output/control_cmd", durable_qos); + gear_cmd_pub_ = this->create_publisher("output/gear_cmd", durable_qos); turn_indicator_cmd_pub_ = - this->create_publisher( - "output/turn_indicators_cmd", durable_qos); + this->create_publisher("output/turn_indicators_cmd", durable_qos); hazard_light_cmd_pub_ = - this->create_publisher( - "output/hazard_lights_cmd", durable_qos); + this->create_publisher("output/hazard_lights_cmd", durable_qos); - gate_mode_pub_ = - this->create_publisher("output/gate_mode", durable_qos); - engage_pub_ = - this->create_publisher("output/engage", durable_qos); - pub_external_emergency_ = this->create_publisher( - "output/external_emergency", durable_qos); + gate_mode_pub_ = this->create_publisher("output/gate_mode", durable_qos); + engage_pub_ = this->create_publisher("output/engage", durable_qos); + pub_external_emergency_ = + this->create_publisher("output/external_emergency", durable_qos); // Subscriber - emergency_state_sub_ = this->create_subscription( + emergency_state_sub_ = this->create_subscription( "input/emergency_state", 1, std::bind(&VehicleCmdGate::onEmergencyState, this, _1)); - external_emergency_stop_heartbeat_sub_ = - this->create_subscription( - "input/external_emergency_stop_heartbeat", 1, - std::bind(&VehicleCmdGate::onExternalEmergencyStopHeartbeat, this, _1)); - gate_mode_sub_ = this->create_subscription( + external_emergency_stop_heartbeat_sub_ = this->create_subscription( + "input/external_emergency_stop_heartbeat", 1, + std::bind(&VehicleCmdGate::onExternalEmergencyStopHeartbeat, this, _1)); + gate_mode_sub_ = this->create_subscription( "input/gate_mode", 1, std::bind(&VehicleCmdGate::onGateMode, this, _1)); - engage_sub_ = this->create_subscription( + engage_sub_ = this->create_subscription( "input/engage", 1, std::bind(&VehicleCmdGate::onEngage, this, _1)); - steer_sub_ = this->create_subscription( + steer_sub_ = this->create_subscription( "input/steering", 1, std::bind(&VehicleCmdGate::onSteering, this, _1)); // Subscriber for auto - auto_control_cmd_sub_ = - this->create_subscription( - "input/auto/control_cmd", 1, std::bind(&VehicleCmdGate::onAutoCtrlCmd, this, _1)); + auto_control_cmd_sub_ = this->create_subscription( + "input/auto/control_cmd", 1, std::bind(&VehicleCmdGate::onAutoCtrlCmd, this, _1)); - auto_turn_indicator_cmd_sub_ = - this->create_subscription( - "input/auto/turn_indicators_cmd", 1, - std::bind(&VehicleCmdGate::onAutoTurnIndicatorsCmd, this, _1)); + auto_turn_indicator_cmd_sub_ = this->create_subscription( + "input/auto/turn_indicators_cmd", 1, + std::bind(&VehicleCmdGate::onAutoTurnIndicatorsCmd, this, _1)); - auto_hazard_light_cmd_sub_ = - this->create_subscription( - "input/auto/hazard_lights_cmd", 1, - std::bind(&VehicleCmdGate::onAutoHazardLightsCmd, this, _1)); + auto_hazard_light_cmd_sub_ = this->create_subscription( + "input/auto/hazard_lights_cmd", 1, std::bind(&VehicleCmdGate::onAutoHazardLightsCmd, this, _1)); - auto_gear_cmd_sub_ = this->create_subscription( + auto_gear_cmd_sub_ = this->create_subscription( "input/auto/gear_cmd", 1, std::bind(&VehicleCmdGate::onAutoShiftCmd, this, _1)); // Subscriber for external - remote_control_cmd_sub_ = - this->create_subscription( - "input/external/control_cmd", 1, std::bind(&VehicleCmdGate::onRemoteCtrlCmd, this, _1)); + remote_control_cmd_sub_ = this->create_subscription( + "input/external/control_cmd", 1, std::bind(&VehicleCmdGate::onRemoteCtrlCmd, this, _1)); - remote_turn_indicator_cmd_sub_ = - this->create_subscription( - "input/external/turn_indicators_cmd", 1, - std::bind(&VehicleCmdGate::onRemoteTurnIndicatorsCmd, this, _1)); + remote_turn_indicator_cmd_sub_ = this->create_subscription( + "input/external/turn_indicators_cmd", 1, + std::bind(&VehicleCmdGate::onRemoteTurnIndicatorsCmd, this, _1)); - remote_hazard_light_cmd_sub_ = - this->create_subscription( - "input/external/hazard_lights_cmd", 1, - std::bind(&VehicleCmdGate::onRemoteHazardLightsCmd, this, _1)); + remote_hazard_light_cmd_sub_ = this->create_subscription( + "input/external/hazard_lights_cmd", 1, + std::bind(&VehicleCmdGate::onRemoteHazardLightsCmd, this, _1)); - remote_gear_cmd_sub_ = this->create_subscription( + remote_gear_cmd_sub_ = this->create_subscription( "input/external/gear_cmd", 1, std::bind(&VehicleCmdGate::onRemoteShiftCmd, this, _1)); // Subscriber for emergency - emergency_control_cmd_sub_ = - this->create_subscription( - "input/emergency/control_cmd", 1, std::bind(&VehicleCmdGate::onEmergencyCtrlCmd, this, _1)); + emergency_control_cmd_sub_ = this->create_subscription( + "input/emergency/control_cmd", 1, std::bind(&VehicleCmdGate::onEmergencyCtrlCmd, this, _1)); - emergency_hazard_light_cmd_sub_ = - this->create_subscription( - "input/emergency/hazard_lights_cmd", 1, - std::bind(&VehicleCmdGate::onEmergencyHazardLightsCmd, this, _1)); + emergency_hazard_light_cmd_sub_ = this->create_subscription( + "input/emergency/hazard_lights_cmd", 1, + std::bind(&VehicleCmdGate::onEmergencyHazardLightsCmd, this, _1)); - emergency_gear_cmd_sub_ = this->create_subscription( + emergency_gear_cmd_sub_ = this->create_subscription( "input/emergency/gear_cmd", 1, std::bind(&VehicleCmdGate::onEmergencyShiftCmd, this, _1)); // Parameter @@ -162,7 +147,7 @@ VehicleCmdGate::VehicleCmdGate(const rclcpp::NodeOptions & node_options) filter_.setLatJerkLim(lat_jerk_lim); // Set default value - current_gate_mode_.data = tier4_control_msgs::msg::GateMode::AUTO; + current_gate_mode_.data = GateMode::AUTO; // Service srv_engage_ = create_service( @@ -215,66 +200,54 @@ bool VehicleCmdGate::isHeartbeatTimeout( } // for auto -void VehicleCmdGate::onAutoCtrlCmd( - autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr msg) +void VehicleCmdGate::onAutoCtrlCmd(AckermannControlCommand::ConstSharedPtr msg) { auto_commands_.control = *msg; - if (current_gate_mode_.data == tier4_control_msgs::msg::GateMode::AUTO) { + if (current_gate_mode_.data == GateMode::AUTO) { publishControlCommands(auto_commands_); } } -void VehicleCmdGate::onAutoTurnIndicatorsCmd( - autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand::ConstSharedPtr msg) +void VehicleCmdGate::onAutoTurnIndicatorsCmd(TurnIndicatorsCommand::ConstSharedPtr msg) { auto_commands_.turn_indicator = *msg; } -void VehicleCmdGate::onAutoHazardLightsCmd( - autoware_auto_vehicle_msgs::msg::HazardLightsCommand::ConstSharedPtr msg) +void VehicleCmdGate::onAutoHazardLightsCmd(HazardLightsCommand::ConstSharedPtr msg) { auto_commands_.hazard_light = *msg; } -void VehicleCmdGate::onAutoShiftCmd( - autoware_auto_vehicle_msgs::msg::GearCommand::ConstSharedPtr msg) -{ - auto_commands_.gear = *msg; -} +void VehicleCmdGate::onAutoShiftCmd(GearCommand::ConstSharedPtr msg) { auto_commands_.gear = *msg; } // for remote -void VehicleCmdGate::onRemoteCtrlCmd( - autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr msg) +void VehicleCmdGate::onRemoteCtrlCmd(AckermannControlCommand::ConstSharedPtr msg) { remote_commands_.control = *msg; - if (current_gate_mode_.data == tier4_control_msgs::msg::GateMode::EXTERNAL) { + if (current_gate_mode_.data == GateMode::EXTERNAL) { publishControlCommands(remote_commands_); } } -void VehicleCmdGate::onRemoteTurnIndicatorsCmd( - autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand::ConstSharedPtr msg) +void VehicleCmdGate::onRemoteTurnIndicatorsCmd(TurnIndicatorsCommand::ConstSharedPtr msg) { remote_commands_.turn_indicator = *msg; } -void VehicleCmdGate::onRemoteHazardLightsCmd( - autoware_auto_vehicle_msgs::msg::HazardLightsCommand::ConstSharedPtr msg) +void VehicleCmdGate::onRemoteHazardLightsCmd(HazardLightsCommand::ConstSharedPtr msg) { remote_commands_.hazard_light = *msg; } -void VehicleCmdGate::onRemoteShiftCmd( - autoware_auto_vehicle_msgs::msg::GearCommand::ConstSharedPtr msg) +void VehicleCmdGate::onRemoteShiftCmd(GearCommand::ConstSharedPtr msg) { remote_commands_.gear = *msg; } // for emergency -void VehicleCmdGate::onEmergencyCtrlCmd( - autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr msg) +void VehicleCmdGate::onEmergencyCtrlCmd(AckermannControlCommand::ConstSharedPtr msg) { emergency_commands_.control = *msg; @@ -282,13 +255,11 @@ void VehicleCmdGate::onEmergencyCtrlCmd( publishControlCommands(emergency_commands_); } } -void VehicleCmdGate::onEmergencyHazardLightsCmd( - autoware_auto_vehicle_msgs::msg::HazardLightsCommand::ConstSharedPtr msg) +void VehicleCmdGate::onEmergencyHazardLightsCmd(HazardLightsCommand::ConstSharedPtr msg) { emergency_commands_.hazard_light = *msg; } -void VehicleCmdGate::onEmergencyShiftCmd( - autoware_auto_vehicle_msgs::msg::GearCommand::ConstSharedPtr msg) +void VehicleCmdGate::onEmergencyShiftCmd(GearCommand::ConstSharedPtr msg) { emergency_commands_.gear = *msg; } @@ -335,25 +306,25 @@ void VehicleCmdGate::onTimer() } // Select commands - autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand turn_indicator; - autoware_auto_vehicle_msgs::msg::HazardLightsCommand hazard_light; - autoware_auto_vehicle_msgs::msg::GearCommand gear; + TurnIndicatorsCommand turn_indicator; + HazardLightsCommand hazard_light; + GearCommand gear; if (use_emergency_handling_ && is_system_emergency_) { turn_indicator = emergency_commands_.turn_indicator; hazard_light = emergency_commands_.hazard_light; gear = emergency_commands_.gear; } else { - if (current_gate_mode_.data == tier4_control_msgs::msg::GateMode::AUTO) { + if (current_gate_mode_.data == GateMode::AUTO) { turn_indicator = auto_commands_.turn_indicator; hazard_light = auto_commands_.hazard_light; gear = auto_commands_.gear; // Don't send turn signal when autoware is not engaged if (!is_engaged_) { - turn_indicator.command = autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand::NO_COMMAND; - hazard_light.command = autoware_auto_vehicle_msgs::msg::HazardLightsCommand::NO_COMMAND; + turn_indicator.command = TurnIndicatorsCommand::NO_COMMAND; + hazard_light.command = HazardLightsCommand::NO_COMMAND; } - } else if (current_gate_mode_.data == tier4_control_msgs::msg::GateMode::EXTERNAL) { + } else if (current_gate_mode_.data == GateMode::EXTERNAL) { turn_indicator = remote_commands_.turn_indicator; hazard_light = remote_commands_.hazard_light; gear = remote_commands_.gear; @@ -363,12 +334,12 @@ void VehicleCmdGate::onTimer() } // Engage - autoware_auto_vehicle_msgs::msg::Engage autoware_engage; + EngageMsg autoware_engage; autoware_engage.stamp = this->now(); autoware_engage.engage = is_engaged_; // External emergency - tier4_external_api_msgs::msg::Emergency external_emergency; + Emergency external_emergency; external_emergency.stamp = this->now(); external_emergency.emergency = is_external_emergency_stop_; @@ -446,7 +417,7 @@ void VehicleCmdGate::publishEmergencyStopControlCommands() const auto stamp = this->now(); // ControlCommand - autoware_auto_control_msgs::msg::AckermannControlCommand control_cmd; + AckermannControlCommand control_cmd; control_cmd.stamp = stamp; control_cmd = createEmergencyStopControlCmd(); @@ -454,19 +425,19 @@ void VehicleCmdGate::publishEmergencyStopControlCommands() start_request_->checkStopped(control_cmd); // gear - autoware_auto_vehicle_msgs::msg::GearCommand gear; + GearCommand gear; gear.stamp = stamp; // default value is 0 // TurnSignal - autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand turn_indicator; + TurnIndicatorsCommand turn_indicator; turn_indicator.stamp = stamp; - turn_indicator.command = autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand::NO_COMMAND; + turn_indicator.command = TurnIndicatorsCommand::NO_COMMAND; // Hazard - autoware_auto_vehicle_msgs::msg::HazardLightsCommand hazard_light; + HazardLightsCommand hazard_light; hazard_light.stamp = stamp; - hazard_light.command = autoware_auto_vehicle_msgs::msg::HazardLightsCommand::ENABLE; + hazard_light.command = HazardLightsCommand::ENABLE; // VehicleCommand emergency; VehicleEmergencyStamped vehicle_cmd_emergency; @@ -474,12 +445,12 @@ void VehicleCmdGate::publishEmergencyStopControlCommands() vehicle_cmd_emergency.emergency = true; // Engage - autoware_auto_vehicle_msgs::msg::Engage autoware_engage; + EngageMsg autoware_engage; autoware_engage.stamp = stamp; autoware_engage.engage = is_engaged_; // External emergency - tier4_external_api_msgs::msg::Emergency external_emergency; + Emergency external_emergency; external_emergency.stamp = stamp; external_emergency.emergency = is_external_emergency_stop_; @@ -497,10 +468,9 @@ void VehicleCmdGate::publishEmergencyStopControlCommands() start_request_->publishStartAccepted(); } -autoware_auto_control_msgs::msg::AckermannControlCommand VehicleCmdGate::filterControlCommand( - const autoware_auto_control_msgs::msg::AckermannControlCommand & in) +AckermannControlCommand VehicleCmdGate::filterControlCommand(const AckermannControlCommand & in) { - autoware_auto_control_msgs::msg::AckermannControlCommand out = in; + AckermannControlCommand out = in; const double dt = getDt(); filter_.limitLongitudinalWithVel(out); @@ -513,10 +483,9 @@ autoware_auto_control_msgs::msg::AckermannControlCommand VehicleCmdGate::filterC return out; } -autoware_auto_control_msgs::msg::AckermannControlCommand VehicleCmdGate::createStopControlCmd() - const +AckermannControlCommand VehicleCmdGate::createStopControlCmd() const { - autoware_auto_control_msgs::msg::AckermannControlCommand cmd; + AckermannControlCommand cmd; const auto t = this->now(); cmd.stamp = t; cmd.lateral.stamp = t; @@ -529,10 +498,9 @@ autoware_auto_control_msgs::msg::AckermannControlCommand VehicleCmdGate::createS return cmd; } -autoware_auto_control_msgs::msg::AckermannControlCommand -VehicleCmdGate::createEmergencyStopControlCmd() const +AckermannControlCommand VehicleCmdGate::createEmergencyStopControlCmd() const { - autoware_auto_control_msgs::msg::AckermannControlCommand cmd; + AckermannControlCommand cmd; const auto t = this->now(); cmd.stamp = t; cmd.lateral.stamp = t; @@ -545,10 +513,8 @@ VehicleCmdGate::createEmergencyStopControlCmd() const return cmd; } -void VehicleCmdGate::onEmergencyState( - autoware_auto_system_msgs::msg::EmergencyState::ConstSharedPtr msg) +void VehicleCmdGate::onEmergencyState(EmergencyState::ConstSharedPtr msg) { - using autoware_auto_system_msgs::msg::EmergencyState; is_system_emergency_ = (msg->state == EmergencyState::MRM_OPERATING) || (msg->state == EmergencyState::MRM_SUCCEEDED) || (msg->state == EmergencyState::MRM_FAILED); @@ -556,12 +522,12 @@ void VehicleCmdGate::onEmergencyState( } void VehicleCmdGate::onExternalEmergencyStopHeartbeat( - [[maybe_unused]] tier4_external_api_msgs::msg::Heartbeat::ConstSharedPtr msg) + [[maybe_unused]] Heartbeat::ConstSharedPtr msg) { external_emergency_stop_heartbeat_received_time_ = std::make_shared(this->now()); } -void VehicleCmdGate::onGateMode(tier4_control_msgs::msg::GateMode::ConstSharedPtr msg) +void VehicleCmdGate::onGateMode(GateMode::ConstSharedPtr msg) { const auto prev_gate_mode = current_gate_mode_; current_gate_mode_ = *msg; @@ -573,10 +539,7 @@ void VehicleCmdGate::onGateMode(tier4_control_msgs::msg::GateMode::ConstSharedPt } } -void VehicleCmdGate::onEngage(autoware_auto_vehicle_msgs::msg::Engage::ConstSharedPtr msg) -{ - is_engaged_ = msg->engage; -} +void VehicleCmdGate::onEngage(EngageMsg::ConstSharedPtr msg) { is_engaged_ = msg->engage; } void VehicleCmdGate::onEngageService( const tier4_external_api_msgs::srv::Engage::Request::SharedPtr request, @@ -586,7 +549,7 @@ void VehicleCmdGate::onEngageService( response->status = tier4_api_utils::response_success(); } -void VehicleCmdGate::onSteering(autoware_auto_vehicle_msgs::msg::SteeringReport::ConstSharedPtr msg) +void VehicleCmdGate::onSteering(SteeringReport::ConstSharedPtr msg) { current_steer_ = msg->steering_tire_angle; } @@ -661,8 +624,6 @@ bool VehicleCmdGate::onClearExternalEmergencyStopService( void VehicleCmdGate::checkExternalEmergencyStop(diagnostic_updater::DiagnosticStatusWrapper & stat) { - using diagnostic_msgs::msg::DiagnosticStatus; - DiagnosticStatus status; if (is_external_emergency_stop_heartbeat_timeout_) { status.level = DiagnosticStatus::ERROR; @@ -698,7 +659,7 @@ VehicleCmdGate::StartRequest::StartRequest( node_->create_client("/api/autoware/set/start_request"); request_start_pub_ = node_->create_publisher( "/api/autoware/get/start_accepted", rclcpp::QoS(1)); - current_twist_sub_ = node_->create_subscription( + current_twist_sub_ = node_->create_subscription( "/localization/kinematic_state", rclcpp::QoS(1), std::bind(&VehicleCmdGate::StartRequest::onCurrentTwist, this, _1)); @@ -706,7 +667,7 @@ VehicleCmdGate::StartRequest::StartRequest( stopped_state_entry_duration_time_ = stopped_state_entry_duration_time; } -void VehicleCmdGate::StartRequest::onCurrentTwist(nav_msgs::msg::Odometry::ConstSharedPtr msg) +void VehicleCmdGate::StartRequest::onCurrentTwist(Odometry::ConstSharedPtr msg) { current_twist_ = *msg; } @@ -781,5 +742,7 @@ void VehicleCmdGate::StartRequest::checkStartRequest(const ControlCommandStamped } } +} // namespace vehicle_cmd_gate + #include -RCLCPP_COMPONENTS_REGISTER_NODE(VehicleCmdGate) +RCLCPP_COMPONENTS_REGISTER_NODE(vehicle_cmd_gate::VehicleCmdGate) From 1cb3f3cd00da2520b812660569152154b387c686 Mon Sep 17 00:00:00 2001 From: Takeshi Ishita Date: Wed, 18 May 2022 13:25:26 +0900 Subject: [PATCH 32/55] feat(pose_initializer): introduce an array copy function (#900) Signed-off-by: IshitaTakeshi Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- localization/pose_initializer/CMakeLists.txt | 21 +++++++- .../pose_initializer/copy_vector_to_array.hpp | 37 ++++++++++++++ localization/pose_initializer/package.xml | 2 + .../src/pose_initializer_core.cpp | 26 ++++------ .../test/test_copy_vector_to_array.cpp | 50 +++++++++++++++++++ 5 files changed, 119 insertions(+), 17 deletions(-) create mode 100644 localization/pose_initializer/include/pose_initializer/copy_vector_to_array.hpp create mode 100644 localization/pose_initializer/test/test_copy_vector_to_array.cpp diff --git a/localization/pose_initializer/CMakeLists.txt b/localization/pose_initializer/CMakeLists.txt index e078e40852a2..32a1525463ea 100644 --- a/localization/pose_initializer/CMakeLists.txt +++ b/localization/pose_initializer/CMakeLists.txt @@ -10,7 +10,26 @@ ament_auto_add_executable(pose_initializer src/pose_initializer_node.cpp src/pose_initializer_core.cpp ) -target_link_libraries(pose_initializer ${PCL_LIBRARIES}) + +# fmt often fails to automatically link so manually specify here +target_link_libraries(pose_initializer ${PCL_LIBRARIES} fmt) + +if(BUILD_TESTING) + function(add_testcase filepath) + get_filename_component(filename ${filepath} NAME) + string(REGEX REPLACE ".cpp" "" test_name ${filename}) + + ament_add_gmock(${test_name} ${filepath}) + target_include_directories(${test_name} PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}/include) + target_link_libraries(${test_name} fmt) + ament_target_dependencies(${test_name} ${${PROJECT_NAME}_FOUND_BUILD_DEPENDS}) + endfunction() + + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() + + add_testcase(test/test_copy_vector_to_array.cpp) +endif() ament_auto_package(INSTALL_TO_SHARE launch diff --git a/localization/pose_initializer/include/pose_initializer/copy_vector_to_array.hpp b/localization/pose_initializer/include/pose_initializer/copy_vector_to_array.hpp new file mode 100644 index 000000000000..2b8b31e3bc65 --- /dev/null +++ b/localization/pose_initializer/include/pose_initializer/copy_vector_to_array.hpp @@ -0,0 +1,37 @@ +// Copyright 2022 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef POSE_INITIALIZER__COPY_VECTOR_TO_ARRAY_HPP_ +#define POSE_INITIALIZER__COPY_VECTOR_TO_ARRAY_HPP_ + +#include + +#include +#include +#include + +template +void CopyVectorToArray(const std::vector & vector, std::array & array) +{ + if (N != vector.size()) { + // throws the error to prevent causing an anonymous bug + // such as only partial array is initialized + throw std::invalid_argument(fmt::format( + "Vector size (which is {}) is different from the copy size (which is {})", vector.size(), N)); + } + + std::copy_n(vector.begin(), N, array.begin()); +} + +#endif // POSE_INITIALIZER__COPY_VECTOR_TO_ARRAY_HPP_ diff --git a/localization/pose_initializer/package.xml b/localization/pose_initializer/package.xml index 88d184b50480..75712bd03233 100644 --- a/localization/pose_initializer/package.xml +++ b/localization/pose_initializer/package.xml @@ -11,6 +11,7 @@ autoware_cmake + fmt geometry_msgs libpcl-all-dev pcl_conversions @@ -25,6 +26,7 @@ tier4_localization_msgs ament_cmake_cppcheck + ament_cmake_gmock ament_lint_auto autoware_lint_common diff --git a/localization/pose_initializer/src/pose_initializer_core.cpp b/localization/pose_initializer/src/pose_initializer_core.cpp index b8965c262c16..cc6e7b86450c 100644 --- a/localization/pose_initializer/src/pose_initializer_core.cpp +++ b/localization/pose_initializer/src/pose_initializer_core.cpp @@ -14,6 +14,8 @@ #include "pose_initializer/pose_initializer_core.hpp" +#include "pose_initializer/copy_vector_to_array.hpp" + #include #ifdef ROS_DISTRO_GALACTIC #include @@ -50,29 +52,21 @@ PoseInitializer::PoseInitializer() { enable_gnss_callback_ = this->declare_parameter("enable_gnss_callback", true); - std::vector initialpose_particle_covariance = + const std::vector initialpose_particle_covariance = this->declare_parameter>("initialpose_particle_covariance"); - for (std::size_t i = 0; i < initialpose_particle_covariance.size(); ++i) { - initialpose_particle_covariance_[i] = initialpose_particle_covariance[i]; - } + CopyVectorToArray(initialpose_particle_covariance, initialpose_particle_covariance_); - std::vector gnss_particle_covariance = + const std::vector gnss_particle_covariance = this->declare_parameter>("gnss_particle_covariance"); - for (std::size_t i = 0; i < gnss_particle_covariance.size(); ++i) { - gnss_particle_covariance_[i] = gnss_particle_covariance[i]; - } + CopyVectorToArray(gnss_particle_covariance, gnss_particle_covariance_); - std::vector service_particle_covariance = + const std::vector service_particle_covariance = this->declare_parameter>("service_particle_covariance"); - for (std::size_t i = 0; i < service_particle_covariance.size(); ++i) { - service_particle_covariance_[i] = service_particle_covariance[i]; - } + CopyVectorToArray(service_particle_covariance, service_particle_covariance_); - std::vector output_pose_covariance = + const std::vector output_pose_covariance = this->declare_parameter>("output_pose_covariance"); - for (std::size_t i = 0; i < output_pose_covariance.size(); ++i) { - output_pose_covariance_[i] = output_pose_covariance[i]; - } + CopyVectorToArray(output_pose_covariance, output_pose_covariance_); // We can't use _1 because pcl leaks an alias to boost::placeholders::_1, so it would be ambiguous initial_pose_sub_ = this->create_subscription( diff --git a/localization/pose_initializer/test/test_copy_vector_to_array.cpp b/localization/pose_initializer/test/test_copy_vector_to_array.cpp new file mode 100644 index 000000000000..aa0dd87bc82f --- /dev/null +++ b/localization/pose_initializer/test/test_copy_vector_to_array.cpp @@ -0,0 +1,50 @@ +// Copyright 2022 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "pose_initializer/copy_vector_to_array.hpp" + +#include + +TEST(CopyVectorToArray, CopyAllElements) +{ + const std::vector vector{0, 1, 2, 3, 4}; + std::array array; + CopyVectorToArray(vector, array); + EXPECT_THAT(array, testing::ElementsAre(0, 1, 2, 3, 4)); +} + +TEST(CopyVectorToArray, CopyZeroElements) +{ + const std::vector vector{}; + // just confirm that this works + std::array array; + CopyVectorToArray(vector, array); +} + +TEST(CopyVectorToArray, ThrowsInvalidArgumentIfMoreElementsExpected) +{ + auto f = [] { + const std::vector vector{0, 1, 2, 3, 4}; + std::array array; + CopyVectorToArray(vector, array); + }; + + EXPECT_THROW( + try { f(); } catch (std::exception & e) { + EXPECT_STREQ( + e.what(), "Vector size (which is 5) is different from the copy size (which is 6)"); + throw; + }, + std::invalid_argument); +} From 0707207198a22bc27f4976375721ca19b5958102 Mon Sep 17 00:00:00 2001 From: storrrrrrrrm <103425473+storrrrrrrrm@users.noreply.github.com> Date: Wed, 18 May 2022 14:23:06 +0800 Subject: [PATCH 33/55] feat: add lidar point filter when debug (#865) * feat: add lidar point filter when debug Signed-off-by: suchang * ci(pre-commit): autofix Co-authored-by: suchang Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../debugger.hpp | 1 + .../fusion_node.hpp | 10 ++++- .../roi_cluster_fusion/node.hpp | 5 ++- .../roi_detected_object_fusion/node.hpp | 4 +- .../launch/roi_cluster_fusion.launch.xml | 12 ++++++ .../src/fusion_node.cpp | 37 ++++++++++++------- .../src/roi_cluster_fusion/node.cpp | 37 ++++++++++++++++++- .../src/roi_detected_object_fusion/node.cpp | 31 +++++++++++++++- 8 files changed, 118 insertions(+), 19 deletions(-) diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/debugger.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/debugger.hpp index 9ecd336818b5..37a0925fb550 100644 --- a/perception/image_projection_based_fusion/include/image_projection_based_fusion/debugger.hpp +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/debugger.hpp @@ -58,6 +58,7 @@ class Debugger std::vector image_subs_; std::vector image_pubs_; std::vector> image_buffers_; + std::size_t image_buffer_size_; }; diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/fusion_node.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/fusion_node.hpp index 19093b410c85..4921c36f3f4f 100644 --- a/perception/image_projection_based_fusion/include/image_projection_based_fusion/fusion_node.hpp +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/fusion_node.hpp @@ -20,6 +20,7 @@ #include #include +#include #include #include @@ -41,7 +42,7 @@ using autoware_auto_perception_msgs::msg::DetectedObjects; using tier4_perception_msgs::msg::DetectedObjectsWithFeature; using tier4_perception_msgs::msg::DetectedObjectWithFeature; -template +template class FusionNode : public rclcpp::Node { public: @@ -103,6 +104,13 @@ class FusionNode : public rclcpp::Node // debugger std::shared_ptr debugger_; + virtual bool out_of_scope(const ObjType & obj) = 0; + float filter_scope_minx_; + float filter_scope_maxx_; + float filter_scope_miny_; + float filter_scope_maxy_; + float filter_scope_minz_; + float filter_scope_maxz_; }; } // namespace image_projection_based_fusion diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_cluster_fusion/node.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_cluster_fusion/node.hpp index 656b2cfc7337..8832e5ee1a52 100644 --- a/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_cluster_fusion/node.hpp +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_cluster_fusion/node.hpp @@ -22,7 +22,8 @@ namespace image_projection_based_fusion { -class RoiClusterFusionNode : public FusionNode +class RoiClusterFusionNode +: public FusionNode { public: explicit RoiClusterFusionNode(const rclcpp::NodeOptions & options); @@ -41,6 +42,8 @@ class RoiClusterFusionNode : public FusionNode bool use_iou_{false}; bool use_cluster_semantic_type_{false}; float iou_threshold_{0.0f}; + + bool out_of_scope(const DetectedObjectWithFeature & obj); }; } // namespace image_projection_based_fusion diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_detected_object_fusion/node.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_detected_object_fusion/node.hpp index 2e32ec87e77e..a252f4d02bbd 100644 --- a/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_detected_object_fusion/node.hpp +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_detected_object_fusion/node.hpp @@ -24,7 +24,7 @@ namespace image_projection_based_fusion { -class RoiDetectedObjectFusionNode : public FusionNode +class RoiDetectedObjectFusionNode : public FusionNode { public: explicit RoiDetectedObjectFusionNode(const rclcpp::NodeOptions & options); @@ -50,6 +50,8 @@ class RoiDetectedObjectFusionNode : public FusionNode bool use_iou_x_{false}; bool use_iou_y_{false}; float iou_threshold_{0.0f}; + + bool out_of_scope(const DetectedObject & obj); }; } // namespace image_projection_based_fusion diff --git a/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml b/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml index e5824dfcff97..0dacf794b8e2 100644 --- a/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml @@ -24,6 +24,12 @@ + + + + + + @@ -71,6 +77,12 @@ + + + + + + diff --git a/perception/image_projection_based_fusion/src/fusion_node.cpp b/perception/image_projection_based_fusion/src/fusion_node.cpp index 5d33303ca1bf..05b061cede99 100644 --- a/perception/image_projection_based_fusion/src/fusion_node.cpp +++ b/perception/image_projection_based_fusion/src/fusion_node.cpp @@ -35,8 +35,9 @@ namespace image_projection_based_fusion { -template -FusionNode::FusionNode(const std::string & node_name, const rclcpp::NodeOptions & options) +template +FusionNode::FusionNode( + const std::string & node_name, const rclcpp::NodeOptions & options) : Node(node_name, options), tf_buffer_(this->get_clock()), tf_listener_(tf_buffer_) { rois_number_ = static_cast(declare_parameter("rois_number", 1)); @@ -131,24 +132,31 @@ FusionNode::FusionNode(const std::string & node_name, const rclcpp::NodeOpt static_cast(declare_parameter("image_buffer_size", 15)); debugger_ = std::make_shared(this, rois_number_, image_buffer_size); } + + filter_scope_minx_ = declare_parameter("filter_scope_minx", -100); + filter_scope_maxx_ = declare_parameter("filter_scope_maxx", 100); + filter_scope_miny_ = declare_parameter("filter_scope_miny", -100); + filter_scope_maxy_ = declare_parameter("filter_scope_maxy", 100); + filter_scope_minz_ = declare_parameter("filter_scope_minz", -100); + filter_scope_maxz_ = declare_parameter("filter_scope_maxz", 100); } -template -void FusionNode::cameraInfoCallback( +template +void FusionNode::cameraInfoCallback( const sensor_msgs::msg::CameraInfo::ConstSharedPtr input_camera_info_msg, const std::size_t camera_id) { camera_info_map_[camera_id] = *input_camera_info_msg; } -template -void FusionNode::preprocess(Msg & ouput_msg __attribute__((unused))) +template +void FusionNode::preprocess(Msg & ouput_msg __attribute__((unused))) { // do nothing by default } -template -void FusionNode::fusionCallback( +template +void FusionNode::fusionCallback( typename Msg::ConstSharedPtr input_msg, DetectedObjectsWithFeature::ConstSharedPtr input_roi0_msg, DetectedObjectsWithFeature::ConstSharedPtr input_roi1_msg, DetectedObjectsWithFeature::ConstSharedPtr input_roi2_msg, @@ -215,18 +223,19 @@ void FusionNode::fusionCallback( publish(output_msg); } -template -void FusionNode::postprocess() +template +void FusionNode::postprocess() { // do nothing by default } -template -void FusionNode::publish(const Msg & output_msg) +template +void FusionNode::publish(const Msg & output_msg) { pub_ptr_->publish(output_msg); } -template class FusionNode; -template class FusionNode; +template class FusionNode; +template class FusionNode; + } // namespace image_projection_based_fusion diff --git a/perception/image_projection_based_fusion/src/roi_cluster_fusion/node.cpp b/perception/image_projection_based_fusion/src/roi_cluster_fusion/node.cpp index c6966c362785..295326f9ba97 100644 --- a/perception/image_projection_based_fusion/src/roi_cluster_fusion/node.cpp +++ b/perception/image_projection_based_fusion/src/roi_cluster_fusion/node.cpp @@ -32,7 +32,7 @@ namespace image_projection_based_fusion { RoiClusterFusionNode::RoiClusterFusionNode(const rclcpp::NodeOptions & options) -: FusionNode("roi_cluster_fusion", options) +: FusionNode("roi_cluster_fusion", options) { use_iou_x_ = declare_parameter("use_iou_x", true); use_iou_y_ = declare_parameter("use_iou_y", false); @@ -85,6 +85,11 @@ void RoiClusterFusionNode::fuseOnSingleImage( continue; } + // filter point out of scope + if (debugger_ && out_of_scope(input_cluster_msg.feature_objects.at(i))) { + continue; + } + sensor_msgs::msg::PointCloud2 transformed_cluster; tf2::doTransform( input_cluster_msg.feature_objects.at(i).feature.cluster, transformed_cluster, @@ -172,6 +177,36 @@ void RoiClusterFusionNode::fuseOnSingleImage( } } +bool RoiClusterFusionNode::out_of_scope(const DetectedObjectWithFeature & obj) +{ + auto cluster = obj.feature.cluster; + bool is_out = false; + auto valid_point = [](float p, float min_num, float max_num) -> bool { + return (p > min_num) && (p < max_num); + }; + + for (sensor_msgs::PointCloud2ConstIterator iter_x(cluster, "x"), iter_y(cluster, "y"), + iter_z(cluster, "z"); + iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) { + if (!valid_point(*iter_x, filter_scope_minx_, filter_scope_maxx_)) { + is_out = true; + break; + } + + if (!valid_point(*iter_y, filter_scope_miny_, filter_scope_maxy_)) { + is_out = true; + break; + } + + if (!valid_point(*iter_z, filter_scope_minz_, filter_scope_maxz_)) { + is_out = true; + break; + } + } + + return is_out; +} + } // namespace image_projection_based_fusion #include diff --git a/perception/image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp b/perception/image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp index ec9183f23797..1e1df50482b6 100644 --- a/perception/image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp +++ b/perception/image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp @@ -21,7 +21,7 @@ namespace image_projection_based_fusion { RoiDetectedObjectFusionNode::RoiDetectedObjectFusionNode(const rclcpp::NodeOptions & options) -: FusionNode("roi_detected_object_fusion", options) +: FusionNode("roi_detected_object_fusion", options) { use_iou_x_ = declare_parameter("use_iou_x", false); use_iou_y_ = declare_parameter("use_iou_y", false); @@ -78,6 +78,12 @@ void RoiDetectedObjectFusionNode::generateDetectedObjectRois( std::vector vertices_camera_coord; { const auto & object = input_objects.at(obj_i); + + // filter point out of scope + if (debugger_ && out_of_scope(object)) { + continue; + } + std::vector vertices; objectToVertices(object.kinematics.pose_with_covariance.pose, object.shape, vertices); transformPoints(vertices, object2camera_affine, vertices_camera_coord); @@ -171,6 +177,29 @@ void RoiDetectedObjectFusionNode::updateDetectedObjectClassification( } } +bool RoiDetectedObjectFusionNode::out_of_scope(const DetectedObject & obj) +{ + bool is_out = true; + auto pose = obj.kinematics.pose_with_covariance.pose; + + auto valid_point = [](float p, float min_num, float max_num) -> bool { + return (p > min_num) && (p < max_num); + }; + + if (!valid_point(pose.position.x, filter_scope_minx_, filter_scope_maxx_)) { + return is_out; + } + if (!valid_point(pose.position.y, filter_scope_miny_, filter_scope_maxy_)) { + return is_out; + } + if (!valid_point(pose.position.z, filter_scope_minz_, filter_scope_maxz_)) { + return is_out; + } + + is_out = false; + return is_out; +} + } // namespace image_projection_based_fusion #include From 946628cc768da5d9d24230765884e387cf8f0bae Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Wed, 18 May 2022 22:38:13 +0900 Subject: [PATCH 34/55] feat(component_interface_utils): add interface classes (#899) * feat(component_interface_utils): add interface classes Signed-off-by: Takagi, Isamu * feat(default_ad_api): apply the changes of interface utils Signed-off-by: Takagi, Isamu * fix(component_interface_utils): remove old comment Signed-off-by: Takagi, Isamu * fix(component_interface_utils): add client log Signed-off-by: Takagi, Isamu * fix(component_interface_utils): remove unimplemented message Signed-off-by: Takagi, Isamu * docs(component_interface_utils): add design policy Signed-off-by: Takagi, Isamu * docs(component_interface_utils): add comment Signed-off-by: Takagi, Isamu --- common/component_interface_utils/README.md | 6 ++ .../component_interface_utils/rclcpp.hpp | 56 ++++++++++++++ .../rclcpp/create_interface.hpp | 47 ++++++++---- .../rclcpp/service_client.hpp | 76 +++++++++++++++++++ .../rclcpp/service_server.hpp | 13 ++-- .../rclcpp/topic_publisher.hpp | 48 ++++++++++++ .../rclcpp/topic_subscription.hpp | 45 +++++++++++ .../component_interface_utils/specs.hpp | 34 +++++++++ system/default_ad_api/CMakeLists.txt | 4 +- .../launch/default_ad_api.launch.py | 2 +- .../{interface_version.cpp => interface.cpp} | 25 +++--- .../interface.hpp} | 18 ++--- system/default_ad_api/src/utils/types.hpp | 40 ++++++++++ 13 files changed, 366 insertions(+), 48 deletions(-) create mode 100644 common/component_interface_utils/include/component_interface_utils/rclcpp/service_client.hpp create mode 100644 common/component_interface_utils/include/component_interface_utils/rclcpp/topic_publisher.hpp create mode 100644 common/component_interface_utils/include/component_interface_utils/rclcpp/topic_subscription.hpp create mode 100644 common/component_interface_utils/include/component_interface_utils/specs.hpp rename system/default_ad_api/src/{interface_version.cpp => interface.cpp} (54%) rename system/default_ad_api/{include/default_ad_api/nodes/interface_version.hpp => src/interface.hpp} (58%) create mode 100644 system/default_ad_api/src/utils/types.hpp diff --git a/common/component_interface_utils/README.md b/common/component_interface_utils/README.md index 3bcc19590151..2703f5ceaeee 100644 --- a/common/component_interface_utils/README.md +++ b/common/component_interface_utils/README.md @@ -24,3 +24,9 @@ This is a utility package that provides the following features: component_interface_utils::Service::SharedPtr srv_; srv_ = component_interface_utils::create_service(node, ...); ``` + +## Design + +This package provides the wrappers for the interface classes of rclcpp. +The wrappers limit the usage of the original class to enforce the processing recommended by the component interface. +Do not inherit the class of rclcpp, and forward or wrap the member function that is allowed to be used. diff --git a/common/component_interface_utils/include/component_interface_utils/rclcpp.hpp b/common/component_interface_utils/include/component_interface_utils/rclcpp.hpp index 0101fce383b9..8874ef6765f3 100644 --- a/common/component_interface_utils/include/component_interface_utils/rclcpp.hpp +++ b/common/component_interface_utils/include/component_interface_utils/rclcpp.hpp @@ -16,6 +16,62 @@ #define COMPONENT_INTERFACE_UTILS__RCLCPP_HPP_ #include +#include #include +#include +#include + +#include + +namespace component_interface_utils +{ + +class NodeAdaptor +{ +private: + using CallbackGroup = rclcpp::CallbackGroup::SharedPtr; + +public: + /// Constructor. + explicit NodeAdaptor(rclcpp::Node * node) : node_(node) {} + + /// Create a client wrapper for logging. + template + void init_cli(SharedPtrT & cli, CallbackGroup group = nullptr) const + { + using SpecT = typename SharedPtrT::element_type::SpecType; + cli = create_client_impl(node_, group); + } + + /// Create a service wrapper for logging. + template + void init_srv(SharedPtrT & srv, CallbackT && callback, CallbackGroup group = nullptr) const + { + using SpecT = typename SharedPtrT::element_type::SpecType; + srv = create_service_impl(node_, std::forward(callback), group); + } + + /// Create a publisher using traits like services. + template + void init_pub(SharedPtrT & pub) const + { + using SpecT = typename SharedPtrT::element_type::SpecType; + pub = create_publisher_impl(node_); + } + + /// Create a subscription using traits like services. + template + void init_sub(SharedPtrT & sub, CallbackT && callback) const + { + using SpecT = typename SharedPtrT::element_type::SpecType; + sub = create_subscription_impl(node_, std::forward(callback)); + } + +private: + // Use a node pointer because shared_from_this cannot be used in constructor. + rclcpp::Node * node_; +}; + +} // namespace component_interface_utils #endif // COMPONENT_INTERFACE_UTILS__RCLCPP_HPP_ diff --git a/common/component_interface_utils/include/component_interface_utils/rclcpp/create_interface.hpp b/common/component_interface_utils/include/component_interface_utils/rclcpp/create_interface.hpp index 3a67d40bace7..c16abcbe7ad7 100644 --- a/common/component_interface_utils/include/component_interface_utils/rclcpp/create_interface.hpp +++ b/common/component_interface_utils/include/component_interface_utils/rclcpp/create_interface.hpp @@ -15,7 +15,11 @@ #ifndef COMPONENT_INTERFACE_UTILS__RCLCPP__CREATE_INTERFACE_HPP_ #define COMPONENT_INTERFACE_UTILS__RCLCPP__CREATE_INTERFACE_HPP_ +#include #include +#include +#include +#include #include #include @@ -23,12 +27,23 @@ namespace component_interface_utils { +/// Create a client wrapper for logging. This is a private implementation. +template +typename Client::SharedPtr create_client_impl( + NodeT * node, rclcpp::CallbackGroup::SharedPtr group = nullptr) +{ + // This function is a wrapper for the following. + // https://github.com/ros2/rclcpp/blob/48068130edbb43cdd61076dc1851672ff1a80408/rclcpp/include/rclcpp/node.hpp#L253-L265 + auto client = node->template create_client( + SpecT::name, rmw_qos_profile_services_default, group); + return Client::make_shared(client, node->get_logger()); +} + /// Create a service wrapper for logging. This is a private implementation. template typename Service::SharedPtr create_service_impl( NodeT * node, CallbackT && callback, rclcpp::CallbackGroup::SharedPtr group = nullptr) { - // Use a node pointer because shared_from_this cannot be used in constructor. // This function is a wrapper for the following. // https://github.com/ros2/rclcpp/blob/48068130edbb43cdd61076dc1851672ff1a80408/rclcpp/include/rclcpp/node.hpp#L267-L281 auto wrapped = Service::wrap(callback, node->get_logger()); @@ -37,23 +52,27 @@ typename Service::SharedPtr create_service_impl( return Service::make_shared(service); } -/// Create a service wrapper for logging. This is for lambda or bound function. -template -typename Service::SharedPtr create_service( - NodeT * node, CallbackT && callback, rclcpp::CallbackGroup::SharedPtr group = nullptr) +/// Create a publisher using traits like services. This is a private implementation. +template +typename Publisher::SharedPtr create_publisher_impl(NodeT * node) { - return create_service_impl(node, std::forward(callback), group); + // This function is a wrapper for the following. + // https://github.com/ros2/rclcpp/blob/48068130edbb43cdd61076dc1851672ff1a80408/rclcpp/include/rclcpp/node.hpp#L167-L205 + auto publisher = + node->template create_publisher(SpecT::name, get_qos()); + return Publisher::make_shared(publisher); } -/// Create a service wrapper for logging. This is for member function of node. -template -typename Service::SharedPtr create_service( - NodeT * node, typename Service::template CallbackType callback, - rclcpp::CallbackGroup::SharedPtr group = nullptr) +/// Create a subscription using traits like services. This is a private implementation. +template +typename Subscription::SharedPtr create_subscription_impl( + NodeT * node, CallbackT && callback) { - using std::placeholders::_1; - using std::placeholders::_2; - return create_service_impl(node, std::bind(callback, node, _1, _2), group); + // This function is a wrapper for the following. + // https://github.com/ros2/rclcpp/blob/48068130edbb43cdd61076dc1851672ff1a80408/rclcpp/include/rclcpp/node.hpp#L207-L238 + auto subscription = node->template create_subscription( + SpecT::name, get_qos(), std::forward(callback)); + return Subscription::make_shared(subscription); } } // namespace component_interface_utils diff --git a/common/component_interface_utils/include/component_interface_utils/rclcpp/service_client.hpp b/common/component_interface_utils/include/component_interface_utils/rclcpp/service_client.hpp new file mode 100644 index 000000000000..64ea372ce26d --- /dev/null +++ b/common/component_interface_utils/include/component_interface_utils/rclcpp/service_client.hpp @@ -0,0 +1,76 @@ +// Copyright 2022 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef COMPONENT_INTERFACE_UTILS__RCLCPP__SERVICE_CLIENT_HPP_ +#define COMPONENT_INTERFACE_UTILS__RCLCPP__SERVICE_CLIENT_HPP_ + +#include +#include +#include + +#include + +namespace component_interface_utils +{ + +/// The wrapper class of rclcpp::Client for logging. +template +class Client +{ +public: + RCLCPP_SMART_PTR_DEFINITIONS(Client) + using SpecType = SpecT; + using WrapType = rclcpp::Client; + + /// Constructor. + explicit Client(typename WrapType::SharedPtr client, const rclcpp::Logger & logger) + : logger_(logger) + { + client_ = client; // to keep the reference count + } + + /// Send request. + typename WrapType::SharedFuture async_send_request(typename WrapType::SharedRequest request) + { + const auto callback = [this](typename WrapType::SharedFuture future) {}; + return this->async_send_request(request, callback); + } + + /// Send request. + template + typename WrapType::SharedFuture async_send_request( + typename WrapType::SharedRequest request, CallbackT && callback) + { +#ifdef ROS_DISTRO_GALACTIC + using rosidl_generator_traits::to_yaml; +#endif + + const auto wrapped = [this, callback](typename WrapType::SharedFuture future) { + RCLCPP_INFO_STREAM(logger_, "client exit: " << SpecT::name << "\n" << to_yaml(*future.get())); + callback(future); + }; + + RCLCPP_INFO_STREAM(logger_, "client call: " << SpecT::name << "\n" << to_yaml(*request)); + return client_->async_send_request(request, wrapped); + } + +private: + RCLCPP_DISABLE_COPY(Client) + typename WrapType::SharedPtr client_; + rclcpp::Logger logger_; +}; + +} // namespace component_interface_utils + +#endif // COMPONENT_INTERFACE_UTILS__RCLCPP__SERVICE_CLIENT_HPP_ diff --git a/common/component_interface_utils/include/component_interface_utils/rclcpp/service_server.hpp b/common/component_interface_utils/include/component_interface_utils/rclcpp/service_server.hpp index 006c08e5c2d6..6697e6a08b84 100644 --- a/common/component_interface_utils/include/component_interface_utils/rclcpp/service_server.hpp +++ b/common/component_interface_utils/include/component_interface_utils/rclcpp/service_server.hpp @@ -15,7 +15,8 @@ #ifndef COMPONENT_INTERFACE_UTILS__RCLCPP__SERVICE_SERVER_HPP_ #define COMPONENT_INTERFACE_UTILS__RCLCPP__SERVICE_SERVER_HPP_ -#include +#include +#include namespace component_interface_utils { @@ -26,13 +27,11 @@ class Service { public: RCLCPP_SMART_PTR_DEFINITIONS(Service) - - template - using CallbackType = void (NodeT::*)( - typename SpecT::Service::Request::SharedPtr, typename SpecT::Service::Response::SharedPtr); + using SpecType = SpecT; + using WrapType = rclcpp::Service; /// Constructor. - explicit Service(typename rclcpp::Service::SharedPtr service) + explicit Service(typename WrapType::SharedPtr service) { service_ = service; // to keep the reference count } @@ -56,7 +55,7 @@ class Service private: RCLCPP_DISABLE_COPY(Service) - typename rclcpp::Service::SharedPtr service_; + typename WrapType::SharedPtr service_; }; } // namespace component_interface_utils diff --git a/common/component_interface_utils/include/component_interface_utils/rclcpp/topic_publisher.hpp b/common/component_interface_utils/include/component_interface_utils/rclcpp/topic_publisher.hpp new file mode 100644 index 000000000000..b2c002613a29 --- /dev/null +++ b/common/component_interface_utils/include/component_interface_utils/rclcpp/topic_publisher.hpp @@ -0,0 +1,48 @@ +// Copyright 2022 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef COMPONENT_INTERFACE_UTILS__RCLCPP__TOPIC_PUBLISHER_HPP_ +#define COMPONENT_INTERFACE_UTILS__RCLCPP__TOPIC_PUBLISHER_HPP_ + +#include + +namespace component_interface_utils +{ + +/// The wrapper class of rclcpp::Publisher. This is for future use and no functionality now. +template +class Publisher +{ +public: + RCLCPP_SMART_PTR_DEFINITIONS(Publisher) + using SpecType = SpecT; + using WrapType = rclcpp::Publisher; + + /// Constructor. + explicit Publisher(typename WrapType::SharedPtr publisher) + { + publisher_ = publisher; // to keep the reference count + } + + /// Publish a message. + void publish(const typename SpecT::Message & msg) { publisher_->publish(msg); } + +private: + RCLCPP_DISABLE_COPY(Publisher) + typename WrapType::SharedPtr publisher_; +}; + +} // namespace component_interface_utils + +#endif // COMPONENT_INTERFACE_UTILS__RCLCPP__TOPIC_PUBLISHER_HPP_ diff --git a/common/component_interface_utils/include/component_interface_utils/rclcpp/topic_subscription.hpp b/common/component_interface_utils/include/component_interface_utils/rclcpp/topic_subscription.hpp new file mode 100644 index 000000000000..195a04c37096 --- /dev/null +++ b/common/component_interface_utils/include/component_interface_utils/rclcpp/topic_subscription.hpp @@ -0,0 +1,45 @@ +// Copyright 2022 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef COMPONENT_INTERFACE_UTILS__RCLCPP__TOPIC_SUBSCRIPTION_HPP_ +#define COMPONENT_INTERFACE_UTILS__RCLCPP__TOPIC_SUBSCRIPTION_HPP_ + +#include + +namespace component_interface_utils +{ + +/// The wrapper class of rclcpp::Subscription. This is for future use and no functionality now. +template +class Subscription +{ +public: + RCLCPP_SMART_PTR_DEFINITIONS(Subscription) + using SpecType = SpecT; + using WrapType = rclcpp::Subscription; + + /// Constructor. + explicit Subscription(typename WrapType::SharedPtr subscription) + { + subscription_ = subscription; // to keep the reference count + } + +private: + RCLCPP_DISABLE_COPY(Subscription) + typename WrapType::SharedPtr subscription_; +}; + +} // namespace component_interface_utils + +#endif // COMPONENT_INTERFACE_UTILS__RCLCPP__TOPIC_SUBSCRIPTION_HPP_ diff --git a/common/component_interface_utils/include/component_interface_utils/specs.hpp b/common/component_interface_utils/include/component_interface_utils/specs.hpp new file mode 100644 index 000000000000..db3bb9517430 --- /dev/null +++ b/common/component_interface_utils/include/component_interface_utils/specs.hpp @@ -0,0 +1,34 @@ +// Copyright 2022 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef COMPONENT_INTERFACE_UTILS__SPECS_HPP_ +#define COMPONENT_INTERFACE_UTILS__SPECS_HPP_ + +#include + +namespace component_interface_utils +{ + +template +rclcpp::QoS get_qos() +{ + rclcpp::QoS qos(SpecT::depth); + qos.reliability(SpecT::reliability); + qos.durability(SpecT::durability); + return qos; +} + +} // namespace component_interface_utils + +#endif // COMPONENT_INTERFACE_UTILS__SPECS_HPP_ diff --git a/system/default_ad_api/CMakeLists.txt b/system/default_ad_api/CMakeLists.txt index f2927d1febed..ae4125cc822f 100644 --- a/system/default_ad_api/CMakeLists.txt +++ b/system/default_ad_api/CMakeLists.txt @@ -5,10 +5,10 @@ find_package(autoware_cmake REQUIRED) autoware_package() ament_auto_add_library(${PROJECT_NAME} SHARED - src/interface_version.cpp + src/interface.cpp ) -rclcpp_components_register_nodes(${PROJECT_NAME} "default_ad_api::InterfaceVersionNode") +rclcpp_components_register_nodes(${PROJECT_NAME} "default_ad_api::InterfaceNode") if(BUILD_TESTING) add_launch_test(test/main.test.py) diff --git a/system/default_ad_api/launch/default_ad_api.launch.py b/system/default_ad_api/launch/default_ad_api.launch.py index 206689f38296..e9542328ed98 100644 --- a/system/default_ad_api/launch/default_ad_api.launch.py +++ b/system/default_ad_api/launch/default_ad_api.launch.py @@ -30,7 +30,7 @@ def _create_api_node(node_name, class_name, **kwargs): def generate_launch_description(): components = [ - _create_api_node("interface_version", "InterfaceVersionNode"), + _create_api_node("interface", "InterfaceNode"), ] container = ComposableNodeContainer( namespace="default_ad_api", diff --git a/system/default_ad_api/src/interface_version.cpp b/system/default_ad_api/src/interface.cpp similarity index 54% rename from system/default_ad_api/src/interface_version.cpp rename to system/default_ad_api/src/interface.cpp index 7286d4006a50..bd54da361fe1 100644 --- a/system/default_ad_api/src/interface_version.cpp +++ b/system/default_ad_api/src/interface.cpp @@ -12,27 +12,26 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "default_ad_api/nodes/interface_version.hpp" +#include "interface.hpp" namespace default_ad_api { -InterfaceVersionNode::InterfaceVersionNode(const rclcpp::NodeOptions & options) -: Node("interface_version", options) +InterfaceNode::InterfaceNode(const rclcpp::NodeOptions & options) : Node("interface", options) { - srv_ = component_interface_utils::create_service( - this, &InterfaceVersionNode::onInterfaceVersion); -} + using InterfaceVersion = autoware_ad_api_msgs::srv::InterfaceVersion; -void InterfaceVersionNode::onInterfaceVersion( - const InterfaceVersion::Request::SharedPtr, const InterfaceVersion::Response::SharedPtr response) -{ - response->major = 0; - response->minor = 1; - response->patch = 0; + const auto on_interface_version = [](SERVICE_ARG_NO_REQ(InterfaceVersion)) { + response->major = 0; + response->minor = 1; + response->patch = 0; + }; + + const auto node = component_interface_utils::NodeAdaptor(this); + node.init_srv(srv_, on_interface_version); } } // namespace default_ad_api #include -RCLCPP_COMPONENTS_REGISTER_NODE(default_ad_api::InterfaceVersionNode) +RCLCPP_COMPONENTS_REGISTER_NODE(default_ad_api::InterfaceNode) diff --git a/system/default_ad_api/include/default_ad_api/nodes/interface_version.hpp b/system/default_ad_api/src/interface.hpp similarity index 58% rename from system/default_ad_api/include/default_ad_api/nodes/interface_version.hpp rename to system/default_ad_api/src/interface.hpp index f91d96e2c2a6..6a1bda419bb7 100644 --- a/system/default_ad_api/include/default_ad_api/nodes/interface_version.hpp +++ b/system/default_ad_api/src/interface.hpp @@ -12,10 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef DEFAULT_AD_API__NODES__INTERFACE_VERSION_HPP_ -#define DEFAULT_AD_API__NODES__INTERFACE_VERSION_HPP_ +#ifndef INTERFACE_HPP_ +#define INTERFACE_HPP_ #include "default_ad_api/specs/interface/version.hpp" +#include "utils/types.hpp" #include #include @@ -23,20 +24,15 @@ namespace default_ad_api { -class InterfaceVersionNode : public rclcpp::Node +class InterfaceNode : public rclcpp::Node { public: - explicit InterfaceVersionNode(const rclcpp::NodeOptions & options); + explicit InterfaceNode(const rclcpp::NodeOptions & options); private: - using InterfaceVersion = autoware_ad_api_msgs::srv::InterfaceVersion; - - component_interface_utils::Service::SharedPtr srv_; - void onInterfaceVersion( - const InterfaceVersion::Request::SharedPtr request, - const InterfaceVersion::Response::SharedPtr response); + Service::SharedPtr srv_; }; } // namespace default_ad_api -#endif // DEFAULT_AD_API__NODES__INTERFACE_VERSION_HPP_ +#endif // INTERFACE_HPP_ diff --git a/system/default_ad_api/src/utils/types.hpp b/system/default_ad_api/src/utils/types.hpp new file mode 100644 index 000000000000..b9a2036804d7 --- /dev/null +++ b/system/default_ad_api/src/utils/types.hpp @@ -0,0 +1,40 @@ +// Copyright 2022 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef UTILS__TYPES_HPP_ +#define UTILS__TYPES_HPP_ + +#include + +#define MESSAGE_ARG(Type) const Type::ConstSharedPtr message +#define SERVICE_ARG(Type) \ + const Type::Request::SharedPtr request, const Type::Response::SharedPtr response +#define SERVICE_ARG_NO_REQ(Type) \ + const Type::Request::SharedPtr, const Type::Response::SharedPtr response + +namespace default_ad_api +{ + +template +using Publisher = component_interface_utils::Publisher; +template +using Subscription = component_interface_utils::Subscription; +template +using Client = component_interface_utils::Client; +template +using Service = component_interface_utils::Service; + +} // namespace default_ad_api + +#endif // UTILS__TYPES_HPP_ From f301c1ed39b81e49400e3e943f25cfbdf3ec4aaf Mon Sep 17 00:00:00 2001 From: Berkay Date: Thu, 19 May 2022 03:27:49 +0300 Subject: [PATCH 35/55] refactor(vehicle_cmd_gate): change namespace in launch file (#927) Signed-off-by: Berkay Co-authored-by: Berkay --- launch/tier4_control_launch/launch/control.launch.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/launch/tier4_control_launch/launch/control.launch.py b/launch/tier4_control_launch/launch/control.launch.py index 37c43a2ab392..b3d26d092785 100644 --- a/launch/tier4_control_launch/launch/control.launch.py +++ b/launch/tier4_control_launch/launch/control.launch.py @@ -171,7 +171,7 @@ def launch_setup(context, *args, **kwargs): # vehicle cmd gate vehicle_cmd_gate_component = ComposableNode( package="vehicle_cmd_gate", - plugin="VehicleCmdGate", + plugin="vehicle_cmd_gate::VehicleCmdGate", name="vehicle_cmd_gate", remappings=[ ("input/emergency_state", "/system/emergency/emergency_state"), From f5fbce31ba4304b568ca18ea7a224d4982113ded Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Thu, 19 May 2022 10:17:06 +0900 Subject: [PATCH 36/55] feat: visualize lane boundaries (#923) * feat: visualize lane boundaries * fix: start_bound * ci(pre-commit): autofix Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- map/lanelet2_extension/lib/visualization.cpp | 17 ++++++++++++++++- 1 file changed, 16 insertions(+), 1 deletion(-) diff --git a/map/lanelet2_extension/lib/visualization.cpp b/map/lanelet2_extension/lib/visualization.cpp index fc9f068669d9..a95a9aa1e49e 100644 --- a/map/lanelet2_extension/lib/visualization.cpp +++ b/map/lanelet2_extension/lib/visualization.cpp @@ -878,11 +878,14 @@ visualization_msgs::msg::MarkerArray visualization::laneletsBoundaryAsMarkerArra double lss_center = std::max(lss * 0.1, 0.02); std::unordered_set added; - visualization_msgs::msg::Marker left_line_strip, right_line_strip, center_line_strip; + visualization_msgs::msg::Marker left_line_strip, right_line_strip, start_bound_line_strip, + center_line_strip; visualization::initLineStringMarker( &left_line_strip, "map", additional_namespace + "left_lane_bound", c); visualization::initLineStringMarker( &right_line_strip, "map", additional_namespace + "right_lane_bound", c); + visualization::initLineStringMarker( + &start_bound_line_strip, "map", additional_namespace + "lane_start_bound", c); visualization::initLineStringMarker( ¢er_line_strip, "map", additional_namespace + "center_lane_line", c); @@ -892,6 +895,11 @@ visualization_msgs::msg::MarkerArray visualization::laneletsBoundaryAsMarkerArra lanelet::ConstLineString3d left_ls = lll.leftBound(); lanelet::ConstLineString3d right_ls = lll.rightBound(); lanelet::ConstLineString3d center_ls = lll.centerline(); + lanelet::LineString3d start_bound_ls(lanelet::utils::getId()); + start_bound_ls.push_back(lanelet::Point3d( + lanelet::utils::getId(), left_ls.front().x(), left_ls.front().y(), left_ls.front().z())); + start_bound_ls.push_back(lanelet::Point3d( + lanelet::utils::getId(), right_ls.front().x(), right_ls.front().y(), right_ls.front().z())); if (!exists(added, left_ls.id())) { visualization::pushLineStringMarker(&left_line_strip, left_ls, c, lss); @@ -901,6 +909,10 @@ visualization_msgs::msg::MarkerArray visualization::laneletsBoundaryAsMarkerArra visualization::pushLineStringMarker(&right_line_strip, right_ls, c, lss); added.insert(right_ls.id()); } + if (!exists(added, start_bound_ls.id())) { + visualization::pushLineStringMarker(&start_bound_line_strip, start_bound_ls, c, lss); + added.insert(start_bound_ls.id()); + } if (viz_centerline && !exists(added, center_ls.id())) { visualization::pushLineStringMarker(¢er_line_strip, center_ls, c, lss_center); added.insert(center_ls.id()); @@ -917,6 +929,9 @@ visualization_msgs::msg::MarkerArray visualization::laneletsBoundaryAsMarkerArra if (!center_line_strip.points.empty()) { marker_array.markers.push_back(center_line_strip); } + if (!start_bound_line_strip.points.empty()) { + marker_array.markers.push_back(start_bound_line_strip); + } return marker_array; } From a72a2f27097149681262502e63f9f3a13451cc24 Mon Sep 17 00:00:00 2001 From: ito-san <57388357+ito-san@users.noreply.github.com> Date: Thu, 19 May 2022 10:26:36 +0900 Subject: [PATCH 37/55] fix(system_monitor): fix truncation warning in strncpy (#872) * fix(system_monitor): fix truncation warning in strncpy * Use std::string constructor to copy char array * Fixed typo --- system/system_monitor/CMakeLists.txt | 3 --- .../reader/hdd_reader/hdd_reader.cpp | 26 +++++++------------ 2 files changed, 9 insertions(+), 20 deletions(-) diff --git a/system/system_monitor/CMakeLists.txt b/system/system_monitor/CMakeLists.txt index 65e933d07204..a20beca4135e 100644 --- a/system/system_monitor/CMakeLists.txt +++ b/system/system_monitor/CMakeLists.txt @@ -4,9 +4,6 @@ project(system_monitor) find_package(autoware_cmake REQUIRED) autoware_package() -# TODO: remove (https://github.com/autowarefoundation/autoware.universe/issues/851) -add_compile_options(-Wno-stringop-truncation) - set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} "${CMAKE_CURRENT_SOURCE_DIR}/cmake") find_package(NVML) find_package(fmt REQUIRED) diff --git a/system/system_monitor/reader/hdd_reader/hdd_reader.cpp b/system/system_monitor/reader/hdd_reader/hdd_reader.cpp index 3ec60be078ae..f31efde2f5e0 100644 --- a/system/system_monitor/reader/hdd_reader/hdd_reader.cpp +++ b/system/system_monitor/reader/hdd_reader/hdd_reader.cpp @@ -159,7 +159,7 @@ void usage() /** * @brief exchanges the values of 2 bytes - * @param [inout] ptr a pointer to ATA string + * @param [inout] str a string reference to ATA string * @param [in] size size of ATA string * @note Each pair of bytes in an ATA string is swapped. * FIRMWARE REVISION field example @@ -170,10 +170,10 @@ void usage() * 26 6720h (" g") * -> "abcdefg " */ -void swap_char(char * ptr, size_t size) +void swap_char(std::string & str, size_t size) { for (auto i = 0U; i < size; i += 2U) { - std::swap(ptr[i], ptr[i + 1]); + std::swap(str[i], str[i + 1]); } } @@ -219,17 +219,13 @@ int get_ata_identify(int fd, HDDInfo * info) // IDENTIFY DEVICE // Word 10..19 Serial number - char serial_number[20 + 1]{}; - strncpy(serial_number, reinterpret_cast(data) + 20, 20); - swap_char(serial_number, 20); - info->serial_ = serial_number; + info->serial_ = std::string(reinterpret_cast(data) + 20, 20); + swap_char(info->serial_, 20); boost::trim(info->serial_); // Word 27..46 Model number - char model_number[40 + 1]{}; - strncpy(model_number, reinterpret_cast(data) + 54, 40); - swap_char(model_number, 40); - info->model_ = model_number; + info->model_ = std::string(reinterpret_cast(data) + 54, 40); + swap_char(info->model_, 40); boost::trim(info->model_); return EXIT_SUCCESS; @@ -338,15 +334,11 @@ int get_nvme_identify(int fd, HDDInfo * info) // Identify Controller Data Structure // Bytes 23:04 Serial Number (SN) - char serial_number[20 + 1]{}; - strncpy(serial_number, data + 4, 20); - info->serial_ = serial_number; + info->serial_ = std::string(data + 4, 20); boost::trim(info->serial_); // Bytes 63:24 Model Number (MN) - char model_number[40 + 1]{}; - strncpy(model_number, data + 24, 40); - info->model_ = model_number; + info->model_ = std::string(data + 24, 40); boost::trim(info->model_); return EXIT_SUCCESS; From ac400df4d8ac706d98aed229cc08c108e7d6a012 Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Thu, 19 May 2022 14:18:57 +0900 Subject: [PATCH 38/55] fix(behavior_velocity_planner.stopline): extend following and previous search range to avoid no collision (#917) * fix: extend following and previous search range to avoid no collision * chore: add debug marker * fix: simplify logic * chore: update debug code Signed-off-by: h-ohta * fix: delete space * fix: some fix * ci(pre-commit): autofix * fix: delete debug code Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../src/scene_module/stop_line/scene.cpp | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/planning/behavior_velocity_planner/src/scene_module/stop_line/scene.cpp b/planning/behavior_velocity_planner/src/scene_module/stop_line/scene.cpp index bc8b344a784c..1c26ef601aa4 100644 --- a/planning/behavior_velocity_planner/src/scene_module/stop_line/scene.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/stop_line/scene.cpp @@ -207,14 +207,19 @@ bool StopLineModule::modifyPathVelocity( const auto & current_position = planner_data_->current_pose.pose.position; const PointWithSearchRangeIndex src_point_with_search_range_index = planning_utils::findFirstNearSearchRangeIndex(path->points, current_position); - const SearchRangeIndex dst_search_range = + SearchRangeIndex dst_search_range = planning_utils::getPathIndexRangeIncludeLaneId(*path, lane_id_); + // extend following and previous search range to avoid no collision + if (dst_search_range.max_idx < path->points.size() - 1) dst_search_range.max_idx++; + if (dst_search_range.min_idx > 0) dst_search_range.min_idx--; + // Find collision const auto collision = findCollision(*path, stop_line, dst_search_range); // If no collision found, do nothing if (!collision) { + RCLCPP_WARN(logger_, "is no collision"); return true; } From 51958054b9f82a35512ee1b4ad3ce50c88bd5fef Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 19 May 2022 17:30:22 +0900 Subject: [PATCH 39/55] docs(surround obstacle checker): update documentation (#878) * docs(surround_obstacle_checker): update pub/sub topics & params Signed-off-by: satoshi-ota * docs(surround_obstacle_checker): remove unused files Signed-off-by: satoshi-ota * docs(surround_obstacke_checker): update purpose Signed-off-by: satoshi-ota --- planning/surround_obstacle_checker/README.md | 54 +++++++++++++++---- .../media/surround_obstacle_checker_flow.svg | 38 ------------- .../media/surround_obstacle_checker_flow.uml | 17 ------ .../surround_obstacle_checker-design.ja.md | 51 ++++++++++++++---- 4 files changed, 85 insertions(+), 75 deletions(-) delete mode 100644 planning/surround_obstacle_checker/media/surround_obstacle_checker_flow.svg delete mode 100644 planning/surround_obstacle_checker/media/surround_obstacle_checker_flow.uml diff --git a/planning/surround_obstacle_checker/README.md b/planning/surround_obstacle_checker/README.md index 0ca374031547..58e4bc790413 100644 --- a/planning/surround_obstacle_checker/README.md +++ b/planning/surround_obstacle_checker/README.md @@ -2,16 +2,47 @@ ## Purpose -`surround_obstacle_checker` is a module to prevent moving if any obstacles is near stopping ego vehicle. -This module runs only when ego vehicle is stopping. +This module subscribes required data (ego-pose, obstacles, etc), and publishes zero velocity limit to keep stopping if any of stop conditions are satisfied. ## Inner-workings / Algorithms ### Flow chart -![surround_obstacle_checker_flow](./media/surround_obstacle_checker_flow.svg) +```plantuml +@startuml -![check_distance](./media/check_distance.drawio.svg) +title surround obstacle checker +start + +if (Check state) then + :State::STOP; + + if (Is stop required?) then (yes) + else (no) + :Clear velocity limit; + :Set state to State::PASS; + endif + +else + :State::PASS; + + if (Is stop required?) then (yes) + :Set velocity limit; + :Set state to State::STOP; + else (no) + endif + +endif + +:Publish stop reason; + +stop +@enduml +``` + +

### Algorithms @@ -49,7 +80,6 @@ As mentioned in stop condition section, it prevents chattering by changing thres | Name | Type | Description | | ---------------------------------------------- | ------------------------------------------------------ | ------------------------------------------------------------------ | -| `~/input/trajectory` | `autoware_auto_planning_msgs::msg::Trajectory` | Reference trajectory | | `/perception/obstacle_segmentation/pointcloud` | `sensor_msgs::msg::PointCloud2` | Pointcloud of obstacles which the ego-vehicle should stop or avoid | | `/perception/object_recognition/objects` | `autoware_auto_perception_msgs::msg::PredictedObjects` | Dynamic objects | | `/localization/kinematic_state` | `nav_msgs::msg::Odometry` | Current twist | @@ -58,12 +88,13 @@ As mentioned in stop condition section, it prevents chattering by changing thres ### Output -| Name | Type | Description | -| -------------------------- | ------------------------------------------- | ------------------------ | -| `~/output/trajectory` | `autoware_auto_planning_msgs/Trajectory` | Modified trajectory | -| `~/output/no_start_reason` | `diagnostic_msgs::msg::DiagnosticStatus` | No start reason | -| `~/output/stop_reasons` | `tier4_planning_msgs::msg::StopReasonArray` | Stop reasons | -| `~/debug/marker` | `visualization_msgs::msg::MarkerArray` | Marker for visualization | +| Name | Type | Description | +| --------------------------------------- | ----------------------------------------------------- | ---------------------------- | +| `~/output/velocity_limit_clear_command` | `tier4_planning_msgs::msg::VelocityLimitClearCommand` | Velocity limit clear command | +| `~/output/max_velocity` | `tier4_planning_msgs::msg::VelocityLimit` | Velocity limit command | +| `~/output/no_start_reason` | `diagnostic_msgs::msg::DiagnosticStatus` | No start reason | +| `~/output/stop_reasons` | `tier4_planning_msgs::msg::StopReasonArray` | Stop reasons | +| `~/debug/marker` | `visualization_msgs::msg::MarkerArray` | Marker for visualization | ## Parameters @@ -75,6 +106,7 @@ As mentioned in stop condition section, it prevents chattering by changing thres | `surround_check_recover_distance` | `double` | If no object exists in this distance, transit to "non-surrounding-obstacle" status [m] | 0.8 | | `state_clear_time` | `double` | Threshold to clear stop state [s] | 2.0 | | `stop_state_ego_speed` | `double` | Threshold to check ego vehicle stopped [m/s] | 0.1 | +| `stop_state_entry_duration_time` | `double` | Threshold to check ego vehicle stopped [s] | 0.1 | ## Assumptions / Known limits diff --git a/planning/surround_obstacle_checker/media/surround_obstacle_checker_flow.svg b/planning/surround_obstacle_checker/media/surround_obstacle_checker_flow.svg deleted file mode 100644 index 35f27a466735..000000000000 --- a/planning/surround_obstacle_checker/media/surround_obstacle_checker_flow.svg +++ /dev/null @@ -1,38 +0,0 @@ -Subscribe trajectoryCheck dataGet distance to nearest objectChange state to State::STOPChange state to State::PASSPublish trajectory, stop reason and debug dataInsert stop pointCreate debug dataIs stop required?yesno \ No newline at end of file diff --git a/planning/surround_obstacle_checker/media/surround_obstacle_checker_flow.uml b/planning/surround_obstacle_checker/media/surround_obstacle_checker_flow.uml deleted file mode 100644 index 1e278b7e606e..000000000000 --- a/planning/surround_obstacle_checker/media/surround_obstacle_checker_flow.uml +++ /dev/null @@ -1,17 +0,0 @@ -@startuml -(*) --> "Subscribe trajectory" -"Subscribe trajectory" --> "Check data" -"Check data" --> "Get distance to nearest object" - -if "Is stop required?" then - -->[yes] "Change state to State::STOP" -else - ->[no] "Change state to State::PASS" -endif - -"Change state to State::PASS" --> "Publish trajectory, stop reason and debug data" -"Change state to State::STOP" --> "Insert stop point" -"Insert stop point" --> "Create debug data" -"Create debug data" --> "Publish trajectory, stop reason and debug data" -"Publish trajectory, stop reason and debug data" --> (*) -@enduml diff --git a/planning/surround_obstacle_checker/surround_obstacle_checker-design.ja.md b/planning/surround_obstacle_checker/surround_obstacle_checker-design.ja.md index e4f99aa7d233..8a72c976621f 100644 --- a/planning/surround_obstacle_checker/surround_obstacle_checker-design.ja.md +++ b/planning/surround_obstacle_checker/surround_obstacle_checker-design.ja.md @@ -8,9 +8,41 @@ ### Flow chart -![surround_obstacle_checker_flow](./media/surround_obstacle_checker_flow.svg) +```plantuml +@startuml -![check_distance](./media/check_distance.drawio.svg) +title surround obstacle checker +start + +if (Check state) then + :State::STOP; + + if (Is stop required?) then (yes) + else (no) + :Clear velocity limit; + :Set state to State::PASS; + endif + +else + :State::PASS; + + if (Is stop required?) then (yes) + :Set velocity limit; + :Set state to State::STOP; + else (no) + endif + +endif + +:Publish stop reason; + +stop +@enduml +``` + +
+ +
### Algorithms @@ -48,7 +80,6 @@ Stop condition の項で述べたように、状態によって障害物判定 | Name | Type | Description | | ---------------------------------------------- | ------------------------------------------------------ | ------------------------------------------------------------------ | -| `~/input/trajectory` | `autoware_auto_planning_msgs::msg::Trajectory` | Reference trajectory | | `/perception/obstacle_segmentation/pointcloud` | `sensor_msgs::msg::PointCloud2` | Pointcloud of obstacles which the ego-vehicle should stop or avoid | | `/perception/object_recognition/objects` | `autoware_auto_perception_msgs::msg::PredictedObjects` | Dynamic objects | | `/localization/kinematic_state` | `nav_msgs::msg::Odometry` | Current twist | @@ -57,12 +88,13 @@ Stop condition の項で述べたように、状態によって障害物判定 ### Output -| Name | Type | Description | -| -------------------------- | ------------------------------------------- | ------------------------ | -| `~/output/trajectory` | `autoware_auto_planning_msgs/Trajectory` | Modified trajectory | -| `~/output/no_start_reason` | `diagnostic_msgs::msg::DiagnosticStatus` | No start reason | -| `~/output/stop_reasons` | `tier4_planning_msgs::msg::StopReasonArray` | Stop reasons | -| `~/debug/marker` | `visualization_msgs::msg::MarkerArray` | Marker for visualization | +| Name | Type | Description | +| --------------------------------------- | ----------------------------------------------------- | ---------------------------- | +| `~/output/velocity_limit_clear_command` | `tier4_planning_msgs::msg::VelocityLimitClearCommand` | Velocity limit clear command | +| `~/output/max_velocity` | `tier4_planning_msgs::msg::VelocityLimit` | Velocity limit command | +| `~/output/no_start_reason` | `diagnostic_msgs::msg::DiagnosticStatus` | No start reason | +| `~/output/stop_reasons` | `tier4_planning_msgs::msg::StopReasonArray` | Stop reasons | +| `~/debug/marker` | `visualization_msgs::msg::MarkerArray` | Marker for visualization | ## Parameters @@ -74,6 +106,7 @@ Stop condition の項で述べたように、状態によって障害物判定 | `surround_check_recover_distance` | `double` | If no object exists in this distance, transit to "non-surrounding-obstacle" status [m] | 0.8 | | `state_clear_time` | `double` | Threshold to clear stop state [s] | 2.0 | | `stop_state_ego_speed` | `double` | Threshold to check ego vehicle stopped [m/s] | 0.1 | +| `stop_state_entry_duration_time` | `double` | Threshold to check ego vehicle stopped [s] | 0.1 | ## Assumptions / Known limits From 351fa12a4b8d8245d61f610c9d985678b86481ab Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 19 May 2022 17:44:48 +0900 Subject: [PATCH 40/55] feat(tier4_autoware_utils): add vehicle state checker (#896) * feat(tier4_autoware_utils): add vehicle state checker Signed-off-by: satoshi-ota * fix(tier4_autoware_utils): use absolute value Signed-off-by: satoshi-ota * feat(tier4_autoware_utils): divide into two classies Signed-off-by: satoshi-ota * test(tier4_autoware_utils): add unit test for vehicle_state checker Signed-off-by: satoshi-ota * fix(tier4_autoware_utils): impl class inheritance Signed-off-by: satoshi-ota * docs(tier4_autoware_utils): add vehicle_state_checker document Signed-off-by: satoshi-ota * fix(tier4_autoware_utils): into same loop Signed-off-by: satoshi-ota * fix(tier4_autoware_utils): fix variables name Signed-off-by: satoshi-ota * fix(tier4_autoware_utils): remove redundant codes Signed-off-by: satoshi-ota --- common/tier4_autoware_utils/CMakeLists.txt | 1 + .../docs/vehicle/vehicle.md | 169 +++++++ .../vehicle/vehicle_state_checker.hpp | 76 +++ common/tier4_autoware_utils/package.xml | 1 + .../src/vehicle/vehicle_state_checker.cpp | 118 +++++ .../test/src/test_autoware_utils.cpp | 5 +- .../vehicle/test_vehicle_state_checker.cpp | 468 ++++++++++++++++++ .../test_vehicle_state_checker_helper.hpp | 59 +++ 8 files changed, 896 insertions(+), 1 deletion(-) create mode 100644 common/tier4_autoware_utils/docs/vehicle/vehicle.md create mode 100644 common/tier4_autoware_utils/include/tier4_autoware_utils/vehicle/vehicle_state_checker.hpp create mode 100644 common/tier4_autoware_utils/src/vehicle/vehicle_state_checker.cpp create mode 100644 common/tier4_autoware_utils/test/src/vehicle/test_vehicle_state_checker.cpp create mode 100644 common/tier4_autoware_utils/test/src/vehicle/test_vehicle_state_checker_helper.hpp diff --git a/common/tier4_autoware_utils/CMakeLists.txt b/common/tier4_autoware_utils/CMakeLists.txt index 7ba9c2020a36..3e30559e0271 100644 --- a/common/tier4_autoware_utils/CMakeLists.txt +++ b/common/tier4_autoware_utils/CMakeLists.txt @@ -9,6 +9,7 @@ find_package(Boost REQUIRED) ament_auto_add_library(tier4_autoware_utils SHARED src/tier4_autoware_utils.cpp src/planning/planning_marker_helper.cpp + src/vehicle/vehicle_state_checker.cpp ) if(BUILD_TESTING) diff --git a/common/tier4_autoware_utils/docs/vehicle/vehicle.md b/common/tier4_autoware_utils/docs/vehicle/vehicle.md new file mode 100644 index 000000000000..fe5e3ff98e05 --- /dev/null +++ b/common/tier4_autoware_utils/docs/vehicle/vehicle.md @@ -0,0 +1,169 @@ +# vehicle utils + +Vehicle utils provides a convenient library used to check vehicle status. + +## Feature + +The library contains following classes. + +### vehicle_stop_checker + +This class check whether the vehicle is stopped or not based on localization result. + +#### Subscribed Topics + +| Name | Type | Description | +| ------------------------------- | ------------------------- | ---------------- | +| `/localization/kinematic_state` | `nav_msgs::msg::Odometry` | vehicle odometry | + +#### Parameters + +| Name | Type | Default Value | Explanation | +| -------------------------- | ------ | ------------- | --------------------------- | +| `velocity_buffer_time_sec` | double | 10.0 | odometry buffering time [s] | + +#### Member functions + +```c++ +bool isVehicleStopped(const double stop_duration) +``` + +- Check simply whether the vehicle is stopped based on the localization result. +- Returns `true` if the vehicle is stopped, even if system outputs a non-zero target velocity. + +#### Example Usage + +Necessary includes: + +```c++ +#include +``` + +1.Create a checker instance. + +```c++ +class SampleNode : public rclcpp::Node +{ +public: + SampleNode() : Node("sample_node") + { + vehicle_stop_checker_ = std::make_unique(this); + } + + std::unique_ptr vehicle_stop_checker_; + + bool sampleFunc(); + + ... +} +``` + +2.Check the vehicle state. + +```c++ + +bool SampleNode::sampleFunc() +{ + ... + + const auto result_1 = vehicle_stop_checker_->isVehicleStopped(); + + ... + + const auto result_2 = vehicle_stop_checker_->isVehicleStopped(3.0); + + ... +} + +``` + +### vehicle_arrival_checker + +This class check whether the vehicle arrive at stop point based on localization and planning result. + +#### Subscribed Topics + +| Name | Type | Description | +| ---------------------------------------- | ---------------------------------------------- | ---------------- | +| `/localization/kinematic_state` | `nav_msgs::msg::Odometry` | vehicle odometry | +| `/planning/scenario_planning/trajectory` | `autoware_auto_planning_msgs::msg::Trajectory` | trajectory | + +#### Parameters + +| Name | Type | Default Value | Explanation | +| -------------------------- | ------ | ------------- | ---------------------------------------------------------------------- | +| `velocity_buffer_time_sec` | double | 10.0 | odometry buffering time [s] | +| `th_arrived_distance_m` | double | 1.0 | threshold distance to check if vehicle has arrived at target point [m] | + +#### Member functions + +```c++ +bool isVehicleStopped(const double stop_duration) +``` + +- Check simply whether the vehicle is stopped based on the localization result. +- Returns `true` if the vehicle is stopped, even if system outputs a non-zero target velocity. + +```c++ +bool isVehicleStoppedAtStopPoint(const double stop_duration) +``` + +- Check whether the vehicle is stopped at stop point based on the localization and planning result. +- Returns `true` if the vehicle is not only stopped but also arrived at stop point. + +#### Example Usage + +Necessary includes: + +```c++ +#include +``` + +1.Create a checker instance. + +```c++ +class SampleNode : public rclcpp::Node +{ +public: + SampleNode() : Node("sample_node") + { + vehicle_arrival_checker_ = std::make_unique(this); + } + + std::unique_ptr vehicle_arrival_checker_; + + bool sampleFunc(); + + ... +} +``` + +2.Check the vehicle state. + +```c++ + +bool SampleNode::sampleFunc1() +{ + ... + + const auto result_1 = vehicle_arrival_checker_->isVehicleStopped(); + + ... + + const auto result_2 = vehicle_arrival_checker_->isVehicleStopped(3.0); + + ... + + const auto result_3 = vehicle_arrival_checker_->isVehicleStoppedAtStopPoint(); + + ... + + const auto result_4 = vehicle_arrival_checker_->isVehicleStoppedAtStopPoint(3.0); + + ... +} +``` + +## Assumptions / Known limits + +`vehicle_stop_checker` and `vehicle_arrival_checker` cannot check whether the vehicle is stopped more than `velocity_buffer_time_sec` second. diff --git a/common/tier4_autoware_utils/include/tier4_autoware_utils/vehicle/vehicle_state_checker.hpp b/common/tier4_autoware_utils/include/tier4_autoware_utils/vehicle/vehicle_state_checker.hpp new file mode 100644 index 000000000000..f71f9474e8b2 --- /dev/null +++ b/common/tier4_autoware_utils/include/tier4_autoware_utils/vehicle/vehicle_state_checker.hpp @@ -0,0 +1,76 @@ +// Copyright 2022 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef TIER4_AUTOWARE_UTILS__VEHICLE__VEHICLE_STATE_CHECKER_HPP_ +#define TIER4_AUTOWARE_UTILS__VEHICLE__VEHICLE_STATE_CHECKER_HPP_ + +#include + +#include +#include +#include + +#include +#include + +namespace tier4_autoware_utils +{ + +using autoware_auto_planning_msgs::msg::Trajectory; +using geometry_msgs::msg::TwistStamped; +using nav_msgs::msg::Odometry; + +class VehicleStopChecker +{ +public: + explicit VehicleStopChecker(rclcpp::Node * node); + + bool isVehicleStopped(const double stop_duration) const; + + rclcpp::Logger getLogger() { return logger_; } + +protected: + rclcpp::Subscription::SharedPtr sub_odom_; + rclcpp::Clock::SharedPtr clock_; + rclcpp::Logger logger_; + + Odometry::SharedPtr odometry_ptr_; + + std::deque twist_buffer_; + +private: + static constexpr double velocity_buffer_time_sec = 10.0; + + void onOdom(const Odometry::SharedPtr msg); +}; + +class VehicleArrivalChecker : public VehicleStopChecker +{ +public: + explicit VehicleArrivalChecker(rclcpp::Node * node); + + bool isVehicleStoppedAtStopPoint(const double stop_duration) const; + +private: + static constexpr double th_arrived_distance_m = 1.0; + + rclcpp::Subscription::SharedPtr sub_trajectory_; + + Trajectory::SharedPtr trajectory_ptr_; + + void onTrajectory(const Trajectory::SharedPtr msg); +}; +} // namespace tier4_autoware_utils + +#endif // TIER4_AUTOWARE_UTILS__VEHICLE__VEHICLE_STATE_CHECKER_HPP_ diff --git a/common/tier4_autoware_utils/package.xml b/common/tier4_autoware_utils/package.xml index 63fd56ae09f8..f3a665bf7a3b 100644 --- a/common/tier4_autoware_utils/package.xml +++ b/common/tier4_autoware_utils/package.xml @@ -13,6 +13,7 @@ autoware_cmake autoware_auto_planning_msgs + autoware_auto_vehicle_msgs builtin_interfaces diagnostic_msgs geometry_msgs diff --git a/common/tier4_autoware_utils/src/vehicle/vehicle_state_checker.cpp b/common/tier4_autoware_utils/src/vehicle/vehicle_state_checker.cpp new file mode 100644 index 000000000000..4e6335469f54 --- /dev/null +++ b/common/tier4_autoware_utils/src/vehicle/vehicle_state_checker.cpp @@ -0,0 +1,118 @@ +// Copyright 2022 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "tier4_autoware_utils/vehicle/vehicle_state_checker.hpp" + +#include "tier4_autoware_utils/trajectory/trajectory.hpp" + +#include + +namespace tier4_autoware_utils +{ +VehicleStopChecker::VehicleStopChecker(rclcpp::Node * node) +: clock_(node->get_clock()), logger_(node->get_logger()) +{ + using std::placeholders::_1; + + sub_odom_ = node->create_subscription( + "/localization/kinematic_state", rclcpp::QoS(1), + std::bind(&VehicleStopChecker::onOdom, this, _1)); +} + +bool VehicleStopChecker::isVehicleStopped(const double stop_duration = 0.0) const +{ + if (twist_buffer_.empty()) { + return false; + } + + constexpr double stop_velocity = 1e-3; + const auto now = clock_->now(); + + const auto time_buffer_back = now - twist_buffer_.back().header.stamp; + if (time_buffer_back.seconds() < stop_duration) { + return false; + } + + // Get velocities within stop_duration + for (const auto & velocity : twist_buffer_) { + if (stop_velocity <= velocity.twist.linear.x) { + return false; + } + + const auto time_diff = now - velocity.header.stamp; + if (time_diff.seconds() >= stop_duration) { + break; + } + } + + return true; +} + +void VehicleStopChecker::onOdom(const Odometry::SharedPtr msg) +{ + odometry_ptr_ = msg; + + auto current_velocity = std::make_shared(); + current_velocity->header = msg->header; + current_velocity->twist = msg->twist.twist; + + twist_buffer_.push_front(*current_velocity); + + const auto now = clock_->now(); + while (true) { + // Check oldest data time + const auto time_diff = now - twist_buffer_.back().header.stamp; + + // Finish when oldest data is newer than threshold + if (time_diff.seconds() <= velocity_buffer_time_sec) { + break; + } + + // Remove old data + twist_buffer_.pop_back(); + } +} + +VehicleArrivalChecker::VehicleArrivalChecker(rclcpp::Node * node) : VehicleStopChecker(node) +{ + using std::placeholders::_1; + + sub_trajectory_ = node->create_subscription( + "/planning/scenario_planning/trajectory", rclcpp::QoS(1), + std::bind(&VehicleArrivalChecker::onTrajectory, this, _1)); +} + +bool VehicleArrivalChecker::isVehicleStoppedAtStopPoint(const double stop_duration = 0.0) const +{ + if (!odometry_ptr_ || !trajectory_ptr_) { + return false; + } + + if (!isVehicleStopped(stop_duration)) { + return false; + } + + const auto & p = odometry_ptr_->pose.pose.position; + const auto idx = searchZeroVelocityIndex(trajectory_ptr_->points); + + if (!idx) { + return false; + } + + return std::abs(calcSignedArcLength(trajectory_ptr_->points, p, idx.get())) < + th_arrived_distance_m; +} + +void VehicleArrivalChecker::onTrajectory(const Trajectory::SharedPtr msg) { trajectory_ptr_ = msg; } +} // namespace tier4_autoware_utils diff --git a/common/tier4_autoware_utils/test/src/test_autoware_utils.cpp b/common/tier4_autoware_utils/test/src/test_autoware_utils.cpp index c2c4bc4e5fbb..34018ed73000 100644 --- a/common/tier4_autoware_utils/test/src/test_autoware_utils.cpp +++ b/common/tier4_autoware_utils/test/src/test_autoware_utils.cpp @@ -19,5 +19,8 @@ int main(int argc, char * argv[]) { testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); + rclcpp::init(argc, argv); + bool result = RUN_ALL_TESTS(); + rclcpp::shutdown(); + return result; } diff --git a/common/tier4_autoware_utils/test/src/vehicle/test_vehicle_state_checker.cpp b/common/tier4_autoware_utils/test/src/vehicle/test_vehicle_state_checker.cpp new file mode 100644 index 000000000000..ca5815f67dff --- /dev/null +++ b/common/tier4_autoware_utils/test/src/vehicle/test_vehicle_state_checker.cpp @@ -0,0 +1,468 @@ +// Copyright 2022 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "test_vehicle_state_checker_helper.hpp" +#include "tier4_autoware_utils/geometry/geometry.hpp" +#include "tier4_autoware_utils/vehicle/vehicle_state_checker.hpp" + +#include + +#include + +#include +#include + +constexpr double ODOMETRY_HISTORY_500_MS = 0.5; +constexpr double ODOMETRY_HISTORY_1000_MS = 1.0; +constexpr double STOP_DURATION_THRESHOLD_0_MS = 0.0; +constexpr double STOP_DURATION_THRESHOLD_200_MS = 0.2; +constexpr double STOP_DURATION_THRESHOLD_400_MS = 0.4; +constexpr double STOP_DURATION_THRESHOLD_600_MS = 0.6; +constexpr double STOP_DURATION_THRESHOLD_800_MS = 0.8; +constexpr double STOP_DURATION_THRESHOLD_1000_MS = 1.0; + +using nav_msgs::msg::Odometry; +using tier4_autoware_utils::createPoint; +using tier4_autoware_utils::createQuaternion; +using tier4_autoware_utils::createTranslation; +using tier4_autoware_utils::VehicleArrivalChecker; +using tier4_autoware_utils::VehicleStopChecker; + +class CheckerNode : public rclcpp::Node +{ +public: + CheckerNode() : Node("test_checker_node") + { + vehicle_stop_checker_ = std::make_unique(this); + vehicle_arrival_checker_ = std::make_unique(this); + } + + std::unique_ptr vehicle_stop_checker_; + std::unique_ptr vehicle_arrival_checker_; +}; + +class PubManager : public rclcpp::Node +{ +public: + PubManager() : Node("test_pub_node") + { + pub_odom_ = create_publisher("/localization/kinematic_state", 1); + pub_traj_ = create_publisher("/planning/scenario_planning/trajectory", 1); + } + + rclcpp::Publisher::SharedPtr pub_odom_; + rclcpp::Publisher::SharedPtr pub_traj_; + + void publishStoppedOdometry(const geometry_msgs::msg::Pose & pose, const double publish_duration) + { + const auto start_time = this->now(); + while (true) { + const auto now = this->now(); + + const auto time_diff = now - start_time; + if (publish_duration < time_diff.seconds()) { + break; + } + + Odometry odometry; + odometry.header.stamp = now; + odometry.pose.pose = pose; + odometry.twist.twist.linear = createTranslation(0.0, 0.0, 0.0); + odometry.twist.twist.angular = createTranslation(0.0, 0.0, 0.0); + this->pub_odom_->publish(odometry); + + rclcpp::WallRate(10).sleep(); + } + } + + void publishStoppedOdometry(const double publish_duration) + { + const auto start_time = this->now(); + while (true) { + const auto now = this->now(); + + const auto time_diff = now - start_time; + if (publish_duration < time_diff.seconds()) { + break; + } + + Odometry odometry; + odometry.header.stamp = now; + odometry.pose.pose.position = createPoint(0.0, 0.0, 0.0); + odometry.pose.pose.orientation = createQuaternion(0.0, 0.0, 0.0, 1.0); + odometry.twist.twist.linear = createTranslation(0.0, 0.0, 0.0); + odometry.twist.twist.angular = createTranslation(0.0, 0.0, 0.0); + this->pub_odom_->publish(odometry); + + rclcpp::WallRate(10).sleep(); + } + } + + void publishStoppingOdometry(const double publish_duration) + { + const auto start_time = this->now(); + while (true) { + const auto now = this->now(); + + const auto time_diff = now - start_time; + if (publish_duration < time_diff.seconds()) { + break; + } + + Odometry odometry; + odometry.header.stamp = now; + odometry.pose.pose.position = createPoint(0.0, 0.0, 0.0); + odometry.pose.pose.orientation = createQuaternion(0.0, 0.0, 0.0, 1.0); + odometry.twist.twist.linear = time_diff.seconds() < publish_duration / 2.0 + ? createTranslation(1.0, 0.0, 0.0) + : createTranslation(0.0, 0.0, 0.0); + odometry.twist.twist.angular = createTranslation(0.0, 0.0, 0.0); + this->pub_odom_->publish(odometry); + + rclcpp::WallRate(10).sleep(); + } + } +}; + +TEST(vehicle_stop_checker, isVehicleStopped) +{ + { + auto checker = std::make_shared(); + auto manager = std::make_shared(); + EXPECT_GE(manager->pub_odom_->get_subscription_count(), 1U) << "topic is not connected."; + + EXPECT_FALSE(checker->vehicle_stop_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_0_MS)); + + rclcpp::executors::SingleThreadedExecutor executor; + executor.add_node(checker); + executor.add_node(manager); + + std::thread spin_thread = + std::thread(std::bind(&rclcpp::executors::SingleThreadedExecutor::spin, &executor)); + + manager->publishStoppedOdometry(ODOMETRY_HISTORY_500_MS); + + EXPECT_TRUE(checker->vehicle_stop_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_0_MS)); + EXPECT_TRUE(checker->vehicle_stop_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_200_MS)); + EXPECT_TRUE(checker->vehicle_stop_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_400_MS)); + EXPECT_FALSE(checker->vehicle_stop_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_600_MS)); + EXPECT_FALSE(checker->vehicle_stop_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_800_MS)); + EXPECT_FALSE(checker->vehicle_stop_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_1000_MS)); + + executor.cancel(); + spin_thread.join(); + checker.reset(); + manager.reset(); + } + + { + auto checker = std::make_shared(); + auto manager = std::make_shared(); + EXPECT_GE(manager->pub_odom_->get_subscription_count(), 1U) << "topic is not connected."; + + EXPECT_FALSE(checker->vehicle_stop_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_0_MS)); + + rclcpp::executors::SingleThreadedExecutor executor; + executor.add_node(checker); + executor.add_node(manager); + + std::thread spin_thread = + std::thread(std::bind(&rclcpp::executors::SingleThreadedExecutor::spin, &executor)); + + manager->publishStoppedOdometry(ODOMETRY_HISTORY_1000_MS); + + EXPECT_TRUE(checker->vehicle_stop_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_0_MS)); + EXPECT_TRUE(checker->vehicle_stop_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_200_MS)); + EXPECT_TRUE(checker->vehicle_stop_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_400_MS)); + EXPECT_TRUE(checker->vehicle_stop_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_600_MS)); + EXPECT_TRUE(checker->vehicle_stop_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_800_MS)); + EXPECT_TRUE(checker->vehicle_stop_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_1000_MS)); + + executor.cancel(); + spin_thread.join(); + checker.reset(); + manager.reset(); + } + + { + auto checker = std::make_shared(); + auto manager = std::make_shared(); + EXPECT_GE(manager->pub_odom_->get_subscription_count(), 1U) << "topic is not connected."; + + EXPECT_FALSE(checker->vehicle_stop_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_0_MS)); + + rclcpp::executors::SingleThreadedExecutor executor; + executor.add_node(checker); + executor.add_node(manager); + + std::thread spin_thread = + std::thread(std::bind(&rclcpp::executors::SingleThreadedExecutor::spin, &executor)); + + manager->publishStoppingOdometry(ODOMETRY_HISTORY_1000_MS); + + EXPECT_TRUE(checker->vehicle_stop_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_0_MS)); + EXPECT_TRUE(checker->vehicle_stop_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_200_MS)); + EXPECT_TRUE(checker->vehicle_stop_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_400_MS)); + EXPECT_FALSE(checker->vehicle_stop_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_600_MS)); + EXPECT_FALSE(checker->vehicle_stop_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_800_MS)); + EXPECT_FALSE(checker->vehicle_stop_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_1000_MS)); + + executor.cancel(); + spin_thread.join(); + checker.reset(); + manager.reset(); + } +} + +TEST(vehicle_arrival_checker, isVehicleStopped) +{ + { + auto checker = std::make_shared(); + auto manager = std::make_shared(); + EXPECT_GE(manager->pub_odom_->get_subscription_count(), 1U) << "topic is not connected."; + + EXPECT_FALSE(checker->vehicle_arrival_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_0_MS)); + + rclcpp::executors::SingleThreadedExecutor executor; + executor.add_node(checker); + executor.add_node(manager); + + std::thread spin_thread = + std::thread(std::bind(&rclcpp::executors::SingleThreadedExecutor::spin, &executor)); + + manager->publishStoppedOdometry(ODOMETRY_HISTORY_500_MS); + + EXPECT_TRUE(checker->vehicle_arrival_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_0_MS)); + EXPECT_TRUE( + checker->vehicle_arrival_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_200_MS)); + EXPECT_TRUE( + checker->vehicle_arrival_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_400_MS)); + EXPECT_FALSE( + checker->vehicle_arrival_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_600_MS)); + EXPECT_FALSE( + checker->vehicle_arrival_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_800_MS)); + EXPECT_FALSE( + checker->vehicle_arrival_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_1000_MS)); + + executor.cancel(); + spin_thread.join(); + checker.reset(); + manager.reset(); + } + + { + auto checker = std::make_shared(); + auto manager = std::make_shared(); + EXPECT_GE(manager->pub_odom_->get_subscription_count(), 1U) << "topic is not connected."; + + EXPECT_FALSE(checker->vehicle_arrival_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_0_MS)); + + rclcpp::executors::SingleThreadedExecutor executor; + executor.add_node(checker); + executor.add_node(manager); + + std::thread spin_thread = + std::thread(std::bind(&rclcpp::executors::SingleThreadedExecutor::spin, &executor)); + + manager->publishStoppedOdometry(ODOMETRY_HISTORY_1000_MS); + + EXPECT_TRUE(checker->vehicle_arrival_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_0_MS)); + EXPECT_TRUE( + checker->vehicle_arrival_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_200_MS)); + EXPECT_TRUE( + checker->vehicle_arrival_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_400_MS)); + EXPECT_TRUE( + checker->vehicle_arrival_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_600_MS)); + EXPECT_TRUE( + checker->vehicle_arrival_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_800_MS)); + EXPECT_TRUE( + checker->vehicle_arrival_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_1000_MS)); + + executor.cancel(); + spin_thread.join(); + checker.reset(); + manager.reset(); + } + + { + auto checker = std::make_shared(); + auto manager = std::make_shared(); + EXPECT_GE(manager->pub_odom_->get_subscription_count(), 1U) << "topic is not connected."; + + EXPECT_FALSE(checker->vehicle_arrival_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_0_MS)); + + rclcpp::executors::SingleThreadedExecutor executor; + executor.add_node(checker); + executor.add_node(manager); + + std::thread spin_thread = + std::thread(std::bind(&rclcpp::executors::SingleThreadedExecutor::spin, &executor)); + + manager->publishStoppingOdometry(ODOMETRY_HISTORY_1000_MS); + + EXPECT_TRUE(checker->vehicle_arrival_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_0_MS)); + EXPECT_TRUE( + checker->vehicle_arrival_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_200_MS)); + EXPECT_TRUE( + checker->vehicle_arrival_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_400_MS)); + EXPECT_FALSE( + checker->vehicle_arrival_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_600_MS)); + EXPECT_FALSE( + checker->vehicle_arrival_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_800_MS)); + EXPECT_FALSE( + checker->vehicle_arrival_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_1000_MS)); + + executor.cancel(); + spin_thread.join(); + checker.reset(); + manager.reset(); + } +} + +TEST(vehicle_arrival_checker, isVehicleStoppedAtStopPoint) +{ + { + auto checker = std::make_shared(); + auto manager = std::make_shared(); + EXPECT_GE(manager->pub_odom_->get_subscription_count(), 1U) << "topic is not connected."; + + EXPECT_FALSE(checker->vehicle_arrival_checker_->isVehicleStopped(STOP_DURATION_THRESHOLD_0_MS)); + + rclcpp::executors::SingleThreadedExecutor executor; + executor.add_node(checker); + executor.add_node(manager); + + std::thread spin_thread = + std::thread(std::bind(&rclcpp::executors::SingleThreadedExecutor::spin, &executor)); + + geometry_msgs::msg::Pose odom_pose; + odom_pose.position = createPoint(10.0, 0.0, 0.0); + odom_pose.orientation = createQuaternion(0.0, 0.0, 0.0, 1.0); + + geometry_msgs::msg::Pose goal_pose; + goal_pose.position = createPoint(10.0, 0.0, 0.0); + goal_pose.orientation = createQuaternion(0.0, 0.0, 0.0, 1.0); + + manager->pub_traj_->publish(generateTrajectoryWithStopPoint(goal_pose)); + manager->publishStoppedOdometry(odom_pose, ODOMETRY_HISTORY_500_MS); + + EXPECT_TRUE( + checker->vehicle_arrival_checker_->isVehicleStoppedAtStopPoint(STOP_DURATION_THRESHOLD_0_MS)); + EXPECT_TRUE(checker->vehicle_arrival_checker_->isVehicleStoppedAtStopPoint( + STOP_DURATION_THRESHOLD_200_MS)); + EXPECT_TRUE(checker->vehicle_arrival_checker_->isVehicleStoppedAtStopPoint( + STOP_DURATION_THRESHOLD_400_MS)); + EXPECT_FALSE(checker->vehicle_arrival_checker_->isVehicleStoppedAtStopPoint( + STOP_DURATION_THRESHOLD_600_MS)); + EXPECT_FALSE(checker->vehicle_arrival_checker_->isVehicleStoppedAtStopPoint( + STOP_DURATION_THRESHOLD_800_MS)); + EXPECT_FALSE(checker->vehicle_arrival_checker_->isVehicleStoppedAtStopPoint( + STOP_DURATION_THRESHOLD_1000_MS)); + + executor.cancel(); + spin_thread.join(); + checker.reset(); + manager.reset(); + } + + { + auto checker = std::make_shared(); + auto manager = std::make_shared(); + EXPECT_GE(manager->pub_odom_->get_subscription_count(), 1U) << "topic is not connected."; + + EXPECT_FALSE( + checker->vehicle_arrival_checker_->isVehicleStoppedAtStopPoint(STOP_DURATION_THRESHOLD_0_MS)); + + rclcpp::executors::SingleThreadedExecutor executor; + executor.add_node(checker); + executor.add_node(manager); + + std::thread spin_thread = + std::thread(std::bind(&rclcpp::executors::SingleThreadedExecutor::spin, &executor)); + + geometry_msgs::msg::Pose odom_pose; + odom_pose.position = createPoint(0.0, 0.0, 0.0); + odom_pose.orientation = createQuaternion(0.0, 0.0, 0.0, 1.0); + + geometry_msgs::msg::Pose goal_pose; + goal_pose.position = createPoint(10.0, 0.0, 0.0); + goal_pose.orientation = createQuaternion(0.0, 0.0, 0.0, 1.0); + + manager->pub_traj_->publish(generateTrajectoryWithStopPoint(goal_pose)); + manager->publishStoppedOdometry(odom_pose, ODOMETRY_HISTORY_500_MS); + + EXPECT_FALSE( + checker->vehicle_arrival_checker_->isVehicleStoppedAtStopPoint(STOP_DURATION_THRESHOLD_0_MS)); + EXPECT_FALSE(checker->vehicle_arrival_checker_->isVehicleStoppedAtStopPoint( + STOP_DURATION_THRESHOLD_200_MS)); + EXPECT_FALSE(checker->vehicle_arrival_checker_->isVehicleStoppedAtStopPoint( + STOP_DURATION_THRESHOLD_400_MS)); + EXPECT_FALSE(checker->vehicle_arrival_checker_->isVehicleStoppedAtStopPoint( + STOP_DURATION_THRESHOLD_600_MS)); + EXPECT_FALSE(checker->vehicle_arrival_checker_->isVehicleStoppedAtStopPoint( + STOP_DURATION_THRESHOLD_800_MS)); + EXPECT_FALSE(checker->vehicle_arrival_checker_->isVehicleStoppedAtStopPoint( + STOP_DURATION_THRESHOLD_1000_MS)); + + executor.cancel(); + spin_thread.join(); + checker.reset(); + manager.reset(); + } + + { + auto checker = std::make_shared(); + auto manager = std::make_shared(); + EXPECT_GE(manager->pub_odom_->get_subscription_count(), 1U) << "topic is not connected."; + + EXPECT_FALSE( + checker->vehicle_arrival_checker_->isVehicleStoppedAtStopPoint(STOP_DURATION_THRESHOLD_0_MS)); + + rclcpp::executors::SingleThreadedExecutor executor; + executor.add_node(checker); + executor.add_node(manager); + + std::thread spin_thread = + std::thread(std::bind(&rclcpp::executors::SingleThreadedExecutor::spin, &executor)); + + geometry_msgs::msg::Pose odom_pose; + odom_pose.position = createPoint(10.0, 0.0, 0.0); + odom_pose.orientation = createQuaternion(0.0, 0.0, 0.0, 1.0); + + geometry_msgs::msg::Pose goal_pose; + goal_pose.position = createPoint(10.0, 0.0, 0.0); + goal_pose.orientation = createQuaternion(0.0, 0.0, 0.0, 1.0); + + manager->pub_traj_->publish(generateTrajectoryWithoutStopPoint(goal_pose)); + manager->publishStoppedOdometry(odom_pose, ODOMETRY_HISTORY_500_MS); + + EXPECT_FALSE( + checker->vehicle_arrival_checker_->isVehicleStoppedAtStopPoint(STOP_DURATION_THRESHOLD_0_MS)); + EXPECT_FALSE(checker->vehicle_arrival_checker_->isVehicleStoppedAtStopPoint( + STOP_DURATION_THRESHOLD_200_MS)); + EXPECT_FALSE(checker->vehicle_arrival_checker_->isVehicleStoppedAtStopPoint( + STOP_DURATION_THRESHOLD_400_MS)); + EXPECT_FALSE(checker->vehicle_arrival_checker_->isVehicleStoppedAtStopPoint( + STOP_DURATION_THRESHOLD_600_MS)); + EXPECT_FALSE(checker->vehicle_arrival_checker_->isVehicleStoppedAtStopPoint( + STOP_DURATION_THRESHOLD_800_MS)); + EXPECT_FALSE(checker->vehicle_arrival_checker_->isVehicleStoppedAtStopPoint( + STOP_DURATION_THRESHOLD_1000_MS)); + + executor.cancel(); + spin_thread.join(); + checker.reset(); + manager.reset(); + } +} diff --git a/common/tier4_autoware_utils/test/src/vehicle/test_vehicle_state_checker_helper.hpp b/common/tier4_autoware_utils/test/src/vehicle/test_vehicle_state_checker_helper.hpp new file mode 100644 index 000000000000..aa26a64cb87c --- /dev/null +++ b/common/tier4_autoware_utils/test/src/vehicle/test_vehicle_state_checker_helper.hpp @@ -0,0 +1,59 @@ +// Copyright 2022 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef VEHICLE__TEST_VEHICLE_STATE_CHECKER_HELPER_HPP_ +#define VEHICLE__TEST_VEHICLE_STATE_CHECKER_HELPER_HPP_ + +#include +#include + +using autoware_auto_planning_msgs::msg::Trajectory; +using autoware_auto_planning_msgs::msg::TrajectoryPoint; + +inline Trajectory generateTrajectoryWithStopPoint(const geometry_msgs::msg::Pose & goal_pose) +{ + constexpr double interval_distance = 1.0; + + Trajectory traj; + for (double s = 0.0; s <= 10.0 * interval_distance; s += interval_distance) { + TrajectoryPoint p; + p.pose = goal_pose; + p.pose.position.x += s; + p.longitudinal_velocity_mps = 1.0; + traj.points.push_back(p); + } + + traj.points.front().longitudinal_velocity_mps = 0.0; + std::reverse(traj.points.begin(), traj.points.end()); + return traj; +} + +inline Trajectory generateTrajectoryWithoutStopPoint(const geometry_msgs::msg::Pose & goal_pose) +{ + constexpr double interval_distance = 1.0; + + Trajectory traj; + for (double s = 0.0; s <= 10.0 * interval_distance; s += interval_distance) { + TrajectoryPoint p; + p.pose = goal_pose; + p.pose.position.x += s; + p.longitudinal_velocity_mps = 1.0; + traj.points.push_back(p); + } + + std::reverse(traj.points.begin(), traj.points.end()); + return traj; +} + +#endif // VEHICLE__TEST_VEHICLE_STATE_CHECKER_HELPER_HPP_ From 584d55714dbc09795af453bba83ae915c2f16fc3 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 19 May 2022 23:01:21 +0900 Subject: [PATCH 41/55] fix(motion_velocity_smoother): fix overwriteStopPoint using backward point (#816) * fix(motion_velocity_smoother): fix overwriteStopPoint using backward point Signed-off-by: kosuke55 * Modify overwriteStopPoint input and output Signed-off-by: kosuke55 --- .../src/motion_velocity_smoother_node.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/planning/motion_velocity_smoother/src/motion_velocity_smoother_node.cpp b/planning/motion_velocity_smoother/src/motion_velocity_smoother_node.cpp index 912f8129da73..cb51e52254bb 100644 --- a/planning/motion_velocity_smoother/src/motion_velocity_smoother_node.cpp +++ b/planning/motion_velocity_smoother/src/motion_velocity_smoother_node.cpp @@ -545,13 +545,13 @@ bool MotionVelocitySmootherNode::smoothVelocity( RCLCPP_WARN(get_logger(), "Fail to solve optimization."); } + // Set 0 velocity after input-stop-point + overwriteStopPoint(clipped, traj_smoothed); + traj_smoothed.insert( traj_smoothed.begin(), traj_resampled->begin(), traj_resampled->begin() + *traj_resampled_closest); - // Set 0 velocity after input-stop-point - overwriteStopPoint(*traj_resampled, traj_smoothed); - // For the endpoint of the trajectory if (!traj_smoothed.empty()) { traj_smoothed.back().longitudinal_velocity_mps = 0.0; From e24a4756bb628a6a6c44059aeacf8172e7dec9a2 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 19 May 2022 23:37:04 +0900 Subject: [PATCH 42/55] feat(obstacle_avoidance_planner): explicitly insert zero velocity (#906) * feat(obstacle_avoidance_planner) fix bug of stop line unalignment Signed-off-by: Takayuki Murooka * fix bug of unsorted output points Signed-off-by: Takayuki Murooka * move calcVelocity in node.cpp Signed-off-by: Takayuki Murooka * fix build error Signed-off-by: Takayuki Murooka --- .../eb_path_optimizer.hpp | 1 - .../mpt_optimizer.hpp | 7 -- .../obstacle_avoidance_planner/node.hpp | 55 ++++++++- .../src/eb_path_optimizer.cpp | 8 +- .../src/mpt_optimizer.cpp | 17 --- .../obstacle_avoidance_planner/src/node.cpp | 112 ++++++++++++++++-- 6 files changed, 158 insertions(+), 42 deletions(-) diff --git a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/eb_path_optimizer.hpp b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/eb_path_optimizer.hpp index 31c9943b4588..a2f70cefc9e4 100644 --- a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/eb_path_optimizer.hpp +++ b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/eb_path_optimizer.hpp @@ -46,7 +46,6 @@ class EBPathOptimizer struct Anchor { geometry_msgs::msg::Pose pose; - double velocity; }; struct ConstrainRectangles diff --git a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/mpt_optimizer.hpp b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/mpt_optimizer.hpp index 046b907268e0..be36be812a09 100644 --- a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/mpt_optimizer.hpp +++ b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/mpt_optimizer.hpp @@ -231,13 +231,6 @@ class MPTOptimizer void calcOrientation(std::vector & ref_points) const; - void calcVelocity(std::vector & ref_points) const; - - void calcVelocity( - std::vector & ref_points, - const std::vector & points, - const double yaw_thresh) const; - void calcCurvature(std::vector & ref_points) const; void calcArcLength(std::vector & ref_points) const; diff --git a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp index d93cc890054a..7d32ce73d40e 100644 --- a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp +++ b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp @@ -42,11 +42,53 @@ #include "boost/optional.hpp" +#include #include #include namespace { +template +boost::optional lerpPose( + const T & points, const geometry_msgs::msg::Point & target_pos, const size_t closest_seg_idx) +{ + constexpr double epsilon = 1e-6; + + const double closest_to_target_dist = + tier4_autoware_utils::calcSignedArcLength(points, closest_seg_idx, target_pos); + const double seg_dist = + tier4_autoware_utils::calcSignedArcLength(points, closest_seg_idx, closest_seg_idx + 1); + + const auto & closest_pose = points[closest_seg_idx].pose; + const auto & next_pose = points[closest_seg_idx + 1].pose; + + geometry_msgs::msg::Pose interpolated_pose; + if (std::abs(seg_dist) < epsilon) { + interpolated_pose.position.x = next_pose.position.x; + interpolated_pose.position.y = next_pose.position.y; + interpolated_pose.position.z = next_pose.position.z; + interpolated_pose.orientation = next_pose.orientation; + } else { + const double ratio = closest_to_target_dist / seg_dist; + if (ratio < 0 || 1 < ratio) { + return {}; + } + + interpolated_pose.position.x = + interpolation::lerp(closest_pose.position.x, next_pose.position.x, ratio); + interpolated_pose.position.y = + interpolation::lerp(closest_pose.position.y, next_pose.position.y, ratio); + interpolated_pose.position.z = + interpolation::lerp(closest_pose.position.z, next_pose.position.z, ratio); + + const double closest_yaw = tf2::getYaw(closest_pose.orientation); + const double next_yaw = tf2::getYaw(next_pose.orientation); + const double interpolated_yaw = interpolation::lerp(closest_yaw, next_yaw, ratio); + interpolated_pose.orientation = tier4_autoware_utils::createQuaternionFromYaw(interpolated_yaw); + } + return interpolated_pose; +} + template double lerpTwistX( const T & points, const geometry_msgs::msg::Point & target_pos, const size_t closest_seg_idx) @@ -65,9 +107,12 @@ double lerpTwistX( const double closest_vel = points[closest_seg_idx].longitudinal_velocity_mps; const double next_vel = points[closest_seg_idx + 1].longitudinal_velocity_mps; - return std::abs(seg_dist) < epsilon - ? next_vel - : interpolation::lerp(closest_vel, next_vel, closest_to_target_dist / seg_dist); + if (std::abs(seg_dist) < epsilon) { + return next_vel; + } + + const double ratio = std::min(1.0, std::max(0.0, closest_to_target_dist / seg_dist)); + return interpolation::lerp(closest_vel, next_vel, ratio); } template @@ -212,6 +257,10 @@ class ObstacleAvoidancePlanner : public rclcpp::Node Trajectories getPrevTrajs( const std::vector & path_points) const; + void calcVelocity( + const std::vector & path_points, + std::vector & traj_points) const; + void insertZeroVelocityOutsideDrivableArea( std::vector & traj_points, const CVMaps & cv_maps); diff --git a/planning/obstacle_avoidance_planner/src/eb_path_optimizer.cpp b/planning/obstacle_avoidance_planner/src/eb_path_optimizer.cpp index 6743bc7884e1..0633877a0e4d 100644 --- a/planning/obstacle_avoidance_planner/src/eb_path_optimizer.cpp +++ b/planning/obstacle_avoidance_planner/src/eb_path_optimizer.cpp @@ -354,15 +354,14 @@ int EBPathOptimizer::getNumFixedPoints( std::vector EBPathOptimizer::convertOptimizedPointsToTrajectory( - const std::vector optimized_points, const std::vector & constraints, - const int farthest_idx) + const std::vector optimized_points, + [[maybe_unused]] const std::vector & constraints, const int farthest_idx) { std::vector traj_points; for (int i = 0; i <= farthest_idx; i++) { autoware_auto_planning_msgs::msg::TrajectoryPoint tmp_point; tmp_point.pose.position.x = optimized_points[i]; tmp_point.pose.position.y = optimized_points[i + eb_param_.num_sampling_points_for_eb]; - tmp_point.longitudinal_velocity_mps = constraints[i].velocity; traj_points.push_back(tmp_point); } for (size_t i = 0; i < traj_points.size(); i++) { @@ -462,7 +461,6 @@ EBPathOptimizer::Anchor EBPathOptimizer::getAnchor( Anchor anchor; anchor.pose.position = interpolated_points[interpolated_idx]; anchor.pose.orientation = nearest_q; - anchor.velocity = path_points[nearest_idx].longitudinal_velocity_mps; return anchor; } @@ -595,7 +593,6 @@ ConstrainRectangle EBPathOptimizer::getConstrainRectangle( bottom_right.y = -1 * clearance; constrain_range.bottom_right = geometry_utils::transformToAbsoluteCoordinate2D(bottom_right, anchor.pose); - constrain_range.velocity = anchor.velocity; return constrain_range; } @@ -608,6 +605,5 @@ ConstrainRectangle EBPathOptimizer::getConstrainRectangle( rect.top_right = tier4_autoware_utils::calcOffsetPose(anchor.pose, max_x, min_y, 0.0).position; rect.bottom_left = tier4_autoware_utils::calcOffsetPose(anchor.pose, min_x, max_y, 0.0).position; rect.bottom_right = tier4_autoware_utils::calcOffsetPose(anchor.pose, min_x, min_y, 0.0).position; - rect.velocity = anchor.velocity; return rect; } diff --git a/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp b/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp index c8a6840f67d2..ec06ae4bd39f 100644 --- a/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp +++ b/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp @@ -338,7 +338,6 @@ std::vector MPTOptimizer::getReferencePoints( // set some information to reference points considering fix kinematics trimPoints(ref_points); calcOrientation(ref_points); - calcVelocity(ref_points, smoothed_points, traj_param_.delta_yaw_threshold_for_closest_point); calcCurvature(ref_points); calcArcLength(ref_points); calcPlanningFromEgo( @@ -1146,7 +1145,6 @@ std::vector MPTOptimizer::get autoware_auto_planning_msgs::msg::TrajectoryPoint traj_point; traj_point.pose = calcVehiclePose(ref_point, lat_error, yaw_error, 0.0); - traj_point.longitudinal_velocity_mps = ref_point.v; traj_points.push_back(traj_point); { // for debug visualization @@ -1217,21 +1215,6 @@ void MPTOptimizer::calcOrientation(std::vector & ref_points) con } } -void MPTOptimizer::calcVelocity( - std::vector & ref_points, - const std::vector & points, - const double yaw_thresh) const -{ - const auto ref_points_with_yaw = - points_utils::convertToPosesWithYawEstimation(points_utils::convertToPoints(ref_points)); - for (size_t i = 0; i < ref_points.size(); i++) { - ref_points.at(i).v = - points[findNearestIndexWithSoftYawConstraints( - points_utils::convertToPoints(points), ref_points_with_yaw.at(i), yaw_thresh)] - .longitudinal_velocity_mps; - } -} - void MPTOptimizer::calcCurvature(std::vector & ref_points) const { const size_t num_points = static_cast(ref_points.size()); diff --git a/planning/obstacle_avoidance_planner/src/node.cpp b/planning/obstacle_avoidance_planner/src/node.cpp index 36c1834f9d27..84894e1615e1 100644 --- a/planning/obstacle_avoidance_planner/src/node.cpp +++ b/planning/obstacle_avoidance_planner/src/node.cpp @@ -175,6 +175,18 @@ std::tuple> calcVehicleCirclesInfo( } } +size_t findNearestIndexWithSoftYawConstraints( + const std::vector & points, const geometry_msgs::msg::Pose & pose, + const double yaw_threshold) +{ + const auto points_with_yaw = points_utils::convertToPosesWithYawEstimation(points); + + const auto nearest_idx_optional = tier4_autoware_utils::findNearestIndex( + points_with_yaw, pose, std::numeric_limits::max(), yaw_threshold); + return nearest_idx_optional + ? *nearest_idx_optional + : tier4_autoware_utils::findNearestIndex(points_with_yaw, pose.position); +} } // namespace ObstacleAvoidancePlanner::ObstacleAvoidancePlanner(const rclcpp::NodeOptions & node_options) @@ -927,6 +939,10 @@ ObstacleAvoidancePlanner::generateOptimizedTrajectory( // calculate trajectory with EB and MPT auto optimal_trajs = optimizeTrajectory(path, cv_maps); + // calculate velocity + // NOTE: Velocity is not considered in optimization. + calcVelocity(path.points, optimal_trajs.model_predictive_trajectory); + // insert 0 velocity when trajectory is over drivable area if (is_stopping_if_outside_drivable_area_) { insertZeroVelocityOutsideDrivableArea(optimal_trajs.model_predictive_trajectory, cv_maps); @@ -1076,6 +1092,40 @@ Trajectories ObstacleAvoidancePlanner::getPrevTrajs( return trajs; } +void ObstacleAvoidancePlanner::calcVelocity( + const std::vector & path_points, + std::vector & traj_points) const +{ + for (size_t i = 0; i < traj_points.size(); i++) { + const size_t nearest_path_idx = findNearestIndexWithSoftYawConstraints( + points_utils::convertToPoints(path_points), traj_points.at(i).pose, + traj_param_.delta_yaw_threshold_for_closest_point); + const size_t second_nearest_path_idx = [&]() -> size_t { + if (nearest_path_idx == 0) { + return 1; + } else if (nearest_path_idx == path_points.size() - 1) { + return path_points.size() - 2; + } + + const double prev_dist = tier4_autoware_utils::calcDistance2d( + traj_points.at(i), path_points.at(nearest_path_idx - 1)); + const double next_dist = tier4_autoware_utils::calcDistance2d( + traj_points.at(i), path_points.at(nearest_path_idx + 1)); + if (prev_dist < next_dist) { + return nearest_path_idx - 1; + } + return nearest_path_idx + 1; + }(); + + // NOTE: std::max, not std::min, is used here since traj_points' sampling width may be longer + // than path_points' sampling width. A zero velocity point is guaranteed to be inserted in an + // output trajectory in the alignVelocity function + traj_points.at(i).longitudinal_velocity_mps = std::max( + path_points.at(nearest_path_idx).longitudinal_velocity_mps, + path_points.at(second_nearest_path_idx).longitudinal_velocity_mps); + } +} + void ObstacleAvoidancePlanner::insertZeroVelocityOutsideDrivableArea( std::vector & traj_points, const CVMaps & cv_maps) @@ -1373,16 +1423,65 @@ ObstacleAvoidancePlanner::alignVelocity( { stop_watch_.tic(__func__); + // insert zero velocity path index, and get optional zero_vel_path_idx + const auto path_zero_vel_info = [&]() + -> std::pair< + std::vector, boost::optional> { + const auto opt_path_zero_vel_idx = tier4_autoware_utils::searchZeroVelocityIndex(path_points); + if (opt_path_zero_vel_idx) { + const auto & zero_vel_path_point = path_points.at(opt_path_zero_vel_idx.get()); + const auto opt_traj_seg_idx = tier4_autoware_utils::findNearestSegmentIndex( + fine_traj_points, zero_vel_path_point.pose, std::numeric_limits::max(), + traj_param_.delta_yaw_threshold_for_closest_point); + if (opt_traj_seg_idx) { + const auto interpolated_pose = + lerpPose(fine_traj_points, zero_vel_path_point.pose.position, opt_traj_seg_idx.get()); + if (interpolated_pose) { + autoware_auto_planning_msgs::msg::TrajectoryPoint zero_vel_traj_point; + zero_vel_traj_point.pose = interpolated_pose.get(); + zero_vel_traj_point.longitudinal_velocity_mps = + zero_vel_path_point.longitudinal_velocity_mps; + + if ( + tier4_autoware_utils::calcDistance2d( + fine_traj_points.at(opt_traj_seg_idx.get()).pose, zero_vel_traj_point.pose) < 1e-3) { + return {fine_traj_points, opt_traj_seg_idx.get()}; + } else if ( + tier4_autoware_utils::calcDistance2d( + fine_traj_points.at(opt_traj_seg_idx.get() + 1).pose, zero_vel_traj_point.pose) < + 1e-3) { + return {fine_traj_points, opt_traj_seg_idx.get() + 1}; + } + + auto fine_traj_points_with_zero_vel = fine_traj_points; + fine_traj_points_with_zero_vel.insert( + fine_traj_points_with_zero_vel.begin() + opt_traj_seg_idx.get() + 1, + zero_vel_traj_point); + return {fine_traj_points_with_zero_vel, opt_traj_seg_idx.get() + 1}; + } + } + } + + return {fine_traj_points, {}}; + }(); + const auto fine_traj_points_with_path_zero_vel = path_zero_vel_info.first; + const auto opt_zero_vel_path_idx = path_zero_vel_info.second; + // search zero velocity index of fine_traj_points const size_t zero_vel_fine_traj_idx = [&]() { - const size_t zero_vel_path_idx = searchExtendedZeroVelocityIndex(fine_traj_points, path_points); + // zero velocity for being outside drivable area const size_t zero_vel_traj_idx = - searchExtendedZeroVelocityIndex(fine_traj_points, traj_points); // for outside drivable area + searchExtendedZeroVelocityIndex(fine_traj_points_with_path_zero_vel, traj_points); - return std::min(zero_vel_path_idx, zero_vel_traj_idx); + // zero velocity in path points + if (opt_zero_vel_path_idx) { + return std::min(opt_zero_vel_path_idx.get(), zero_vel_traj_idx); + } + return zero_vel_traj_idx; }(); - auto fine_traj_points_with_vel = fine_traj_points; + // interpolate z and velocity + auto fine_traj_points_with_vel = fine_traj_points_with_path_zero_vel; size_t prev_begin_idx = 0; for (size_t i = 0; i < fine_traj_points_with_vel.size(); ++i) { const auto truncated_points = points_utils::clipForwardPoints(path_points, prev_begin_idx, 5.0); @@ -1403,12 +1502,9 @@ ObstacleAvoidancePlanner::alignVelocity( // lerp vx const double target_vel = lerpTwistX(truncated_points, target_pose.position, closest_seg_idx); + if (i >= zero_vel_fine_traj_idx) { fine_traj_points_with_vel[i].longitudinal_velocity_mps = 0.0; - } else if (target_vel < 1e-6) { // NOTE: velocity may be negative due to linear interpolation - const auto prev_idx = std::max(static_cast(i) - 1, 0); - fine_traj_points_with_vel[i].longitudinal_velocity_mps = - fine_traj_points_with_vel[prev_idx].longitudinal_velocity_mps; } else { fine_traj_points_with_vel[i].longitudinal_velocity_mps = target_vel; } From 15783337c9c6093a2e0dc5b481e8a6ca94a9a6d0 Mon Sep 17 00:00:00 2001 From: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Date: Fri, 20 May 2022 09:28:09 +0900 Subject: [PATCH 43/55] feat(behavior_velocity): find occlusion more efficiently (#829) Signed-off-by: tanaka3 --- .../occlusion_spot.param.yaml | 1 - .../config/occlusion_spot.param.yaml | 1 - .../occlusion_spot/grid_utils.hpp | 28 +-- .../occlusion_spot/occlusion_spot_utils.hpp | 1 - .../occlusion-spot-design.md | 1 - .../occlusion_spot/grid_utils.cpp | 167 +++++------------- .../scene_module/occlusion_spot/manager.cpp | 1 - .../occlusion_spot/scene_occlusion_spot.cpp | 11 +- .../test/src/test_grid_utils.cpp | 94 +++------- 9 files changed, 80 insertions(+), 225 deletions(-) diff --git a/launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/occlusion_spot.param.yaml b/launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/occlusion_spot.param.yaml index 3ea4bb66ea99..957f7988a621 100644 --- a/launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/occlusion_spot.param.yaml +++ b/launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/occlusion_spot.param.yaml @@ -3,7 +3,6 @@ occlusion_spot: detection_method: "occupancy_grid" # [-] candidate is "occupancy_grid" or "predicted_object" pass_judge: "smooth_velocity" # [-] candidate is "smooth_velocity" or "current_velocity" - filter_occupancy_grid: true # [-] whether to filter occupancy grid by morphologyEx or not use_object_info: true # [-] whether to reflect object info to occupancy grid map or not use_moving_object_ray_cast: true # [-] whether to reflect moving object ray_cast to occupancy grid map or not use_partition_lanelet: true # [-] whether to use partition lanelet map data diff --git a/planning/behavior_velocity_planner/config/occlusion_spot.param.yaml b/planning/behavior_velocity_planner/config/occlusion_spot.param.yaml index 3ea4bb66ea99..957f7988a621 100644 --- a/planning/behavior_velocity_planner/config/occlusion_spot.param.yaml +++ b/planning/behavior_velocity_planner/config/occlusion_spot.param.yaml @@ -3,7 +3,6 @@ occlusion_spot: detection_method: "occupancy_grid" # [-] candidate is "occupancy_grid" or "predicted_object" pass_judge: "smooth_velocity" # [-] candidate is "smooth_velocity" or "current_velocity" - filter_occupancy_grid: true # [-] whether to filter occupancy grid by morphologyEx or not use_object_info: true # [-] whether to reflect object info to occupancy grid map or not use_moving_object_ray_cast: true # [-] whether to reflect moving object ray_cast to occupancy grid map or not use_partition_lanelet: true # [-] whether to use partition lanelet map data diff --git a/planning/behavior_velocity_planner/include/scene_module/occlusion_spot/grid_utils.hpp b/planning/behavior_velocity_planner/include/scene_module/occlusion_spot/grid_utils.hpp index 5aba0be4d52c..64f9d1d2c38b 100644 --- a/planning/behavior_velocity_planner/include/scene_module/occlusion_spot/grid_utils.hpp +++ b/planning/behavior_velocity_planner/include/scene_module/occlusion_spot/grid_utils.hpp @@ -109,7 +109,7 @@ namespace occlusion_cost_value static constexpr unsigned char FREE_SPACE = 0; static constexpr unsigned char UNKNOWN = 50; static constexpr unsigned char OCCUPIED = 100; -static constexpr unsigned char UNKNOWN_IMAGE = 128; +static constexpr unsigned char UNKNOWN_IMAGE = 100; static constexpr unsigned char OCCUPIED_IMAGE = 255; } // namespace occlusion_cost_value @@ -133,24 +133,7 @@ struct GridParam int free_space_max; // maximum value of a freespace cell in the occupancy grid int occupied_min; // minimum value of an occupied cell in the occupancy grid }; -struct OcclusionSpotSquare -{ - grid_map::Index index; // index of the anchor - grid_map::Position position; // position of the anchor - int min_occlusion_size; // number of cells for each side of the square -}; -// @brief structure representing a OcclusionSpot on the OccupancyGrid -struct OcclusionSpot -{ - double distance_along_lanelet; - lanelet::ConstLanelet lanelet; - lanelet::BasicPoint2d position; -}; -//!< @brief Return true -// if the given cell is a occlusion_spot square of size min_size*min_size in the given grid -bool isOcclusionSpotSquare( - OcclusionSpotSquare & occlusion_spot, const grid_map::Matrix & grid_data, - const grid_map::Index & cell, const int min_occlusion_size, const grid_map::Size & grid_size); + //!< @brief Find all occlusion spots inside the given lanelet void findOcclusionSpots( std::vector & occlusion_spot_positions, const grid_map::GridMap & grid, @@ -159,10 +142,6 @@ void findOcclusionSpots( bool isCollisionFree( const grid_map::GridMap & grid, const grid_map::Position & p1, const grid_map::Position & p2, const double radius); -//!< @brief get the corner positions of the square described by the given anchor -void getCornerPositions( - std::vector & corner_positions, const grid_map::GridMap & grid, - const OcclusionSpotSquare & occlusion_spot_square); boost::optional generateOccupiedPolygon( const Polygon2d & occupancy_poly, const Polygons2d & stuck_vehicle_foot_prints, const Polygons2d & moving_vehicle_foot_prints, const Point & position); @@ -180,8 +159,7 @@ void denoiseOccupancyGridCV( const OccupancyGrid::ConstSharedPtr occupancy_grid_ptr, const Polygons2d & stuck_vehicle_foot_prints, const Polygons2d & moving_vehicle_foot_prints, grid_map::GridMap & grid_map, const GridParam & param, const bool is_show_debug_window, - const bool filter_occupancy_grid, const bool use_object_footprints, - const bool use_object_ray_casts); + const int num_iter, const bool use_object_footprints, const bool use_object_ray_casts); void addObjectsToGridMap(const std::vector & objs, grid_map::GridMap & grid); } // namespace grid_utils } // namespace behavior_velocity_planner diff --git a/planning/behavior_velocity_planner/include/scene_module/occlusion_spot/occlusion_spot_utils.hpp b/planning/behavior_velocity_planner/include/scene_module/occlusion_spot/occlusion_spot_utils.hpp index 38ac306584d0..ae0eb5432fdd 100644 --- a/planning/behavior_velocity_planner/include/scene_module/occlusion_spot/occlusion_spot_utils.hpp +++ b/planning/behavior_velocity_planner/include/scene_module/occlusion_spot/occlusion_spot_utils.hpp @@ -121,7 +121,6 @@ struct PlannerParam bool is_show_occlusion; // [-] bool is_show_cv_window; // [-] bool is_show_processing_time; // [-] - bool filter_occupancy_grid; // [-] bool use_object_info; // [-] bool use_moving_object_ray_cast; // [-] bool use_partition_lanelet; // [-] diff --git a/planning/behavior_velocity_planner/occlusion-spot-design.md b/planning/behavior_velocity_planner/occlusion-spot-design.md index ba7ccb7dd5b1..3cce4365e4de 100644 --- a/planning/behavior_velocity_planner/occlusion-spot-design.md +++ b/planning/behavior_velocity_planner/occlusion-spot-design.md @@ -112,7 +112,6 @@ obstacle that can run out from occlusion is interruped by moving vehicle. | Parameter | Type | Description | | ----------------------- | ---- | ---------------------------------------------------------------- | -| `filter_occupancy_grid` | bool | [-] whether to filter occupancy grid by morphologyEx or not. | | `use_object_info` | bool | [-] whether to reflect object info to occupancy grid map or not. | | `use_partition_lanelet` | bool | [-] whether to use partition lanelet map data. | diff --git a/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/grid_utils.cpp b/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/grid_utils.cpp index af94ef8c00c8..46f48b057ac3 100644 --- a/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/grid_utils.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/grid_utils.cpp @@ -80,77 +80,21 @@ void addObjectsToGridMap(const std::vector & objs, grid_map::Gr } } -bool isOcclusionSpotSquare( - OcclusionSpotSquare & occlusion_spot, const grid_map::Matrix & grid_data, - const grid_map::Index & cell, int min_occlusion_size, const grid_map::Size & grid_size) -{ - const int offset = (min_occlusion_size != 1) ? (min_occlusion_size - 1) : min_occlusion_size; - const int cell_max_x = grid_size.x() - 1; - const int cell_max_y = grid_size.y() - 1; - // Calculate ranges to check - int min_x = cell.x() - offset; - int max_x = cell.x() + offset; - int min_y = cell.y() - offset; - int max_y = cell.y() + offset; - if (min_x < 0) max_x += std::abs(min_x); - if (max_x > cell_max_x) min_x -= std::abs(max_x - cell_max_x); - if (min_y < 0) max_y += std::abs(min_y); - if (max_y > cell_max_y) min_y -= std::abs(max_y - cell_max_y); - // No occlusion_spot with size 0 - if (min_occlusion_size == 0) { - return false; - } - /** - * @brief - * (min_x,min_y)...(max_x,min_y) - * . . - * (min_x,max_y)...(max_x,max_y) - */ - // Ensure we stay inside the grid - min_x = std::max(0, min_x); - max_x = std::min(cell_max_x, max_x); - min_y = std::max(0, min_y); - max_y = std::min(cell_max_y, max_y); - int not_unknown_count = 0; - if (grid_data(cell.x(), cell.y()) != grid_utils::occlusion_cost_value::UNKNOWN) { - return false; - } - for (int x = min_x; x <= max_x; ++x) { - for (int y = min_y; y <= max_y; ++y) { - // if the value is not unknown value return false - if (grid_data(x, y) != grid_utils::occlusion_cost_value::UNKNOWN) { - not_unknown_count++; - } - /** - * @brief case pass o: unknown x: freespace or occupied - * oxx oxo oox xxx oxo oxo - * oox oxx oox ooo oox oxo ... etc - * ooo ooo oox ooo xoo oxo - */ - if (not_unknown_count > min_occlusion_size + 1) return false; - } - } - occlusion_spot.min_occlusion_size = min_occlusion_size; - occlusion_spot.index = cell; - return true; -} - void findOcclusionSpots( std::vector & occlusion_spot_positions, const grid_map::GridMap & grid, - const Polygon2d & polygon, double min_size) + const Polygon2d & polygon, [[maybe_unused]] double min_size) { const grid_map::Matrix & grid_data = grid["layer"]; - const int min_occlusion_spot_size = std::max(0.0, std::floor(min_size / grid.getResolution())); grid_map::Polygon grid_polygon; for (const auto & point : polygon.outer()) { grid_polygon.addVertex({point.x(), point.y()}); } for (grid_map::PolygonIterator iterator(grid, grid_polygon); !iterator.isPastEnd(); ++iterator) { - OcclusionSpotSquare occlusion_spot_square; - if (isOcclusionSpotSquare( - occlusion_spot_square, grid_data, *iterator, min_occlusion_spot_size, grid.getSize())) { - if (grid.getPosition(occlusion_spot_square.index, occlusion_spot_square.position)) { - occlusion_spot_positions.emplace_back(occlusion_spot_square.position); + const grid_map::Index & index = *iterator; + if (grid_data(index.x(), index.y()) == grid_utils::occlusion_cost_value::UNKNOWN) { + grid_map::Position occlusion_spot_position; + if (grid.getPosition(index, occlusion_spot_position)) { + occlusion_spot_positions.emplace_back(occlusion_spot_position); } } } @@ -198,45 +142,6 @@ bool isCollisionFree( return true; } -void getCornerPositions( - std::vector & corner_positions, const grid_map::GridMap & grid, - const OcclusionSpotSquare & occlusion_spot_square) -{ - // Special case with size = 1: only one cell - if (occlusion_spot_square.min_occlusion_size == 1) { - corner_positions.emplace_back(occlusion_spot_square.position); - return; - } - std::vector corner_indexes; - const int offset = (occlusion_spot_square.min_occlusion_size - 1) / 2; - /** - * @brief relation of each grid position - * bl br - * tl tr - */ - corner_indexes = {// bl - grid_map::Index( - std::max(0, occlusion_spot_square.index.x() - offset), - std::max(0, occlusion_spot_square.index.y() - offset)), - // br - grid_map::Index( - std::min(grid.getSize().x() - 1, occlusion_spot_square.index.x() + offset), - std::max(0, occlusion_spot_square.index.y() - offset)), - // tl - grid_map::Index( - std::max(0, occlusion_spot_square.index.x() - offset), - std::min(grid.getSize().y() - 1, occlusion_spot_square.index.y() + offset)), - // tr - grid_map::Index( - std::min(grid.getSize().x() - 1, occlusion_spot_square.index.x() + offset), - std::min(grid.getSize().y() - 1, occlusion_spot_square.index.y() + offset))}; - for (const grid_map::Index & corner_index : corner_indexes) { - grid_map::Position corner_position; - grid.getPosition(corner_index, corner_position); - corner_positions.emplace_back(corner_position); - } -} - boost::optional generateOcclusionPolygon( const Polygon2d & occupancy_poly, const Point2d & origin, const Point2d & min_theta_pos, const Point2d & max_theta_pos, const double ray_max_length = 100.0) @@ -453,24 +358,26 @@ void imageToOccupancyGrid(const cv::Mat & cv_image, nav_msgs::msg::OccupancyGrid } } void toQuantizedImage( - const nav_msgs::msg::OccupancyGrid & occupancy_grid, cv::Mat * cv_image, const GridParam & param) + const nav_msgs::msg::OccupancyGrid & occupancy_grid, cv::Mat * border_image, + cv::Mat * occlusion_image, const GridParam & param) { - const int width = cv_image->cols; - const int height = cv_image->rows; + const int width = border_image->cols; + const int height = border_image->rows; for (int x = width - 1; x >= 0; x--) { for (int y = height - 1; y >= 0; y--) { const int idx = (height - 1 - y) + (width - 1 - x) * height; unsigned char intensity = occupancy_grid.data.at(idx); if (intensity <= param.free_space_max) { - intensity = grid_utils::occlusion_cost_value::FREE_SPACE; + continue; } else if (param.free_space_max < intensity && intensity < param.occupied_min) { intensity = grid_utils::occlusion_cost_value::UNKNOWN_IMAGE; + occlusion_image->at(y, x) = intensity; } else if (param.occupied_min <= intensity) { intensity = grid_utils::occlusion_cost_value::OCCUPIED_IMAGE; + border_image->at(y, x) = intensity; } else { throw std::logic_error("behavior_velocity[occlusion_spot_grid]: invalid if clause"); } - cv_image->at(y, x) = intensity; } } } @@ -479,43 +386,53 @@ void denoiseOccupancyGridCV( const OccupancyGrid::ConstSharedPtr occupancy_grid_ptr, const Polygons2d & stuck_vehicle_foot_prints, const Polygons2d & moving_vehicle_foot_prints, grid_map::GridMap & grid_map, const GridParam & param, const bool is_show_debug_window, - const bool filter_occupancy_grid, const bool use_object_footprints, - const bool use_object_ray_casts) + const int num_iter, const bool use_object_footprints, const bool use_object_ray_casts) { OccupancyGrid occupancy_grid = *occupancy_grid_ptr; - cv::Mat cv_image( + cv::Mat border_image( + occupancy_grid.info.width, occupancy_grid.info.height, CV_8UC1, + cv::Scalar(grid_utils::occlusion_cost_value::FREE_SPACE)); + cv::Mat occlusion_image( occupancy_grid.info.width, occupancy_grid.info.height, CV_8UC1, - cv::Scalar(grid_utils::occlusion_cost_value::OCCUPIED)); - toQuantizedImage(occupancy_grid, &cv_image, param); + cv::Scalar(grid_utils::occlusion_cost_value::FREE_SPACE)); + toQuantizedImage(occupancy_grid, &border_image, &occlusion_image, param); //! show original occupancy grid to compare difference if (is_show_debug_window) { - cv::namedWindow("original", cv::WINDOW_NORMAL); - cv::imshow("original", cv_image); + cv::namedWindow("occlusion_image", cv::WINDOW_NORMAL); + cv::imshow("occlusion_image", occlusion_image); + cv::moveWindow("occlusion_image", 0, 0); } //! raycast object shadow using vehicle if (use_object_footprints || use_object_ray_casts) { generateOccupiedImage( - occupancy_grid, cv_image, stuck_vehicle_foot_prints, moving_vehicle_foot_prints, + occupancy_grid, border_image, stuck_vehicle_foot_prints, moving_vehicle_foot_prints, use_object_footprints, use_object_ray_casts); if (is_show_debug_window) { cv::namedWindow("object ray shadow", cv::WINDOW_NORMAL); - cv::imshow("object ray shadow", cv_image); + cv::imshow("object ray shadow", border_image); + cv::moveWindow("object ray shadow", 300, 0); } } - //!< @brief opening & closing to remove noise in occupancy grid - if (filter_occupancy_grid) { - constexpr int num_iter = 2; - cv::morphologyEx(cv_image, cv_image, cv::MORPH_CLOSE, cv::Mat(), cv::Point(-1, -1), num_iter); - if (is_show_debug_window) { - cv::namedWindow("morph", cv::WINDOW_NORMAL); - cv::imshow("morph", cv_image); - cv::waitKey(1); - } + //!< @brief erode occlusion to make sure occlusion candidates are big enough + cv::Mat kernel(2, 2, CV_8UC1, cv::Scalar(1)); + cv::erode(occlusion_image, occlusion_image, kernel, cv::Point(-1, -1), num_iter); + if (is_show_debug_window) { + cv::namedWindow("morph", cv::WINDOW_NORMAL); + cv::imshow("morph", occlusion_image); + cv::moveWindow("morph", 0, 300); + } + + border_image += occlusion_image; + if (is_show_debug_window) { + cv::namedWindow("merge", cv::WINDOW_NORMAL); + cv::imshow("merge", border_image); + cv::moveWindow("merge", 300, 300); + cv::waitKey(1); } - imageToOccupancyGrid(cv_image, &occupancy_grid); + imageToOccupancyGrid(border_image, &occupancy_grid); grid_map::GridMapRosConverter::fromOccupancyGrid(occupancy_grid, "layer", grid_map); } } // namespace grid_utils diff --git a/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/manager.cpp b/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/manager.cpp index ebbeed5483db..5666439bb421 100644 --- a/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/manager.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/manager.cpp @@ -58,7 +58,6 @@ OcclusionSpotModuleManager::OcclusionSpotModuleManager(rclcpp::Node & node) "[behavior_velocity]: occlusion spot pass judge method has invalid argument"}; } } - pp.filter_occupancy_grid = node.declare_parameter(ns + ".filter_occupancy_grid", false); pp.use_object_info = node.declare_parameter(ns + ".use_object_info", true); pp.use_moving_object_ray_cast = node.declare_parameter(ns + ".use_moving_object_ray_cast", true); pp.use_partition_lanelet = node.declare_parameter(ns + ".use_partition_lanelet", false); diff --git a/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/scene_occlusion_spot.cpp b/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/scene_occlusion_spot.cpp index 48fb1f8e05bb..cb2b98eff5a6 100644 --- a/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/scene_occlusion_spot.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/scene_occlusion_spot.cpp @@ -151,9 +151,12 @@ bool OcclusionSpotModule::modifyPathVelocity( filtered_vehicles, stuck_vehicle_foot_prints, moving_vehicle_foot_prints, param_.stuck_vehicle_vel); // occ -> image + // find out occlusion from erode occlusion candidate num iter is strength of filter + const int num_iter = static_cast( + (param_.detection_area.min_occlusion_spot_size / occ_grid_ptr->info.resolution) - 1); grid_utils::denoiseOccupancyGridCV( occ_grid_ptr, stuck_vehicle_foot_prints, moving_vehicle_foot_prints, grid_map, param_.grid, - param_.is_show_cv_window, param_.filter_occupancy_grid, param_.use_object_info, + param_.is_show_cv_window, num_iter, param_.use_object_info, param_.use_moving_object_ray_cast); DEBUG_PRINT(show_time, "grid [ms]: ", stop_watch_.toc("processing_time", true)); // Note: Don't consider offset from path start to ego here @@ -183,8 +186,10 @@ bool OcclusionSpotModule::modifyPathVelocity( // these debug topics needs computation resource debug_data_.z = path->points.front().point.pose.position.z; debug_data_.possible_collisions = possible_collisions; - debug_data_.path_interpolated = path_interpolated; - debug_data_.path_raw = clipped_path; + if (param_.is_show_occlusion) { + debug_data_.path_interpolated = path_interpolated; + debug_data_.path_raw.points = clipped_path.points; + } DEBUG_PRINT(show_time, "total [ms]: ", stop_watch_.toc("total_processing_time", true)); return true; } diff --git a/planning/behavior_velocity_planner/test/src/test_grid_utils.cpp b/planning/behavior_velocity_planner/test/src/test_grid_utils.cpp index 013b8164ec64..a50831e65b21 100644 --- a/planning/behavior_velocity_planner/test/src/test_grid_utils.cpp +++ b/planning/behavior_velocity_planner/test/src/test_grid_utils.cpp @@ -38,73 +38,6 @@ struct indexEq } }; -using test::grid_param; - -TEST(isOcclusionSpotSquare, occlusion_spot_cell) -{ - using behavior_velocity_planner::grid_utils::isOcclusionSpotSquare; - using behavior_velocity_planner::grid_utils::OcclusionSpotSquare; - using behavior_velocity_planner::grid_utils::occlusion_cost_value::UNKNOWN; - // Prepare an occupancy grid with a single occlusion_spot - const int min_occlusion_spot_size = 2; - - // case simple - { - /* - 0 1 2 3 4 - 0 - 1 ? ? - 2 ? x ? - 3 ? ? - 4 - */ - grid_map::GridMap grid = test::generateGrid(5, 5, 1.0); - std::vector unknown_cells = {{1, 1}, {1, 2}, {1, 3}, {2, 2}, - {2, 3}, {3, 1}, {3, 2}}; - for (grid_map::Index index : unknown_cells) { - grid.at("layer", index) = UNKNOWN; - } - - // occlusion spot (2,2) - for (int i = 0; i < grid.getLength().x(); ++i) { - for (int j = 0; j < grid.getLength().y(); ++j) { - OcclusionSpotSquare occlusion_spot; - bool found = isOcclusionSpotSquare( - occlusion_spot, grid["layer"], {i, j}, min_occlusion_spot_size, grid.getSize()); - if (i == 2 && j == 2) { - EXPECT_TRUE(found); - } else { - EXPECT_FALSE(found); - } - } - } - } - // case noisy - { - std::cout << "TooNoisyCase->No OcclusionSpot 2by2" << std::endl - << " 0|1|2|3|4| " << std::endl - << " 0 |?| | | | " << std::endl - << " 1 |?| | | | " << std::endl - << " 2 |?|?|?| | " << std::endl; - grid_map::GridMap grid = test::generateGrid(5, 3, 1.0); - std::vector unknown_cells = {{1, 0}, {1, 1}, {1, 2}, {2, 2}, {3, 2}}; - for (grid_map::Index index : unknown_cells) { - grid.at("layer", index) = UNKNOWN; - } - for (int i = 0; i < grid.getLength().x(); ++i) { - for (int j = 0; j < grid.getLength().y(); ++j) { - OcclusionSpotSquare occlusion_spot; - bool found = isOcclusionSpotSquare( - occlusion_spot, grid["layer"], {i, j}, min_occlusion_spot_size, grid.getSize()); - if (found) { - std::cout << "i: " << i << " j: " << j << " change algorithm or update test" << std::endl; - } - ASSERT_FALSE(found); - } - } - } -} - using behavior_velocity_planner::LineString2d; using behavior_velocity_planner::Point2d; using behavior_velocity_planner::Polygon2d; @@ -215,3 +148,30 @@ TEST(compareTime, polygon_vs_line_iterator) count = 0; } } + +TEST(test, erode_with_custom_kernel) +{ + cv::Mat image; + cv::Mat cv_image(100, 100, CV_8UC1, cv::Scalar(0)); + { + // line 1 + cv::rectangle(cv_image, cv::Point(25, 5), cv::Point(75, 5), cv::Scalar(200), -1); + + // line 2 + cv::rectangle(cv_image, cv::Point(25, 15), cv::Point(75, 16), cv::Scalar(200), -1); + // line 3 + cv::rectangle(cv_image, cv::Point(25, 25), cv::Point(75, 27), cv::Scalar(200), -1); + // line 4 + cv::rectangle(cv_image, cv::Point(25, 35), cv::Point(75, 38), cv::Scalar(200), -1); + // line 5 + cv::rectangle(cv_image, cv::Point(25, 45), cv::Point(75, 49), cv::Scalar(200), -1); + } + // cv::namedWindow("original", cv::WINDOW_NORMAL); + // cv::imshow("original", cv_image); + // cv::waitKey(100); + cv::Mat kernel(2, 2, CV_8UC1, cv::Scalar(1)); + cv::erode(cv_image, cv_image, kernel, cv::Point(-1, -1), 4); + // cv::namedWindow("erode", cv::WINDOW_NORMAL); + // cv::imshow("erode", cv_image); + // cv::waitKey(5000); +} From b64e0d0f61e80adbff1324ded766ee47c8be54c8 Mon Sep 17 00:00:00 2001 From: kk-inoue-esol <76925382+kk-inoue-esol@users.noreply.github.com> Date: Fri, 20 May 2022 10:37:30 +0900 Subject: [PATCH 44/55] fix(system_monitor): add some smart information to diagnostics (#708) Signed-off-by: kk-inoue-esol --- .../config/system_monitor/hdd_monitor.param.yaml | 3 +++ .../config/diagnostic_aggregator/system.param.yaml | 4 ++-- system/system_monitor/README.md | 2 ++ 3 files changed, 7 insertions(+), 2 deletions(-) diff --git a/launch/tier4_system_launch/config/system_monitor/hdd_monitor.param.yaml b/launch/tier4_system_launch/config/system_monitor/hdd_monitor.param.yaml index 32d3a425b189..77a23eb0f9aa 100644 --- a/launch/tier4_system_launch/config/system_monitor/hdd_monitor.param.yaml +++ b/launch/tier4_system_launch/config/system_monitor/hdd_monitor.param.yaml @@ -7,5 +7,8 @@ name: /dev/sda3 temp_warn: 55.0 temp_error: 70.0 + power_on_hours_warn: 3000000 + total_data_written_warn: 4915200 # =150TB (1unit=32MB) + total_data_written_safety_factor: 0.05 free_warn: 5120 # MB(8hour) free_error: 100 # MB(last 1 minute) diff --git a/system/system_error_monitor/config/diagnostic_aggregator/system.param.yaml b/system/system_error_monitor/config/diagnostic_aggregator/system.param.yaml index edea607c1bd1..af6b9ab8a64c 100644 --- a/system/system_error_monitor/config/diagnostic_aggregator/system.param.yaml +++ b/system/system_error_monitor/config/diagnostic_aggregator/system.param.yaml @@ -140,13 +140,13 @@ power_on_hours: type: diagnostic_aggregator/GenericAnalyzer - path: usage + path: power_on_hours contains: [": HDD PowerOnHours"] timeout: 3.0 total_data_written: type: diagnostic_aggregator/GenericAnalyzer - path: usage + path: total_data_written contains: [": HDD TotalDataWritten"] timeout: 3.0 diff --git a/system/system_monitor/README.md b/system/system_monitor/README.md index bd4eb3fb863c..79f390a80d7e 100644 --- a/system/system_monitor/README.md +++ b/system/system_monitor/README.md @@ -61,6 +61,8 @@ Every topic is published in 1 minute interval. | | CPU Thermal Throttling | ✓ | - | ✓ | | | | CPU Frequency | ✓ | ✓ | ✓ | Notification of frequency only, normally error not generated. | | HDD Monitor | HDD Temperature | ✓ | ✓ | ✓ | | +| | HDD PowerOnHours | ✓ | ✓ | ✓ | | +| | HDD TotalDataWritten | ✓ | ✓ | ✓ | | | | HDD Usage | ✓ | ✓ | ✓ | | | Memory Monitor | Memory Usage | ✓ | ✓ | ✓ | | | Net Monitor | Network Usage | ✓ | ✓ | ✓ | | From 1abf325f51f8f4dcf8c761e8a07d781790b64a95 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 20 May 2022 12:41:15 +0900 Subject: [PATCH 45/55] feat(obstacle_avoidance_planner): dealt with close lane change (#921) * feat(obstacle_avoidance_planner): dealt with close lane change Signed-off-by: Takayuki Murooka * fix bug of right lane change Signed-off-by: Takayuki Murooka --- planning/obstacle_avoidance_planner/src/node.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/planning/obstacle_avoidance_planner/src/node.cpp b/planning/obstacle_avoidance_planner/src/node.cpp index 84894e1615e1..74804cb66174 100644 --- a/planning/obstacle_avoidance_planner/src/node.cpp +++ b/planning/obstacle_avoidance_planner/src/node.cpp @@ -82,7 +82,7 @@ bool isPathShapeChanged( // calculate lateral deviations between truncated path_points and prev_path_points for (const auto & prev_point : truncated_prev_points) { const double dist = - tier4_autoware_utils::calcLateralOffset(truncated_points, prev_point.pose.position); + std::abs(tier4_autoware_utils::calcLateralOffset(truncated_points, prev_point.pose.position)); if (dist > max_path_shape_change_dist) { return true; } @@ -976,7 +976,8 @@ bool ObstacleAvoidancePlanner::checkReplan( current_ego_pose_, path_points, prev_path_points_ptr_, max_mpt_length, max_path_shape_change_dist_for_replan_, traj_param_.delta_yaw_threshold_for_closest_point)) { - RCLCPP_INFO(get_logger(), "Replan since path shape was changed."); + RCLCPP_INFO(get_logger(), "Replan with resetting optimization since path shape was changed."); + resetPrevOptimization(); return true; } From 5afabee74bf5e77174c91e75319bf22f43c3be2f Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 20 May 2022 12:41:27 +0900 Subject: [PATCH 46/55] feat(obstacle_avoidance_planner): some fix for narrow driving (#916) * use car like constraints in mpt * use not widest bounds for the first bounds Signed-off-by: Takayuki Murooka * organized params Signed-off-by: Takayuki Murooka * fix format Signed-off-by: Takayuki Murooka * prepare rear_drive and uniform_circle constraints Signed-off-by: Takayuki Murooka * fix param callback Signed-off-by: Takayuki Murooka * update config Signed-off-by: Takayuki Murooka * remove unnecessary files Signed-off-by: Takayuki Murooka * update tier4_planning_launch params Signed-off-by: Takayuki Murooka --- .../obstacle_avoidance_planner.param.yaml | 44 +-- .../obstacle_avoidance_planner.param.yaml | 44 +-- .../common_structs.hpp | 8 +- .../mpt_optimizer.hpp | 1 + .../obstacle_avoidance_planner/node.hpp | 17 +- .../src/cv_utils.cpp | 2 +- .../src/debug_visualization.cpp | 46 +-- .../src/mpt_optimizer.cpp | 64 ++++- .../obstacle_avoidance_planner/src/node.cpp | 269 ++++++++---------- 9 files changed, 229 insertions(+), 266 deletions(-) diff --git a/launch/tier4_planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml b/launch/tier4_planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml index bc3962ca5adb..667d2644f16d 100644 --- a/launch/tier4_planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml +++ b/launch/tier4_planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml @@ -83,28 +83,6 @@ # advanced parameters to improve performance as much as possible advanced: - option: - # check if planned trajectory is outside drivable area - drivability_check: - # true: vehicle shape is considered as a set of circles - # false: vehicle shape is considered as footprint (= rectangle) - use_vehicle_circles: false - - # parameters only when use_vehicle_circles is true - vehicle_circles: - use_manual_vehicle_circles: false - num_for_constraints: 4 - - # parameters only when use_manual_vehicle_circles is true - longitudinal_offsets: [-0.15, 0.88, 1.9, 2.95] - radius: 0.95 - - # parameters only when use_manual_vehicle_circles is false - radius_ratio: 0.9 - # If this parameter is commented out, the parameter is calculated automatically - # based on the vehicle length and width - # num_for_radius: 4 - eb: common: num_joint_buffer_points: 3 # number of joint buffer points @@ -161,15 +139,13 @@ # two_step_soft_constraint: false vehicle_circles: - use_manual_vehicle_circles: false - num_for_constraints: 3 - - # parameters only when use_manual_vehicle_circles is true - longitudinal_offsets: [-0.15, 0.88, 1.9, 2.95] - radius: 0.95 - - # parameters only when use_manual_vehicle_circles is false - radius_ratio: 0.8 - # If this parameter is commented out, the parameter is calculated automatically - # based on the vehicle length and width - # num_for_radius: 4 + method: "rear_drive" + + uniform_circle: + num: 3 + radius_ratio: 0.8 + + rear_drive: + num_for_calculation: 3 + front_radius_ratio: 1.0 + rear_radius_ratio: 1.0 diff --git a/planning/obstacle_avoidance_planner/config/obstacle_avoidance_planner.param.yaml b/planning/obstacle_avoidance_planner/config/obstacle_avoidance_planner.param.yaml index bc3962ca5adb..667d2644f16d 100644 --- a/planning/obstacle_avoidance_planner/config/obstacle_avoidance_planner.param.yaml +++ b/planning/obstacle_avoidance_planner/config/obstacle_avoidance_planner.param.yaml @@ -83,28 +83,6 @@ # advanced parameters to improve performance as much as possible advanced: - option: - # check if planned trajectory is outside drivable area - drivability_check: - # true: vehicle shape is considered as a set of circles - # false: vehicle shape is considered as footprint (= rectangle) - use_vehicle_circles: false - - # parameters only when use_vehicle_circles is true - vehicle_circles: - use_manual_vehicle_circles: false - num_for_constraints: 4 - - # parameters only when use_manual_vehicle_circles is true - longitudinal_offsets: [-0.15, 0.88, 1.9, 2.95] - radius: 0.95 - - # parameters only when use_manual_vehicle_circles is false - radius_ratio: 0.9 - # If this parameter is commented out, the parameter is calculated automatically - # based on the vehicle length and width - # num_for_radius: 4 - eb: common: num_joint_buffer_points: 3 # number of joint buffer points @@ -161,15 +139,13 @@ # two_step_soft_constraint: false vehicle_circles: - use_manual_vehicle_circles: false - num_for_constraints: 3 - - # parameters only when use_manual_vehicle_circles is true - longitudinal_offsets: [-0.15, 0.88, 1.9, 2.95] - radius: 0.95 - - # parameters only when use_manual_vehicle_circles is false - radius_ratio: 0.8 - # If this parameter is commented out, the parameter is calculated automatically - # based on the vehicle length and width - # num_for_radius: 4 + method: "rear_drive" + + uniform_circle: + num: 3 + radius_ratio: 0.8 + + rear_drive: + num_for_calculation: 3 + front_radius_ratio: 1.0 + rear_radius_ratio: 1.0 diff --git a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/common_structs.hpp b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/common_structs.hpp index ca7e8c6aaef0..f29a955ae38e 100644 --- a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/common_structs.hpp +++ b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/common_structs.hpp @@ -126,20 +126,20 @@ struct DebugData void init( const bool local_is_showing_calculation_time, const int local_mpt_visualize_sampling_num, const geometry_msgs::msg::Pose & local_current_ego_pose, - const double local_vehicle_circle_radius, + const std::vector & local_vehicle_circle_radiuses, const std::vector & local_vehicle_circle_longitudinal_offsets) { msg_stream.is_showing_calculation_time = local_is_showing_calculation_time; mpt_visualize_sampling_num = local_mpt_visualize_sampling_num; current_ego_pose = local_current_ego_pose; - vehicle_circle_radius = local_vehicle_circle_radius; + vehicle_circle_radiuses = local_vehicle_circle_radiuses; vehicle_circle_longitudinal_offsets = local_vehicle_circle_longitudinal_offsets; } StreamWithPrint msg_stream; size_t mpt_visualize_sampling_num; geometry_msgs::msg::Pose current_ego_pose; - double vehicle_circle_radius; + std::vector vehicle_circle_radiuses; std::vector vehicle_circle_longitudinal_offsets; boost::optional stop_pose_by_drivable_area = boost::none; @@ -212,7 +212,7 @@ struct MPTParam int num_curvature_sampling_points; std::vector vehicle_circle_longitudinal_offsets; // from base_link - double vehicle_circle_radius; + std::vector vehicle_circle_radiuses; double delta_arc_length_for_mpt_points; diff --git a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/mpt_optimizer.hpp b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/mpt_optimizer.hpp index be36be812a09..4786083dcfad 100644 --- a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/mpt_optimizer.hpp +++ b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/mpt_optimizer.hpp @@ -219,6 +219,7 @@ class MPTOptimizer void calcBounds( std::vector & ref_points, const bool enable_avoidance, const CVMaps & maps, + const std::unique_ptr & prev_trajs, std::shared_ptr debug_data_ptr) const; void calcVehicleBounds( diff --git a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp index 7d32ce73d40e..8d2e42c41723 100644 --- a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp +++ b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp @@ -44,6 +44,7 @@ #include #include +#include #include namespace @@ -158,20 +159,10 @@ class ObstacleAvoidancePlanner : public rclcpp::Node bool skip_optimization_; bool reset_prev_optimization_; - // vehicle circles info for drivability check - bool use_vehicle_circles_for_drivability_; - bool use_manual_vehicle_circles_for_drivability_; - int vehicle_circle_constraints_num_for_drivability_; - int vehicle_circle_radius_num_for_drivability_; - double vehicle_circle_radius_ratio_for_drivability_; - double vehicle_circle_radius_for_drivability_; - std::vector vehicle_circle_longitudinal_offsets_for_drivability_; - // vehicle circles info for for mpt constraints - bool use_manual_vehicle_circles_for_mpt_; - int vehicle_circle_constraints_num_for_mpt_; - int vehicle_circle_radius_num_for_mpt_; - double vehicle_circle_radius_ratio_for_mpt_; + std::string vehicle_circle_method_; + int vehicle_circle_num_for_calculation_; + std::vector vehicle_circle_radius_ratios_; // params for replan double max_path_shape_change_dist_for_replan_; diff --git a/planning/obstacle_avoidance_planner/src/cv_utils.cpp b/planning/obstacle_avoidance_planner/src/cv_utils.cpp index a73a5c70fdeb..3e59bda315b6 100644 --- a/planning/obstacle_avoidance_planner/src/cv_utils.cpp +++ b/planning/obstacle_avoidance_planner/src/cv_utils.cpp @@ -441,7 +441,7 @@ bool isOutsideDrivableAreaFromRectangleFootprint( return false; } -bool isOutsideDrivableAreaFromCirclesFootprint( +[[maybe_unused]] bool isOutsideDrivableAreaFromCirclesFootprint( const autoware_auto_planning_msgs::msg::TrajectoryPoint & traj_point, const cv::Mat & road_clearance_map, const nav_msgs::msg::MapMetaData & map_info, const std::vector vehicle_circle_longitudinal_offsets, const double vehicle_circle_radius) diff --git a/planning/obstacle_avoidance_planner/src/debug_visualization.cpp b/planning/obstacle_avoidance_planner/src/debug_visualization.cpp index 2992ab4ccdff..678ba112cbd2 100644 --- a/planning/obstacle_avoidance_planner/src/debug_visualization.cpp +++ b/planning/obstacle_avoidance_planner/src/debug_visualization.cpp @@ -484,7 +484,7 @@ visualization_msgs::msg::MarkerArray getBoundsCandidatesLineMarkerArray( visualization_msgs::msg::MarkerArray getBoundsLineMarkerArray( const std::vector & ref_points, const double r, const double g, const double b, - const double vehicle_circle_radius, const size_t sampling_num) + const double vehicle_width, const size_t sampling_num) { const auto current_time = rclcpp::Clock().now(); visualization_msgs::msg::MarkerArray msg; @@ -507,7 +507,7 @@ visualization_msgs::msg::MarkerArray getBoundsLineMarkerArray( const geometry_msgs::msg::Pose & pose = ref_points.at(i).vehicle_bounds_poses.at(bound_idx); const double lb_y = - ref_points.at(i).vehicle_bounds[bound_idx].lower_bound - vehicle_circle_radius; + ref_points.at(i).vehicle_bounds[bound_idx].lower_bound - vehicle_width / 2.0; const auto lb = tier4_autoware_utils::calcOffsetPose(pose, 0.0, lb_y, 0.0).position; marker.points.push_back(pose.position); @@ -529,7 +529,7 @@ visualization_msgs::msg::MarkerArray getBoundsLineMarkerArray( const geometry_msgs::msg::Pose & pose = ref_points.at(i).vehicle_bounds_poses.at(bound_idx); const double ub_y = - ref_points.at(i).vehicle_bounds[bound_idx].upper_bound + vehicle_circle_radius; + ref_points.at(i).vehicle_bounds[bound_idx].upper_bound + vehicle_width / 2.0; const auto ub = tier4_autoware_utils::calcOffsetPose(pose, 0.0, ub_y, 0.0).position; marker.points.push_back(pose.position); @@ -544,8 +544,8 @@ visualization_msgs::msg::MarkerArray getBoundsLineMarkerArray( visualization_msgs::msg::MarkerArray getVehicleCircleLineMarkerArray( const std::vector> & vehicle_circles_pose, - const double vehicle_circle_radius, const size_t sampling_num, const std::string & ns, - const double r, const double g, const double b) + const double vehicle_width, const size_t sampling_num, const std::string & ns, const double r, + const double g, const double b) { const auto current_time = rclcpp::Clock().now(); visualization_msgs::msg::MarkerArray msg; @@ -563,9 +563,9 @@ visualization_msgs::msg::MarkerArray getVehicleCircleLineMarkerArray( for (size_t j = 0; j < vehicle_circles_pose.at(i).size(); ++j) { const geometry_msgs::msg::Pose & pose = vehicle_circles_pose.at(i).at(j); const auto ub = - tier4_autoware_utils::calcOffsetPose(pose, 0.0, vehicle_circle_radius, 0.0).position; + tier4_autoware_utils::calcOffsetPose(pose, 0.0, vehicle_width / 2.0, 0.0).position; const auto lb = - tier4_autoware_utils::calcOffsetPose(pose, 0.0, -vehicle_circle_radius, 0.0).position; + tier4_autoware_utils::calcOffsetPose(pose, 0.0, -vehicle_width / 2.0, 0.0).position; marker.points.push_back(ub); marker.points.push_back(lb); @@ -605,13 +605,15 @@ visualization_msgs::msg::MarkerArray getLateralErrorsLineMarkerArray( visualization_msgs::msg::MarkerArray getCurrentVehicleCirclesMarkerArray( const geometry_msgs::msg::Pose & current_ego_pose, const std::vector & vehicle_circle_longitudinal_offsets, - const double vehicle_circle_radius, const std::string & ns, const double r, const double g, - const double b) + const std::vector & vehicle_circle_radiuses, const std::string & ns, const double r, + const double g, const double b) { visualization_msgs::msg::MarkerArray msg; size_t id = 0; - for (const double offset : vehicle_circle_longitudinal_offsets) { + for (size_t v_idx = 0; v_idx < vehicle_circle_longitudinal_offsets.size(); ++v_idx) { + const double offset = vehicle_circle_longitudinal_offsets.at(v_idx); + auto marker = createDefaultMarker( "map", rclcpp::Clock().now(), ns, id, visualization_msgs::msg::Marker::LINE_STRIP, createMarkerScale(0.05, 0.0, 0.0), createMarkerColor(r, g, b, 0.8)); @@ -624,8 +626,8 @@ visualization_msgs::msg::MarkerArray getCurrentVehicleCirclesMarkerArray( const double edge_angle = static_cast(e_idx) / static_cast(circle_dividing_num) * 2.0 * M_PI; - edge_pos.x = vehicle_circle_radius * std::cos(edge_angle); - edge_pos.y = vehicle_circle_radius * std::sin(edge_angle); + edge_pos.x = vehicle_circle_radiuses.at(v_idx) * std::cos(edge_angle); + edge_pos.y = vehicle_circle_radiuses.at(v_idx) * std::sin(edge_angle); marker.points.push_back(edge_pos); } @@ -639,8 +641,8 @@ visualization_msgs::msg::MarkerArray getCurrentVehicleCirclesMarkerArray( visualization_msgs::msg::MarkerArray getVehicleCirclesMarkerArray( const std::vector & mpt_traj_points, const std::vector & vehicle_circle_longitudinal_offsets, - const double vehicle_circle_radius, const size_t sampling_num, const std::string & ns, - const double r, const double g, const double b) + const std::vector & vehicle_circle_radiuses, const size_t sampling_num, + const std::string & ns, const double r, const double g, const double b) { visualization_msgs::msg::MarkerArray msg; @@ -651,7 +653,9 @@ visualization_msgs::msg::MarkerArray getVehicleCirclesMarkerArray( } const auto & mpt_traj_point = mpt_traj_points.at(i); - for (const double offset : vehicle_circle_longitudinal_offsets) { + for (size_t v_idx = 0; v_idx < vehicle_circle_longitudinal_offsets.size(); ++v_idx) { + const double offset = vehicle_circle_longitudinal_offsets.at(v_idx); + auto marker = createDefaultMarker( "map", rclcpp::Clock().now(), ns, id, visualization_msgs::msg::Marker::LINE_STRIP, createMarkerScale(0.05, 0.0, 0.0), createMarkerColor(r, g, b, 0.8)); @@ -664,8 +668,8 @@ visualization_msgs::msg::MarkerArray getVehicleCirclesMarkerArray( const double edge_angle = static_cast(e_idx) / static_cast(circle_dividing_num) * 2.0 * M_PI; - edge_pos.x = vehicle_circle_radius * std::cos(edge_angle); - edge_pos.y = vehicle_circle_radius * std::sin(edge_angle); + edge_pos.x = vehicle_circle_radiuses.at(v_idx) * std::cos(edge_angle); + edge_pos.y = vehicle_circle_radiuses.at(v_idx) * std::sin(edge_angle); marker.points.push_back(edge_pos); } @@ -754,7 +758,7 @@ visualization_msgs::msg::MarkerArray getDebugVisualizationMarker( // bounds appendMarkerArray( getBoundsLineMarkerArray( - debug_data_ptr->ref_points, 0.99, 0.99, 0.2, debug_data_ptr->vehicle_circle_radius, + debug_data_ptr->ref_points, 0.99, 0.99, 0.2, vehicle_param.width, debug_data_ptr->mpt_visualize_sampling_num), &vis_marker_array); @@ -770,7 +774,7 @@ visualization_msgs::msg::MarkerArray getDebugVisualizationMarker( // vehicle circle line appendMarkerArray( getVehicleCircleLineMarkerArray( - debug_data_ptr->vehicle_circles_pose, debug_data_ptr->vehicle_circle_radius, + debug_data_ptr->vehicle_circles_pose, vehicle_param.width, debug_data_ptr->mpt_visualize_sampling_num, "vehicle_circle_lines", 0.99, 0.99, 0.2), &vis_marker_array); @@ -785,14 +789,14 @@ visualization_msgs::msg::MarkerArray getDebugVisualizationMarker( appendMarkerArray( getCurrentVehicleCirclesMarkerArray( debug_data_ptr->current_ego_pose, debug_data_ptr->vehicle_circle_longitudinal_offsets, - debug_data_ptr->vehicle_circle_radius, "current_vehicle_circles", 1.0, 0.3, 0.3), + debug_data_ptr->vehicle_circle_radiuses, "current_vehicle_circles", 1.0, 0.3, 0.3), &vis_marker_array); // vehicle circles appendMarkerArray( getVehicleCirclesMarkerArray( debug_data_ptr->mpt_traj, debug_data_ptr->vehicle_circle_longitudinal_offsets, - debug_data_ptr->vehicle_circle_radius, debug_data_ptr->mpt_visualize_sampling_num, + debug_data_ptr->vehicle_circle_radiuses, debug_data_ptr->mpt_visualize_sampling_num, "vehicle_circles", 1.0, 0.3, 0.3), &vis_marker_array); diff --git a/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp b/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp index ec06ae4bd39f..bf3c02949ff9 100644 --- a/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp +++ b/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp @@ -41,17 +41,18 @@ geometry_msgs::msg::Pose convertRefPointsToPose(const ReferencePoint & ref_point } std::tuple extractBounds( - const std::vector & ref_points, const size_t l_idx) + const std::vector & ref_points, const size_t l_idx, const double offset) { Eigen::VectorXd ub_vec(ref_points.size()); Eigen::VectorXd lb_vec(ref_points.size()); for (size_t i = 0; i < ref_points.size(); ++i) { - ub_vec(i) = ref_points.at(i).vehicle_bounds.at(l_idx).upper_bound; - lb_vec(i) = ref_points.at(i).vehicle_bounds.at(l_idx).lower_bound; + ub_vec(i) = ref_points.at(i).vehicle_bounds.at(l_idx).upper_bound + offset; + lb_vec(i) = ref_points.at(i).vehicle_bounds.at(l_idx).lower_bound - offset; } return {ub_vec, lb_vec}; } +/* Bounds findWidestBounds(const BoundsCandidates & front_bounds_candidates) { double max_width = std::numeric_limits::min(); @@ -70,6 +71,33 @@ Bounds findWidestBounds(const BoundsCandidates & front_bounds_candidates) } return front_bounds_candidates.at(max_width_index); } +*/ + +Bounds findNearestBounds( + const geometry_msgs::msg::Pose & bounds_pose, const BoundsCandidates & front_bounds_candidates, + const geometry_msgs::msg::Point & target_pos) +{ + double min_dist = std::numeric_limits::max(); + size_t min_dist_index = 0; + if (front_bounds_candidates.size() != 1) { + for (size_t candidate_idx = 0; candidate_idx < front_bounds_candidates.size(); + ++candidate_idx) { + const auto & front_bounds_candidate = front_bounds_candidates.at(candidate_idx); + + const double bound_center = + (front_bounds_candidate.upper_bound + front_bounds_candidate.lower_bound) / 2.0; + const auto center_pos = + tier4_autoware_utils::calcOffsetPose(bounds_pose, 0.0, bound_center, 0.0); + const double dist = tier4_autoware_utils::calcDistance2d(center_pos, target_pos); + + if (dist < min_dist) { + min_dist_index = candidate_idx; + min_dist = dist; + } + } + } + return front_bounds_candidates.at(min_dist_index); +} double calcOverlappedBoundsSignedLength( const Bounds & prev_front_continuous_bounds, const Bounds & front_bounds_candidate) @@ -351,7 +379,7 @@ std::vector MPTOptimizer::getReferencePoints( ref_points = points_utils::clipForwardPoints(ref_points, 0, ref_length_with_margin); // set bounds information - calcBounds(ref_points, enable_avoidance, maps, debug_data_ptr); + calcBounds(ref_points, enable_avoidance, maps, prev_trajs, debug_data_ptr); calcVehicleBounds(ref_points, maps, debug_data_ptr, enable_avoidance); // set extra information (alpha and has_object_collision) @@ -990,7 +1018,9 @@ MPTOptimizer::ConstraintMatrix MPTOptimizer::getConstraintMatrix( const Eigen::VectorXd CW = C_sparse_mat * mpt_mat.Wex + C_vec; // calculate bounds - const auto & [part_ub, part_lb] = extractBounds(ref_points, l_idx); + const double bounds_offset = + vehicle_param_.width / 2.0 - mpt_param_.vehicle_circle_radiuses.at(l_idx); + const auto & [part_ub, part_lb] = extractBounds(ref_points, l_idx, bounds_offset); // soft constraints if (mpt_param_.soft_constraint) { @@ -1331,7 +1361,7 @@ void MPTOptimizer::addSteerWeightR( void MPTOptimizer::calcBounds( std::vector & ref_points, const bool enable_avoidance, const CVMaps & maps, - std::shared_ptr debug_data_ptr) const + const std::unique_ptr & prev_trajs, std::shared_ptr debug_data_ptr) const { stop_watch_.tic(__func__); @@ -1350,8 +1380,19 @@ void MPTOptimizer::calcBounds( // extract only continuous bounds; if (i == 0) { // TODO(murooka) use previous bounds, not widest bounds - const auto & widest_bounds = findWidestBounds(bounds_candidates); - ref_points.at(i).bounds = widest_bounds; + const auto target_pos = [&]() { + if (prev_trajs && !prev_trajs->mpt_ref_points.empty()) { + return prev_trajs->mpt_ref_points.front().p; + } + return current_ego_pose_.position; + }(); + + geometry_msgs::msg::Pose ref_pose; + ref_pose.position = ref_points.at(i).p; + ref_pose.orientation = tier4_autoware_utils::createQuaternionFromYaw(ref_points.at(i).yaw); + + const auto & nearest_bounds = findNearestBounds(ref_pose, bounds_candidates, target_pos); + ref_points.at(i).bounds = nearest_bounds; } else { const auto & prev_ref_point = ref_points.at(i - 1); const auto & prev_continuous_bounds = prev_ref_point.bounds; @@ -1457,7 +1498,7 @@ void MPTOptimizer::calcVehicleBounds( // interpolate bounds const double avoid_s = ref_points_spline_interpolation.getAccumulatedLength(p_idx) + d; - for (size_t cp_idx = p_idx; cp_idx < ref_points.size(); ++cp_idx) { + for (size_t cp_idx = 0; cp_idx < ref_points.size(); ++cp_idx) { const double current_s = ref_points_spline_interpolation.getAccumulatedLength(cp_idx); if (avoid_s <= current_s) { double prev_avoid_idx; @@ -1612,11 +1653,10 @@ CollisionType MPTOptimizer::getCollisionType( const double traversed_dist, const double bound_angle) const { // calculate clearance - const double min_soft_road_clearance = mpt_param_.vehicle_circle_radius + + const double min_soft_road_clearance = vehicle_param_.width / 2.0 + mpt_param_.soft_clearance_from_road + mpt_param_.extra_desired_clearance_from_road; - const double min_obj_clearance = mpt_param_.vehicle_circle_radius + - mpt_param_.clearance_from_object + + const double min_obj_clearance = vehicle_param_.width / 2.0 + mpt_param_.clearance_from_object + mpt_param_.soft_clearance_from_road; // calculate target position diff --git a/planning/obstacle_avoidance_planner/src/node.cpp b/planning/obstacle_avoidance_planner/src/node.cpp index 74804cb66174..ad5d93395210 100644 --- a/planning/obstacle_avoidance_planner/src/node.cpp +++ b/planning/obstacle_avoidance_planner/src/node.cpp @@ -138,26 +138,52 @@ bool hasValidNearestPointFromEgo( return true; } -std::tuple> calcVehicleCirclesInfo( - const VehicleParam & vehicle_param, const size_t circle_num_for_constraints, - const size_t circle_num_for_radius, const double radius_ratio) +std::tuple, std::vector> calcVehicleCirclesInfo( + const VehicleParam & vehicle_param, const size_t circle_num, const double rear_radius_ratio, + const double front_radius_ratio) { - const double radius = std::hypot( - vehicle_param.length / static_cast(circle_num_for_radius) / 2.0, - vehicle_param.width / 2.0) * - radius_ratio; + std::vector longitudinal_offsets; + std::vector radiuses; + + { // 1st circle (rear) + longitudinal_offsets.push_back(-vehicle_param.rear_overhang); + radiuses.push_back(vehicle_param.width / 2.0 * rear_radius_ratio); + } + + { // 2nd circle (front) + const double radius = std::hypot( + vehicle_param.length / static_cast(circle_num) / 2.0, vehicle_param.width / 2.0); + const double unit_lon_length = vehicle_param.length / static_cast(circle_num); + const double longitudinal_offset = + unit_lon_length / 2.0 + unit_lon_length * (circle_num - 1) - vehicle_param.rear_overhang; + + longitudinal_offsets.push_back(longitudinal_offset); + radiuses.push_back(radius * front_radius_ratio); + } + + return {radiuses, longitudinal_offsets}; +} + +std::tuple, std::vector> calcVehicleCirclesInfo( + const VehicleParam & vehicle_param, const size_t circle_num, const double radius_ratio) +{ std::vector longitudinal_offsets; - const double unit_lon_length = vehicle_param.length / static_cast(circle_num_for_radius); - for (size_t i = 0; i < circle_num_for_constraints; ++i) { + std::vector radiuses; + + const double radius = + std::hypot( + vehicle_param.length / static_cast(circle_num) / 2.0, vehicle_param.width / 2.0) * + radius_ratio; + const double unit_lon_length = vehicle_param.length / static_cast(circle_num); + + for (size_t i = 0; i < circle_num; ++i) { longitudinal_offsets.push_back( - unit_lon_length / 2.0 + - (unit_lon_length * (circle_num_for_radius - 1)) / - static_cast(circle_num_for_constraints - 1) * i - - vehicle_param.rear_overhang); + unit_lon_length / 2.0 + unit_lon_length * i - vehicle_param.rear_overhang); + radiuses.push_back(radius); } - return {radius, longitudinal_offsets}; + return {radiuses, longitudinal_offsets}; } [[maybe_unused]] void fillYawInTrajectoryPoint( @@ -268,41 +294,6 @@ ObstacleAvoidancePlanner::ObstacleAvoidancePlanner(const rclcpp::NodeOptions & n is_stopping_if_outside_drivable_area_ = declare_parameter("option.is_stopping_if_outside_drivable_area"); - // drivability check - use_vehicle_circles_for_drivability_ = - declare_parameter("advanced.option.drivability_check.use_vehicle_circles"); - if (use_vehicle_circles_for_drivability_) { - // vehicle_circles - // NOTE: Vehicle shape for drivability check is considered as a set of circles - use_manual_vehicle_circles_for_drivability_ = declare_parameter( - "advanced.option.drivability_check.vehicle_circles.use_manual_vehicle_circles"); - vehicle_circle_constraints_num_for_drivability_ = declare_parameter( - "advanced.option.drivability_check.vehicle_circles.num_for_constraints"); - if (use_manual_vehicle_circles_for_drivability_) { // vehicle circles are designated manually - vehicle_circle_longitudinal_offsets_for_drivability_ = - declare_parameter>( - "advanced.option.drivability_check.vehicle_circles.longitudinal_offsets"); - vehicle_circle_radius_for_drivability_ = - declare_parameter("advanced.option.drivability_check.vehicle_circles.radius"); - } else { // vehicle circles are calculated automatically with designated ratio - const int default_radius_num = - std::round(vehicle_param_.length / vehicle_param_.width * 1.5); - - vehicle_circle_radius_num_for_drivability_ = declare_parameter( - "advanced.option.drivability_check.vehicle_circles.num_for_radius", default_radius_num); - vehicle_circle_radius_ratio_for_drivability_ = declare_parameter( - "advanced.option.drivability_check.vehicle_circles.radius_ratio"); - - std::tie( - vehicle_circle_radius_for_drivability_, - vehicle_circle_longitudinal_offsets_for_drivability_) = - calcVehicleCirclesInfo( - vehicle_param_, vehicle_circle_constraints_num_for_drivability_, - vehicle_circle_radius_num_for_drivability_, - vehicle_circle_radius_ratio_for_drivability_); - } - } - enable_avoidance_ = declare_parameter("option.enable_avoidance"); enable_pre_smoothing_ = declare_parameter("option.enable_pre_smoothing"); skip_optimization_ = declare_parameter("option.skip_optimization"); @@ -436,30 +427,40 @@ ObstacleAvoidancePlanner::ObstacleAvoidancePlanner(const rclcpp::NodeOptions & n // mpt_param_.two_step_soft_constraint = // declare_parameter("advanced.mpt.collision_free_constraints.option.two_step_soft_constraint"); - // vehicle_circles - // NOTE: Vehicle shape for collision free constraints is considered as a set of circles - use_manual_vehicle_circles_for_mpt_ = declare_parameter( - "advanced.mpt.collision_free_constraints.vehicle_circles.use_manual_vehicle_circles"); - vehicle_circle_constraints_num_for_mpt_ = declare_parameter( - "advanced.mpt.collision_free_constraints.vehicle_circles.num_for_constraints"); - if (use_manual_vehicle_circles_for_mpt_) { // vehicle circles are designated manually - mpt_param_.vehicle_circle_longitudinal_offsets = declare_parameter>( - "advanced.mpt.collision_free_constraints.vehicle_circles.longitudinal_offsets"); - mpt_param_.vehicle_circle_radius = - declare_parameter("advanced.mpt.collision_free_constraints.vehicle_circles.radius"); - } else { // vehicle circles are calculated automatically with designated ratio - const int default_radius_num = std::round(vehicle_param_.length / vehicle_param_.width * 1.5); - - vehicle_circle_radius_num_for_mpt_ = declare_parameter( - "advanced.mpt.collision_free_constraints.vehicle_circles.num_for_radius", - default_radius_num); - vehicle_circle_radius_ratio_for_mpt_ = declare_parameter( - "advanced.mpt.collision_free_constraints.vehicle_circles.radius_ratio"); - - std::tie(mpt_param_.vehicle_circle_radius, mpt_param_.vehicle_circle_longitudinal_offsets) = - calcVehicleCirclesInfo( - vehicle_param_, vehicle_circle_constraints_num_for_mpt_, - vehicle_circle_radius_num_for_mpt_, vehicle_circle_radius_ratio_for_mpt_); + { // vehicle_circles + // NOTE: Vehicle shape for collision free constraints is considered as a set of circles + vehicle_circle_method_ = declare_parameter( + "advanced.mpt.collision_free_constraints.vehicle_circles.method"); + + if (vehicle_circle_method_ == "uniform_circle") { + vehicle_circle_num_for_calculation_ = declare_parameter( + "advanced.mpt.collision_free_constraints.vehicle_circles.uniform_circle.num"); + vehicle_circle_radius_ratios_.push_back(declare_parameter( + "advanced.mpt.collision_free_constraints.vehicle_circles.uniform_circle.radius_ratio")); + + std::tie( + mpt_param_.vehicle_circle_radiuses, mpt_param_.vehicle_circle_longitudinal_offsets) = + calcVehicleCirclesInfo( + vehicle_param_, vehicle_circle_num_for_calculation_, + vehicle_circle_radius_ratios_.front()); + } else if (vehicle_circle_method_ == "rear_drive") { + vehicle_circle_num_for_calculation_ = declare_parameter( + "advanced.mpt.collision_free_constraints.vehicle_circles.rear_drive.num_for_calculation"); + + vehicle_circle_radius_ratios_.push_back(declare_parameter( + "advanced.mpt.collision_free_constraints.vehicle_circles.rear_drive.rear_radius_ratio")); + vehicle_circle_radius_ratios_.push_back(declare_parameter( + "advanced.mpt.collision_free_constraints.vehicle_circles.rear_drive.front_radius_ratio")); + + std::tie( + mpt_param_.vehicle_circle_radiuses, mpt_param_.vehicle_circle_longitudinal_offsets) = + calcVehicleCirclesInfo( + vehicle_param_, vehicle_circle_num_for_calculation_, + vehicle_circle_radius_ratios_.front(), vehicle_circle_radius_ratios_.back()); + } else { + throw std::invalid_argument( + "advanced.mpt.collision_free_constraints.vehicle_circles.num parameter is invalid."); + } } // clearance @@ -554,42 +555,6 @@ rcl_interfaces::msg::SetParametersResult ObstacleAvoidancePlanner::paramCallback parameters, "option.is_stopping_if_outside_drivable_area", is_stopping_if_outside_drivable_area_); - // drivability check - updateParam( - parameters, "advanced.option.drivability_check.use_vehicle_circles", - use_vehicle_circles_for_drivability_); - if (use_vehicle_circles_for_drivability_) { - updateParam( - parameters, "advanced.option.drivability_check.vehicle_circles.use_manual_vehicle_circles", - use_manual_vehicle_circles_for_drivability_); - updateParam( - parameters, "advanced.option.drivability_check.vehicle_circles.num_for_constraints", - vehicle_circle_constraints_num_for_drivability_); - if (use_manual_vehicle_circles_for_drivability_) { - updateParam>( - parameters, "advanced.option.drivability_check.vehicle_circles.longitudinal_offsets", - vehicle_circle_longitudinal_offsets_for_drivability_); - updateParam( - parameters, "advanced.option.drivability_check.vehicle_circles.radius", - vehicle_circle_radius_for_drivability_); - } else { - updateParam( - parameters, "advanced.option.drivability_check.vehicle_circles.num_for_radius", - vehicle_circle_radius_num_for_drivability_); - updateParam( - parameters, "advanced.option.drivability_check.vehicle_circles.radius_ratio", - vehicle_circle_radius_ratio_for_drivability_); - - std::tie( - vehicle_circle_radius_for_drivability_, - vehicle_circle_longitudinal_offsets_for_drivability_) = - calcVehicleCirclesInfo( - vehicle_param_, vehicle_circle_constraints_num_for_drivability_, - vehicle_circle_radius_num_for_drivability_, - vehicle_circle_radius_ratio_for_drivability_); - } - } - updateParam(parameters, "option.enable_avoidance", enable_avoidance_); updateParam(parameters, "option.enable_pre_smoothing", enable_pre_smoothing_); updateParam(parameters, "option.skip_optimization", skip_optimization_); @@ -719,33 +684,51 @@ rcl_interfaces::msg::SetParametersResult ObstacleAvoidancePlanner::paramCallback parameters, "advanced.mpt.collision_free_constraints.option.hard_constraint", mpt_param_.hard_constraint); - // vehicle_circles - updateParam( - parameters, - "advanced.mpt.collision_free_constraints.vehicle_circles.use_manual_vehicle_circles", - use_manual_vehicle_circles_for_mpt_); - updateParam( - parameters, "advanced.mpt.collision_free_constraints.vehicle_circles.num_for_constraints", - vehicle_circle_constraints_num_for_mpt_); - if (use_manual_vehicle_circles_for_mpt_) { - updateParam>( - parameters, "advanced.mpt.collision_free_constraints.vehicle_circles.longitudinal_offsets", - mpt_param_.vehicle_circle_longitudinal_offsets); - updateParam( - parameters, "advanced.mpt.collision_free_constraints.vehicle_circles.radius", - mpt_param_.vehicle_circle_radius); - } else { // vehicle circles are calculated automatically with designated ratio - updateParam( - parameters, "advanced.mpt.collision_free_constraints.vehicle_circles.num_for_radius", - vehicle_circle_radius_num_for_mpt_); - updateParam( - parameters, "advanced.mpt.collision_free_constraints.vehicle_circles.radius_ratio", - vehicle_circle_radius_ratio_for_mpt_); - - std::tie(mpt_param_.vehicle_circle_radius, mpt_param_.vehicle_circle_longitudinal_offsets) = - calcVehicleCirclesInfo( - vehicle_param_, vehicle_circle_constraints_num_for_mpt_, - vehicle_circle_radius_num_for_mpt_, vehicle_circle_radius_ratio_for_mpt_); + { // vehicle_circles + // NOTE: Changing method is not supported + // updateParam( + // parameters, "advanced.mpt.collision_free_constraints.vehicle_circles.method", + // vehicle_circle_method_); + + if (vehicle_circle_method_ == "uniform_circle") { + updateParam( + parameters, "advanced.mpt.collision_free_constraints.vehicle_circles.uniform_circle.num", + vehicle_circle_num_for_calculation_); + updateParam( + parameters, + "advanced.mpt.collision_free_constraints.vehicle_circles.uniform_circle.radius_ratio", + vehicle_circle_radius_ratios_.front()); + + std::tie( + mpt_param_.vehicle_circle_radiuses, mpt_param_.vehicle_circle_longitudinal_offsets) = + calcVehicleCirclesInfo( + vehicle_param_, vehicle_circle_num_for_calculation_, + vehicle_circle_radius_ratios_.front()); + } else if (vehicle_circle_method_ == "rear_drive") { + updateParam( + parameters, + "advanced.mpt.collision_free_constraints.vehicle_circles.rear_drive.num_for_calculation", + vehicle_circle_num_for_calculation_); + + updateParam( + parameters, + "advanced.mpt.collision_free_constraints.vehicle_circles.rear_drive.rear_radius_ratio", + vehicle_circle_radius_ratios_.front()); + + updateParam( + parameters, + "advanced.mpt.collision_free_constraints.vehicle_circles.rear_drive.front_radius_ratio", + vehicle_circle_radius_ratios_.back()); + + std::tie( + mpt_param_.vehicle_circle_radiuses, mpt_param_.vehicle_circle_longitudinal_offsets) = + calcVehicleCirclesInfo( + vehicle_param_, vehicle_circle_num_for_calculation_, + vehicle_circle_radius_ratios_.front(), vehicle_circle_radius_ratios_.back()); + } else { + throw std::invalid_argument( + "advanced.mpt.collision_free_constraints.vehicle_circles.num parameter is invalid."); + } } // clearance @@ -879,7 +862,7 @@ void ObstacleAvoidancePlanner::pathCallback( debug_data_ptr_ = std::make_shared(); debug_data_ptr_->init( is_showing_calculation_time_, mpt_visualize_sampling_num_, current_ego_pose_, - mpt_param_.vehicle_circle_radius, mpt_param_.vehicle_circle_longitudinal_offsets); + mpt_param_.vehicle_circle_radiuses, mpt_param_.vehicle_circle_longitudinal_offsets); // generate optimized trajectory const auto optimized_traj_points = generateOptimizedTrajectory(*path_ptr); @@ -1156,16 +1139,8 @@ void ObstacleAvoidancePlanner::insertZeroVelocityOutsideDrivableArea( const auto & traj_point = traj_points.at(i); // calculate the first point being outside drivable area - const bool is_outside = [&]() { - if (use_vehicle_circles_for_drivability_) { - return cv_drivable_area_utils::isOutsideDrivableAreaFromCirclesFootprint( - traj_point, road_clearance_map, map_info, - vehicle_circle_longitudinal_offsets_for_drivability_, - vehicle_circle_radius_for_drivability_); - } - return cv_drivable_area_utils::isOutsideDrivableAreaFromRectangleFootprint( - traj_point, road_clearance_map, map_info, vehicle_param_); - }(); + const bool is_outside = cv_drivable_area_utils::isOutsideDrivableAreaFromRectangleFootprint( + traj_point, road_clearance_map, map_info, vehicle_param_); // only insert zero velocity to the first point outside drivable area if (is_outside) { From 3949ef12d345befc0c739a0e2a66489cb51aa331 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 20 May 2022 12:45:08 +0900 Subject: [PATCH 47/55] chore(obstacle_avoidance_planner): removed obsolete obstacle_avoidance_planner doc in Japanese (#919) Signed-off-by: Takayuki Murooka --- .../obstacle_avoidance_planner-design.ja.md | 330 ------------------ 1 file changed, 330 deletions(-) delete mode 100644 planning/obstacle_avoidance_planner/obstacle_avoidance_planner-design.ja.md diff --git a/planning/obstacle_avoidance_planner/obstacle_avoidance_planner-design.ja.md b/planning/obstacle_avoidance_planner/obstacle_avoidance_planner-design.ja.md deleted file mode 100644 index 8610070c4871..000000000000 --- a/planning/obstacle_avoidance_planner/obstacle_avoidance_planner-design.ja.md +++ /dev/null @@ -1,330 +0,0 @@ -# Obstacle Avoidance Planner - -## Purpose - -obstacle_avoidance_planner は入力された path と drivable area、および動物体情報をもとに、車両キネマティクスモデルを考慮して車が走行可能な軌道を生成する。trajectory 内の各経路点の位置姿勢のみ計画しており、速度や加速度の計算は後段の別モジュールで行われる。 - - - -## Inputs / Outputs - -### input - -- reference_path [`autoware_auto_planning_msgs/Path`] : Reference path and the corresponding drivable area. -- objects [`autoware_auto_perception_msgs/PredictedObjects`] : Recognized objects around the vehicle - -### output - -- optimized_trajectory [`autoware_auto_planning_msgs/Trajectory`] : Optimized trajectory that is feasible to drive and collision-free. - -## Flowchart - -フローチャートとともに、各機能の概要をおおまかに説明する。 - -![obstacle_avoidance_planner_flowchart](./media/obstacle_avoidance_planner_flowchart.drawio.svg) - -### Manage trajectory generation - -以下の条件のいずれかが満たされたときに、経路生成の関数を呼ぶ。それ以外の時は前回生成された経路を出力する。 - -- 前回経路生成時から一定距離走行 (default: 10.0 [m]) -- 一定時間経過 (default: 1.0 [s]) -- レーンチェンジなどで入力の path の形状が変わった時 -- 自車位置が前回経路から大きく外れた時 - -入力の path の形状が変わった時と自車が前回経路から大きく外れた時は、保持している前回経路を破棄するリセット機能もある。 - -### Select objects to avoid - -静的で路肩にある障害物のみ回避対象とする。 -具体的には、以下の 3 つの条件を満たすものであり、図で示すと赤い id: 3, 4, 5 の物体である。 - -- 指定された速度以下 (default: 0.1 [m/s]) -- 物体重心が center line 上に存在しない(前車追従の車を避けないようにするため) -- 少なくとも 1 つ以上の物体形状ポリゴン点が drivable area に存在する。 - -![obstacle_to_avoid](./media/obstacle_to_avoid.drawio.svg) - -### Generate object costmap - -回避対象である障害物からの距離に応じたコストマップを生成する。 - -### Generate road boundary costmap - -道路からの距離に応じたコストマップを生成する。 - -これらのコストマップは後段の Optimize trajectory の手法である Model predictive trajectory の障害物・道路境界に衝突しない制約条件を定式化する際に使用される。 - -### Smooth path - -後段の最適化処理で曲率のなめらかな参照経路が必要であるため、最適化前に path をなめらかにして trajectory の形式で出力する。 -この平滑化は障害物を考慮しない。 - -### Optimize trajectory - -参照経路に基づいたフレネ座標系で車両キネマティクス、及び追従誤差を定義し、二次計画法を用いて車両キネマティクスや障害物回避を考慮しながら追従誤差が小さくなるように経路生成する。 -自車近傍の経路の急な変化を防ぐため、直近の経路は前回の経路をそのまま使用する。 -計算コストを抑えるため、最終的に出力する経路長よりも短い距離に対してのみ計算を行う。 - -### Extend trajectory - -経路を規定の長さ(default: 200m)に拡張するため、最適化した経路の先を Reference 経路と接続する。 - -### Check drivable area - -生成された経路が走行可能領域を逸脱していた場合、前回生成された走行可能領域内にある経路を出力する。 - -_Rationale_ -現在の設計において、数値誤差による破綻を防ぐために障害物回避は全てソフト制約として考慮されており、生成された経路に置いて車両が走行可能領域内に入っているかの判定が必要。 - -### Apply path velocity - -入力の path に埋め込まれている速度を出力される trajectory に埋め込む。経路間隔が異なるため線形補間を用いる。 - -## Algorithms - -Smooth path で使われている Elastic band と、Optimized trajectory で使われている Model predictive trajectory の詳細な説明をする。 - -### Elastic band - -#### 概要 - -behavior_path_planner で計算された path は場合によってはなめらかではない可能性があるので、その path の平滑化をすることが目的である。 - -次の Model predictive trajectory でも平滑化項は入っているが、目標経路になるべく追従しようとする項も入っているため、目標経路がなめらかでなかった場合はこの 2 つの項が反発する。 -それを防ぐためにここで平滑化のみを行っている。 -また Model predictive trajectory では各点における曲率と法線を元に最適化しており、平滑化された目標経路を渡すことで最適化の結果を安定させる狙いもある。 - -平滑化の際、障害物や道路壁を考慮していないため障害物や道路壁に衝突した trajectory が計算されることもある。 - -この Elastic band と次の Model predictive trajectory は、計算負荷を抑えるためにある程度の長さでクリップした trajectory を出力するようになっている。 - -#### 数式 - -前後の点からの距離の差の二乗を目的関数とする二次計画。 - -各点は一定の範囲以内しか動かないという制約を設けることで、入力の軌道をよりなめらかにした軌道を得る。 - -$\boldsymbol{p}_k$を$k$番目の経路点の座標ととしたとき以下のコスト関数を最小化する二次計画を解く。ここでは始点と終点である$\boldsymbol{p}_0$と$\boldsymbol{p}_n$は固定である。 - -$$ -\min \sum_{k=1}^{n-1} |\boldsymbol{p}_{k+1} - \boldsymbol{p}_{k}| - |\boldsymbol{p}_{k} - \boldsymbol{p}_{k-1}| -$$ - -### Model predictive trajectory - -#### 概要 - -Elastic band で平滑化された trajectory に対して、以下の条件を満たすように修正を行うことが目的である。 - -- 線形化された車両のキネマティクスモデルに基づき走行可能である -- 障害物や道路壁面に衝突しない - -障害物や道路壁面に衝突しない条件はハードではなくソフト制約として含まれている。車両の後輪位置、前輪位置、その中心位置において障害物・道路境界との距離から制約条件が計算されている。 -条件を満たさない解が出力された場合は、後段の後処理で弾かれ、前の周期で計画された trajectory を出力する。 - -自車付近の経路が振動しないように、自車近傍の経路点を前回の経路点と一致させる制約条件も含まれており、これが唯一の二次計画法のハード制約である。 - -#### 数式 - -以下のように、経路に対して車両が追従するときの bicycle kinematics model を考える。 -時刻$k$における、経路上の車両の最近傍点の座標($x$座標は経路の接線に平行)から見た追従誤差に関して、横偏差$y_k$、向きの偏差$\theta_k$、ステア角$\delta_k$と定める。 - -![vehicle_error_kinematics](./media/vehicle_error_kinematics.png) - -指令ステア角度を$\delta_{des, k}$とすると、ステア角の遅延を考慮した車両キネマティクスモデルは以下で表される。この時、ステア角$\delta_k$は一次遅れ系として指令ステア角に追従すると仮定する。 - -$$ -\begin{align} -y_{k+1} & = y_{k} + v \sin \theta_k dt \\ -\theta_{k+1} & = \theta_k + \frac{v \tan \delta_k}{L}dt - \kappa_k v \cos \theta_k dt \\ -\delta_{k+1} & = \delta_k - \frac{\delta_k - \delta_{des,k}}{\tau}dt -\end{align} -$$ - -次にこれらの式を線形化する。$y_k$, $\theta_k$は追従誤差であるため微小近似でき、$\sin \theta_k \approx \theta_k$となる。 - -$\delta_k$に関してはステア角であるため微小とみなせない。そこで、以下のように参照経路の曲率$\kappa_k$から計算されるステア角$\delta_{\mathrm{ref}, k}$を用いることにより、$\delta_k$を微小な値$\Delta \delta_k$で表す。 - -ここで注意すべきこととしては、$\delta_k$は最大ステア角度$\delta_{\max}$以内の値を取る。曲率$\kappa_k$から計算された$\delta_{\mathrm{ref}, k}$が最大ステア角度$\delta_{\max}$より大きいときに$\delta_{\mathrm{ref}, k}$をそのまま使用して線形化すると、$\Delta \delta_k = \delta - \delta_{\mathrm{ref}, k} = \delta_{\max} - \delta_{\mathrm{ref}, k}$となり、$\Delta \delta_k$の絶対値が大きくなる。すなわち、$\delta_{\mathrm{ref}, k}$にも最大ステア角度制限を適用する必要がある。 - -$$ -\begin{align} -\delta_{\mathrm{ref}, k} & = \mathrm{clamp}(\arctan(L \kappa_k), -\delta_{\max}, \delta_{\max}) \\ -\delta_k & = \delta_{\mathrm{ref}, k} + \Delta \delta_k, \ \Delta \delta_k \ll 1 \\ -\end{align} -$$ - -$\mathrm{clamp}(v, v_{\min}, v_{\max})$は$v$を$v_{\min}$から$v_{\max}$の範囲内に丸める関数である。 - -この$\delta_{\mathrm{ref}, k}$を介して$\tan \delta_k$を線形な式で近似する。 - -$$ -\begin{align} -\tan \delta_k & \approx \tan \delta_{\mathrm{ref}, k} + \left.\frac{d \tan \delta}{d \delta}\right|_{\delta = \delta_{\mathrm{ref}, k}} \Delta \delta_k \\ -& = \tan \delta_{\mathrm{ref}, k} + \left.\frac{d \tan \delta}{d \delta}\right|_{\delta = \delta_{\mathrm{ref}, k}} (\delta_{\mathrm{ref}, k} - \delta_k) \\ -& = \tan \delta_{\mathrm{ref}, k} - \frac{\delta_{\mathrm{ref}, k}}{\cos^2 \delta_{\mathrm{ref}, k}} + \frac{1}{\cos^2 \delta_{\mathrm{ref}, k}} \delta_k -\end{align} -$$ - -以上の線形化を踏まえ、誤差ダイナミクスは以下のように線形な行列演算で記述できる。 - -$$ -\begin{align} - \begin{pmatrix} - y_{k+1} \\ - \theta_{k+1} \\ - \delta_{k+1} - \end{pmatrix} - = - \begin{pmatrix} - 1 & v dt & 0 \\ - 0 & 1 & \frac{v dt}{L \cos^{2} \delta_{\mathrm{ref}, k}} \\ - 0 & 0 & 1 - \frac{dt}{\tau} - \end{pmatrix} - \begin{pmatrix} - y_k \\ - \theta_k \\ - \delta_k - \end{pmatrix} - + - \begin{pmatrix} - 0 \\ - 0 \\ - \frac{dt}{\tau} - \end{pmatrix} - \delta_{des} - + - \begin{pmatrix} - 0 \\ - \frac{v \tan(\delta_{\mathrm{ref}, k}) dt}{L} - \frac{v \delta_{\mathrm{ref}, k} dt}{L \cos^{2} \delta_{\mathrm{ref}, k}} - \kappa_k v dt\\ - 0 - \end{pmatrix} -\end{align} -$$ - -平滑化と経路追従のための目的関数は以下で表され、 - -$$ -\begin{align} -J_1 & (y_{0...N-1}, \theta_{0...N-1}, \delta_{0...N-1}) \\ & = w_y \sum_{k} y_k^2 + w_{\theta} \sum_{k} \theta_k^2 + w_{\delta} \sum_k \delta_k^2 + w_{\dot{\delta}} \sum_k \dot{\delta}_k^2 + w_{\ddot{\delta}} \sum_k \ddot{\delta}_k^2 -\end{align} -$$ - -前述の通り、車両が障害物・道路境界に侵入しない条件はスラック変数を用いてソフト制約として表されている。 -車両の後輪位置、前輪位置、およびその中心位置における障害物・道路境界までの距離をそれぞれ$y_{\mathrm{base}, k}, y_{\mathrm{top}, k}, y_{\mathrm{mid}, k}$とする。 -ここでそれぞれに対するスラック変数 $\lambda_{\mathrm{base}}, \lambda_{\mathrm{top}}, \lambda_{\mathrm{mid}}$を定義し、 - -$$ -y_{\mathrm{base}, k, \min} - \lambda_{\mathrm{base}, k} \leq y_{\mathrm{base}, k} (y_k) \leq y_{\mathrm{base}, k, \max} + \lambda_{\mathrm{base}, k}\\ -y_{\mathrm{top}, k, \min} - \lambda_{\mathrm{top}, k} \leq y_{\mathrm{top}, k} (y_k) \leq y_{\mathrm{top}, k, \max} + \lambda_{\mathrm{top}, k}\\ -y_{\mathrm{mid}, k, \min} - \lambda_{\mathrm{mid}, k} \leq y_{\mathrm{mid}, k} (y_k) \leq y_{\mathrm{mid}, k, \max} + \lambda_{\mathrm{mid}, k} -$$ - -$y_{\mathrm{base}, k}, y_{\mathrm{top}, k}, y_{\mathrm{mid}, k}$は$y_k$の 1 次式として表現できるので、このソフト制約の目的関数は、以下のように記述できる。 - -$$ -\begin{align} -J_2 & (\lambda_{\mathrm{base}, 0...N-1}, \lambda_{\mathrm{mid}, 0...N-1}, \lambda_{\mathrm{top}, 0...N-1}) \\ & = w_{\mathrm{base}} \sum_{k} \lambda_{\mathrm{base}, k}^2 + w_{\mathrm{mid}} \sum_k \lambda_{\mathrm{mid}, k}^2 + w_{\mathrm{top}} \sum_k \lambda_{\mathrm{top}, k}^2 -\end{align} -$$ - -スラック変数も二次計画法の設計変数となり、全ての設計変数をまとめたベクトル$\boldsymbol{x}$を定義する。 - -$$ -\begin{align} -\boldsymbol{x} = -\begin{pmatrix} -... & y_k & \lambda_{\mathrm{base}, k} & \lambda_{\mathrm{top}, k} & \lambda_{\mathrm{mid}, k} & ... -\end{pmatrix}^T -\end{align} -$$ - -これらの 2 つの目的関数の和を目的関数とする。 - -$$ -\begin{align} -\min_{\boldsymbol{x}} J (\boldsymbol{x}) = \min_{\boldsymbol{x}} J_1 & (y_{0...N-1}, \theta_{0...N-1}, \delta_{0...N-1}) + J_2 (\lambda_{\mathrm{base}, 0...N-1}, \lambda_{\mathrm{mid}, 0...N-1}, \lambda_{\mathrm{top}, 0...N-1}) -\end{align} -$$ - -前述の通り、真にハードな制約条件は車両前方ある程度の距離$N_{fix}$までの経路点の状態は前回値になるような条件であり、以下のように記述できる。 - -$$ -\begin{align} -\delta_k = \delta_{k}^{\mathrm{prev}} (0 \leq i \leq N_{\mathrm{fix}}) -\end{align} -$$ - -であり、これらを以下のような二次計画法の係数行列に変換して二次計画法を解く - -$$ -\begin{align} -\min_{\boldsymbol{x}} \ & \frac{1}{2} \boldsymbol{x}^T \boldsymbol{P} \boldsymbol{x} + \boldsymbol{q} \boldsymbol{x} \\ -\mathrm{s.t.} \ & \boldsymbol{b}_l \leq \boldsymbol{A} \boldsymbol{x} \leq \boldsymbol{b}_u -\end{align} -$$ - -## Limitation - -- カーブ時に外側に膨らんだ経路を返す -- behavior_path_planner と obstacle_avoidance_planner の経路計画の役割分担がはっきりと決まっていない - - behavior_path_planner 側で回避する場合と、obstacle_avoidance_planner で回避する場合がある -- behavior_path_planner から来る path が道路壁に衝突していると、大きく外側に膨れた trajectory を計画する (柏の葉のカーブで顕著) -- 計算負荷が高い - -## How to debug - -obstacle_avoidance_planner` から出力される debug 用の topic について説明する。 - -- **interpolated_points_marker** - - obstacle avoidance planner への入力経路をリサンプルしたもの。この経路が道路内に収まっているか(道路内にあることが必須ではない)、十分になめらかか(ある程度滑らかでないとロジックが破綻する)、などを確認する。 - -![interpolated_points_marker](./media/interpolated_points_marker.png) - -- **smoothed_points_text** - - Elastic Band の計算結果。点群ではなく小さい数字が描画される。平滑化されたこの経路が道路内からはみ出ていないか、歪んでいないかなどを確認。 - -![smoothed_points_text](./media/smoothed_points_text.png) - -- **(base/top/mid)\_bounds_line** - - 壁との衝突判定における横方向の道路境界までの距離(正確には - vehicle_width / 2.0)。 - - 車両の 3 箇所(base, top, mid)で衝突判定を行っており、3 つのマーカーが存在する。 - - 黄色い線の各端点から道路境界までの距離が車幅の半分くらいであれば異常なし(ここがおかしい場合はロジック異常)。 - -![bounds_line](./media/bounds_line.png) - -- **optimized_points_marker** - - MPT の計算結果。道路からはみ出ていないか、振動していないかなどを確認 - -![optimized_points_marker](./media/optimized_points_marker.png) - -- **Trajectory with footprint** - - TrajectoryFootprint の rviz_plugin を用いて経路上の footprint を描画することが可能。これを用いて obstacle_avoidance_planner への入出力の footprint、経路に収まっているかどうか等を確認する。 - -![trajectory_with_footprint](./media/trajectory_with_footprint.png) - -- **Drivable Area** - - obstacle avoidance への入力の走行可能領域を表示する。Drivable Area の生成に不具合があると生成経路が歪む可能性がある。 - - topic 名:`/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/drivable_area` - - `nav_msgs/msg/OccupancyGrid` 型として出力される - -![drivable_area](./media/drivable_area.png) - -- **area_with_objects** - - 入力された走行可能領域から障害物を取り除いた後の、走行可能領域 - - `nav_msgs/msg/OccupancyGrid` 型として出力される - -![area_with_objects](./media/area_with_objects.png) - -- **object_clearance_map** - - 回避対象の障害物からの距離を可視化したもの。 - - `nav_msgs/msg/OccupancyGrid` 型として出力される - -![object_clearance_map](./media/object_clearance_map.png) - -- **clearance_map** - - 入力された走行可能領域からの距離を可視化したもの。 - - `nav_msgs/msg/OccupancyGrid` 型として出力される - -![clearance_map](./media/clearance_map.png) From 76b00b56db5a8d32885b2dc3754bea166d9ac0e6 Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Fri, 20 May 2022 14:04:32 +0900 Subject: [PATCH 48/55] chore(behavior_velocity_planner.stopline): add debug marker for stopline collision check (#932) * chore(behavior_velocity_planner.stopline): add debug marker for stopline collision check * feat: use marker helper Signed-off-by: h-ohta --- .../config/stop_line.param.yaml | 2 + .../include/scene_module/stop_line/scene.hpp | 3 + .../src/scene_module/stop_line/debug.cpp | 55 +++++++++++++++++++ .../src/scene_module/stop_line/manager.cpp | 3 + .../src/scene_module/stop_line/scene.cpp | 12 ++++ 5 files changed, 75 insertions(+) diff --git a/planning/behavior_velocity_planner/config/stop_line.param.yaml b/planning/behavior_velocity_planner/config/stop_line.param.yaml index a2b5ac5d5fcd..6d723c510cce 100644 --- a/planning/behavior_velocity_planner/config/stop_line.param.yaml +++ b/planning/behavior_velocity_planner/config/stop_line.param.yaml @@ -4,3 +4,5 @@ stop_margin: 0.0 stop_check_dist: 2.0 stop_duration_sec: 1.0 + debug: + show_stopline_collision_check: false # [-] whether to show stopline collision diff --git a/planning/behavior_velocity_planner/include/scene_module/stop_line/scene.hpp b/planning/behavior_velocity_planner/include/scene_module/stop_line/scene.hpp index d3589d6c9018..3844246bcc16 100644 --- a/planning/behavior_velocity_planner/include/scene_module/stop_line/scene.hpp +++ b/planning/behavior_velocity_planner/include/scene_module/stop_line/scene.hpp @@ -63,6 +63,8 @@ class StopLineModule : public SceneModuleInterface { double base_link2front; boost::optional stop_pose; + std::vector search_segments; + LineString2d search_stopline; }; struct PlannerParam @@ -70,6 +72,7 @@ class StopLineModule : public SceneModuleInterface double stop_margin; double stop_check_dist; double stop_duration_sec; + bool show_stopline_collision_check; }; public: diff --git a/planning/behavior_velocity_planner/src/scene_module/stop_line/debug.cpp b/planning/behavior_velocity_planner/src/scene_module/stop_line/debug.cpp index 455cca749f9a..9b71288983a5 100644 --- a/planning/behavior_velocity_planner/src/scene_module/stop_line/debug.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/stop_line/debug.cpp @@ -87,6 +87,55 @@ visualization_msgs::msg::MarkerArray createMarkers( return msg; } +visualization_msgs::msg::MarkerArray createStopLineCollisionCheck( + const DebugData & debug_data, const int64_t module_id) +{ + visualization_msgs::msg::MarkerArray msg; + + // Search Segments + { + visualization_msgs::msg::Marker marker; + marker.header.frame_id = "map"; + marker.ns = "search_segments"; + marker.id = module_id; + marker.lifetime = rclcpp::Duration::from_seconds(0.5); + marker.type = visualization_msgs::msg::Marker::SPHERE_LIST; + marker.action = visualization_msgs::msg::Marker::ADD; + for (const auto & e : debug_data.search_segments) { + marker.points.push_back( + geometry_msgs::build().x(e.at(0).x()).y(e.at(0).y()).z(0.0)); + marker.points.push_back( + geometry_msgs::build().x(e.at(1).x()).y(e.at(1).y()).z(0.0)); + } + marker.scale = createMarkerScale(0.1, 0.1, 0.1); + marker.color = createMarkerColor(0.0, 0.0, 1.0, 0.999); + msg.markers.push_back(marker); + } + + // Search stopline + { + visualization_msgs::msg::Marker marker; + marker.header.frame_id = "map"; + marker.ns = "search_stopline"; + marker.id = module_id; + marker.lifetime = rclcpp::Duration::from_seconds(0.5); + marker.type = visualization_msgs::msg::Marker::LINE_STRIP; + marker.action = visualization_msgs::msg::Marker::ADD; + const auto p0 = debug_data.search_stopline.at(0); + marker.points.push_back( + geometry_msgs::build().x(p0.x()).y(p0.y()).z(0.0)); + const auto p1 = debug_data.search_stopline.at(1); + marker.points.push_back( + geometry_msgs::build().x(p1.x()).y(p1.y()).z(0.0)); + + marker.scale = createMarkerScale(0.1, 0.1, 0.1); + marker.color = createMarkerColor(1.0, 0.0, 0.0, 0.999); + msg.markers.push_back(marker); + } + + return msg; +} + } // namespace visualization_msgs::msg::MarkerArray StopLineModule::createDebugMarkerArray() @@ -96,6 +145,12 @@ visualization_msgs::msg::MarkerArray StopLineModule::createDebugMarkerArray() appendMarkerArray( createMarkers(debug_data_, module_id_), this->clock_->now(), &debug_marker_array); + if (planner_param_.show_stopline_collision_check) { + appendMarkerArray( + createStopLineCollisionCheck(debug_data_, module_id_), this->clock_->now(), + &debug_marker_array); + } + return debug_marker_array; } } // namespace behavior_velocity_planner diff --git a/planning/behavior_velocity_planner/src/scene_module/stop_line/manager.cpp b/planning/behavior_velocity_planner/src/scene_module/stop_line/manager.cpp index e943d3537e8b..6be80eb381c9 100644 --- a/planning/behavior_velocity_planner/src/scene_module/stop_line/manager.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/stop_line/manager.cpp @@ -93,6 +93,9 @@ StopLineModuleManager::StopLineModuleManager(rclcpp::Node & node) p.stop_margin = node.declare_parameter(ns + ".stop_margin", 0.0); p.stop_check_dist = node.declare_parameter(ns + ".stop_check_dist", 2.0); p.stop_duration_sec = node.declare_parameter(ns + ".stop_duration_sec", 1.0); + // debug + p.show_stopline_collision_check = + node.declare_parameter(ns + ".debug.show_stopline_collision_check", false); } void StopLineModuleManager::launchNewModules( diff --git a/planning/behavior_velocity_planner/src/scene_module/stop_line/scene.cpp b/planning/behavior_velocity_planner/src/scene_module/stop_line/scene.cpp index 1c26ef601aa4..7ab118518ab0 100644 --- a/planning/behavior_velocity_planner/src/scene_module/stop_line/scene.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/stop_line/scene.cpp @@ -109,6 +109,18 @@ boost::optional StopLineModule::findCol { const size_t min_search_index = std::max(static_cast(0), search_index.min_idx); const size_t max_search_index = std::min(search_index.max_idx, path.points.size() - 1); + + // for creating debug marker + if (planner_param_.show_stopline_collision_check) { + debug_data_.search_stopline = stop_line; + for (size_t i = min_search_index; i < max_search_index; ++i) { + const auto & p_front = path.points.at(i).point.pose.position; + const auto & p_back = path.points.at(i + 1).point.pose.position; + const LineString2d path_segment = {{p_front.x, p_front.y}, {p_back.x, p_back.y}}; + debug_data_.search_segments.push_back(path_segment); + } + } + for (size_t i = min_search_index; i < max_search_index; ++i) { const auto & p_front = path.points.at(i).point.pose.position; const auto & p_back = path.points.at(i + 1).point.pose.position; From c7766f57441d2972e66f0916818a2d9fc1d9fdde Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Fri, 20 May 2022 15:36:48 +0900 Subject: [PATCH 49/55] feat(map_loader): visualize center line by points (#931) * feat: visualize center line points * fix: delete space * feat: visualize center line by arrow * revert insertMarkerArray * fix: delete space --- .../visualization/visualization.hpp | 10 ++++ map/lanelet2_extension/lib/visualization.cpp | 56 +++++++++++++++++++ 2 files changed, 66 insertions(+) diff --git a/map/lanelet2_extension/include/lanelet2_extension/visualization/visualization.hpp b/map/lanelet2_extension/include/lanelet2_extension/visualization/visualization.hpp index 9d21ac69bd2f..026a78ea1521 100644 --- a/map/lanelet2_extension/include/lanelet2_extension/visualization/visualization.hpp +++ b/map/lanelet2_extension/include/lanelet2_extension/visualization/visualization.hpp @@ -83,6 +83,16 @@ void pushLineStringMarker( visualization_msgs::msg::Marker * marker, const lanelet::ConstLineString3d & ls, const std_msgs::msg::ColorRGBA c, const float lss = 0.1); +/** + * [pushArrowMarkerArray pushes marker to visualize arrows] + * @param marker_array [output marker array message] + * @param ls [input linestring] + * @param c [color of the marker] + */ +void pushArrowMarkerArray( + visualization_msgs::msg::MarkerArray * marker_array, const lanelet::ConstLineString3d & ls, + const std::string frame_id, const std::string ns, const std_msgs::msg::ColorRGBA c); + /** * [initTrafficLightTriangleMarker initializes marker to visualize shape of traffic * lights] diff --git a/map/lanelet2_extension/lib/visualization.cpp b/map/lanelet2_extension/lib/visualization.cpp index a95a9aa1e49e..b846382c99b8 100644 --- a/map/lanelet2_extension/lib/visualization.cpp +++ b/map/lanelet2_extension/lib/visualization.cpp @@ -21,6 +21,8 @@ #include "lanelet2_extension/utility/utilities.hpp" #include +#include +#include #include #include @@ -880,6 +882,7 @@ visualization_msgs::msg::MarkerArray visualization::laneletsBoundaryAsMarkerArra std::unordered_set added; visualization_msgs::msg::Marker left_line_strip, right_line_strip, start_bound_line_strip, center_line_strip; + visualization_msgs::msg::MarkerArray center_line_arrows; visualization::initLineStringMarker( &left_line_strip, "map", additional_namespace + "left_lane_bound", c); visualization::initLineStringMarker( @@ -915,6 +918,8 @@ visualization_msgs::msg::MarkerArray visualization::laneletsBoundaryAsMarkerArra } if (viz_centerline && !exists(added, center_ls.id())) { visualization::pushLineStringMarker(¢er_line_strip, center_ls, c, lss_center); + visualization::pushArrowMarkerArray( + ¢er_line_arrows, center_ls, "map", additional_namespace + "center_line_arrows", c); added.insert(center_ls.id()); } } @@ -932,6 +937,9 @@ visualization_msgs::msg::MarkerArray visualization::laneletsBoundaryAsMarkerArra if (!start_bound_line_strip.points.empty()) { marker_array.markers.push_back(start_bound_line_strip); } + marker_array.markers.insert( + marker_array.markers.end(), center_line_arrows.markers.begin(), + center_line_arrows.markers.end()); return marker_array; } @@ -1183,4 +1191,52 @@ void visualization::pushLineStringMarker( } } +void visualization::pushArrowMarkerArray( + visualization_msgs::msg::MarkerArray * marker_array, const lanelet::ConstLineString3d & ls, + const std::string frame_id, const std::string ns, const std_msgs::msg::ColorRGBA c) +{ + if (marker_array == nullptr) { + RCLCPP_ERROR_STREAM( + rclcpp::get_logger("lanelet2_extension.visualization"), + __FUNCTION__ << ": marker_array is null pointer!"); + return; + } + + // fill out lane line + if (ls.size() < 2) { + RCLCPP_ERROR_STREAM( + rclcpp::get_logger("lanelet2_extension.visualization"), + __FUNCTION__ << ": marker line size is 1 or 0!"); + return; + } + + visualization_msgs::msg::Marker marker; + marker.header.frame_id = frame_id; + marker.header.stamp = rclcpp::Time(); + marker.frame_locked = true; + marker.ns = ns; + marker.action = visualization_msgs::msg::Marker::ADD; + marker.type = visualization_msgs::msg::Marker::ARROW; + + int32_t start_index = !marker_array->markers.empty() ? marker_array->markers.back().id : 0; + for (auto i = ls.begin(); i + 1 != ls.end(); i++) { + const auto index = i - ls.begin(); + marker.id = start_index + index + 1; + const auto curr_point = + geometry_msgs::build().x((*i).x()).y((*i).y()).z((*i).z()); + const auto next_point = geometry_msgs::build() + .x((*(i + 1)).x()) + .y((*(i + 1)).y()) + .z((*(i + 1)).z()); + marker.pose.position = curr_point; + + const double yaw = tier4_autoware_utils::calcAzimuthAngle(curr_point, next_point); + marker.pose.orientation = tier4_autoware_utils::createQuaternionFromYaw(yaw); + marker.scale = tier4_autoware_utils::createMarkerScale(0.3, 0.1, 0.1); + marker.color = c; + + marker_array->markers.push_back(marker); + } +} + } // namespace lanelet From 1696c2b081f81b43ff2900404e8478dec2cbb1c2 Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Fri, 20 May 2022 16:02:23 +0900 Subject: [PATCH 50/55] feat: add RTC interface (#765) * feature(rtc_interface): add files Signed-off-by: Fumiya Watanabe * feature(rtc_interface): implement functions Signed-off-by: Fumiya Watanabe * feature(rtc_interface): reimprement functions to use CooperateCommands and write README.md Signed-off-by: Fumiya Watanabe * feature(rtc_interface): fix README Signed-off-by: Fumiya Watanabe * feature(rtc_interface): add getModuleType() Signed-off-by: Fumiya Watanabe * feature(rtc_interface): fix definition of constructor Signed-off-by: Fumiya Watanabe * feature(rtc_interface): fix time stamp Signed-off-by: Fumiya Watanabe * feature(rtc_interface): fix README Signed-off-by: Fumiya Watanabe * feature(rtc_interface): add isRegistered and clearCooperateStatus Signed-off-by: Fumiya Watanabe * ci(pre-commit): autofix Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- planning/rtc_interface/CMakeLists.txt | 25 +++ planning/rtc_interface/README.md | 187 +++++++++++++++++ .../include/rtc_interface/rtc_interface.hpp | 71 +++++++ planning/rtc_interface/package.xml | 23 +++ planning/rtc_interface/src/rtc_interface.cpp | 193 ++++++++++++++++++ 5 files changed, 499 insertions(+) create mode 100644 planning/rtc_interface/CMakeLists.txt create mode 100644 planning/rtc_interface/README.md create mode 100644 planning/rtc_interface/include/rtc_interface/rtc_interface.hpp create mode 100644 planning/rtc_interface/package.xml create mode 100644 planning/rtc_interface/src/rtc_interface.cpp diff --git a/planning/rtc_interface/CMakeLists.txt b/planning/rtc_interface/CMakeLists.txt new file mode 100644 index 000000000000..fda6025b84e8 --- /dev/null +++ b/planning/rtc_interface/CMakeLists.txt @@ -0,0 +1,25 @@ +cmake_minimum_required(VERSION 3.5) +project(rtc_interface) + +### Compile options +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 17) +endif() +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic -Werror) +endif() + +find_package(ament_cmake_auto REQUIRED) +ament_auto_find_build_dependencies() + +ament_auto_add_library(rtc_interface SHARED + src/rtc_interface.cpp +) + +# Test +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + +ament_auto_package() diff --git a/planning/rtc_interface/README.md b/planning/rtc_interface/README.md new file mode 100644 index 000000000000..45c1d4e8b9a2 --- /dev/null +++ b/planning/rtc_interface/README.md @@ -0,0 +1,187 @@ +# RTC Interface + +## Purpose + +RTC Interface is an interface to publish the decision status of behavior planning modules and receive execution command from external of an autonomous driving system. + +## Inner-workings / Algorithms + +### Usage example + +```c++ +// Generate instance (in this example, "intersection" is selected) +rtc_interface::RTCInterface rtc_interface(node, "intersection"); + +// Generate UUID +const unique_identifier_msgs::msg::UUID uuid = generateUUID(getModuleId()); + +// Repeat while module is running +while (...) { + // Get safety status of the module corresponding to the module id + const bool safe = ... + + // Get distance to the object corresponding to the module id + const double distance = ... + + // Get time stamp + const rclcpp::Time stamp = ... + + // Update status + rtc_interface.updateCooperateStatus(uuid, safe, distance, stamp); + + if (rtc_interface.isActivated(uuid)) { + // Execute planning + } else { + // Stop planning + } + // Get time stamp + const rclcpp::Time stamp = ... + + // Publish status topic + rtc_interface.publishCooperateStatus(stamp); +} + +// Remove the status from array +rtc_interface.removeCooperateStatus(uuid); +``` + +## Inputs / Outputs + +### RTCInterface (Constructor) + +```c++ +rtc_interface::RTCInterface(rclcpp::Node & node, const std::string & name); +``` + +#### Description + +A constructor for `rtc_interface::RTCInterface`. + +#### Input + +- `node` : Node calling this interface +- `name` : Name of cooperate status array topic and cooperate commands service + - Cooperate status array topic name : `~/{name}/cooperate_status` + - Cooperate commands service name : `~/{name}/cooperate_commands` + +#### Output + +An instance of `RTCInterface` + +### publishCooperateStatus + +```c++ +rtc_interface::publishCooperateStatus(const rclcpp::Time & stamp) +``` + +#### Description + +Publish registered cooperate status. + +#### Input + +- `stamp` : Time stamp + +#### Output + +Nothing + +### updateCooperateStatus + +```c++ +rtc_interface::updateCooperateStatus(const unique_identifier_msgs::msg::UUID & uuid, const bool safe, const double distance, const rclcpp::Time & stamp) +``` + +#### Description + +Update cooperate status corresponding to `uuid`. +If cooperate status corresponding to `uuid` is not registered yet, add new cooperate status. + +#### Input + +- `uuid` : UUID for requesting module +- `safe` : Safety status of requesting module +- `distance` : Distance to the object from ego vehicle +- `stamp` : Time stamp + +#### Output + +Nothing + +### removeCooperateStatus + +```c++ +rtc_interface::removeCooperateStatus(const unique_identifier_msgs::msg::UUID & uuid) +``` + +#### Description + +Remove cooperate status corresponding to `uuid` from registered statuses. + +#### Input + +- `uuid` : UUID for expired module + +#### Output + +Nothing + +### clearCooperateStatus + +```c++ +rtc_interface::clearCooperateStatus() +``` + +#### Description + +Remove all cooperate statuses. + +#### Input + +Nothing + +#### Output + +Nothing + +### isActivated + +```c++ +rtc_interface::isActivated(const unique_identifier_msgs::msg::UUID & uuid) +``` + +#### Description + +Return received command status corresponding to `uuid`. + +#### Input + +- `uuid` : UUID for checking module + +#### Output + +If received command is `ACTIVATED`, return `true`. +If not, return `false`. + +### isRegistered + +```c++ +rtc_interface::isRegistered(const unique_identifier_msgs::msg::UUID & uuid) +``` + +#### Description + +Return `true` if `uuid` is registered. + +#### Input + +- `uuid` : UUID for checking module + +#### Output + +If `uuid` is registered, return `true`. +If not, return `false`. + +## Assumptions / Known limits + +## Future extensions / Unimplemented parts diff --git a/planning/rtc_interface/include/rtc_interface/rtc_interface.hpp b/planning/rtc_interface/include/rtc_interface/rtc_interface.hpp new file mode 100644 index 000000000000..df9dc4d1c243 --- /dev/null +++ b/planning/rtc_interface/include/rtc_interface/rtc_interface.hpp @@ -0,0 +1,71 @@ +// Copyright 2022 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef RTC_INTERFACE__RTC_INTERFACE_HPP_ +#define RTC_INTERFACE__RTC_INTERFACE_HPP_ + +#include "rclcpp/rclcpp.hpp" + +#include "tier4_rtc_msgs/msg/command.hpp" +#include "tier4_rtc_msgs/msg/cooperate_command.hpp" +#include "tier4_rtc_msgs/msg/cooperate_response.hpp" +#include "tier4_rtc_msgs/msg/cooperate_status.hpp" +#include "tier4_rtc_msgs/msg/cooperate_status_array.hpp" +#include "tier4_rtc_msgs/msg/module.hpp" +#include "tier4_rtc_msgs/srv/cooperate_commands.hpp" +#include + +#include +#include + +namespace rtc_interface +{ +using tier4_rtc_msgs::msg::Command; +using tier4_rtc_msgs::msg::CooperateCommand; +using tier4_rtc_msgs::msg::CooperateResponse; +using tier4_rtc_msgs::msg::CooperateStatus; +using tier4_rtc_msgs::msg::CooperateStatusArray; +using tier4_rtc_msgs::msg::Module; +using tier4_rtc_msgs::srv::CooperateCommands; +using unique_identifier_msgs::msg::UUID; + +class RTCInterface +{ +public: + RTCInterface(rclcpp::Node & node, const std::string & name); + void publishCooperateStatus(const rclcpp::Time & stamp); + void updateCooperateStatus( + const UUID & uuid, const bool safe, const double distance, const rclcpp::Time & stamp); + void removeCooperateStatus(const UUID & uuid); + void clearCooperateStatus(); + bool isActivated(const UUID & uuid) const; + bool isRegistered(const UUID & uuid) const; + +private: + void onCooperateCommandService( + const CooperateCommands::Request::SharedPtr request, + const CooperateCommands::Response::SharedPtr responses); + rclcpp::Logger getLogger() const; + + rclcpp::Publisher::SharedPtr pub_statuses_; + rclcpp::Service::SharedPtr srv_commands_; + + rclcpp::Logger logger_; + Module module_; + CooperateStatusArray registered_status_; +}; + +} // namespace rtc_interface + +#endif // RTC_INTERFACE__RTC_INTERFACE_HPP_ diff --git a/planning/rtc_interface/package.xml b/planning/rtc_interface/package.xml new file mode 100644 index 000000000000..96293f6b48ff --- /dev/null +++ b/planning/rtc_interface/package.xml @@ -0,0 +1,23 @@ + + + rtc_interface + 0.1.0 + The rtc_interface package + + Fumiya Watanabe + + Apache License 2.0 + + ament_cmake_auto + + rclcpp + tier4_rtc_msgs + unique_identifier_msgs + + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/planning/rtc_interface/src/rtc_interface.cpp b/planning/rtc_interface/src/rtc_interface.cpp new file mode 100644 index 000000000000..c4e0ed0bc374 --- /dev/null +++ b/planning/rtc_interface/src/rtc_interface.cpp @@ -0,0 +1,193 @@ +// Copyright 2022 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "rtc_interface/rtc_interface.hpp" + +namespace +{ +using tier4_rtc_msgs::msg::Module; + +std::string to_string(const unique_identifier_msgs::msg::UUID & uuid) +{ + std::stringstream ss; + for (auto i = 0; i < 16; ++i) { + ss << std::hex << std::setfill('0') << std::setw(2) << +uuid.uuid[i]; + } + return ss.str(); +} + +Module getModuleType(const std::string & module_name) +{ + Module module; + if (module_name == "blind_spot") { + module.type = Module::BLIND_SPOT; + } else if (module_name == "crosswalk") { + module.type = Module::CROSSWALK; + } else if (module_name == "detection_area") { + module.type = Module::DETECTION_AREA; + } else if (module_name == "intersection") { + module.type = Module::INTERSECTION; + } else if (module_name == "no_stopping_area") { + module.type = Module::NO_STOPPING_AREA; + } else if (module_name == "occlusion_spot") { + module.type = Module::OCCLUSION_SPOT; + } else if (module_name == "stop_line") { + module.type = Module::NONE; + } else if (module_name == "traffic_light") { + module.type = Module::TRAFFIC_LIGHT; + } else if (module_name == "virtual_traffic_light") { + module.type = Module::TRAFFIC_LIGHT; + } else if (module_name == "lane_change_left") { + module.type = Module::LANE_CHANGE_LEFT; + } else if (module_name == "lane_change_right") { + module.type = Module::LANE_CHANGE_RIGHT; + } else if (module_name == "avoidance_left") { + module.type = Module::AVOIDANCE_LEFT; + } else if (module_name == "avoidance_right") { + module.type = Module::AVOIDANCE_RIGHT; + } else if (module_name == "pull_over") { + module.type = Module::PULL_OVER; + } else if (module_name == "pull_out") { + module.type = Module::PULL_OUT; + } + return module; +} + +} // namespace + +namespace rtc_interface +{ +RTCInterface::RTCInterface(rclcpp::Node & node, const std::string & name) +: logger_{node.get_logger().get_child("RTCInterface[" + name + "]")} +{ + using std::placeholders::_1; + using std::placeholders::_2; + + // Publisher + pub_statuses_ = node.create_publisher("~/" + name + "/cooperate_status", 1); + + // Service + srv_commands_ = node.create_service( + "~/" + name + "/cooperate_commands", + std::bind(&RTCInterface::onCooperateCommandService, this, _1, _2)); + + // Module + module_ = getModuleType(name); +} + +void RTCInterface::publishCooperateStatus(const rclcpp::Time & stamp) +{ + registered_status_.stamp = stamp; + pub_statuses_->publish(registered_status_); +} + +void RTCInterface::onCooperateCommandService( + const CooperateCommands::Request::SharedPtr request, + const CooperateCommands::Response::SharedPtr responses) +{ + for (const auto & command : request->commands) { + CooperateResponse response; + response.uuid = command.uuid; + response.module = command.module; + + const auto itr = std::find_if( + registered_status_.statuses.begin(), registered_status_.statuses.end(), + [command](auto & s) { return s.uuid == command.uuid; }); + + // Update command if the command has been already received + if (itr != registered_status_.statuses.end()) { + itr->command_status = command.command; + response.success = true; + } else { + RCLCPP_WARN_STREAM( + getLogger(), "[onCooperateCommandService] uuid : " << to_string(command.uuid) + << " is not found." << std::endl); + response.success = false; + } + responses->responses.push_back(response); + } +} + +void RTCInterface::updateCooperateStatus( + const UUID & uuid, const bool safe, const double distance, const rclcpp::Time & stamp) +{ + // Find registered status which has same uuid + auto itr = std::find_if( + registered_status_.statuses.begin(), registered_status_.statuses.end(), + [uuid](auto & s) { return s.uuid == uuid; }); + + // If there is no registered status, add it + if (itr == registered_status_.statuses.end()) { + CooperateStatus status; + status.stamp = stamp; + status.uuid = uuid; + status.module = module_; + status.safe = safe; + status.command_status.type = Command::DEACTIVATE; + status.distance = distance; + registered_status_.statuses.push_back(status); + return; + } + + // If the registered status is found, update status + itr->stamp = stamp; + itr->safe = safe; + itr->distance = distance; +} + +void RTCInterface::removeCooperateStatus(const UUID & uuid) +{ + // Find registered status which has same uuid and erase it + const auto itr = std::find_if( + registered_status_.statuses.begin(), registered_status_.statuses.end(), + [uuid](auto & s) { return s.uuid == uuid; }); + + if (itr != registered_status_.statuses.end()) { + registered_status_.statuses.erase(itr); + return; + } + + RCLCPP_WARN_STREAM( + getLogger(), + "[removeCooperateStatus] uuid : " << to_string(uuid) << " is not found." << std::endl); +} + +void RTCInterface::clearCooperateStatus() { registered_status_.statuses.clear(); } + +bool RTCInterface::isActivated(const UUID & uuid) const +{ + const auto itr = std::find_if( + registered_status_.statuses.begin(), registered_status_.statuses.end(), + [uuid](auto & s) { return s.uuid == uuid; }); + + if (itr != registered_status_.statuses.end()) { + return itr->command_status.type == Command::ACTIVATE; + } + + RCLCPP_WARN_STREAM( + getLogger(), "[isActivated] uuid : " << to_string(uuid) << " is not found." << std::endl); + return false; +} + +bool RTCInterface::isRegistered(const UUID & uuid) const +{ + const auto itr = std::find_if( + registered_status_.statuses.begin(), registered_status_.statuses.end(), + [uuid](auto & s) { return s.uuid == uuid; }); + return itr != registered_status_.statuses.end(); +} + +rclcpp::Logger RTCInterface::getLogger() const { return logger_; } + +} // namespace rtc_interface From 93d95dd63a9d84bdca4fd87acb4b200098dd8bf3 Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Sun, 22 May 2022 02:07:04 +0900 Subject: [PATCH 51/55] chore: sync files (#911) Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .github/workflows/github-release.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/workflows/github-release.yaml b/.github/workflows/github-release.yaml index 93533b54e1dd..19e1e9c12e57 100644 --- a/.github/workflows/github-release.yaml +++ b/.github/workflows/github-release.yaml @@ -9,6 +9,7 @@ on: workflow_dispatch: inputs: beta-branch-or-tag-name: + description: The name of the beta branch or tag to release type: string required: true From 6b73a234dce5997ba85be015bfd6cb39a79e6387 Mon Sep 17 00:00:00 2001 From: RyuYamamoto Date: Mon, 23 May 2022 15:43:48 +0900 Subject: [PATCH 52/55] fix: replace boost::mutex::scoped_lock to std::scoped_lock (#907) * fix: replace boost::mutex::scoped_lock to std::scoped_lock * fix: replace boost::mutex to std::mutex --- .../src/distance_based_compare_map_filter_nodelet.cpp | 6 +++--- .../voxel_based_approximate_compare_map_filter_nodelet.cpp | 6 +++--- .../src/voxel_based_compare_map_filter_nodelet.cpp | 6 +++--- .../src/voxel_distance_based_compare_map_filter_nodelet.cpp | 6 +++--- .../src/ransac_ground_filter_nodelet.cpp | 4 ++-- .../ground_segmentation/src/ray_ground_filter_nodelet.cpp | 4 ++-- .../include/pointcloud_preprocessor/filter.hpp | 2 +- .../src/blockage_diag/blockage_diag_nodelet.cpp | 4 ++-- .../src/crop_box_filter/crop_box_filter_nodelet.cpp | 4 ++-- .../approximate_downsample_filter_nodelet.cpp | 4 ++-- .../downsample_filter/random_downsample_filter_nodelet.cpp | 4 ++-- .../voxel_grid_downsample_filter_nodelet.cpp | 4 ++-- sensing/pointcloud_preprocessor/src/filter.cpp | 2 +- .../outlier_filter/dual_return_outlier_filter_nodelet.cpp | 4 ++-- .../radius_search_2d_outlier_filter_nodelet.cpp | 4 ++-- .../src/outlier_filter/ring_outlier_filter_nodelet.cpp | 4 ++-- .../outlier_filter/voxel_grid_outlier_filter_nodelet.cpp | 4 ++-- .../src/passthrough_filter/passthrough_filter_nodelet.cpp | 4 ++-- .../passthrough_filter_uint16_nodelet.cpp | 4 ++-- .../pointcloud_accumulator_nodelet.cpp | 4 ++-- 20 files changed, 42 insertions(+), 42 deletions(-) diff --git a/perception/compare_map_segmentation/src/distance_based_compare_map_filter_nodelet.cpp b/perception/compare_map_segmentation/src/distance_based_compare_map_filter_nodelet.cpp index ab51a7162756..b96b8faa98c9 100644 --- a/perception/compare_map_segmentation/src/distance_based_compare_map_filter_nodelet.cpp +++ b/perception/compare_map_segmentation/src/distance_based_compare_map_filter_nodelet.cpp @@ -43,7 +43,7 @@ void DistanceBasedCompareMapFilterComponent::filter( const PointCloud2ConstPtr & input, [[maybe_unused]] const IndicesPtr & indices, PointCloud2 & output) { - boost::mutex::scoped_lock lock(mutex_); + std::scoped_lock lock(mutex_); if (map_ptr_ == NULL || tree_ == NULL) { output = *input; return; @@ -65,7 +65,7 @@ void DistanceBasedCompareMapFilterComponent::input_target_callback(const PointCl pcl::fromROSMsg(*map, map_pcl); const auto map_pcl_ptr = pcl::make_shared>(map_pcl); - boost::mutex::scoped_lock lock(mutex_); + std::scoped_lock lock(mutex_); map_ptr_ = map_pcl_ptr; tf_input_frame_ = map_ptr_->header.frame_id; if (!tree_) { @@ -81,7 +81,7 @@ void DistanceBasedCompareMapFilterComponent::input_target_callback(const PointCl rcl_interfaces::msg::SetParametersResult DistanceBasedCompareMapFilterComponent::paramCallback( const std::vector & p) { - boost::mutex::scoped_lock lock(mutex_); + std::scoped_lock lock(mutex_); if (get_param(p, "distance_threshold", distance_threshold_)) { RCLCPP_DEBUG(get_logger(), "Setting new distance threshold to: %f.", distance_threshold_); diff --git a/perception/compare_map_segmentation/src/voxel_based_approximate_compare_map_filter_nodelet.cpp b/perception/compare_map_segmentation/src/voxel_based_approximate_compare_map_filter_nodelet.cpp index 70f90bed924a..9f338633b4b8 100644 --- a/perception/compare_map_segmentation/src/voxel_based_approximate_compare_map_filter_nodelet.cpp +++ b/perception/compare_map_segmentation/src/voxel_based_approximate_compare_map_filter_nodelet.cpp @@ -45,7 +45,7 @@ void VoxelBasedApproximateCompareMapFilterComponent::filter( const PointCloud2ConstPtr & input, [[maybe_unused]] const IndicesPtr & indices, PointCloud2 & output) { - boost::mutex::scoped_lock lock(mutex_); + std::scoped_lock lock(mutex_); if (voxel_map_ptr_ == NULL) { output = *input; return; @@ -74,7 +74,7 @@ void VoxelBasedApproximateCompareMapFilterComponent::input_target_callback( pcl::fromROSMsg(*map, map_pcl); const auto map_pcl_ptr = pcl::make_shared>(map_pcl); - boost::mutex::scoped_lock lock(mutex_); + std::scoped_lock lock(mutex_); set_map_in_voxel_grid_ = true; tf_input_frame_ = map_pcl_ptr->header.frame_id; voxel_map_ptr_.reset(new pcl::PointCloud); @@ -88,7 +88,7 @@ rcl_interfaces::msg::SetParametersResult VoxelBasedApproximateCompareMapFilterComponent::paramCallback( const std::vector & p) { - boost::mutex::scoped_lock lock(mutex_); + std::scoped_lock lock(mutex_); if (get_param(p, "distance_threshold", distance_threshold_)) { voxel_grid_.setLeafSize(distance_threshold_, distance_threshold_, distance_threshold_); diff --git a/perception/compare_map_segmentation/src/voxel_based_compare_map_filter_nodelet.cpp b/perception/compare_map_segmentation/src/voxel_based_compare_map_filter_nodelet.cpp index 3c206f7cec7b..3126e9c29981 100644 --- a/perception/compare_map_segmentation/src/voxel_based_compare_map_filter_nodelet.cpp +++ b/perception/compare_map_segmentation/src/voxel_based_compare_map_filter_nodelet.cpp @@ -45,7 +45,7 @@ void VoxelBasedCompareMapFilterComponent::filter( const PointCloud2ConstPtr & input, [[maybe_unused]] const IndicesPtr & indices, PointCloud2 & output) { - boost::mutex::scoped_lock lock(mutex_); + std::scoped_lock lock(mutex_); if (voxel_map_ptr_ == NULL) { output = *input; return; @@ -241,7 +241,7 @@ void VoxelBasedCompareMapFilterComponent::input_target_callback(const PointCloud pcl::fromROSMsg(*map, map_pcl); const auto map_pcl_ptr = pcl::make_shared>(map_pcl); - boost::mutex::scoped_lock lock(mutex_); + std::scoped_lock lock(mutex_); set_map_in_voxel_grid_ = true; tf_input_frame_ = map_pcl_ptr->header.frame_id; voxel_map_ptr_.reset(new pcl::PointCloud); @@ -254,7 +254,7 @@ void VoxelBasedCompareMapFilterComponent::input_target_callback(const PointCloud rcl_interfaces::msg::SetParametersResult VoxelBasedCompareMapFilterComponent::paramCallback( const std::vector & p) { - boost::mutex::scoped_lock lock(mutex_); + std::scoped_lock lock(mutex_); if (get_param(p, "distance_threshold", distance_threshold_)) { voxel_grid_.setLeafSize(distance_threshold_, distance_threshold_, distance_threshold_); diff --git a/perception/compare_map_segmentation/src/voxel_distance_based_compare_map_filter_nodelet.cpp b/perception/compare_map_segmentation/src/voxel_distance_based_compare_map_filter_nodelet.cpp index d7997e03f03b..8dcca4c0f5e8 100644 --- a/perception/compare_map_segmentation/src/voxel_distance_based_compare_map_filter_nodelet.cpp +++ b/perception/compare_map_segmentation/src/voxel_distance_based_compare_map_filter_nodelet.cpp @@ -43,7 +43,7 @@ void VoxelDistanceBasedCompareMapFilterComponent::filter( const PointCloud2ConstPtr & input, [[maybe_unused]] const IndicesPtr & indices, PointCloud2 & output) { - boost::mutex::scoped_lock lock(mutex_); + std::scoped_lock lock(mutex_); if (voxel_map_ptr_ == NULL || map_ptr_ == NULL || tree_ == NULL) { output = *input; return; @@ -76,7 +76,7 @@ void VoxelDistanceBasedCompareMapFilterComponent::input_target_callback( pcl::fromROSMsg(*map, map_pcl); const auto map_pcl_ptr = pcl::make_shared>(map_pcl); - boost::mutex::scoped_lock lock(mutex_); + std::scoped_lock lock(mutex_); tf_input_frame_ = map_pcl_ptr->header.frame_id; // voxel voxel_map_ptr_.reset(new pcl::PointCloud); @@ -99,7 +99,7 @@ void VoxelDistanceBasedCompareMapFilterComponent::input_target_callback( rcl_interfaces::msg::SetParametersResult VoxelDistanceBasedCompareMapFilterComponent::paramCallback( const std::vector & p) { - boost::mutex::scoped_lock lock(mutex_); + std::scoped_lock lock(mutex_); if (get_param(p, "distance_threshold", distance_threshold_)) { voxel_grid_.setLeafSize(distance_threshold_, distance_threshold_, distance_threshold_); diff --git a/perception/ground_segmentation/src/ransac_ground_filter_nodelet.cpp b/perception/ground_segmentation/src/ransac_ground_filter_nodelet.cpp index 45aeedabe01c..ebcb02df2c61 100644 --- a/perception/ground_segmentation/src/ransac_ground_filter_nodelet.cpp +++ b/perception/ground_segmentation/src/ransac_ground_filter_nodelet.cpp @@ -231,7 +231,7 @@ void RANSACGroundFilterComponent::filter( const PointCloud2::ConstSharedPtr & input, [[maybe_unused]] const IndicesPtr & indices, PointCloud2 & output) { - boost::mutex::scoped_lock lock(mutex_); + std::scoped_lock lock(mutex_); sensor_msgs::msg::PointCloud2::SharedPtr input_transformed_ptr(new sensor_msgs::msg::PointCloud2); if (!transformPointCloud(base_frame_, input, input_transformed_ptr)) { RCLCPP_ERROR_STREAM_THROTTLE( @@ -322,7 +322,7 @@ void RANSACGroundFilterComponent::filter( rcl_interfaces::msg::SetParametersResult RANSACGroundFilterComponent::paramCallback( const std::vector & p) { - boost::mutex::scoped_lock lock(mutex_); + std::scoped_lock lock(mutex_); if (get_param(p, "base_frame", base_frame_)) { RCLCPP_DEBUG(get_logger(), "Setting base_frame to: %s.", base_frame_.c_str()); diff --git a/perception/ground_segmentation/src/ray_ground_filter_nodelet.cpp b/perception/ground_segmentation/src/ray_ground_filter_nodelet.cpp index 51410771edb9..68d8cf61f083 100644 --- a/perception/ground_segmentation/src/ray_ground_filter_nodelet.cpp +++ b/perception/ground_segmentation/src/ray_ground_filter_nodelet.cpp @@ -310,7 +310,7 @@ void RayGroundFilterComponent::filter( const PointCloud2::ConstSharedPtr & input, [[maybe_unused]] const IndicesPtr & indices, PointCloud2 & output) { - boost::mutex::scoped_lock lock(mutex_); + std::scoped_lock lock(mutex_); sensor_msgs::msg::PointCloud2::SharedPtr input_transformed_ptr(new sensor_msgs::msg::PointCloud2); bool succeeded = TransformPointCloud(base_frame_, input, input_transformed_ptr); @@ -366,7 +366,7 @@ void RayGroundFilterComponent::filter( rcl_interfaces::msg::SetParametersResult RayGroundFilterComponent::paramCallback( const std::vector & p) { - boost::mutex::scoped_lock lock(mutex_); + std::scoped_lock lock(mutex_); if (get_param(p, "min_x", min_x_)) { RCLCPP_DEBUG(get_logger(), "Setting min_x to: %f.", min_x_); diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/filter.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/filter.hpp index 1b53b4dfc0ae..79ecf6cfe251 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/filter.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/filter.hpp @@ -167,7 +167,7 @@ class Filter : public rclcpp::Node std::string tf_output_frame_; /** \brief Internal mutex. */ - boost::mutex mutex_; + std::mutex mutex_; /** \brief Virtual abstract filter method. To be implemented by every child. * \param input the input point cloud dataset. diff --git a/sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp b/sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp index 821e2de462bd..373e7a626621 100644 --- a/sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp @@ -106,7 +106,7 @@ void BlockageDiagComponent::filter( const PointCloud2ConstPtr & input, [[maybe_unused]] const IndicesPtr & indices, PointCloud2 & output) { - boost::mutex::scoped_lock lock(mutex_); + std::scoped_lock lock(mutex_); uint horizontal_bins = static_cast((angle_range_deg_[1] - angle_range_deg_[0])); uint vertical_bins = vertical_bins_; pcl::PointCloud::Ptr pcl_input(new pcl::PointCloud); @@ -224,7 +224,7 @@ void BlockageDiagComponent::filter( rcl_interfaces::msg::SetParametersResult BlockageDiagComponent::paramCallback( const std::vector & p) { - boost::mutex::scoped_lock lock(mutex_); + std::scoped_lock lock(mutex_); if (get_param(p, "blockage_ratio_threshold", blockage_ratio_threshold_)) { RCLCPP_DEBUG( get_logger(), "Setting new blockage_ratio_threshold to: %f.", blockage_ratio_threshold_); diff --git a/sensing/pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_nodelet.cpp index 52f092b6bc89..a1c390bc45c8 100644 --- a/sensing/pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_nodelet.cpp @@ -90,7 +90,7 @@ void CropBoxFilterComponent::filter( const PointCloud2ConstPtr & input, [[maybe_unused]] const IndicesPtr & indices, PointCloud2 & output) { - boost::mutex::scoped_lock lock(mutex_); + std::scoped_lock lock(mutex_); output.data.resize(input->data.size()); Eigen::Vector3f pt(Eigen::Vector3f::Zero()); @@ -188,7 +188,7 @@ void CropBoxFilterComponent::publishCropBoxPolygon() rcl_interfaces::msg::SetParametersResult CropBoxFilterComponent::paramCallback( const std::vector & p) { - boost::mutex::scoped_lock lock(mutex_); + std::scoped_lock lock(mutex_); CropBoxParam new_param{}; diff --git a/sensing/pointcloud_preprocessor/src/downsample_filter/approximate_downsample_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/downsample_filter/approximate_downsample_filter_nodelet.cpp index 26ce9747a73b..8e6747d85da8 100644 --- a/sensing/pointcloud_preprocessor/src/downsample_filter/approximate_downsample_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/downsample_filter/approximate_downsample_filter_nodelet.cpp @@ -77,7 +77,7 @@ ApproximateDownsampleFilterComponent::ApproximateDownsampleFilterComponent( void ApproximateDownsampleFilterComponent::filter( const PointCloud2ConstPtr & input, const IndicesPtr & /*indices*/, PointCloud2 & output) { - boost::mutex::scoped_lock lock(mutex_); + std::scoped_lock lock(mutex_); pcl::PointCloud::Ptr pcl_input(new pcl::PointCloud); pcl::PointCloud::Ptr pcl_output(new pcl::PointCloud); pcl::fromROSMsg(*input, *pcl_input); @@ -94,7 +94,7 @@ void ApproximateDownsampleFilterComponent::filter( rcl_interfaces::msg::SetParametersResult ApproximateDownsampleFilterComponent::paramCallback( const std::vector & p) { - boost::mutex::scoped_lock lock(mutex_); + std::scoped_lock lock(mutex_); if (get_param(p, "voxel_size_x", voxel_size_x_)) { RCLCPP_DEBUG(get_logger(), "Setting new distance threshold to: %f.", voxel_size_x_); diff --git a/sensing/pointcloud_preprocessor/src/downsample_filter/random_downsample_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/downsample_filter/random_downsample_filter_nodelet.cpp index 410c1a1171a0..3bcf0099cc78 100644 --- a/sensing/pointcloud_preprocessor/src/downsample_filter/random_downsample_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/downsample_filter/random_downsample_filter_nodelet.cpp @@ -69,7 +69,7 @@ RandomDownsampleFilterComponent::RandomDownsampleFilterComponent( void RandomDownsampleFilterComponent::filter( const PointCloud2ConstPtr & input, const IndicesPtr & /*indices*/, PointCloud2 & output) { - boost::mutex::scoped_lock lock(mutex_); + std::scoped_lock lock(mutex_); pcl::PointCloud::Ptr pcl_input(new pcl::PointCloud); pcl::PointCloud::Ptr pcl_output(new pcl::PointCloud); pcl::fromROSMsg(*input, *pcl_input); @@ -87,7 +87,7 @@ void RandomDownsampleFilterComponent::filter( rcl_interfaces::msg::SetParametersResult RandomDownsampleFilterComponent::paramCallback( const std::vector & p) { - boost::mutex::scoped_lock lock(mutex_); + std::scoped_lock lock(mutex_); if (get_param(p, "sample_num", sample_num_)) { RCLCPP_DEBUG(get_logger(), "Setting new sample num to: %zu.", sample_num_); diff --git a/sensing/pointcloud_preprocessor/src/downsample_filter/voxel_grid_downsample_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/downsample_filter/voxel_grid_downsample_filter_nodelet.cpp index cbdc8ba0e85d..edc4d3e8316c 100644 --- a/sensing/pointcloud_preprocessor/src/downsample_filter/voxel_grid_downsample_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/downsample_filter/voxel_grid_downsample_filter_nodelet.cpp @@ -77,7 +77,7 @@ VoxelGridDownsampleFilterComponent::VoxelGridDownsampleFilterComponent( void VoxelGridDownsampleFilterComponent::filter( const PointCloud2ConstPtr & input, const IndicesPtr & /*indices*/, PointCloud2 & output) { - boost::mutex::scoped_lock lock(mutex_); + std::scoped_lock lock(mutex_); pcl::PointCloud::Ptr pcl_input(new pcl::PointCloud); pcl::PointCloud::Ptr pcl_output(new pcl::PointCloud); pcl::fromROSMsg(*input, *pcl_input); @@ -95,7 +95,7 @@ void VoxelGridDownsampleFilterComponent::filter( rcl_interfaces::msg::SetParametersResult VoxelGridDownsampleFilterComponent::paramCallback( const std::vector & p) { - boost::mutex::scoped_lock lock(mutex_); + std::scoped_lock lock(mutex_); if (get_param(p, "voxel_size_x", voxel_size_x_)) { RCLCPP_DEBUG(get_logger(), "Setting new distance threshold to: %f.", voxel_size_x_); diff --git a/sensing/pointcloud_preprocessor/src/filter.cpp b/sensing/pointcloud_preprocessor/src/filter.cpp index 323181e94a73..947988c6b107 100644 --- a/sensing/pointcloud_preprocessor/src/filter.cpp +++ b/sensing/pointcloud_preprocessor/src/filter.cpp @@ -210,7 +210,7 @@ void pointcloud_preprocessor::Filter::computePublish( rcl_interfaces::msg::SetParametersResult pointcloud_preprocessor::Filter::filterParamCallback( const std::vector & p) { - boost::mutex::scoped_lock lock(mutex_); + std::scoped_lock lock(mutex_); if (get_param(p, "input_frame", tf_input_frame_)) { RCLCPP_DEBUG(get_logger(), "Setting the input TF frame to: %s.", tf_input_frame_.c_str()); diff --git a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp index 7da2aa6f2d86..05a404c635ee 100644 --- a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp @@ -115,7 +115,7 @@ void DualReturnOutlierFilterComponent::filter( const PointCloud2ConstPtr & input, [[maybe_unused]] const IndicesPtr & indices, PointCloud2 & output) { - boost::mutex::scoped_lock lock(mutex_); + std::scoped_lock lock(mutex_); pcl::PointCloud::Ptr pcl_input(new pcl::PointCloud); pcl::fromROSMsg(*input, *pcl_input); @@ -349,7 +349,7 @@ void DualReturnOutlierFilterComponent::filter( rcl_interfaces::msg::SetParametersResult DualReturnOutlierFilterComponent::paramCallback( const std::vector & p) { - boost::mutex::scoped_lock lock(mutex_); + std::scoped_lock lock(mutex_); if (get_param(p, "weak_first_distance_ratio", weak_first_distance_ratio_)) { RCLCPP_DEBUG( diff --git a/sensing/pointcloud_preprocessor/src/outlier_filter/radius_search_2d_outlier_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/outlier_filter/radius_search_2d_outlier_filter_nodelet.cpp index 3a512eb8f83a..4a905d216bb3 100644 --- a/sensing/pointcloud_preprocessor/src/outlier_filter/radius_search_2d_outlier_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/outlier_filter/radius_search_2d_outlier_filter_nodelet.cpp @@ -43,7 +43,7 @@ void RadiusSearch2DOutlierFilterComponent::filter( const PointCloud2ConstPtr & input, [[maybe_unused]] const IndicesPtr & indices, PointCloud2 & output) { - boost::mutex::scoped_lock lock(mutex_); + std::scoped_lock lock(mutex_); pcl::PointCloud::Ptr xyz_cloud(new pcl::PointCloud); pcl::fromROSMsg(*input, *xyz_cloud); @@ -71,7 +71,7 @@ void RadiusSearch2DOutlierFilterComponent::filter( rcl_interfaces::msg::SetParametersResult RadiusSearch2DOutlierFilterComponent::paramCallback( const std::vector & p) { - boost::mutex::scoped_lock lock(mutex_); + std::scoped_lock lock(mutex_); if (get_param(p, "min_neighbors", min_neighbors_)) { RCLCPP_DEBUG(get_logger(), "Setting new min neighbors to: %zu.", min_neighbors_); diff --git a/sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp index 7a842665e5f1..91f9aae7fede 100644 --- a/sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp @@ -38,7 +38,7 @@ void RingOutlierFilterComponent::filter( const PointCloud2ConstPtr & input, [[maybe_unused]] const IndicesPtr & indices, PointCloud2 & output) { - boost::mutex::scoped_lock lock(mutex_); + std::scoped_lock lock(mutex_); std::unordered_map> input_ring_map; input_ring_map.reserve(128); sensor_msgs::msg::PointCloud2::SharedPtr input_ptr = @@ -114,7 +114,7 @@ void RingOutlierFilterComponent::filter( rcl_interfaces::msg::SetParametersResult RingOutlierFilterComponent::paramCallback( const std::vector & p) { - boost::mutex::scoped_lock lock(mutex_); + std::scoped_lock lock(mutex_); if (get_param(p, "distance_ratio", distance_ratio_)) { RCLCPP_DEBUG(get_logger(), "Setting new distance ratio to: %f.", distance_ratio_); diff --git a/sensing/pointcloud_preprocessor/src/outlier_filter/voxel_grid_outlier_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/outlier_filter/voxel_grid_outlier_filter_nodelet.cpp index 88b8c9d7a36a..c65533011987 100644 --- a/sensing/pointcloud_preprocessor/src/outlier_filter/voxel_grid_outlier_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/outlier_filter/voxel_grid_outlier_filter_nodelet.cpp @@ -42,7 +42,7 @@ void VoxelGridOutlierFilterComponent::filter( const PointCloud2ConstPtr & input, [[maybe_unused]] const IndicesPtr & indices, PointCloud2 & output) { - boost::mutex::scoped_lock lock(mutex_); + std::scoped_lock lock(mutex_); pcl::PointCloud::Ptr pcl_input(new pcl::PointCloud); pcl::PointCloud::Ptr pcl_voxelized_input(new pcl::PointCloud); pcl::PointCloud::Ptr pcl_output(new pcl::PointCloud); @@ -70,7 +70,7 @@ void VoxelGridOutlierFilterComponent::filter( rcl_interfaces::msg::SetParametersResult VoxelGridOutlierFilterComponent::paramCallback( const std::vector & p) { - boost::mutex::scoped_lock lock(mutex_); + std::scoped_lock lock(mutex_); if (get_param(p, "voxel_size_x", voxel_size_x_)) { RCLCPP_DEBUG(get_logger(), "Setting new distance threshold to: %f.", voxel_size_x_); diff --git a/sensing/pointcloud_preprocessor/src/passthrough_filter/passthrough_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/passthrough_filter/passthrough_filter_nodelet.cpp index 8cadce439f6a..35ef8f61da57 100644 --- a/sensing/pointcloud_preprocessor/src/passthrough_filter/passthrough_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/passthrough_filter/passthrough_filter_nodelet.cpp @@ -70,14 +70,14 @@ void PassThroughFilterComponent::filter( const PointCloud2ConstPtr & input, [[maybe_unused]] const IndicesPtr & indices, PointCloud2 & output) { - boost::mutex::scoped_lock lock(mutex_); + std::scoped_lock lock(mutex_); output = *input; } rcl_interfaces::msg::SetParametersResult PassThroughFilterComponent::paramCallback( [[maybe_unused]] const std::vector & p) { - boost::mutex::scoped_lock lock(mutex_); + std::scoped_lock lock(mutex_); // write me diff --git a/sensing/pointcloud_preprocessor/src/passthrough_filter/passthrough_filter_uint16_nodelet.cpp b/sensing/pointcloud_preprocessor/src/passthrough_filter/passthrough_filter_uint16_nodelet.cpp index 9968de2a3302..130e3e3de793 100644 --- a/sensing/pointcloud_preprocessor/src/passthrough_filter/passthrough_filter_uint16_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/passthrough_filter/passthrough_filter_uint16_nodelet.cpp @@ -48,7 +48,7 @@ PassThroughFilterUInt16Component::PassThroughFilterUInt16Component( void PassThroughFilterUInt16Component::filter( const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output) { - boost::mutex::scoped_lock lock(mutex_); + std::scoped_lock lock(mutex_); pcl::PCLPointCloud2::Ptr pcl_input(new pcl::PCLPointCloud2); pcl_conversions::toPCL(*(input), *(pcl_input)); @@ -62,7 +62,7 @@ void PassThroughFilterUInt16Component::filter( rcl_interfaces::msg::SetParametersResult PassThroughFilterUInt16Component::paramCallback( const std::vector & p) { - boost::mutex::scoped_lock lock(mutex_); + std::scoped_lock lock(mutex_); std::uint16_t filter_min, filter_max; impl_.getFilterLimits(filter_min, filter_max); diff --git a/sensing/pointcloud_preprocessor/src/pointcloud_accumulator/pointcloud_accumulator_nodelet.cpp b/sensing/pointcloud_preprocessor/src/pointcloud_accumulator/pointcloud_accumulator_nodelet.cpp index 980d77a17099..fdb6bcc9102c 100644 --- a/sensing/pointcloud_preprocessor/src/pointcloud_accumulator/pointcloud_accumulator_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/pointcloud_accumulator/pointcloud_accumulator_nodelet.cpp @@ -37,7 +37,7 @@ void PointcloudAccumulatorComponent::filter( const PointCloud2ConstPtr & input, [[maybe_unused]] const IndicesPtr & indices, PointCloud2 & output) { - boost::mutex::scoped_lock lock(mutex_); + std::scoped_lock lock(mutex_); pointcloud_buffer_.push_front(input); rclcpp::Time last_time = input->header.stamp; pcl::PointCloud pcl_input; @@ -56,7 +56,7 @@ void PointcloudAccumulatorComponent::filter( rcl_interfaces::msg::SetParametersResult PointcloudAccumulatorComponent::paramCallback( const std::vector & p) { - boost::mutex::scoped_lock lock(mutex_); + std::scoped_lock lock(mutex_); if (get_param(p, "accumulation_time_sec", accumulation_time_sec_)) { RCLCPP_DEBUG(get_logger(), "Setting new accumulation time to: %f.", accumulation_time_sec_); From 2a85716bc154eb3f00586b2a59c3756766188020 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Kaan=20=C3=87olak?= Date: Mon, 23 May 2022 10:49:32 +0300 Subject: [PATCH 53/55] feat(tensorrt_yolo): add multi gpu support to tensorrt_yolo node (#885) * feat(tensorrt_yolo): add multi gpu support to tensorrt_yolo node Signed-off-by: Kaan Colak * feat(tensorrt_yolo): update arg Signed-off-by: Kaan Colak Co-authored-by: Kaan Colak --- perception/tensorrt_yolo/README.md | 4 ++++ .../launch/tensorrt_yolo.launch.xml | 5 +++- .../tensorrt_yolo/launch/yolo.launch.xml | 24 +++++++++++++++++++ .../tensorrt_yolo/lib/include/trt_yolo.hpp | 10 ++++++++ perception/tensorrt_yolo/src/nodelet.cpp | 7 ++++++ 5 files changed, 49 insertions(+), 1 deletion(-) diff --git a/perception/tensorrt_yolo/README.md b/perception/tensorrt_yolo/README.md index 5811fa88a6b7..71ece58a9557 100644 --- a/perception/tensorrt_yolo/README.md +++ b/perception/tensorrt_yolo/README.md @@ -86,6 +86,10 @@ Refer to [this guide](https://github.com/ultralytics/yolov5/issues/251 "guide") - [YOLOv5x](https://drive.google.com/uc?id=1kAHuNJUCxpD-yWrS6t95H3zbAPfClLxI "YOLOv5x") +## Limitations + +- If you want to run multiple instances of this node for multiple cameras using "yolo.launch.xml", first of all, create a TensorRT engine by running the "tensorrt_yolo.launch.xml" launch file separately for each GPU. Otherwise, multiple instances of the node trying to create the same TensorRT engine can cause potential problems. + ## Reference repositories - diff --git a/perception/tensorrt_yolo/launch/tensorrt_yolo.launch.xml b/perception/tensorrt_yolo/launch/tensorrt_yolo.launch.xml index 047c86327086..a548939f2ceb 100755 --- a/perception/tensorrt_yolo/launch/tensorrt_yolo.launch.xml +++ b/perception/tensorrt_yolo/launch/tensorrt_yolo.launch.xml @@ -3,18 +3,21 @@ + + - + + diff --git a/perception/tensorrt_yolo/launch/yolo.launch.xml b/perception/tensorrt_yolo/launch/yolo.launch.xml index fa357e32186a..2e27bf63c277 100644 --- a/perception/tensorrt_yolo/launch/yolo.launch.xml +++ b/perception/tensorrt_yolo/launch/yolo.launch.xml @@ -1,45 +1,69 @@ + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/perception/tensorrt_yolo/lib/include/trt_yolo.hpp b/perception/tensorrt_yolo/lib/include/trt_yolo.hpp index c951154820f1..af8065ffed37 100644 --- a/perception/tensorrt_yolo/lib/include/trt_yolo.hpp +++ b/perception/tensorrt_yolo/lib/include/trt_yolo.hpp @@ -147,6 +147,16 @@ class Net void infer(std::vector & buffers, const int batch_size); }; +bool set_cuda_device(int gpu_id) +{ + cudaError_t status = cudaSetDevice(gpu_id); + if (status != cudaSuccess) { + return false; + } else { + return true; + } +} + } // namespace yolo #endif // TRT_YOLO_HPP_ diff --git a/perception/tensorrt_yolo/src/nodelet.cpp b/perception/tensorrt_yolo/src/nodelet.cpp index 85caeebc02d0..70b7750b31ac 100644 --- a/perception/tensorrt_yolo/src/nodelet.cpp +++ b/perception/tensorrt_yolo/src/nodelet.cpp @@ -51,6 +51,7 @@ TensorrtYoloNodelet::TensorrtYoloNodelet(const rclcpp::NodeOptions & options) std::string calib_image_directory = declare_parameter("calib_image_directory", ""); std::string calib_cache_file = declare_parameter("calib_cache_file", ""); std::string mode = declare_parameter("mode", "FP32"); + int gpu_device_id = declare_parameter("gpu_id", 0); yolo_config_.num_anchors = declare_parameter("num_anchors", 3); auto anchors = declare_parameter( "anchors", std::vector{ @@ -66,6 +67,10 @@ TensorrtYoloNodelet::TensorrtYoloNodelet(const rclcpp::NodeOptions & options) yolo_config_.use_darknet_layer = declare_parameter("use_darknet_layer", true); yolo_config_.ignore_thresh = declare_parameter("ignore_thresh", 0.5); + if (!yolo::set_cuda_device(gpu_device_id)) { + RCLCPP_ERROR(this->get_logger(), "Given GPU not exist or suitable"); + } + if (!readLabelFile(label_file, &labels_)) { RCLCPP_ERROR(this->get_logger(), "Could not find label file"); } @@ -90,6 +95,8 @@ TensorrtYoloNodelet::TensorrtYoloNodelet(const rclcpp::NodeOptions & options) new yolo::Net(onnx_file, mode, 1, yolo_config_, calibration_images, calib_cache_file)); net_ptr_->save(engine_file); } + RCLCPP_INFO(this->get_logger(), "Inference engine prepared."); + using std::chrono_literals::operator""ms; timer_ = rclcpp::create_timer( this, get_clock(), 100ms, std::bind(&TensorrtYoloNodelet::connectCb, this)); From b089c41b211e506dda7fb0e27e6c8ac22f7994a2 Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Mon, 23 May 2022 18:21:40 +0900 Subject: [PATCH 54/55] feat(tier4_planning_launch): create parameter yaml for behavior_velocity_planner (#887) * feat(tier4_planning_launch): create parameter yaml for behavior_velocity_planner * Update launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml Co-authored-by: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> * feat: add param.yaml in behavior_velocity_planner package * some fix Co-authored-by: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> --- .../behavior_velocity_planner.param.yaml | 17 +++++++++++ .../behavior_planning.launch.py | 28 +++++++++---------- .../behavior_velocity_planner.param.yaml | 17 +++++++++++ 3 files changed, 47 insertions(+), 15 deletions(-) create mode 100644 launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml create mode 100644 planning/behavior_velocity_planner/config/behavior_velocity_planner.param.yaml diff --git a/launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml b/launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml new file mode 100644 index 000000000000..d47649bbe783 --- /dev/null +++ b/launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml @@ -0,0 +1,17 @@ +/**: + ros__parameters: + launch_stop_line: true + launch_crosswalk: true + launch_traffic_light: true + launch_intersection: true + launch_blind_spot: true + launch_detection_area: true + launch_virtual_traffic_light: true + launch_occlusion_spot: true + launch_no_stopping_area: true + forward_path_length: 1000.0 + backward_path_length: 5.0 + max_accel: -2.8 + max_jerk: -5.0 + system_delay: 0.5 + delay_response_time: 1.3 diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py index 7e5e575d6e00..699602bf3e4a 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py @@ -297,6 +297,18 @@ def launch_setup(context, *args, **kwargs): with open(no_stopping_area_param_path, "r") as f: no_stopping_area_param = yaml.safe_load(f)["/**"]["ros__parameters"] + behavior_velocity_planner_param_path = os.path.join( + get_package_share_directory("tier4_planning_launch"), + "config", + "scenario_planning", + "lane_driving", + "behavior_planning", + "behavior_velocity_planner", + "behavior_velocity_planner.param.yaml", + ) + with open(behavior_velocity_planner_param_path, "r") as f: + behavior_velocity_planner_param = yaml.safe_load(f)["/**"]["ros__parameters"] + behavior_velocity_planner_component = ComposableNode( package="behavior_velocity_planner", plugin="behavior_velocity_planner::BehaviorVelocityPlannerNode", @@ -333,21 +345,7 @@ def launch_setup(context, *args, **kwargs): ("~/output/traffic_signal", "debug/traffic_signal"), ], parameters=[ - { - "launch_stop_line": True, - "launch_crosswalk": True, - "launch_traffic_light": True, - "launch_intersection": True, - "launch_blind_spot": True, - "launch_detection_area": True, - "launch_virtual_traffic_light": True, - "launch_occlusion_spot": True, - "launch_no_stopping_area": True, - "forward_path_length": 1000.0, - "backward_path_length": 5.0, - "max_accel": -2.8, - "delay_response_time": 1.3, - }, + behavior_velocity_planner_param, blind_spot_param, crosswalk_param, detection_area_param, diff --git a/planning/behavior_velocity_planner/config/behavior_velocity_planner.param.yaml b/planning/behavior_velocity_planner/config/behavior_velocity_planner.param.yaml new file mode 100644 index 000000000000..d47649bbe783 --- /dev/null +++ b/planning/behavior_velocity_planner/config/behavior_velocity_planner.param.yaml @@ -0,0 +1,17 @@ +/**: + ros__parameters: + launch_stop_line: true + launch_crosswalk: true + launch_traffic_light: true + launch_intersection: true + launch_blind_spot: true + launch_detection_area: true + launch_virtual_traffic_light: true + launch_occlusion_spot: true + launch_no_stopping_area: true + forward_path_length: 1000.0 + backward_path_length: 5.0 + max_accel: -2.8 + max_jerk: -5.0 + system_delay: 0.5 + delay_response_time: 1.3 From f2577c6f2193578894beb3846446dcbee7d59e16 Mon Sep 17 00:00:00 2001 From: RyuYamamoto Date: Mon, 23 May 2022 21:17:10 +0900 Subject: [PATCH 55/55] fix(map_loader): use std::filesystem to load pcd files in pointcloud_map_loader (#942) * fix(map_loader): use std::filesystem to load pcd files in pointcloud_map_loader Signed-off-by: RyuYamamoto * fix(map_loader): remove c_str Signed-off-by: RyuYamamoto * fix(map_loader): replace c_str to string Signed-off-by: RyuYamamoto --- .../pointcloud_map_loader_node.cpp | 24 ++++++++++--------- 1 file changed, 13 insertions(+), 11 deletions(-) diff --git a/map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.cpp b/map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.cpp index d5bd22eeda8a..99f46ab58fa7 100644 --- a/map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.cpp +++ b/map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.cpp @@ -33,22 +33,24 @@ #include #include #include -#include // To be replaced by std::filesystem in C++17 +#include #include #include +namespace fs = std::filesystem; + namespace { bool isPcdFile(const std::string & p) { - if (!rcutils_is_file(p.c_str())) { + if (fs::is_directory(p)) { return false; } - const auto ext = p.substr(p.find_last_of(".") + 1); + const std::string ext = fs::path(p).extension(); - if (ext != "pcd" && ext != "PCD") { + if (ext != ".pcd" && ext != ".PCD") { return false; } @@ -70,7 +72,7 @@ PointCloudMapLoaderNode::PointCloudMapLoaderNode(const rclcpp::NodeOptions & opt std::vector pcd_paths{}; for (const auto & p : pcd_paths_or_directory) { - if (!rcutils_exists(p.c_str())) { + if (!fs::exists(p)) { RCLCPP_ERROR_STREAM(get_logger(), "invalid path: " << p); } @@ -78,13 +80,13 @@ PointCloudMapLoaderNode::PointCloudMapLoaderNode(const rclcpp::NodeOptions & opt pcd_paths.push_back(p); } - if (rcutils_is_directory(p.c_str())) { - glob_t glob_buf; - glob((p + "/*.pcd").c_str(), 0, NULL, &glob_buf); - for (size_t i = 0; i < glob_buf.gl_pathc; ++i) { - pcd_paths.push_back(glob_buf.gl_pathv[i]); + if (fs::is_directory(p)) { + for (const auto & file : fs::directory_iterator(p)) { + const auto filename = file.path().string(); + if (isPcdFile(filename)) { + pcd_paths.push_back(filename); + } } - globfree(&glob_buf); } }

0P=|G?|nt^mwXB6y2fH(_Bu7 zbEeR+)-`Nh%o(FmD)n)Glp)J9GuMoft07wP-r*`sHOy8sJ9>Bud!gJ?n5ld=W4r<$ zqFG30!=&Pbs-5{^skF+TN_DPsr5mTB`b>a97B@;&?k#l@gD{kPOfcV1iC>RPV~He=6L#m!>eOj>a$xan!&-DdgroIt#Fy|)(MYx z*Vb08R|nJf*Cc}XM~^SwjQAQ}mEQP-D6#lOgsR0&YpY%1eSGuX5(gyyjf$rFgx9x_ zAo~8oOqY`_7^`{*p3}P@(~&Lod9|_rB1aE?51R{WBRQgj_aOE+HgVBs1=z{$LlBH{ zv;g+%J-m-YHB8?LUYkqe<(^a-@q8eNb@SUN-uE66C?!zSWj?6H$TYW9%fR-PVoZ?= zGtoGUT~8~ndJ|?f?wpl5-gw@a>Y_WL{rP*EiTZnrWd6Y;u1Qzwa#G@KDI3iJ!kpbC z8lJklV3g*BEW8XWp$*-cw?|EgUnWISTk9snMHIm=39I3`hX&(CMvDk8twR*`2EjdC zCF~BTif(Tf@+`T^30Tfl!?G43q7CR+HD{XX2gB|zZk^+>b_^JSQzAVc32syS29S)E z_G^zqT^4(^8|=x~vLGO;X3R+nEI?ERgk!&(phZss2(?`S;C!{0N-V&OYJ{{lA@J3_ zll5_O`Noml@a)JVfM|=w?xyq8!LrGM{!-c2Cjm~7>b2o&JMUFeBN2cTwaJwg=7R?}Z%}*CwR6AvtL_q1?L?h}T zUvitxA<1;T!O8lQ%Oh`z8rnJ(`rYSG^~3nUzId1vip?nE5$RDNAWrIBB|%<%48au* zCUQVt>&4v1f=!yf>dCQWfms< zQb6cl(N~!ziC~Yk_dUK>NH3p^$~7vvuCl0Z!W>`#44beF(8&hnN(JS;oR``B^ko*Uip$@R*E1NW{DNUO(JRI@7zD>wGR34LCQ17Sh z^BfgC;&)PVnCf$cd+xiGcj9k{Gk_*bgu%l}%<~T*H4P~fs+I!c!ri*7tY;rgp5+mf z^HY!sfY9ziN^x2?yCCcVJjO75t6hy(2%1(GDU=)(dCmr8m4p&<`4SgKps>^~Ydk88 zRBc^TZGKz~;RPab1a%7pcAq76A7onpR9X?W#n3sboTEy`^Ta(oJF3w&AfLW*_M z=btHUFidvXD48*-mTs45IF?PMmd&`AO&GK|(iV+q_Bk3soSqj}*1Ep1HK6xnygQFU#Wl zDJnV7R|1#?0)+<@n1n2a5yv@HFP=;lzc2FP#|xzut2QK}I4&rMlcRh;coiRNq&iQ* zP!yo4NlIj4#=K-)g1}X{C`+jJ>PbyS%>pIK7$l6X>_~GAkOrGjx^w6h>FyZ1kyb*arBoy(q-)**3-@;K?cV!&p5uML<2(4N zKjyygb**cybDirvA02qnnKHGKM74NzT8DcuJK)@-Z;cN14`+@v4Q^}j!cjQTBqoT{ zEcOfy!ZRnGF&~}=$`b8F^b+djE3UT@?xdl~d*ZxS&)$#E3G=)mXFNllZtHW~)?>yt zfVmVr?GneF+7t^dZtUKRgBr96Eok{QO9{Y;jNXBa_gn;S$>d3l0A(U$PsE1qt7l~R zXPn6h_D2lAATdcfmyycH62v;|a-YseB_oKe*_Xk&gaIIepOytllJ$e3C=mx5K-Kut z9q0CaRFd>JO_FuX+p^IV&!A<(z?$rc1q!6Np0N|0x)G?xmD!Qg7ReUnK#(4=3@We@ z4~fcbQ0mU;Pc`e!tQcyJM9IvhYQwe&lpS?FjR(9<)|#=dkGu=*-Eu3d8sB4a-!_cH zHG2Laa(p+;w_pcNlRSaCUrG99A8$=ZY27>O9Tr*Gd~V$Q^~dg^*TtI6{e<>hAY}24 z5{NhYWM<+r!o+fYq<}C))DsoC)3Vig#voG&TN@Gi6j~*c`f!F6Dl8PqXyWG4vPTBpyyjvLeVPck=e=<9J7YQNZ60#; z9*W8jUnx7V%emypT8f{|fF)fXSrogLsMp2`n*-#8iNLo6u%Gq4IBQgfT2C9mZtW6N z*Z@=sC)P*_l+_bcJ9m&jYl~$ymB@CeX%04I%erf>Z_M_7`gTq)<1}r$ixK+=b%aD7 zV;$)&w`=H=d0LPcjPpXH4Vay51ys+A^dQ%1>jU-1nnoK+j3C$NXt`L~+0IPf*w*DV zh45K=y?&Ux(mNiUd}9UQWR6w1hGHBMKh8NZUm4d;46O%ZUsl#Ik8KbtieV-ZI5kk2 z-=CPLm2cjhHf}NwjOG;9R~JS1U(-;xHxl3`W|K( zPttl4a{{vdZS7-P!)Tq=5SHPq5DDQ#JU{@cJY|krh9XSthq}h^lL$jX!U#5UdS|$a zOz!=>UUOk|`sa$b6e%7?G4Y>Jx}$U9dMGBNB0j>6RO6(kbL;KT7V9EIoUJdB5La!`3* ze|qAgY|*PrIp8t9`KLtD{zL)9IQ>^Xy*JOHdlsccgP5zXyJrdu zQCXExVU<7WEs9t_71W2vhqb07das;T@BQWL0*sirZ$QRkt(iF*ZeeCtg`8R+`Vg8{b$1E1b8nB)RZmNj;cc>qnLTS}K1;0wTagkz!>Dij-nH2D)X+^DvjAlufm}KGd zmY0;r-#b{B=to?7C2pi2a|zhIPvh>UE_9Ogrk+FbrKRGMY&W2js#?A6rUyr!FUKDzIG z@TF^Euh}({9x5h1qI-J*gl#MPNVjN3dNonOOP;2qbjgSmWMy{gB=-|ED^OnY{ZCC! zjissI7NyYuHf(?cU`2h7B$^0AGsp9**Z$gRBkba{U ze5PL&PKi^9oO6PUO30@~cTlQqszTOc#us2>Q&E zTM3ABOxlUiGodl2%8Sqe3jRf4oa0CZ`5$I9hnf-qT2HG3OJh68M0{6^7Pb{FB; zA?xNMlMZXvje>?9ivS*Bs7Wd69lVdiCvb_mp9>8Y!i2Q<-*$1*35Bw>NuuZ~i$Lql zKfU1nkp1c9<$HX0x}Zs$p&}A^P*6VZopS&nOsL$|(N8eZF0=?XD1;vLDRv9Ni+e#V z8-r6m{p!kZ+Fvu833jtzf8{pH8PlvOCmw&-zl5`O^2O?PL?5633ZQG|o}EEeTCLa| z0N+zj_0rGmF7-LvS2lTlU&i+O%~J+zd210wH&`$_|**! z<04Pf%G*P|;4v`IAE?~?H?#fqCW6@&SBf=W>3adU2LY`Ium+r(Rz z6&beNJ*hyA5f6i)F->FxPA%SBk>As;2fZg((vb( zfEViVu$?`J(-!ji5_sQkkGfxuzHRmUu>E=o9P=)J{fD|fKasgUCZQ>=Mx)hPcBl%5 zR6@R`#E7&)_gwC*nEM%it1QeW$obCwv?Vrzpgf!#mM+?5{M<5tr1;D6nKaapK zo)%(0n+}?Pa^J>EB30$S-nX(*M>5~Vhl%SfqXbgIz1RK^Wxmyd5031z{ycI0s47=} z=;89K)obNv?cX$YvpS)-jYrihQdLeZ@ai*%a^53XptR_R|2^&Be|6tduxNf!h<=Dk zqJ-|x2aeMH2ls8}Q(`Ozn%UbLS``%0(LcLyJtAhIdGI#YEcb%d=Gkl)3}sku8S29< z=tk_&{IUDC^V0l6(Pz~i6|=?Pd$=4{uXCzq6*8|YI4Z67L3y&PFU^*!x2C^TuMxHP zdB8*%7&>9*wKc#p^zLrgFyCmFnwVY z^=l2ed^t6|Y$(FK>U|bB);dSWWnA%d*@9RvhT73g=nKWg&x#g9X*mU*UWsF(A4!xQ zUCUsA8K6V$_|xbZAi9#xZ!hIHhi(^2Md z+mou8^|RBl_u<4w!nN6I$ZI*6{`NB`Op4$*7gE!igpqyknMA)!b2CXWWN-G{YVrj#2voI_Hp;E?-t2_ z+kE49s_lQ3xiubk4*y*#$^ScJ`$&F|z#~Xl-{YJ4#&O)?wznZs=xyUeWZ`M}A`Y|h zCLS`jy?($QzQwjlj0-{cZ0eDp+wVFhn`5z!v`GH3QxXhQo3UuU)S>q5r8wlf`xg6C zIGK{MNa-N5o;dIl=w`=F7?FaYCrHbcj@YfSMA;wQ?SX!3jtMF!S;^v5>^y*QX>D*T zSqm={gysw5p6%oEKQ5c839tYIDD8h7jK<3m>^@}Yzqai>!(S3D&VlsjLRRyDXprN3 z8Szb6Ti$*D2P?S02uAXy`oGpS{ptksSHW2M4|Gj`DH!8#oX1Dn{2UYS`%#9S^5M)^ zE4Xl^6U?ua5h9E?|0L1=#%SWlGD7jj9T?I5Rb`zxZ~yzzeP^g}X~aHN1R8f-1;$fH~nKxLSj z*K-M!#xP!yJc>U~+HU%Dr~=-ljD=ECFg6A6O-i`Bv6*gz59%bv-o>?NL)kV=2WDCM zIafU&(}~<7JBD!O1Nq1wdKLLoYrf&dn2t2R;KO;NIAV2NID!>t>@@cIpBxor#U1i3 zZ?9(0!WbH&&tvSImU}fP;(mc#fng?ZTE+D?gQdxqRrb}J3Wo}_JeH^)QkZbFNH`5p zh^{fDHz)-WRk6fSw@_BqQHiVp8~Il)pM9U>J#V^^Zk>NMAMNs4bauJoI;Uf8?BOGE z96gf9_eVnf$|GeS8sl|DAbp^Ic>7;Ye`vah^9G1Yu&kK50sW|nP);F!NIk!OK9V@2 zE){R&+}_0r?EzNw2OPK)wSrNY6gQoJEdZ`t1CtI-ao?^NQV<`)g6C z<$cyZNZ)Vk&eiXT+gG@FwHJQ%0EGQrjTZ;N0mxD2ex89*OaBN;_<}(F@i#bXz$^ZpQ{Dffb z;K|e!v^^I&LG*33As4@GeOPJ$)lK6B@*s6s=E;QU_^fRcl6KS7V$cPMaACh4EVF3Z zCo7lxi{$T-jinQEC7J_e{&S?@S=0T_w)HFMMA>Z$MEHNVOu;QY=Ir%9EgV-zHNwx! zh9)9i+ghJqIf|6$jyUo$hpue~7`Xyi-WF=>z)11m)FA(hyISbAHV(?n_-9in`yoZ- ze)%~s9R<`Y%({9YeqI_`QUaYW&U9s)$r~p)wgQQ3&9`*r;Cms!ZSuH5MIuOedV-!s zc7Gxijt2t(NQH!=7ZwgSogaPl44v%N4V$+?ml)LE`N<5^ixCmYNiy8VWG8(b4n{|VvADaGdGnpT9RoWDkZ%;zrbS@if>SA#(YbMA3 zfPP?hF+AjLMt(Hz$R)a|UIKFkNQKX3Ve z*AyLV`M)+roumGb148rbhdkPr8^PDuR+@-!njZ@7X0J3;3cb&-9(c%xbjXe{U;WYU z=Tql}fo}t=w>%bIP%QSfZqZW~Yd!YmQ%em)My>Z@h$~OCgy{FHmRjbfBk3HD8@^xz zv;YLP=jU1R3%vCO00^4Mb3H5YS9QVXn`x(aOgKq2g!F=s(qGECW7wNnw7@Wq>FqDh znB^VA<&p5#l^C4@{R9iFE&D^u*3a-3pS6?9)2m2_!hDw5SO4Cj@GoK=Y1#VOt>e&s z@~`XCM+iS-Jt-M{onfRK{94d0_GU79MM%4Gk_a4++F6imY$gfHK!jdL%F>@c705ju z2_;fkHl`20M1cWC#WAPp4v~W!cL+&ylzPA=EA3Au`a=sv(_uav$*z3?i%|K7R8Si*9UYw**69aiZI!lXcIIy zhA(El*ch>HVc#6RKk&^BeluZla~z$tEpI~1MWZa_8uvw;DPM?#&07y9D!z$OgpKU` zyz=UY@FJ5d4;vyqId*1}BP@4j(~m@@OF!<+=eKa|E))+~?k<*n$ld)|wfS*(sSb;C zZ@KA|)!s@gQ>*Q2C(qK}r|xT<`)hqSt@hUkeLsRkvJGlqzem3=-u>Rv?&JP;wX}j!2r!P3}7fs8;_PDV=!*)kER3iWZWPWc*M>%7a(CGQ&sr|ud`A=ZG zzk)VMW`t5VY7Pn`)&_)Fq!2^980b0dh2o8jK>l;;(P#R#j1n#nv+J})UJxKPMkF-r zL=YMKtkza?>hvDE3+uSh@+E-L03_J;99RHO z0$9iZW;z7Bn7II?H8bJC$z|U#5tIY;L1|+v-3BDsrO=nYG62<}Ktufw6C?m903)Qa z^C4T&?62^U-E7p#f<=5$ibJz$a7u zGIlx29xi|}pbPjSU*N(a*2UYcE&Myrb5WIVV;9mV3>UBqlO>(kZ~Qsd_4Nh*V?gQ0 zj^fWQy)!#hvw=A`j(o9Is85_T+UKFZDCx3+UC~}0Rx09HjMaTfv%hq{29CLRH}diJ zUC-lCzbl{vxB?+Z5rn`ev$2X7cES1$-}R`aGElYtX8ZK+sxwF+`c~WBsXV0Vd$5u% zEVc89F~A2fe1-a%MV}!VdPpC-&n?x9NQ3_+L+?+Z{%xe1+9LabXWu=@hruFb`h4KVBg5?3^xB)agP&+&vo6$@^`5o{GG9Cggf(*_WvtAer~gA&?^0pAUwln>hkCM@P5( z@0lh4DNg^lbC-sraHu`(8UfzR#sYWPZrnrW4fudHC(WEUYHGzVCht|UJ>nX#bvX%m?a40db)yB-lf`dykF~^~Wl|N?@inOO-B%&7A1*O<(YVC4 z@t8j+$C1c^5YVeEzFp?w_$pTrI5%1y7(y5tO#k3h8^)u1gC!a_m#r3EcN;EAjAc)} zGq@xalkZOqD5GzH+r=bxE%RX-TzT*QMV z5C>_B4+8!)57pezN;Y*LY#FMKYP{QL8uH$(XGVIL{t-qjag1)p@;>zUj&1*hT8Hkp!5{0b@U|m{(`+s~y)dQiDHF*7q-~k0+nZ9Y;uhm5O zBNM)s(Kn}@jY!7J=Lwr}3f4Yvv>yTWQOLbwn;PbwZx{@(ZJiF?wYKaF#zC!oGsm4f z?ya^ocIH<9{A7Xo5=doud8NJzLCmBY%ai)v%Z^7{jtwPMzvCfKmeym6_1YeV;Lz0Q z_46|*g*-u$B1TY%Le9(K014Iw(r|@Qg0w+3bBKlpeQ{CAl3{2B44pL`Y=#+v13@>joy{AKKa#s)yMzGt=O8P5T(vuud?DAQZ(`%ii zh(W!0R}*humBN?a_~7Jd+@pY@utB44Z_)yP8gs#-zv%v_1J{m6oLX+S83(%2rtOneTTZ(23AsXy z5vp#GXp$OzJJ^;q#;QWiDEclHSjIQb@Xr@VKKCKlQK89RXrm!C!Pu6px;~bY zYqQX_8_Bf3S&2ppnS|AZ{7{d=I4LvXLZVQJ)bSWeMMlWnu|o_)nj&KVuGm6d#NWHw zbGG@j>2IMyn=7_Fve-JDtb&*P`y$WLT#r0lhp;V7kUH#D-P7f#U<vWIbbjU*}cw zjimnAb|q8gOxZls7wxZ2Z)R&Xx}2$0Hdiau?xHnFS^gmBY&ps3C*YL(rrbtxn%(AR zo_38rJ|@-RCe0fcLrn3YnLAKaXWz4^HqzyVFB{P%85mW4sViN$@lTl>mKV>)i{V_M z>h?|`b}LQnC6>FFVKHPF(f{&AWyZ(MTC1gvH>Y`4-ZqC2-XypMxjK0ThiTz57mjF{ z7510oZuJznkFcaV3wXdWc!nEu%%=^41#TPH$5@_QpHSKqK8zbC+>bB zomJ)Qb&aeS!U)f#t690m^CDUO?Gb{R1k@oi;j7U>nN6&(A$el^cMTP(aONSmUeZc0 z{E9OsRi5hL8|I=J^cZd z_j|4{1J_^ zZDNVF{lI>v^aIDfStMWA-g@Y|S=Cw#1i`v75rZlCvE^+*TI)Fh2spTYr;?%@&vA;I#58eF5FlQ zGi5nCTeRJUI$1&}`T`)bElZSqRcBeGRm3+w-EH3t14BcikyN;YbkSH0p`zMI#Yj)o zC54TOcp@Phgtw$4hBQTt@QQwXZpB;9FOfJ+;yJ7OijQh%B57&sa}K)|Umd(8vKEPE z?&uXiW0@q1f!5|r6)XPMeo2%cBwF}~R|0H0lc+XZTdwS^1Rk0qVoA1&P^`kdWRhu5 zwY7@#uLi;VlIfWw+oaT2gCnyOECMhnZ?IZ~l#;76U7c;q_UBf4+L6qv+*G4nu^N`| zm%?`Y&=hesysR^Y<563O*3N1~9bPJzr(~xd#iz(tnN;qGwoW7dPf^`|sTa~DUzn5e)EZn`?@?c^ViLqD zM3)sl&g{)aHsKvW@X_VD^z%|(@A=Q!k22nObUMPmQBKfE@IqaR(!O?~={=F0xQq;C zeGCn$Xz@}{q}C^tvXt?)UPmj>_T+urx}TN;`KEs3_O z@kd=plSt9FfK-jWQGoB6aV9X_-t0oCSs7YM2M^+{duYqImh=X&FXB;;>!A`zgd4&E zXK6>uBb%y=CuprH0&EQ)_=Oyr7lf+AE6#wZ+vcBdhhyojmm*~KTA7OQzC2rGYQ_0!deqGFI2;)Y&rj@?aUvtyAK(# z5-8wdpT}Mm8%D>Y0gjA@9>DKdGzdGxkrcph<@8rt%dc*-e9s8Sd38qwDCH=`0R!do zQszLOj`u+!)AG&1BFYzunlX2>hf2-giWlFWe@0wxa~5uTHFF*)wAC2P;!~Zh)po#Q zBrW4z9(LRylGa%uGoSP@aMn5KC|?~Y@GrlsEZ|i9AzvStk@pN);jBxZ+Et8OTm|E8 zM8Oi0h3;_ZcwvSM6^yzKc&k)lw+f`w$S>9$RN{9;MzYs$wLZHA7Cjw7_u_N z&sTnkuVOsuPG)q>Kl&#_!2E`0ovW^=Acqv>w@r>% z!gffojlRu;{Q40vEA39J9Z-C&JG?FuO|jh%o9M%hfE@H;GqJf3SD&FTI)^6q%}7wo zoTj}f^(noM9nXq%flnt>(M924-*j#r(twWRq{D7TIz?K57=%}0ose)rc~mgBFsw59 z23-Frc{?k2t0TL1_iQ0U+{#qB!@kwiq`PIu4cYP*>)7VP6b$ZspP z98tI+16zT%_~46Bah0zMcLZ~qy}Z@4Y~X!B>oGkF%h87?u@HjUp5NDRpj2zyi|xr_ zhbuU+xXGM;C^~ROk*?|*xy}4QjkJ|`&Hd%t5i|{m%*&onO=E=4S(ulpFWhlylFdUL zL>M4bbIa3H_boI9c3Uz>tOA7))q0z2O9Nf9+BJ?_Ta&k8>`d;daaUjAi&6`#_ie`N zmot=U8=O=zKI48$9s8`uY17t8Pb!bdNnl)3r-%1bn4TOvm6-69U0_r=6crllId*$c zo@YFulRViCS_(^@5LLKuET@TzbNjT$`=|&}R57Xax5D-`#L?DR-rTU@*dYmU_y)~w z)v%#`Ix@Qt3^YiV8RdX(r1k2l+fKVZ+s_;xZD8pOR9}g#Rq7x`J~As{B`9ZRMd?0!ADjg#Qia6 zTnz7osCSb2IOJ%so*P=YM$G2f)C3xA1+=tg=7s*vb8`>91x0;?;Fmh&gq{?ZbqBg$ zUzv8TnDdB(!Uq*U-gQ*(NUDgeXHJe^NW@)wjMF>)R4hA@70iNF57H|^eREGbqzvD{ zjNXYv5|;V#Qq@9ZyZGaUrcRZrYzNeRR}+8suG$LD{IxC`V{@ z3vZd(o^V*f5Tan7pykxlJWymJbZS7Wn-xuBt>-F}MR6~(k0tFEIKS2za`#$i{_SFM-_4xIuMidq_nZhN z!Ojm}Sn!T|4dj%K-$S~q2?u)i1+eF^rOQ{6>W)QK`QD*QYIkxyD4r2HrCBjHm~tyt zC^JOs!W>l5j$`4uzt-+-LJR@_V*Y&1?o3TffWUI~r#SnS7J=BZaSZ?P;ZGWNxwciw z7q2W$E^%BDd}GUr;L1^Antd`s`!KJ1bLLszmA9X6%pOSLoo5T$TN~DQQ2It=9 zQmxDss|3K#UFS>;qs5|xqA~>6VH_+ugJXR{`6H?W>J98qbjD-ywAK^YExS_VC178Z zXdsGSc4L-F0NreDAgx$-=kiOyyDia3F}&=-+nGS{sI`%5XW0{qmk8GJlxU)*Sn)bE zY>#MdV&wl9y$Ky5iAb#7%wcb0aC*{(zJuW$^)ae>6`%(w13}-C&d&i6GP>c8&uS~D z8Np->e>}V|ni6*tvIi~Nf^~ZmjIB!SZx+)~UUaIwi`#&oop0$vkIDd!n|t(bvPB^vcs)k60KEjk zO-KeIv3!5sAQ(p8?Gvg3e~=TVy>;6M6tfDvcWd`N(~Jd-^$%>sY0kSu#S zBeS09N=?C=DYu-vOB`e)JRd$!pT2NTl(3?gceXywyvowE61P&Q*6X9e*g<%A}JADT^t6xW2wN6bw0 zt}99O!2t#J`|;jTi6l}=5OhW%35`l>z3rZkVw_wlh)p?vMnr@7Bt1}Qn68@4{Dxq3 zwX1*R*{L3o5`;!lBbNHbnE&8KVWLKlSt8=gWK)ujM3~TxkusxEZOI++evP5qFKdp* zD1k~@D)8cm;jOQ%-q4dMrfCVTz6(dmD5W=Hkh^H%ebu7mBrpHGRXo}}ffb2TyHl25 zAnrTCZqf|rMYoYK%UAs-bEA^OR$*^6jQ(|a|Msn?A7aATbq)i9A4VP{w&;5O*r!#8 zlvj__+RBjMK<)S6;8yGM_|Y!WZ$ugJnT8>}3e=)7W=Nb&TQFTy7^XBlHbbsmC<;Tj zcT}=_+9`~{b(M1X)3mH}EqI5H|70ET4DA6ogXz6wC0E5%I~gu6=dLgY5;FRfiz%Vn z8xF!UcKMoW;d0|d?^$WQ-L4zIUkwd5aH@86LYYsojpzipH`H0EV4;f>fkbfL(5aJ5 zFI&h@KQpW{fkHGQg|(=3I^uHZH3D|<_gAz9xRYD=Mha~Kwf-|9E>ye6} zC>F!3*xQ-0db7<@0DtW5tb&xB^EL0>(5dqo3Q^)G!XHzFuqdP{DWZbG7a{Uls?`B9 z)KC{Ebj|0(p*qU!GKECJ@g!WYE!xo~XAV$7eYtH9QB%xm>6}8HRFc(85<3R-#2bh% z@m<*URXW`ma9w=AG{yQ&C(|j;F_9upV{Zl&!qH&*g;{qv_b`!hSO15hJccRK^vJ%C zqm+xz^jqX#D3w~V@H(es*LyV(2q*yt$mfp*QvUgb+DOL!(vR{_{}~+}yww4q@yZuI z)zLL62%rI*D9gW1*taCQNq-50`lHpiADSSLhVW;~0BMTeoA#2dfn@dC{~^WWv-;aH z4(z=};b%7vlf@Am=KnDc>`&C+raA34W4 z_%Ho$LT-1EbLwufS~)?GbnaIm?I^x_0e?UciR}Q`-?w>@cM#jwe{cH&nbN+GR*XN> z`W5XhgD%nU%p+s}5OVrLzQjQOxX(+jl0TpNAZy^ivF80J81H|Fp!EwfYuAvgGjYpV z&4D+s=T;%rin@QMwaNF(O-cN%W`<=|i2Jr;Hzxv{UTRfxW8_cdAR6B;;L@&)fR4#QeZ{0jQj`9S7i77Lfr&H&EOLxUw71?2W)9^IS zUosv|-CQ&MGv(6ifpI55dW1Yyrjlo@gZnu5xfIAn%JhjLpVuBhGFK(6o$8Lr6lKfQ zpYLj~Zkj)jp0nzHe1Exl|0Qu=x^_ZF=T+Q|Jaoi%qm;^fP8T?4^8Obk0CWIJO=Lks z04T^m02>`Z`6elgtODx*Q>2~-D)Jvlzg2R-NRVxx*U5LhJ*GmQo026bbqp$ zaeS!zyAjUcJ>E!ZD4D^9>V`uxGF+#0!JE{JIFy&`RJyc1uPbPEmS-A|^fbZ(AACKyxb1j#o(Dt$8pwwNuuFauY?FD%9tj`* z_51wVHtp{gzJ4{>G=n!hb}AvuRO7`ChmWMXto3x`;K^RtBYnl^xM+m1TdLEI?aXJj zK9;H7>-h2{M;A#VUBu-DG6`%ll_zBFYduWQ z2*9$TMH(HMf|ZxpM@lWvH=HM^p7eb?#NU2W| zdJD!a+@V0I2hS}3WY85RtWElKyJ)sM4IkJ1GOT27AYcD9I_1So=m^do{ebrS)E|fC zT+z;QRPi42s_3+HtN1>Bc$swd8Ao+F^id&_#ICh<=e2g3h9^SXzjA(V3A=}f(s7r1 zcLH;~#rYP;XF3iCyW2d$W;iEW-#BA~HnhcK@Vh5mlkbG9o1`oA4!aSl zBgs`1M#$O4X%D1)5zgU;;fXiFk%DlW*R*=u(Q7YBPmQAUZjMp0&| zZK=`LH7sc{_u(eDV;@Y}eu%Z7ZcB@EI$%kE=C)yC9PdtRHxuv8XMoFM;72q|mZbCt zGP8-n=k$bgV2RJk6pRrG&q;%g6L50irtah2m}nh(*buR+dHasQQQneB5$=v221!TFMWnKthUf(v2v9d9it(qv~V-Zf@1e zp%+-fnlEQ90u#@=c4JN;zYhCswsiv@=Yn-3ScvUh9fr5b~5G@D;=1|t!GyvGeBMdF@x`sFz*7X^u1t>nh%s&(OzzwWLN{R7e zCP8>wm%u{^FL4^-HpoYdddEv*;TH1_DZkrb>-}927Oq+Wfl7X(X3{dXfJ#9C%32ah zjCF)iF7~Ad$VK%8xfWoM#^=FuK53HinfitTkmH)ZuO?+3^8!y`gdeTrWV)Cj7@PB) zpQ{$F88zCej8;q)nMV|F$@=G7LD#(+f@zaHg;>S7<<}ai<`td;>MP~8Tdu?js_ufS zC(bMPqnffRiV5x|;GEIwJ-gmLdAUx6FtDVN>hegGP}53P77f0=iZmm4gl(shlz&v$ zeWTa$8G^o1UGlSN8dcWhEmM*OXZDC%gz8wHL)xX!#K`FLzg6~iAckq1(qmml(8wwV z==&`by{j*-Lo`@&uRilfXQrF%Z*rA@-PxybKQk{ZW1e0>veZuD%bfsng!LK>sd@^j zX2`2V%Oo`2zg4^ACDoA8K$U|nMj*`Uqh@*IiA<<$OWM16#i{jm40v zZXEge#o#bLbTz?+$=(IcyVTtH8HR11^2`29MX&KJZu1EUb_etqr;xCB<_?vt<>Wn? z1YZ>*lk#;y+z*M27ER(^W>LwD*Kxp17yhI98&UYo9vQ82rU;*9g)ju<3=t%%k_g(hjNlH^n5Nq@uv2rh_(r#>^#e_<|Pe2o9{xkfF&p~%7N(Rq}*jN;O$liYXdxv-hBnI7p8r* zglYkzR|Mo%}hk?vR9UHxzG#ceVwx!PQhc_K(Q_c4OM@WiVp zC7s+!2p*HiD}&Tmn#UjHbj&*Hq3Yi?a~GbQo9H@c8SP$V^1^tFm~cbEK*nrrDztgp zg_;IMqlazP=*4_}!cLT@z=J&Z#d+POiosUKO9kxau%2?`M&SV3l$cuvebpRgQ*s#R zyvu7CgtmJXCZ&YnIq&W&j*QBRmzECXe5AXL)~66|P*@$Ie$k$^>!Mla1=*Ns^^Rv9SAI+_1*t;e$#^gD$66 zr!3bs7ZGpaZ8vl8TDtDCMb~XrC04Hlo#gAGv^w+BEbgBF_}&M8tcotz8*8r(BWQAT zFc?Lgy=B;{XP>z8zdC>Ca;B`{oJvGRKSbt1wvgcbjoOOAn3}a*?KiWUo}vSE@+6@W zx?(VnIe&Bn-Ki@ME~cCnsh6d;>AhQpE}ehkr&P;b=-9f>8S=!_ zT$}ZcEH)y&QWg{$i8%W~R%mA+?_i?{vHvkpXzv3jV&@g&V53XuU=uk*{)9jrJaXua z00$D0;_5o-1UX@sIf1ZAH|w0hgH9)SorzSPiEW&93TVm7oJj|rDYu-d$Xuv-UC4PK z;|TMFV%f1W+iIhbv$xtpyll^5yRxXdavQr|uyN&&biK^$dd16CsLWM(&=qRzipDGD zAr4}gbmFGPzySapY8?24lZF$rXF^x(2C=Q-<~RZG;%yJCaSfe-b!*%dCje^gPGrq- z$(XQo0;B;$M**X2=n!6B#Z|O+2l73GojmPYJ$+V)q$P-5XGq+cy)M{zk(asn40?GZ zw!HkXy{}Jt1*v+6wA$uGfY0@SES6ndA^{K-q*II|GzkI$fB_Vg3`56>mn+r5g4Ti9 znLVHr9)@7w>~7EvW{k^;w(MIcQ(%B36qEwRgu;NthlICa=sDef**dtT`6!(;eu^`` z=VrWXXIuu1{f7qqhg)4n$pVIqZ3meHrd0!GYy!|xg#8mZz=I&1csDd_TtXW{1t)a) zGO;BuhQStY?u7eIU5QLJCQ!_z`yX6Fjp)1S~m&OC~avqA-LAa4Y z=-VWZm|dtPU1-UJ>G^^g$z2$|+%TM7B5&hDmmfCh;-=dO3r~We`5-Fd)7=II}GZb!l^SRyLiI4Z&>%0o3OCL`*0R8+ioRN_!nL}V~= zFDr%uNCQBARoqKaHaRHhG2n=T8EP(JU%0C8hZYl61DiG`EvPD3V24!>_ixdU@(%wAvaJVkAm{6yrnL8hm29 zS&0B3c><=Xnv&8DTC~PB001Fj(8?fd77NP7RuLp-Cl3W#)Wt~ThuTDC^1 z-E8@zpS7jgOGP_Kc_-kcyA7wg@1%J|r#nV_OCSa?U(LG7MWUy4GsELCWFrBE2@sbq zE(cB&8UW+~p=jNha@g()I^lS_xC$_IxpW*coLEV&*jr$XUbU=OL*Ti)@uCT|{n*dW z&QjMd6DGZd5!l8t&}7H)Dh=^QVSt|1PZCx$N4{Z>uaU^XQ_p!7oil2jQ(>1gHk>m7 ziXW`V8Q$?71;w-A#GncDP@Zt~G>&2MIkBXhwPtEuw(~fLhAQiXtqBHc>kcwVJ=It8 z&`t!w+9DrdlQ>6`y)Pi;MWM0?%6st;jIK~XY+rCPrT{~?fC9o#R#|X%zTl*NLbgjL z@nr5C6A4E}!0p~bIG6ON_JVc(qCOTnBgBwPt**a03aRRf69J2}kbvD=FI~|dU;O!? z(xAk$bHy@QMUxT%BiI27yZ%bJC5mPx%DcttBgHckh3NIU{XC}&PdS`8ck{eimShEy z^l$+YZsG0@oUn(?s30G=p3Jxh%nd2DtSq$~DYckKe)Tf{2DtNXsfR|Hdq+A>!8v9< z_-%XmMQJ)lTvx~)Ff7d_OyD$D4@uw(Rm5(2`00vhfeKOSiYSeWbo+`-h-;Q~dG>Ba zZdQb$2zXBFX2@u{@I zK&oG!uI@A=(UJxmfSrKB>e1cmF~sSb34xj^jhc5^j+HTP__|bh1=K_d8%I)Dp zW|g1pYb#>lqV8v_DDqcF%2if~l_pQGMUtwX@OWu=T7xVfdym-Jh7g!PE$8e&&{?x( zPwV3gj`ae=d;t5chYCOlR#1|dE^hs{n*!{dfqEz|4GNVVAt)Y0PB%zhILXMCP|@0_ z!KU(*jD3)A-d0bX)?5mEZ(Kxu-H3Neuyf;mvdoxn+7a?d0)-&;ZbBtWkF<2085bZa zpCmUP9XlV#0t(XL0%43c7DePfZ>cBJ0aHsANY-JfcQ=EiJu&NXP`RX0<%7&`25~6| zN!C5Tpx20cE_9JA))?>cEJ7fYB7t@06zMB0szp9`wG*UwTIpVGhNC$FhQUBK6t+o? zf&-2W?Ic3sa#ys$m5RqOENfTE1`K0?#X7o`nLu58%UNkI}a?v53 z5~7ll(hbr`cL^AzboZjW8wBZ2k#0ngZlq00iFYnUH@e;D+;i^zz5l`d%rV9{pFkHB z1WOPG&v6ZJN(>`w52LycgHwjDG!0{%;GC6q8>4x0^@r>TzB(OFb#TP2(ZhU*1uD-^ z_22d=E=591N37E8eQrClvw(c_xL4&_N8t^my)zJqQy;qG;qf3H(bXxEUmI{`e=STp zc2&Iv0h+;h*eNO7b*~L+>A_GrcVMwz1VSsC$Yj<=NXOB3m;QRB;fJBh$&SRhc5!gF zm}a&~%D8dUxK=?65>xmLf&ZI$Dy?)xvFQ;dg&gBijB8NPQGO{&F(Q6lO8ynRn=(*; z*$&dWln4D(I8a1}t7LJ{Qj!buy@>K-Lh}<{C;fXTV^b!5>D3asq*4gH*Q`SC9c2%^ z1q-GZB%*|CFd`WZ=g?lgZ$#dg*wyv5aazC*{rz3Az|A+PY}3W*h-w2>ib+-7u2ouF zm3_rCgQT+?-7`blr3dxcxCH*_>zG=g1edc~BqLHNNeZHp9;RKb|6^`npOcCjDCqbJ zx}<{t2W@|c!|*IUj~&~&u6(pFwdts4DQDWAApUf?K@Wu8dBoHO)aC_5&4sIu3s*}P zu)`L_LdUEIoQe(-R3be2>##_}7WYdR{SQ4%wU;bH$MM~kXx$bCo>hdQ_Po<@9U)mh zv!Fshd?BFKa~IvuK_XFleKP6ll<;nXklc!(+sZwiMB_-;{3EPWlo#(%R=4O@6?ZH9 zlDb>fD(ZML5Zs)=5@E=wOYn&)a@Y&YMCl*UQgQ0naC=uD4z6Jly|bBHv*myHNar2y zV7tK12@1&?kjUE3-xA-`>6R)LB0)S{<=U{qCYcgyt-h1wCLNo;) zJxe{K&Ibm!4+t$wJZ6|qVec^n2udE73t_hrP2p85)^IA}P7;#O>Eqh3H^L|5p~+y~ zKy1KdB_Mo;MI5s0{H=6E9Gk`c6Wv+ndlc-Kh#yBZYg5!?aQ6cd@uMSD7r{d0?bnMR zXxO1^(`RNq35Ua)-@&>@#N7JmejKh-MB_vd`x((y-OrSFK{=q&JP4?}u8T=3rpy_$ z8VjVwCS3vrRiWXsFk~7fA{Iy>Kaamj%beN57Gm^18W#=G;A-eu@}3{|$Q^Wsx#oU~ zc1du=kA_ti4Iw_n)EBIs~{PPj|qe*|bEk8UB%?ppy#6A?_Kv%&zY_%1tqqEr4k6d6iTnB^n^D#NR#$XQK^s{(!*nnU(=IXXR6KnYDV0xmN09u9+``s|Y&y_gnNwCYOu z(Op$Sasd> zjA=H5(;;tKc4Oca`g9Y>tIw3=6iX!+UN9(b+M%(Tr1Np=qC~Iyc+7ezfnw(kyJwDy z*LJe4i1e7?8se|mpb2uPKkSrkq4XC^(>Zb8PtLP=_=a|qwxSS40vlbmO4ZnAxks&7UPio3&zI#02I%CPWvg+;k#8v}pyUmvAoeTu&-t#&i`*0~ z5_`Q}nRYzF0;e<;4-eWtWuO90BG=||g*r>Gld;3c7uD9_jAD2Mo1hDN5sFKaqm3fR zlY7u3ADVhBB`;%Ve>knn>4aCIu8_GUlw{G1yL03(%Q;<114aZv^{%<^9{EO{9P583 zV*ycb54!J8!UsAp5qX>q2~Dr}$*O%oActeHa=OOFJJ~1-PrhCDE)Em7X%(+;j=DoCp7spB%4 za*%fWmZd+$B*%C^&K(80c0mq}|E-=cwvPIOE}@^Jejrt@qd_oJ=b=F;VJB|IYeeKD zJ%3R@xfLH-WI}oO2e)iipcy-mp-4|zLd^t111IBXV~je}X!m_?vvhyFdb7-M4j%LD zI6P=zp&I0rSI_V>&rb}#Y$)hs%QnX^!b#B zux{y4*!0fiwVse{kIeEnSXbXSC4D-f=C1v8vd4{gVnl8&V$|?xC1S|XW)jcQ_sR7I zhxL82Sf#Y;82bsW=$tQjQP(jNzDBuL&#i8_5ArYUl)dAB_Mz*n`FOK~^X#iPP<1jY znLJB_JeP8Ek2=tx$O%zYFB3RB-3y!$jWs1`Z_#ZeCvUJ zj@QQua-=))LKp_aXWsaTi^u}>FR|=PeW-3zpsBNaqjJ9g0Sl{V1X+n51j4Gj2SQ%Bcm0zQq=nD}4^oSy$`ui)FN|}Q!5F=8%r;ni zWeLAyU6kFgEJROanP8x{^LDCYsI}2D@#?x5PiI+}?Kb6Fb4=# z@;de4l_~#TL8gttWW{ zLX>xTZh(jJ{fh%Pn<~0wrjNgR=Il;#?xl^t07Q$ljrMmJ+Jg%&Fct}?QZ1i(0UnjZ z_3I1#&90Su@3#Q)P4~ft&qs6%DrbnCmn3sFj`-*oeIS>3bODJE$^6W)0}vw2^nEDp zeKPIga`R)DSvV@um=I%dmjAM{lY_g0C8RG_K}-@5(g}40zXK@G7n|w8ZTs^3V)GhCZ4ONC=r26L|K-;C zX)d#i_PHjf)k_(akwopjYG&1{3&CT>It1ZKz>U^Mp~(%w0r3V~@SgSFI>-(58T9nmz51_uB}*@LQKvP2 z29GcF78mp!2DWQ`fs+`W&tRrR-ZVBaL&JBS$^6)ZH@I#C_}y!sl;`4bQKBfd&!nn0 zK{=`w7REtOx5kR~?g!zRmKMGBJmqJkAwH+&*OZHzsaj6eIx>$F6YN>ewRj+K%8=K7 z5Nd%xBW$j(Eo;4rV9A{t5=VB=9t(SmTBfd|M?vC_3z@ZIWfyh!eH*~#B6_Qyj;0`0 zw!vO&964)hZdRG|{XB(GJF?sZn%r1a*%u@#KLJ{ zX!%Tza6%!pNJ5Kd#R1u`{Gv5#BOH-qIiZ2%x%rtE^d*3%O@R<9#UB->P$#LD+}YiPc<}-=iip5j9K=T*lj1$b2(cUfgC{_AeSE({)0{WIbr9&W1T}ZY=7ubj2Y)!_@*;D$h9g{Y#7rhqoyZc90I$&cy2Jwb?>i%Pq$wEKJZa2m z7cuQTrRD-LZR=7@v-raiiv}aH!ieQR1uy>v}3j=>;H}N*7i{ctb5x z@pyLY7$PWLmK|dudG)AVd?H`Nl$4pbw8c9Y1<@=p-F_HR=N|mWl($d2-@fwQ5UU@>d@ZB%t!b5<5*c#)PBlf%S zwsKVTpp4~eb){W;Djh`Z+LvYLDs;T`Tcm7e<)%V7hC@F zBSYQs{7ZTBeAdL1C1eo`w{c@&dW;-AC+p-u#Z++_ijL8sY=pLn+@ zR=nm`MdN0sTa+{PGMluJi+PV3-RTa!KXy#aE1c2XOuuh9DGc>M;ZUD*#{hTe`gq=y z&{w*qV>appHqKv^Cv$^6%Sed9FMecirvupmX%I(}xqL%y?%i`Y95m%{VLbCUtnUd6 zRw89MHddk(#Qv^yNO}an7JJ(QG8-cj#;x?sw2(W(_aQ$7*Uj#c*RT=%BB819&NlEY zX^=b=B0XTnj{%g_>mZ5SmFw{>rR-*@qi8F=s!LTG#)$|4+*lbtw2T(ejIggGYGB4_ z3n5+6Rg0iwB)Chy0{H;odHo#ldEs*p1!xe z@cH4+*}-i3lTQ=vMY;_s`UiU#5)mr8`!VqJ^b9R$FG{eeTip?1!TN7*AdYboEJwEh z@-M)ylzs4wen}243{@EmC)UhBc2!aWECj~}=?JhZHlvc>na$6Ve82NnKa>FHmA;J7 z*F!}|QH%mCH{_dvSWiWJIfKHssg;d|AKs4liJ*z_#)98-3^0(?rXMquRD#?lkF%30O)-Iq=xmBPIum@=qcxDJlo7fY;Iu^QkCWj)?7&?=sh5Rvy0I?h?W~q3 z=&j1*ksJJQlOeD3D$ynF_d<{pkglCC;=(cAf6?4VQo}SClc=m0f%^1EEdNh$K+V6B zzdkq3ylIg5A8NnXnB)L0ql6nS%P;qMV3LFqj;Bi2Zcb* zw0Ti8{ck4>xs`eU4-WxWGo4$NJ(6RO{U3Nvrz0)R4g3RvDe#o&gS^9+t+yW^_VSaX z9wgK>n;KWLGy^r0!nce(F5`0!|E-i=Xk(`f!baak&9uKF4*qZUW*Mv zy1GsxkFDqk1&orji2Zs$QbS#@O6Fs^5#pd`devwUybkQ&z>f$ zOQ68t)1va>79fp-i7rOXWv3_ViH~A5vtCLi5{@IJ1gZOX0q}qB8LLr1I8OV?)hlLt0NCfXZE!L5O5JW!UL?c|~ z!U{jA8da54$3tAWM>6N18h|nzFc*U0!z~y`nkflQl4I{OiNfBgF&5^w7#m6HzFeM` zfINURef-;*l0oi3GhY5O@#&9cyC&jK^efL`wcCnZ``mm{*6SvcUjrnqlL0OF#yxwO`C@@ZIOG1F=(VLf4OmF>%6heBhF$^JrRAm_%8d(*SS`a6jVerYvA^57 z35P$DEn=y&sM-Rc?0rDXUA;5?!v}a84pGX>F?gkA-i?!w+PCp&WNFZ;I#}*xt;M~C zZM+EM8{T&-GFYIHzrz9}}khxl(h!9n0p#LHP(z zI6YjyQBae6T;VuOl|W}MYum6kAZ}*rVOD8>*C?e7A zrI4DofaS2e`&^MY{P6aMio-}wO75 z;w`EZaFhi$*4L8n#)!W&7M-gbwFg@6G00sZ3WZcRx#(;`t5Hea3=Wz?B_DEj#tn^# zpbayjM{+@<0tp#TP}W30P30VTPsU9_>ww$6g8eBlkLz(Md-LZsZzQ&gYab#Tl@R9e z3_l^*<7{<8Fv~CxZFw7Ily}=Ce%7u+)0{~NaqjUf=(Q?@`NfPqlVbI)h^agW1S4@4 zF|`zF)611~E}(|6`MVkdw#n~IiT`Avh;4d=0B}C~++lM6bryi!KfdJ6D@cHbz1P;o zI5-d;AUIn-f=pIOMqsEDV4Mprx+yb#Cy8xVP1?VhkI;v4J^&qz_5k#0ss7rf7k=Ty z(y8YTYI0H35|p0lO#Qx`cd~h}p{>8pcP)3GWUbor1nE?avD@AmLMvCnAXTR|=kv^d z93I0?UT&LIe5JaFaJ6=*gMnu9nq%M5kPD(KMRK!Z!`}M^(cRY=^39E-A34gB{w}yO zL9BN+vB1NyFfWCD1y(Z|h|LJ*P@}3?{ki-3-r!O`0O9$}1>SHL)e64hY64Ye%d9jA z)oKE+7dK65gvZ_TSA&6^&WIvVo;O}Ap#AJxppur`myRHmt;2RuG;xY_Kp`}R#!(m) ztj4>INaRXCOfFdaL2%wsbVu(sA2B$qT+U8G8`%qv2b_KLrCcz;qlV!^YR19gms3L? z&@HV4UDL0Om>{C4-v-AV{n?7-O<{kzLc$z$M;GtLo@)Nd!_~Q*?826IOs_ViGV#A5 zk~wgL0B%oVu}?Pmb<@O$xFuLpraiWKq@#*Lr9Q{xt5-bWV)J9{Z>&nz&Bd@hUhsPu znLn?L?q>1D+z(<(yW(>6#>HQYlDvDc?pGqa>!mI?^>B0FIjKD@{DA8uGVDEFXy)~T zlaFuq#8qTa;Pi%F;H#;wVWIWV=}GQae$cjj3@N~&F7T=bPQ=L$G5|B$AgOzuU7ae39Yod5 zPCp<+q(S)8XyZ?8E7hE)#VxA?p(O5l2MOmUX$v%2{mOvDV7VTWf(RWVFs`!7GRNp$@^@vgJNx`K>37 zMEhe?)t7xb2eCOn&UIoo-(~q+)w3f14Q$oX2$L2FcOM)i;W;1W2Va*@Ejaj8XPjl@ z+?=t!QZQj?Ezj1hd34wzMUXET^qv}Q?inMiB})!<Hx zb&IpLP)ItTF{A^1gc;CJ{CF|83r&B}=DtKm_8OzU#8#9J zP0;C;VR%R@p?DL`q@w3mR({-~&iJ&3o%T@V7i26~f-mbYb8)rWo>(Z&2>9J$KFtog zsoa+H0N3QCR)w;l)a+WAEN|&^!5S;;Fr1CO)i?a^PSbn=we1iCz}r$yrlXLjd&uC3VNbZP)0jKDTRVDaScdH%d$Gd zv4!Ly8WAg^QH1w+e)r+fbynt%G?h%F^UU3r{9-ziF78jH9TZ(KntXX^d@dRSFzm-k zXkZgXgQ|33Nq3%8W3SR&b${ZFf~ zp|Q@oW2Jd@j(kz9G*Gf7Esb+Oh}i&^bhXpDfU0}V`}WB{l;P4a(U7MFslbZ$v|76_ zRKD)|SvAe;ILF=<6Yy;Ta+lYijdvItk*;$(C9j>$7GY`{fKL4)R&iVqBo?tiUvB3BFGm)bI0=gZCE&aWJT_%d|XKUkaY~?22@P zygZx=J z3*i}IeoitNSwq@LebZDM+^Aug#g?Lhi=Q%we=XB-T<7hEim>xucu0kPkhyX#PqcPU z9Wv8)Y2l94c3Jl+tz|hb`!^*^c0z!CIHqd3V~a|gKAzhKSfA!Xd%Ak_cSPg2bI&C9 z7sGMJop%~ObXty!m9U7UiZmG`qiH9-@s%+4yF3pUzGiL`s3FM zJE2cah`2N|a-Ab?^+8Zno^uU|wYMpw)PK=Y$}Luv8>n9}_4L*18z(k`bqTt(J+8Oy z)zKR595DEaxom;0{=ClfzZP@vK5TlwFq|JudENwU^;^!K+_63I&|M16OzWj^eXXTF z(J=31@G0tzSs68#hpnq5(@_r2v(|FZ4UR{(a(q2a$I`8n}km(ehjg{ zmvMkz_WoY50K+A-iEcGW;>uWf=-u*MQCNDX4u!+`^~yQtqzPe(1>TR5#oLI&QGMw% zDTMl@ZWxdGD0A4)pffv182rTyUD^!im0aSJuntPu74EuRz^Fi3I$5=uaySK5RKZj_ zi@Gu|{(f_%S#rzF@>vMv=yazjM!14DkefNRlnN{E>5B!%M*f2j*f&V&Uw$VnqhD~7sQ`J zSODo_fS81ASO_;j^LLa-_!d*qw(F^`D%@ze+q6Ynh~m0wF0|2HU=vz>8Tyg~WJvSB zGUUR)T#ktcFY{mU#o_N|Jm`tc$Oo*#dMo2M(t8tcJ$|TMP+=++#3hfM(i62L9h>-! zy+0SQ3QNA@&)-3R$FQvc;)*t=T9)6IE>jj{yk51KUq)J#+0lKg;FT?MUkNF<4InT< z^=1hMMi4`Tk2oYf?;RjFDRlY|@V^gwLPkEmc8|U~{}PqD!t|AKq)G`Dlq~QAdD;C2x#L2_sFuRA(rBLj}cy zhkL6ljll9M$QeUwWnN^@_9hnmO=GSRMmP=;IoIpGMvLP06k|(5jgmryzL=8TZ-WVr zyr+cr`yKTi1nhk@BhWt5Cq(YuOvn^#$%!K+T)qlgjN&$!jE1t=6#&~{N<0x)^uz## z5WJgRaeNr{qhZ46w2(ZPk~;R*V5Lmlc_9mo1)8|{J;Js0eJ72Cv;ZParOO>6403Y# zH^>Piwc{nd7*YQ-77LMhyC3_p(Iq@zBY4y=GzzO8x`^Hq1h&ECP)`z1$bTP) z1HuKN==T(LKR1MHOP6;)y4M>?H3oOp8`(M@cf%v>jK>Z4P}-`i9APMtreWV$s}lZA zt}*X~wRWxHPG?SonvG85qi^tQ-wuiw8~juFWeQ<{AxbUmyM-Ufq~qB-B4rOPw?OXV z{z`r_^_ATta*79c06+OHZ#6=UkkF^CDpT-=XP;%D)vD92?&z3u&uRg{P&kwP;Iq2V zYr|>M;b9N-01FWg6Ze587s)pUd246P1RN~toy#}LZpiCYIC*cQb;@s@TAm!epKfm% za&K`z0rgJkdVJY24VK%ZiB5kucV~S;qGkYj+WP`9ba>z7%yvD)^|~Lffj@aHeP$qa zYCa&vAGS^z#9BgN7|b?KpA~u=*tLY+9bC`SN)W1?hVEmT8%0Qv6&OXzuxuDbDeyBG zM=Q&j8^@^Y6d1=ocvwI!k}^3e$7B?1{zobPBeri&lT-P#4R8Pj_}0*g4-sIYAuT)UvTxn6z3ziE>{t>bLo zI!&9*P>^L(xZaK-e%Ce~Oa8&l4je-(yH0%Fezx=twD?&6jx{h-IeprURWEJLwpBSx z#e+}%>=Vx)^>e;Xt{C7tcn-Yn%qgv5eIydg2p^qI>s(39$;#RV%Bu{u($kiEZ`2!z z*-dv&4f^l|LC{xtepBU=@E~e(QD*lk91v6biG~=c`S2DeNHBjOsJCqDj1p-I4N7`| zC-wHx4(ok0#i!#ToV$k^!)xD^nS8ulg5f2h!fUkpvyme3NtMDu5YY3@Ao!IB(q;_c zv1LpKG&8wgJdi}h%B!==NDst}v{0W6B}C{eXpIb(dajFwE>o}o=a(8j1T1&FCXPBPob(>Q>t-VQW>eTbMYIm4h!COVT+kTL?1q-XOL zn2&n7C}l#Q_Ho-3^=>-6L#H4D2h_uyaUpFAi`kW-7Y|%JuNJfd9u_LZg(K(?kmJO7 zbCLyFUQA;C2qXAhhYcgR@@niutNBXRnOei4 zN?*luJ8A{Y&Kz7P3`T|e2*^;hTjFj!`b?F(X4 z|8HXip!P{Su)?~3&)PWu!$>&L4%LHq$8^5mCj0SBBNpIEyU&IY`EAoqxAOwN6qKjK z(U?g$bg_D{1-Zz8(Dn|4gmZ@LAC?HaiY~nZt8~9~hdy$vq0&K?JqiZNWJomJ&;sG; z4Fw<}fe;8xq7v)+6Gy+~c2^dBCQzlmK_uehQQrZP7zyKmhLN`9qpWoggV{YIAt~q} z!cGxdm;Pe>U8?)UX81@^f$O1?PZw84Q0RN?Ekp?nVmI2cL|OTlbbQyzMl<5f7;AhrV3tXKwH z#nDnvmsJ*~gYYHN_vT`~iy$1^s2KvZy#9U$tEWWMQ)kT_3j8scJ)quc_phqyjNVK_ z)Hl25k-yY7A(cFe=o17B8)^2Sn@4bMy`a7$Td!%M9GA%pMZB^=t5iB*ZMvDW6MN9O zCi^0)kT-iqE*IBPJ6m^8lfIvb!zww;M#r4y!Fvp&@JD-$x?4o^aPMnge2ua3dW@pJ zC1I&jodUoR+vsivN;b;&mA-zYnY~3ojdly0)t=_YG>-V&SCs?mw+B82lMr#%^~Zqw zkl$)8%F$9GXt9Ji950b=#d{)O-7XlDHu^$DDD`#pK}6iM71~=zJ^#hf+jMkaAaXYKuhUN} z^Ia+;5EGpF^8Mrsdnz^sDm34ex>Y^bZdzr>G#W_$Qjy~@U^(%~rvrC;&!QA1R#SSN z23vT)?9NqOlPH?WK~?*QsZCa9S`AZgQ>!aID|YVcPf=u|*KEI%-L*?b zujp7l2EFiGa%ubc;I^Axuz2G#`B`oEP5wvWQO7H^XK8))sFCl|%HKJk-U#pQ{InEy zi){hp#+UZsl<);U!jaqqT`F}$V+xycM#``3 zNQ%7tgV*#XYTvfY?UyArZJP-+OuZi5uWD%8v2r+k{?1t9g<&w%UR-Ssd+?ySi}4X+ z+fy6(lTx9+yHxno(n~w9Z8JDiKPIq;X9|Zs>dl+^6wm6k#`NN7(D1>8+sC7ReT>-X zHzr?{9MH?x5tw*89k=;x>bDK$UDAi<_N(Zecl`%lvUyMTSJBGzPMSXQ4t3giTw4WE zGHFXd;t0;bJuD*{y@OSP1yZ27 zlTU3RSD}#1#)k8b?u+70QVFwE2PcYJC(3RoT6HgaR5Qm|zIr>?bchqxqjgECSyXnraZvTD)d>;#>serk{NxL)5zYWL3dtjf{ zvzxnsOQABr(a+RQy5>$Eo@FJiLo=6E zi-c7%UPuF%<*NXTmo*+Sj#$yuyu={H9b4`Q1=E z;*Y&QVs@i|P_dAV*l^9Rajcv12l)Fhzx8Iohup|@q>2xxlkhsu4`)~pC#MVSUB_Pf zNNA)8MJkiLyBInzL9{#as9wddW8DIa&N9b8I6y5Toin1VJDAiwq?I7@<$45VPXvty z)*!A`MH@7%E%IssMS6|x^~qp5$w(@+NX|3KC~oekyBbkk=8?P`QMU=X4JaI$jv^%j zDVXxGs_3Kn63D0zOji|MmFgne*Q3=5qczc@A2`LR8)1S`u#Y%mzlz10XvCU1#abl9 zTGhpV=(I787iH|R7A!M=ENP*IXCa9eW zOo*RyQ^8u<>`_O2?pqI!4f4clEW1D>J11!)32Mq%I~fB{MKe5w_ymGa3221Oa~u-J z)d|&bNv_;UF9?(7Op+>{lA_B@8=aC0%_*w51Le!e_2?rE3Gllnb?_u;a?Pn736mi& z6A^@H5fo^3@E#fgki)=~$c&VQ$&~4{jg)1L)J4hEcjl=}38~w4sk?!x?+a2taHoCJ zNZXN2J1|ev8Aq1FOGthKsWZ1MIJ9b5OheYRM4Ix|#7?MQvqn27(qC~-Pg2Z4aL#B- zh{H?FATG=x*vugLnnB8wNvWAh;hagHn29R|Sob}3JIG`s%0i%nKH+w}mgjRl-!l^5 z3F?182*v9gDip@0{~9h@=yk&sBKg)CDb5f2gqbD(hQOLXmz0mRqmN2Zj-XkNP;HJT zkB@8sc0rf_)iPH#wcAU#v9e>H8Y;4d8IVmFvKhtMX{qHcndK4t=RI-GdzP5zTA$}e zl<&cl|CllIn|>~9g~L=H)6Cfu2jpBmC;S2%o&tZ$f*7d+kbePrRzdJo!EsGN98sY= zB~)xfGg%F~_|c5lG#tMt3t!Udo@sXZRJb@#b_E!E(p|k;LA+H)8tieMshonhoK~xx-o;}{DiEto zTEq@ruoS5VOS;Ssv*fH*0gaoZ&`%1LyY%W2^tnB|77v^h6uX)Y$>a{mnEbil8%GzU$K{?Dge9LABx>wSWn5i7s*VJY)5=RQ24~Ck`8ynAmqCV?YJBDsmo| z=v5kTfDtFZpzFM{*#Y5RZL8o+_Mo2;S-~&J2G}gpu&?Z%F zG;u(zOF$S`Kq9e6l2%`qg_{93u!KERR+B_|KarxX;;kNua9r?F zJSSer)qV&Ap}Jr}6RzURrxDc@4~TAR2qo1em6|72BoMn2wzo>Qx0ttQeN1YjNMhQC ze)y(IHbuvY7ZUBT-Z3l*_yhN3y&UZ+Oax(;D3G$C>OplZw@Ps&4Nm5o8s5b}Vql3F& zNOn6PC%Wmsd~+7u6w=ro_N*zK1iPIZde7>WHhkBNS&!x;Y4f{XJQVSh%WYcYlyIto zIX4orP`e2edL3tab3^c6JXgQJ5g)(Nb9b>lUplZx-$>-RlgY_cVw<{p8G^f`+;R-ZaW-NdwV}5>Omp=VyyM#z|8T$9LeCq-9dA-xH?9c&s@2s zaeiU7&Mw_{+jnn0SIeL6&DlTBG3KrQnmjZOj!m(u%h9q=BOZ1}bx5}yM%Dhor5_lU zKC*e2nU5kq!tOl6me|U{So9h78Pf3xid7MXbt@(FDCYK~GDa+gDKkRxoTHm{{{DkW z=+)oOo>g9z$aMSLcSLCI+0V=BGx*+Q;8O5HRjsa>>-lo!v7E1u#^ z?84{y1-H4+?ldVk*VG|4u^HV_*w z98$(SncLFJ2;K8g2%Dmif_|8IofrLSO^ZI3=zuk8Sp&8X;jKB#f!SsLt$9KImAS=P z5jpd@*+(dmtiq|H_>5R6qbuTrM3>jC1;7}K<$R143DUaEd$aXufr(pE#~c0sq%E8^ zwd^>g(iCtYavIG0IZi_B;xo^;j+Fp>YX*RE!M2Y7-lN_t@nWVLS|bOO6*U%DLOHt{ zzf=w&7;gZ}6aW9m;JK62pmRJ%{4L9ed36=0A?yM_2?s?wmhW}f-~0{k^Lc;OH* z_;ZkdE;zq6*Ei_8vF|nCU`bO+qwovi0Hw0mF_`Y@w~wE<4g%Z-?rELkUf#MD0SCNy zF{k|Ze=eN-4ka3FpAPtK|349AW$6dme`b6RfZtvsx*=Q_fpL>u{I11G_QU3s-(iR4 zfNuK#0CxBTCYtry34VMD;qb4lgQNhz zj$vQ?Irri#L6RUnm@Ko)AcSm^ z9Tdco>u(@Dy~mZwcln{gZt(WS4MstgA^)FZaN*(7f8T!o-+4S}Tl~VO;Mby%OF~?1 z>Cm}O+=x=Q3*%E*!epmSV|M_++KCeT#_Rn17uft#{HbrIJg`;NfYSN)^IzUzKznuY zyJdn_;ER*wYR9NkWChxAU?=q@YKU{2$@WC(5Z)T?6>AGcBr`UJf&$YQhT(aUmJc=9 zOekcpM7>Ev*;|dV!jwD3FjWudq)*IXdvl^3b)gJgh+qJ=qJ2111#b4dA$YS38uD%= zZw|ykG!_@Suh5OWjWc^9~efr-cq%Xe`OjrH6eho^G!Fwm394>a1 zmrv&c2b5O)aO)qzxqp&aH@W`elg`WF9P~_i`l$>vmqFJYo0gHgC#z|g4=Gqb;Gdld z3uTaCfzC1VozzIYDA=3RR(%Chan7;43?-t{(J5qAAvv;Bv;f65a5A_7BHnF@uoLm6R&yiD= zpl1Ne-{B`R=TCR|#b4~7|MU)DLQdT&%q~<9p6UhIKTU8-^+BO%dH}xS!olD_yu(D| zz#Rri&=;hzrqq{D0s=zhxcFof) zC1A@bKu-dXEILyN8>4aw#JYq>C49L!Ne8gVAAZFmd!AvD{d+c~B(02-jb2|gu<#|R zE7uzcqtl=e7y(z?_&xMcxEHZF|S$h~zTD*KVYf5DhQTj+oK9{{|bM~W( zLX50jh_m94uMtR#%qGN&_g9Mj3las$YSZVQ z+m`|KU$)M35Fv~zHy(FQ2@OqEKTJ?*&k#C?L^w(>_VNje&>GEm+7*r6j4`4|)WHmU zD=V;6hQ=Y=p{;n|0~>|Mi^{>kqG7LAle9V+Op?*tdT8Pi7R<3yAG2herXox+yi13_ z3=u5_d4U!{c0ZrhAH5d?4_JQ2C-7bRUkWI24s~M{l(rv;PvtV1u+o$6+Il6YAlh)2 z1n+4>4+D@I$i4wyM|X^)3)L%N$`F>_iaO`o0?)-$;U^Qm!bavuehymkmT;{s|AkTb1-7^p}{jWsG^#$*7V;=>}H?y=9J_J0X zI(|6T-9X}|^cDP$G#6~6_0^`vs*tU!^FWtN?SdURRbxvB4gefHgj9Dl zWeKr*N_10puTFmy`APQtGj>OX^?jJi>0_o-n!gz%q%uK5ug01=(^GX4?h+SdxniksY*reOdJxBdM6pX}p5oXD^2V*u5| zb^jR|5268ZB5z+mq5b*ZLf#-Ohm>7@3uOS7YVLPf{58fed6#mvsBg>9KQAza{=J!y zHIX?dm{N#?qq!HZ_rqN|7dps$NzLyKZt5<)+6F=pm&A&XGJTz)ki{=j`gm1P7lBq{ zw)YKnLHKh-mK~|;ZBP-i8tg3?GI`~A@zVrU7tf{}I!d)U)x4KXB5QF=-m3W^=U&Y? z$KD^$q|dO8N*hoc$0n4B%*^>S#h3&-otH`8$yE}xxA9#ywE${<&R+?pKO@~aTzdbUV9K!a9l|$>6mU*3HL|z4 z%V4a$Cvy(r+lbFqyR64fTtFo7EKUoLUefwTK?DUN+F4``1spWUxMFc8NJ zlf8=u1e2Y*yVM94$9}D|6jN@6p95B2=Uu=rRiL1AN`vJ{_VqSrQt5L-_iHlTqF>0t zj^|nGp9$R;3O7H`jx1$-PUv;^&j!S>&pyBzXh0Axf0hT94{v=)`v})bNGt9}QrG_u zd6Fj_qbdE%)*EvZ)@E&T`^|-72iG(f{zm)HGi^-xga4`#{38w2EW?n?cV%x#-z>wfc$xBok*WIM|6` z7%@~8!i-23X_WeyjI`Bxo; z7oDpp{M|)Q>PH;=gW0Uedq9;|K3T8_Q6Xc6+b%e?>(J$ zbQ=0v^I!Gw@xty>H}iG*A2XvDZ%w`qy0=to{^+=aAN-5odqKEFrcc+O@>E{%fG0Ck z(8QtvrNg6&nPKDLq}~?wC4l{2JUBK%#BEzHC|^s!d08f*7+Af1xsyu=?(%1l`)@y- zlH?y%n7k?-hUW#NC@+tioJR14B5(hUFrJwt9*^}#(qWPj5-`%#p8(#!xI!`yWjtK| z!LxirwsXh|i!iR^IH=jnO|3v)9^{7X!pJm5PZ|{?SAbEIc=qv!(zPLszAFLnJgo0V z{~B@pjZ9sM0|ppk0vR zFNcUIPVw)XnahU=(=z&7nz&#@0mW4?p!@MB{>}F^aq(*Y$Q4&5dZV}4_D{tX&_&8l zL%)hUgEriArPJ^Nru4SFUZ8c7aV71wP378b**6i}+f25YqtpyE)Y>e!Mxd+7kyQSJ z*&Od54)KC3{)ckcY=RHrt#^_aHYx3IQOFty@;{|={-DWWm(lcp(v^P?^8Y9-2m7Cv z_7Ire+z(BT|4w~@?~Ip=7dH1h=QBBU**AMf6*FH0Ctczm|35#f2yRubsCp{X6p=xC<8M?}dJy*Hx3| zza|<)AJ#_m1=0Zc{`UmwH*K;%;@;vjb$Oz3x!nAt@gdRAf9Id?()8*L&{%U8G@Ly1 zx?E4BgMvVx0O~YU^{F+>Jvy;C;+b78%k&{M*|Rl@fL^5&0bSl zi?g-0=2|TGb};CBXdy}BP*1W0oocM)=G-^&_z&~#0e5IA?n%KhXeCu!86?-1ull*{ zOiJNA5#&ve1NtI~icr4h;t(%Yp8CB-RRm2*jg9*1)uA0X$pXuUntAtPys6O{mZJB| z2A+OZZ%R~lJ@q3l;%}D*<``_$|9%0*cKSWZzwT61I|&cwf069@t2+NNhajthpSExD zP>u?q2vS=DjR-j?1c8g!Glgzs9vTSU9Ot4E;&|zp6~wbIu^h(yHGm4r4(?g}g<$h{ z`IqmiO#c8$PH|i-c$fO@rz@{yy>Pzx!IQP2j1Z1ZGsl-7QOzzt4_F_(eld3f2vz5y z1p$fj_fSps^ z?WidM(-Lr1)XGY)YbLsvqNQAOM^<&V{@~usL-Q!}w-_I$qFZP&CEPw#+Kii_ z=N{iJ3-JPACrs{u3fKQf-COuY^>y#x!_XblDkajPf;2jVNP~b#iiC8DfPjF~Eig3F z-Q6JqO1FSCNJ)1$zXPJ8pSbgTzn&N@)}s+S9{x}#lf|L7!s>AIuc_!`ofqbHm{2&9t833`Ddl=_GfelZw= zw^|fG?uKVs`Us3l7Y1=YdZ|YxPm~2Yo? zp&?+XqRCjyZ{=86Ea((VQaLqLG3Pp}W*Gb8n=CNrR&3XzL33UK67(KR@8$Bv;*5au z<$7C#()C`$mCDu8jFtC?+Y2jIAmqcKY6K#q)fyDq%+(JVoQta;afF%HYVj3}*6IN4 z+*-XLBH{q(qnXjCII1sO>P>VhnYSDi2z%C>;V zy;P3L=_w_iA&*JL+#bq-Kiv`vxOn+aa0&JLGqQ?=`ZUQ@@ywhWZT7HmB+GA$wV@(Wi^TV37}sT+2OiSK znL3T8Eui6NS8xgEV0z&jnpTUPjlKH_YQQM zb237`AgE#%@d^*rD9v`VUK|Y<9puEx+XDn_^swEtS{3_84zYvz~TS z{&0~nEg6jlbr?~a+aDlRyjRc34X5ll9lyjk=f(*&wvmGA2-EtXHo#v_DVH-y6;1kV zJa9_QCcyqG$eB|JGB3EjYo0F1mwifZ$VYO~$oz#l_YUL>>N(3`{*_eavDyc9$GGW4?7OGtTdOtv&&x&IaN|FWYY9JXQRw5)oCY0JY3;2f1FhD;eRdw0epiaL zcyTz-ZQw%8a5B*C1>D$R#m58rJ1t)&J;1MC12;DMfh>cl;;0IaOa$Af_G$Nrg0jD4 zoPb1Lwru5$m!IH){HZK6ltQ(!#f3-}*9dL1M6}!aU_DbEkdHLPrC(!4~R~ zI`zR9CoWZ#Z%eqxBU77R9V&b}RQ+_{LedTr&{8w7&TkO9yF8KithK)jKfJ!rmhA*TnLQ|aS$w2MbY8gQAM0a;uqXrRtJSTua6d8PJfSAVVtqg`=L zVP|qqLJV&I#0F;?#N;cv`PZ96DKvb8L_4)xBiNqzM$SHiJg`NkqtEbd=p9zfn`sGVb06g^XPfPamkE?N z=DDrxoK0$?xoZ&H^aR5esQ)?%r<|2i=cl3ycArevo_eevUvHacis2<^xmoQn08iaR zz%~EE$+1`E(Mc`(RMyw3*>3YC;)>X1XDGrT)TA#i$njFo!k4>wnDmauTnKWuIf${I zCj6elBzjTAQ+_h|LAuIHE(8`|H1GRQ54vSUO;fsOy+Da~qY5FO@T88{>$D&8+#Cg& zp!E1bi!kI8M6W7+mVSc-cS9Nt+@{8lH*dNhqT%6716CMHnzWpD7O zqktZ|_Zq1(KHw25oN)EZ#^z@TqW&(d;Bd~cWOI}7@st@?U?oI_3{Iq`77s|fUh?@I z_#y%G1jHDZfv4^LLQhAyHzr|!&M?{md|(*!flz!gDsqbhM1r=@1>uF440rLP_teEt z0Ozq)yA}^`h^upl(97U`LF+*b79C_uESJt-7*<`VAIg5WQm&F($vx2$@P4&@;aTP8 z=w*}4%du1KAQ7XvAj=v+O$uc-DAvuX=P+8!B~o~^R$ncB*Nnn=d>0@V9Purls zuEAKrXco@gfU(h<)byCGjWyv4V-A5g62pC~rNe?W;&E3Zdyxz=!gnk)m-D*~Zyptv zOA?8~3ciM9vOGP?U(6~;l^H4Om-N0`G{BS~x!v+b28p==^#Q^6b(&?~FGEN)Oy60UY}y`IqBiv?jaLZ#lEqgzahDLO;ca zn(RL;G$Y9pOv9FLp37}uIan<0GpUeQeL&r_^loSL^YVLSR=&rJI``+(T+F==*9ABq z?02@_wLe^?8i2=L?a|HQ@7(TR@3=cc^z20^Hlp@>Xg_+;F=(O0{xx(t;p7f;xh#dEht;N5o-$o~%T8YzjgXae_bj zi2U&?=_kgDk54cQ0$mP799$MB)iL};>by%kIPp^BaB!^!4j!#}OAlOCG$=*AMIA@5 zG^REik5bPeR%eUXU#l9u%Y<3J=KCbC>uxfIt2_+b&jH_4x||cFQh3if3-*EVSfc^L zgU9fGt&K3?MxC&77o|Tt8WsA>CaEVb)cQvEUMFJBMNeUrqb zE83zwxE@m4n#5w&)beD1J+vAl`G&h_t7d$|-FgfytiYyL9iEN1l|!l_v7&7T${XSR zt;rlEO>HJN8xdm|DO?Sr?PlQ{k+TvhJbg{=mgO5!t8Y^HW<)z|1~;O2TT|}rG;wsi z-rtA;VWvWm#X6lxH)ByGQw4~cJFS(4(K-!g%9UxOl+*oMQei4sdBSh`;Yb@GH(Wp)vq%1u!LlyBlU7{!m#cb&;RGT7e_@R|KHr z@k5fcHiT$;V$hi^=Vs2+8Kj_7lH=N%+7jqCL@7oPWZo?VqQMpg5^V70?y<| z8{+AR`ZnK*y+50wca9!xE}pg_vb}&25HO=2D%@Eh*B<&17<$x~PC!4?oDiCH=xx0; z*i~>(@D8j3vI1ZI?BuS#LaWL&@)2yaJ-1yT9aA-90`Sf%A}k zeS)ji0zwt>fAV}>qYuXsZe1bP9#?iZ%3)jsW!x3-PU^V(RWm&e!OJ?t@t)U0L}Wb~ z?$lldp(eYJ*hCklMhS8FqR2dhzZwR?GiGiKHs;Hw8TG;2L+BBOP>&@#%>q*S06D_1 z*I;01)7Xo=7hkpA)Z9>~!!$!gr{C%%drpTN6gN#rnACG83822A)m5NEo1%7lA@FuI zl4ullCf12iY&OoxOK&Ki;8wa`0_+Y0y_c^nX-eSFXpp=GUW6T?+j`R`w|vo?2$+P0>x1%L&%e0On!o^&U&bYOnZ8C0sr4 z^t-*mA=dYYNQ=wWu{T|=5Jk^t+{kV>5fH=E?w=ekI%?w0ts`Es&8sJ2#aOK;J7K&f zu=M_b-0Hfaky#b(ko$Th{pnH4+PApg#yr!yo~w)jQR)B>P(`=#?SU`PX}OS&z0pKg)R~Jo5Al#b(UJ>i~Xf-V@c$S+CyX{V6}} z<%4yrQU0UdFFE#ydmHvAv$2<=K>WhhAR8&s6KTQ{43u=I!UXPMMhXxu7X&FF-JCF! z0`Yok4VKxeGfCp(QNA!Jj!Evb{w|T4cVNCRW$mua_)k_}r{J&*JQG>?NV#Xi_5Nx( zwkr2x9Oj9A>PJc>e|Hh;cpS&skJlJ(dP=>~yp*CR$Z#vqOYvPiVa~nUz2|w}oSRfc z=5+P9+}7TxOI#!QR4Q~^0Na^9QXE5{i;sA4+4sepAXHK74|mqr{A@9_P?6_^p~sSs zpGzcC5j8am@dQvVQi@O`-x76{lYN9-mPo_aBmlVBG_2&nQA)ZI)+i`@87p7HnZ1CbgIa_g z`Ie-koH?kkm4>ZkPQpZ>JE9AL_I91Vq?u-S{zmk2 zEiK;`eQAdiyD()fx7rK2+no-0as=+!a#3nRLS^O+r_!JA806nX4^L%Bs0LdVezof|)Mu zF4hxIx|J#-nJydJ+>^|+l_u?zE|((qIbC@xU9l})zNGncw#`*F>VFyqh0@AIThPO3T7X8M<*-X2H8h$BILy6nR9DNK z4i3@G2)bR4fgZh0?q_K%xid*hhJqjJd!W(Bq1%(MCsSUyw`K$!=A8NCjf8O>rPlPl zBXrk+K?@HF_(ETFH?%G6>eErng<$bfD=HP@N6GI4?-q%m~q~y*K zkKP>UJ&`-htDKjeBbTU2D3VH<#}JCDbO#h>S3==IxP-43#)U^;$JBAgK*mVihaFK~ zhqxe&-c(e7iR+ad3qiYq5^GE1Wg#vAV!9m%5#78Febs^L^4P=cIi~}{#&z5f6D|Ri zr`nfH1cdOi`X5H<@Zu%imn}ZLRzu^PHQWE{{w*X8wZuaP%{@M6pTK&7m&tno^QZ);|*H_({)*Gom0?4$B+PDf(EJzOY;KCK|4Eh9I;H#@# zPm@`Q^TzLaW6__gr^Z-qPZI4cc5@S&0&(myMJT?K*9VZuH1p}N5W(Q643CGn3uZ)B zPVi8S2Baxki}~y_&NfE~rWmLycF$EK1l*DLDJx9iQKN3KXj%7@*DkxwpC_=22I4x@~oXe6UrwR-?3)`gmg? zquTc&?CJQ!JlY{ar{qlb48M#ifRFw6J?THHr}ShIwvQfmJYVue4!pZ|@n-xE6bX6= zQUJczs2}l4D3=%ncQ4RK>Rd2^a*p`swFbYx(0X1VXSX$plt!GoEm41-=(ko-S{v3^xs?v*d#VSw@h#Ih(fKWt#JTdahzc*J5 z-&6>oZF2Y)0CeULc?U`X-2+Jgf8FQ&uS1<8uo!-Ch5s3^^KkdsnTYr&$B|ucCA2zv z8)@@!k8!pg=p6BEa(1QyoulvH$2XDQw^{#pam&xCCBJef84 zJ${)3GRfI~i_G}_7vs%+Bv55Ha(tOj-4y!K6&3l6o7Vt)PRLC92l>r;WJX4Dlleul z#|0n8A0foRaAt&M@GMW^$uQxL-^F=VHYg5s`|K-m{jnqvjxH{VwTq&AWCEuvqGoZ8 zr>`+;(P!Ep=~zzNeSbD;{^)%QSq0(>{z5NM`O*xylU#xW6}cBLRjY~m>$qHIqd0rP zp8Z%kpac**NE-ODoW3t7Tlf`{UzXE-$0Zg6qg2yxjmS(r!=I)Z@lX`CKY6mYf#>Hx z)?Yu_)rz9vR(ss10WUnaXIcHOtDWzmv&TvWR{33!2=G|GKfW*&#C>s~A9l|T9edw< zH#fe{8Rduk?jA?0;%ZDI;N>BUjL%Q1wuPrF|MM^G+Zvh=i0A($cI8iZ{ZgBn$)uAj zBP@Hkf-FYtbIbWRcUGFb1GYIM=oavZk1ssp@nvh)e|uyLp+q94aQ#}T#zKUo%5W)- zIpo(DObv+X>>sNB{D;WKU$R$lScV4Rwd%!Rn{7`PopAlFC=`J0M1716)kQ?Zu zLmm|06d;LoT~j%4d7pA@qOzy9MZ?RJGN%U3)g&XtVFfY347ySjF_lNcKd1F(i+>Y5 z|G6xUP>=_f1F3=sq2J-^S0Ar*xpZ0njbhHZW9%(+nsX?o4om4<^%=()L^rY<i$n*Oc`8@gM2Q=@8y!L{e{anWL)K8LN>rXh1|KS+RcXGbu>Zm#ZUIQcw-r1aYhkFwQDnwbFW zLeE9dNH0E*0}HeQeyw>VLq133y~BfI^fOi+T^rSt){q`(!<#dW+-kdHDC3zc?Yn2> zRM4yHc4bdIueujWgDB`#-wV~DvTBOba#SU&U^lYo#n}oF|1X0jt;grCQsW!Cns~5 z91i>tV+9IFc;YY$Cp3=6F=u3<(pVQPS(I@XV)?LfS5iwr+)n6L8s|Y)EI)3AJD5Nv z&6w^n=5@{2L-P$%yW*rLmw?_iN8WG%WkwI?*63Cwlhdk z9-x>#7)_qAR4YfBw$eCl3q4JypAOeaAE1fQ`!J^y`K(uTCdz!8ekR(|X2#pQq~F|+ z-@aIn&hOQ_C!G~4)|6^IY$7c++FzDIKPgZrJQbp1*_?DnF-sjowZ5K~knA;Ye=j7A z+Eb+bguyVg@PolZMrpfE28`LnN}T@&1F=z7ju*Equkd~;V_x}m^I}1ZkoQ7*y1e*O z(RLbfYSGf$LAsKDH$!7p_$LP0NwWqv+2wPZ^ULKc<@(-?Vi@>{35fo1Z=uCOLoDIP z#of)&qvW}qszsVBIUiOz4s)U-ofz{<@$GpWK;WX9CLosW76gA0#fBDJJ9!w*+t|Nkn$yF*negK+?wRys1n+fAr8y5ng$8thKf>a22;P^gd~5X{WgxvmBYu?(K;~sekud>O?51d-5TQURd?P^4V)9l zT>(l$e-HfHK8I1{YMR&S1hT{;c#WNT2&>|r_2M`ut24DMz6?4Y=-2jpIfZT}=O_+= z<@xQ#y&!v3Py>lU%q4jtQY950~b}$`ZN~BVF#0loP z<>AMqNlnkyBqp#P5Kv2f{kDFSgpFBX%px_NFnzPE*?JJG9cjLhWzw_ju=}J_<2br6 z1(j(&h2*hMFdM!URLpJK_n`1jFC*hbS3%LQ6ObnSw5u0Lc1z z1u^}by3X&fcRC?$#&)sm3E+xJInxw`;ix7HUK9HyUCGQ#+@_~xm+;BgW|Qg4QL2bA z&=zX`%GE52WiB^=B}A$r>78hrgaS`@NbhD6=j~tGLg=@0Ny!pZ1^LrueVTg`If5xf zT<2w@#2%&H+46l@Wbi1@=8>adaE8j3fxNpHeo)tDCdYk7sn4Vji^FecnW`E-9^&aM zY2M1VsLN2@XjbrXv7kU9#W4c6T&poN$Q7Vx(!jOtk7w%5^VH5%ryNrJDAk+q<-?@S zdZ5@6;GG$ZnI(G6Fj)B}kv8!Ws)@WUPH#w3QSPfOBlHR7!P@%X;sWL@{TD4mqg~WR z^aB~DF(3QJKlGGxZyD=5c;ii#2bZ>IF8sz6w|4#*N?;LE$!C{npj zM6F{;yt_3xzPT>6660tpyB~<#bKN*w$FXd8KT=@jc?e5P;6?1#(n;lcDYQ-yRw&ls zTIao58pkH-=*#1Xe&%D|I!Si0+rZE??S5XQozWzd2QI zy$Lg=`ql05T?_YrVtWT5tiQ=F=dwP0ld)2y!EKR>FApuRo@$Z*@M1f6I|NnX)eCV| zs2e+#AWsvP+Co;oCi$DNu8)&FQEY+1%67cJE!MA@*qasc%s+4fKF0Gz$RFNm!^Cqd1Nd?YsC{ zFD)^+3+0D4ieWxA@k~naO&fKpG7+=8t(RHYYXIbfOs6lLYoktK)4yw@gcz63VABAe zGh?ZE*m7a1Wb7NBGh!fOdi%Cvd8j@bZuz1w;g7d()zX_u@0~2{f|H!Kg99B=zzJhfd#pO zB+?qTJR#|Gt*?mo_xu0!qQRMU3K+l*E@?RDpx4uI*{T~mmLN}!zJhTsjsm>c(5sQV zrh|3<vQR-Ws$T{decN{8q7RQp@Po7CWVbpe>K~JVFeXVZmxPn|8 zV-LHtzrVY(pb!&t@_PFSZa2mj4v%Y0rz|+-tg4Q64m#QxbKw%zgSjGVh``+7pVPtI z;T`BEpx2&=OnA~Hhf#Vlrk7HBvzGT$zF}(?89xu04*%Q?y-SL(1-*wSHw6LgXHy_? z4%DeY0Rhp(AR$@L#9%Saro<2_p*iiB*Nf?N-aPG9oOWlA*MI7vpI@dErd6+>9BB|e zmmFpKfi}jjN_v_$W{qC!frazFs9ucS2lv@nFVaE1cn1OH)I@KxdA-Cpng;Yqp;F;# zDZ^WI>B1DgHbJkBlNe&tk@C}L9Bn@|dd;U7h64+dYp>fNi~6e)ZIl&w!7$gH@E{|v zmdx8wEY6L6vA|g1K&P-LyKM1~3-Xi~d)Bj^e`N5T7yB>uYyq*}6|2Ry28xy~lSb-L zBQy1n92Ol-I=5TQ9=g|M4z-q&2(y{KtD|8vyS2kt&;dDNvgj1VHn#XALY`&OCBd4- zE_m@0jsrCI(BXsrc#XK=3;c1~3cH=$(ZtY)X+Z-KWV{~JOKXdV5U76m)5e5m+P6Gd zz%&pJx`kvdR+KJ_00bcaNn_$5;P>X%e=TD0@)mz$6(-V(-|xPJ~L7W0qG{j>IWRoD{CL|6eQN_z?bCwYH)^}Zq{7tn974*Ba*uXrNs`)hcIGyuD2l9 zNSL*e}jB$pZRjA?&o44>6k7!T6vK+SSvm4nNQAcLk z9djY_RlbZ&X#$%-yeS2ngom=grr@PbUQUFuM!%elxI6lCD&_&1&DR9A?7g|j1QTl| zEM23#1#wn(E`OjP@f3RZxW#Z$1V?!c4B96P9)5(7rb-$&woO$2=1WE8GR;-Iz8~=?S zj>nnER*e3Bf>-aQw=OV3VgiBC;vjlx1XfQPB!+`J0GiNT7y#M15@e8+Sv*gz81&(U z2a-uHBL>TYA7_ANXK&9N!jkat7lo^4l{29Ygh5PZamV{gjO}OTj}GyC5weE2QPFw% zbD)ykGDt8Y{@hS=;ZIr+xbow z%{v9*jW;`m(X)V84re8M-2>jXf?64L$rp8x*rHx^DO)n~*#k+rPTc^J7} zYbZXvJz((hsAJHgMU}JGs>66^)OzD2%j%263A6R6NrJKUu;WZt=@)NWvW*rOw%1%k zfkeJsUqe-V_ol5P=wWNGL@ z@p3h?-}8(o;+WgL^|XG6>ve4Qb{l+OK5l;OQ1IJK#{S5-@wt~bhi`Ml`Q&J=7@Otg z>~uoM!TwCj%AJGx66}+M^*-{_>5VVOhH^SH&+ZzHjm=|4SCgF^-69sr_Qi!Xr`5xGuj@97Kkht-72yY+QTZ`FCe) z?vn=iCrc#u3hwgOIJO7Jcz-?8LTynR%nvCwN@8IYZc)|A4h=e}LoA}8WbScxE_Rq? zl_Drp**7y;2mmc|A-AgW1cvq%>agUMNgBV$^hm>?WoUTWY=(5xd&jg6qzHFklKrM; zkGB}XBUE-I&})N_>Es_Rx>vQL5~VH2J7>`7d>J20Gmt zBM1v@YTUgBUcnLCM+{0QH8qZcjs(nd;Iw5u*24G~sxnF$oJ-|>@1sBG*zhxQ9h5z= zAuZ1Jh#I{sPh0u9#_+{jYdqJ|%Z^;!?fk>m%=Kf>PwfUh1-NZ`dQfy}R7!IY>l<2q zg@b`!-(pKxzJZ7?@KdPnQqCGRm=Obcj-C%{$;l92?dzJ|low|2_f zeU{CILwj?Pw##+uvXu*3MwV>)%101a6!sMQo{r~cJ77M0(bv*fRZdjlJYw)@#{1De z>7(~sZ7Z(|n$-?CimLXHa_kdG)xnnup48r7%|x^Ne1uh61J=3m`YO}-vAkGnPFt=X zXR9)%RoF))mq?E_j)|Hr|5{JpwPCqPg-a>Bbu7L&M-(NV5_b@rCK`qLHUv%H*|Khc zV3`^8T%V%4yw@lql^@{#^dmY}Y*R?wY(UM&&-5yL&5G^$AtjGPQ9n#KIHP^j$eeYy zt$<0H7x;HG^50H`%R0$_;ogz`6g>V7R!Vv8iA2V^MyBt~Tz`%`_&E{&j&1q>(;M&) zkdS{2<@x;$s5H(jM8ge|e0Z}dF#wGUPTToGfObdFx3sA)fY3k9=lIFfEc&d9H=11-h1?A-Jm1^4pgcvUpR3 zH|DSM08yV+4)Exsdbc&Y%bmZQOl{thxeTt3*5tr5ITzZk5b3lcL;%i8l1)fAc%|sN z9!dU!Q_xBM>ocawmFMT^H|Ai%ZLW8*vd#@Y*b?nmN`EmtFBml>9AJ@sIU9kzc7M4# z-R-Vm56nWgR|gV8W1^8`cnXbjT;83m=`4YeJOY`&wB3kyL?la9cfweAh;>F6=pS>& z7gE%4ve?8W)ymkTm3D`v(TsUe*Vn4PqO0fp;zgf5L*>m-j56sxH?FI~%Q>w$;mfCt z5X_A2MWp2-5Fk9|k4ZQ;3d8J@aW|$gL(%q=lP8hkU8eH=%;`j>H$guUExQ5K_~8sr81gh??E%jxNY<&Mnb!`NsTCgVMB@g(~^ zf)-C32A0du#fB}TPzO9`(5DWJGDDkBeX>5L6hg9Vu>(Qy?F0wI9JU=tnURl^AcAgD-nGiwrs zG&Z!#NaGfW&+0QQPO9vUV8@ooXDTVlO*^}v>9Z=mMz6m-o2t#y5c_}tFkvwYsP2a^1%v39f=&SWFPNSZjy@4YnJ*N< zqLhxZ>3gFdg}8O~Dwy<5jT<5S3PczQCHH1Msb;4J1sG4!qzr>k-M1P8sjG&ITt&#* z;GU#0t^!{oPy_$g3L?(U1CM>S;ci< zn#D)(iAqWY&`3Zca9yldC~$|EWez^Rrrs)~G66eWv*=((MPPl804eN}TX8e@y6RwB zfZgPRf5;Xik&9e{lsrWw+X*f$#c_RYA&3?bO9C4Fgv&xVu0m4N6(Yy(+-j_^HmNa8 zY6F8qX{8jmg^XKmtCP7xL14C6cx(y|rd>K^wg47A`S@8<%?y;>M-GO5KGfN*bo8BqK*q1fw5&CJw=?JDM>W~c$FC@ zN`ZQOi3;3*6Q=~Xo(y%&MV@II_b$&Wj8sXK-mWj`77h-JeFY*(4=qfVx*CRyE1xF^ z0&x)Qi3A<^&Vq8?+Mo{D0SDCBbhKq)fWwWV2#;{1+L_x01eeMblD1n2OYV0M?2rX&!eW2lwLFh9l~?@YAdcH4opjp^(5t?6Jbef@r*w zxePjB_a}KV3P!Px@L?Vl=0LR0vr6m-bE`s6Ao_W=;UNP~2>Wb!NL1^wIB{qsz#@DW zC5{H^Y$nO*$Gzc&aU06#Q-N26Oh~0pI5*&&wwmO6r_%`&*OU_TRy7*}iV@~?Q)o4g z^u6$Abu~sGVq3D{7!gTC7Ogi45SX<)>~<1?s0TtlsMY>XM9+RH`+f@U+702zjg_*qNe zx=}+dfXwKhJp6$$LBye_XW*uk$e2&bShYNYfCS?m>gRDEIv3o)meNT&~|gn z+Or%n4I8h6I7|m+Un7U4UjF!jxG(p?Nw9$>#z6AE#QNPYUztG=Q+*Kir=Xd+;M<*V z+Bj1bD${Qvc)`oG5%zq2k17#D;kzl!O;1w1on=ljhW3FFr^^eJ`;nZcOqfS44kV9J zeHD!Y{%)K>r?-)SI7ctLvR8WQ?}x?t$vJ(Nz!}E?GZs ze)wES-s3R?3u+?;Q_8Fm`ZlqTu0+Da&FuB3_VNx3io^P=>Suw2y5D zD1zv3;OtWhi(+V9LMs)%Ovdd%&s1;{Mf7PZZ(8~T2A@YTpW>307CQK0(G8%sDqz%R zgm23Vc#_KJmv5bhle*gNjriOZ)a%a)cV&Z2%X*46z~M_eA2x$~TrxD*6Go>bgeF_s zkRXYtZ5gr=36h+#a&LyC@JM_xjG-Gr0Kp!c3-+qca=-gfvuzNQy`1UON@&#~dU?^k z$9SMV3sDVpSqcY_ZD|L*S|W#iS7{mYQMgG83ZxFz{yQj*U~EAzIE2i2B<3r1X!X_L zu;psQjqPDQVVnt)Y!C>yBG{W@8z)NC5#P9RrXkTtu4MRAC~B-4<6s`5nO^6>r4&tY z|G1Z>#4shqxrL^&)0d;VD{kzB*LsADCYb(l7eQ9)0tlb?Hna7+<|AGoC@776?>ZdZ z@*~}ku2>+ONFN#%j!*fa+3NJB;`%gsmrMHh;!r_xDr7a8DYf_92_V%;K9{4Ags_} z_GujZpS}jcs%a9_=BbUu*Ad1c$i#65_<{D2yogbcil8nrJ3Z>bR zydf0SwmG;He4T1j_RWXN?zL(uzR^!dnKT>%x89;<(*vCX(1RRI?3S zB^>bW*w34mBiBqbJMeOYo#X`+i4QO)_BTpt+FM~g@q#e6!Yg^|B`VqU7m~NG-SyB8 zr@|XlKswkC#XA;$g(Y_dDb<{Nn&6TQ-Q}-zg#nBo8f>Sb_t*p(@3?642RpQ-;1Cx% zqUqrnI6EMIazu!;D{+^hOeKVe+;O$KB_d5sH~aAVEF*%V^8%4WQ~fL9^;gBg6nv#G z2veQSX~kX$<1XI1+#29QD8nqQh->tm|Fb!NyNmN>CrS7)A_YBX=Pi8BJaxiG^^dxY zmr}3KQ<`ee(vA6R-ii})+{TEd|9s3wvrx-KmmS<(pJlE=(gS;w@&l ztpWxc?)DyZxW@iZtY>jVPWr{IQ(Zn#OXT^xo`iZJ-gXafyrfWMl0+rTD&WXS<+TO% zn$hqgAogN#@{0CwWS_l6-H-Evi&&w^vpDQhSd!ReiTA5g_xHOLBu)%D8lLx|Z%V?h z>T6>+mA)~Jd(+nV<~f{CJF!oPqEC;tPdAs3?S14z2XgHRpOJnaDFO81S)WNo-w6-$ z*_!{pHsD5b6Cf)BLeK{js_Idr|PX@Vp!7DEi=CdjkXLUIx&UxH9OY zvorMI%NK`3E{AG|p6WR-h zz#B?|57Po4y$qD24_1B~{8&HuiD)plXrO#q@Y8`{bO`&Q0wBw?=MGOqHA{LKp87UCy(~O)AUu07JeMRQpF5&ZDWdpg zMCsdza_&n7r4jGcE@Ich)Uep*#^u!5w^psNc^vmekx6$)u(TfAo%X`tQBr)sUF`G&;+b?5w-^T2h z#T*XA9Pa^v%CTUcSOn!*B%4^2@L06+Sd76~to>LV(l|VxIDF+eLYp|^@Ho=)xGRHk zWczUxr14Zd@zl!kG&b>c;qeUR@l1p9Ec>THF6m83x0Dk&l;bT$@uHg?IR_K&>?c4- z69sq@1(g$pY!XGn6UE9CB?c3v_7kN^lVo|42N^u}RhoPc|q|HX2Me*-thlO)=w1u?Q#PR!-S3ORz3au~QBQa$6ioQ=NEHjq#i* ztVujrJ&)!eZCC$j^$tWC*LFL5RGS48y#Yd{iKpf9NfXjrZ%mhO-b)VzZhi5jH zXI3_6Rt;triBYu^`}d^3seCEYN18R5o^<4&HME~KW^*}{G}{6|7XB1J76O-eJ#gXQ z&y^f6uvagVKJ$~rgW!mZZN4jnd-NZ~W;vdqln;ppeQkwHAPm=NN=yB&5H@JAf1LS! zu4IK&Sx3p#6niF`mPZ{b3>eK9WGn%u_=ulI!CrmzBkzH`8JS&3?iuM5OGU@w?uW~% z`O1sAWB|P0bD2MkU?w`q@D`_0kti@Ujei>dB+cf66w!&~*}c}RGo-P?38vILuD0=d zz&)@`%5Co3{y@lHs**=w6zr^7^8V_Ch5wglJSW(sqvZg5H7kUupQZBPn-uXN=G8i6 zZt&o9;Mnmo{E-68;dqTR))5g*hvNuecyII-wgB-ME7Fnzr7Jv{*0`e`)cOmEoP+DJ z$DWU#+7ntlK}}2g5D!fkis*i-SL`hE=mNq7LD!(XSUm}lyI43=Fl0njTz@3Ww5R^q zBuc@7w|}22z3sAj@*iB{|B@B)`xL+aF-uD29ulzw8B{$ONiYci0z(H>9VxX}SYW-e5NGtjee71s6G>=NT#Qu{Vnx~GuE z=AcMa8QTl5Rk_utYQFTMU)>Lg1l0?T;utV;Hr^UCZD8IRw&*k7iA=l_R06dnO7G!> z+GFFFLY%RscgJmL+e;>1e;HBmA{V%G&5oJZWbbR3?j19$aI59LnOJw0{n>AA?38RE zoU~+lf8o0U{IrdoeX#s)XZc{I8kzNQwU+4F;aVeY&f$71=gQ$mr!ec$W{<)%V6LQ_ zbF@8dwQ{sGFOPM+TPUk{44OfwE)c$za<_ADHG$RsaI@o?{h4d=_;6*#{seRwbE0<< z2-pRJfOx_Af4_abi2+we*bP)+_o`n!55G;J@P;XGpg)Kry!Vseb$#{$MQGA*t_;Qo z)blBnQrN@q1V+V(AL!)2@4@XQ4Fj1658q{SUz-UzdE>Tx2F5-E0*234eL_&X9Ha`f zH0p;po~dVsajf)O*kj{J9jdPl)H^b&Jt_VSok5Bt3X+2DLl(e!*q!a~{&!>H-cvC4 z?>)F*lI3g{n>;2DZ;6@`X6s!)0z*=Oo|uvH}$|;{0LX@57#2$ zaNG~r>Y376CR_ARC!(TQ0J`|E98-#c42|Dupnr4-{pbh3*nO6x7W3+)7~^m~dhDYI z_V)K2l)(dSQ#0*mL}uN332AfPcKF*v*RGU(*WaA8b1#6B0ISq4%jJzM0AdBIFCO zL}H5;9PA-KiOFXp1Qj>DdJ{WcLzPWkg`E@EUZ0WXp6mRydjf zp9*>nOD-Nliv^qTLQdKpzsU7JJ-+0OXUPAsWO`pjK^}1YHbj5>C`iWU-yb3T^GoLc zy!v2`8$V+FZnI@86Fudt-KfC0bIw+URC7*_3cs7SF1W%}zlgei=Z7Vhrm-yeSFmhKDl4df=svUvw$5 zM!o39B|YkW26h~Yg=&Vrf(>ZJWLXXx5xEo(9c?XcomL;5MP}$hR$9nQHcP+|{qknX zm?IH;>9|$*R`D~#k0TtDe%OVjQ$F{WcfW?vX75c${$72UERUxDyVVDI_tYTz#cDzt z7}R8e0(UqJFC-|!`i}wt4Sz#wfeg~LSFbW4GfwtStP8Fadz`D? zUP_$E71F{ucZxfyUtEZ=YJ;G(gh5pIX?(T1sv&CY_4|kK6|%pfSTj5HL<{2wKM%= zJN^~!@Y`iTtt8$P*@p?%1RtAe*2I+1pYO$bsW88VGJ%7wm3=a^p!H^8BwNSbgLmeF zOFc%LpNyM;%YX#u(q^}`F!ODld;5A@J_<8oTfQng9$S6N526O&A8n!MR_dLoSXLXR zyeb~N8IW4oe|i}hkqpF47%8~)xRYHUBsgQ%{EfuZ~!=qz`T=p`^^vP z{N(SB{J)fj#Yoc%WG_yhrf0lAIv^jv)N>bB1v!BS(Tzbt6W_Pde`xRfCkmmjA&>vl z!T8U&n%7OlU`RM&4?Q$S6Bvx6lyf?yr3Rc)Lr<0Q^;*9bLZ{Twe^aZ;((+Ikxsnm~ zjH*?Mw-dQt8A%_pk?MUn&lf^GkOa72V_zs4D(QEk4lA#xI7Nk@0t(+QN z!sj?eP<=nYpYBUtL_z$z@MizNSAqYh3s3B`8H@}+4H`%&mnIURBbJuzOLH-XQWiLM zQo(`$#Hj<+(olQErJIMYt6!jjWPdz$eq;ljUcZ838y(-XlU>cl*AfhX4<-D5>U{6y zotlcbwPl@kTYi`0uv^vkcz@%M5xrn2{j-<1rycr5l=o>y){kreVovNJ%x^#b4s~Wl z$umE`*F>%itD}(74?rg`nto&gD3#3i1E;%lq7q^X=uGEp>-1k>WW*O~vxNO&(>chsYx;0IL{0XmWoY z4d1ltoK?&;ScP`ZD$Y|CAeDPAfbrmm{o#TjHFLe0sRZcc-DqIiXl3s++GyjN0Xlhn zJ7={tzd=1$v=;jt;g&FVAMv4ni%$Z=%v;?ovXT~`MRcaqPC6Ukzd2c2(eA9$32JyODEhWon*0P+oYlk_d(ZwZt>KSn>R+qemX+=h+j{7gBI|(M9xkGhF@?%WlkpiU z%kfdbjRTPz8*-GmYakF7v$#;BHIUYzbsIaeU`K1lXWMHOzO8&qcW{J97Xw4)<@jn$ijR1VNyww-_YD3q+9^12H32<<@ggRbFLBZ% z12cJM&+6U54wF^&>C3!+h9iNt$FG3K{s8nX3X53gCGU|gu&oANV&u>`=*C_A@6QrE zP1zG3ce~=$E9Fjcrt=ol?qEfV3ZwEuOzWreMkph`_6EL5QO1Ct%w^ICytm`$2f-6#^U|teSt`aHVE}Y|2FX?)GKXk0-s}tLF&ts>0O|BxkN7cP2BX z%YJ7%Z@%PO@;swYzHlW*t5s|b!_V5_Cm*l2@nrzp3hibwS!ZUsL}B{i)vV1fMVkho zCid2|=#f(}-a0j2Z1q02S~6CD@^f3IWNi-`Jw!40;i-?B9A<7-#g1&p?dh0*w0We{E}#PM8K< z5Rjg}v5tdPemF=CMCP*2>SXutb+U$xGAtWm4M35A;dmW#YsusQ3&pYlQ}#Ey{tpM~ zUeR+{G17AtSP6n7FRT>o&+AY&Ym#A7vY`1LvZh!h2CIZ0XN0|nUtL&%o{-|3LgBxN z=g3PC2Hk+7WB24ju(5I0YLR7(V0CB;cBa21j-~@^)BK-Vo5QoKM1P6@`ZIFU1#AcX z5Rggv?GAUbn)(+?X|jc9rwNEL#iWO<005A7M_os;Y~6t(;+{9sTXmqCdXmDP==xAB zDj`}1$fS(WoODTo>ltl}U~wD8UVtO_?Yj05=TZs6BZ1R6^oP)UF;5hQK3;XXZHxi= zUQL~s(g*D#=gsWycl_1ShXA65(I=~_>i>3a{=MHWE#djaX7=2_&d{e9*j7CgH#djK zT@W|_9ITXQG=6~;FvuBZ-W&BY^xIrIyTjQAWPcbuT+C#d5tN&btk--{zu5^IAx_k6|?klzgxc;G297A92X> zpV#0iFs*(|ez;<9wa|d%RRas>iKDc^b!EVUHUDg6b^Dg>GCr&)whL?D`tlPa|Qw3U~!rBHj*PMpe=^z=3$ zeH&j&b~P26E$}QW2oID8%=Krea6AZ7866W6)32u@KCNgyy$vj}p`Aq)oAi@BHEu7U z+;0P-*`5uYyauj~^p-a!RXkN0@I*ZbakKj$C#{_^ba^X$FW+G~Z-JS~ROrlcVPc6^_Ugip<7)yE4q zf|`iC3_xv^@a=pi1UmY|W$06oJnl<6QJ}GaC*Z=NV+NL52Bqsqygp%f=P*x#DkR8hTfu%d@);UkrRvMvw-J4RsfE+ zq)%y+#GzZ-y@Ka69n8SG!TBnIQG5I>$1h+cR6$T`iQ|PNW*4cV{<CTLYkMBS0SURZs z3`>5q+JzaoCxwdI{=PYb%y|Xa2^~0qJ;V|vvOw`ApUJgP0p-D6IG?mvIm&f5o4*%e zk;Omug5Vz*Ykgn!tvssc65sMkGn($===hU?AM^2a;tz77^MB#iK3YlneKW8YQZQ&L z;K;T$KZp^uR(o`76Ub!%VbCK0n;+k#0__j-dX827r=?8z3_RgnZI;hi-n`&)_45pD zZpZ#<24+}quRE=^4&p!OX8{tPa$4^c;%>?965}`g&?PVb@!38jqmki_!ba-Rz`)Vc*|8eH>)nVUknvlYjfd6kt(c)tAow(f73^m`uODRVE?8ml9G3jS~M5E`z(37Pd+*En9+=iTQj z8G_w}_WQh+Xi1Me$i9+bkqM3s60LP}i{8c_a=1%*=w!N1ZFhn#lz5&zZx)1%5v$1K zlNHeYX$>-99>a+}6@6qgCH3v++=ujc0g6kXBv>al7UTDxFbmcsK1PFw;1*`R19&#& zztp`7pA>?wsaV7=6KJ=P;IU6Q_+6epz+J^Q#jkh1R?EvIo;FVR={{h47<_97O#|## z58j;PS?RIDb*Su+xx(I$be;1 z2#}wzUaWO~Nw<2Z^3Mr}M;(*D(p|HPM@#XCsU_2|{jmFq?lpEjaBz%qAk#UVb8p;~ zrEW+rAhEf;**4af_OWAP(eKU2^-e|te4_lX4tC)*DBj?#;*xv>9TQWce}9KwBx_mv z)j@>wAo$At^M2RFPB+rRF_YVQ zPW2s7MvTQRb_Ew=F?g_6=*|7AV-HM|^Ts}!Cfk5D6c(>Paf2CP9#H<38&L;y!V~|A zlu3e{uxFYFR;0amBR4XVGV8*Jx6*&zg7uP1*oyYAEwXbfB{IIS~zy*ja$VR zJnp{Xn-ex~M=%6gbRv>-fIASGML)a(QeBb2l``JT=|(bKY3op1+p$0p7i5;`Lrr+L zRVcBE0w&T@{6ax!meFdGEXCZsn z^OlngoZvMC5U1UG7pw6rP`A46Gf=;IImg<73tT2W;$>{JHO++obalR9X@6(AF4Er= zO0j$`NM0>{fR=w&OQ&Q1? zh_`~xtyq49W5&%m05L!*LhR4qCT_}`#@~=7VMT8)w1g4}qjw!CABcTU9z)Hzw1G#c zS@$&7gYYy}?1Aey^HmibSQhrwZst#v7nr+V%W`j^ktr0zgS^C$i*2?MEkoN!`^-Sc!J0E+gk7t z5j}*czwq@mn_fxM&qYJ8`fcl1Fg=mY(8_CknDk?& z^DFh=ujQ!!dmXL*LL;lLD|JR@+~aVUfZT)?3xC4vb1RSpQQ^jFpYW0Ryi0IdNc2uo zA1CX;*o43QzBwL^s@zN*{#{drct6$?c9S8JEblcD1O-;S0wrDxYJ{QzvT8)FX>V!c zS`5s@1=vqM!iz@309QwHQErb%y+qHg3HMn=od&pf%p@Wq0z;C#{0Jo$6}-? zMiV)dYhlT=p7({oNJJ3ogQqa}jT?hxOUQUEG)%WmRNjmP?ufJjYgt$jrMJNNtfIWAbVOa_d?*k zcXKfzBb6b^6;vn+3?-;jk4&nr-oaRL2_>Ugss0#t{MCSFW&m$^vq5x(T~|R&*!VfX zYuFNNEwoe3*{zIgPtEkU3GlCjxUpq&f&3>$)YclRAU#mj_gO zt0d8@dJ#V#q;AUq?bnEX_F=%FU;+AN73kfgskDuuryIgYOedky=BO)G`sSDi>*7ZN z!5^sqegK}_q!cZYKMqcQ`oALn%Kx=#tlIF+|0S(e@`L|N=kWhhT#bY~!KbLbE6)8< zg38f;#3yj_Ka1^qdcIa?{qDz6V1Vi58|tH7owH#tkx$GV zx&Chjf)TGIP56HPzmj}>5mj|Rx7rcmNbrC_&(E>Ue+*9M%WM6U`w_fW#t zS6k78PUh>ITMVG}^F!QO+e0tHL+Kak-s`X#$@q#V*T0f}eV0{){$UuDf|5m$n=E@t z&bxfx={!3r{Q@17`tHaf9b>QE`XWC0y&l0IH?Jn&B66+!x^FS8r_hnqV`+6{tSc-m>b zJ-OlRF@Ev8k`v0)6AD4eYP~HWox+t$4tsI_981Elmz@5hPX4vlKPb6OLu-PY?4PBk zf2GrZ_5UF?g@}}s$V`9_?JqTK_zCde`^w1ae$s9jN@I1s4>(*r)KXHx0v~nyXz>b2 zZ?=L#mW@dopHKATF4m{#N$jUjl-uopwfzhD-6#5&+rP(g-p3*5UpT7&(N5xbAJs2( z65k%x!PBhzvwzi}Kh5I4?4P{vJ|ZG{XDtp_svhdFJ6a^`g>NpY%0E{*Wr>-xoKmj> zZBIULXPNSa9r&_Rg<(j5Pk;6+RW^A!iJGkiXS()z?q+^dajtB+vuo zCpgj(Ap}kUr1?JIlL5*DH#Gh49W7`pKX&>_Mmi*x!%dF>=Zles7W_ffLijF*^EkbE zoCZ33!5kFm?-$A2jX~S_H=LI_UKOr-L5YY=Y~Aj}96)Py=-ApeJSD163@K zR#_GCCjt8LMDQHA<5KSf0Oao%u*&^+U#ryrniufzS^5j<`lDr+e^#FP3oqayZFO|5 z{!XC}@Fymol6k>T?(1@JdFCPMnid0iDlGqX2Yhga|K$2}o!6hg)rVZ@A(MZYmiqS? z{qSZ@(uk@7<@@If;0KG{m;`MlBG3~h|LzCJ1n%1&e{L+ zUg1ZDHY*bkNbo74f}9(e1CoN^$DPOpsUx9PGcHSL=g56<%KrLYBgBf zkKb+ml%fG{&txRmkl=KLD=p15=kxS#9Y3=EHLtjUt86piz?d645GNx=4ON(cy>3E? z+w3?~02Zk|N2&uXBsrNKD+B<~@MQxiN*E?RqID<@ zvz&scbOt#ke8P~lD!EXk{8GIV^@JhCP{*WHw{x-aEDE%sf~B%k={fz$Ddc&TW%^Aq z&~4N?&Ly9$7x<7qE+M+Kz7Aur0HHUj3{zODr&3Q{+ZE4A!^q^tC6XUhFNXGYc-G?@ z_@vjd?Zf3C<+<1F@TGK+rkYQ_F#xyN3@NX*vTcN2Yb<_EyxNY3h)F?&*sgos%YY_z zxkG~gJZaddGu`2a?71FOkP03?6sUem1`5zlcm{@x?lGYQ_i_RPa@>0i@md|;-P;g- z(n-vaG;Fc9w=r0Yo4zsf>>T5x5j(<&!YttD&8%Y&lj+a?E~NjvIQwt^UH&@Ca5TCS z-3<_b0jGg!_?#wv6w{N&Ic4)^COxF~VzpkHwFYa+SVEJgJS_*t6MStEW+CC_7>d;4 z4(NIbz{iYwW3eVs-6RMz%C>myb3V5uSAVhr?HDhcfl*OR!(`e72QIb>(TI?akWo&! znDK<%-G=R$c!0s{)YA|;Eq>49_}fl?}dqEJa{aw~%5 zJOR3Q(t=YraPDnA;rG>dCv=O}VAgi9FsfdmD4O4DXd;QUo$~Sltqe%DF z+GJf3taW0^X}75%WCK#T04WK@F-{-7keE2c%OkoFcTa0IIv7RNEFc9g5=tVmbZzuw z$kf{O;)u#-vqKVGF6K=mwhRH{BI1OeiLH=xo#QO^$!Y*VfN#-haw(OfA%X@g*lD;1 z?0~dxMY_>!rM^zM)`(&yIbe+K=0aLVzF8+hIS*ZX$^utCO(|mTniqaB7QRjyHlHSW z`Y@J=i6i3M4!0^~no?%R{JyHiY7A`BE4B8>UzvLRwU*^iJI)^s;Q#SR&&t2I`1}$dRDu1^UQvHe+5D&q{^Mbo-+e`W-MIb&4D$~K zSwCL|NnxR=U5yFntode>5}v9%ar&`$$l+&;<DZsP7_(s#;!Dl#IVhGgDyj5RC|h@W848_&m>|Gjg2BN47F-xC)D^(%bVK-J zW{2fx`N=U#>8Jc&4xH5gyqEc}m7n~7)zDuD;o^Ub^99*I;x30zJ8OO4!Tc?G`OlWT z9K#L&(oy}7wiLgcd;Eo#;x`joKN>9m_c7Uero=;vw3KjpE0bZY;$k_`$;Xe~%%<-|yOg&2IniKB|9aIQylG@lW5iAGP^^4`=_J%Kxk3 z?31&U^3P)AaH{R6oTY^RVBh>>w9$U9E?6Iwfn?|)TAw#jo}<&U+SPdAXKgax`2TC3 zvGMO6sgFd4AARZ?*PD(@=H+N4eUTp=nrEmw2S*1Wdeck>e_r@`93G5VF*6xv(W5&R zj+S-<9Kn9RdJ15RGD{WVNU+@==}h?t82Kc1A}I7@rq<#u>V#NpMcTv!Yj|k+r7a}n zk61T8+^DD&LFzBm0*RnhOu7Ar(2@5*W7x;ca+ZbBA9xS=!?5^n+{{z$N=8rECthwE z>Pc5Aa(nhq##}Z3i(SSV{@-c=;&K<$Z^B#T$Vrxg;g+4hjMm}$1f$}M%ZGLsNm@_T z(vPt2J9+*fD*`_%&=ah#1fZ>FoOZbMXBg(#G#~XBPWSfz=!p2cnT%g}N>AK?1m35koR9=Hlb09c^wxucoPPDdxi2LY4g^I^$ksVM_yI`P?B)F50$ ziY)!q!pVUL$+!k%Ntq=1WMKRC?l24tWjXdm%((R6-?5PKR$7H?^LN7JS9yMhm962RMURZErnX_JdkRCF@3 z8-21Fh;Ue+Mn@~~YR1YDNC(O0UbOOv4w3`W#RFfv&5tn2ho`RAD8Krn9IHd0U;!$4 z;Lc$P<%h2WcRuv09(Z^^C=r3@SbYrK`NoDSWzvfac?#*C+;Of36~19!{qyUI@Fy^A zQ~z6Y#akU0;pU2l=%p@4kq$q40=4$6z$u^%AVT1C)%A@H&gy_!~A1d^8b*3 z)Yo#QFEsHdtJWlq=jxbUU;NqL`%`h;vJ1F-6f4Q7*PyA94^GmOx|}u>FMi-x3eYXn zoe~8YWc7rjh6F2wpaCv9aXehrofd*o;7muku(;ty2~vO^BMjNxLO4!7&;!RKn+kyw z5bbHfiHKm@;H2{ph;?ysMcil-RJ~!e`ti9&iuwr!HX-_nC7uKNNdW|1wKD#=GV{PX zbiers6o$EZP#X)}K)Zu2m!7AMi#7>jJrFY!+#{tVkvs0DpITHOlagB89H3;FSv)|? zl)hFgyz~k>*`)t!XY6f8S=s8j%yPuHDR`Lxrt2wbXt}hyDN0dJwA!ai1Q&~z)aDm! ziLJtnYA>3TWY^6(C}-DG`3|Pn^;$v}k_Xctin+T!gP4VHC5~8coW}k9QL&96Pv@j zSOaj)s6f_MRv{4zed}pRg37-CFoH$2Xb7h@0xHeZmYrxlqEBfCF`jK*cD?}_ zEj9?^CRxPMMA7Ac52LKFBy$jxzI zsE!Mv18gfoaS2-xM--LkR4lFB3N8&!#-lhjcNq$@YYh#eV@x7F?ibb#2!*6PajjxR z;%Mlke310ARbiR@^pP?`GU=-U`OR@lVnxDNk~Cd(UQ8%DDA4BM;JMXZpB%Dz(X2^n z9@Ofgg&El(qA4aFQcx)(5Y`T3J2eH^+VguJ?Z;))#s+3RsM=Mx24bEcS#=CW=5d@!}1=?XD^bXU2!uaCbCiI70}M`EK~gGib>rZ09FiK1{h^lPpt} z+@0m{AyrE>MYeleHs9@Gnu(#l@-S^L!{ajynp3&#`WqxM3?&V%xY0G?qg8X+hhEAbx-x3EFW`|Em7jV0s0LPqZd&y{# z@OJRMBBA0FS>ZPN*ugosx+Ep*Gliu}M4WMT^fwHtjSC#Xid@iF!A{1SRCL3OJ_T%H z;g_E*H4U3z4Jh9|4^kd2IAA>pkP2EcvH4h&bnYuIA-}ZDrCkjzi=X$JmiL+R43}MSO zAN%$juxBoWN_0j@X}cq+H8-BMWk&4Dc4rh;ULwEftW@ZBSE5*6vV6;|T*-EKre|KN zw&o+r1T7`I#;+NpIrq^wo>yX9u>-Yq9V2w|nO2CWtQRDeVmO zwdUt@T+c!<-l0CO0wjdL*m($Mf1#D7_}&g#@H;!?9}cZ<|FJ{szpj;?-$NL4txn?| zdqMp(aWpeM9EknoV*qucgFSEOT(~C;8C2XK@c|7u0MUf#zz+FE2q(tOg#Qcn7w{Jw z8dXI3T-kaihyg(`OH)C#cxy6(wSQF{!BVSXDvIBG^%RcXKu0Sujag_qmScwf7CjklV5xP!N>QHr3awIxTBPk-SXWJVRPI(EGn!gxG zqi$^!QVl3dE^Y|Vcr%b<1rvy#%S42HXp3o*+mQ^dGU7VuXFJhp(x`P83P}WMYdE2O z3R3>DK1~VP1bH+KOliB>FOWW1Ci#Xf&Q4R7D(yKK(YbXL@rJ%}Mjj~Ni>WmUrp(jz zV!(stIN_JOzFn?8Bk5uETFsRHDv$O|s43k`T7}hm`fHBN#bhDftIeo2PcJJXWC*Xd zqD0TFB?8t;4H|Bx#AUP#l#>{i2;?;5wSrhV%(|q+@4+|YLRn^ePMW@x?Nx=Fsmed_ z<;btprcz)T(9*8X1>Ps*dDvso`>e0Z?4l#9p!G)DyPV<2Fos7Xj%yr+qfXe@H+bFO zeu`w>nlN2RyE)>jZL>8RN)ycQYdnl{7yeNU;C*^j z-z7nK#0fUO2=k@U6E1k??t4g>s@I-8&w0Dl%7nihibJ)|YL^3Sv*wlZoVL2o*BLE8 z~qa3veY@LOi^ z@F@Af3*p693&V)UF#hu^a<$Xw`m#37cdlxzER2?T83)@u*r|U%m%$miTRBuLc%^~> z_MXp&0WlLn5|@%;LmWY>kIV@{8bc=99zPF35`;=Tp@0y&ToX*^L_^xH2UvCCG21wg zG(b=e09OFYbInyK5H;fatlrsAse1vn2q6!-&8Q~4dB}nzpX^^j>N}4{+0_I@Mb~<- zrgb~0+5@qjMS{Tfv~&2wv3t6dzB&QHT9$hG4U?f7l}Yaap%_sQY%znc0@w>LO}zJE zAjow>sKZ=8g@aa4UBmg%2ely#979NB>mw&L6KAi+rW+q-G^-niOmj0_1rkIk#Rz~YHsWql@(^fMWWyB}g+r!&Fxy_~mZ zX-H9y;m=>O#a8$X#vlc4uf{Qfb}S2+&9T`DO{-$r3`}dzazD+gB@!;psyjbb2U3S= z)T(kdu~8UjN21ZSd(7|pIwE1ThB@L7=&8{aPeJJ!+cr^q$L#WjYN~5%hebzhT@*mR02& z+jz&m1Zy#=L}yCP8?k3SA3u7U4yjOUpN9byjwr$);ZligvpI~WerI#cMf<|!`^YC^ zh3{jeNw!C#yjo3W<5O&`N8_{^X)+(F2$A`(+Ec31!3-`T57Of;k>$d&SPR>GhPD{N&dXIq~LB-q~)4voCCHX8{4gU1UvWn7>* zL3GZSPH=+v5mvC7c}&(W(wOl$@AX#^KuN0r$g5ONn@jd+_M}`Ck8se5s~vXSqfn>{ zL8-g3XY#3?=!`lkc6r~kl;4cvuvzg^scvzU?SIK3BzN_!88S1C#se%#YA{znnD%;D zG>(J*CU5!nT#7vl7n#D@5I3lzNF#BznI0ChF=P+nHi&ff0TTGoLN zX&x5jvBV21v(GU9NI`pOMeD8ka>!?q(TF=*(WXx%2ansLji!VMwz~^3&Qpx zTVpzbQ;jHa-XrYRHTW`M{>0_N;_IW`oRU<)7;B(@Z^p?=`tA?--7p@5* zB-KOuKrU??Dtb?#)K}~|q|dKkur=Jvt>KXF%i+a0G;tVF{m=)+BT5yxQUics;@1Eq zFsa5I4fZtLIgF4-#3@|+xzG_1CAIqPDV%TcBAg+>2e5z09TU3mgJIGH@Wue%e`yNh zMFFICnTIp&4@%+rm_4h%halZG?uC!rx7Nl{0AQAo?3YxKqXAG{0nj0Kueoz739L+V z!u(F#@n~f~)OOn6p0-k!#E60<_O41|ZSbV~kM z=Xw(o7q#Jv@py~5v=%7+)@kL5pc!yhtp!*j(T#@fFss1;Ah)EGFT)NkI zXqk2NJ|?dYgECNF6Rgw9UF!2GpO2Ph2N)`){}x(ip#TCJE`5Hgx5fN0{OWdg>m)qX zP5iDUJZ3Z@<;l}liPR1IVPt36Mdq^Gn`>ileC3VryxRG&^tLLJsr=5)&PvwYaOyKH z7)%BEY=E8mX#pHNM9RBS4kw8d??1<2>>9Sgmph0VmAi2XG@p9~K%}~*M!=h|p)>Zv zW<~~uXFzo2zA0j#Oc(+rRU1!X?wO0aHT$GMq}T2JK5|bsbX^T^fe2O#@EuAbh_5J1 z7rC1Z0tyK?85TaTBg#87(z`Hvnn`aVpDm4G3EUTxA=>#waiMyZ4H{u9zJ}_Du$O}F_{j|c4%X%a6?%^h+AM#5Qi=noehTr(N92v!KTrA zE`0+Ul2W$07`jxx^nxx^I<_pq2y_A!X_~XV51+?F^YRriF0wb7u@zt=T2^C_*$s~&6hz-yQ1+b1y3Pcl^! zJfrmHxh4u>fC-#7_I$vibUjEzHqD|#N&nuBUX>@|H+tli;J}oY`#sBEjmTG)eTFFu z&_Oe4;`Mh|{BKJ%B5=S?sy}2+p3(yW1Vj_-T%VVkj=9tAUl{^#$i#MEk!n$|QstY$ z?hi_7z`J{y65xmrRUX`&@k(edoZT5Xzct6jZsBFgj6k|gVEh{1;UfA)tS_0sa<=+Z zRNh(S^40B#BM35=*Kl60yvMSvBhC40y+_+?587>R`)p&xmZ=On>f5%n^(g$*{WU=W za5X_(EE8<^Bxc0vuI4G&o%QvNB~JcmA-kQRsXK#3^R}oWq}X!;`l}2pLDG9KV2qQ+=ZQ@I5xD@%)h=yuEHAPF%2} ztY;;@;&N-ep2M)9Gxyv%d@fDsc!@!CcJJw50cELDCC37KZhio!WgC-6wG+qc1gL#QayuRuTu2$=m zXMU>YX@zkSO-dXOR+@%4j+)JAA38!tCNLV+(7g2+DLhj}riQJlZtKQ$(y^FQ(!aUY zcDDyF93fi!)v_*3+zh%FvEQYAXXloL4f=ZI4hA*ov|_shNmtmY$Rr&j0!d)M5nlds z9hqsMWXVGx-$*1~YEIflsgU(Rsxve+l8sXS@z-P4s@`*xHhRk$a9QyBa#gA}c6Ju3 z0a8rrtN5}5kf>i@+z$e-VX)ev<<@d@yo;8y5d!0)0P)x)g!tkR|*CO+;By+54aTev8@^yCaz=S+ln1VX<< z;FwZTc!;^#Ri`D8rM1`=@uMPC8%A@&u#ri&px5Y(Ov($wYz z5gwd87o^DOS9IB9{5>qd)jI)?mZ`7 znkT$1os?55?#f6Flj0FIatbJZ+s{`J(%G{3uq5>Dg7Zd+=6Pf5Hl@xFwFP+_ElW1q zS{{ZX<6K>=fF)Wa4VlihJr?4o*p zu~nbY-3eG*O1{CqG#5qe?t5mhqGoMRGXD&ue)ou_Skp3dKKMk!R#23s>v<HT?n)5*kgT*fd$+B)r(n@I^jh_tGImK{oftGbbZ=fqykwxa6`EhN zw_xH`GPopHUyQf9$dU78Xl4HzXTC;=Id(oPeA_n0%&Vmg82PYf`Nlw%4b;AR zkMv28b?jUe+5^%RnJL+-nxd<)I zif-y>4FAh`H;Ko%_*mbCnt2A_gy**C?~n(-D%qHOR_+eFn4xG7q`_Q>rfMsDHlLd} z*c2IQeX9S&20T>SwtuLcV!B^VTxE1cd&J&z&liBB=;s8FQYVJ0AOHr)RUOZ2Z3a4^ zQQ%Y)AmS&Ex>6X)wgChs1TMKE;NBf`XXdJD*|BuIVzfg4Zu zbd;9>C6O=ub+#wB6L(02MHR@-9A?`}-T zKlJICqC^yg^K)qxXjBP_=z7sW0<390LECs3Eu9b90CzHj+jc=>d=8X&JWLV2FD9it zXl5?!_N?_x+~y7U`JCGXN(PD@`_~vU+O^zCb4nH)6Z1#-&Q2A^)!wp;M)1a6EXIzh zAyD#AYg#NFvq#HN3`WPNd$p@o*IBM-XeC~bRB&=hF<6V%_%%i^yF>uy_fhKA_)qCq z>nV;xrN0WUU2C~HmHJ(9?N1QW8i9s?L`WBO+fF_M5237B-2)FJowx%Y*5*1H{o0n}($Gc-~&qfy9XPeE;*)N_?=u9u3 z%VQGRS}d)4II(o{1oq7G17zddE9&P}Zm%MumG7=KTx&~SeZxI``$O-B*jJ7VR{=7B zJizTA%^O&|8_R*!?q{#*4b~s5xgHyQzm@)ckH=9nkll0Zyx5sQNJA`xo;NF)B$pGg zt0|r$?;wV(RwIO?FYj=#!RB75#O$jRQYd{n0{(`wd1g%nxq-mOa*D?b=yIFbf+|YS z@d*8hD^w6jpPdoD@JPF27zq(qCz-upzt8?D9yRlAWDD)r`(Wy`L8^G~I`0$hxcl%_ z0?-8UH_tpGfOfV8=wmCt8z8$s%%_i>&;JC7O9S2K<@DU0$rymtW00z6h^EMyC&_2_ zq79Cu*-Gv92*cV4Lm*HIVFXT9h&2x*06Zo-1RZ}f%2QOU*i z1QW(z3hY(&>)%G9(GX$5ItbgvdNHab$TFkBCxV4@5Ia&7`jyOA!`@j-nSXZUcO7+}@Zv2NFUrU?~c0^UeOp#mTwI>FqI zMuz5ooe6J~t#~BDjXth$jOL30C^@=CEgzF_#A&xMl9=&gi^9$lnf6El;LqVZ*#-lL%09rdj{BLzoxPr$d z?D?M`6(`qu>kM^SdtST&yhLE~VG80rfb@b=$i1eILepnt4SnfkqQRzX2XWrU!w_QM z{hjw8a~zx~J<%T>q_l|}y)-b_QEv>ora#oYrS`7%OO{rh7-M0G>YTlj%C#_(mB@t? z`TFBS;l%~;ls0x7tS@oi%CYkYh{i#L>BIMivp#yZiJw~8j=zYXDNa+>LPj z?hQK8350f`7ul3^k(}k=4jdXy3}!ybR}y}j+_QO7@%V7JG9mV>f=Tm*XTMbg3AmzI5mY9YS>Z zj{>(QCREZNZ;gj~?QcD$Te`5GBFTjFK^eOuCj=1*jH8HhLZTeFzcx&X;uH6QNa7i) zNF+jkK}B4V7x0PH+45y5n=4NPx2$jH(DlAD3~R8V>v$9@=h*@*2NQGh>Jh|Y^$Y^J z_ZPBul;vn|+J&XnKD@C`5^i&%>d9`b%k7Cbb1-M>YJ%EYS12vnX%`)y%aqNzf~4l(D6(`1B2+>baI6*rKPn7Sh)o&r;AJ>MxKJI)agKvu?{@>rMvQ zBngnMHyFo~xH=r!o(eQ^3&%QQEqtMw>dpqywKhi#m#`(>KuJ=mN_+x8$LQOmD5u@H zoEc@JDQ_pDpBNyKkXnx!-iilhQ%HDNTQD7`D3aj8@-u+%9(jZAMpAAU%u{##&U%mV zxSu(Bzbi;`gwN~z$*1^4W{?IS>PyKo_1SSvf6Sa>ZZD}yKIcD0dAZO+RoY(sBu}_r zF0E9GP}bG%SwFh2bW}mi^BE0;VhudHd3U%FTRxOV_j zOlYE#bpJG=+-{($YURsIoMNeRneUr|t`+QB$)p~5+{5T++e}53=1~U8bxu9#=u&cT z^b5^#?qVP{VIl5Y0bVxO7Ba2FP1ZK(5%mO#p>62K7C@j z*je%%R$wFFU_3`?2my9kN5f!=V z^;RAAmp6wJ$1R~@(?RA}UMCKKh|q}wT`&8f#`p*@22c2k@!eA46}^%B0!W9YO5vo= zLyZf{#Kd{v;CSPJIpumBAEGOSrmAY~e+7uZOaoW0A-?p!q;K4Rt3AR+kbqj#k&#lz zKK_!mPK<|9J+3ytDWyLo7o>O(Qjq4NYvw1$rVGiIq)m#8@L@|%jCRP=+=$&ZTCHUUi}|D@Uc7cqn+8 z+VJU^;p~j*klU(A z(JN2qG}I2#=U%NEG!VN)#N$@UAiN^XW9Y{fRn9}mVaK7(8w5n)!1IfHBf-xhQ;9|) znb(AV$q?LwY$^)wMYLxC_wirkf%a=9yvl(o#DgKQy8pE zu^VxM0WClSd;NOA$@A%|V;<)qo8vDDk&4E>+3yvN29k?yO$P0m6(9-18?|XE=E04b z#5OrfxndQ8z95Jr@yV%e^n;mq$w3~ao zE z)e*tui}V-)K3ybqI13s3^N?vq$=HjB>b*m^5U#Wpz!d;B=A|m6^E8) z!`)X^2BQ#tDB6{}heV6*5N&hc8)qN^)J~$GX)ZM7@v$bSg3c9YYdUT03kqaE&gm-; zA3w!RZp~AlLX5)e#YPv;}UD{p3E*mtyLT@vKJRcI8IAxtnPPmqL--xoUY+xyq4-xG>O3;2F&(}Pj*1c+2KXFF5w z=IFg^^iOzmLJ&gC(Vv(4F+zo5b56yfK-w$)(>@rjtrI3)O>Y-9_Ri>exETIHUfLj~ zBpB%6XS-m4S@^Ip8~(g_OA%~7G)5>Z!zgYPDbAhgq_f@Hp?{Du-hhFJv8;`kxA3;m z9I-v6!u+l%n*U()yWBG?{OZGJaA)vyqwcWJll^3oPd=`buW7t2GDc7XNQFO2%9f$le__-+!yl#X`!pK z6%flHINkKE$?Yf9DGceKZ+-&c|@3Pfm$%mS#FCQ5G#BnuRF$a=*X^}M&Cs~rXy2|P#Zp2UtFvzwEQ?#9$?79W0;4# z8+Y`KRn_gi2!$g=g2@%02hzc(%HRj;q*4Nc0A^CNsm???mHfb{d$YZnm*3{_>H&16 z@+`31j&{2NP3a$jb zF!NzzpeaSA4X@b5AN6ETr1-Gu>$RD=x#70ei*~kod6MUBkq87jG$BPSc8^e4rbl@5 zch|((Ukh%IIGt5QvO|jT4j6SIWyFtmEN>tjdvUR&r_rr28eXm)uRiT=sDluQ{m4BL zadTt6IIz}Z!65YO5N}>A6Nrx>$6UMr`Pe3eE1%rKo6J zL49);vF}Pd=LW_ycB)P{x}Q#rvM`jkN%Hx0lOLp2EniJaN%rxe|*U z!}K*StH_lqY^5-h>a*m{;MY^Ql&@p)&-yihqA$2Raz?WR1mg=~;M)O9`LuFkSmi^^ zGubyh*4o$*TXNd(oHSf-=U!(PE~TK55VYPQw_ak?~NS7Vtn7AbG1 z+l|^h?rU@!!W^|^O2X_-+vZ*jKp^{IXFEdZ^*2wKU<<4rc7*324L^r56plDw70p-H zkh~{B1IUz?XvUnWFCkXt^5O_~~fZFPERj%9GlWv&6q`SLB zT9IxfBn9a%MQK#JMJEVIN{1lb9ZHEvmq<5=3Me25^Lq&q*V482-skLd_IF+9uRrF6 z&-*-MjQbwj(=wB|dxmtJW??pbTdC$P@#q!z&c`Np%)FSs2>(^$S>QQ&-^=GGv zm;?(V;vHUQ@s-BOSb3CkPVHw2w#&b{9lw>htduQ0()q@vW-IB_gX~L7@;x4Jx1R34 z&KBM2Wazm+jB0m?nIndx(CbV3IR#aDS;#iKH&B7z9y>fo<_)8o+j&>60uVij2wv(( z3vlSdw29WN47Fm98mI~kC=9Ys#HC;50~o}F7c1KFzS3P}pl zX&mYZ-k8+pd8d3F#<0N%B7z+s!wDZZCnJ^Pod524fiBs_=0+c{ujrIVk+WLYmD1pK zRqPiskx!_A$XUJB;^id%xK8P9>B>M3hW55d%I(F6g-C5zm1`^P3sYbW zoyxaY)~A~M6r}~n3O>zsJgz-3|40Px6_wVa>_z|Nv;dIB?ZMnD>RmLJJ+R5E4R_s_ z1n&64bguIoZGD z`}YO9r&Dk9kw1og&lZgXjQ>eF$LKP9&mv3QJk8xg+`6QiQQW@e>!PR4@XBKBPvso5 zqA0daj?w41C(EE6%%SDfQ*+c@?VuP7fGkcta?(u+WL-US(mgZjUR}*AYGXJvwiNZZ z2Fy`c*9x1E*`7x$a|pgK?qI~w(0;W|dNL+{tlcgEaxM|P!jGGi((D7n{%5q?C~rx* zOD$giU~+Nr84{oyrz6@B*`mP*(93pJy0Sp9R!V4d;o3^2Gw^amuc0r8fY_M9oBjZ0NS)s zG)5m*pNg6H(=TvfJ5N5Xx^65FEETloM%QcQ=jH-Ax2*B)m#wuWcCGiTi*#^R0FxU} zKd6hum_u!Fu)#R(3zq31mpGIMZjLP9C{-Z2OU}UMynx-5Ao>{K=KMp`7e~D!#|vEFj_Z6yF=splb%_`+ug6uO0dWCXH0Z@1t8)rnx?Cg zOEX6%|NW!c5_jH`FiE)5dgO=&uwKtj4-`GhxtydXDI@_QD_Qhdr0-1QZ=c*8*662C z&pephIL~g*k-hu(oAbWtC86!}P-;q`M10MEw9e6nz^2UPeDJ9Qt`G!XGGXL zdEF--M;ih{`G|)ld`pPbv{4D7axRB>5HO|utur&L#iIfs_~cXwpsyV}Ge37@e7Tfg zw>P?$)r|#iEqs|Pe-wPquF$q?dr*lC#$XXTi_v=g86gS}V($SOOK|Y?$9D+{m0S*L z)ad)qjFLcMh%e2SKW3h9ES*AtM9?p~o;DMt&Wy*6rB>^k&*cjZx{tyU$DoVDnS;q( zjC56{k)f|SjPo7YRI04#=lF*Nj($i^HRb4t(Tg&RQYC#b2`KOC+@fs_ zBVITDl{x@#uF?DZGH~FxdV${p!84qFE>-IMzy4h6h}1tLHm*I%UA7;6Kox&=#KC>} zKTg|+k2)M1&e%){-}y;mPvk;yi|g2MMzox%vfy+_tLytle=l5Q&RtjT7fpO#V~TY; zVkYhPjy{+B^xKm@;D4XV$cWbD3lst-XWcsYX}+GkM&;Y}`){YGx@0NN<=Iytb`UcB z9~YWYegjVZMG%ZoJ-uj`|>Ch>LH{&2BfZEhZG zz?lvNpw*j8k>lb3w%z+Yi(E`Jc(q7y$A2^qRzr5hsBU+2IUm5b4fXpcL9(&oV1E~= z(0Uph|Es&W|HhZ#uPe00Gdq@_?dw@m?iioXdC4GZkSU1cH0OP`?3n_29mgr~OtS|J zllB=y(PWDs=04xxXc3K!A1)FlM1GU96D~u}`Yo+>mxA(jBZYp%qq2#g&N_s)HRUpk znn{UMXJl54l7MrI6e~W{)$~XQ8H%CR49&blonlg>u)L81qsCAyG8ZwC2+Q_dhT7pZ zal`HDSK)f9dCig9(vc+s{nHZ>2-1fXN}D&Q^6tY?G3vX4re4BhJbaZflFaxb%1e!K zSH)}zPE5|GLU_;2x=&lhvm!fS1N2zC^3#OUe#R9LljQKE{r)Xe`B(wH?N-knu6J2s zY(4vN&bK0pwuveK%HQ8)BJ z?#uQT3bKI#zT*LX05Y}r$B55knqQQ5-g+ZYH&J`fZ&*zFrKoj0^~|^5?(soj-c9i% zOtVz=uf<}Dv{^$Vp1u7Mm>KdN#6q17?TXMD_s7X~qX=5tV1^QE8@o~ZQgU_}fZ%7C z$iwNzjNvUaUFBs6F=3gf;dUbLl_Cti8CMOTV#rH9P=mC?5(^Ho|Qw(EwYHhG+nM=NR_ z?yoek6$ZO&I;)FpNBVQ!wBCr}x(-7h{8)!b^c!YvSy$-h8H)x2u_ptxz7YrwxSE$h za6o+jG4?dm82E=sGyCEpwa|S;?nt9f=qc%|7|mq(>Jss}(3JwTG`QjIPw)D*D(CLV(qr}drHDMa{{tC;B? z`gdB+;O-XX_ndrTnjcxum~%9A-oiJYSC3Nph(*r1mS+Gg;$9mmGVOW_fXiRxh{_`go75z!+U!L9;NnvgDI~s;4-pLg)!n@ zQIcVl2dbel^r0{Y5^8gAMh*m{7mUDHxAM$CWY`^fRq=5u?SMw>()0(*>5j)E2YLI2 zn@hcOlggMWyP)2_Qd@!j9<4iu<3Lpp6HeN_@jkIV&yXrw$k%IntSfoS$<29hcZm7+L(FmM$<0Shz==+6Z4oF53uqyU26SX?8R)6$3^X&^JLR18+{ zD~pU#lXt=F6*>53$OnD~4>*UH$sVxISj|1;o0J3-T|yR0en{NSJRk82*Bu&(`Zaj| z@fb-p_@Rb`b*4uP%Y6D{ZI_VDCr0q7bipeD$9umzheDBypDiZbYGYxN*4)zsKgQK$amg|(~X2X?6ZGNY4_+8y|8az&vVzytX#68Uha`SD5-@mQAm2@Z}GEH@( z5>Sd^?Qx0YsmtSGrqlvTvG|77p?sv5S~psQ=oAf}nTtVK?j6X7sK=#bb*4zVmJNNN zf_kA!=NZ)Z8BQQtpp^o_W2UfXTWLHWDCouO?rrQ*PL3BijJFK)F0-4OgOx1@UhUdrz=mpcHc0s4Zg52xzM@R@Pbdkz*MsHrPcAd zdU`4^#D@?{iHuP|-t&xLIYk|MnVCitRK^d?z5(D+WzYUQID|OMo$?C?EQG0H>}^)+ zu84iHkHar40?ZV8oE7aOF=Q5cLGX8w(J zf!B|g(@+21U*SzzKVosu&r8)O|6MI+kCWVH!B+D{Y#c0I8Fzv=*M>!dMZS+_{uyrq zV+%(@MhB`Z6@kc`KyEX<>4I{uEVrJRJ1fgmJod1TmeZMN8+~6+w+zLui(u@%jCaCa zbdVXK`nW-Z5hF&y!N> zM{3&J!eqG&OBpmDnFL8ky-y>0=4^npjI3o%!(kOIq*1^*=Vv|eK$Oq1d(E2+I0aOJIAUqKE zcSS)N**{+u{MW)m=`U+R&9#q49RAzeK%;>;J<9hUhJ#Q}X3=Ra7&p`C9|E*!$#*uJ zJrgCv3fA0#_hP7+ZqO}kXViowjvqBqb6g89aUQ6Y19Y+H9w7V`eDgXkoXwDPK&yG? zb-E%-+})E}aAeHpZd?;9Epp8KF=G!`_%4qzY|q{%BAA+iSEsElrdml2)Y3|-J=m}yj|q!}si;alXS zDh{jhd;6{NQ~~o>z86WvH;&3WfoPz2PJ%QXcT?TJg7SeNAm}mkk(TN85k`JC=ZYOE zp~{vq3ZDx7V+V*5#q6vD^n+ip&{F(i_xfu=&!3BQEt{3h*s~50!fP35a7qlRdO{Yk zrZwd&&ETqdAwRZYgxTB}@2F|z!))6#UvpX(}8bJ6!+ynjv6$V17`WMj9za#GbfxhE_(Hu8e+o7q4p{He0qlOZ+ z^hl^1c7}nm*W6F)1cSF8f5yOqA3EFq^6b?9NjGJOLx@uk&?YuQh;Rhe40Z(NptS~6fGxdu5a=z&9!=o`5nHND?JNh z*3xN+Arj8ttFZ$&ob-`=02pGS{&3E20-EVyc&?LgeMFE0G{-;FgZQ;5`@pSty7w7S+xe)&KScE1uQdmx-nPam7LmjGt%r0_JrmD>lQ z{KVOPuYrGR?ob|J)uH^{NBJe{V%?e&Pe+a*)OZD6DTHf$FP(%wMA`Sf2L4_4R{Tw9 zE)9iLxrxoSh5WhgWhzQ3DEu?(`W?mgtI+(_rt{5Z_mkUnd>+Lh1`yc~SSELCy3q^i zr+W9N^EjGdwcemU2?XD(8A!;jAAO~s2tKdxO2CkKz`E&}auhyTQaQy0HpK?2C#gz{ zDKFRjm~yn2E<0`mYO}pNBA+H~w_=(K?;gQ2x4DTHK$XCmIR9}LXamk6u^+XRby-Z0 z^enxZPl0gDagFzvl%v{s*KeL6(s;STDE4>C@ibN4`3J(Sm4Rv&+V`E|YU?pjKO}KE zs6Vz)aIZLVJR+&z?^?<_h@|v$fS$!_E?jUihc1XmcyTW1j1Bk+y!`J%AfS3F1_=XK zf)aQld;dmaBDKQiPLbw!2=r5{@h@2DzeVaxFW^xo_m$#j9`@&4 z6`CWSjudg>;+}02m#0d)a5+=i4}$ogD30CiC|TeB0c%vE#qNKHHIK1(mkP7`Pg)&( z&l*!SkLK}!0jH34@ck2zETU~JeInCm3JpI#BK?usBNoXpp%C%S0YK8uydeKVd!&?| z1p&YskjoVg9LeRj8KguiWJC7uA7$L^u_@a;*E`)C;IDw?MV`sj@l|R%n|5~^?W-|T{XnY46 zr%?Pm?)nN^|F<=SQ!8wpi*EcIa2E_U@KDKv=Ft)EN=gOPKM5c3hTZK|r^Uz1ac3Q@ zL_Rl8HQjrZrF?4aHX>9v{b{l5Sdr_|?wMAq=XJJK@27RFnn z+L|I*1*3k#r{^bo8p(=RK%g5)fX4KgiTBGoD381~-gGo{@tSxR;vAO1aEF#8i?b&AiZ*u|BNo^k8Z%FQNw0W|8uF1 zagWQ`-2VxVg^SzQBc4Gl?9lFJ$uH@tA1ZZxJ|*ZbXs#{bd?zJ|X47{hFAwuOUH%jB z{=fb`paS^M?%$UI6$tTnnjUj^Mun<>j7*8C#%IWhiDqaE6{4n~fSQ4`FwW&AtwW{ys<2=fbDv+*el#fW2yJ>%*q8VMPW45QElrUE}nf(Z7IajG+hnmaTa*%&Rt83}jZ+nD;MyJG5j?5O1 zryw0NX*KRctHqbFqG74btm zMjJpM`6;?U>Fr?G&T8vD+>RmKrGs@^T%HqZwttc`9ajhUU&p5dZvk zDqa(pvFjF}W1Q0%6p7N`)vBH{&c`^W9>fR2fu}nGo0uT#za%k#DlZqeSFg7iR?u{Zly9U<^v-aO++nD zdl8IBLrU(=O(zpZiFH3w5YJQ|O3x4<<<>LO^?I^5U6Tn_ubYUFSlj$xk*tWK~|anLoIcj2H6L-u2%=ol;pB~wil^H zAjXejbw4u3Ii7k3fVeJ$w#%rhQU0qyq%6v!>n65Ag_=zH1Q)ke$E$4DV(f*P^+x3H zAQ0SlD%(hD_hIa*(l^<9`8q;TTlBK+&uH2Aq zV7?5QI+_Ikgs*pfKw1F%kueS+`%G77FyWgvcqBC622uw_o2p(RC76F8buurHrWwv0 zuAZPvfgaTgihEZ;WKp^o z9}N^=NyEE8m;}om5{Lkz8G0y&yb3W@TGZ6`g@X)*rnsG`r9z{h!t?ckvX!J~7j69& z=INarhjJLzE?c~OXx4ZS){b;vPw*vriZh%?yp$fXFi5YU%%saI&tYt}aHaUmu%1(X zO>)+;xhnT{H4SULgDQFb1SuZ1%OP4?BqDf%POEC|*aSpHcwdDFO+kV$vG3@;w2i7I zp&^B&$s>Y4#;jVrd{u`)PmSA*z|7-a-=n^EWQ_A5jscXJT-;#qmf9o!91?P`K(|VxhkL z0&4Y(8=4V|?h{Z|!ASu@XD#UWpq7fsoSD+m_iC?6zSS#{>ceoVFhhNC?RIA-_Q%8h zPXoGh*?0$$JgcH83m)ov{H$sm<~GuYzA+3wa`^;rHg)M`(s{ktZOlo&VxdS4hgOnz z)95iHUC+v9`wYEGE!V44V1(a@7yrqh8@-EVSDj?Ie8#uHO{oTPv#e3N(?!gfLiJsW z|FZq8dmru%Fie55;+lKd4Pp)LuEmO+bfrR3<_Bqz?2foX@&!djcg1b`R_4Ret4@~B zu6{%h1eQQBFspY^eYj9Ub9Z80KOwBE9U065Vhl7UxRex!&CJAl+MV*(8B#ERUkWO1A@4u8DF%P=v-YMp>`8eghf=&!1(fKmEZz#!|Tq%uE ztcaQWcyPlkx^!798oe|iGA$FkKAIbwOq?~V=4-+b_JP4jzGMUlp=9T43t@b-lv33; z%;+-9BmYXLsSEkH+wi-Q&9lBzTsPr+^J1`-o1uoGS9P0Ee+7sC8EtC9YpbjW#4@^T ziP@Li>0v$hR(Y=;Vls=NyjAhtlu1ESUKYoCCFBqIS7MnnCsGUd1zo?G23c5=W((~L zw<$}fUdWNVBHZs~F_=LqZ7nAcY~+X;Ol5OkksZs3x_TWcGT(y{Y&6oUJ;d%N?@wj$qJq1qPc?LVLMjH0M6l!gt>F}7eHpTMM1q7h#diF=P zmMj-}hd(!CQXG4AeY-@ad2J3aY%D{pqEzh$o0Y8M+kUOwT(YmvHPj_XQ*LdS+xI=c z(a#FDgZboDWOQ;kFi7Zmeod#WqySX}=IPB4YFCtf3AIU1gErAiF>8f?(9IqvNyBcd z!D=b6{<25FAtix<(AzSNymR9dHg=ta&`q^EzIM0=0(2h(;+(gd~w~gw&R$~Nr=Ov9l#(jr#f{EF&o;vsk+%_jutggaq=DB9`nt=3%F_1C9O#SX{dXMN@QT*)W1- z++fk0Pod%*tLj0SGzI+VK~$GaQj17lcgXM<`d;R+xM`l??#O>lhIXA~Xty-@!|UuT zY4f#C`^;JgE(PWBPZVkQ-Wl9;mT}-g@6y6IpmqDCTC@cQg77h992AcZwDyGLk*t?Puk60?9{5| zs;P#&Np$Nfk3tZigN%AXB+y0C6Q^Ly*e1FB-;#=_i|viJK2nl zaUZK*ic^rL7oWgQL|KTQsvz?w>2?|+utQ~X4xEPPt|$&C9pMcxu9r`QJ0c6Yt_>M~ zq6shNts$;I$AtSu%#EK8Ty)V)!Ogr-TL1*rDnYs}<#G>p>&io^YqG{%D!h_1sl4Uh zx9(JW3q@Rxo5Q)v@1p{D>tiL!z!nZgv6J|Q)Ds$3u#V}Dx0c>#Py0UecmmvPzx%{6 zLdS(U@Pdh(G7U-P!o7Zc2pJes*lwne#AzF?wUF(!1HFqcg<-#~TKNgOzh^&KSOLW z5sbUti|pND<2T?b)egQNOcXy9A>{+g_VrYWQ-P=Pmvm$uUjla$;kvbQU(~YDvewLY zaTHS{4UV)ykA0l$;-zOIE zbC)M@)Sh8#7Y=*T-wFvQFuC7$*9+XZpy+6h8UryA1g+n>tJa4cpBb3$AB<2WkjR85 zQH))5$0%s~iB9`At~W7ZnNUQKj0Ap-Q4s{!Rv;`tAb=Z1S64b+3@+Tu z=c#D6jykDdrppEOJ1OuqX%aK&X@GO{l4~6agp(NJG^Y7L4TA)QAkWd?f(0@Zb$3n| zBCsRnN|Hgi`czhp^KC4y{o@ohTowVQ`cVJ+VAXXD6LE=WS zJ0v`Co}t;BiS9ky&B=!(t#!tE!%?=H6 zT{u>z7*`KuU>KqAG5B;d4nj=pd@qAQRXDD|M!(AgqS{eFY;3#T6r?i4$GKF{SnXMW zX6Nl_o+%Fgs*tJLT(~C;`G#)hW^Vh+#Y8KrKttP({FR9kVXSgQmMgAfJ7H*Rv?fR_ z&bR&MYilA_nVdoeZxYK`F6}smiW}O+x$GEzu%?)Mu~wu^mg%sp>zQA1&0@3+XS~PU zV#iVMh`RV9L|hk)zkYQI@6oWSP!~Rr8QD^KejRobaG_)Vbz?A1X9jmG zK?wZWb@QDVNH2@sAX=HC zcriw8-TN9R_}zq8imvMW_q=CHTUYK}@gcA;@);k`c(-3a2_tJD>8r;afdn?A&!N+p zHlfqa;82jx(;;O>5i;f<@j$ZK@H)w_00VBU)q0AXd*??cTL%nzq$NOQcB= zzaDN)Cu-5{b0u8S7yf3kkw=u9U3P7aB!4=i&$00dQlK;}HPybkQKq;JexnhO2jL(A z?tO3#FEzM|70k+w65E9klh}qp-N_XT*@gG1r1lCx0*QUPh)Gwek{Z}>0hv}yCoRQN ztnY-=zX^vYleB1+w4YX~eqO{oqJh5^an2}A>NvMS-OC?GI=d!1Sf zFD_mqmfxohr<>`Rq8kkwcE_c{?Wc*WHDSj+0O{`ZK5giz4AFaqY^wQuh``#}PGq9v z9=jHuF|j`*;WiX(8%}VMrpKVK;uhurk-N{Z9I_{J-7T_K$zp^IGN{P(fVdhjUrOHN zOAz&~5$IiGxZ(I%VTh?BQkC6}bO=k{ZA(eVt`5a4Y+M#I$BV@+H4s7VJKeTCNf4{; zx@&v`SB;6Unpnes<<%@66%$9Xz57f8u7>wk4SX|-!-NqooJ=MYb7fNpo)043Cb1)- zd736ElzUjhm|5Eby(;*YXKYBrb%N*jda@@fNMN|mug4);7um+^hZdA?8`_l9*5}`i zw)cv-=bl3pM+R5N0S?TsPT6nF7HI)~lN#R$aa%p!V1!q(anY#vEEwOpA*BP`=-q8P2G)daZ*&cuuOcI&JTv-uYe zi`44M3R96jklmydxcS_rtc2nEEskE}=qqCMY5IIzk;$7o#H-A=|>hkdOxWr_ZOc#a|`lheSj^O3byb0LhpZ zJq?h`7vn(!(eX=cM@002(No6W-JJ?3$9>(QiHxum-GcrVNmmEUBT;Pr%BsK$-%#OW zzxUmvu5kEk#6%abk-dj%);*@ogOe!`o3m?ezBhwj7z7ee5&rB}=i)e}((L#}bFiU1 zRJItK*oQEI7cXGz&J%Kd8PY6lpY`hJA4aN?Xso%iP2B>05M4`=eBmeL;qg(f3vSUO zAxl2Lm{isLj?Rq%ssHVVa^`W4_JYF;py}BJ1N?Tc4@6|`BaXWF5SpBc)O@H?37>t% zJt)%5OyUzwUlHej>0LZ^_u*`8SliQtK04Ulnsi$t2CrCC(GK;#uKpInO?NpZ-z5fH zFgmnBTMja^gOPUUi9~7=Xqvsg7R0o2d*CYsoa0pSw0Za4MCWkbz5)Lbm6KJ)OPHGs_G|pf1LQZl>&efkOhNuwR zxz|2-S&?uQFDu7Y#wsFO#*z4dvytB)>6JrDgZmjw*t?7_AzNra!)quA-!djVbkFguSG;OVcCV1rC*>pE(mJY3*-vD}B?% zeu-9rn}*NT0NOwpaEka`dYb8A=R#3jg7_4gC5&&3+*%7NvbNH^mA0tEM znFDzt;n+kGtIx|tGAQGHYc;2q@kQ~ItE&v4R`dZOPHs70OQZKMpjRjF{Ycdvup@KT zI#_C{|1qNo-sc@#YIqO$=shKqk0}W;jTc2JKqV>4Y0BMCr4zK)uSX$dC=j3ur0G;p zu9ZxvaThk#W9@HJbeI}VHTrxki1yUkFsTS3xe~~}xl#ppfl5!N1D!^@$azd!gT&o< zi4$Rz1W9<>U^yUtn3RA*Z`*Fn3C4i)o?NT4>0O<`({HSfvNPqphzJf=6@kIWjKFG7f>fv-0p7$)H?;)j&(uGAe_zG`cz2wPiZliLUsGgJN z!NrpN!42>Qf}v|&rB^kzbpyDxg02TRYw0FkD}T@m3Ahz<-`2 zcrtXh)phdjgnbU-ec0tr18<`AHL7)k0~A_6FNBh7zVy^`SG;aZ5EjUy+4P83#$3>0 z^a@(q<_M^Sce-P{vl?>NjpTJm(Be`49-zLXp!>amiY{nYT?n28g0^&G9E=N+1L(QjF;C|-BBx@4&s zHixbxAABx1q&nPQ@JinQx?WlDaj>)0=mmqJ7=e&d{s@&^)sHmYYHcMQ6_W_Ir9pjCY@M6rmloV&9>R>P_{L?ZgY}w1Vr;$EJR%>_m z1`1%t54>^ai@1ftIQz9@kTFP-mas3_#=2+xy%}CUL|PROH_-&!ijac8H9+>I31N9v zYnhbeP1==fZh;-r7h?LnBx&SJXz@zl1|SJLTI=a8Zoe#I##A9;(Y$KXA=H=HYk{{i z-SgTi5*@oAI+Qn?h!;m2kLYM-__CwfcQmo|>odA1m=iR(kpjvt7uk_*|53V)2im1-7FEy3r|x7G3grp4#JU&1SOrF|-{*e<8^F zb-#OmTs3e1-K%Nd9J_2{2r%%d30_ksocA*tGb8BDek5*Bs5q@MDG2Nqh^u@_O%6Uz zg`;g($z%BOEfjZhA(Lw8cFHwst56bj3f`AqbqwzGCZ^`pNId~MkDX>CyDoLBUqr>C zPlXrv7QY06^K=w%|W~3q~J7qIaUICxaEvaCETD-0O$*ib8c76_pnIf2vKqvBzcV6^Ods2NOQtg^ILj||%^0wzgwHsE;3+~y^DLxU_X|3mV z59Bkxp3$3)DQ!iKVTB4q$>P77k1kb$S{YDtZGuvno7JP|(jOlN!w>uPK6FWB?hLGBj7Kwy zVIxj`50VQ>hF2K0!dj8KKXC_dJ8Pr~Wl{UiJyWfy3>1_6NDcFy?dcwa!OUWR47*+( zyu1SX#CB;@e5x1YaJS&##-!x5Wao60(EQoNhBEYUFPYx2m!MTtAibUieF}OGPxEo3 zor6;(5$ta-`>08nUknVn_rQ^#{2wnc>q0%?(F&u=nBRV>obPsz4HMnL*-muVj0_fjvIjDzoj%fN5hPFh153=n{&lAYB9E z?QY*(yOB2m={C00QsPazE~qn}O$?!TQ`d2NWuGi?|Khv8z{-U;T~+Q&LX$g`cOduF z205>_aRG0MMaqm z#l3^<;^t_um5uAgR2)-D>()=Io}>eBEhL?7B1YaV3NV?}J2q_L=SMGHLGkDf5Oqr9 zdb6Y|V!ZunBxj4EK0NWZ$3erAXzoDa>Td1cV19%1^E)@zZlLUsw0=<7tgc(Ol=XZ& zgx#Djo3;L=i$UBd8+v2thWoQx&$Uel*Seh>AMY>iPa#pcwS1iTAO&&ZG%UYBT#nndH|A!D4X>gE)v&nn)az+ zx`@VmAJT)r6w7?k)mLu+@Wjj2s)Ax5c$T2u+dnAT6zzt@05i0VZ=CdXFeTq>kG7Xd zS)+{AVZ4_)TST`+xLHcm9y13x8DA7_iF+s*j7mqgnM02{7(QiMWkgE0g$hCVEY|w0 z&_|UC)cXJvfxx^vR!i>URk9GG{Tk(FG~c2U2nHHMQ4zj8W~qX&Fj+7Oq|Q|swOX~f zd^ZS96`mlEceJZ?Rj)-*q@IafjM=PZKV5>wsfGDl6Ui3%(6l6ym?aVn3P>s9WC<49 zZ*gu$Ewu^I>P3WkRiUJS!Ro{>pn&5HiNtDfFqUJkk19)TXUmmu@yQa6Js!*fu`JJ6 z(Wq9r1E5?wK22og-XPWNX}{87ZjN_k-fg78_o3)=^r!=*w3H7}k*=X4#rpe*p{pmR z+<3+;mdK;25zLv0=Oq@(;+XQSC7)BHoR1BaZY3NZB7Pd`3*TD- z=9j?!%t+RuCBD<3Zq^V`5uVnHp!R&*o$Acb+-w=aB#h|~SXxl&iqW2R6a-R34c;cq zZK9Ow(kZFKdx2n?SMgC;niA>LGVM^E zHpR*xhWPN;ni!Q9IcV;pdsXqv=({Bp?6!O9>L{H8;qAq|S zqpKS+R*zcl(YFL4kplWpj3^jrNRf!`MVLC|!O{-Qdiclk zcgcMR*=N;rkVrsO`%=`UidWcB<5*G45*zsC;Cab9M{jk*HHGrtm3gqo?!+3vEv0zq z_ave24P1R86ej348rw)8&wXUs7LIO3c0JW6}becFkxbQx*1&ZG4OB-QAXwg_DwN%A)(Oz=Q z7yX2F_SwqN)TyI|8M}p4m#K=t?3TM-6$ zIf5@l*TT4^2l(s<>h26&G`}Wv?^qDQ( zK|Achus#3Lup1l+IVe>|DBX91D7uz0ECu zo7ejGZr9uVg|`KKMOK-^$pm^u<-^4{P$64y%K#aS`FMr%c;&iiNvm!tmR|K2-P#4+ zy3FyCq49=t-NqY?RRr&v8Q!(2 zVzPSzHq|;Yy>Mfi!eHjhgc8NX{DB5k)8MlC@U?(Rb4@Kv`(e}k$)#umGyBPIGu@bp z$&b>Kar>7s-^)Ekn%XLV3Rf2=c7fpP4URHt!|^*Q5#dvN6tTTUXi>BZ{#GoYkSIrZ zkXYDDug}aM%MG7~jRh73xO`#+8I?Rlh0kUUWA0$hxIA6TYeZi1V6vBmLM^Qbiovs7 zhru}G9DyFifl8#`nWn_`h{L#C@xeMdXv9jS+ZWaH?hN@u{A_g)IawsZBw_T>42{+U zEhy2~S2@)5=<`Sv*Go&e{S0Xdg5H^kqVush7lXPLR8^}Vm3Tq&Pi&NR3>X{NMo_I}+=m2p9he?djmTuo*{ zQwuoBOohM&otOpPtcB|p3wmt}`fc)yLkkAm3x>#xMufuhA54w!o9-OM@$xS&^65ncQQ z#BWiYd@Ggrto>8qeTgqLqlq43(@Pk$NXnhDeF9COX(; z_FF8gDdv2NiR*i`N}Wjt*B;!vl;<$66$Ov@JTwBDB`6ilg&B^0aqXpaWA-Qk-56m} ztdx_4ScFZsU(reg?P7Job|++;y*SaLiC|&>>NZ z4+2DR+6RM?ImHi~Hiz0D2b90y!JToNopaB0R9%_U zox?7VSC^V}T^zC7>K0sjzV+tP&ik#RigF%R2r=BJJ38z1PCXn5qnk;R1*0uj2P#nK zUtL)*Q-9>7IU?E1Wk5Bd@d}A!V&XEQa7MiSHusGrF?O8KWuuxA6ao`b2fUTy{oSMw zcBbkz?Nx_zhltdMf|;UrXO(g21*gA{0v)St(EtJcOZb-GK9|JPP3RI2GK$lGsB9nT zT|M>P!_OR57m~&}w?F6al%z*H>&{yR{MV*l&#P>YN4bJHLw;qBO`A8{@z^UXv#$Ei z>+PqC$#1Htelk^4gdJ!{)=6yP^o1Grh|U(~u8srCPZ}HU<$avODSDFJC%3Q%j+3x*B;yIGK(839#K#18}gx$zoKKOtZm4<#$xs=(9SW+-E&i zlK$Uw0im#eYWl4aJhA2TjW%-E_Zw#`7B@SYv!8FiVy}F^*~Q(?zV-V2bHTI^7JY&2 z)VnP$8*v3Af@tEhROL3#05S;$-k|alBcB|cM*f#!eb@CbBSt|S+oNXVA)m!`^)6l; z%S{c2Uam;7>KViSf9#!wUzF?i_JwD!kdcDgdEYA_c{{$QMmxRy4YX>ao=|^n&vGk5_{9dj!@Bc*gDdOfEe7oE4 zg(U2@qH_a{4W{&C@in{q!+9xJug;#>=I`!*Qev`+vrIm+A9>H|#pdQXml6X1V`#%& z@=e!17;)WbpDS%H35C`}3HTQqr1qFCzLVub9Sb5P?W=B#&b=-#k$3v-RVfiBH3}Ho6fnS6 zGKoJbaq_+JGHlfSa=5ecr24H+%j{FR)n72kK;1o1AJNxwn>C{r(-<(K(>9XM0Lt?&8Ki81@)n(xuI;TTZe-FUh*D$s? z4ReZnN21oNlnk3CXb*Hd|E~C>Th&Z2CT_Us;A^YO12 z8+BxC;H2WeZH%)Iwb-a2JiXYYbe4aqS#9A_8HnmqtnT|r2L6V+3hBjq@hMup{q-yP zDoFk-x6VCsA0?ahb0H2U$f?I~`2>q-w9zWHkGZArZv&;u?vox!~X zxL61&xrqrSYTKyNDgpAk%umB>-#74`Dxzxp%1H z6|UGy#O>0ELk$HGORk%5gkHG|zz)$Y%GZj72WLVVR!$@8p%j)2Z>gs@ZqP!rmA&3qkWgf$%8YU)2wbX zo!fRJWg5K6OcsZ40wq(iiv&zVfKnP@Gp}GSv)7K(pJib zpu+u2H|POVDS`kKWD%~gPX=svJ(3QR2PhYb-#td+#e{9cI)VnTPmS%5d5XIkcz?(U z4S;3!3E^m!~6??3Nx9yFk zK7h*Fbp!mB6!=%%J^yRJ%C$Zxf=s67D@ak;4CDm~hE^O=w1oA>`riy$@2??SV4zG- zC*319Jig{H{_+NGON%g($L&@bR13^8Isa z8PGj~xQAiOTB*j+U5C!;K!2_Lll~e9^Y^9{^!K(9zZJ^%xKsdZ?~Emm0sXbvaV$u= zJ52Fkc()CnJji>=SLr0+;uRw=$TIiT`hF`)qrUF$`f}kixd%pAq(tYA%P2wop8R{z zb#zbWo63l62>I#I`5SxZ|43I+`}KW(Z}0qPrn%3=@%s51#0J_O_T1V!5d!^Y zJXJd&xWVg82|RTngdj0qpQZY=hyn8EaQA|@7zSzTR|3hGn1`|)Tk6&U>k87bpK<3o z)~bK4ZNAkXgtKgnH7Defa?*FiLKwK;UWIHh{Cg<}+w<3%9`7H`Uw>)fv}PGgiaB0x z{{L$xznf|XA`PRSV!QypG zek$@CG;5}HF^+s6@`pl9(riHy4xxOgphh`S;>?>!{t5K(G_-VRv0e}|tR{GMYoqXD zK6sB0OYtJTn~((2(NF$n+wEo<=qRWJr);}+#gOggw)~gSqkX?+;`nRr<^^4t+ttD^ zzOGMl5|AjsnsFE9`cKxb`1@LP%v`SA;wlnD2+y>aT}7*ioYu8+dqcq~obRZ!fK%`K z&BSpBdi1~k5@o)5iQeEBe6q_MG^t|dWaVD4*DbD{>2!3WNb%CH>&TofA^Cvp77sOk zsZza3vvb`x;Yfb+2kT}MyPL-%z%J<}PT!}tD2L;Bvxk0!Z2m21q%TkF=Pr^pTO!3a*1Z*-{m@hPaf@6rB5l0?bzrHq&!y)J=(kU?PwSL|Qw!EI_^-&ygrPaf)2+Q4^>_TIZCshd7dx+Aemf&~Og^X4|&?{3pN9H{X2v zik2rP)64MrrZURuP5w+1Qb5Qu0qpbP}v zt0ym+X6Qo$BVT`oe1+#*OL?C&W=N<8ul?2q*s-Hil(mQJV{g_g%mHnY-}BRD7lii& zih(IIF9%?0YS()3LnDL0=ORs4kFL^GPSewg+t*MXU4h20Qa5l{WP~%2gJdS_P zs(hbC&78t(KrhhqUcJx>x!@Uoe901oE(Ne(Xa-Gd~ zeQAZM6!4;Fl)5UhpeuY8u(`b7Ck7GPtF4K(xwPISx){m_y|hH)3W=2o7Nqguz6Pgb z9NMGfLR8)lxRT3iijgcG*AO)T3@?2}SXz3`r!U^9xzYImuT1A8y^)^OFv@NyK%wNq zp366LTZe+wZql(_9=HIg)0Da;Lql&`ed3osHjGai2{Xm=O95B%(H(G`-AK~t6UXK8 z(Wl$4rIwJ3~nVin+^Vq4LKRh3cPx(+V zh5lyk^W(rxoqb6vJoRnh{w}%A)WWxVfp4~?+u$~XZ{;?jX3On{38>``)4b{BPRlp^ zD_yr+%~rbYMo}w0jw`pPS9%cy0;_#)d(2n+?{lTCZiCwfk!J<4avSrH!;cKoK8{4# ze)u>V78~00JRm+HZEYeo@59<;#v6h4sT>MgkTlLQZ3iXmaq@mp8Yz36S0UuM zjs)x08Gql`!sokZ>(0(xGiKpbD_-Q>?e_2#1Ol;uKM@qa$V3n1a45;Suu})LtqCKe zU;a=giq*XhORGS(;Bbi>fkEfcC*I$#`id|I0+ASA)iqzQPR&EBig`Pz8mcY)YyzCO+F?LO|BPcv*dBgp~U zm@VI9u`yT4m0r{Z8hec72W7Y*pVjb5y;Hl1e(5ESzHdh&;YEE+YYE~8fA;~m>i!uY zrhd7tby?+l(T&Ah*6q+08r&Yxy2B{OHjZSM!utsjy4t@8UCs@T*Y%YssRFlLsZh`zr;44?|XP{ZptUIeXKGr^?4L_~qm2G@Z@BesP~em-Az`ppuIjhM!-y;t8rfT+kN2bGb@$KX@BGM z6L$ftXnbx~i*A1XX5~n-ZTEqTp}H!vFWw1;ua5R%-3Oj2%HPe~b{{wZU-iW*yzeDy z{w)e`y_MVL$OwJ1K6wX7?YL5;ecfY&Ck~9Sm89;1wYZ<@^B;H>J!0BHD!P+7O3m zL3$e!e%R#0awKe~f>sblWfq$HeD#ze#q)SJKFTa+|3>o?T;VYiK1j^+d1)dZ?b%oJ z)1CgMM9QXfvP1@sN-uGpI}dB`lRPxWDXA;>f+f$#mr08Tsksc4J`* zx9U#4XIf}AT$jn!qj&B^%U(|4x3$0!ifIK6w)!LS9<;Xi>%=>rluka<`lT* zT?pZOj0M`+s)yl>3q$iDs;t7u-iNjy+B(3&2O4k*@m}n8a&<^Mb-A=ntgLo6{>=N- zXzz6;sZ@pd@`=bn$1J(hjk=)5)57Hcx|9(uvldLU-EG$OKtvS2 zXfDjgl;aYy&ofnHYpU$F3^9?SXXLjkUoo#`ctSUxQDSa!zd9hpp-avrOZ|E&h=aWB z!SGQ4ek%KVFP!&4U15(TzQkdl)EaNzgFW<*xhhtim94I)L^HNl$}m38^tJREM7X_S zKNT=?w>b0qCS#L_>!R{Q1ZgZQ0lZRzaUOYJA@;zYs!Ewt^ZrPmSavRWm7Lamz@yq& zPT{I5MJ)W3G>-c$KoAX^4@y*sX;A7uZ z8ZYDtuf4{&@TgKD{zxbme!B3u!6*J$0{pEp7JgbAeAm`gsa~@v|o&2B}n`}ITx&tcQkvZk{4`)9Jsm-oszV^(_L6ZqwlN2XvFkJKs$i@+Hy8`<3Yo-q6a6Yh}rlCFB!x6fP0m% z)b=Q#Rn+_}I6`i_n&V)|x77=;JSl%`tEf7d9`-|x2lJgHkZ2EOxfT$F(f} zS{J>R#|_rgiFwaQ1o8_FQrt@oezl1EOU87ceQ17Wvx~)G|HF?L!vESah~ILHlICnn zI9u_j<=M`dF2fMIcc>ahL>dtyR@w&fe+9{j%h1j}9@ij7wqMVWANS+Yxi`yIB=ePH znzfmd`<^PyEACd?JO!}=O-IwGu^sK038EASkKlK{SE2n})Z(bpj+t z@&2ls;i{h=hM48&E(7uRZ~dmRokanW)2{dWWMext`5(JYL;f}IHT6qxxSXX_)vq6@g8AooiEOKEzABTk_AYrdy?{*+MK>>YRZPOk zg8~O^N3!3CfM0zA72~!P&Gf~bSo+ouS&08aG9Ofv-7LwA%Pd{y*zJP400_BufYG!bK3jQTh2c z{f{1f{82UISKF5Vubqkf$@HIFZDpU{d1=2h9b?f>n-b%3k9H3olU4o5Xm;oNgK439#1MB)jFU0?u8My#bN&3;$-Z!I9tE3 z#VJ|j`0DJH01Uf!a0bdj$NYY5(!^Kiv@Ov7TrzgfvV0wO71}LK{7I3^lXHd3FOHzM zhg~c386~bHwuFwq)CU%PbDzCyPEF8dtn1)DLs20tQmV7LwED%_>;LqZEAX2y*KgkR z_UP41_VNzV%a}jEa4AnHveUm{YB0+}xUmrr}tBMl5Fhu&`y^}@yLi)!B z9-dwv8}x(X^ZbK^+VB3@JN=6mn^Pae_O~AeRnVsgt8Q}y(ir_Ng^F|Ta0F5V9two( z*MK;lokjvD|Ix@g$or!RKJeVW1yv3TrA2tuaka$;;QaG;-2OesvL#i;&wbV=Y$xzE z5D0kX-)#+v9A^A@3!w6 z(7@N)*fW{8yWN(5Q{wSicXO11WU-yqu-IJcYrKF|+{@T3wyeIp zwZn#_(l0`Ci%Ey14BQoD@2z2frBAF5g4MWY6Ea=W`eOw0$q=ZAmo9BliNdG4K&S?W+k)jSRFe9 z&T95D#B4~&N$WYbk-IZs#}%9b5^^%=T!Vey+}IiLs`6?*rx~qOg~Y@=Y~oqI!DI$r z5-H=f^xq38YEJMxLX@_tHyEI0$A^HBJgFXx-k=$g?YS~;cWKN^iayD=dxL;aKkUhR5chSwFT*@XW?S!&$-2#b#_swi%>v zE_d0^Y_9Zq3T~|qg<5QV97{;wTARwlS|Pp>#B40KT3|L;N7FG|8!Iz_ri(NRL?BxR zW}HP3DnxhNnsui1iNfWQeL+l|ra@oJnkAI@g4}-Al{KO>UBZsR2|4S=t?-PP zYZOVCF~|xNxi5)-%^O5o=Ei3#r%0Mb>ANrX0OQ9CdHeg|+ww6|Gg8pj|D?pr zQ`RSs`dF_n5n;LASj}{1p*r6BeiV#8S7f)zdj;zx9&sY`3CH`1UU~<#ELF~W{&p(o zquZNLm*fOz-^*fnEN8Mci(kuu41&$Mpicslrh?#UiW{@5(E`Jx_<`FEzTn z^Xx_7(ys>Iz{nyyT;5!+Xup7uP34CoIbT~5cg)v&(6n3Ay0ZdGyt5cte_RHLEX<2P z9GO`K3R^lc;B)MuVL!cf+zBYtVHOS@UnsuOewVHGY-wusT$f-+i4)_o_6gFl?I7xl z$5ge>-$>HGJ*Ro`N`STp&xnPb;z_8ejoHfJBU3a{ha(x?$VkNPdm%TZtp8Re-rppl zwPIczd`T?q^AA$u75)9+4Zi-WjfISENU_?UbJ*_&0ngoK(F^t4-;I(a6lLy4R9#T3`|4A0K zU7M$Za6weyneRGKPSd!b>xRcO=p?@-s%U0JR^dz=e(gY|D>H)m17#>W7(dtMct(w! zuOd{lcl@Fs%f7m|QwZpx&{>aZ_&%KjWsNBZp2ZW0tI136Exng=AlHj#+X`NutY&ot z5$J`j%{5~?YJ|Jhw@-y#ZTx$VPpoDGiasimE5-Ci6F@-6nANUkP64&K`0Lsew{*LK zfOcY7v+BWd@Z`H%7crsL>6dZ>*jubgz0392?yb8ks_QJwW{Z^tt%(D=DI&G2CB+Wi zrTFFNOImx@*H=|L*Yc$AZDBx)6+QNF*{E(11Rto)9j8M8TG<&+ZRZjmUC3<>ES}vpA*DI5hCnJ(vf~Mf_;v}f%_>hGp2y@E)-lhdmQ&YKAin4)sG^>HTHj)P z64qx~r)Uuwm0GsR63b+=rdiw4T11i|KWxI+3zYlwy~Pu6!=goX&K~GW3-*$dzIrGT zve`LgF@s3KYQMLFL!ku`GmXley?90FJ>mjzZ#gj zGfpiOnl9x(Q`orEEy$P+2kV>{k}tcDrNi1qcjFMv7MOPCW4ndkHTy7)sGyh2=1H~N z+Cd4p|9mJb)TJ^~xds@gqR)ojp@AySYi3Miv;O|o`rc9pYNV8G0PBMx>>?=7XMNAY zBy|LZk|=h$X@N1rY=(+eBc|H(5CHE&?7|!m=JI}IdC2Pe2Vk6;uAWhWflQOIz3Eru4SX}`iAUQWG9GJK1@ zkC|@qki~plSeqO}TwOsP*>~|h3OiscG<{!9e<9fs4=c;JdgJlI^zEj7D^`4Pl;qgQ zbULl_Fo5?_jP5U1zpC0>&>4!Y%5R}r`Yg(Hosya=fJN=fTPKX^W}wcDx^cm>>H3wr zqLXi045>^{ZrnjHOtxiH80uRRU+pIfpv0{3Qck6JbTp;ZD|)b9U?rk%ORLr|-drzv zZh`-ly(nl1!X^Y_TBS3Lx*>;imJZbKp7;97JTp+0Kb~vVp{8kDh!PxA9_#ni=eVfk zL?p|41>EEh29kJ5@FOUi)biN_@{U0g1pi3lpwa>2+x5@^Jk3yZQF^1;^AzM6?zTeY ztT0+Vp946+H{ggfbZN|bDCE+7P`N9bo$WQ~uniEO0>@)}udI}>?zh$EesS3c9t~j8 z_AVXo^aBGFNnMnzGS?F~dV6I*2mf{exSDgcjFXyFC*oOkXb9i8`#J!rzvo7a&R8hn?%UsH3U2z}yhd}SYaKYUL zK}-X&13h^C_tAbyq^}p`1i@@x`x&E4>=gTOgKqUV+4y#waap>^q>A6N>zS$jMR>pyGpk%L6f20F-d4V=(^FM-> zWyH|1Q{7t^*yC*C43z9e12^1)yg478fxhS)Y0EaDkOxH56`g>R-*dVlx0#&^NZALR z#b)LJCBM`2EBS7zn0b<^Q&?sw9S7TMPCa&5H3)@l^x_Ad0Q7L^jf2jH5TGRo1u5e< zyY92udqoU0Ytu)sk^`pFW{FRXzG=F8U0xJb#{HUJKqe2khO5B8CQ5oFUz+wLK2NNX z7`Ym|t0ZUAkUpyUr5wM!3=hZUH3mHj*Nt_M z5P~?xhPg(jcE_{3MFwdg79bAa{~``A&a(V0>;6LW7x8CwDZ%FO8uY)?QTuHqe7>mp zJVXCV**bSBuDJ1+lE3`JqP3spQTr8(euv25D+P|CfSiAAwLecZzgGw2f}x`AgF;5O zXXxLowP?3z=-9Q^f3c1__Kz)Z?QJ@Y3awL`1P4M)K0If5;$g15mAZ44Ix2<|qQ#X= z!(~l}uWa1Z67!*pO@l2R8S&#EBG)-zw!E4pc(xzSWGO{MLJLqHNjGLIta5AS-l%b0 zLh?f%C{R{$Qb-+v4Mm?u)bO|}DD5s6GeD;SU0>e!5BKz{$xqA0zxLt&VT!Kf;(qKo zwWOIfG6&X#r%aaKPUn?UHn zR{reeic5Z}5WpFezv{p+1B&n@UjqufIdDFw3+!o@*C&UMk{+aQR+4Ox=%j>=dvtyy z+Dij*0UyWO@88%Z!=JY#3|2J%x+VF=$$s+u{`bG%Q0CAA3-)CH)1@%>WdF;@@pL=y z4ubHnVQrknSlA+qU<-KfXw<}!#jC*1f7>Br6T4spcK+Ct{r}SnEc4&?anxqGp)5%T zC)oyGnMJjjuLl|QY@h50Fye^rhbyPae}E00mncakq0I+dub-EkA1Q1rTw5k-7leRJ z0WB6}N>F-tel7;`Gw7H3d7sYDpWt8hnX}xvb5h^nnhnK{w(oIp02i-?s@na))M`el z;2wm8g|x|x4-KZG0lMPDXH_tar?5{@67A{4gZ3-~s1Xm@I=yRWHK-dBRcDTy)`y6_ zO}<`}Cc0*AmIp!jJO=W!1`)~(6Hxm)Z*EYnlMIv*XQS6x86$5SrUSCf%VS()%D-E% zG6QvH$H+EpJij$N)-vu>TVK6!VxQoXjj;_7eqy8U6y2k8+JM(9 z=QY76#-e1Zb3@&5sm%{lnp50JWRu3vN`O++*X04n>IZ1q+*R27JH)+$$D+M4ZSxfF zz)%|Ja%>JzV?%OQ2mBaZL=gON*~77Sp`0J1d}PqqfKjwa)xo=R>O@gDB|o%z(aLCz z>m&5aWr-QYu(Lpzz2)AH@q>VK(D*7{|gtQC48#LuS*_s%!eh&mon60dSMD8P;-kWZGlJm!jO zSlYWVYX197QvsWek(0oVTQnM_T7J;Oe5pkAn{X=tzW9(|eDOJRcF@s38WInQ=*NEZ z#pfJ4@FUIbyO?hzC319ZlFp>*>N~69Jx8CJE^q)y zDk9UvAZr2u(xTl+hJ;e@xp%gkA6F3=LaDaTQ@9dcZ0mDnb^$J6;AEa`9`u}|% zUjl6@{_&@{@Y%{3@R1SjAs|ibBmGDH=g<2oc;z!$p>rgGAu*aggcgp>d_Wu9CLza% zs#OQtQs8QvmYlp{P<*QU*5${R6?dp4$-!u8>f9;-(n6>IUQSe5t}n{Sk=~eFy)=U% zKFF5LvR=oHg_kGdal87#D1XIdqsJNTU{0NI5Bo9u)d$8CNr~|j{o#4%@lPk1{TD&F;~!e00>r{G*>$*IVGC zLa{v=NN0(v208la$$IaB2Ee1!93iG{^1dVlm=}*Y>X2BaX@cuLK~PnZHKj#3pw z;XTD-`|hz9PTkkd0To9o2ww+dAi7!jaY5Oi&!C36czxvz4G0e1zizp@x)5$^jVvuY z0pSorAc$C7$r)mE2A&;r&fd`PhS!q-WJWEwa9ns4 zH_W8zxY~fXkV6K~L}5k0-{4Y=>&{L~<&68=w2XK0&(htD$P* z!E_1oR^y~x8HX){R2(601mBX-vCydS>uzh31?@JJ0ZDJ}bxdTnnyWjAa+Z%kYlqE6 zznKv=0Nh_e(D%NYE%KFsyaFc=*Zhub=0K?zRxf2}QTE!GRnlu8{D^K!0PE!D+6sw& zg%h(_LHR1*jT)Sl8%NxTR7YQh@R{HTk2kTNcMy9(f1JDd$~kA@TLQs%j*T}vbBUo3 zyidNIl72Ov+>i&4r_sqUNuZcWinu1*sOic%kPeB8^GVTrwBh9_e!oM*igDqr54v$= zZ^=c5#aj0BW6WRE@jbJmCW2A+`c$=L>R0B82ySXT&kCyXculI>COi;&S-ItEe>SR2tVDf8;lrW8p8a`X~?BY zK*{FuTW|=1)8AYd3ZP}n+Ad?Xbu4$g_@&C<{;V+a+b65BL7fL zz+u%VwRwP~O%SswC(5|Zv{Fs2?U<7+^}VkBr1*KCpr<>@L778^HY2?yu7V?74*53* z%lt_M>mtw-qYbL)Gd+&>^A+ZC8(G3(wi1&yks25-fs)g9!((q$h4&X1J3PsNRV%Q% zXWV@i+zWK7SL1q7M82?h7x1NzP;w3Hs_nOp9d7M)rIcy&7k53ZRwK2iV?Gd=GqEy> zzPgjg1Y_g`f$lETq1*2tQg0jZ7N{T`^f}TZJLr32gfPbKbTa3~J%q7mbz!y&L%QJX z%Y{BMC;&V2ci?s&f%{;8$`%X z?i~pQa{ypKSpmDJp^kO!36BtsJY!E?Jsuz<3^{pQkrfYKa9_s5xj;!tW@OjkzLx{( z7SBzt6c!!j5ytJFCp5$+5yF{BdH)`r95SAo9m56#Q_IeE-fy$!x#s@-$n(kc0{qF8 z3^wXcK6|fz-ia)$$fX7|yyr)tVvHPo2>@#@V;tSlNWhTs%0oLf|4j%}%=5N+`ws=< z9|*a#XDcpLfEEddZb+_l6gDF-9U4j2$;3|$*L9Z#$yFvfomU?xWXSHz z?IWFC01?G{DWwcCbGoA-vd_xJr}NzGt{c$M&@y*F*V^WK z(&1uzQ8HOlr=GalBb0{O0T^FH#}XP)rDD2Qdh}z+@_Q{wSZw>8_A83?x^tPY4n9m- zTN+||hFTtOxd2ykL|Cyr9t9uf&F06nHF|lV*)yd_59cW^yv-)k0xjx zTBy;<-btZcd7$%+)`tecm-T0mVu`|LDGD0Y6iLC2gQJ4M?+yGmmz!^u#x8ezV#KC% zLrYu4e1=6qYxrWk@63`;q?dfuXtKb_J<`5s*H)RpjGkK~(dnHxh)}QWFJFrrp2dE^s7_>Hb=LJY@_VZjkI-9*U) zXFbA;XFOV?sT77}%j=)432W7i+`UfC01S^*K-t@q%1+X~vX+RlPgm}`FVxBRle5xg zeq()2(?J5iIVkSSMH4TTpQTe1z>D!c{gFEUocA%zcv02Dfwzwt&T=R;HVq-1N)72R z7tAKq#weL&=}jDtD~^R*%Q5HEJ>zs4isD?%Ta2Z3IP%mc&R+H9g;+V!0N=KU{0M%- z1+VEG zzZhw64^xvNqj2hg@(@ti?V(novv1JSdu?TVR05Fg?CuAW)KO>Fx42iInrUZY?y8qW zT$k%XvYErdnf9{I=Xua?0yBp9ymak3I*$%6N(-t@YjQFbz6-tkQK~da zD^}9Hms%SC+v}u%^BRZV`usJsZMbL;VY#OUjCQ}LL(54nCtREYwcVSJ7|bK4 zN?FE_5EFTX1;-|BtuNIZ_m=}x=o`iqlY>=2qcie6e{KZ3=}^#_3+<~W5_CGlbP*87 z;AhHx)c3Qx4s<-DJ(pYeziv_4dPZLhT%Hx>9>Gt)yPm%=8iqr9@gWm%2W)R})Z$^W zgYBCq;og{Zmg6``+}I=v_L*X_8Fj+`K#oXgHKGL&u00ipN>CFK$wu|u!==x^0EQz^ zKwYvKfK~bVk6gO?52xR-xb4Lc?!zw9Wkj_t9|4UHnB(=$<;|vt{2b`9Yx0=dmTI7j zVeR!684&^cBOovEPan$1yLXD-Xh`~y7T$h8t}Av!flBn{2fX9Y-MJcc@y26HZwOAi zoap??q~S->byB}qxOQUVGq3Wu2-lW>+Z6gA4~~@_)@ZhU0AG54aThrDt|_?j!R1g( z;V`mLsCo((9NTNE-*ssB#a9au3KKXxp+K;WZY_2JQyc&^od4#fpTYWz$WNY7=D{gg zp*I4UhWk(v0--Q%4zJCh>#~1%P+lO#a_8cUbHk)e&>>RX6My<~&RAp2*`ujN&vQ*4 zpy(^^eYf;`hbH-h+v@+FrC&zH;U9&9JTu6HXflWoym{SJHI*N$;XKp+7}_Lb^7(_h zJvrL_L7o01AJpAS;9vWoegy#k5;IOeT8akTLvkl9fSt-Gu)>S&oyzHXe%(M13hY|1 zKfMC^hV!Aq^P9~!xRZ}@O`m5Q#H?KM*xI3pGL>$=u?J1QM`pt9(yC zGdjM=XH1rRVTHGWQ!=Kxp0lNnzz6B)ShrpBnLo#p{){1<{GKKK-@hSdqy;^UcGrl# z-Y$v7x=bYUL#&dG&hK8&#sLXw610<$u%D8zb@xva(h<|+QI}IxaFxl`G&9JO+yv+X zr1q-Dz6}?-C1>iH5iI6VdJmjyYhm~<3g4B5PUIMmYOG8Q{^rTtai!$*?h>ei3nuER ziZ8C@Rxj~srt8)Nw|3}Bt(@!K$&q|{CKB4qvlDM?Y}0#75Ex=|1-p#?m-i|76l?7= z2P=^Kmz){*o}!P?nC9M~&;#FX!D5J2ht7nR~rS zv6yMutULb>!Aj(M-rPW?JA~p~#`~espl9-aigyc^Cfd>k6<292fPXF11G9fJvZ$d+ z{9X8d;POamWvaKv@BCAXyQ|9!gT3Ncot(B-Ho0^Vw)zH9HUt3F--Y;uU8H_dJ9URy zI9w#0e`!NKh=1C2?4j|Ua~H$!zw|de;LiQ<(X|JBPZ9^b54{|_=5wr0q(K})W>X_} z?|pWRgXbn;n~?+6c%MHh=YyeuKuxs96|`wI5R0HpX|WOoDi8<<#3s#G($+)_(hGrm ziL02xZ-C&ds&e4))uYXi&SY|FIYi&3zlLyJYvn@R!zUh#f)HzQ-@6bTItIhrwDzV3 z$x7h!Xv;dc(!w(&h#BCZhC2QS?+Ow7;Wk=1Svy8>04bE3$LU;@piWvqG#vc2 zTF%58($8y^Msrri3l~DAu-Eo3PKG-S9l<#&sG?>f&!-LQyOgL8j>5|_1|tzU7Ss`L zv}rjwpnRsD@msd|x-yiWBOOLL_iRf-k2RbfY|m*tf7JJOvxA~pt}Pw8?`>y$-|<6N z&Di^!aQV4lUVhKaRgC$DJ6y**>e>S>#nMPK@OZN2-UPPLu3#=__PXSX?R6XOIPi?N zKSW**+!vxC#|LLGdnn!wW}6mV^0}0i%XCdUm0y2q4JDRWt}P%z|8mm2C^h{D84b#C3{P zeKzvGYFwz{Tz*LEYQUk8v>+-JzqQ}o>L4mAscb#oD+!tjSskbj>N~=pgQ32rcD|Ob zESXLSf$3BQQ`wb89amzdxD*9(;)D^Z2)XPnio(aqhcy!VnjqRG67)FTwerpGEDN<& zfhmuMzLx~U3?CDuHqVVT1vbv}Bg$}#qpvCJ;Bo|bwCUGtA3 z>My3;9(j3?HWcr5YPY1}A~hjBTo~4HaTbYzu)~C8kOJiA{O{}Ou+i{T$tq?A1Qo?{ z@>f+U*iZ*Xb?Jdk-nn;uvBa2|aMe`|OzmW=u_{QSjdfmk5%0V>uX0g3f0 z#iuSH?{JnsA$(yVHV(&7-lfLnA;d8}{SzQ@b^U{X7LfS+xeEX!-c!?7acVge>6@y@ zCEs4HwVd_nZR!o-n)W*TfR%oWye|V~v`QmV)Kn3}2L~fqZ9&c*in2 z|1HYgwx+XZZ8@)uEX~qWzH5MSCBO1q+Rf0Ku8~tK&l`NxZYRihPcZHw%-wW9fvV~L zV6PD$yU+AfzrS6cVj=ejzB^CHbzmQG%)bs+_sb`fR6%+vy?&~);=_~q64J95oC z@41Vvpe{c*m7R(S!1kCwybp?eI>i#}S7RzBq- z!Aj$I`&0OS@cpjI0S?uE*5t&sR%6f8KTr{)F;v{+tO%Sbe5q&a#lT{-ijI{{+KZHu zCzhR-G~+=tFf`5?=tV#%4RxFeSrTm0K0zY*|_|D;Fus-HTNJ=c|VW9+F7KJNZq5sho_b+2mQ|A6Ad9H=;1^DGT59V zccN-2P&%1A&H_nxyGC$n^*V(l=F;OhF%05)+@nig3?q+k#6K7bGe%d9gqv3ojYiyT zfsaPoj64{9Vn1Ot7=$1ft`=Nb%^DUX-JGWg^)_!G6ZhqW zP4G?^q2IMm71s@{@XjUBie5ULx~J7^ zvLfr|>CD%x*Y{;rFozz>EW%4D(n9EMO&%!|d;`q#j}(67a=4Y0dh{wmcwwS=%#miH zgc*9W^mnrRQMVfv1gDRoxtW^l>eS@lSC?tC18lzIqF{H&)hu|4N119zjtd5^$w3V0`-%n7JZ{Pd;y$AL z_fAga)vI>JMyRde_E<#X@<7+$D)y-z#x0u7BSg^Kjh2+2{=hE469uNYdD2rajV_m4 zTXduUB*=~24A)8;e9Wo{Z{Gbb3+XeMzC1sj>Q{ zsOxKLoMAYrr#yl*=^*W=-AUOGWYEaMR|y#(mHP*X-U+?EkAco^8tFfAi*%7uqPi-0 zJ}6#+gI6P|T0QH?O+SUW+j2Z`O>|aBPEnkIvSy8z0Cf;*aOm1bAPPr;UAe+1LW1)q zO7G0g$JMvv*_j!r^c2m*0v4~sgznIqt>HapXb(6>MDW(&p=w0G8z<50JLhha_aVv_ zqr_zA}F_0Wi2E= zEEpNQHgN`%Xcg%u8OWQ>76`xVyc9F*1`3P~@gL$^UBOXkrp3mdLF3TK}=mwqzc=&fOVa6r7Vv9g8! z5%>F3CBD(u;}`jOue*4a-aZCrd687Rp}24zRbZr^+5X-Z?V8+f7E#a!FU%euplRtktP-86^6Le?`rIR8W$g8cXpOK>Wsz|#8x2U1$5+R6xLzi39pAD2N z!m@`NggXP*by>D^1-(Qcx7lzZ0YR@*vyk<8vL>sMl4l_N#;*#Tqb+3 zBdUQLhvP21wS1Btn&ACdSM@C)8Y$s?yGY1^9Y&+0z$SSkG@oDJtQ{IIK|2BC)}XE5 zZvkMVs=bAL1&<*hm_;GvbNkD+XO20Olif7dln+?GNspElh(E3ypx0iMOd^r_?|}s%r;Vq9{Llvr^AaIYS(tfpC-Hj-#>7cw<38W&6s2cEr>9IGZND z{$+gK+jAO12wEMuf!r1n_fi>gn*m7xrHuSp;``CK`_JBeXG3yH$AjgJB0-}T>0|L?=(%qn-h>A#e4&B||sibtHba$sT67PU|4(Hr+?mg%J z?tAb1e&#>;&fa^iz1G^#BMgP&(z<%0(O(NNbymV*=##9T#h!4rsl~%*(ZhN565W+b zq~wb=dx6U*N*|PDnXL4?z!yGt30`gKR1-+ND;$7VH^p60-g&UStK!5j84^41@vgq> zn}@1xi$+#lW;2SUx#aQWE`n62FiUGV{tS^*XN%7|8hsuo&Or}f{!=lZAYZZuC7&e! z#8m%bq9+gde4g)!?9nrChU24f;ctg~?3TkAX50?HV4uNg&Ze-5DgsDa14ttRD2D^6 zDgvmF0`_qN=`#XvEe9|w2eKRmuyF<6c^k;S97ubv9K`Jz1ZfSr9})DZB8cTEh=(hf z|0qBpBABDqkD!%lln@k&15$y6D6@p9NQcN9hdg~7q8I^E84gj*KvrY`X>)~YF@zXp zAZtW~%2tFb4u?K}8*0K85;+xWsvKtM8D;?ru@(t?-x~JzD9nZ{%%LL8`E8g}M7U!` zxLZc}y9{Lf;owaf^kf)vA`W=kAtEv&BDx|Xb~qybC?b(KGMOtfRXH;KZDeLdWOhYl z?r>!OQDh-;R73F7{~Dlk(glOfMrjz zQN`$C956{_LTzh8LTy6gR04!Ck%T0XhC8v|GqEZHv#vFfX(W;5IFXGckySM5?n>hQ z$Ry6nqB5CZ5IWI(WMn-amk8{Srxue{<6C}9{ zqPa6Fxl7zRt|VCu^|2&2aWbOV#1-IGDEjVHdPxs<77NxY6kCP}JTry8o)2E>$@{8| z-cyN{1;NVdi8|fFUI%0VzhTc=WPYoN@bfB2YAsNXEP$-Wk%&c-s}@qfE8O-hj5jW1 z7%faEPSG~UWtXsg4Ib9Ep1~iJrZRZ1j?Mk&gqHr9f=yW&UqLW&`6TF z!UD*4NccRQS_R6MdskxSRq`ydMD0U~22+VTdZ{K;nvQCz-n&xENYJ`y(O5w&A`J9x z8GX+prHUAd{)`AD`gRhBUZA5_1pkSJj%xvz8 zK-G%ul_+p)=>%)mOOnJ)7C=dS@f{oUSW)c#T5v)4z$@lDe#tn$-`V+CS8qrqvpMFwLr%sEhp?S$0;76=htW6%X<( z4bc9a?&7JQ1roBCS;WktXTlk$>|+N9dN6cX@CZ7twoTtux18pM}xtspq6 zBlJT@s}HD*3y?1=eYo%h#@0EYCO@dwIrOn}WURCAq;vRT(d)U+XN(h*J+v!5_?W%dn0p~!z34GLgfYE0a(W5YdvQ;DK@x2We2Tpoou~nyZ&iK1&3x|> zD{028qyKp^S$aoYZEMGVdrjJM6q-yU*R2$thke>=eVXEZPt5ytA2uPWwGnzXbuPC) zx5@e1k>nYj5b2YwqMmdemt1!i+h?p*C#O}9xz#{@!07#eNz8y*)xfjy0WI!0IXB#1z`u6spD)n&cFM-Bh3<2V(7m-c*nsL-+Z5 z)EV>4AotAq`x$D#89MSAre`zEu`{>MW|%c*n6PGVYs}t#Hp`wn!&W^L;5pe!$x$%m z&q4`9q=b1n&uxq0h;+?~`HiIediAPtNW?zuj{Xd_yYaMzwAW`;VP{sE{KjglpoZR@ zfz7)q*M)Q8MiaYtBl4z29Dp*&6H|=^Ysn|);ft@UeQk3W-&8N!O)NS*TC&$za(cGp zcpkg-ZsNh)>W8lg7CL)j1U4iuHv~UAdl4@^)WTZ+gey|O`S{S|AvV`aL6IXWA1py~ zE?$G)z|J#uLp2Y}ppg7it?(-Kn^h5du1fON(pZ-|#nfo>WkZF#o(*(0@iGmuYmK>U zoi9e~{BCUFtDFc+HW$%AcZ@%xX}A?~4t_N@_M>;Prgs^{>ECzQ$#`^8ejYpd$yVxFwYwf+@=F-=(u2L9|j}Rv9B#pMv?6<&iTNs*V8eN+o z5FU*4gAopmOQC!RI8a?_?An`_)*eP@7Vf3BSo>+l^SbuVfx5eCU#W(^-a7xf$u^90 z{`>~;vuci(r^_eg-X_i*$ct(RBvonLRqyPxJlv_l<Sp@*=^!+`U{K+U6I`y+5b zg@NV`6&X>FKqTRCimpK%IVevx3-?qBO)?HZ@D4zepVOGmeEt)kI`4j|=C^X}{j$7o z6;k^j&%ae~e$%fxs$;c}yhf`fKqQ+F@>k*jK|p7^_NqZfRJ@PN0LN$^EM_i3YUfFM zvimOuP|hYP&gOW}7V?xuLeFOW&sL>GS2WMou+KL%mD!|D>ST7zue(aCq64PDfL;>- zlO|Mn_}eu-aF$B8in&Nn7eyGt-U;TRp_C)7{XWW=EKZ6-mdZLC7Ic}FrVW8nwa|(f zf1xAfp5{ofXV8K~EZ4h@U1EYI=@>zKl1^jqdD&Enm`AQ83M=xN3OO2$kqWDdx$0GR zIVMuedBNvrr-iSX01+}WIE=&mV7>>%AnKzJMtR~6Dtr3_Uzau&fvjh?Z{_0~CwM=J z;m%Nx-hI*0%EFZPag1$8w-v_o8b#u$XsIXkNz`rM3fc&3E%h2VGSz*vk&<(BUGx4X z%O=e-TH%0v5es5!RhZRDh+eynPcrc7TyX7-jw+Z)eiuy-getJgU?y|&o;Qe zdAHjmd_AUEM)*z$K?)I160U?4FY>)UgrSpwyUjhvFFxLhQduKsL4}4qlrh}f=uc}( zzNe)Ax@x@&Tlb`>hI`$!s7w3iL&AD(INM2r_?|k00A5;1sftNn$$eF`vi?%lXEl5G z$0S*2O4MF-R-^NzcP zx~S@*Q;ss%hB6$&A~|PL8Qu1EJUIr+byHc~LT3F1Q^WPVpX`^8qgX zTj-e*Aye3&685@UR5R8dh5LzSz({LBM6&OF@ieR3mCKPa3#~?qVW~FfCRriXDkj-w z1C^%f5q6Q))+QL0W<|Yn2WBOfyKl|QCimOOWs~p-7K2uwtr)zhvQ>Cq{+7mctOk{C zEHl7*_rsRDh_R|=GYEC3s-rm6(>TEc>w!sn98h(q;{j@wNp20{_-eNp9nUIDv&4zz zV83FShK*rZmG#K;GM?9CuLrAMPuL&uyqR)$58EE}zjHE~rZJA6#4BS%PNNyGX>uzj z@5WR&?|DRQns>b-k?BIffuH`@?$-|%a-r2;?}P3N)$q*DrtvN%glU2$muhO3$Uhct zPMjef@|+7IOP(Ui@0%&quAS!D&67rrlXKR+Pw8Zk?ZFd`q=wNJIGxiRK>T<%3S6me z^R9tlPP~%kpy0zcm z^y&KTiJP3&o=)>C0UW(c(P{~9eQl!% zr2-VK>4e^T;f;9%m0B3;1VK*}ka&^e(dm+!Mup09)FKR&J%nS9RdJS z8*;~yhT&woRkge>v<%|R%pflZ$*<=K!0`bJQzHA7&%~a+X%sr4^h6q(xsHM>^O^Ag zA1uxMIF&g%LS#%AdcFM_k^KDi1KwM;}({KAI6b4UspYFXet=^xUzkX zANvz>wMQd4b@Zy{SA2lQ1iv>qB{Ja9tIIB4AIR*RCX~!F2xQRqHUiZWE&$Uf1+?*z zMSZk)*_vbyTNAG}Zn@rz*2a21^yx+uHC^`uoeisE+A{|lJRvw78KA|5IOPJc=E_7G z3r1|t_(HosB8Z%wcymqxfV1R?qu3TmpoiuFgq_RN(ZB*}5|E%w4}pP<@AZICBEj9; zuL*8HA8r>|W(%+JsbC4>VxSf(daa|w*E;kVzNVpgP4Rft-3oVcK!!*YyE4l}uR<+N zkb$3tv)z#rQdH7W?M~$5ob|fnK=EI+Lh8pkfmA6t= zW`oIt{6=+2aVmIejUBD=+2qgy9ewRRlm%zY${^nrz4b!Q=Q*gh)?S}anO>Dejc+!U ze3-@DeAPWVvDZ}gQMuX7uBNHs>sPW5l2jJw!_3GY{t@a$^^dm_&4oI!Iqo*JKip=O zQ=8Ep2=n+>WtkZ-_(I<@D78tBK3X|y%vL8n2C|O_LTr=FG3e6n075o;Guq?MZgmM} z?MS~?>Ej)Ys3UwC3L9^*z43%wsgG`Jd?;&*D(?E1uu=<9ub4(h?qE(}^{X6CQlXn= zT!OPj<`~1KGb8GUn@Bkd@hAMrcUs>vU_}krt+QlR`u&DUQ;1lJD^*k0MWyqG4yZeX@X15zf0bpnX zP;><)?&VE>T;<_C?rXQ(O__YiBw6!q_~1PDpyuHHmLsq2^!2#IW)8cr0h31^>Jvxw z#HvhYxbIcVXMI$STnTJA?<)=QgOY5dfGtd?1rN_$w3%=u6VM)*%RrJ#6YyzlGa zI)q-j{@q2X_h*}v=bMAPfHhu(lNtbfEyBZEpg=9Md@TxfEvh&a%?Hx{uDZ_IAGP&S zFg;>0#GT2LH`K!kAw6Hll9gf`61;?tiHAl-iKk#u4-tSl;)H<13m|3*iTCiT z#U`?a5fOL?1Ne6=@LKj>G`9S-KKyjI_!$N286NV}XV>2fu4gvm zznxvn;schXLT0gaM?iC^MSr;c*z=q<6IoFQv>n9VfNKKk>SN z50?Fw5E}T|8&tR&1mqh8^%{h%8lJc`2nRQaBsYi_H;6Sfi1#%}%r!{vHb@~gN)t57 zP&dl5H_8b#%F8z@=rt-@H7dC@J`HYEPHt2wZd7e(RO@S0pKH|EZPY|+(jsWmrf$+< zZ_*WL(vxq}*K0DcYBF?bG74@oPHr+OZZd6XGV5zHpKE%y+w>f%*@B?ilDhc?d-F?y zW-IyTS9;CXR?V+nn%@LBzfEqoDQHpv6VL z#Z|Ax&8o%SrNtw-#WT6ZtGLC@yP?IWuf=z+#c#L8AE^~a&>BG98pz%nB+wcx-x{LV z8fw)V=F%D-+!~SG8d)sTQqdaS*BUd|8oS#Xhtw8N(3U{mmdM_gB+!=Z(u%L=xv_)B zD*(DJ+a?qpz8=w*)zIc|9FslQ7Acry)f!`<8=H7^QxWed+ z17HIvfpeGRj;jBw$=QEN3;QD=PDjNL3C{0E6aLH4CAPhGK+VuyZP)86!U=9f&%&qO z$=!ygJ#K`CYl}ky-{`o6fUIEND0NR^K1jWsaMjb4$4&45sp=^>;B$`)egOCakMQf8 z>*{|!Is1!D@jt}SZ8qr!U{8Kwkw}$}XKo#1sW`Ky+_K)tHa zf1I|t%Yi^9`VWk!e>M#M|CJ@Ju~qXGE`!kQj-APK+*BHUz&WXP>U02FpeWbWI!8D! zNmF@%ifaUOM5YvmIU%yr!<-SJ^l*0kp8@c?kDRDn7juM1d6~fkaY8cXMzg-0aO~{A zXDH9#G%EX zMfvWus`mJtAS~h30qL@PW;+N8}CTC|B611#l8_C&KX6CFzW4NBO6(T<#2@ z|AzVGv#-(ilgXIrlTq|T{0J@>cX%i8-D@Q0ndJBAyHJnWT>Gb=d~?*DR}{NL6Lb1b4AkTgt-ANIUU?_{#-RSG|G%L z(lTy$eVabSue$#;E)aSq+dUTXAH3Y-ohJ4aSkYqOaHJWo0h%B zWdug91rYh_EvM=qxBQvcDBwT6B$+lp?hcr4R{aX0Q9ONuBP+~;tCs;HC9xf zI=|t7KG?z?|4y-GGbCxwxa#V`nFGKC^dc-=u2SWHoeQ8nalCP5mC`i5yRG}nD*aWu z@h=Zfjq~rQq@rJhcx0-VZ?Qz}ks3!Xc=`hGSWYjD_F7f-9{8jE$#DKk**>{g?8&t| za9($jP}lz~7f27G|Hmh%ltME-pRwQDoPL>p9z{%`!*>%;eg;a11)K4@J~DvCe}|kP ziSI6<{7pU%tl(L|gVI0JJ|4wupztljQAx3T=)y{(%KBEaspT|Q0Nc0f%xe$re)Qq3Etw&&3x?8^4mtj^o1I{_qt|q()4n^~$o4xh*67;FP5m z$!Opkrprw4uZLx2JDoQ!GZR~S$wWMFG6@Mzk#uRVutWp0QSR z!iv6L%pc0yLq8D6=1|&KI-pzTL4zw7C+ZM2ti6z$wNbftRZn_#l>$(2ZCyw=w(8L6 zuB_7Se^J&_AQ2W$hDexBT%P+*<&Kg!0zs@h{M1^>iImwNFWeoFi&XpEwWhYQca@9Hqb)c81IpfifRd_dm(R2W zT~MvLHf6e!#85R}L-$-F1@t3-J_kCds3~DS+PO?7&JuWi21nZmjZM!)Z_7LiEUNh& z#=modd?*J5#>#8*t6WQumyWyzf2xb4gQE4@WP(y``~5GH$jWOo0{HyGqGG7vxu!Rp zxP3GHJv7C9UU;}I8V~N!Y{PhJw!(Y7CdONOeb2_IdXx_!#>sAilE(9o6*MwZ`1Q<& z$(b~;0MLKOG4c0ama#ILDkB&P-~grkjIwx3;bdl}ezGAZ{yjY-fBOOEV5LHGMy}N& zk;bQ*K7s}!8dnFvvjG?YMZn^ZRdkCcKmONMFb zw733@|9>$hRSr6>HNZ<>{%$HcB@vY`MMyweh>0xQYb%(TWy03=ztB!o=i zON~>$(zYE5qpG=cvJyg9@G-+85(p-M{pcfu`6y~h@UtxC46{i@JhXH1KuBxokR+@3 z$V}eH!>`~#Bg6ixj9|F>OhEkWYTUW~S^iA$o&BM&{&spWHV3EVVEChLpmtd>Z^=}d zD^Cpu#1*rX&6qT_!@ zu0&4P>wfJmkbJ(yOr$KXo{c^YnWj#4PFzA+YhC*P?c0-pM|68;RQwcS#64)w) zR!M3@K2=7%nqe{8Y5;CR_~8n#2yvkhl$R!zis5n~W~iw6Ea^n(S{tS6ladY%G6+r( z3Udoy4z+`ytO8&=nwhk_3ZlQgWtsl1_>V3ZhRV|_?VGw#oKZ66v};~ICz)a{4J4tS z05~w}OEK;By;A9+S-Pxh+NITIe)`+h`rk$)Z8FsS+ ztB?cfo8yxrA<*ZO!;_zfDq+D=WU#T28UTSUoDR-nh4-hRhK0NOfwZBm>OPeBhf<<) z`-NqZgfVcE0ykICE;?PcaYLq0& zco3c$RUkA4Zv5d1v5Ac4EhQ*!)z zBH#UCcOWYqxc{tKvif9yb+ZQ0&GGzuWXE>&zR+p?k%^;&rG%XHxS!O; z9LDFNNI>v#0d6kyH+^P408IW_r)}L>Zx`zPJ>;Z^oBjSzKoEK3kAmLFFC-kv1>EW- z;>2+K74Y}19uudk!g$J3#c?{7Kb5>1{vzwLAz+wfUOJjk!i+y)F_;rCOcfGbHg4vMWxK8U$NGYGiyQ{fM5W8pgH=u|z+C!>td<(|SIh zoy(Yq!QKD`W&HVtr^3h_xIs^QWk^}*DdkGVjS>_zXx{uF|KDgsy%1W{M|jYt!cnK% zWGyq^6#9WM9~8krX+oCog^$B9`bQ|nI4~$!U=AQi710_XblYRBiB z&O({A6yQ0UX?F25WjN|o$Uut!14*ALUkx6?8uSxbehttpM34bBpt@&j)P28s1^NXn zzYZ8Qh=P?~4~R6#H6n~KN_^y~!cd+s_-(Fi$%$T{FIb36_rtBW54nLtD|)x9YV>EG z^PSy)7ZehY_fR@)aU_xjZo%x>`h@!AV}1jc9L9D7Xy*gooA<_R+sy~&i}5dSI-9-7 zrOyoe+Ip+(W0Wlob}j4Uh)T1a&Z3fe^sa{ox6}%;ahG;nNwC(n@r2Sm5+9dQU)pme z2(HU2ncp*I)y&x&Pl;#yg#HDX1+gcl$NtUVs>|4X~4Xh`CyDRl%L}j|F`7Y z@!V_Yon>YSeL99r_BRa=q(EqWR@2!Pe7M)ZA=5pyK7%xJ^JBxZI|BGnq+NiFmIm?I z^>yZBa~EDDm-jf0;>XJl*S>MDRd+tD{fs{S?AE$RXV<$fyb_v^npJ1B-!_BE{D16n z@)WH1+TQ3^hk!G6q}X+kWp~}Kf2(rO{M7%|p8Jb5@4G!0BLVG+a6Mk+cYCf4jCbmdic8xW19K`QV-5&~00>Ed4$;+J8{$J+|myF0i z03j@hI^O@|n~!|PkDJdch(qSn-$07srwM{o_l3RdUwK6SN@oCjeGsQs!RZ+=J(jG( zmk$|TwReI{NtDkXv7B>l5rtB60%w%6o7<$~WwY_!YCB0DvmIyQ9>oUrs&`{+6Q91F zU+cH1ud|=|g6fx8{r;&cq64(Jq_OHW<)9dU7ui;K_Zu9Qul1@XzKlYk8Ut<80pr5w zgCnF5zxfz6s<;vfg$Vxeh_DGy@ZIE=*YTjY2?p^qr7k6kC*Tmw^4*n{*Y&-#(1Pd3 z2ImI}FvZe00qArZX8nb+nq_>R&@NN+&j=@X1<8MYIv+yMI!qm^_NY%MOv`{kloO;r z7;qmY0MEcpGw=;1U-rWWKRA{ip0mELj*t#OEEa*qy&1XQ#YobLZ)Av17);OSjn%gV z@E7vxNy0GCpz==GW{7`=YH0#XLv|E}r6UG#J7lCv>Mti0BY14WEUIEnMmhPtgMwZt7I^j4j8nX=a1Sj zJxl3D5nA9|Bnf`Tw~E)d0o}yH+5Cvs>;0_iFjP#b#C|yQx%w${@Dv{+sk{XrDupl$ zKM1>T3xNHkW2*uE-1J9h;2N0{toerfEj9;;zuDJT`n2q?ZMVug6jiDvf*sneyTo^# z(I=v3Xt@`Kjk~!9fV_Lg^#5M~DdS|7OnccU|0Qw7WiFG;&#bznl8IS}H2}=MUlM+S z=)h4-JAvT;Ao)Zr0*Ftd*;PTXv#1fk5sXy@r;??b$ArAO-^vde`gG@`!_y1H9&f2X}FrN;g#;0$>Q-xf${H09`fbaRsL0CKV6CrY%O5f4A( zyCQ1Q<2d44!%6AT{=0!5kkAXA=0*CD>RAuRFE`Q8`mhhc`zE@+PP2a4uJyD2q(^Af z{g2-YlczKvE4)ut53Hn-Ru#4ZFF?fm38?SE(>JKJZ1_ULd z(S;LvGQd*9;g{63c(;r4-z9!oQg9slxuk6+3s`YZ!jz5JqQaC@y5O~%TeNSJl~;Kj zxsp$pYZ6#cQ<_Ry&@r;)o!=>R0nu40HY)*AdBaKRKx<}VL_x})lJNm|3cLA#UH-$0 z5xFS;eI$1Pe-qUFlv{zCD~=rnjeh6SnC!k#)=Xxh%{2*@oEpYU!!X$;1y;$HAd-7L^ptA2;N(UZqObB=ZZ`}R zCV9x*p31pWeczVlWN#QtmoB#D8&ztM2<4A*e_{Ew_l?K%K~R@RQ--x3Szr1?dY>78+$!f{EEhJ<)>! z#A%|teRDTW?7h;$_?!vl>G|BTg43biSUpBbuaHGy$%rzHuoOhCOk@5il0IX;I7t(k zkTG*kSOzeG+aWWXw$DVx=E4^O5F6lzdnKa=?dxTqZlfo~_Ij=AR4mwtWfvmxjNXQ0Dn8)QBKC;k zRPDEYOS}WxW=g0zMmf=QM#jAb-Pjoa=tH5a}iGqjp+A2R0O>Ev9@-hpTJYdhV4P?gs};bq?I<82iG zu`O{cY!@Se|v5Rdv<$mYvcNWdR8;6DKz<)EV_o}<`J*)5G4fzJo6HRrz8!!W?gdSdI z^$nc2U4I-DmkE0^oWx)Y*tv30TojoJPhP_k_}tM+MQu4*sRUgwpzc3f6?kS!FzVI- zL`f`mWj1}W5TJ6R%W`09M+ns)C+x*P1)Sfn|0b`vO|k}^5778eDnkf{i%{1S)E{Ww zf*%wa{1~JcVxb=pyvdqJ{XoKH>k9$r>WFCe*7YCP|BCM@#h=%IZ#ZRS*Fok?JWHcf zC2MNnia$-aGx(8rMp)jrHL(WUdg?)ImLRX z9!u&G`zCzu;pY9UY952;4QEq#-}m>_hjV8ZW4lK*0!L;k`$V4w6_gAA?o_-$=O=JO!F`OIn_(!0fO4q#qjzu#q)P|j z0HA=`AAc)>(eqz=2h*1zcq`5yAYiyB<3|UIp@86rz~-x7)*prN$Ot%A` z-ir|pF|2ZwMgJkN`B}RyjEMAVBi?|>`6^X zB>QegINPvbHt4NqDXWLE@l-Rss-t+cIX&M=X%4#9*`pwzfDlSW`O1Ptau78MaF5Gk zv#vY-5cRq6U!2tH2oe(hw8C!SHaW5UlHC^8MrO zS9`55J+G}Q_+>W0G^73}r*#GM$P~_Lr7}ezS1Z0V9rK;A`Lniogqi-{yT z>ofiPgfkDl?^($Aj~DW-uFssSoo|xv?lk!Y!f3P}la?a?qgA@I&Lc0j+!fAdn*neC z&uZ%PFFU4@?Di?j!PC14p19U!4<{hjj>A}P-I6tSbNh|kqmvY>7aatR0m=8tr(gXo zQSs770NTh)kSFK2!pV$-0|KO<0&S_oO^F{p)dWUa0uuQ#ZRBV4OW%0lJO_#hM`+8y z1pK`&F9-krP}N^X7V8_vgg{KZ$uE(`qBj9x8EzccynEce7GC65@u`7$NG9p@dm&G4 zjISblGvION;CFEb@r+E~;|H?WtR-Jd(CIp=0YN$IbiF^y11}`wfVqa>Xx&|gaKCH=@D}iA<7XRiLKC? z@&-R%6^S7VW~8?q03PhbMlBBw-#1~NXbIsOwA7_&D)+5L;wRqSB9YfsWg$<7zPN_h zrz_5ZN1&&|(Y7=b5LNP3&TN>~bIvH`@W5L`@{uu(D3Qhw(K9?DWw>Z&!bQ(UsTm7b z=Ih>%&q~`O4l&3)QO=du_pmA5O$&eD#%^SfVa&HEX?|-Z9V*w<2y#e5b3u~IB|2UT za(wp7J@HwJ9(-h!dnFUOE)v_eAT}^|Gl;hvJ1`cIkKbL_6c|q=12} z&F{@5Gg^n0DiH3Cl`51Xu*Hj`+YdEAA^#Yyy9|#709L>-p!V`$`d4L2-DXvA(3`8R z&6LJ>=p4T`J=W-7{=RC_R-7T{4T<|Ppz*t^#XldddvK2jBPD;L)dCZQxbT#TQpYLB z1Rf^?DdyV=1hpqRj;N>2Vm9#x9>T2P(kNA@N9Ek`gNgBOU93b@QO=0^&Dp z34cvh;i32sYRi8EOj+a z5OKUNb!E`y{~{m%BZo83yXTiU_gN$=3vaEGBqE`V!Jf(KixwnSt0TnW!fY^cYiqJW zGy3tx9pr*^SYjg5S^272I#;*-HrlAx`f&Nn)d^qjFMN|9or6#`dJfE|KPltWmEWk? zS;X8E{a;52O_mb=E{Ho*@n8sp zf59hjz=YALP>AS?)+!&s2iKYu!gv1ql{}JBAl>*+@XEj6`M{#Ohr}ko-}zqBV-4a0 z0eI?deTy}}&eQ#^oA_JU(2VW7a znCfc#pKTMkD#IYvobBuxoA`!0{ z;R?PZPff?y#50?b;=!{h6QKtr)tkh=qXE|;K2%IPSPuo zWI{C4j)k2N8_$b|yWn~9W*cdT@~Bd?LTO7nU(ZKSzUm8rmJaEP@t9*xrSh1LI4{Id zpX&Pa?w{OsxRZm#4dpqTGBy&a8QOtA>N@0m?3PfF_e}Va?G`yNJ@{e}e|Mc^zKOC%rk6b|9 z;l)|%uwR>`YhT-0ns4oNun)pVF8*n8_KWlrcyU%<>2LH*tP!*hc1H{n~GhN;R z(c{yU>6tKn&wG4p1#jpy+T4_^&f#n~eIhhmTPa&S#gkV?9!>i`Dp+sEGZH!7l@}z; zs^f`bCw$W|(TELz11hHXqbE8(yeUsAq^|=M5M|SGL8LCHHX!2nsD%kCa!TJ<(n(2{ zxeE>!@Oz*_lqw%Cz9)qT6mdX`e3F|n9BwGdHWO~GNLvTMqsC1q;LaRg)WZ^Dfg;HW zXu&ZN7?2rGcau^OF(T}98=;JmqjpND2zk3v8S0Z$XiWX z8J`4C!f-v=+){6bU2oo+p`=`%Y7BxqkI&*qpB5s*GB=at9-5x($imLyamSSx9hr9PQ?(l<0$vGZZ-_33!% zXO<2ihrd^1~PFr zy(Jh!F)Kq8cLxBuuO(nM_ zY&aA;5dqZkJhzMJ$D0ahkJkNz(^q@*&hXQtt&L?`iXNO}zEaf+MEK%ZM0;Cf<%k+D z^-I$Y`07|f{*q_sJDEwavn>Mg35cPN07-+#63IoBtVXgh#laAYbB>*vOqjUEs>gxL^d4iFBn> zc8ec|FYI$^#R*-xiGgW9eoI0y52I5ve0AdxdU^ZJ8zsw3r7%QLC;1d2^F2L&WgyE0 zCh&VU?GPs7hN1bpOyb zgD-C4Em=+#vYy`;6j!Y5R-IO zu|#XmMEKLbC{89aA89~ABe{Ti>VSc1Psx~xs&v_?jaW|!Zh<9UMf2}UGrxUj_FsL$ z^Bb|)KX2iavEgu!V(3UQ*`VHjGg3!#l-AhH|~zp z`5NXHM?8gkmNJS-!4ne)LMM0Rb6-YA`3adwLd|RUdSXLuvQZ33h`h86TO~dnAyPGx z&mqikI=eBpX#yc(O6C&}r*>9S64*|~0wJCR_ArJ?gGdQ^+U6?FW^#z_q3mqUn;jvx zHzBm6UB1>`)GLz!YLV3E=NV;S{QWgS-**&{ssq9=0lgISXHxul-}Y}(6UQmr^;+~` zLh1m=!(aV*(T;-!{AjDC^1tQF{Mz|opV%8;m{T0FOSZ3hJO*h)6YgVyt+`R|n z#QSEf4$P~;9*NQbgBk3%5wLncms7RtT|WGli&D&E#xwo|vVC{KFg_VV(fd4)G8(x{ z`W|DO)3JF5SteQ$ds#*r6()!ByW;sp7y-j2%=Nw&)4m*b`AS1yF;6>YX}+;L>|YYI zOc!akVEo1KMdp2nw_}Z5JyA{z)RMZfmP5n-#P><$Qiw(r4dX)>cF{Fa-XFI^GJ+T^{{xi(d_k$nWDgZ;b!Xmdzi+OZV>;gE`mNM-Jn!YYlkZd7Ao`l&Gcd}-rxsc@9)e`I zKXO{?esTrTg?4Zj>a_baJZS28`&GX?f>#M;{B7}aXR=(J+bveHbm?gUS7(WLrRyW* z&sV!T;Vs08T6=VCN!xO`)5xDms>_y(*3)3W5 zkG?L|WYN`}*?!wyoBa@mZEu&plo0P7#7t^^K2&<)G(tL7f;gaDIE@e)hak?VkLa~s z2)Lh8x)2(8OuONm3{kpAY|RgQga#Ptc+$tF>v-MDUDEMpsixP3JB^HV>~QsgQ}&&E zv|c}L>NYT(nOkO zX6Q$$RVxPZajVdSdCq)vAWWzEFUTCS4~x7w6S8;wdCzur(H|swB#QF7Q>}D!CU)G+ z;4Sf?0w)Mto6M!fx`9nz*fSvY0`#C$81?RKaJW14w-Mq7XqW(PDKJ{%m z-%8p<^QurnMW~~4cIZ|YKwMpK?&>o z<*=Dg*}XLT!n&?x zB9QswK!rZD4-OAoee=Y>@=SivKYMLS1)CuvU3QZ`QZjSViem71uq8=YZ1NrFWcH5j z!@Wkpz?C_bvFK#MvAMs~C8o9kNW+r1Tv$0?$;zJA8xuAA zNJ_plz1M>A<|t9zMx%phP`A5>ZxiGEgn#f(&FS`{CV3co02R*XQ(Sl67MZ9gm{5mo z2Vcg8-Z-c6R*GaIpCyL#|3W>UqP`O}5xA9|rN+fVol}@$?zHkh>Vcg_d#quvCfr zJ9uYHs83GUxBcJG=|+0phmlxsL$#@4MA!G@1x!3R^N4Sf&}9fM7O+z0l#}c5yf(==zAB$4s#q#%m8+)DU;8_6UbW>l-%Gl z%)p8!suhx)%*Na*=B(!bs{89)lsG7ydDvZCu8sE1i43;JPee#1dkU7w;+?f^ z>~|fzsrNe>Bww%i$BY!Gai3E`=>5!`d}d|2f~6 zchZCfsU-}$a;D0Cv8Ba%r>Le%q@%;0=FDc6A5_QNN=s|!*PpwZj!wK_rA#Ku zeu3CNR#gh5dKm)6Tk{&4S1GF)s>-!4YFG0dD^BN@Fqe34qB5XZlD0sTr})KGZl6&B z5*M?VBtZ6?<#~QKoLsTz`FA!;zW~K?JZa z=SiwN^7XK}nt8**d2Dv{$djM5e0LJW}EdcuU44=SpJKa43U-*_3dGDYpeS@5PbKbEy)k!Q32!;{lyX88P+ z1k8~DL2#QOu*XX=m=A!4 z9n<-o3@fFFa!6(~gt^dKfONJQrT{{wJAVN)uoi`xx;8Zj3V0wLZ4r6wJafH_vr+E< z;qEQ`qWbpz{|yW^C=4kjC6W>rDKJQPcZxJfDcwlt(B0h)LrAxxD2Q}}bf|R9Z}3x| zbI-Z;J@-EDE}4g=I9YSz6UW@7c0aF1=l_`8;68k zk5x`v*LMc&-%~~}*4RIszQenVUpKWhnF`<1E0Pux1lfY*ITTzDGx6*_{*sc`IQZ&d5~HDf>kJJ)RUSWe zCXYRF0W=!hL@|3kb6qA=t!D$8tc6~y`8r1u-o1rd)>x`%g@Ja#-u5Sf4w^x)T!NBJ zf?R`xb`k?mzP!|!(D+Ootfm?4KcL6BuD1SI?U}hzCqmrFtjIqG?jNfe66X@48Sfe- zsjdhQ$uJMj!qV*F4swSFF4Y@5ojl8%2s+gWErW+1V1{`O1XULWRhow}_jzZ-!!jqr zT2IXIg{=egAXxXqDH$Mrnvyur!h3lb2ZO`k7KM-SL>LiA5FQYLsv#3hkZG6jo}!3_ zlZd4x$gE~0`9XNVXQEAbq<}rkfvM)S3yT76)Z{?K;d;crX_S_EHTQi!(HM%<~`g2hgd1^?eiQsFPJ9k60ygGoX02G#j~HBt*f~T=ivbd+baiUsr;;wO$ z$#K$6ak7(f@~3f%Wbw+p@v2(!>aOvc$?@7v@w$`o`ls=RWC=#R3C3CprmhL*$qANC z3D%PdHm3=8WQh*EiLbO0om>-Lk`vvU56{jgx zWT`d0sdZYZ4X&y1vUrKG(E?10S=%GrRR@h z#UF=hBBo8l?tuTtY7+r9uHq2UZ@_7O(uU#Z;=kAOv|?|HnOF|(U#A)rR+PBa8_vR! zz-e#s;5>_*^f59ohNqz2trRrJb`8`;YF|hlaD(?d6r+%0Z@8kW0gWUnp0i3Q*Xg4T^a&)00&n}1gOLq45em|*<5IGVwG56gCx512#>G_->W zUWe;qw(sA#k9eb9og%)gjld5E8ZcnT@7n}M=)nt&(LTmu=jSKRETrahXB`F$tBeai z%uRH9j;NF0Klp*T)@h{AqlH63c@s~i$;$J%I|T5MD!#bRL@brn#_YGn5GHk`VY_^y zHh_q2%IE_JGtw|3OlLX~N~C5#RQMzCMqbe2jS=ZsvIaDL z9|hBpc_BGJ?p%QtGF~V@>f_?o98BDO`nuMP7>12un)Uu3r2P|yt*y@N`E&-@iCs?TCs1d0Z;L>7@7 zTly7S(pw0dh9X#4C5*{ct%Ms1;09t?B`W((Rge*W$-xGGt!N zzbHHI|AzSSdv*8af3v#lRbH2GQ^Y6J)5dfyk>z$7-8Gp$T|`@kCQI!p{Oj?)5?}&8puGJ#4F8gr9OUfs=?XG zpcBW`n*l+VWeDB$KD=-=*t_`RV{kNc>t2*Lq2tlXqzqFMeQ4YTVAD7c zB|wHG`0k+>(b$yVpzmccz5xvtD2IK@^1w0WNdc)`JpTYFcbLg|pm`Q8h9pWI;4vd) z??YLs=Yp2Pqb5JS2X-F8(IcMl9W6#2B5TKy0wj}30&Noymx9H)T)zZi;My6mHt<-i z>VBJD&Impzc3w?XJaWbPYo9~X_{{s3gE z6Xh$v>SM2)l5?%iN;+tHsW-3y+EWmc+(HBH6#>l1aH1jP!&m_b|5G(_5E=N{VDz6{ z{NLwgDg-ck|3tfgGngR>%75R$I(#=NVq*SX`ulk^^#CUz4Rj)J z=I~dr>Jh1>p@=UYrl>A5VoEF!lTrT<_fIHg)BPN&AbJ($F)XFOu?hYM?w|M)fl%!d zg1Y*u+oSaNWi0Nx*lzojq9Kxri_}@C>dh8^M*RHZ{`nV;;m9_F!bSJIUgj$zkMs_Zx$VZ*$`s zE{)8SFL`ug`_G@m*a`=XEv$ijp`>WkU&5Qg^M5P7D;t&WjUA^j-|i0vV6*E_vJwEv;Lpad4C)1 zeV;#g-=F`t3;A-g{d_sI|NOsL_@UARzgq_W0SAI@Py4%v>E}%QN6C`JCwqn;v;R>t z&F}7!KRitTc!%b?^;Df z!=faG5_S4w;E|}pVMvG(@8SJ8tUsJYMbUKqK^P+JvL_#N;ZYEgfbZP$aT30ZJf?)C zLzzM`sAdi~l6NwRymL|gyPA}Y7?cnMq6g03R{Ir`ukH%(*P48MErCD>vf`Mfv!CXI zWn&f?nUzG@7~ZKq^n=plCltJai)9g&qYb9a79C~^=m^G2lClaD=ts71TgX9S+XV*H zh^5<<(1T|YF2p!9qT*mO_j1X4OAW2u6~K8%O6pr>x1$A)xR-lL$E7&u=?yfS=8xz6?so$t2gQUX;M{|p0Q!b>c8>M4?6xrNa(vu!C0nCSXV64Wv zlFmHTx)T|Q@p?&wdN+YTDUl>9jgHM45d{}fcV)tL0SDt|c~K6M{fl{G4vZkXTVo>!$lM?>Qgx-q7ZiilcA4 zxQz8Abd*&JzLbJJ4O9W4l+l@V8dDUAD3vwNoU1j?G5K1BC62|Y#j0Z;4NM@hM>WpB&KJo)-a4ROIAjQb za~PrgjT3|hzO<)icpf-?+_VA2vkymvz${F_>l@$|+8`ROq8xxCXZ<6`ekap%09&(p zbl^Sdft&~`JsxC7j{r@&D9#PZJh8pINh{XSGqjaxMUu7Wap+URtMM0dKC1~u0wJ(O zoj((bkpqS#asgdH;jaNR?DWP!r;+{J8M*^DeJ2T9?)_U*Yw(}W(El*|)iA&a%*r|4 zA!{fWK*!IS2GmWAyXkG&#sT)It8Ry1@hYK>`VTK-KiSTFvCbJelY#Ua6!l<;-Hm(V zkp0HDRCbdsY3Ei9NZC4?V6}18G_erf|11#zmfLLWhltbYgyt*8aAFA&$ zQRs^hf=HolV}ekUOCtD0gSjcifBs}?2Xjj@TRzI930!Er=WVxEI~vZUq%Mu$_WBkrjdXD2e8 zMP;MTps9Ol$ZZx2=Ylzzbu{f+6pKOCp_^(I6~ugs#no-(@wuqHp^%D(BR)tGJE=Tm zjiu}-pq?Tck~%n=#o!I(!S7Ah7BQjF5YktNs6Y!8QL{*mE;$x$c4U5i!QVHRz*IirnE#I4MdSmjS93^QS4ljP)YXF! zx6K*;o~lc8lTR^&nFUNoqEb$K5X-%!k!%-QJ?T6%0kHu*!*_Y2-LA^b z7JX2m$BNDmEC$qg&K{FWbLqP>WkcU=WCz~pV7~KiK?ie6` zF1+-Bs`_mZwADMTQn z9kNs^xbGNfVvD?$H_MR>(OM_+`-2i~WE;nj3RMV1PN`s$WK;_bxsdOfK1dk+eE7ggTv-*7Qb9;Qa zrdrdR$;M1@5kjy}_DD3rR$>~tx_)ksZMz#dwDyXD)v4eTW!H0rs(2+EG3ih|m>HLp z+oP=3?-lD@;MH0iqODP?C(t3K@QIK|u&HP^n_G`j=)Nk?*~aI71MdNoJ2XCMbdriZ zCwC?BWpKrrvi%5u4ZqJ8H~*Pei%M+tN7V&{G{fF&K<;T|0czwt2>Ce=6b*~~u9Ja_ z_G!9l16#zMpdjm1W?p$SaSwbL{za~P7DZl6sT5nLP3 zn451Pt1e1`0`62d`CdI6&A%fe5FlO8BA>7R_xV`0=JiwVaCJju+MdZ-sLZW(9h6^d zLfHTxK#kh?bC&M>U#SWG+a1?W*Z6N)fXLL46n=KAqjTHqz8<+wxaHNv8=Vht6bQn# zA9szTKO>A2fE@wTg)g^A1Qs&)=Gr}-NpL+}_Luu&ZyCt9o*pC(rBlqyU5EMnmKySJ z$=lx(KQk5D+b)q=fLrs|sUZjegK5DBbRFh{#ZdGg8*%;!^SSq1YRDg9KK~1T-T$%? zXS1}bPx)U`6OwnAL1uZMubS@;{khyAYX`_92#|=f`|~yX(-w|>#RnfT?DoSWevq~f zqZ17yV6|+8-@nrzMJ0k8&O`8gFcSL@PyOH54v>@JHTZIJ*HG!T1P;Sp_$xydUjbwHDp6Esiyyo}O-J>Hh?zF;#8cg4Y+(^;^c?+n3{&~LSKSbG~GlsI?6 zbGZJ#RN+GgpS@KgfB`~CnzuNge*HR(so||}c;>q|TNxx|;B|hw{qak`0>aDV3hAku z_d*a$F8HF&ebF<@3#Wrw-{j&M^3Q$5gAq`sSoC}3)U=-E_`t2aVa8_b zMdN}Os}1}W-}$zFQt*&PWxfqLZb9~@v_EA-6sW(VPv*kC2{%7k3-^Y z{d=KzLYa)ryY5fqgnz65Vrcd4aO!UCw$rp-I~#XSq`Ieu(t&!jywK$dLPbG9Kd44} z-v9jjV}UDreLMjJ4r{v(m=L>bSG0;?({h4YOi$%C2J{vG$dj?{}Ly|TJ{VE(|coI$3eF@pDeSFoHCfd>Dn z_d@!FEv1z+=QEzw^R|1JCkwG0UZ?Asm2F4cj8@y{DtPnb0%#wF6d63ml@%JU>T1t~ zZnC6KbS*Yo7w1ryks9ukoU~v(sB(6UrPdn?dgA=Cn+gr9_sPWpUf0KEWp5d^f-@z& z&lVL9X)TmsjiN4+jFAB5G2QMbjGgrtU0$fzw|m+93bg4XUtehkOd!S<@zje@o%r+g z8bm)vX%`LqDtZ_a6=Kz3jYHT!r4r}ExWVdU%hV<~{TQ{HrEU{BYD?>w{Nl8AnPNK; z0_s-i<%z zIyLf6BnZM2s}^B)iwVuTSji}Jk!)Of5q6dIh2`QS_-4(wS5>NF0^9b@Z>k>z!i^Vk zoReipH)|4Gb!l(PxRTt!U7$YRGERLejOS$>Ms*26|KXLyqaK_~<@r5`T%x*r*0)BU zjL?Ls|CCDsfArqKBguohfqR;4d+E7ZaZ_{HLf`9cwfb=81-6nAZJwK>o`{}80hA&6 z^x=1Ec>Ii7;mi<&8}v9U7p9`UQXgYJ55mAVaYWD^q;)>Z>hJKGO9ZJ`8b;TtT=DT8*>XYX* z3K4S6x_yL?ERw!f3++d}Lo{=G1X^8jOYob(0_m?@x;y#BG?KJXjeMZ*FA?2f*gyDOp z+@+K6HxJA0W~EglL>|f-qY`FwvRTUMOqu47*Oz#{u+nLn8b!1U8^=bOTGPj@bw-QDP@5AR z_lsrf)k}1@;THYFgyYr?Jr0kZMg60`<2O6;wq6JB21jRIREWz;p(2eqdPyHQEcr^$ zTTkZCxHQ`@JvqHMaGrq`COXgcI0NsbJ;SzwcTqI#2OZ$d)zD`XugM(Ul~U%yUMK7 zG^E*9lTiE4K^|;@Ew$;bxnOO|=)1MYElr4Fy99^W{-sEid#CTE-hWSj zK?|X$r$N!_sLeW*T^FWk9&ye1F5iC72#>$H8@5)JN0GjGR`P{}g7{(beSr;#J9$r5 zn_ZEF?52dX+gL%tk78oB1ZB#z&%x?7Y*)0tAW0f*e4sAs+3=R;dGnVl(|XNMZ`XM! z&W8v39^@jdAonrPCPw5N>T>0FEK0Q|44A=H-oq~_@fOAjP8xh;A?r4&?$hgnjSH8mpG)6)9VQwSfU8mn4gs`BbcQaD7TMrF$l{jayPf?2p&6v$Pf7^@hW#Ay zh5gqui*D<0`h`LxHoXl~XcjXLT_prpBQv$fm=GL}d1}Mo6bhewX4l|tY3v#y!gJ}} zV|$J20|gT+&;rqjj+p#3qF%Rl)x!Y%-n3(4Ho`4LNMxUotKhjJQx z81Y!ULB@qop#wA8N>X=j{!-y&@L`4pZ}GcJqem1|D-(7I>t1;`;hrxefR&qdOq2sN z(g4xy+me20ALT!Bi#sMkndoY_XMf>q-MKtZ1r+eU*s*kP`<{jHNSL3CC!Ovhh86{} z64<>uV?hx&jyxM9%)<7bc@CB&tzttWJu6b405`YorU55 zczfkYQO7y6(zhcn#g=XFyD&2v5|%bTM0~f+2C>n2f{BAp7_M+!gGE~Vr}~{;8v%dy zdl?@&k9jb5I$ssjXMVe%=*`jSfFkL`@WlaB)2CG2Q}ZJ(lejB8gX73cydrLyb{~*H zBf63yjuaH!$cZ9+>?_m%D#Zs#UBFXr#I7F!*S&s4h}?1k07})X%09D(4!`n!JY}e< z5Q(QClc$im{tZ$h`uonR4Ys>qy;2qRu{m+uN5I%V?uQ+o{)L`Oig?@H=vaz)H!wZ+ z#0=p5xD{C->;)Hn5|h4h+*Ap}v~m6HuuAO})25iFu{MhFjvIgdF`3=Gs@h=W9- z3<^L&U;UJPUQqz(+>CxqMSw4&(5So69Xj&d()qRQaR4+aM7StqNi7Jf1YUmZim=1U z_W`y$ERIJ44gny~PQSbgo7Xhp$6a)A$E!T3x38&-P6t>PlWZyx6zPm-q8QxcAmot8{4*92g_;RPp`B`=K4qNYPOtr?n7)C!bu70@7jsnv~g-aFB4LM?xu#TKMD3fWQ#4)7V>Nafd~*qAn)KFi(|0Sg-jr^29iqQ=A{_ z*33sRRkCPxt#~!5xHA_U!BZnW>^MW_I3r$T?NdVB1Y1S281oGebtjy)yYU7m0hYXp zDpIlUToONM#_}X5x@?4dStO=wCh*utJl9Hk=9(0^VdQ6#fOTIx_c0;GV@PyU(r;uD z=wmd4JtPuaErS`7?kcNys4|k}>g<`o~hLEFcxUsnyuF^@AxjuBm9k zsZEoqNl3D2&@z@8ANOuD`~9?T3&?;gBNfh@d8Czj(v-S;n)0JK^RhSt zF_^iuL14TzYnS zoiZjlNv&c(w_)7A$OA6ddic(5SnoG*2 zN-EAus>n-g_)6=vOB>uu;VGrf&84kVrEO=W9pq(Qd}Te_WqodC11V)g&1LVV%HE%q zjgXgr;wvB1E+2O*pGYa6YA&CdDxW(mUm&ko;;UHEu2^%cSWl_gY_8azs@OfN*e9?2 z##i}6yYk4b@+775thw@Hs`Bcr5}>F;<*x$iRAIPRVWn1qTdHnMSK*#lK`5#T_^XL@ zs!80dNmHxITdFCitEtYbX((#w_-p8OY8c#Wm{Mz4T59f1*RY@0a8lGh;IDn8Q_Cgd zUdxkO%hyu-WV%-HycSAP_msa*RHshdy-qTiR%#;~mTY}w z5w1n+2)uJ0J|3w%k5n_c?`Xf)7b~wFYOI)VcX-psmNb~jqx8BHRsUVm=4>6ZJu)We7^$!1T%Y#_4FBH-Ys*2I!d9?1LTqk;|-~@`cEdkdC1_ zo`)ai8z;`N4Uf@UN=C2jM<9|0(>HlvPKl!K#%aV*Qy+}0o z8tM6|w`U_WqwRo=-Dal?PBP2)%p{Tag)Vn>P8+u361;P?MI0)dQj4@{0^ z(F=X3DqJZ0GBmV=(6Td6)k6L*Tv~TL?Q-0tCIzzfB}~0Mbm-^M0-wL-svSl_%MpSo)0LT0oq9?6kQS4&lFgXT>75{kQl|K3pCUj$?y|c``r$v zjnP=*C}#>z5+a=Prw-#QpTKo#fSD^suafaFmjRuU=N5P1x# zkM2`9E$+H1&S}tk60;{0VoH(5b;N=qlJXTA_f_w}jK1~w2Ar6TttGgey;8{V*sMdA z<#vCVWv#HOGXA%!zn=e+>hFKX2mWMB=!)hQQ~NVzI3x^mYs^mi*AIF&vIDLiGN|ub zHT<(seBGPKF1yGVkK(svg1|}kKf{UT!+Cu224a~WhmuQtG9F6g#55*HesuM6<+Fa-PL^ju^h26W+@rX!+-|WfDk@)M%fje)KQssI1mc|A`uKyu z3#bW$$ux@tPsL2EWMKAwazerq8DuOmM!t!6A0>R_P?`FG+@PK@`ewZ`K=>iZ_uuO8 z)+4snsHy_q0m?_((UxKt@Tqw;Cz%OVUB5V#BkKSJHO~y+nD@@rM}|Y&Fe3HA#ME2b zUeMLqhN=2b940bHo1j5%1KER1#te5hnqVApzt+`r zeY#me{5NYJ)?aHL5;;*cZ276j{Vl=pE7M7oY@9b3ODK`8`(Gv)a+53mMvB-T08B?q z%C#JR_NyV0%f=qhNpv=lm(t8LaB-w1SZ{ZN-`WcS*? zx?lYfJ@;Sw{^iPCcfa~u#f$sD{QZkjpOpV~FVTh6_~n3Mf{J{)W)~ zJNb<05!wG>s zl=|OO0DnH(4uAqs0_c#JaQO8Se|vYYlYjpjMBEhmlfV8M6Dbo#YcQ0?{D1-350$Oq zZ~LJ}9ogKZRNE`Mezfd2XaL_aYNzybL;UH~t! z|4kYQf%V@ff(N!T{(CW`jGYF8WLL|QEKFV5;+SCi;789?0>xsb)yO_)zbV#aRe#}9 zZ#wD&{IyZbMCzwHsL{xO@XKcr^NRmB{S;eVb)YIoBn)z2dQ9>lr$3yUJ8&DTCQmZ< z-`7w76`S^|9o3pMnV%EwCa%qDs9HHn1;KT54~IGRgzH6%m)XY`peO2iVz=+pk7|`H z?%7<6WUqN!@CR(5tRQS1^n@5r&JEu-91KPtO8AS#{t!m)D;-1ouWz%tsrS>|UTuw* zTD7+c@E`BZb>Bf`Qnj?6rj$!d1uK^lud$Ug+>qs@L1F&1`@N;H+}qn5fjIb*>2rpk zl<5oLo=}_O&4@F>*vv@Y-Sy{D&?P4ND3L2oW0)v|MP7^~`-X9>A{F!9SQSAnlQ>ld zvZaKoXzr140{TucYdK9ex+%2kDP3qi4Q;^l)8aLK_m?q~;Pmo|n9PjbgXFInK1XEh znSLbF$fGs`Ur|orgV6OH7#I0QZVXZ@&5tw%GbN_AjmuM@iPFFb@T-lUWm*kA}7?H85IAtJ(-~wyOqqziiYbL^DGG_{|P|)~%+m z(x^Hx$xtFF4W!gPj|tY}xAON{%I>#oe~^<*yuqE5q;G0McKK-+M4id)I3tnb>_Cv0 z*>&B(Y_00PiFZ-egMUl+eiy_{*8UA8b>Mve%T4F`boaSs|J)gtcpFnsqo$ukrmk9&y1eeA?5&+wpX8{Se~kJ2Zi5F8Ov@j) zKEa#%?yX00=IH&5n(t^*zmTnA%Ct6Ow^gr0R&Bj%ThSUuFLYZe!3E;VB@-)WKiL{mS(%_`Zdd&-EBRI!p2P(|MGj7KzmUn ze5?HgDR5SGdwtj}U-shPsu+!Q->d&Xb+OfsWANmll_K-Wx2A`97YA(|)Sll*g*Yzv zKeH+b9L^J#gQg^CC7z<99liyKY@Vr1$BEARV}yraS3F6u-*+IwxOlzF}{@$~XK znc+z`((}#(Y396FrxJWr_NA44O5S6-oA#zNj|lp=5my0F4g^ul-Ltm}@sLC|_wbhN zVQ|;n?|4`SeX_Zz^roUa zT3Uv{I1j)~Iueq2&xk1%YmkPZ+9yHQhy^`~=OEfPx++eZRh;Xs_T1NmhIe<_or~Y< zfBTl$_Rb`O{Yz-z{u*rH#_dd>!FPsS-;>`^no{{b7}oq&nSypI1~@nNag86O-nz%I zh3#e%; zBs3Fc-D5M8RRJryy^l-l?V)GHq(hOys*1=`&1b%&HJI&YoBK$QSvIj`%wa9A7-9Z; zNmBZAMqHE!)o_Wr09ZNT!7GP6-*}LZPruN6_S~qgP4zF$Bav-2C3g7?I$!xT@=)tD z%99r4Z+?@%KMwP$SZ=Jh zssIX+d82svs!p&ZreTkw~x@7xnyu|U%3;pDM&osC>`I>AjkQ1ySfAf z2;-dG?bVFs4Ao%oAqLZkd9l5FHs^HGO@({F`uHAfSo#@`GEKLglr?M(oY&k(J1A_O z?W11bMV+67I!kF0h7Enz3V#tIi1WZWv1+2b0p`OX=nPphhAr(f~F|U%+8x7eS(1w9ewUH5C~eD_KYR_0`-Aov)-H zjYuSi*LQw>ZV>RW4Qp43m<^^A=S;JOzMJ)#Vn*lDx9a6LuiS|*@y^KoGwxIrk!Z{C zKL8AGY-7ddNv+NT;ePM2i5Xv--PULRT0da$-tj4xGzL9Z98Rv99zjDDj9Ip0a2diB zoETwZ8U?4vdv;%VsWpVdb8w8HXn!Y9QAsnqZ*T+^$|f0&RGjl}09i$-H258{yDFz%lx@ML?z2;P;i2sO0%h;G1r zzVLu5q@rEcE^aDk5kbRkOvnj7pQ8iH5Q;}SQPcC2SB_pLwh0!ER#DAO8nSF!y*vaJoZUU&FR zf*;6bbRb~lq1l18A5;oY0(zTpY2%2feuK2RgZ!Y51Hq#R9Fi(xc& zC^dw^enRT;-`vC7=HF1wbHsF{wsK>3lQ(##_@&9cCcTJ{&ww(-4Np&VtWXIa1rgDiq4Ht43k8I^ah`sSU@MY zE|#xqWgh5-vw>?r?tOojD^7H2h)9JGP@k=s73ycn#w-BVsDAKOX^I>2)x{{E2@<>xCIEoCoR`LScqRZSR}p+x z@GMut2ruY4s$mdX2lnb3UMdVQQwHO3dJ#h17IO5hc=T0h$ahJ?YKin!vK$#*@hX!D z`X$T^5pZLiY!?i&u=*?zSP}2a4)5ClShpkUU8D6qE*MjT+3tEI(Oqn-F$-fD2ry(Q zcXaSQ_S!L1P+0Xxw+O{ja^4^blQN5!f@0i!MjgSx0JAs$5*&spX#<4-7Q7J0TY!v& zV~(;>wllK1y%N26!U>OWzM8?&nADw<&^i&Dg9hiD(J%{fOU%2J^Bqe%nU3UGd&aS7xQ&1yVIH(UQ>!E>m{q9B>St; zX7u(GN*rarcS>_zPkkR4Oxc+^kLfK%oCO?4J+6l=zf^0j*A={<`YoSegDj_+*I@pX zAiyNMdd-&_uF1-nUGHchrYR4&DJH5Zkh-Ptx*0&g2A>>nozNTI0Q=)==TUOyN;eU> z)ueG+%AFh0pB?1!`q3z}&|@x9Tq@;jpXHK1%W`?7FNR@EGevarBd<;seCk`kXT)?QN+o+f1N8b>G#k5Zkm+lnaW?PZpfY zQ@EL36v3yvJSq`ARLFk6DDX9ZaEf8jRI$)Oan_K6h`7Ll)XS+cgU2V*T$-6zCVID{ zB~qGi)sSa%q}bmZ(m-mgs`aJ!?w1m5mbUUK#|#ygPf84&2@Zu8$2XS^S-uVcYozg& z+1)K0(|&QdCmrz(N-N>rT6bG}N@R%Lxp(bQC_nTtPeswd>Uih!b;h`*Xdr<&Bg znw;N+s<|pJ#fydfcm4EEszT{zb#;#+GIX6y<|X|>%>#V+jpVvO6s1x1t?I@`!h~+0ZaOO&_mX~=cdtTCqUe8WZU*T4-o?5TgQm;B)k65km zLT^wxuQ$eVQ32-^nN3LX|sAeB9*7t*_Q- zr)U_^Y1L+Jc<0_aMDb>j|ILSUb=ThJsvg5HOm>nZRAn#_HiAY{LJGX26m(S;HTo31 zaIO`f!b=ccu2$bX!TM-`r&R@la%zr)LIZA~07#RRKa(nAX*!|YO)pW&{wS5rUf6Nt zN$ZD=4xAgEH!nJfC_9OtbdscXlD2k^Q_$d+C3Eq#v**1*v&W%autFH)U}xD;GRK`a zMS+8O8ey(F&Jlzk6?aNYnnFt(o4W;Px}mzIc*R~(!NhteGT_L zbs(e&Vi($r9vaauSiUV*m2KYrwpG@+bF9ALm;87MQSpd7MV`$HUng>*W&PCt;mz?r z+Y1w^x%x4U}&i zb>G5U-!{*@txJQ`s5iwt=^B34)yCD0C+>(=9lj$ZK zA0(dOe@PwY5ba9rLvLf~Ch`GYLNQQ$T5b$n6HD-xuA>E>@H8GjaM8Yu+QhvP9p(1! zWV!AEzM4DyN*?^EVxLeR^ZOoZw0{?JO8IcI{oxo9-h+@GJ)8N!=Q$e8Ppb@thsMocTOEJB8Spow=M{x;^*dO;O$DH0AQNTiM+D zO}ekcgbiE-ppUk&I4ETs8kCe!G#fexd6HOw+{@{WHWg; zb;|DbVYWgD*!w#9`-lYJ0&5N{=9yF#A-8dtsNXN%p~|H5TB46!V#rv!*S5s&rTaB+ zp@PlC%PJ*BJSCVSQ++AMgIL7g+-lk5lOdzLP0E6+ zs`@JIDbtegnUiFS_59TkqF-?9bv*r$UQm6t7TnB|-^{`pe?qxIo3p~+&yOK1?=iQ6L-|s!Ew{m|lOSyi z-nKs*8s~<6 z9La^@)-O-NS$5g3Y-OBZRlei2j)7YTzuiK#-#T&r$>luWyv3@u9zUB1Z zI~G2S==i=K2+RV)$EQBa5;}V!dzP{1TMkg; zW@q{voH$00y9jwzYK8NdQrGX>)-MJ=!?19zgbYt;9y|9`Ajlshr0q$xSI~4N8o!@9 zx6PQ^9CffXK+;fUf6&VbA~21YV?#s{bC+VfmkWr?TUOiM2yzR7?gbp`d??1}@vf_d zBLW^bh4pV$Pr=4?@$39|R>PicxiA8qLvw&1`b{d)B*n$2fj4gp`jaXxiH3p^x2@Hb zmc=7)3wVLZlvgBU?#fYJ99wmWy>8&T3jj2Or0&MR#5aw#0wDvm0br0PE8QOeV4~*7 ztWvTCdAj#anx$5y6Ydog)SXpY3YTj(+4O>sHis(pyHjqbs#$B)m`xY3ohOuQ*S%c+ z6mRv|rjrXz;R>BnbKkHl;3itbtse`juaCierY=zjz(5e2L7%LWt?B!80dI`kDa)1N zw`$w&uJ7H~7(!D`72o1>S{>C!Sk>OOO0Bo4Y<;=Rbu(@A#ZpVaIj(-|vHjYRH~&0k zs$ppy2$O{*UGLm!cUFYqh)Vy-`ug&4rbOnIo#SgaHICK^6)vsQGVCiqU48GaORV$U z6%Hr@1hRvo;fPiVpb|fUb%M04dNT|zlq;X&aP%nNaks9vuDKyZ6wU{cpsyA^WLSaF zowC%L^`4QJ$kK!5-c{Y!p|6V+zwNy8@qzo5MK6i6Hd&1%oeuM=f~~ER}T+WbQSN)yS~7|9J3@;q?W6F4YIohjLNMDF<1{+7t_kCG6w_)bU=fqw*Wd zsrzkcxuaWkJUc2cTLf{$9wC&($XH@?ztLI#$dQ@(L`z(U@c-Xp28M7l&UC&u;Px&?brP7!;(+wxh=j9K%G|NI) zOD4oU*@7pZC#J_~bY|6a>AYxs{&Ku}_q=*~vu-n1&f)H(M1hyfqRvkpmSw-F^L>ba zcu&5O*jm$hx~I{=o1>dV^-Y?bx}jh4W1h+9#Nr7H@wn;}l@^Gb_Y6Zh`r!0L(-!&2 z{vjBX&vivGcn4ux_{qlcQdF+UBWNJ6X|h>ClWD5$6;H9o!?mWbQCzAwxLT|qsF=c&Cs${Q!hwiUHhePD8Y&A z?Ps&5ulnm5I&&3ax(O?)eEDsc&!pFa)JJz*+h) z9EPdqJ=i`Bhr(<=N;os!pP;l#*<38EXfAD6r#lf8)ByNWf z<-;4Q$^ywZt77C+EPSIfyf?>=5oXR8#i7);M-oiJFUr|Lq6;X*=1>fh5npU;8W43+ zhh_N(zwx0VClf3m4hLl- z8X73rdf+z2i{(Dh1aiw5Gl~)86I&rGjN^5YzV#?MZSmD7`_v!wOhSW$N`WzPIijn~ zY8KM!37_oO-zt%tG_j5n_mB`scEJX!(BmiQu(2mV(e!{%7W^qn?taj7RgqB8SU2^% zd!I-E8g$I+JYoO=gK{>)0Qxv7Fp6ZC`|f>TrdDP@oU{er&&l#m(j)2X9$)!(R64cB zRpj=TLfKA&+b3^A!NZRRKyivV-ZOMS>AHk4hSbOdkZ+c@y$HabOj17c6wuOK0(Og1 zu#rKkDvHA#1&Z<&t0NANA8p)t;qocI-Bnalw=^4mym8wH#Qp zJPMY5PN$NLw(bw44Zd@$TO%Qab|G*-p`%xIQ`;^*MJ?kCzy=%%(ctLl9w{oy*1}-Z z*{3t`B$bAokVokt7D&TLWT|*vl;3%fSUsnYKur#HGYY*3non%}Ob!uNQ4muT1SGBB zL+yDOgwXQteCKqc0(K%up%XZztg;xlPaC#o5SyO-7?@C3`1pmTuuMWtMm$kg{(EDV z|Btw@46ADE!rgR-NC`^UCKV+lH%fP>(w&Ngf^tI$; zN)Ad)%TqiqkODj?Mm~9wB|RBlLy`<V@3mdnXw+FjxQ1A@dnIRH+1#%pGMzN zjExx8MTLWmfv}q}Q|QQ$^`GbCVi)1K2;#o6Xo?V+YDKjR*Fp6T4^EKvA$^1ZK{2NB z04g+W@N^E7+QAyiHa+L-fG2>pKvV`pV2hN3!(hzf*DRKN6FGaLp~Q}_*$)#;6@qI% ze8qkCnqeN5nGik(R~#asDu=B{PecQz=z6{sPlU$+4{FmCrPANP)@GR)i{Y9p&EVa* z`$Hk%LV%|TSRikK%zj^Lo@0HAQXYEkk^FlX65_0;c(Kw&Nd)#wQbbY|05dw}3_zdt zl$kuxI@O$dR&z&JK3Br+Ww>W~o)GmtxaYSdD*kT;rHoSY`Tjy;@Ew_HuYIt4*m{NQ z59ZM-2=I7Y66S+eLza2~B*x}#irw;oB(1_RXz4b;L+$A* zV_91-&|bIZ>@dudc7dBk&kohfylfH2lI~M42V;MGq0#3|1<6}_l8Ki@C}j`=qqt~&neLE&3iqP>MyV}NktnO{BN&di@V78Wj>u(H;2cdi*rHdW7Br$Ze|~FM~}tT zeh|xhk6a+y$xg?U!lH{@G>4Z8#trKO?2He7hzEtV0GZ;9pFl#@tQ#^4NKZ;sa(+6H zXzcmBARZcA6{v=q@L!q^|H`&eEFN2zU7sk>AhY@%mnql0U$8|-Hy(6@d>ZOQHg;bN zatT?Vt4`W=avto z*Jy^20R-rG%ZL9;+iaiUUm?s0qVyxMC47t+;l&}fI81c)B1jN(NM2CAh+Q@k#S2Vj zfWLyG$Bje%SvKZPiWoFWYdAWA2JYhnStdAFVJK5N&*5T5v|;W_X1v`mljca%RluY< z7ocOGn>3TJl9i#P7BMRtgeXVo_;g3l4gEf$F+`VOJHNZcs^r|k5v zprI?myJSsy1%&*epX8_|0HFgAPw|B9Dd7>9*!&cd$>%`>K`N8vWd7%%A;6%(MY}R_ z2c4Zx{t%6j8YjNZS)>!_x!gEct>G$`rt0*71C7s_;!RgXJN|;isj6 z?CUh5Q23pdp&|m^#GAEy&0`hZkq&W!WM;$BR^-P^{jpRmz2j8x zy28Bfh7v(~@WHJ5TNr1e>sF~x=FP*PIv*#dp30x1rnv;f6n#njr=+ffXNn-0($G;y#mHe#Bh?9qlpV z!9$wWNvdXT$KS9)4)MPhvY!fB0Cc#S(23{4IHM3iO}l zI9D%2-ZKHn`yt5tXTsyWjdEq|a$tbmi~n@u6bn&e@J3cWN3GFFP{V1l2WVf!F4pR~ z9LxWb@G1)?wCr|PC(VW6{v#h7Cq(><*b1oDQFOdg4+aG-r&3H zzd8xiVc0V#NAN@T#n;u{J7`tqhJ!v3W{@ZA>=uA&=!$ZyDAV)DITd6T2$p)clqM5J zUg67IU?Vz6hZItruB?oyjqL&VB!%LkMnTyvuWgfEVnK0rrNxK~Th$+y(k4p@&;P-B zn9lMcuV18psB+J8bmXOk=O-JRDlDXTDd81$SpOYhOp5^XT3!(|ZqQ1H2oR%I30j82 z_9fbwma*oG<%^4=r;9O-{G%(qL#X&x{eidsmiW=)+EybzIZ9CpELPos{f?ct)#Z2h zoO$u>XBd{%jGddE5fGFyD3iY5DY{^x6 zsQe)8y!QPc#8lf&E)1~OP9JhcYtJ;jQX-M=i=Jlzm}e(Mx2ua6pnLdQQ}NqR=RITZ z`+JYBl0w7M6ePa#9F(n&U{By7J}CjTnBh(ZhSA49Gr6BW(ORU?f%G(^gkCROl6bxv z4kv1X!kf$?pykAr+Trxp;%!3-n)sP0tFwd^LjV1>pm;K|qkXXobSMS*WU(P5EdFNF ziz3UkJ+?(GvyBh|aoF@K)+Rz;1miKCGf|yHrf&vD{vMGZc2q5|f7Bx(kS{9{6ZjO- zhT^SL&YA$UrgGu%^2g6+MD_IVxk=`dD@DA7>$<1Ppii~!k1PL`2H`%I0qwOQJT?*R zFgkXG>3|LN+msI~Uf@0oHyRt1X4rVtonh>B!k%d`d4nAiYgDm9^Ju94g<7Qb@V^Pe zXvzDAvJ9aK!?lgdX>W$js=opH7+8{R`ptka zT+G{QINmc`;^f<1-D<)T5cn)44$7OWzRb7C1fhX4Kwdx7;W-=3Js*CY$e3Zq)e9Bt z-}PV;UYO*30f!}-Z~Ra!S3h=N*XxHVKs<&YFTF^Ie&IR)K^#u(e1cS(&-Ena?M3m{ zn9j^%9KGFaY;bI!Dqm7A6l--;XesX_OvX8QmEr-@Z9?( zDNetvCxqcXiuyu~N-;xtA02lwf|5-i4JE^F zY(ngP7v0jJ^jh%rrr>&UAG@QRML#n)#G#Y*{%YO`s$+8LNBMB`tK*P8W8?{<81Ytp ztYIxfy{@u_>tykg;xMkrY4fv6(A!O&%F#)~Cqg}+ve`920ThIgL6AJ26vOK%_0>iV z)Z-I9Mxh-RGI)z!yQ8hdJkS}{VTp?H{+E`sM+h<$3tC{9azwJTN=K)SISuhs@*89e zk+>RruutgE_DF6xib>j68lWLt`rmw~5@85;TUi!1lra(nZp3ECaYGMj#rA}4&<|!h zgG9UH`s1n2sQaIU3c^wbb&>0Zy$Gjx;O4|R^n_3x3NONHxt#28aANqDpW0eb7dCD> zTRGq^%}k2cgP;#&0_6Ros5itujv#`wsl}AF?rhS!;lh=r#z*Ks<{Y7^DErb&gA-j% z5v`}An#r_L7TShy9=p2$`V6i_h?@T}W+?E4-aacyXWW_^0XC!*l z0~t{~oKS{|D17xXO1}Cz^T+e5NMu<5PUS_oRzdgOC1OB$LL*`@QgGDZLye+J1!MVv zaNftrG8)*Knl|a`Wv=q|kQHx1CXAZP4bheuTP$punlNgZ|H7~)zqr;YV9pI4=0@P3b=yz%&QT_Ir&5! zZS#F5bPqS8uD?7D{3^p>4~~SuYM|?DyQ`ecO*~$shI)F4i9$)ev`^;x`EN~C=-^y) zAH}nW(^pOPChE!5RiOwqCf1wBaGefN)j0@;mxmVnURa+nYOhPKka58aa>~ipKoDqt72gyG-rcpL;zYlUPL!nxTQ#dh@;1=EU zp^bMw1%K~$E|Da)CsDw!xG@!1(oqw<&s*f&`HU!s^T7P$sqRoe4@}eylk=wRsB72W-x^B}@mbAm+Wrh?X~@_6aF7rNWtyzudo z#H^;r9x8v|QIuI{cqP&GVcWp}|7X2e`F(N^RdW(RZ^37IJTg0c*R*bl7 zZ47Fe*c~@3@x(g+trz-@6t4Zckf!CHqtJRtp5wM;F@8cRzxdJm*Y}X(5?RfG2ajdn zZ~Rb_{=q#*2B!a)CXd=zO&+gbqp|V&`QDGoQeF&^0B!o@ZXXzQ>+jn1IMf1?t`}() z410(0?s?@IEG`CgKni}362%k#NBMo#%^x}hS91q3oZLv>?B8B_&!(mOm7{42gaCJ9 za^uMwiMt$}WLSkk)KD~x{^lfW9`Wu&t=A|uBwfTC_;cv~Ea8~9@|Rssol)wtoSJyu z8XHv3NI!)->@Fa*hiSbfG1~tKSR`1v3?Cn@?#!I3J13oLj4V4vCPCmb%adMi9})np z7x-*#jUypr85gWf1Z@utOWKCBL zLg8C{=Awlo$Ec$vonvTXjS9{sA+5n<0eXwZG?7-yw$Wz%Q`MT`*7CN~{1u@4)Q&6> zaXxv^w<83M8`iA;uY+% zYZ_Nyi>w!p4?gkGM4hS(K zWWxs50%iq-CV{q5hJDrpt_H0$+>XUEI$rOdpQ@p$;3Nl zcXszaV9#CT%S2Ywy}$o{pXsz!t%dXG&}fOBtCUZHpRe=HwnX;4-Ndu~qfL(_mxD)+ zUlYc3Zj3y`F7cv@HkL+p!(9uvr}Re2u{&i=Sfi<`{UA5sj%Tio$YPx9Qr3!3YVNhC z>D7#5I^cOzat2Z5)dT#*&tCMBF%LGg;}X#mdu8_< zONX7fY4j}4PO*OLScO>sM~nCQVf$=rb`qSy)I2IJ6)(K0kg-g%c=zv<;R`ukPdZNT z<|2e84&i*C05b1xhBXbLgI?z~jtBfa{^EhA0`24NGX8IPpvW6DSIIR$pD8>SZ{b@DG0qDR_gsq4b*?+jk!d^m;EZ;3!t7&fQxYjyNtBaP}B+>!x$P!K)|xZ#5Se--XCm?rv@C zt&jOCpPkVn9P11XyzyD!gY>Y}C!V0p%i7g7eS!br^Qrn)#nHQO8=XnEu+&hHGaLfl zwAA{wub_RMu=K?6?U_tAP3Lz%HWfN@K5lhoV`5fJIMUqQ!0a zHmUt%dXr)}1PbKUVMzUq}IKMqvCSQCaZ&`p;7 zw)1xXDq&${_YW}yqmq4K1)qS=3g|M6#R2j3rx*}#70K3jH=viguAUW$1hC%h-+-k;W84h>4sa8|sP&z%a0*3kpjW!TQmLbun8{tO2D> zT!7sge#WU#5xLF#$3X6)EXn|ZfD`$P=?zWh*Fr$L`G>*AWqAsKRsVgrM%4v$f^OyN zn9orjJ5A_m`6;D&buGl;~*(dEEsM_nOLG5b@V z;#qly=5phnFbp~rtMPPdA7y*uNP|8_Og`X5%vV%Gyl@RUalDB%haUM5u`OwP zB7|h?JR@}%eMg7$G&@!JS{)tK7bk;GPpD~(wq2@nT_jCh4>w%TsdbVQ?}4!VJ^fHN z)|D$(>|*hOaMjNjLd8;-Gi0lMb8h+a&(2TtPFvV6g3PhQo8qtY84V^}N6-!dJ)i1Y z63+OFWS9&_NYM;ID91$*_rk=TcR?mIy&g0A%Pj*yRulm$2lF6{Ul;Mm^y}uqB|nDC zIu19ye;xZD7ZH|tmTK8*Nic!Wqe7BwC@VabR)hR}AD|GLkw^ni4~R(QsnVA8^x!Sj z7ihQAXfdzHYFlngVT&J zA)gEmmJ&8(w6T`VwFCnM|LW47zQl)d<%~6DD{s8g%xzQTnDRDPH`IdWUwNIDI2 z(hg;sUm+kCKsn}sxO`KqykTo|W0b%hR$lm)01mRgwrBPU9EpI~S1%poW$HUkG&trZ zDhwpfRfHb$pwTFJu6IZ&eg^LSpL6z&$ss*&Cm_l7Wo z&P1CNLR~EmWVpdN;nWfSWA9ZM#GmGj@grO2#JlU(AQBnzp%N;^0&6MSr!f7%J^=2` ztEI$eT*4{|FA-}#hP$&0_du-hS840bzAGT`k$$P*X0N>2S)m1*0^tzu&P0S)d;Irz-kFz??L%t35l2%DW2q{ zxQ(B30lgM#naE&d6BAYzZXHquQ)ecBM$HF0`-_}j)1F&tHBoa8(vke{MOnbGK~l99 z8xvOvyxAw_*WK5t=)dn57*v7|2;4}>yanub4VS05DL9d38tPtbJ$ZX2q~r0r-6@dM z$wUg#Mde_RPmIoUIwweL=l6RF2JWTNpZD@nHuU->d<@}TW&I4mLCx{PLG2%>(lU_% zRhj5>9vQ6P8RFD+RYkqQBw5->A{6S?)-2^x`bR|R$&H>Md_<+(^4DsyQg3smVj`)A z%b(17zhtOn?#nn|7oSgK8vozh<%KcWPuf*0*Y#f@p4cY;Qp*c1^bjI-xxd~Fnt#7l z@#BF!!(;j7kDu!=vpY8`F^ zuF&u;G?SoHyi3j_*6wv4TC4Th7*drALy?lx;jhHm|e#ejfmTanvBOn@Z7BM$nzfb`NZofAq zw89b0PJbVcTgO8MbCr@93QcWQ#Z$$?lr+je<|_FK$?I1Re|yD#eu@T$fqyF?eNddxK$r$F_BbyfZ^~JBXb?K-n8#O>7**~|vrs>SrW$>KlQc5V+Gbmad3~=& z9=rIBg@>H;-_#`kjtDGd_B0mddTF+UEAj%1teEGU`zG3WTB3F;zdJH~hl@<&zx0oJ zp7_0hd^PC?7<*V|>iGO_?BT~)5&hBGvpG7}zxR#koFO|aGNnTUHK&kU!AH7zs7UwT z)FXr#{Yckcq08&EWB}Or+jtEC_Q72v`uiC9S7jeg2h;tVD%B5lCb&t)A>Z@y8Z#d3 zU$4OTI#L5Q@V^02}FtNXUKK~J_Ir{5*ksdv-cibwW zu1_i?WIsvY1J5@6X6%#5i}-hAABDzwd*EPjGQ}<*42gHL00aIIg#ZgCZW`n+rtDlG z+Dw;j5YOgvnm;e>p`M@fm|k3f$Y6AOpafC3ZkQ||IKy8~{yueplI{!YPz{_vFBl}H;sSv%1KnxT3@^`8&ksA{ zk6CIy`fn)CSy#{xH!l&l_zNkn?@hzc>aijog8k~d1X=ZU(1oU}RJZAW3u;n7YxY{+ zS}61qTU@=R!7*1~fBy~_BkFTX0*@0i@0;M9&kqrT-t{0blKr@aK=t^mX#m=|-!$zU z_3Fn-jtYX@iI=oS!w?Wvvc0CCjMv`z>tsmpDJ{7s+paKKWK#w|suM zIE7hd{nB(TKGgkW-FWRHm#UJ$!c#9#d*WhJ>v$1L8-zjT(P>r9E~6xpfdBjX(*K2O z=eZ-Bk^jSG`lC807iqpg>v&}#idX$y0Wzr>p8sDV63L!2a94(Onz*f+|A%uOva8zU zbD8POZL($gKD2PEk?I*NiTO6k?>cvyy_hL1o~MYX8qqh3X1bG6Lcg)ycGd7g;Km9s zdA9``NvWlPAlFWZ2bAko-pZ~KvcpQ{-Y*YV3INGa?)!0}Q(U%f)&YyK zGyIeGJD-JGIU59&L;vxu^7q5g$Ykgw7 z(kkuIGOuc=dWIOXf+s$H?!F^Y{N$+)^v?w-@xXxTQfV0gKgfMs=xCJ|05NH^~~K<-u$nSkb@F#(oH8TVqPs zJ)e2s!40rZsqgE_)o~y{ntJNKGbToZgr5WX(k>6j>SR)9Uw`L(Huigg`v1flFI6uO zgAC=#(6;g%;7oWi>Asju<^krEEufBzzh8+?_?JxicVYt3F)iSo43qy;`f>lqljinF z`Wzr>(5!LoVa>~I0{|e2^q8s4=e&NQ>IJ&kuX?lrLVp1yEsxpAGQOu=)X=<g>OTD5Un0l9}*70Jp|a;JiG&kxu#qgny|$_+v78Rmz?9zuobB z%Kg{v!TD`dHleoc#ke;W;WKHcW%7G=Bn0Zsk)OBa`*|UpO8m=4fW7Q@jZ9L4mhXU8 zU~ZW%X8j{O`YF)7OM^c_InKZZ_a>r<-A@o_%aC*9byAw_v7PV8eBA1{OJDRsHM!B@ zl&H#XWej*C{XFUSX(ww)w`M1M?I}hZ@YYbus6Vp^XgR=8O0t4nXFL5WA?(KNIfAWW z)S=x0@;wkcsw9}g~RL)gJ2SUw|o6L zx6Gtc`mLQa(G1p&JbdR5n_{vkxSan&LqMMfmon0#CPyyb4#!3>@!C^RTjEPrPZHi+ zFCwWQyCQy*O(nRWwVXzqgOZ^~jerCIS})RFxIuYKq6YT|(JAGmi3A%f;Zt8tMk0nh_7lB*)bj zf}^2R@Ia7T4)MZaF4y+H8HA+aiS9N^F53|pt;_(+i!295eNyJ@%S#P27qG0u85(%+ zbVxTyd8R8(age-C420`@Fei!Z?wJb7hd!l}=8G(*6aw*FFi-v(8vOPK{}<@}e*y{q ziN(VEBg#-su%SO9<;VMR2Q&++`#m3BCbm_{;{G*I_dL6zCHkKu>RyngT`s>yr|doBm(#^o@;+)yKKW z^FINBguY26Hv%Kp9xr6=g2%r5o2!$K!+8Jkh_&FGoy~YfCbg#IMV;lZqQZy}XNVnM zVrJHtUu!>I*AUo%+Fuq1n*C=|socM6uKpJb;#8W&%Y*D}K&$&BDD5Bq@*SPLf6SZ& z-!6p00~^nQ{ugj7qytp(vgO_w;lJvsfAyD>?!V1_e7S`cOSju0QcS)WWN&0*T-=98 z8|2=3&;L=XJ@>UVuvd&_ni?(=X)GA!tgtBBr=jn60&HL0cAXze=5f0Af?FtwSXATE zap$|!o+U6%F3B#*7pOFX4Qksoz=ig1`_i{zuF9PM%U_=TkIB{-_d$m(>u2m=WT{*b z1c-gfzn==WPM$I%Df@T&?UnDD;Ng~b?`0@t< z@M0CW*%@m&x?CDZX_^Ba(M&&eF?gTS>KwSvN{2~Qj^<+IxU`lMa7uT+?OmS(JIvZ`kXb6%DhA<7Z0rQm73#|*=!02=mk9Na}`(ghCM6? zY>N<2cMN4tS&53WFraT&%bv2uJ*D(AAz>%{2$DmHn(?J(Js9$@C=1o`r#}5cq<3#I zd+r~G;6xd^Kbe&O{ymdk5KrI~@LWoSk+#E1V*mZRNdX7@@b3p(G}Gb&N5*yOVDF@~ z1^tHNt;U&c)FM^8cz#-4_8t)h+=php0r*{-HiugoGATfzlCaFW)R`ucCN8y#Ln9ci zP--gVS8CS(N~6`!Ky4`ZU7k>9?qlK-lXnGxKtuvJutQMJABVO~m=->kN7xy>CCRDV z->PYguPJ#j;;OZ${UGsXOz}dq?={MXz85CyZaBSs&WEFk`JLG*cA8SVc^bn-?Od7W z60<9Ad%A0w<0A!44QJ`uQ&RD-XUooTL~lTAt9D|!{1@Sq;}3V%AYrs}m^W(eV>S?} z7DORV)lG|^-iPrdXdmq@EPv?j?7F+Zx4o6$iB$Wn!Nnt}cuCXogOc~alQZgQPk1zT zI=2_Y)O0!zv+j&0!XHUxr#uuBEk?N^1|5{PB92sr3T9%EHPiI*BF8Y@h^3nY^^TQ$ z;kveS&Ut5zvCh7dH+LHk5=0%E18Gpn%?D+&q0EIzF<0v|RLFwQDY7}#A=Ttn|BfPS z8|hB_RC5#XF+tiz`3@RSXt*}tlLAm=vlU4XzbvQQmORKYxcP`k`SREx2e{HpSM9ZK z>k!LdT<768Nvja<$&c|4Ot@Mz5cji|zO+1=Aq z8bk_c;k>RD8*Y_Gb5p=`W--<1w1g@Bvg+w{rx&GGLEVd|i;X5&o~p8T1AZ|afVL2&rMgx< zLgFwjWjN-J!b+#(iTl7<$5mU514;}>MK<7Ex-f(#uq#v%=be)x8gEHoq59Z{mM=;- zpz=*uY5?bOG-V*qRQ6mj?#C5F^n-*evuh#!q?%Z!y$JY!mm%KnB=odmK~vPu>B&^*9E7XHre@H zs^2}+YdP7MqV$J8lq}OW6Fv@&yi8$C%y%Zv+kx@QS z;mcHkZRu#9IrWqwqcXymJJRknBX3hYY0+qmWwRwNr#63T&Od+JFm^QO+uqSi!w1-P zmc}zo!0NnjGq0%mkiz^{Gd9cmlO_z2zRzuN3g@I5y*>tmEvD?H%C=DR*G05ZlGKWt zL_;N_EZ1@Girz(2EQJhNgx?hyV;~ z#jfJn@m=UJoPPbTz$1dT@)6j;TYI^P+YEdBB?$?8GNwMb9OD#kZq16?@!RiCy{tT= zPKF58JZ2yDB&K>k;uVK_bJnT#tNk2x`2$o}sFu^gkh-JOiv>%A#DST_>+m&?V$AyQ zKPt1}3t3I4Ox#_2oy5oX>iAuFIj{a*<|C0}mZ76nEtepN5%b1^qfM3X zy>AKXMt%JgpO2)~WJshDSu zBlV#Er6>D1qDWpooEY1fK1?@tv0b7eg=4d%I0rsVBnN2k#kT$LqwC?eBe%1Df%*wh zb>UB|K=Q%bWCoy{&dBzhV)6Md+jq4Q-f%!-K@e0-Dl*jVY!SZAcduSi&69spX}Hs7 za zB?Arm7TXvw>!36}{#Fw8xmHi02|kq!JKaMX_ZD)*eGruiW*}2QCR&Er8$6;d(umjd zMEsm@ER}cSrqF3QJHh?d(p&Nc0`RB{z3dcV&I6efEnhC-zi zcrc&A=W>6*6-P1oRa*S&EGJZUc+nF!1QrENT+WlC$YX4Ni64pVt%t)P zt>eVU#R@Z(aO1}nWC);*;mS@aORI?9iA4(g>H*sV3#FrL(x-FA6~KGj z`eyNK587`B6$cne&Jj%+L)!$osx^Jaff|Eo1eXY*aTgaxMd&%&^r+A)s+w? z$9TB1a%tZ7GyJ0%;(}^n;)~E`c4r~ zzcrrnF@Yns_*VHuC&{LHmRfZ9c3*?j#(k3Kdu!T_VRx-;zp*{leUls}j<34IFw>r* z&}g&z;hE}(BArl*QPVxw@hZJF@3E?!c^7?)Tje8;)60`xQkeLXT-7_!P9(tWO@M5B z`E9AcIR~gI^8I-0!_K5cGBMk<3e;5mw|qKzFc6&QR{Yz%z=(ZAhDK;n>+p-bwn&md zX9QKU1JW+_paYp0K%d*DE^2o}sxXRpzH$;J_~JS~$MgfoJL%ful&MrP`imKKLO9pI zDb4uY#)Qsz-xF`r4d7%>*9F$g%X0!NW1;}V7^;f~&M%|<7%W+09LyvpN}gsb`7K)0 z6+pmw;i~Pa8U%Fmj`=a=i*7%T)@q4Pd{Xg*))&4lny|#f-RVkY$5Ckh=$+LVd?fZ)4#`Y(O7okqckD>3i z$UdN{lnLNw`KEARQCrTF)df&7_)0DkMC60mPRBa$nyrE){l@f3o=T{8tvAzw(rdK> zV~I%Wyz+cVx!$KtA%=Zzc~24WB5&1x#$+Sn7Ah`}YmrV9%C+m^-J@ID?LlZFmNyCS z7<31d3mf;G@10*G?qM)tgIew2jtodfR{>ihn#x3Ky4vadAOg14{+e2jt%}+Oz<F7oMiYe#+p`iFUDDR zpe)5(55LfgC7fz85J1>lP;ukJBop&XDHn#Oq>oZihbyr607wR5qJ{JzadmJ896UXR z01~E62Fo54Mo|2=8Y(z5Gt+N1H>$!R*DEgZOcXm%_pmE6U!((B=T&XcGKE6D@?NiW zD?Y;qmVI(MYw(B{HHIT&nJR`%CzvYR-5ocSCPFosD(C&yEUFeu zCN`?J3ec>ow{y*`YIo#&SMz!S#qGSaFT|glPVvz{tEx7y;b%AA<^*L6P;kp0s_w&hYf%}!nGIGecrI_f`|iliyKguq%s2ZvcV0hx z3pr!7=@&eDWHTUwW$|^8ieuyJd)d~#;1UHiV8f^)lD|9r$bN%uXa;9*cT_*@xzeyf zR{q`tg^3-R4}inZ*f{uP=guVkiXq4N^TspbaY1j)&-PLt?}vJ3UQtf%OJ(1u8kAGo zE?9RzF|X} z)Jx32+)!4KuKU(hy5)G(^Q^)7XyrYBV(0;det(KMux&E%0C_qeRXf17*7pb3_Tg|<--Ztej_Xu>^5BPn-H2sRaAuOAP>0P z*95$E#e8g@c#ta2e30%Im(3iE$PO@INaAR2WP0nM^8Q_7o1r+<{U<>PkLFqK-tRk0 zmx%5fx^*Wkr%4<3SxgV(qI)!Fp1Wd(wNSAf8j7x%l7EClu62uRS@>#66ot$r`j1j)~-hKjde^!40G>4$-yE7Y8R< z!ohOCqZr^ve3Fdsv@ArNTOH`2m_~*$C#0eB?qO;m8V;|{!e~g71qCGjDYqXgT1jgC zD?xvXm?Z|l&&L*4J9RUCNqXkKVge3ZWCf3ooJ#jlYR8VL5I9FRnCm?iRa5SUVzOK% zmr?&8HAsg|06`F#gVs{;jD) zJBfl1t!xWEeo^b%8WS8hPo>&!G0LbX8H}%LBP)Bci_*F_lmA$+^7C3HV`lL|jb=Zo|8&y@G)x9c@1+$Na z+#22emJzQeH=ewZm|RgGsjLrVwl0tR_^?IzB{s~KxNaQ$SjBq);~UE-ChX@D9)+tf z3VUO`*h>m3ps?~7*?Gq?bhJVN6=dqgMAZ4IAb*%G^~eX;{9UY+D5PnDp~zEeP{9$o z>Q+9~-Is!A22-VtI{(@&S6)fo*jJmbJW@C~LZyr%R1ZknWhE{MWtNqX|@H!s}_84_< zw?F^Xj?%Rq$Xj8TTeucb8-e%ma#)H?&|T0-kw`By?~%>MP$f0a2B!lJ zPK^qRv-YeVD;!7mez?AE6W&CUqUcwg>)nSLM4|LO6Gz59GQ zrOj?}mCypA)SA|tM%%NIvyG)st{@ybZ8v0+Y;9L`qET&kEE3fOk%4*}34!-aQP;rm z?>Hd*$RWcY8Q@;SQalhKOz-x^CXe!zIvCr9`Y__m%RGa@zSr{tfm$0I`=rch!1fV3 zRXZ-C&`ct9Ie%#qy2S<<@hJ+cQNIAhwihC?4Uj{eaB`IWEy}KO%6h?y$w6_&zf~p~ zTRq4oiU+X^8pT(=@lB4aSXlualNWC+y9i@K{1QibvqnMQU_~em!pX2NNLE?=R_NzD zT<^lvdq!5WG_C1ZJ(EMZa}7bVccXU=PnIbp>lTL@5N~4Tf$q1d)U@#H5hm zGCsgK*%>V=P>;Gu1cfrl65sMhUaWzQxC3P>X|R(CfGeAm&}+254T(d8 zJILfEFp?bLZ`6MD`k{S;_Z^p8X6uVxv~lKldKmK1X?s~Z!Ma`9Y@IM55V{Se*=zKd z&}O*#*NcJQ@Q0-HLclLr>a%Lr?v+R^_1w*oJgyS;YP@W< z8+PXA4-8!<_a;=5-q_WB758UPAtX23|A=0Hw#HG1yCTKZ?EXoLb8-L^Q>&X!k8!du z=%J?dNC+_|;~a~E@|OpM&zN7#MJw=CF9v1Zs_q<>E2v&hR+0X;oaMsIy;j;d#kHO? zp;8K||%g^)ZQCLIGPCmcZw=P}({m(4%9>-N-WR9DMdjk)d zop!$o^*>$7Vxw{Xx?Z@|u)5KD=6vv_Rpz#IuS7V%Xb-7lqc`!)h^)Fm6D(1YtA$#) zX5u2@3JBBnm=ZO-@%J;fOtpZ$V{Hn>14 zZyW?GQ5E4sMedD0H;okY1uzvN^Cq}YGTRxz(bkL-qV}>_2iB4>sp%`Gi_rY73BfQ| zdRQH__Y=tijL+NJ#IE`Jz|CQs?6aqENKq>i^DBw^ASksyTN?3}yFv@}>gBqOTO%SO zUh;OGKu3XgixM8nQryIu72XR%hcB5a$*?1&iPcoIqKS7Po5jkjNT+M z`Sdf^0L%3>g*fFmFUrkA^7RxdqPEwSCX6TP!#Bp*tOgpurMLJZmm0P92swn&;;VL+ z7)}J<(k*-%TMNuG`=n``x*1<_N__@(KhCv=38+@-Gi9?l+TWaOO=4-}J2~3hnfp}O z$bWWrijaLxH5P%aNx|Z|3D8Ojav$vh&h6f>g^o;k(tqx5?QfK^Bcd|&j zR9~vZY+XM_pfL7hDIiSKL&2t+)YELvP7C19#M2C%Bj->IzKbt5AHqX3rfbz0F-&FJ zd`E07?6s5$wE#Tk-lU(jCdy6CSs1ljmK86?GQy3WO=!Yb%f+Dhg?FOnWcX=9Toab5 z?LS6ZE*|JO5`-cfJGlXBCn?@EL}SUH@oMN&gXve7(>;~PjRm#w*!&!3kobAWu)HkRIcl!j3aka7IBt(Q2|!MGb*kl{-;(K@%U*dSMH`#CmZ9&BR(s z=AB+M1H?fZY+gEcvyIZx&D@P5K0lw;ggKau_3{ZKZp(^~TpG+JLN{{KYb6@|_3OU2 zm~GYV8@ACl9QUkk<=~{#-_9f1(u%na$wogo?_8e`AgDPk3ISM#N%%G;yYX_TxHO$b!pzLaW8px@@=DRu3vM*rn8`Ss~V~C zXsZ;9h39hzEf(cg-*u~_ZF+Abe_oDCigtWvcC3?~9)jTG{VAWfya#jpCZ~t6W$&N8 z%}kTIrmWQ3$Z`B_5bMS9Uhn_m?XBaYT)V#SVHmoRR$=H45h+Cn6c`%mQa})CkPemZ z8iwxfPLY;S1O!B+rKLeYQh|9+FfRAC_qFeR-Ou~HAO9Q%#x=)r9>-eix4yqyw@#1W zb9(S%p2XCoe4b<1@~{KgzzDO1I{Y)E)ZnAznmfP_X|f-_<8 z%b=<4AVYf>7=%{f3Qou<#I7-$IJ?Zso-spr6#^!b8 zFmncV-T%77Xn35%7a-I7faXhlmwYaN+#C7YuJr^9WTL<$!J53LMTT!XidSVwe-fPl zKW9=DGfja@&{BQjU!rI6npyB~JxV+fsIUjd+Zz$GrYS_qNb2Q=sG zeA%n%dlSGoi|LNFvpS=A44jL0RQjSQ`kMt5bU*0IL=HAIJ#CyRX-Bd8 zT|4{+vaY?)SxZbc&^)hzF8-zX3o_9eD0y6@OG;Vn&x02~5_=q}p_ z9l=z*CX-!}8BKne?9bNO22x+@qf}IwWCqgTcykere`Ed>C#DP1sH}d(?-lLAYY(Pk zx6gm)BZy)~+p^D<^&=+lgCJlAszIVceR}5P`R&CQQR)h?eU4rvRg~Rjt@j0e`FF8I zOE}64A?(tA=IV)18GX>RiPaDJBiWE#8K(FrG+)xlaFV*1=)Xj&6-7SAl4TNA@1{ss zK^|KKT&2HT5bjZfUM?fSnQU+c`8D8uWeJn+dQC8nJ>W^L3wiCJmAKnF$aFWhd8{<% z@f7Z36MsUG$lh9m=7q_pO%2Ze6)l_){1!gw4*@LN_rTDe2j&Qb4g_X^_IqG}2(^PS z@d!h)w=+6JC@%|M$|nIpwYb+A$b#-N${?@^Qt!NYH`U_NqH#a;u%EdzoFBcodQZu_ zNuR^s1On~MRg5KeWdSi@cbh++sW&3iue_)4JANa}{n-)7Nnm@(IV z(jSRyp-@>6zUB$>k|_pb6bQ(GThLBx!y2v_k>UhIZ4DhcW=qtFMIq>!y`s5QtaKbP zj(E$&+*5TUAH1>eY2{YYDIkE28gYgt>dKe}JLST3!Plx%#V8*Z)zu0BB<^<_4H_G^ zjADTe*9PB#GxRNM8b!ONhIvI>ev#*YMB_4u9@w%I=h67NOaKFPPyi8@gfC!#-Wj}) zX+l;97@$XxUQmIY3IBo_<#Izu@6L9ES_~*|xDHIoAqbgAzkNWmcybGxF$__E8BvJ1 z<%7!%CtG|McnOCE8v#XA_E8d(9ZPs;C?AQPhZ~K6n0lsC=CQylW4V;Gu&R(TbGvEx z+-m{5peh+KyKc5lP4~Bod!CilQOR%RMj0eiO2C#fq%RhD+g&*2GAss%Z|QEpP{_=v z+*wdMdUZDkBHG;BN+${j=C5WM#qFAU?1m8P&cXUoH9y}L?C8LD0RDlnAs{pe9r&x~o0anXTiE%-nuHHP+kIQ0 zH-`l*I;O1yZSn*O+10L5Fg= zeY){s)w!^kl69-dL0Raimj_90RcCEXG`AP!Y0Wj4Y%+Efj78(@%Gn+IUS~6jc)hDX zRQFnG2!e6cgL}pQVW8+-nFrHLq*UN|nb=T`CNI;Qq%4crTKii97d`EZnqQ0Htxs%M zO+?YMepAQ(0Mxzdk03x?fuToY08{CTCUSm${DlgYr_mXa+2KKY6}S3lOXE+IAcY-l zXYk(t2Sot9K69JzDpc#k2$q+xLKx+~4?XH%Hkz6oPAx%0-5@&bd{I5FFCde2|K9!= z5Igu@RVu;oa0^7nbZwu*4Tgl2yMLy&j_I`mwW4Ym`jX9Or(1H4EAz%n7QIF=Ot7BX zHXLlu5IjRs(lyVxeECF|_qzH1x1KMnZ+fI{%55cZS}uU-3_R$c?0@N$p7sP&U_-sI zSkx|y;}H&}!-&G2lzqt*O*6#FAGjEbQ`^?<*x06lIcjQkU&^@`CkK ztf1Nc1dB0T++PfUwaLcn<&HhHM8PXCJXBhT!^Qme0&){w`j`xp(5t@yAj@k0d#S$N zz9cEA(ZOKujZtJrlAqKnsquS1iV2VeDf>z;v*E%@RNFfEs8l+L`sgI6PcFo{& z%0z+%2j}eoL5f79tiHlEX{wS!j+}~34$G%l%x3E)kdGqkm4Zk>08nI}z*yBjJRYAi zWKu+2-tSbj@x0S5k;(a`x2{!T^SJqD{Uoz1xA9=5oK@K>n3K1z2S;tO`QTX(qtDRE z1aCuHH~G)|3$XsM0Sk^mG|B(8{$!cD%pVkak+c4BbXvymlr~q*<#YDWA{5ITeXPg7 zMyKtnS^u{T^FI`!@b1e+FVD0GUf{fMxgTek63Qq?cw_^N`{8k36gXB2hUxlW38B3= zFzg9Ql_`o{A2qOm=3|+&9NGZoY_Bsx+4XCi)1fjaa!Aj*X#EXBB)IQMnb=1hQaImK zquaEH@MA*WJ~2m&wVAb3l>4cT+wKbKlK_1>O4j9#j`_StN_3kpA61a)lv-m>C#Z*p zLY_t~%g@i`Lxx1u+0{Ffo*8ItvzjFchGd8?zJZe4slu|M*67a3+z0Gfu7q?mO+vKWhym@vGzcjN!l~hB4xL+iq5bSfy6BMB)dj%rpAw9e*iIYG#BQDKOwE z-R6=Lt9~p9XPnk`1Gtc}7w8!l*7fV9Ynz@MZQn}kcZTIYH*L>dw`o4! zTq|oj0Uz@kW4De)HiKD1x7wU&-OQ{`2rluplWG=kbx`Rx7NpoIn{I36oPG7{*)8`!m(b2DT5PJWZn}SN{las+*@3#*xZR1B zcD#+=IjL;g$H?2X^Zu&M&fw4^o0FYM&FQ9nzFM@rg9RV`)BPonh~}epo6n7~MC@!o zSW4Eh(bvQ0Wv8b{WuI@M7~hZWwXwj!`=KUS#|iyTwalT|Ot_RU0wX;Q1Th(Gz0h~z zXhQKYJPy8lMr~xiYC;k({mN}w)%0+ys@h012OPMW5IBbLcIxphKOr?kg2!FAFMBW0 ziUws6qnwx9X)BfQaSsub#+ly!KyW2M+BXv~1m4L;^Eeo_MhB|Ozs2oV5wd2YL4&<~4F0XG6zKd{!7+=B=c?~<=M)=Dc zQyv9&i3?UD!qu3VSj}EbYp5XOLbF-e6J9HrAdxV*a78YWHYw^2a@2XXf#EA*WVv7vKCO=Za53kMS$Jghopi{xog* z2coL+qtPZDMFsK}idU0*jXzy$dH>2T@ow0X0PDr~Z~7eTFQj}{W4-ZWt9FKMUv%VHSg{a!TH>DbqpVMK+>-h$B?bH1iG=@JJ5H5@W2a`L6FcHa$k zi%z?EvMj-iI~W?glWnm=ypNkX7)#rcgXzUCr!V_He%K*b@GZNdvusk*zFOX`PX(4w zMAgzM)bo$&%~itc)v`+k@|DHR)sjR%rcb-q9HQ} zSehBq`e%K3!+xYfl#fxkjtVgEH@3tYMXSF8a7KWle?qV}qPr8#5qi z=}q=v4K67V+8k;Pc=}4RIR5cWVgx0pBL0hth3;@}RX}Z8^{6LiI~dcvs5McitG*UNY&djMNfgz)MLW}pQj;&pl24KqUH`s zNt-@^r4jX@hzK>>chwE-U6f1ogy$ZV)FU#IA&vi~0n=3a^(E9Lj~3J^$b3J|6V1eA z#tKryFyoBRb7xW)yf+BgU%{CvZ>t(_(|ACfT%ac9PxJM?=wq?xf*5I7-hfI#!%&}5 zoCRF*TuWgX%SKG5rynJY5JKx3f3~jGAwiICB%HKhArct&kM|>LhR50FZwSanpa%*K z@REI0>#;<)nl*}%F*IY0e-vJjd(X7?g-L>0WkGKARHP8Gog_|c91IP+V+wXvYC#U9 z%H)vhW+Irt6csA^B0nowO4KmX;cIUC1D*RE2r-*I<5*ru&HGod=HshT1^6Gn^vLVs z4!s1?d_}223j^Mb$Cu<~76J#tgI7fb&6o|NWgWP>MHSU6^#(cJ^jICRg=2dqMb+{P z%*Rqzk$? z9NLIf#T+xm-!t2kRqjk&8{zl3M^&^XQoHu(eQ@#q2u;Ao{&32$6#v8{AF+dp`}0=L zQ_ctFDMIbqSc>o3UYB$f%mlJ-B6G7Mk%)P)_)X7+Xd*S&h1f^oM~hJwQzA=o9z1T# z8JyN`IsJqVhbzU;PX`9|YF59lSGTZ$2+~e z&)wz-g?LYPo1~S*)cZYRnr=_%e?B>w3E(|FT!^zdJz6e%`1I>K*0XVdLCA|b-W{<) zog6Nep-zv9I$Tg7{B#f&wlJ86kMqX_<#|?t1KjEu(0GAOd;q-sSLOHep;iqtx(B^K zt5U~@pABTZ_9;>?AqEY4B7e-6cX&J(Ev^0m8F1QNipn4O2Uc9#z85hTZ}il1t7TsQ z_=ClV9tuoQ3K>r}|3VGXI@^i=K5zWT**45$XTXXp|C6=s+xo>@IOqn?e`h;BA0AZo zD%w@}4T$q|f>LxeZde=ZdzO1n!NUQ0gDB5qvGtd+IA(ne?fk>EilvLqchOj{%VXva z5AJ*C^7+?DL9DMmKc-czaR8T|y8$KV)_}j+qj;B<0E`8~@Yd#r30mnHH!u!7p0?#osFajO&m%|~y`Z2rk$0luwzxyLz zmW^IMCnWv!h@oj@K4-%Hi8_H3k@-tW{%1JjzYs3p7sQ*wuyeLf;Kt>lP(WQ(pM2}g zAJIW0Irlr&Lqh}Iz=A*lQM=|ZQ~&#@UO51u6ahe#AnfZP)L**_KDYw~PA}s+>mQa( zA}UbHC?=v)*(2f{aSw7Cb$sme^!$ABU;~Ti6Nnr5eVu<5H`!#iEy{n7+hA5_@I|HA z?{TC5d`9bFk&5|a+=kL%XlIJUbCwXPOk?Tz|HB{+GUzM#-^9 z<2~PLC>YbY3ST)_a+8z-6ie!@z84<;zAE(B6&s)`^k2OIIV;HiSMT^=ekxM5auD@- zb&CjuLZgBcd$xL`6EPhB0vG|Gg8>--4?6!DdXUGDpTWMsaU&3s(H1~JDUqx-KrbFb z#>{g3BQ^e;Pk&yz3I_^TG{B;mKPz3qe-se!nA&FC4rrmdX&gT=1q%T)D<&WEKJfIQ z5fVLq6p`H(wr_b7Wzf&q6~%~V$sR;vBB5e@%8cDwNnW5)0&rs<+RxmAf**~yQ<3Jt zVy2H-6`R7fbd?davjm6Dc;!U7hzVYF;w6rB>84BO@L%V5Ugq zolnxp+UCM&gztHY{=|}UG*>dj-eZHAvwTCm2MY_2pqyET(?{d-1H#t27~cxIx0u-S zHN|8&m#_J2m;z(UeyJ1`AsLdL-)><-(QK!1!^+*Dr%)YsQ>gg!PL z-qDSWf}>dxxth)o(2ZBdfnZz11z87usd_UzD=jdKembQs=RF8|X;!%WO*e%F6cYOm zs_6x+0af?hMt)Hryo(M;z--IN>*yTvnZ53VaXAi@Oc9qyFPf9$LnTSc`Rn|A$C4$Jz+Js#C^*|xfS!5=06NZD6ZaQ~v$ z3iG?*N0N5KF%}!6gW(XB=usx4j4?Z->lCuHh#1Yb&Scs5GB{Hpgcr4mP850WL(9O5 zIu-+^RFU8P&J=EH6GwScn6urzQ~P79oZlP@fO_N-i2o1YF*@qsWw=yVagTGhq0&Bd zc>YYnb_Q?4XjQ${*pbXKaV&&pZ8+q`kfhqJY}XwUIaKUrU-H9?UDgL%qvv<`(1 z*)74ES>_+jw--QVu!8+d(EY;Elm}L#_vC5;8Lst2+fznYd=i})kDoTwJr1;j6Dao$m>7A>2dSQ+*s=_W)R@##K5J#y9?s7C^c9+&2zwBnJm5+^!zz>vM;$YDBI^{pnA#J38`kx<`v zY(`{guUtkH93zDS|sa5-Lny)0W&ccP3)gRm>j7DgY?` zID>k)QM^Dc<6;7OXvIVEj(0-JtYZYqfEWmF3~)(snb4AqNXO<85~u8@kv^Ef$k9_4 z8cI&Kk0PKT$creDxXjj~KWx2jaT>NB9ht{{`ow`qD-_o__m(PKMmFpczB1GwYaA7o zUW_+LQ{<~ZhMQ4}y_2|B+&WCNUIH}kEzRq^>js2RM;H2lg~B9RfF-Gm009Lc-MH%Q z+T5c16u8TEbFm?8FP0K5*zA{SzQ$H=5}FN5t=3xDG#%y^*)$$8_~v99le$i}KC^RO zY|*E+aF= zj@R;E8X4366x1;~ z6uACRkt~aNZ35SSly5y*ZL;FpYR$oBgLv(6lqVU=ljqy#F2=Gbcslx(CvT05Qjd4v zL^0eTb~*JCW-lRDJUJ+ti0;UCQA`#cTlP`9@Ojm!<1Tm}o$twZ!CLi`Z-;9HUk}m6 zZaJM&8q$I2`6&lvpg8WL2K%ATKo5V*3trKC%7SqV*V>zr&^H}3%dXzz(w67tOnpot zcw64O5;zHZo3zUyVu7#Jm+uCysy8dz+*p=Bx+#`tJ$XB=P6x|n{`V|~Oar)IM3g;m z%4fcNwoRm4-A1utDoI*v(8#r|9HgZesAEUj$PG7S((KKoVw}rIn_N+ZU&^8hc@-T% z&*N+n%BVERCM^+9H?MSDOMJwRgYdviVuXxziSW*#GcKUwO4r;h!Pr_O)4wq9ZViK^GvfpVJ?EJ8n~k-8(EceJHRy1|FvNC(!a?t_qWuL5 zi7($eR-xBJG$zZ(CeAnO<1c=pS5H|2If&j-XiY`UcONIHf`O|gjo(HeTfMO+ zsz|xNw0pZfC9S1Ja=+q;HC@_RgzUH5eK`<5+w<@Re!un3fZYG=y!;opd$}pOfAjhI zuTdu7Z>g9kIkhE{Ug)#+DLu-Yt)8HNb+`&aK7ctT*B?$4;PRyxI6(Uc?5+7Ed>{iB z02TQOXBC=~{SP0G+ym{h`8&pQDcChLhqL^P=r?-g*K&4%zND{6(DR;CJB4(8jD~NY zOA+v)inMFEy5Z@8TBhi=K$OXVbbD7FSDX#TYkdq^;7~r9885#J5uv^DGxJ?YRSnuh zVf$Vt9N2Y=b#3DYFPUuoa=+(}61_Q$Ulk-wc+R`ERg$8$uin)n@s%ygpMMTE(TS5rSojn#PS^8Ep>(PIEVZft7;t> z5x2xSl>AT(-~pKhtv&>+O*XiEA+0`8!qu#`+VjT0fhdQygNZqB){Pp>dq?0%@$}YJ z8ucKqBqeicUj5|tp`Tb9*}q6)k34E!NuBS){MDm8#fG z>WK{prPzF)U;lDJI*e|yW$X)%F|F>`yTe0XE%f;Y-YeWL`abwKM`L~P6{!sUFeL)h zeW`Wo=>0GGW6uSW34Tg-M8h`Fl)$ckJ`+OK2J~YnOZOrm=(B8IWMBhdlF&Aj~8TO(B@!dyTzKn_W)Z;NRb*F+|kSrxsTGyEUtbgTvSqHo?jHu;Iv#6_(lUXb*b)JZpdc+ zQmqA`l6t9Y-MHIlVdMXF|1bo$YrA6IbciWm+6vwIqKNFn)GhJq79hb?!x!FQTaw|XAcm`l_z&p)4k^6@8(aF*XFF~)4Tds^uV&J z|HcIS01Mb^Hv2{QW^uK%mE?7U0cGBkFGGHUvW0o-Hs;rcBkZ1D%fp=If-%)ptL(!z z>94#RHgF~|&qgo!us>osQnL3kP4?B0A=V};MQhpqU9oJfBXO#&Vm*aVis#8z$C4}2@&lUa`6o+$PkEmm zTnPUxb~Kw6adNaCM^t^Z`8=)pc<>eu>Uetz7=u|`o4$pbU?eZbgtz7pmkPvx)dLgN z!Ct<#_QJM=LeLIcF-3`;E;JfIIN8Lp%@H;@5JT*%%P)z{5#ChQ1~@XyFVBT@__On5 z@pV*oTmJ0p>G=2Z+ew;j0|a~N54TpOJC>;<-6ZeKkp!?-7qf2%$qOW$e8p@7<(3Bv zRL`MRP>FM^Jodi_oWJdGDV{`<&_|67G$Z-11g#^(Y#in(KP`8PhF=ML+&h11&-68a z+v5n&^?7PMc$Y*ot6-o2_AV@{%bQCD8nJ$t@qk}OilY*V=*VW`eIp}n&W}t#v$Bzq zQPCNU%I!7g5DMznh#ic{dy>OtBqMiwd?&W9H;2dhO%EWPi)+Qt(J!n!p&ooaiLh=k0%$HlIT7fO zv+!IkmNaZH8o#P2#xD z?_d_0ccvDcBl|~=;Z7W$=gcuq0meVTU;h#TFI?V#=DG6&ah*{A_Io+$Whp*Ti)?%M zqYSt9lO**!PychRsPLrS_RQ~mqPTB|CcSG{D@KN_#TpJarW<^40HDK@z7^A7LM0$N zxPWNfAC2vAqa*n}I={4(e+S54dZQ1%iVIr(ZXnEKnR9L+Yy@Ve`H(;0t%+lDx$fHX z%TjP_@QLj3j8@gdirf$Nu@<_>N1U(J**@ui0M5SE6gG_fk4-?;+8-ANyXWPEA_O>F z+j52I-%Qlj>i{hR;{|NcgG1hjz3I1Yd@t?UziiIr^;Qt8D{Aq{%4CV>hQ2f$uCu>- z2lxXp9Hb*2T_45lYNj?bHUa?=-d-BOV1<+Jr|o&P$V*T6HRVSu7()=@qyxcZ?>Cp< zFOhK=M%|ln0;~*6nwy`-1)!`*JOK1?+y-Cg&@&XdDUcvzL#HX8(`SG5B9<~8xV7_` zS>Kz~1OT0A))?WjQ(3dk1>&4MPzq%FfySK+xk!sOA1W|xIv*zdmjs)j36~AFpME6_ z_kPJm&KGbz=-L0E>;EslBGn~8TL?M5aLAeEnIZPQ9tzXVPCiFJ$z|UvIinY^-N`z$ zl<85&Rmm_0EM-DegPYR9{N4}G810d;-pnST1f(Aff`CT(pU;f71YWp!qnLbCyh)l| zE|qI*YR>0w4GRgJ3h=8+|I7kij@YCq&QSeU6S{Tv!@Fd>qErQUc1tfAQl>EmWv7kl zRtuI$;)A@i1*{KHKIGL@lyz$=a~kU%qZ>BH#*0tt4?Z&}y^j3!v0Lcy%QAVrHFJ6l znRoNsytL0LUscgsvf;LukN8heGh76dBY*|Cu+w)Gnirv>DZLBE{d@og z{@3(k0HrDWD)q^g;pM2`z9Kz!_>j27ob*B@CV2r95`!CP=|M!sn4-~TaEz6HJU;=6 zA8^-3iwE(7E}w6tvjSy#y0{mLkmbf70h+`p?qk1-2Swpf93F^>igAZ8Q8mX!vuEnbgoA`=nfDir##^mvC_w39I+-e1u}xjObb58qR)Pt} z1wBhZq{Py(&`#5NFAk#D9~*<_4G^j*85vS-+`F&hF!q_6g5*j0(R3os)emOmy`MAQ zjI|@TL;A|AUQm1SMx#hSiRn_=gsKZD@0C?eRg7_n{p1}hg__sb`3BZh)#V60lCNJ= zN!Zt^8GLr-`-AvgeFy=h!ptCAAVLS6|ceJgK z^tx?yDxo#_pcjI}bVI#cpj9ppD}dBjYbd?MgA@$)ORVA?1;ps^QC~Zb*HtPImdKqb zrZ))Hmq>;v-_RzFY@I8e6L&2X8*W^c#T{6kX2B`B|H?QqDjKG%MC8ou@;F4UOkQl9 zrf!^~_noRPoyHBF+0}6p#vhHqzp3Z{w{40a{nc<_yh-4EgZ=2QdhZj`So$dg7Zjok z66Z*+AQX?e@3PI0HWMHrhJz^c;(Y@L8NL6-TBGnF=*8Zq?F+k1fQccZmaFI^jmL8G z=Io@p7ANrs!%>MK^j1=`>xg1ll_62)y`tI@@miaYf}wKGrT5B!lM1kMvC%Ie@<<>L zbpX&{fiaoaMipmor9$W~M(ZIer+eaXjLs~U&WMl^#&uiJ74JOBpUzr;^v*l)DH_#S zlG`o#yt1d&NRCf8S?b9UqB~4>b69)N$~axxGB2C9pcrZL|8LTBSmI?I{9g28NA5u%0p*$73Nm7G`;ot4~Zr{ERt z{Yj$;-mu`Wa$=g8@f^9ym8*c@q8l~JQCvDKyH--Q_?08iaC@aFt@V_{vb=-P!m^@k zE@-jRioa*E%1mO-vU*6-!m29YKQK*9@&1df=lXzPvuYs~CpUIPR(G>*wYG;R=Jl(j z^~N0uVK$G0!6KWcZ~MBLCH3IOwN@}?DCbM8inNC2|)8NQ= z-3iIpDe0Hd;ddjromt5|Def$yuD3GT@s5tdyxPUeqMvedaAt&Hjl0Z++$^2XLTV}= zeF`?BeX$s7zgf40a87-}ZH3=4Af`n$KuYXociCPiD&W+0vD)VTx9CemYPIPceb(PT zXQF?0-|8T;Xg_pI zq=m-XMc<(iZj{z;FfHIB{^@0((WPSpOtE-kQvY&as6Ym;YF8Uct*sBILk9l0;b3;l z2O#74RuJ5)hONBq(am`hVpJ_uf~vXPM|ziP;U*gbLTv0Tb0_0-G}Ud!KH?xvE(VH{ zu1;?22yX*lgH#=Q46k%wd>k}7aRijfEAZU|B3C1-i%g}cz0cvxcm}lFE`p>Fdnik7 zk)2z^B&FJxvLEdtp$CE0FR43%tQV;0_DrRvq|CzYdYM>OKEVS_ccL`f(%CA6Wl3UH zg7f5=*)`2%H8KZd3N3TE^hJ8K26tj>dzrbMwdL;jvGOzzJ>(4t>M@|PkH6SM$rkrQ z#zZkc3PRrw8ZYO5^Z+Rp-Mh&2+)T#GDJm((_uWi(K%#geLDI~wiSURYlSO@1!qyXI zqi!t(U6Z}%Ky}2;Z2&JYw64muaFhotljyI zCe_<~DcANYZ-;0o-DNo3-3bx7S)R>yEl@@?Q6-|5ESs0yOkSpNFd?-%SJ=@^(Xd`M zfx`F^Cfcf$tLRW>Y7Q6t1TGOP8=vE!Q(%^%qL#L*ma7p{s2XFgo?-r>*p9qNx2aGg z&wQvdaj)1^p-5+>d$_i~ri2>jw{AWQC>&&t#`pVU+vltld44Y<^bk+3+oJndH{Vb9 zCJ)4$#PgT7O$zAgYB;!(n20A)Js$iHE+upPlaUQDmHJ0*+jl9*|FWC^M_J4tr67Nm ze)-VV3c>QX=DW5@h3Xm&?7jQ3q$q`-!uHm%Dz5gYHh%YsB4wReH8|RCPMU}+IMv*H z-SI0A12o|{AY~92*#57>^cU_FLZ^8DpOLZux1xvtI!yn-i0N<0*nh=$67Od^%6S`xISl$xputGM!jV_W{K-f$9*ER2@-u@n>+-Y02tD&c zqrm1XDRGMl1?lllg#~%Z&p6EUvkA%a3z9N%Ig*RrG(G_af~bEZW3R52wPJFfkpL~$ zE9!Q%X)>xX*^8t3fs%wgIQx(N4qXCX}7Ucu@=S4U3nR43~=9%K0sA+lWwETOA~-dO4kdFdRVf zJnG$kO&bup-E}z%zw!+O-Q?qTj@#=yZQSk0{5@Bt<*Ryyr;DrJ-tcL>nt{&9xjS%& zQmnc`o#9^5t#%y?0L3G%z-6uiU-AVBFqAx4fYlR_%CT z>SIR<`#t5SUTzbIsNwzFL=+^x9J_|3DX%(A?!Gm=xu)IqOi+?tq9XWiF9XGMmrkBn zp~3fy6DTg5v}(wwLt6l9K(up(s7$1WVQ&ICb1s(`Vmrj1jFEC%SnB5H-3UUT`(LMo z;0M&C&jNa<#9nm-pPEVBwYfNRL@XoY@gY+Bb}Y=cb~;3wx*I34^1(i= zl?5{$gr*p1gdqn5OKNu`?+xC~E6(9Dd((qUDF1Y&d*QH=S$?O2C%%ixgg>I7*M$E| zLN7( z-TLg~4+L^WKeMA6bUR5xpB+D<{WK~K!`w~Byq3?M3q?TS8RR4?65>eP3UZw4bjS(g zOKY>jmuLbR)J^$Pw`f#iaF9`n>)EoZ-Gkzo?8qGVPZLuz($N$PPGB_#JYL^|Z zNc@nxDO#k{)2&eQ#( zkz1&{?31N^3oRC7#v6O1Q(GDTwAkd6%-CDe*s8caOR=kXY*$6N=3FF_U( zhYq^l*6==!3N_vqOlaKW=2r)U|J9(R1Sx@N!8ZTwxRU~WIb|X2|FP^?ESzPa&NAdOJU3wV;uG|>;lIZ21+V7$0w^PsE4E{HIWseGgG8{P*Yvd?F(_4!A> z6>g0vpqE)d$_xH1I|BAF=X~W~?vej{BZz2foR#cozzF?^-AL(PKQH4d#c%y{D!?}2 z1=#kVtpH%=fpQS{&ljGfe;{o8|M6bv?`rcOY;Mo(xPHo|&;3I!fWq_ld*Q+V{R;S- zs^)Pdcs}$6nm7qaU@=fxL3E#r0uViY_YY-Khml4vz~pd;79y3Uei}Ud?jQP3SAfo3 zl=m|k(~Llt!sSeWu>H#lgyx>YzE&YHUEs93l9%q!VV-IgDr=k@AoatA6dgo-Hjt|b zB1X46UkmhqDV_gaDeZIpADMkH96v(z!*1Rn^&d)5nEYE^mW}5UPj>g@`h01qoTdbq&CbFy{0}&z`0qce&kqm`^e91v0y94&BXe1 zMFTX6?1lM?tot)}L^J00MUrB4wCgdg3lx@Hk}U`%h#2S0U|a@-fUqBlNlJm5ZPg6& zF(JgQATU0kFPfA9s1n3R#OH}7>5{zDE%hXSK9jhH0gaf{#;~6ot$Yrs^nhB+Nwd@} z`zc7!p_12IqP<&~)8;giVPLa&nmfHdkUg7on-g25Q`r z{pQ$D0ry>s2X{JCU z6q|O_o63PuKfAnE-*(m#9O?PtnBGevnjX6rmQ*X~pD$5REJ&byk3?R>lc78hgl^F0 zrtF_gd<6u@bnW9s>3Mu7w?Bxat6>^^%p>&Vccl-+h8bgj zIW{aq4{xW#(!=7UZw-Qswoyd+yca9RVkLyWr1J$7ieK#`aG>IH&$n`ttSh|qS-!;C zdwZVr3cdY;vp@lZFNhP?;oKvDxCTA(1H;j7Y0OmyQxtcxWE1y>WJe*km_|B5 zO>o6wi8NTGC@Fmd5(chnV>C!P1d|xe*pHvOTUpAJfeI9GM~g^8K_-ok-jJ4q zZHIm}7%h^D0W@leV6S~Aq8d*FA{|h~HXv{V#Y>=#Nl7i)8b)06lcjlA*PjP8;<0fU zxnrq4Yd+G0Fvwy-S;GG=SII=ryX_p5RcTW1zfw<{>1dtQ8xhe57_ zC!@U0xSfif$9_y24jn2uf|jf1jiQ6bpAh!%@4sc9k^tTOVhXl4znq`oi!WmvEyZUs zNs8XB(8y)Nv{QwHQAdPCBQBEUaQ&#HYW+nALrd+L+ z(}rH8%e~s<7arbqu%ZX)&d`cDo6Iuf8iQqp^{Fnj25D3q;V&FYQcJCxYqmeGtzo$W znVgO0MtHd=vCXO0fy@mi!uVAKLD%)(g=@&0*`jxmDqBk5YMMx8ce^&o=%{rEf<87LqHAJ#3AJB)bg zSh|Yy&UHUnvg`@g1IH+DUPwc*5GU~s1KLWm)mUGR<2C{{bWg(^TRa}$WOFW*Bm58+ zI*RS^<$CET9Y}VWitv)g0%){NOy!#<6zUXG+of)?@zO5m=_^lLmcTt1yqoq|&QKR8 z?2=)Hy@FI{20_`_VaK5rD5e>sW*fYYzmnT8P(5)$({=}B=ypL5*BMq$Wfm}$TqR=3olUqK8%TMo zFu0S;;szt6K^nv@1KpJ$t1JaHiAY+PI`(2BnqFet9F8~SHEQ-#D6EiwIy;$BB?o}-x0T&;^cpu?9AJI{t8;3qOseFZ&ai1f+xemQ~Tzq9sedXhQ6#{*) zjC$W?^HyCJQ>XId>+;q#^-~=6gCF|IE&CZ_`ztMr(YpAX#`~Ms`TJyhU43Vpp-Ef} z_E^&luyY}{rwTZH=`TF%|Ku>B;I7w5q?0y%;Ls<>K$pPaeDR=V_vX+{R5Y6a&~vAqR9fsk;wj09u649=qpsT2;W)(WY0 z38{+@sjmxZ91Uqc3~8kbZ4(ad&2^$(DfRc!A^^L-HIU>xB_~B2fa`QG%{f!l;BO(HBuS#-eT>MZu_} zB}Ag{Xh%!AM#B@LWnV6ey7_Sa&PbB*;=kQYObzhT>zU3PRC-DJp(s1vvjaE4cBGvI5+n zV==%SVDwyg?kRNA;#Y>qu}kOcalge4qo?Lior4;*@0gT^{non-Ptfts=O_K~?_d6I z0jNU_`!3wNvhm=o;rl4Ya2|Xre^w(1y^wYPZT+>S0Xyb~vw>QxZ2YOW{%4kF)BMut zbc&62k3$P1fDCbx*`~SD;-(E?N$ObpUhH%=KBXMFHq-tdm3otWz9i`*Aj|c5;^h>u zH`b(tev0X z*Er@KLn0XoR^z-FYx=Teey=n;SuqmSq=U~iy*p2;B)!?5Q;zA^T zPW}Q6#&A|65Un=)gSpn&J0#d^^{RpY$&z%le!X^WvtjEM=jX=V zVT;dAhl@p@n~(R`Y)WvCIk#FNl$KjBv000^+VF+e%Nr)d*2_alH7&QZ$!;ZVcWOxK zAznkgZXmkAk@#M3*yy4w#W_8ScY3(m0d}Q8zomT_|GZvRpHM{d)z?E-HxL705(2Mx zaJuMfaXHE%0dXawlHDPB)s5;8%0}FdAN2G;Iu7fjbMKEDzczLlGj(@*G;aBPV}HW- zHTS`!!&RA=JX&`s+$OX&P&dvgkq!%@R|K@rDWH}dD<1fBBK>PB0cTn%}H|@($FZ1tHpg)W{{yc1Q zkp>QoME_47n|~f9S6H~PQB9|Om%>Dl~@<^ui?bzk8ZWxwV<4Bg$`jf5hC zNOy_~2r41c4FaOlodeP$CEZ9PE!~2WlG5EJFz*d04?b~p&z{}SzJJ2Z@4B!22Kjp$ z2l@L?^gNMS#45APZ6+Jz#0u}yR1_Iy#i9Med3S4R{M?k)&xvH9{pE*L#2+8xKhSf8FKiZ=Y+-l#99Uj(Agr>sve+bPBj9M0O&R)}c8CJyEQFF*r1AkICCz{e9o16weDeJUjMk&2O9l z`>xC8wg&9A2?_;*Oggu7sVKlX$aV;c#U%7G-LojMpkPSij@xHlTFMtR~%W(x8`(2 zV4rbb7aa9BM>r4 zQjc7bs(E`{k$>%njK%3Q<;PYs4}gIGmqX@H>+;`dhRXho4=~Y%rtdH1qf-kn7X*_} z6P-0fw>Jb?SBgHVnye^%_#)0`-=@}8i5Dz z8X3H^H(MChmN%Qejj?WZTpcjo>Lkn=f#j1d$V0j_VP2XGpVJf1_Wkbwu!|}9m-~M5 z)s|o8zsD8s!dcqgv47-0@)Fq}nr%Qhv{W150_Q!Ti+t^Wqqg|4^G2 z?au@_+u5=m)@qs{TVp8)CPvdARya%)j~q^~e>-3*z8ghG<wbFuqhJ0m5A#f;6r5;p2Xyv3OF%GR+W&kEF_JhZYd_pUYD%u|Q zT~p~?skM9q=}Z}c{h4+;z+(+Lp_%8n=zCZiQW5<%0O~`QNDe@KcxVIx{FMy>>O(uh zj9~Juk+vCQ-Uat^t>&am5 zgzLGM$7PIHme%<9GuO4XGgTy@>|-{eqm{8v0=l0{*Ajj@dc&^F9C@E1nEg*sRxE87 zTvN4D8Q6P@^!ou%`&-Lv+ABk4HcMk>VdOyA+gDe&^6e{jp?J4{GN}Y|c+Xq8_)B5` z+;n#A0^{}7;;mM9_3>@E+gR_cfgJwwwZ`g?F7E$y*#CD2TAhm=?l>r$TPf)wdy%t&5HZv#=M47vmA0c-wV=OE=< z@*8Uu6im>iHOlYL4%NqudvjIaJBKUxD=xISo=Z`ekmy~4TEy8SmA(f$2Pt?&=i3M` zuq{c0k`+>e=Gy?1zjX9mr|`u|GNM989iZxQ2JZVbOr9vZ_xzhhHXJL?@}!X7gXt zhyI5;hsS0P6k%zmj>Eul)n!#$OT-=L?!2%!N*EKIKQGDYp?x^XGxQIr#ZSprD=aQ^ zF*Cbl(fHAG0zo`hkwT2SS;D2&KQ)_Y$inYY_nZaXCAoz2yjOMPP4S>Cokq!*&@kiD zYnR8D&!D>?8L;{JX@wY09pQ-zvu;ga1OE6kgA2S8cy#1aJo5 z8qmi<-fS;%Jbr9o)Rb)Z%7xhJa9r`$Y|bXC4E%Ax_L2Ga`qw^rjt#+fIKEdc->1=E z<*~$v%VzUG`!A&bpYBEPn7d`hUmi_VfN*#Y*7#*OoUfH&5k(yTYt!ss%Gzm>2E-=L z#QuIBO*W4h0e<2sh4gfq)heK&hQlz8_&k0pXPxqm2h@!WI0{rV-bi`f28!4H1#(WUq)E;_S2f13mD zXotsLwD6LzseXtXBIHng7dLFowEg+f34U5(Ts->e3Imu&9jHd?fk!XVm<+p*3~1=* zF0fb(v_|m|s`grj&br#$qU7)U>sNKB--)kc>_wA(4(qDt(RnyE?^?5*K4!K{*$axr zMrbLgnm6)9aqIosNtVU#kqp;w%&)Dzk(iB!(H%WKqvJk~cnCFDJTY3x5_R-S^P$pt zUW(k-ZeJ0noqAxtgc|Dt%%eVXXm{V}gQP#9h~7R*n{Xq=<|HP>s%*wF#R^F4;h*A4 zPgI=y|0f3|4N;4vP1z}Df(uYwv+^T^FM64uR~VP8ivL&Fu0Jj3>!Y<;E^bF&U6O$Vzec+ z>Ws#s0;=bVnQC5A8Wco)s@nIF3@CZ`+s^i4CKS@&!lX}ySQZ1nUAf|ZN=B#X2siJm z@i<*_I6PK%y)#NAfshv<7ysznnDCMf_HJByY$Djb{;3!=O1=tcRaidM zbO!#EN!*6Mj(1b0J}eAa7#Mefi!gWy;K0hTpN$~T2D<@d^buDa)w8|W@3tys;V%5U z^Iz3k(D4Aytf=yI2qN{t*UP9-#biAZHJq>%h>YsOOr*BgIVMowR1;??Mao2XXg1oi ziFq#8_VQc^v?`lwdI=r`#y}?dGbZpi=E6T+d{|m&gR52@dh$LHm|zt&lW1bSYiE(e zD(rR)PYtm^Fj*<~!tgUo-NpOFE?R3YuuwYX7o%A^9pS$qRAb93@t)EsYc&v4G+#z# z_h?fItb!J{S{c6knH}p$bp1;0tCOu@!QEv!%Nj8GP31BqXolr`C|!t4)7q>iR|;w= zst6dza(S&e1cfZDi9}8}zmkbClk-ENjIcEhjxkhx{2J1SCZ*Byl+uQHiOx7 z2747*WnQeTjCjx9G6`mPhSGX=yccH))f2|*SP)`x z{Y`mCyf+|(mWA&V@`BK8P&|#0k;_2cG3=)}Nr2llAO~fSaoHWoYGv z%GYxSAWz?~Be-<)A$LX>r%KTV$6kl6`~vsGYocOvTqI3iEr|`eSo?Fj`VSFW&OEp8 zH=ol9`h3-lQ*>UOB}&@PSIv_p)GaLMUMJP*HfP=cH+P9?;5SY#AiONV6I_19dk~ayZ8aPEZ36niFA3rHCFEXiU)nTYNljlu=wW^3D9jMaX&GH3OZ$GjFoVl zIAN>?33zpsPj_^lBt|o+sz`562*Z4`K7-k2sM#rMsD?z4+*3-mByL-f#UY}*8y+8F z%<}x;O+^@MW{Kl)daf}v+&H_a-*_pf?9X|6DVm|_KX61{s{tXh{ppCh{sBvhZKDAX zIHEQZ8DwuXk=ZYAG*fxAZMM)wc0_nGz{(A@F_$ieMeG_5z00^4-n!WlAv&W17VPxn zNyY}(+Q46jzL*zMq(1KMl372J>%iAG-gc87ao-k3rUNzffDdjK`^(UpwF@C%9kuP& zqV%y2hpH>6_1%vbgbWxlI_wD5uql)bJrO8Fe>zGv_Hai?Mp}7)5+@AVVFJ_dIC%1j zoc7L?NQv3Ow2G;SB#upqs9#*zon!5>$8z~HBfh0(sGn54yT&J^OShDiY|N<}V{PBx z(jIgi0lrq-Cltl2ci+ExED&xU0=EG}5WVgGIFF-e@e@xTh27F5nz7WpH-FK z%RhQtv^`17HzyqTJnoiDIVxS@ku&b}!necGU?G>owKeFOwD{V)YB#)m8+;}z5j?)y z>hI=J7yeD;AR^#nUIszoiKIEtb$1`MaJp1^!8&t=Nh?o?_+e6tni}3tsB%_u8hT6Q zGTr0{3)r$yHBPqrBH%OVENngzb;p1PqCr5Q&VXyz?eGpPW;-APW(=PWxL_b~%9_S6 zm^a3Sk|c4-&{?jg35LUjN^`P^u+(QT<=~JJr^xIN9Rf{OHHhecJ7EEbY{O)s?YA8E|dN${9XX!z* ztW5-(w%k`W%>ww7cV+yR3!kv?osOjQ?Myw4Jt=`vo@(9mVjl>IY~TR03FK!Y8)pVq zL=%A996UA)*?zaSs5dGt_tn9CYB67I=3zM>Y}!UGJXq6ZX^3v47b!Ig+0aMbMy*}8 zpd$&DgeEV}luzRO*fUo^DroPfpY_nUMIpQ3kX2yKwMT(p!4>1X=(oFZt+>k9;sad5 za$bXHMn76>K4*pkj`R@C=ge@uQeHXP17kTq#S)h+#arasa-piMh$VnIm8yVd4xK4Z zxy{0ybE?5wvTWr;3*RyUN;T;R`+zWC%iZZOL(DPVd(J5e=F&U3iUin=X8+{MGy!QH|kB64q|7IJK8hR@9?KtsruB~ ztEUhm1pA3Dqi|j*j`+!8vP|Ej&P03zl5p#*3*y07&Y~xx@3mUsB3ykji()*u6fjX+ zSG(#azY;h5pSDrRgpe< zTdC$Im`?z&HYU!1oB_%KqZX&%tN#kZ;YQ5gDR>AfNh_5WJ__jo9M@WqBHlGpLNh^PT|99_c|?h4;M;mXdi(eH@6 zA~uXSY@^*9a>JfvCgUAGbC!BusOUlaqk+6f-l2FzMQnEpXzH94qC!oTQ~BK&*@ix= zDlg%DP2Pj$&%x0R5LDezuV$}9O0=>~Z z9;OrFpACI^`gP?34r<*8!(@f;J?&)YVBZK_f9Y5-u)4BbLg(WIY`WrjE*3dwMpOxa z@ZqhqKWqezNIHMQMe8(<09U>bZkWiDcca#|8+{3gAALzLcquvCY@9V-0(Yv4VlF9rB~Sm9KRn ztV&%k%C}~F;^l%BUmkRN4VviJpnt#OumL-%e`RPJw0e|)VpeoP?CEcrR|)G_$m z&i=yqK>WB9^w_8vKS2|Wa{W|NWB#5iD$YEW8@edcYY&40{8}bt<6@Er__xw0JSgp? zCpD=giD-Oj;##N-*-8wfp9@>@LIODY4Ie))EZ7|hYTR)k4Hh~~e+#)mU^D^|Vep*} zmBeAh0~x`?!x5t6r0Kn?efW$nLYTXJCQ{Xrm?2U;B1%OZDe=B~3}wcG{%gyi?bKMS zxciI}Hp4Qfk{Z4S5}X)5pI;Bn95BXv9~y-u`i~8rItI5fB)^iam`yQOW&YwNWxQyV zmH@b+rzSh`XJ({$#VlrI@;WHpg=>YjEM{l*`z_|=%*wLnzF#!X0v6IEOZhc8?Ir~+ z6j^Mhc_euAk!}pE*+or??@fybRkEnEXmg{Id?#WKa>|$@mU7B5O1ME@Oc?^b1o4uj zt7Y3sBRSq%!&x-d(**nef~Kj+>(Q`Z@2@8zqCPOJN8~zMtH;76E2zVzeNa%3V<2D9 z1S_Oe;SD9E>f*F;%`Hv5DiA-+BMG9a`6m8|JU?y?TA15OQc2>RJnD%w zB!~-*Y{MH6pD<188KfprhRqO2B9Lx`wchRwRyFB&a{iS#kP?35CV zGg%6Y8gb;u2Cjevy%aWsgKCkJERP~U_|O|H#C)|OqN1ZLNbdkGooI`<`q3VDgc@0o zNSIU`>6Wi!nEOB&xDwbM?-zZIqf}sq{S1HWX~+~|HJJ;036*P5=5{JxWh%SkFp4G} z%p?E04CPie+32=yN_z546?`A8u+Xgxxj>e~lc(KQC2#Q=*=Z0`SUR#1!n3rCvBd!+ zs?GAOY{SoJpuV<#lE5sVi+$^vTx~p%weOx~Z9uN})LGUQ0TV^q0YWX}jf5}zr;!em zUi8dM^}Nh|w*>gh`u$SY{@Z=4THFc3$v4@{XT%@qp^MdsrpCd#dCeY88PmqU9tK=rd6Sn!XMZ3 zvL7(MXCJg^-<+KhWky1tj?Y#JT;E$6`(O{H#Eg5fyEfMtS<1vuYX`IT)kMjH;^f7* z`Hif!nz$P0^l6-Ev@}v+=`d-OIdhE`jVmKkQ#~JllLO}Nut@d@4>k)Xcfi&1y;38Z) z*~iz)CtoQ_BF}`WsLITQtLg&=ff{zLGm(#EqsjfTk*|7+%E;^agHW(qgFre3sX9^G z{TVY+cC%+$dqK~U1dQ@1;Sk$+KEVei(=gGOyJ9{um=`7EEjf;d%X8x6cVmDs-{Qhs zg%e!$w2%l{=8QC_7#554lFZDk)Ou*eV)na!*^fb17}IU`LbLiN*?9=0L+SOs8q0Z2 z92Im@NhtY^!YPK=Rdc~9G7zw&D*mES4aB!UzSYZrxvV(?b-6rD_Y*=W@qGbh^{P<+ z+)4!!y1cU4DU-~EKv(~?*lGl{_1e;%_JkTGoFj`mFi*B+J%*HgPhl}qa)Ws131WPD zAagBcJryO}yE?k-l~%7t;~s2&pw46CYCvs9+v?cskIn1c8q3}i->A;Y0%s#Ncs4c6 znif@io;=2E-dzp2+I1+(Ufg$wl6@_@=Mjr=kp+uUNHg3$GNM7HJ1?`-N0U0O+EibU z@>X1pVEX!ntDk%?fN*MM@+As3l=(IYWyjcl%yxX`O|OqX%I!c8%{LD-Vqx-ZF52c+=3I<>^^Juj=Ua~R>7`x#Gc5KT2l<8mw;a95<`lmzgSk^* zzk!7vYl#27tFtn&hfd$}zj8p2H|8vAPFBCxK%vK9wT{6^wJ;>>cemscphzvXu)Ua0 zP~3;Z0f+^N8p^I<4{g|M^TKG3Cii_Z2&YiqL2@b$#G3uztT5PDnl0pdve;6i-a-06 z(!1`}=%0vT79~bejpZ%0OpOIKU}~U2*zge-pF)Xb5<^bP_Qds2Sz#eeVSb0@dGB2k zLE-!jnx-z3uXnT#&wSoPUKqfkPocdlDq!oh3V8nI3qyE_s&qpTRjeGTGz_Hzasqx1 zl_&Wgl5{B?x6HFo0ij3w!6`SaJt$4($QYTg^8xGgh)<;S*Ph874o*=buaCrBg(sh< z+YA$f5oW5RXSiF@%Yc0U4mcD`RtN>eZ}=Q_*Y>CnGGGXhi8NPJ9GdP{rvUgC#{kr%DkVDP7RKQrb z83pDtu-)lIP)^nKrFDXWg-b-^w$aih`srL1*u=pLMexG#j^Uo6;;~B9q2#4hFt_-_ z5}(}1m9l$^eN*;{LW!Zbs3x_iK?u%UrYav1apT}?W_1?KfkqNVt&*O@+ezGkMy#d< zeX)mksWDuGM9mKRl1O&ar4=$&BHKQt^6z9Q2WH+)ll`2jv6HFZnW-8NR)MkI$$Iog z?&3Ofrsk6ZXw@m6rRcx+0^>@o`pN(5@=5GTvp-k|Ai=mO{x(Gq zBwR)GdU9hoYv>%e(hsc2El`L3H6a{g?_oDkK8=)|qxDMem#o*l!$QYAr!GLSH{YO@ zzSC@fN_&ddE1XO9o1vgEYH-)SdKX~SVqHkcWbsUo}-51<@22{qs`t*6jdEPd$Z$naa#H( zhdc$>$DhMt7*e^w(>P3kzH%`oxMA@#X?YCZwj1({){%yI65Ewg>r)y>5&F>jl@a@u7$ydhEx8v7QvbIqUN^=<4DiZ7^>VQJgH{f!KHmlFoHN-heoxLHIQq zoJ$yNQ9Ye3;gf}ghzI7Ujvh|TfL2|Qk$$vcT!wy(X)beOB<2t|1P=k;6~YQjht&wm z<};*wW`?ksn&5$943OI?jP)T`E12HC4ZOu-lpMxw44Atr#u%lXtN9rF^@O1xBVs>F zFwZp3%ywEdPS4MU9%g12lsM|Sm)+XecYDtfwd7HylD?FOIGU6|iV#hb==Kd}a5?9L zBr01$rOHxPk@TaCk5?oWxs-_!nFU-zWKpo5lnmcWPANPrZeM+Gaf>zY{YJ0AmCC(- z|GcWBTXzvM(1*$&sUHx0$*V>ptz4@|rp&hdfF=~noEZ@(z0nx0bClRbYi(-PL}fu{ z-AwDuw%H2*%wz^6b9LL`g~c&W1W2gqfi;BU>x;rprq}Y;-TbhfTixQ{Ol^B4Xx~hI zkQZ3CZBPU6aBey)0Eo%fKZsIzYz)+pi&3+D5UFSO%=TNAiz$NQ64t~ebGBU+psE->bu zOs2E~uQ>S4M#dFc|Y<{SQx z&}i|>rJKl7bG`4=O>NaCOJ23k2oyNNAxkWiyrH`mfCxu(a@Z_&yc6Q=ghoe&7%k-G zkZTjjL%y*28Ny4}5Q5;UCqgHKC5zDz3a*<5U2ScZa^wz;kJV#hz0oEY!Tl=jiyn&r za+|7OZ+NoDjF@V_U-*WZSJ{`gilnV*u|w_WB{eD|hO6A`oz#^gG>R?{t_>?ca?iw(7FDND_?R8@ znXWI}_+APYPiovw4sNu*dJ2`Qxk_J-Wv7W4n5qA)&(BA^IhQd|uhKvOg@_IyP{H#T ziz#{qW{Vd!sIr=gf`ea1=v{wa>^wMCP%JMx5Z5}?>*pC$lJ6Zm-*%&~VpkmUav3xY zH#9&$yenmGEFpmOd}J&ry`&o5Tx6Z)%M{68S&Krh_2eQ`Zzes}j}z$GN+us@?#2E^ z<-ne-`NztUBIino-t^*kTv;wiZ+`_-yxvV3apoDikiz&aVVoZ-r>DX=+x=yKsFiaK z`=6db-Kk9y=bN*Hn2y=MY%O8>GcG#q9_?GNr3o3ExP;=$*GxN?#MUKD7n-U;rg zqJtCec#`Uq9%m}2I2e|}-mv?)i9XySd=tWS1hz?HGvuFieaXOlfG)$}mYj>_kUfPl zq21uuV3I>3ItaSP^i&9Erq8Jk+%^qBdMi&3Q;?K?5{BG3tt3x4iaQ{rNuW0_Mrq9q ziG=qAY{5+lh8P@=>4o10@}cZchdWe1ON%q9SeSEaFw;pEXU4cIiGz$a-3H3W^MHGC zogP@bYr?6|MeX0CmtlvcPfT)xm1&+J$LhQ~qF_bCUrPWTbbD+MDS>*9`Hm4wFJ+^Q zWoG$S4iB5;)-aT1(xNz*v7eUQMqT0G%q|Yot7$m%tW^skDS6}7_mRBsgvo; z0D;Ro9*SOTKw&i9sKkH#g6mWVuAqs^z#q#ui4)I7bV^3VvYD;>wFjI}_0hU1U&+x% zCxu$&YddAM>1DB=P<~-Sa23q@Yv!TN;13udmN~OVsgKFKc;_DMe5TeMo$#h~l*KB7 zf7zlOiD>l_Yf#@r!6HsZn%c$zM=WFai+UdWUNvipe|Ff-Dd>v*xC<*W-?$s0;{IeU zjT5`uTAg4m9`!0K#D`1bV{p2~sI|6DOfZtxSOV0{VG4E|k%u^0x<`{Wn>D9wEZ_SU z-@Vf?txt( z!Frd;6Dp1+hp9&e|HM!P&pb#@png(QJ5-Ef70X=6^vfL75lOrm-^xdXE(z7BD1Ln(W znr{pj1UcNCBH!Vof{R%T1}aB27I*z3F`a}Doz4)!W*uCR1y$kwucKthEhkUX(c?$H zcyu&;P;l%OiOtq!6gg-Gdvd>ed-VzPHJLWm%---}vkUN7 z43)0v7`5xJT8B4%O5ygFsgi&4MBDa$(sQ_E2_qF7|GuJBUK^$+cGXv}2euh_YoZk_ z%?o4a>C*U{TNSM;3SY0I8Qko?-+3~K8@St`Pc+ktt>jo@6E}-y$PXP-vc#bJo+Zy* z5%EBYpl2|5{zaDjNb!%G{=ck1Wcp}+a?Crk2>k_t>ibn22U_=QYtE3V4E91a*eJ>G+yMgNg2 zGLlE4*Fv~7u{#w;QKL}ov1pRN@4YA*5#lkQx4Q66Ov--5hxV#2LQdO{07DNt5gcL^ zCP=Uhm_W}@X?U|cLX+hFj4l=iRU-(nRfJ)#f%M9K`piun-gA zg`yVuz`T_*G0uy*CoR7O#h67WhwQG2#>IvVD5CkGTu>`W`j7CKsB*i|oc%M;;u+0_7s167gcJ$)Y2qe5${7YA&xzwnUg);Fsv|{aK`U+FCI`Q;NQ6$u;9s9| z7k7>?Q9H5~nQ3!PE4n7^R;BfzfHcw^XImYlQo=pZ-S*|cZj~y75rjkWemA?c`|aMo zpoklL$JTYF6(R;^c#(`qaj=ZE)u_;#(RE6>wxR12FAoC;UcW$nL`UU{j7A0THqba5 z#VQ(jO&bRXjSu7mok!I2WIw2Cv@-`zd{BfiGM#nlOqU z|K{9VSs7DmWmo7Rx9YR29LS-9!oz)SLYj0R+br(u7|h6)6se@*P5MSoMKRsJ4vJVY zG<@^?s#p2rU{eM_7zsA|hRbU>{Afn0p4)q<5jjOTa|zr-@0c_%PQt)jR{(GQ6yQ^y z8>HeHepk}}dr}3UBlim+Vqx09l?vF~-B6$f$1@R$56TfXZXL~GCXcwbJyhZ`Yp^5Ub8K=x9S5& z(>Z74N2E7%qU`lXprO-V=oOpGA7iaxi4}W_w%mH|xU(}oC=2WN4JM6T-LZ39YuAeR zA-H*ReGcX`E>fg;so+{e08~bryQVs9F152nGOxO3=NL-Wto~9)dXm&E2h!_z|C5X` z3b71?3q*{91E+Prq$TY&TwbwmyYNBCPPaGImamop$03SPgLrsKM<9o;Ktl5yy0*Vy zPFOmrCj3jL9-x@3MzV93yrVKgIPjqpy~eRHt&ahbh(*8bia`j-~i zzxN@YqeNMbydhcrXV75HkE}z5k2{BHO$bhjuKp!~a;1QV0(91ETgqldxCVAxrFds; zV7QV&?(-4j45fCR@(Q*hRimYLi{kMKEN4PNl@=lwrsAp!C%9(NxCCp-_4z z!^6$m0m&!binSwvx70h#emnAePwU`h=%k5zGVz%+k`d`-w6Emt)Zcb4=Bf6*i^IJe zTPkdPeJ9^T0d|>r;8sunc=`w_Vgyaf=e0}^vtpBbj_pEw_spaq&o$}l@Xe*m(D(ZUaKk{5RKC1iI?ZmqAPL}4-TrO~{4cZH<%sWau>1uX`~oHUR#xI!{$gGx zY<5ZP*@%Dy{XygZ1Jd;`vfId)%!{inG2K_!NO=9O7|X)Bt^{oJ+%sK_Th57qE=KWE zN@ie_lY&6<;IKLF#5s+>miQeCfRg;N|1YKLu;t@rt7~d?#q;# zuB#!BhBxKMS$$XdpS_C^s@zURL}j#p0MGAF3aaW~=ox&6i_S(Hrd|>V`72!XcLYNG zre4K)v9Ks61Q{=8q^D+Ps!il9E&`g_2`sEili~b7VcWcnP0ls5f96vOQ{4NeRE)1K zuw3+I(MahsCpI z&8Ums1PIz}5EG~!rr}=%ZOByKKM(kq0GYqAT|FQ0GahyPb-@1)$ov;y?{5dKNwlUG zK%M~xe1QA9^!@8SZ^lq7E!xf74%#mxLB%pbsceXuL5%tee~oPu`wKsqqlXE8$l6KMB5vB?h_ z|M$w~)tQ<<$o?0gUAXwaf_DECG4j*-fbrTTe)KP6B=!F?KRRArCv*Xundt&j1$^F_ zAR3S&xba_n-UUhjeEIqP;(WpJ{bw@Nzx#BZ#rO+-fQ{l=asKy(tzy_GBds+ML2pX^ZQgvS2RY51?yBtW!^(^uvu znz|s)z*D70$3SlikpyAPBCjz%WeCS( zU@fLcMEGT7#3Z$4WX8Qi$;?WshsrKy6s2k`WtNikdkOE#FKQ?8?HEJy9WoY{3Q%E| znBI19EU_hbie~i)HPHZ!rs(2cKlWYAC9~2ACsy;a=^zvH^7*(dz|kdl$^1RA&bK(T zmaf_#%d)6GT3xcJ0cDMJiSOba$<b+XNw7Iv|&E!%VpXR+CKir@-f?UWAg zV9$f{lCSqEN}=z3Qc+Xb`K)RXxYNJ2DT`gIC3X`u_}E_oxB;JjZl+I--wMsRDhxX3_e`!?hLxi#`c~4ed!rsS%v3<(nxGh~Vl3#y70(-y| zeIU#wa$z{S9qeWWgH)UkPlyx>r)taUuCgvQ^y0Q3D4?D)mr4u-=5(Q}%=f&a7st*E z@^CwFdxnli0|)iouceWM_()BY!bCFFGW42&R1D!+^?W>FzKFO(Ns%7F^&+UCfk4^m z&G?9xLgwWj-68%6*5@8b(L`O%*IMiZ3R8Js+)k1H7%>@l3f%5Z+uHYjsm`9^Y_%J=M_E#kHH1#F0fT}NFan-&xI$Pxail^IpC-K zR3vq9$A;&{k$Xj45ekC8$!7?`wyA`ptj2LRGR~pt*0cIi`-98j$t6Cc_!uWqz+$-& zEE6?zo72Ed-TX>4$OTe~EdXq|Gv!kv_>DRGg4I3sRdXsnXBqEgJ%GqQzcN9Eh6q7c@Y}@4qoQ3$P;PV7U_y-PYt}Xph&jLw55W0eCdCQC5=UX%)lptgm01?G>RknME8q5UMr+)M zPl%-92B~Y<1MrZLi9Aao{3;w^7rfmGQ5+Bm1m`k9Vdk)Io;IPeL!Mki)ifZ^wsg-M zr?;V1e1qm*$4!F0%mz+|f&eA5$0Xf+jn|qs0(C0Yv{kz!wqK8#ck&9Vg@!nm8cNZm z8Tiwodbmecda_qt6Vxizd2y$%E*2PzoZSN0_ha*+TMpw zN3`(QbMm=gr}nz`I&G}?9^5D+VsoNJAWd*TD8~MlZ(3rBSnA|Z;>+|b?Ag%h_>3!YtT}T>EEru0sfFos1CZO^gFOt2Pa{8c7~gw6^f~9zwQK|SC5@Wl{(|b_ zT$@f4jkV!{s)*uvR|V4tgx~t3io*&bk4^Lu-w*XTl@u8S&MRwV*b5MA_NN!M+c zMdXn#L*+Ji3wusAM<88+%wVpYI5N8Eb^U!S``XjIZzKC%d-+7T=k6tEW~6zbagZ1Y z8>s6KzVG1b09QMLqNhD^_1^^}=T~*^xLu5dK<}0Z^lmjUA-~hR6@0DN_!Zy&-&}M5 zhj(57tBr(uyx`wbqg5p*eQRQoVEphR0R1f`T|>bMO8E*Rm7HtjuCFPC3-IAdN>${6@Ii&RwVlqtSc)Pq}Ncy zo5WU$-H(QDUf3Mmb_ay`@J3IfGf9JyXb4V`XX-5@*Tsj4D$^)wC&Fr=w79I^WEoN9 zPnjmxca}-|bHGFOb<*Xk70RjAUUV{ID8jY|@8n^udRXDYQP@?39+7@7MB*AoVU61? zPm{VJ|qlNfb0s7fUPil zI=^XKxYrnbqrd>HC#PD1S@XFhu;=A3J2EWgkC^5VWi_-c4rJGoDg>-C!A3c1}9uF34A6z zP*hqHJW-2P#sI_dePW}YXH2?x_t5Sp2{Q(z>&hkP%=!zT5ETvkT?OBpVu#K4dK&~g zQT8}k_+*|Iauee|U5E(Hjbw-nMQd`1%&iQ)SGQ-?Q(mcZMAL_B=q}8JYuf>|AU#p$ z+2|*VM*1--CFL_QmYK|HueFkh)57SR3?b~fVYd+opFlR|5?lymPn~xC=9Bz*+veW} zNun$yhpNh+I_>%`q{i5_Eu_VHp)95+MK~G~o0Hvb2XRDMHM8e6K~a`Y0p?3NC9{4@ zxfQ!@OL^4@sLT2F1aiv-O$`3a@7j3VmkYZjQCEtpDn2#|awO3!6BmqaH0O>FldR@^ zZPQrIo~w>oWnU^mU41`QFPB?6+v}fOwK&zDTfN$}v{ni2Cta_Cozq;eM%+VPuLtwU z=YK$eeIZpk8Or@wgkCwTpoq+3*{Ye!na#R|F4)w%mFbF{q@N>3ZDWITCHF=LZVgvq z=e52Ugx_9nd; z$GDJ7U6`;Coh{952l($O7S8ZIzQxxaBlq%PI>Cm*aptWv$KirXd*uPS>j?GJiLrX) zX3BhT0j^Q|vQ@{Wyl%ATtJR3zHY+#myKLuLBIC+8vtBFmFLp`Q+}!RHvZ&g|Z8zN$ zA*NlenwnsJE;r%YZ7g+=7Z+d6zW5e1>sv($CF|k+x0Ge1i?7FJbMj)x5soHNC-x8= z*l@BLB!b_QtU7tUM_^fZmC>B&pmPvFst$CsuT4N;ZxO~&>~Tjy0)cQKAPl_~bd)HU zrJyEPxWP$uav~Qb+yocivMzMgs9MC)1Q0h_4jc?p5*+kJix_2pwx_)VJUotN5&f`^ zr@gcee0e_5O8}VIY;8E9^hPx64L1$c$GzFSl3dk+0R~rTNe0rJc>7n(VOw8+Vv=fJ z{A~5qKK3p7o{!Y6#e!g$qqkIB(k(L|S^QKCMTlh+T;P_KK&0ss*%4(m^cb~p52J)Z z8d!Yrrl6O^Xdqfj3;YHKB+btr+$nvZAc}}Ywa|(vw1D=t_v!G6swiN zfb<+Z!9|>)*L7H+71K$O-Ym);1}hkx{ZaA`DkzA1PzU8&k^ADRwjV|28ajJXBPo*$ z$kUn%gaQ%nQ;E99v5jk2QYO*Q*;0fanqxMMws2iyu`|?dEBVGqoJhq$v)F8=rK2r# zuC|6$G|p-Y-y0)Ei_E^b%}>Gh(jZQqCkSu>lNb9jdyZ5G_#KB+p&AlRO;^CWR_9C zy@?^G=ZV@@>zX{K14CkXMNR5}h0v19w_U>Xfw(d zX&^<7E4j~Y$-Oe99<7>3KAYLGbSRgTYPyk|uRv?=r?#v}@V=~()2SffvHVx!k+LSf z>VhB}vacX{(7l{|i5nYBi1yZYiKXlYsPKN>c3lDSw`|{ZJ}8hA5Wb(lX38XL@&3sm zy)c-$Xed(i0Rl`|9Y$l0RgBrPpO&dDwDE?CRqU$~UF1xMF1u8lzRixgH>1xQUp5uS zR}p>ntG`Xfb}c4}uybBg;P4|Ps3@87*boo=%3z;P3vUZ~e5A=3C9cHc0Iowz!wLqJ zlfSqYF?d(K&03cO3j|K8tp|m4d{%y#!T4>2O^@Og`H5MXGlQzk97gj zt&74HCZcVz=Nqrox?)(?p+gnkflFLw-?HCJP<$Z<|G=RhBY8wKH+_n^ofDpC#5IWn z34}NX5(nF8mQ$MA1dZLC<2M-@W`YWpw^fm^MmT?&`AATjV5a)8l6VDy?|of|5%83S-Rbi`BTpC3W51bjcHe(OxULMo&M5{ivvkLxbJ0{T zb<9WHY*5?yvMAGi&_zFP(}p{`8LY-Xd!6#2OYCGThR{*l>MF!=)uB6W&T3ID@36n{ zWanDkpz1wSYqc*^zU(D0`%TAnbBsUv=f0i01Yguu(smTxdFz08Bz{TL zl-{-M*+`#v)ox+;@e06!vU*_){bufwz;>PMVg%QoQ50N$ANzv-3y! zJ6B1V18*=X#vNZbc-A-VBwXkK$K~Qr;EbZ~JUie5+IQKUbHPS(-LpsR7RT~{*X&b$ zK<48(y5~BE=teXDlHTC4iPsBqA2*752@BO1Z0Rpp=G|0j&4wbcnXRL)hr#s^xD67z z-Qsf-c5s~VHiS`s7Dwoqu;(me=ppCuOe)<&n#fa`&r_bs^PaS)qV!Yw=4T0!Hjf-U z9uRqI4SMhyxWI3Kqr5$%)4X(Ayp$X~Eu%bDnY?8kT(5A`KBIN#w{sJ0@phWmbyhcY z;q!4*_u+K#VIcJIit_Pp@eY9Q`!GoR_>{S2s-bu@U|BS|`|Z2Omie|wAwhFFkmkDnjZfZhoIf4pgqH&{j%UgqM#LZ@D=5kumvprk^a|c@DZ445ker( zH!#_4Alf1b$X32s_d~cgFwx2hiH$<;>Y$Pxgh+qnrn!Mdi%d)RER-QS6jnKu)i;zq zBb1H!6$kSx&V^7az>Wp$haC&?25JR1@nzgm52y>&0%8W50BxgMA0P{`>6tFk;m0By;1Mu|tWC@$j!RiVPR-2?W!E$bPs5*Zk4gJFn(AGLC6 zto`FhdF<;aHTn_oe0PZW>yN^)K(~dxEWj0i%3G32On8$heF`nX(*wK7#+;e8_oTt{ ztDjx3USX?`-Qc_6EtQx_U+4I8aUtLcP?kI8E#U?&+_w{+to6bD8q1k)*hUIVjT)9+ z_FXN=frw$IGeOKg+u^PO>BsatJj>Y?867ay8qXVv!b+B3>6D7q+i(>yA%YP^nV62-`wfT;iEa`^Qeya68h*?{69gp|7ZIghEF)zm=WU=C zF(uok6)8qq7`EBQo^BVhtF@m7@$hG8zCvJ5m~ui~NW*g0m@TOj)kC^l?}5;`|1dfo zzBNgh3&$hL`R1l!4;WUEiB|eP1{O{1a|yMka9C=7VPdn6XNX?2Dfbbah`MATNrdHA zOfMpE#J!w7PUs)mUSrYIN+k~D@5zWAeM^#lJ)Ey1BzwJ;#MrcCF@izFmfB+>hxFK( zB)WFDe@S>HDkWP`AK(AW>n;NOY$5Qms9DjVzMQ5J;&=Gl*_J342qrifk)MJI_JsOB ziA|L9RECNuL@8(Xo$H+UQv8PxZo^Y=dasU`6?yWn#Jk$7WA59SxV#wv8)4egt_P6^ zq%mfiS8?%~4AnCCa}ZTdTDaLi+L2WJqU!=PfNDdSWnS1>FS(e`J}Nd7O>%TEoweqcL7oFZjXwxR;OzPwzG#n4uF;E=^+9? z<%|;%-Q4eWgs;0UY=(y?F6jz;!%$a*2ZOUwnA0h&R>qe`Al(?W!q8o!(jw9=Dj-OA2ty-X zf^#+%r zABi8yJx3mD=F|jc5>wJtOH|lFT1wg=^ZEIx4mLhP1B?QK;0R%Fz3PW0cc#4^>k^>MO$M>HK}z_{4m<&YT&- z0aLe+7@**^x1KoFL)Cd5oif=%stHawQoeM`&p+JCCMk}6Lvz7{Qr#O zs4}|G{sA6xDcAVjSKi~zb5}ip2=0A0!$`>9+j&)17p!o1!gC)6{1cKoo_Kov`0DNl z`BgaHK^vq8uJAq7SV<|G^%h`yVDa;*)) zeUtyzJoBfg?Udtf{f>~!vu~3`iAGTmV9K=A`v{0%7Bm4{5FTtnc3-j&>|XlAzRWm8 zw&^y^G9aAyZklwM73~;_eQUq)WrkDi|K;>pZ%xz14-4IhZxflY4~phDGGN)qgw$Vg z*RLyPYmRJRwFiV6!^YJEPy4BHQ>~~!0YV0K$5ayJOr$QRG1*u z*)4%@H(|X1KCGSMT_^bVaD%N#OI6y|(mJDnR@cH&@o2l;dCXum@CPYmUiwJk3(~47 z%}<2_KGRe}m=GnL_(2!@v(ykZseJ6dnbWFOOH!apXxDjbjpqt=hC)#uTJYytkACK6Z+?1Re%TL`h5Yuhd4_0G6 z^Km3@RcL%Pe__EXT1D`k&-`hC-v^v(Tos+I^zQ_C9BNNemkT%YhbvO27bjTDaDPkw zzGL~o^lX?NQ+3sq16<>bjC7J+R&Y1O3M)*W6~gsF;IyS>9Vndg59h!$7w7s~@?hF# z0JvFL1xAA{g9ZSHQgyLlLip34X%8YJ8rUHP#QF(>4sQ@jM^X6~OM!J-SN`bG%aNSD|DH}91u#&|c4jmOi zT7wC1XfAi}IOmeN8f)ePN)8yr&DPy(hY7+J4l2MtK))!3!I+0DZr^XurvWh!yS)3- z;s34B|0yTIgH-FlYypst6n1vT>Gy@^nf@mcdPb?W*8?cEce{k&p(uyx$ZK2$zYi7l zsE&Y?e!Qi1^V9V%(gljHqS^)p?RC4==>WTn91iy?HdE@Wu^5OcF0JIgOZ;L!!(WUA z#QJPbf&dE;RuljxpbfZq_E^~dh&iQa{WGM}A1HOOjo>Sfh7pX4I7+2|(>lB-a@M?{{AmWrKJvA!fqN>voD@xbY`+!%byla-ds7_u>z> z7atnhgqulLI(y#Eed5I2ZL}-5PMHfoie_$|>z~eQj9G}MiqCPaGRJ!WD>7GPON;Dw zWRp6`?9s@Z@aKh?5srzk##&k=M3x*{RV#_@= zF9uV*b2*!D1b3G<-wGqMZFP$gS#0%4G30K=P-FLP_3|ZRZ1<_AGCt~8GkR(&U#pe7 z{a*JruNUqEZ*9g`hKHGA!(KKv_#?ay+9CMXtL-;Oxpz`~t5ABNPj{p9IcIjquK?G2 z2|Y)mt)>EbR`#YLlI;64;kPYe;8CNz{nebIb|ycp9)&p z50^^bTOKZ#&*dGiRPC-DuGS%Q9IZ9optoCZW5_?+c+InVwAn4malF-c+v>P0-T#dF>ak|cJrLlMktKGT1W_fImyD@x4;dFB0E5x{)~?@AFCL7q|@9hD^^* z={}1~|7!%C|0yWp2Y^y<#wlOgNaLwf0?rSNKo}>4_;;itZ+>&=Jp(&CQ*c7UfM651 zaJgG1UwjNfDljFoGre|y64#I@{Zj&tMsoXXEXp$&y74NT@LYW8u{%SE;EC$ngp?3) zLOk_Ch4LNOtU)8NChg+9oOg=d+tdj835Za50wS%E2B(Q)IzxneH^0?gQ*aulJesLr zNJ>mdc6Q5Wz4pa~%u-9lPm-0hUwsU}Hv#yeLoeHda%Y$+-L_K)Zt!F%nSTBvn(>N! zK&cs3<;K_^yKI&Q$f}yx^6pB_QA4@3h!g@jRkdvVOxANGo+Vh#fPvPUxOdLuB@!rtY_OVf+hQA5Gjg{FwCt8) zHN)rBp*PB6XUI4scjtSD-uD)}qxN&TyJJswb(eR?U6I-MCOnBO_a=QA^7j6$X1v*_ zNcnxuz;SCY7FSh&2(K)|Mlm(HXn< zGHcG9H_lmas;twkryKR_ZuT?zKkp}2|2;+bpRwM4V;=fP*4uxJK;-ba4ty_k3ufi} zjrC@$W_WIrz;OQoTHjm(%of{N+C@gJDaltaLpp`+Agos?P{K4+fWL<(GdzBB#$P>3 zMM_-e2EKt}2Gy%cm2^_DY5ldlC-}^n7i^%^BpL8A5ZTPZZse zC9GkJ?&cfqj2Sr_f01D=5VS%LGk~tH-5wV z{9AAQqQ^Hk=$qWcRbDr0Nahzl*6l>;TK_+oD11L}in18|KIJ-(uR`v(xWF8a&U@qU zM0sM8rhCsxJ$B3Wf1k7WKkAKB9gCLdFKX}Vkzl^j4Zy zZZDMRQx*-FzB>n=nyWh}+>&-An|hKzl!-7$)Xb{^*HHFxJC>TaXBQT2b1txu#=@?S z5?xb8`AHN2oMvpMQbOm&-$%a_&CKpML_dJ_urrT^L*!VvZ@FquqfftvbSTC&PS043 zxt8)J*~jo|N-_5ODf*o55{$Q<(oOXHvOh3U_+!e!w6-?8e%2fRTFU)&pX>d7%GvvH zbNrw;9$^@nt9@b#H~$n}@L)bUQNdv@hsEOlpY+B=R!2YRjjsj0)yY5J`C!)s-kmtr zNw%)#g6tzDE1n!oWhp`qm)_a>Aa1q>#~th?TGbvMBG0ve*YKoH4kYU&F$-LChJZjK z`y7Bqof`&i7Ze{@Uq3n_ith*0Np7o8X3OzNMg8i}37d1L0B`~FaGzb)kx}pmO@%An zfY>zu_H~Ww$67Z@#1rQ8cJ`b0R=@Fo_`2rH5%}+L_wF-{hQzN2uK0#At0E}YR6QO= zLP`^Y`E$0UtxSLQSpJTzLuIpbMU_evnLV6J1Rbj{Nf;XoH0g# zTS6HXv-+Y#KgtBL-L2UoevtCn*7dtt!*5%d&m)-M`~R8`-a_snRn>&Bfy>}0(ZU_w z@B#q@W2YSSo4icd=dglL2 zetG$`|8E=vfC=>~&zWP~lroB`$h@O&<)?{LBUGW`U4#ZA2r&W`q_1ve=JY|2o7;M! zutR!WlAn$r08Tm33WdNZhgzH$6Ydz?_U{-`D*9!BMCOxY!f3pwK2Pkv2#yb4(tvSa zCcQ_qA_63(=t3WznpxBP5NeK7tESp<&AylpYI}5B){e2L?LA^?IE|8@;0diZSQfWW z-%whD>0`L+EfYE)S)@$5a4_>$n(!Um$4aO2nCV~xq$v6@BOTbR0hh#kEKXz$<<$Ro zA^Mub4$P8L?${k7g!>HP+~*06FfmAidEvAFIj@sGV|v^dOUesrh#{u&nGwnUu~{h_ z4;5j=eb~9-2{q6b=mxZ`@>CxYaztO^j)cc+a|wJZ?pD}gHh9NA zto#yK=+B(|q^5%brhX=%R7M2JS_bFLMz3%z%nq=t&KWv{755Cl9H|#mvh%^~ky$y_ zO>Sg;m5+6NmGW=yzwa&-y^D@pgU%wbq}~jaOROWjgLc0qiOy`L=A$<&q!A70b)gap zgMN|dQeFv{DNCYYWHLpyIafQ)HT`0xLu~^3+q^uF;$Fux0Y=*i>Umy>FbTYrE}&eN zF)msveNvwb6c<*)r5c?MkburO;0zG3Y`v5dx~h%WH(e_AFoKH(rAZhF52<^Hs2sg{ zLz5LsYg~jUNxLRgH7XfCY%Ge8n6~>NbWh}d?eUPf)|LL}iK0eaAYY`LCsxXprFz!w zL~_(hZ;9fTA1z))-{MIF>pgi?PDI{?lbC*>7c5j%D>Gl>xuMWKWX_=~0f4_B-~EPA zoRLqT=^fb>(KdlAC5a?%nn++NlpHTr67d8O1Bt0TWb7g340a|7=?YPrgO#Mx_RA0N z%mgL{JU0tue6>IVC%R*sNW^5|;|3{5mbP7l&MN~ErbGj_EWBo2u}THdN8Ma|-r#k#JY9Pbz>2L?vd)oDMWXqK{v>NU+E(!u-ad^AZ213Rr881I~N>lD8O*80R39 zFI_TC1=^S}RbTWX7Y_AGrWYPE5b>BwkzbwF7k??b44pSbQIpk|{)9_1b8rn3_?S-N zl76_>v6Aq~nz-GD6yy;|Oew<5Kt)wt#{Wn(1h}t*?DZmBmNe~Y$CRfCv%6eSTTn#T zJyMEF6nWSkPvlE*Y6m-KwZh#%jQ7R*>a^BwTyh~)5f{C#WmSj?8_r*dE0_Tmy@NKp zKLooR(hzLYB!kKeZm^|t((;nv7i<^F9%oR4%W(O10I+Omy=_G)jZijh8@x)Pax2 z5jCU6NeDI0wGnZ+$8czf$yUdLncOT*z33p*+e@@5p(!BOb&_ z^P3jdy~KIS-)u-IxFFdv#FE9FZ8H8OSs^G!G^u4i1Fi#wLwkoWr7bjwsS`!HUc6M( z>1hnA*oSf6hE5mNfLz4K**wiV`Ja|$avrkA7Mk+kLUy_j){R$>h|?e~a3|0UjF%pw z`PAQ`F`JLOiMDcN1ThUkGvfV31b*Gmk{WuMdPl&-q>)AgxrgSK-}BHqL)kJnDC5hV z5>vnABK~{?bwb{xYraOSGnD1{@7bE!q-^+NYCd8$RVDmY8YOm8H_W(HQa+F zVY^%L$OIn90TV)scuzIXCgsrnDS!Oc`^(`@`A_E1LxR`Q^;4UzMpiWA_Lx8BY{7Z~ zWVwkJO4`z^#~~j$4C$NEVzyfAr~G@!{OL4xT9@A1m1BR z9t1Z_yW6CNSIx9tS?<7KM~S4!(Pc-z)v3O6DY`mtf+Jx6wV}d;XYU0CE|ooozP6UQ zZ1i00V_aWFhyC@AAd)7{*bm%q4Y<^b4ywj|r2Si56|T%6G{E^t^`seznL0AW-#Jlv z)g4h&63ErHAn)k#CehO3#rC0zc&rBFP({RaQK0MOC ziy?+l`or33ZcfbRqTaa?6ujP8K6nbA3!NjFT1k{kZ*JtG<1VFcX$p55_bjXL=`o(9j!rqiI`i0ZV*wmoOKzalxL)TxQsJJta_ZWPClbdOX!| zc)dP4do>Wy4}#|A+!t+cIyZWmOL)!if}#zy`^pSZJvmlDBs_y|MR4lP@a~9U=Pf(0 zO*!ybvj`C@YMF5Ym$g7e{Z^L1(9qz0?@LqnZaL*4G(zxeQl z+a2mhx^3R{5}NJ?n($G=-0L{Bye{iy?m%TfJh0D>5dhoO2b>#pLaeO6a)++*cd#pZRx?r{aFyI~JO@JZb8aCpRbl;C-;fa~y7 zcmVL$a66I!A^=!YIS41@22m0ss1>xUE22y#zDtOo?@ncr9J&H60nxuiV7denO7rDz zz-QTJRUl^bdE|?5pDzlJNRpm|;GX|vG~PvN5QZ*@nh8Yv%mrE&0i1Lxh*pme3m_^$ zL*&wdqyXYlQFGSNNA+(6N`PckaW3sqA}L=B>@&7xf{4+`3f*HgV^p_A2n-;k3!?L0 zW(?+YkG@9Dh^r*W4;Rd>3_!#Q6$kmC-UTc^^cR8Svf~8h)5|ET;siDF5rGl)xUKp< zI8msS+3lT{?KR-K(Sae)fXdkZ?Uyt~6@}NMrb8gPqE52ger3eW95=#}i1Cl?@zjSv zySzA^3n1=H(5Hz&IAP}6X+PviKJ9+r(Q+PvZCv@6JPOcg00ToB3$ou70 zEzcLX5W&fh+b^z=_#$$p0lC8Ud*W=3@l*EwfKWb>cQ+osn|%vMJ`-OvDYU59XBfc=p7<(1?hCm|Goo&Z4L$;RVFXMr1o&ixoyQS!>)1Qq zvCKoX=Jg)sylU-YAZ1R;Wnm%}U51=B`E(eq+!b)q6Eyz}ADfir#q{+Tmw3$AabiMl z%-AHRt0wzy;0Q*6o(oG<68i)1`XhJ8?W*~eJWHhE!)eddhA+J4j3P{Qp9eXa@;DqI zY%T8GXVvR=U2r(^lLmY3Zb9e^jNqfJ&onFpILQFxwmoJJj}7dc^ot)O36hU zaNYu`<;^!9jL&;n8G2)cu&AI*JZeF8c!$a%BeLI7wz)@Nbg!H$5@)|Y6~nE>z!8V= zFedr%6~*@lZ*s1t@Ip zqbtgSUNo8$xe5|`5>f#v^hxQk{75unp2I`etBI&;X2@!0(QD=fYUZ+Q7Bp*?1wbVo zazn^$zM2#?zQsE<3{3R2hq2d>(1}}+N%BGZ2k3R8Hg(6Ebv*kGuqr8n2T#i3!R_#1IRlHe_ZsjYZeX3qD{XZ)Ra_zP3cL9m`0A zA?x;_8T_dsi<+Xc`Sv>+?g|w)-iw@ua?SFuo64J8;`dr8$y+U1TTL-Y)t8#ti#+)5 za$dWl=joddb3(cw*ct)meq(Rg#ONpwm3!s+p)KgB4MN@?D%c*b)xKz_I~?8qy1ZQ@ zy*>VQ`!nPY68a7@i4M}E_7~(GnSveJS{=DhIQqL0S^3%;-G{qXpsZZ*bw>`dDUL;tZEGiamv)bgrk#d6Mp2_mFdS-Id|Pu7TvzW0 z=8|=_Ml}2!(l_&RgjM}G7(+22Uk&cqHyclg>jZ1xBbF&HQB4TGO;ibij2t4r zROC^gFj$YtAkAvpb@ZY8F4t|co3N3fJe3Xk8{%w(%^ORFsInXJ2!+Dy)J<60>X3BQ z6W1~b62R$+ii3wmIxUEDxB-h=VF-$&u|C;#k&TIE6x)3Y{dh-S>7ZvE0qhz83R41! z%Tt>6poL~}^2Wc5paIZ3soZh^^{0lU^8o1G?RLv-X+lSdB(WP;VE|f*9 zj?&ko=Xvo(e!>BtaDd@V%5%cE^wMY!#b8u0wG%xe^%Z8DWgX5V6K*NcMs^!H%MG#~ z3b-p$G7y|(=0WQZPdqSHQO8e5?v>X35xNRel)tN(Ibk9Ro`}^TN7cOcMW7Oc_EwL{Mb>nG*L`G3A#R6z&c5w zFzFRFnQ$~gG&bq-Q6GrK7DYBid!3TS>DHn46tkr|Q_WO*$e65FtJKoe6`g5r=V`v4 zDc+iC!8fFS7~I6kOd^ys>^5yyK(lKJGcpR~fSMVFH>8agr8{gNlMWf9H)lkWr>$^t z*Ped#!^KsmoV~$5+onC+>NMLCpXF?Ctur>O3w|@pI{i?v`61=>qnZ|*pgPOzEb=vT z&Usb1^=<6EbIuC0#yaDM(1cmy$iPgP?)u=eyow1h3d8>d6YvD!nzRvSa zUGsiAYbaK0_rPn&`D-BP8m{6;451}p?WZB-L-ZMU8g|cvrZ(M{5ZC=U0h^4rWp16qLAlz&+A_ONvIu)OxLVf?TWdf0s7s44NNCI6_c_UO&{QTH99GLGXq z#p711=Om^#L4ofMk0)j6?uo;wLTnc|q69zR)vo-8V!$OrC?Ul_{_ zo_6QmU(H)Ne7gd;51#P41CL2~g%NbO!3!CW`H2*#UZWd6_4N`)oN2KjvTK)?P&QH< zLkL7e@t@&-lnJBb$TCOWr0ckI@_;MGOI~3)(eBH_Q-i@*JX0Ai0ACYT(68S6Ts~1EK4x*= zO-r@bn?iGEDZdnIJl+zoxobIA?F2>A8R)8WM7)e7nV_|AlVY)o@r0f8z-ysD`A$?& z{43i}L)BK$F^VJm^^X;a*ue=^4x0<3`7Yxy!?*qIq4D70#2V+r{o}VrIT*7@v<1TO z*kYVuL}ixL+-^coP7&0`gT^2?^U4WqjH~#*jTk%#g^eH~{6aBY#VyWeoSRod#PM%? z7B&+rR_RI*S$(i(BR7~?Z>F^B!)YXyCl77G3D^QjQ(Ne7w9-3y+O#qz9*Ih#Uk>zr ziCQ*OB+F4d^Ezqa${~i_<+oy&yEs}^FEdxBI~pXh2;F;EDX^ku_L`T&F{rC_c=&-} z!cO1{A2p`UM<`=u30hy01hRu_k`zaDNv|)f6UsYJEQ{hBib9C}ndPr_AH3m4=-tTR zGt;_S%%|yvrC8SMezmViMyfL*)BNMh_oLp9D1%9!SA7TF0trxt(8CS5Qw%*GacdZ7 z$V&~m;S(Es=yOC6}6wuB1 zUZFRIL+E`zm@}>6&1YCpLuW@7Q{B9u9D_MLG#iJvsGgM6di-oI#c5!FKF0BuZGh)3 z=Qe!A(zScgBz{lswjidCr|(2=AP_fdyYagYC!qlf-e>S7W)DrphH;ZxCIyhbT1hR8 z6j-U)lyI=BbsWBFSdW~)*yYPAab(?mK_+g!8PAk_qqR9s@U>eSCkmjIPwEiJc9lp< zpN%MjMa!c!h!Mz#{gNlQq)C+3rqwM}TcE=ziX5g;HRohEZc$c^;I>rnXFVP4Vru*V zRnivSrqbdgf%yaW5fd2>$b@N%dX1~QZvi63)+d1rQrb(!^fAjdQF$H1+z}U0^k(KV zgct)hi*n>Ht+&d#yxAL1G?LoITgQ~vFD;A~er*jGlAI$Yc;8J?!2q;slH)!K?@uCD zN`i$&2X(s!HvvW9Z8-8O@PN;`gLacR9P7x!YlNC`amD8O0!f;AP)Z$UvjjV$XO|kw z;jn1ZY_(fXpb4r;M4mE33^R+%lr(3h5sIn@uS_c`w9?YPtjN98nOHNM84l zO7g(M_l1`%CfoyCcw7VD!%Mw)9iQKaQ9!zH-TD!nwqH-M=ixw2bX!#dqpS{1_AsJl z8=hXpERdW^6rH~S;1PJ&k&QJ)xa#&L52;Daw+jP^9aL55(Qm0X8bfM(`3>$~{I2mj`IMHPE3If_Nkuvk1 z(T2A`v%)NV89Pgsa=horf-WM8yuN>Hg?i>lfy*pPVWRL|e9MzL{z=rg0_!sd4NY?y zoP6QnhCnUz8EGk09xFa5pky=^B+p-^ODC z1wW@TND;)rS5d*WN~Q2x%ovR7a4ucYRm&b~uq6p+!_CdMm^PyJo2|JC%ywl)FjVb# zNPo7|WT~LMs5mwpUVfmT*EwR!WrsXaHCvRW*<~X3iXc97vA4i(+l&>bvcH)$l8x54 z9jZYWkepUV&P|I22LsJMK;?;UKDNU>`IL&X}M8B@;AEZ`PGL9 z21@Tedvjyo-bd{2mK^n?Mh~RWtP#Q};f9epVX4P%xNT+?Z=bf=TwsFC@!zg^)6D*; zxbwp&mD?5LPQDLwv$a=4qbf!$@*Zbv>Z}yKrD#ea~jCn7Rkd9XOcOZPmSP2gWqaWwuV z#r40|Y&QL(xc-?GI!yml&E}(&<=Jk<>qdJ|`1L+v6%zI3Y3uHKj#mpoF~%WJwl-b5 z6jeENs2#V~;>Q9MT^58!`q#0m#>apz&sQ2zTAG4Jwx}yLY@50Qo z)h500Y+5gPkPOUCO1~_zf%tla>`nTKTy>rDZ^5ab3TVhgnGUSx5}tngsvTzMSHx96 z9bB-0G6TsNl9~y5j_NlPny}wC6BbVbb6kxi(RB+~HRO91s$n}69ia1{6dM1bsOzcF z_{ncXU8{C}8RxkCcZJ4bqOL!IT=}qW`~~ESe%uDaB1kstEh37{MuIHCV3A2-$B3!U zrXXr4*%u6!e{`=D28$kGgRfHpXm!p=kjcHAlo&t?VS^0cyt;$1TYjLDu4@62dw#NN_^#wi3FwiwxD#4qGJ$R~jqN{~>2`4&*+7cX(JvZOJ zbBPu@cHS6!X#;UZ!cl{`IaBjO+<{!iZXO^k#$-_(Lf*UL1i;fPeB1d+AF7{0e_4)2 zrl0bjUf~OV(K()hh!Ors=lCo1SIc(c3-tHDs&jmr5)=RUlqe3%du@KX`sIh52c@L1 zOEw=~hq8XA3$&ooBDxCW;p-!TQOPNy$s{ZEBt^o$j&URIE>a4UMctJY+K}FpbJcoSV50yy0L?&{dIL=L;s@lfua@#`Qf+PD zSMxsx_HU|rgu2xkAPX%#5>d@KIKiJMSAgdRTTfB{_bU6Sv- zg<;A|Z(z1?@FwaW*X$zBmKD@O>yL@|8OB}E;dmjgTh$r5Hn~^&C)`0lQU?E7HNP@o zd|u7>QXGCqW8_$)i3ou!mU$P6_ z|JQ}@=f9XT{9gF}SHkG&+vwihTs-o z;8t)!o+p^b7@Y6oFqrR4m;(>TmuUE%Ccmg#?GK{C|9f-xUx@~jPAP@d|H>}@l|aM4 zT>A~p|1Y+#UyEI1K*m2M8lFqp$qgm3Tpn&nrMUI2*wv_h3^ZyW`l`EpmdTQUFu3#| zW%6f51*xx04BvIaZ;A?ku~GdBo4fh|ZzP`IZ%jB}J_Q-$fj8pkfd3R^X;V+EC zFB{e4NJ+g&5~62@>6z(9r8!LRC@fo;&Mdze;&J6jzEfu?fmyg^!Mr+uB)9dmTq2PhUyo{*=GWU zwZG+w{)S``{jKTw@nQ9|(Hysf)vuSzb9cnplPE~F;_l*)*enySe|}i~e2w1- z=}!LTtByOk9SbDRg-N-cGi)!Je#N3=K^pGKmmSpJHZChm zi9LtEA0bZE$dyXaQ=#*PmOgAMjXzP+0b?(tfe9fDdFopI+o6 z1HX<<|4{)lcs@2g<*|MjAZK2_KOhYMRe)eBG=I4daCj{BGyR)?=6!(0zu#h6ik8Kl z8&KmONL1PNi>y`?Be`3?FD z^PNjz<*eiZ>(i|I@yG&wktt;S*L@R7O zK?O$-poSBHeccHFRQc~80sdQG_gul~@0?7(?W-&MI>O&Hi?706f=!)iV2dsWL}2_c z7ri}f_zUmow~H1i73Jl#Ht>i-H>59rtowN#@GvP`);gFtek$N1Y#si9ud}7^1cT|1 z7`{$m|7xrN1Ag?)TTN8Q3qPh@A}L{PxkC~{`Y%uH)E#Nh_4{Fhr>}tufYY1+pr8QY z0DHTNU%op60QR3uFwF@#*gpUY0ssyH;Y&oq{-X(~3_yo{4uAqWlSw_5!v&nY6qVxq zPD}MipZ@b->jSuS{`bPZ|9kqt8vyXx7a;_Uz!6JmHp#&u*-k3@%4IU^4nM~-KP5+25|pY zMDj zGEph&XNODJWd4i8<(cUF-!0N4SCe5TfEF@zr_R-t>y*DU0hBTNFK9c))+WfFX|#O$ zJ_i0Hz3o4&vzSkX{9uOsZG6aCaUYWPqV&}}3gmir8Awjv02+Qa%mgqjt7IxGTXN@U z5t0wTFOyS1LhZ&X-o#w8R7^L?%vJ(AuRCx6Rv_FYfbvXy`Vznj@w9Zo%zWXgn5x5 zdQ!Ygt+_ltW8pp5TeWFNHh8Y7(rz#fYluzf%_e_L?b3ZjDp#3E4$T%hDy8RAQH094 zh*J*?WWz);vr3rO-(Y(3!Y|3;Qu%oTE?*u4XRXQidEBt{V{M0Ya^wLgk)k)UR};aGNG>E>WObuLd9klTv);=jvD6b2%tjO}Bwj;hhC_C(+SdWRMIJd0+X(Kf zWy6(vO#cD2CZxFxEHR@q==>A~)q^iBqjSA8fVnwb)XL{Nn*>jWE*SJ-Pk5p$^`d^> z`R)Vj@t}Y~*se==mXE8j9#09jWdOf;iJab)J+!wzm3?G8d1b(IuTcO|;FZ69=Tpf5 z+Y|X0(d&fZDEK>=RqqyWyRwzZj1_LKVZZi+Jr^mO`UKY?5-@wXI-V2|potKUzvi9X z8vypf8cpi%mv+C2JRpZ#Zvu=fYrvgZ;4;I_mA*w8ad2}fpH`)f#?P8Nquu>B8`90S z(gGlzCi5$dz%`DB7#UiSyv?Vv+D`WDtmeVlL>^UN>m%7)*PxXFR9K#bV3LWHdmi zOQZVCxCita%9zvgP2;huQp%a5sft1xRQUFXMC6K4YI41Xkt|ZK0gHO`-6vLQB_G!aZ4NFo*_!QK-0|ww= zZknPrsD`498t2dxSnxsty#N|m7Mzw*Snx_gCWJH*KYM40dh4GYn@Y|mH+!leoV>Ef zx$7PX2eNrM$PRD~z6eECtq3)6bu5Lwq>c5&Yo5@RTyk}gw0j~IkLe84R-{~vG`@b7 zoh*Z*yQVW8#8q`c=n_F9*27IjaDUnj=OHtDvx!_GU}q#jv}e{xsme(NLHj#-K)w#$ z;31tdji_hYN;#>0hVF>GekkO=*UP7)b++&yk`I*{(x2j{9hnm777R21r$Y~}ipykc zhS0@+e4HIYb~`uC{Jwfw5(`gxEAxJo#spb{t&(V|0gJtBQ4+@q;ry(^=4_tqWKGxy zo>l?3Oi|}efBwm7^e7@NbA{>(in+ekqdaFWft{_DVxi+>q-)y;d+7eP(KRj({aA&P zAm>E_sWIU#M5-}Nc&@#8eXr5`q7HayFO;lMm|rBglg?%kc#cb}C3*tsqe#66xLT=Q z8PUEx@H5XH6hJ<}7f$Bvf&UKOafT2u|IQoaVyg=>m=s?fLJJOqS4LCibA8?k;goD) z<=fQn3g@{!YyNoc{hO#u9=-UcVT=l?{2?2vXb)e!OQHNDx`TxjAHDRqz03Dnjek9z zzdq=_2{W|7zD<5?wgu=-S5DNi$bUHh8LKa_@Xk-(45njVGA9~Yg*bQJVT8MHx+#QA z@y(Np&F9U@EKy@|2M=7Dd{_`piXB&1dtPcnFL2aU?asgJ@=$b1I6hchY+O}6(7N|z zcVk?r7Q5ET<+y&qD_(e4>2{I`GIzMHD+V_Tj+6?Yd5tpnhOPK4FBgNU%xWNP5D3kdXx8KXtIxV|*_}Wx=Jy#N(zv z58%N~tMiN;xVn%TqLRg&6`F2pAZnosomYARe>a0MJNs3ZS$5UzFpC}8u%}9aFk0n2 z%)C}}sfZs_mZGqWrgO=sLqc;|IA(wbf{SujLt8dFB@GbsHuBR_MX!bcTS;G@ndPhH zEEcP(ts=A4yqej7Pc?fRmCwOt1N;ycv;rCs(YD`Ae$6rWQFdcEJ1bWco{%|L)KyD= z03W>d@U$2DQ<&x|jo<6FW`e{Vn+}JQsPWFd=B1+7hx@lLyJCskD**ruP2*jhZ&|N& zUkNiR?ve1S4D}v!N6%}J6FuJQy&;fW(l77m_;Ns9Qhs|t=N{YD!J7}R*}gaMvEc4k z5W*}SkZrW!?o;$Ov-_Yw_tbX8F(1md^WONA)6Rq|-pTHyGeh3a)Xf`9ydA;$am?Vv z;Yi(&@U+GsgIPyN9?wC1-WZH3Fvo>1n1`{`Ej~%qIrx;_n0K(0*J>%SocTV;@l(a_ z3jHVbPwZ8z^~FxOYi*s^1y^4ajX&8a<5)e~%84>P-d28`yR~EXAm3?s!iD3cZ!GLW z&Hi*${>lEQjJGF;E3LsNN6YWVtA&kPF!lEAMwXqRCjq2@#TXpEw zrp8j}q&-x7#VCZi?!-QrM_M1jw7hkl+kpPOcqF zkv8G!a&*kMr9sN28{zq?2CV9QpxXnuk!9fq>?TYg&7Gp~gx5V3!VA)3xz>PKU0NnB zFp^41Jtn+xAAp;$Ku6|s%s|fUm3*cy0qe`LK0pTUvP^la$j#Up3?u$l6NN{waFuI3 zX}y;qZSv*xBDv)rWK-=>DkrQN%xcfsD{%bsZewmqC*;P$j($oW+~LXSH;uv6{K|gx zTS++0#^P5UdVDncl1aAb0fHUMo}qn7Knj2iR9ZR6y)T9Knu)A9vx>39rRPipzW66# z|2xKDwC4rQ*WnhW-Gi>AvWyz5aJ=eEr`gVw@nXIqD%1azUMyT~)Zms&d%ub4cDD9t z*6l{Lfx?)ZImT>e8tqx2!b_fs@RKt)6)SEPzbVRlL{Z14)q`|9%^Dq%^rB9`j9O{J z%L1RPOS%Nvw_Jf&o=ZGsl|`gc?@-uz5!uCR$fK$LMyIqm={U#uDw#$v7D7=JUE9@w ztX{Zoyo|i7Ear%z?^2;MkqJT9EX)u^6yK3Hy?F6_*&zAZh-gIvre#4ZVR(}GM9@HS zjaS}7S%J|xmEBiwotjz8DrHw}`zvji^XzK{#@0f2t7hf%*{+c&?zBA0LwGE1bx+{- zGFns3G&#U|(gCus5m}wxOy{tw>!Vq&n`l|!!DfCx*eSBC8hFdflRBppPSHO6=n6CV zO58A(nQbHTQ)yNU67p+7p!lqV?M=q8s3SeF$m3TT(vn@e$XN3;CJLvL(aiY?zAX?Ysg)dHm2kdCqqJcMtwAomc0 z(*^I4+%?lB)_!0){X|v9gScEIC@+-G%!Frr|J`Gx?F4Z)t!q&+eF-(s9Z5PDn_f8- z=1Z{V7_ogSLQ9j#!@nOC?5BsB6h&p@Bn8B18G(~i>3?bY=vI5&k{V0pP>FMC3HGOs ztD2R)gJUHb`MDOBRstjAE8OMP@+B1j^i29`gKEl<|6e`sNF zF7@}RntAkTul;tyMo4Sb$IJPkqIbUc3pdN6zS zQI;gd;>rW)VaAR#bg#blcs;iEXnwUs7+B!uvsXs7%HRvQ@~8mUI*DqFND6Vj5`uz} z)&V~ug-vZ4HD`Zuz!urf)jQG^qudoM+TH`%t&+!WGD>rB+lp9Co5bFYbkL1_&rL|u zkv$6J!sCE4350jGqM!mjXmvs5V&|E70Jei?>URfH!*S>$aqbyBzv@m^?lwT+Da`9h z$>@2V_ZAwjZNqb0+33f;O^o4f6FRL@~%R zc1W}LPuSB;Bo4?S4)EOb4}9_Dd2~Qlxo?iWzqgcsC2`;@-oTn@-%7PWfBV3u^1ue) zz&CAy?Y{akJWmnZ9uJg19+Z0e{>9TFwWm65URZ@*{=2RyA)Zt3LF2wb)@`8C@~2~M zPuKQ>Hs*u2%Jp9o`*uYI!^~^R4E;-q)!Xd?kZ>T?gTV#%khqV*KobajW-x|22yQT7Q21EWq`zwmJ~4tHS;m-Y)c;ti8~=B2a{?mQSSBJH8t z7Q&DjI=K6!zcoTrJ#>I5Qimy0moL&#J zAtb@`gWzP6pe9L(GF0de5~v+X*o#R((q!bUB>dqdIDawyhsosp$&~&{7fh3>(UOnU zQ|KL1NPt{KX<$|~s^N8XCfZ&aFew~2e z?|;&j_Jhi0k$*Qto0alGypJnq0x=Sc=l)gV@Gaw54>}!zf$?I zV6xShnkDje^u~B|6dQ6&mHOt`Et_9OT4>Q^einrO9h(#e$#~PvHw@odJHskoH{(Gc|In8Yss%%L;{OkOZyi?Uw)KH7It2uzK}sY96e$T^^rAyR z1eK6RQVBsR>0ES*fJk?DsdP(scT3m0FIc#@?z8u~=X~FHpXdJVQr|h}m@&rqg=M`& z5uyi`?NpA(e5~cn*k%}O19sr zf9B8`*)b|r?OhcL;+piCA=u^1(rrK16=!6GP8!sp@JJn(2o>50Cxw7W_uBL4)F_&@;yCbDob-Az_>;FBK`$s!!C{J_vDF|uLk=LVh)#Lq z@u2OVn=it!f~Z{pI{Q0;Fd4%xjF?I&gE+OV;S7isbNum3pG_`ZS?h8V^iXf7L{X-9 z1+%G3){A4Rh1c^`NyqEhS($E;qy3VpSj-N#<0oxVoM`6U^>-w z1~(qCI0u$uQH%SAIlozc?Te=ScmKGr94o{7)Oyl(B@2jcZ%_LL2amY0b0oV*19%12 zdc8;2h`B2bo+p{sVpp5YO*~&6zZ7H5LCIgcv9OTVm*OzN?6fkVi6O8Oz*WsOa}4+f z!B;4BFe3@lLtW5DG{->JTSe;99W&Z)LS&TBCfu|uZo~^9*>+QT>PXAUc@dX1O!}}} zadi-IXjwhdAny*NaYtjgE(f|}F%v5UFBPmE!2WSJ5Q<`nIwOpG{r)9lbo0I%cm(MU zs2h^BI8Fef_?Ny3cC4mzT=mpkd4`yE5XgRDH&|h`C@otVb zuDbv&z}1X;Q7-CfQwqJnQyIf|V(z8E3-6+>Btn8>DW2(nMWdX#ilPI@IN@K!zyq6~ zk8$2XjQ?oQ=-e^>>)M;yJqtHH$#QPXgvm2&qNB~rr`ANI`5a)059*P}@cp<47Px4B zLr{|b)Mpy?2%=>%(I4`_YCG53v7$9JZ~^@m(oBBGn{y5@Ft*0EBa`4y2(+}68D+OL zkPsczbWQk8ah+n!X-?Ef6U)YKL?u9TMN*|md81p`Mzs9%g6#@b2X5F%o;=`sJ@BcH zUyZi24zh9SnY#maMdvse#4{Z$hDV?nC%n?HAYp%3Do)J>!Et`f89t!6mldOQqK@@0 zq&n6W$%$S|?k2k8W1+*9ds-d{#cW_wjM2^}=FBaW2@s*G9<_ob7C1hD5{Wp0)L8Dh zn1eLuKD7c_@HC|(U8%Wy_$B+2D?uD17Ve>Xy&>AJT&i3mQ7=BGXefwxp#}L_jl|B~ zx5AwskG+0!3+k;qQk@vf%hn$i2Q|5r{36K9lEyK_&C30aJxTY1+#AtTz?^PKim%R$ z=d?g-Di8Q;NPI8H{*zmLp zP(+I@cfI2G}mZp_xg z^hAW(+?*e^6=-i%6KH3L$AKSs^!Jfx9^L%N{O%~%6ER~Le$s`l4vAJ^vc$apPGNqR zC{qD#&PV2=@*CAm2=c@U53P$gyqQgkC+qI0LN>gaP%b>zkx+mS(G@fuHuokKEwzy3 zE$r8F2OGtB>Ub0lPh5@GDb{!wBbyO1C#v8Efd(6w-T-@umYUCjd~QoH#92wtC%p-c zG@wf~WKivhjQ2ucOi31;Nfro6Ts&nV2uK8_7ueo=%EMDnqWKu>e1^q13*P?WonV>~26o{*!@5tQ0bJ^IKp7%h5hmqso z?}!l%r2M%#J=+jPB#+x|aNdyVya(E^DV)n)fPsh>U?7q)@cnJ#!6&3;{PgFj!eAsW zX2_X}K&O^?E>)6y=7IKm1Ceut-iobz5@Y2*5qkNyUuT;{o@-9q?_B_d7z9RXDd+hC zWbVa^FfqWXrDlF< zfIy`T@TmJ(>o4}&OsM2@TO-QXDL6ZkE&)?8d^QF3znp^d9{{F{Z!7#Lg?>Xo`48k8 zzrLjYHn8E)^0TOA+gISu_Y1i3%+|Z=mt%YIV|h0w`8}$5{_l;=cm0Av`1!ql`lx6; zTd(S0kLkx=--ze;fc+mFlQhqqZx`!#MKORwgb$Jj(ZGMwHEs!3m}B>yra|EkgwC%gL~Jc6G@ zmEao_{cLg{gWkf){OidbZU~sD`oDZF{9}^XA9f_eUr#RVsolvtD_O_H?!6=>8N6s?|B(IvC>H%4U54|VNajZMQ?#Ju*LTG`Thl-A_(f5zzh(db zxg1Ajexzbh8~MnDMs(wBSS4oaK~lpiNW1?o*#*Ffom&`BTQi!)CDCpoxP zKxi(I;KqGu5aiU+?ZHGc%@>Eve?vfM)kX|(hOp9)_u-Tni}&OF4r&6P-(GF~8T}bK5W`-H=vWg=P ziPNT2j58Ikz4u1reB@iYzBVNZ>y)Y8NgZ=Y4v@s=+0olBd)sIh2yP-^V9Qt^T`uLS zIQlf8Q#4#wKODoX7K~EIC3|@;OYPCsVWX#}-hs+H!xqh#5iY8XIq`+$d}J-m&lMrf z$lk^v)G>1!cjX_^s=s5EZ{f~V1%V4CFVxVVl)f^01LR@+Lf@UKD4)%d6k(VR>T4C9 zJSAB)+&SfMf_T49fN@oyR?-Upc|Ezw_2>1Z2>7>fe8rR-75pU!^=Cq<1q`6U@B$?X zV2!qhnFthv=K+zNsh+b@bRmH6H&%)G+-nYb&$*ZvJI@2c?2#8cFIe1W`0n4g*mVKG z2dBilpd%UxK9)Jv7f?;mOLG5CH~|762Y8d2oxRCmU*BXEXZZCm$WEja3GSTn3J(NE zf^Ls*dSSOVDFuV5%N^n9^q|1mCg4RXt?Y$ z^X;4Uh*3`paQof59Xn%4C5W-mDKRxJ~`*x2xjj<<<(T}9Dkt*cK3v&4z<#!AHm zE7t@{e~!-5=xep@i-;Qb@FSCMVC(!zQ3k1z8&GCAw&`&YN}ckAm=*q39hg*fenJq> zuY1D%tMNN(FF8%>sexlJzLpO=RyDOVW&zRN?{yUb4q6SYfI8?Vum!C_r*P2oGq@|A?T*GQev! zG}+orxG-ADb+SV)1<+pHxRB51ho`Z9O1S``2LCa(Yt?}-F8}$95wNK7(b%*F15YJs z&h_jPf8>W=#<5aw~5x^KpI~+(HX($Hb*q6`x zvcbsqSb@*l`Sw}Z7`o*Ud77VIUT5Jd8JdAx$9^kMqcx2CY2a`JRO8&D<$$t*Ap;F< zRACU@5j;3M7W@jJDe;Ayji0u!8S}a1wS>LUZm53EQqK?BAjelQj7F0>xG^`e6-shp z7V{gVANc5BQK`;G^V>i8@hKv}ry%_4Q=WN1<3G3(0K@#nlLJ?a$(2>SPMACIU27CI z7aJ|nH%YOx3H;9w@~_A8t3jTv^M7TKU!&xIaFBmZiu?c8Apd$Szgo#Z%=iBvuK#RL zex1JmowF9WRZpQPUT~)mE7&h@)t~qS?@##yN0!j(hEs3yYx;pY5@Aeeg~9uQx-CvO zug>BZ-*s$ozGGZV#+Xmv7Aa=BDO{?U;us?raXV!2<~%r!;t#Ng`?)GFb)}+q(!X6s z|4xzRxUfgy6OlZjqIBeqCFdP`B_DpZLeOB5@ziKWnf1z8iPL9-Ro>!_iF$7u^~~~H z8*`0JGL|GEJW8)x;`IF6UY1$Ujnp{6`dBLY)}3~qyi?DrbN630c6|>na*R}8J)BEvOo@6Y|Ilp35c32UZ$9W8_^>oD)-B_#c>`4 z3PkaqH1R6&ZcJ9m)E*4EsE@s`HbEwRxJQ#8dlkKgJoaH3+?(_hBp{v+;Gjm+4wPb9 znD&>O^@w*9jGr41!PNDf301XfoC$m6hBh0n70N&o+(h>0gx}G|RgBzCJhSS_9(WrU_L*Djir?MQ*D z!3wBy?aU9zv}K9KQG*>_3TUrqfk96?o5~Tew^nP{*)V72-T+|LXI@%#z7Z5{Hmlrd`RUD+IjP9V(_+Z0p>>q{o z9&FVKks9ZxT;N*C{)8eEAZ(Y}VuwKt%AcaBgx5cg0R{G3OM+CpKW`1lyS?%-CZ!GTgysByPd^$zWB}sb6fJ=%*3^F z7|Vj&;ScK?;qwJ$_+!>LrJr$ozr zf3J6o21glcio0_W3|f9yjc5y1%FiX6;}jFT7%KOaPU_z1i%u^GBrLPRT-Q;PyI!DV zY*e-I5jVuEI1aJv?nDaxCol!n4|sl1kM}$pC}Ddw*Tppq7pRax5GnzM*lRBeh)_up z*Rx`dy)Pu-fS9hKW(+dOX-aEPriW6OA8WSTnv_eEF~QgK9GLjoug~tT51;q^gn3fehz<+NhaRK zp0N|$VANnVtC)Z3Jr2jGaO+QlMiTqio>1I~7;A}ccHD2a2>fJ#b|Z;r4dKS!uCCX~ zE=hc{x7w|{KF92|=<#ioz+_+c=Dh*+jIkjt%Gx(QjYXE$7rNsN?h5sX2JEENk9 z#;SLtH`$Z;M^a?n8N1`_f|JEK7NtT`KPB*3rpOvEN*QmEIGg2(Eh(ftOD<8$(7lwX z{?U-?6TWh;UqPA%ztR0pMrGsuR~fp-z7LRukX@dbQfab79%1C(bKbI~bhrf3FtCEw zkQ8Qn^ejCf^bRjH3&?@`rfUyc_&Y21Qic^Q3$RJzv|)Y7gNMri2}=&PMiS&Dg`^wa zYaZ+^-MRc}u~DQSH*gR};!;>tz%2Jn5+_{|g%@K#Lq1Y4H~~Mb`2FiP^N^?q6C_0? zeK~&5!j>LP-`*|lwQLe2iXs>&-6k&0~jHd)3ERvK{e!G!Sm?)nNIV*%MyV1PR&HqPLm7 zLbE`DE7ziKT3lZmBvr@tSMf*^$^l97;SeO*)UvYVcs(qiBre*cq_xWOYYm**DxILb z!wG?6uxUHvKc^HUfCM6CPtzgnHwwD31-yHr%}BG~BvF_v=+>fh4THNG-pMq$CK~4| zuW$>(!gb-$bmE(9;a6_*??^r0H>tMJyciyda)-J3QK# zNBx-!2_XP>wS(h0yE#u)NKP55=aeCSQrV{Y@QUIrTbQm0r2lQ={068B{?i)p_cZR` zxjCi(0CqKHeg`dF1^|P*eD~LBO`WSO0R-5Qj@h{G@g;S?jmuvxL0+ygx%Q=f)m45r zwny>ot=tR2&qSSsin7pS@Gks#Gpp?7QgUaLCP%Taxd#I166hK>hy}C>UwAfUOutCs z&kCvD-*K-5D^7n|Nd1Ciz&)~tCU^X69K&Ce6=i+lDNd^+?>+GTwXx8tiwd(v!BQU^ z()$?cpFnd_Yj9`n`2UM-!2g;s`CkdO{vg>WC#Ei@rWc-}W0HO&Aa%bkwsH$?sM^MaSr-trQMhE&WqtAzASz0TjY?v+5>vT7~zQz~$>7j!BrHAMy3l zH|hZ0{T%B;GW^YY+OQ{^>ekUdW2B60yG`UYMLz2AY<=JH!GJ&nDiFJ92%TrK`%NI? zciSE4M&h6Ro!F(=y1E|r>)6#QNctzz&183J|9X#-YVAEvy`I?z{Cnlmngm~C7x0Y0?rRdDQB$-KxOz8u z6U-#p&4$D(v}MtP-TES+l`iN-UfV5F;XEPkdt0AVVEE*Log&`BTb&X#E6+a3-DKYG zQoO@o(4!>wdb>yU@rq@i##82qg<)@fl9WB(?$x_|ywmg4zhZaLn)PIN%3bzke>SO|e{!B_)P8@w9vgPF)|Ykr zcz1}k>SS+?l|LmGBNl`LscyX?ZFS-px$aTRJzXmr_?iGk{bj>ZPb|h!rmB}X#<1S%Mz6g%_4n!5pTlsy0NVYpOCN(BZ z4&#%3dA?Jv1SR)SJk#};G(wSjPZc;9_c&aAn%v!FG zjrbuAA2nHQtI`9q;w>|6eYd^=Ywb1i&F$%HZYLlH5i;xnD z!>Q%Ja_XaX1w%R;rFe45k(45-Ic^A8r{1;ZY-JF=#UrFF(H0JV_&{#tYIi*DcCsg_ zp@MIzV!}aJ3U$k)Yet<|X!LOuk3PI(i82g_D1gFy9#ed#k9B0pWKGqRPTPwi=`D!w z$uLx6RGT|cF6j+PdB&e6VwoymxtX8E8=}eqoAAn207qd8tHKL)c_Bh;FN=>0a5Yi4GHvOE{r7 zqR}B0cV&B)e;^#DA|g55MX>AnB7uY}pm5m2Fr#ERn&jE*=HWTjd!>C!CRSX(!u9phfHA{+H5L6N3Vp;-Ci1KcRb093W3ZDdOvS|>_@M*PdK&Cq1wzMbFW;VZ|cH5l6nq% z_Ive=sRM%hpJcJNbp`khEuEVi4Q@uKrYYag%NXoQx3~PH3S>MJ&&co52Hm=e23e%T)zGJYR-2u>TGpBo@<0xD< z5S&Ug*S@kb9PGVH_XvHEf4h{ zo~9MM)uQ)kAgr%^nk(#i+vB#Uk$FRNEcN^C)>zM?u#e|)Id7HH#wysnbzzb#vg%G^ z*-pKCyr|sH(_57JE23@5BL(Yx!8?J=+9k7@JEd78t2R}3S5y4j-rF`2L_MJ$M;dFW zCbeI8XXTqD%-XBNJK6Ab=bO5+w%4F$zZsUrH_Mf^-*)%pa|8RDdgnP}^*iD~94>})W79hkK%DSA zgowEvhybpwjT7DnNAx}J30en=2B*vYPK^CvG9rPAEoV}0$4ESxcO9IW8ur1VuR;@F zg88+8|JJI7nU&gD(LTPbA~}5q+dv6b%GYh~>-S*4nK`fU+gL|)knCONq4>U(nfdT`#U{J@7siRO3@84ZL)bqQ3(!T$g%Sp`NytHvtS zfWYC1*Crr|>SMrFqo2qj!^I*kcOXYW-8NLD9^fE7Rq^dYg?8HL-|c6Kj_1QDc1Pdm z3)lu{f)LZqFfzFXcEQLH90f8cqWBa#+I4i883qRUt_DN}V+LD+5>Aan%T)x+_b~$OH769Z3NS-pNJ+SNoxl`*}RYIJ6Pj^x(G6 z_SY&v8r2U{-p9Uq>xNUY&w~`7M-e_6jXs(KA&>V%?sM~lv(eC|(eXftJCp(O^t@Ga z$b|bCWR70Z^R{S+VOK;0)5fty&_MFz0U}fA@Qz{0L?FWb5Uqi5?S*ik{qR8Ih*0hz zhwx_s3PIgO(CAxGPd8tW2*mV;V9ag4DHZIh>qrnszZEl)s&^o@4p$Mpkj)0Zg=7$1 z2l@$4$lDIA%nq!g>qv4P*ij1+@b{w|JVR8`eD4tlRY5^&IBME^0eFoyEEY*z5L#T&J_a}&$!%U5;MHecMS=q< z6hU8acR=pqfZ}l!&~eac1|cVMD#=A?+91&fv7nRrc+6t&L58?s@i^Ypw|ob0Z!h}r zh%p@YMKl^D)R*Y=(|gTKp(}tug*{m9d1wWwAP6N=@|=jcV>ln0f0Gch8ag6sEL!0@ z_WEA%qkJT^b$`fUV%Q;M^#vm1KqTb|^EgA_K; zh_LtwZ!2rN$l4z*TdTl2NL3NkoONO?8bGIpSY{o> zX5Ucs0zb+Q&nV~8&9NNPi8l&7Rq`3@sxs2YqEJL~1n{(O9 za@h}aZx$QnaggQ(b#oSUFyQJEMb~i&VB`}C;za zDic;Td(mW;&cuGG$T7{tfvMQZ$aq1wc&V<)rL5S4x7b&$*z2&^hqNTv&N$SrIK;c8 zC$T7cs3g>>D2B8&-iWaIR%xPLsRdkVa#?A58Ns_D`tRNMGnfhs$Q1sIj`D92ZKs78 z#d)vs3g5pb1w`*-CuG1WAi`4>yK2ZfiK8MD#ky)hRS`~J`s^8vcfMBn*7c#y5j!>(K&EnSx%DK8Km^W>b^ z8tb>q%Up`IGg`~8cm-4Ee`LAuF!w3Tsx4-HdwE^*CO~$zU*35&meg~(3Z{1mLT(_l zciz|yaXPtD9Db@AMe0-}kUZ`Jv)qleCD7d)aV0Y>er<=lDmvj2drLq56;-LL#yzIM zd1|$*bwnCo#s$S8zO1wQBhqX;D(WiNrS+zixMjA;Bt>oqC-_OBD=N9k2kb@%Bg@Zr zSdp8|#|5iJhFu9IVGAY-SLGzU5|K(=5C>k9UYM~p&8$z1ei}*~5`^;3nl8W~SG+4+ zF*08}NV-z_s*(FnM1a2!I!ZuX{uT7AudyF7EF?g?O6Fb`Zqus8+o`$+MmXadGKxk= zdeW!*7TT%{rKQ3a2H$CYBuP!qwoOgR2OrtNeP3we2*k4_&?)OWgEey_NTFDw(bR7z^P&mrUrLjyksN1x=~FM?$g33~5m>Gh4b^*_g75nIY=L?FOVZ!94>UQfJ6 z$a}NZp2u)CnOC;?bI)CevW!#%7Gm~Bp((4CwA@J2jautUpVdUnu>)jw{{ehW5R=UZ1qPxDI=k87M=PqPO%-c!6|NOzO zzTa96AO<|0~JbL&pcS2rBH4lIm!Y;${;OHT-Q+m+#SEEoH z+4ViXhj=A9VA#Cfju(AmifFH9!BWO{g7*zNp?>X*Ylri7M9)L?-O7d<|CioEq@U+^ zYENc7AHI8xtq#+Id>AvnE{dXvF=wdwflfi&QVd@XcdhO{I?qM68qauwqK1zwwj17` zOX7)W6yCFSt@|7)P~utF*TKIu^?8mk@Cj_#egvmJR5QLw(CJ$!v1X13*r)9tRW1`S5EZr-|l;9 z8dbQI=&=4AmaEHiH!?3+Z?gCK9eI*ZUI$N_aqjEn-LA=ab#inSbw!9t!Bg^iNR$32 z?iv2hTU)yCoTs_*&>{ZLmF=3j1nR5A1*yez8NsumGxHs;UjX%`=MAn@gp~lUXwJZb=I*wD51^J^{*?`VQ9@( zD4R1%^BCxcbz>B&UYdT_6^VuMT#!%a^SZSh7yciXCs2|yYBH8#tNyx?f6Fg}b z6Bn}z9a;^C*!S*th!*OmRv2y-M)f;aDqHy~Md?*%4DtuX{2>B6ep?T#M3zC*LUE!lHr7#hi>y8ITg)p8pOYP6Gk|R5#ZIVa{I5te*N$Ko#?lgV)JYynyq}`2E(qL4c`@~^bC+1~DmIT?X zQ&YLD^WrY7r4%z+((PU?K9*V%FOC0u>^7_(9(Hn=VS_ICOLlI6jtSgeBNTg;0JQG>0Vw+m7O#21zDbmKDp3exqY zmsE!idW+i%3^X#9#EVM%s!nvMq7H}WWq`lix@uK+II`|nR6ZxYW;=8^y4O}zx!byCe|R_s z!Y-~xky&>pJsL-qEv_YOTX*9S&rCCR@^UuWd85>}ck?e@Tm;%u_vB>1^*TN1Juq=a|Fjk@8tfK3Uu?Z~PHzu`EcJ zL)%s&@9~11e`$A;%yz2U@uEt5X>U>6b|`d`QoRV$kHKc;75tJ?FAOq>l5ORYUa^Ax z+^%m<=2UQO0k5V^cxyE5)%+3Fi=wh|6d0tI^km&b_Q)eNey@)AWCQA7K7Cboze(+6 zGrYZgmaBcg&F-Xlr~_etJoXOL5Hd>_}n$}LkL#1eeogP?Yw9M6mwjF_<$pRlVO z_DFGEbx2`*%R~<8Tocf%7aTY6G|LI{-`I^lz06uzTz>~DjkDT3!v@p9u$CutK(X&n zvX`>BH2c=ESl9qX<$13)PLDaxMO3nfRt~7)PNj5&7rC9_YX}{ZoIZyT)`>WGa^UP} z5HRfVbh8UHqH6QgIlt4zNTZ_y_r z@eihhVWUjz)rjx$MQRF+UCnfN*x2i8am21|01bvG8y|^&G#K2kZ8n@X#~SIA(l<}t z)^j62OW4U(qjnzUKDaQ(r(B7%!57fZBiZA}9L4w~Fu#CSJ6}+Ih%8@097h;gAgWxr z>61teyf@E*L}t^H$c4FMGs@}O+ItT4BO`LX(3uN3$d>?kd1AIQ-#L4&>7OkBivvNc#8mL#7hWdJTsR0 zW+58uHb}#eCa(`oxfCY>P36d8gr+cc?|jkKTF(C3 zHzy@YMVC%Zf6#KftcU;7LlS0@FbPSe!b1HeW9v41U}v%0qjxe-7m9oYZ4tSclxmv8 znLdzfA?=0i*lznX6AW6l0C4$P_U!pc*2gVaib172zT28cqsX0JB@ zYBEl-G-Z9w=J-%>MDP~KpG3!|L#@uKPyt>8j5vlugUbGTc&69E{Qc-*PwKdmU61iB zi}Hm)+da718dAkO8cX}THY2}no066*S^!Kf!h}w zfYP}EMoXttxN_lVcHggVUm-7coAbtk{#B2DV$CJVLgBHI3%K(&a!Qx#l^;Zs0k?FX(vnH}&SYOMLq8C|wi=VNzHbGCloA{znQ+=DK=>JL{BJnqL>Sn}yV`F32=>YA$O|C(G)Qdy_wk9U5 z8ti%nutguGioN^=TT|oe7H6yQq<@r~B67|P9}W{ogcpgKTh5(kpOD(fGlUk$3n667 zpZNsSF&@lG9X#dTNt_Jz21_Jq3X6^QX#~vd=Z@$hphjpz1lb}YoOX`1+V4ETTE}pD zV6vd&gse0m7drXf^aNPCY)~9PjRhJGU!s4{G`7YW`HSJhss8{LI2<4<{eblSbtU;s zVdpggnpXa9UUEaMXb|J2R2&1*BpFY};L`lmp0w|kWR3S;4+jl3@B8cFC2~LvHHUI2 zFq)39T2Bg>GAwoV*!3|y2(xEJjwyvMj=gu5M6PuIW^Q)vIl@dccag?7X(D&BYo+<3 zU2#F-ZS;-fgIx;B%`6Khg)45!rb`qZCPk*66%IEsBZoB2C(bK-RH1_@p{R+(eUdiV zRPqjq4g$1%ei4lO3uYIF_=^K?$d+3oQ6F!wg;hB3m}iBx7a5ElbNoDUnV@-q2YCM2 zK*dAPPx_r(48_rv^KPpim>25Gxq~!XonTnAFB<=@rW2Yt`4?#-L^X0nj6!AwH#3JC za-7}7p)#A#ss(DBF)|f^U%7pg^`Ehj3vEr|SKu33O7hN?;7_rT0G@2=i*ds@EF`%l zi|K~~`!SvHyzKRlr!*%ke`{a> zVRt6LkgL+33fMLM?p3iGWtFX&>$)H+-NN=0IXDwE^JB^XxL3X-hOx?%zR}1R*82p5 zXypUXQEi_lRJd|+%t{r19v5`s_`8TE6_Ceuwaq(|$K8nr6|GA-Zs$`={0dX~1+C9jLRQx*&r&R_VHd}}B#I zGLv$dHeIxWQ2;79=B@QXOj#tFC7g7Gpaf^C zUrxV|`%Fa3@9gsZ@_ktAN!KT8+;A?AdY_v}ni>c6Ur%Iih+q_rIdwPM#e@d9J214K zdA#|KctMA*2VY!$|C#{qEzfYu01J$!Kh-kPEucNRbmPm$K?J`3S`gfIkUJ;?SnK^i zlhm+Q{)+~E=jB#@x7+_2Zv4+@<-g3%LtsK=-xdsD@P@$+eK$Td{=OxEX@UaNNUnlI0&l&(X2pB>l1M`9d zI{xM z+>pk0e0Uu*hs$gl2Ypq{Oh>DL`&j!*KYgIPIAW-UP1^PQNVqGvVx&saKu)`i4kHN> zY3i>qc&3h*pQ+)&bph zQ*iamOJvvhtD@N1QJe>u%8i1EfstmMdo`S{@kF&a7R~ny_^Ud{zkaONJKX;10)D2! z3pDQ~_zmU?8IMWr+-yVDb2yZ8@d_;Tqc$}8L8JDa+W;`(u6VySFTJi_DtS! zJ81~Dv@u;4$}u7gR6ym-6rwdmnJ#F~zC2dN7k3T+BO!~ZgWf&~=KZ1x{C87yxf1>8 zW+J)lD={2=*&C|uBn7=l#skcQ3E#)`8+C+#lZXB*g8JD%MFckt0w8q2yb+wrM$oTc z2IlPoe6~A|qo7k2>i0Vnu&~1foM1132!WqAo?6)HpB@A#7}O7J*2lo^n1np}mq1#= zuc}VOb9R>|Yt(m6-~u-N!0?JDUW58Bfef>Fs*(r;DLKXyB}Pq<9}JAFKiB+b*vSHK zi1fit^U0vy6RQG%qWR$y>UY=NGn2}XpvxdKV04{l27TEYz>5Hz?)zpJ*2kd|aV134 zjV_j-6ttt@KUpNojr|yS0npjy3Z#`_V3EgiK~tEj4#$8)bWDL#wYji6YzIfsf}LLz zA2(i0&V5Mg1UNpT<6MeIe5(?Gyk4-C+((P1IGA@OJ5dZxoVNe4zIRO4O&tFTb&!h> zzd}L`1wP66BVmTSI1;z|+m@TvGwhAyBsf73s3{uym7XT$z>i2t5+V9V%XiS^Pl&Oe zuf+`5`h_8nmkmBjvwE#Wy2UlP)>ZU1q|TNbA8r&_Zh%|=#o!n~A%X3XF-Y+DzH9XW zafbuf526I{`XE%wuL>tMuMl8A7j8t{&{HX@G}r9$?3n$y-s-gBV26`GjBoXC<=*SeQZte53v|RxNhK;b9z5r0Kq}w zz|dHJ=R(kT9ozq*Epi!{4y?23p#HH%E{;k^Zwy1m^>zQ@| zC0r-)@#w(EV*+YOM8FeMzNWab~nSHGQV!%#O#61R=M#;c1og+?Ehb?!m^;4Xh%ZNM`7)Y7#P z=*ltz-wqU}087{Fz}p=Gn_AK14@o-p(H!)#kUt5{3Ho}Lc0CmT7CIst?u>9ymBfkn z0^8dP2TUX7X_df4DQ9L&0!47#iGthoDwKbt(3eLLj`U;m2Dz(+z0| z4g+|SR?9V68fdy78cXJvj~%gl0D9YR(`N?X!9Y z+t~&b=5FUJeM%L=1N8@nG4{B1A&(-;24vx40y3k%aVI4t{BEwBWtr!)V)r-3C{6 zRv(5dXc5v15P4;<7~1}BHF#dEW!oc@wv7Hf5nMQlFaopZ1&<|pai73PJ2W#BfqCH| z0^v>u0`+6gHUi0{&z>{8##FW>@S6M3lu&1wCGcoA3vgQg)$82 zEq;?(v;jxe$~jPBr3Gby>us?GW3H80$TTA{sEpMB+~peP&h;pCgvBqwpXX5G@cd<7mRe5rPw^3=sPcDl ziiYu5SfZ#CF1X4N%|{tCSLJcgui$(HrMFncxzhUSYkAVgBx`xm=gy6KfBZ=F#)qW~ zb;^gkH+;&MXQyGxpA)&{EtE%wO3vUULJUgBf}8Ns`!+7xG*nUa{!Fm)sW^p#74c<3 zUnIg=sg(HW_5nm+sj7*AiE;UF^&s=0o%{qZS zf2+ktC&pw|D0u%-X8GhIlXV6Bp^;4uF7L9uFGaH2e?CW^hsxX7AB%UfZmv;YE&4rzefxY-B8I z*=)`)A-k#Xhu*E{h$O%##|)3;^ce)nFW+nthAD5E2$5#6cd@ayM)T(ju0(g+ittBw z+dMSheynznzo1wBDS2VveeZ{y1B#DdTlE>fdTBMJo5jyLtY7w;vr0#ArG22T4rVhL zW2012)Zd^`kv43am$5hOeYI_G%1_L1Z`$e}MbV6<`XjXlTI;s`IZ7_fDFM8XuqP| zimem&5GWE}bfSOIa7Uq`mVjW^g$3Z;-P6Y*A^6~iSTg~BMvp^*RqYPu1I#Ur=s!^7 zZg_C9YvBfj3tiz1@Z^1_g&)^1#GoAD#iiJC=Ol;ha?`rE`Mx{M z;KDcxb6iMVXizxzM0x5u{hp?)kZ;?F-JT8beTg`Id6yo-g&YX=;7g!JDS-&FZ3g)H zB#>S46qA_U2qcQ8B)#g>@}L^GSzS(uYZ$u!g3qg%(~}2hzS4cL+n#L^^eoI=hLyF{+22l(CL7;b0dLpNq zg;YTQW>~^-BDepuOAmBEg-l85Jv5;gRbb3}o#>OuGxr={ou@vy%Ht~kZsV(9QH5b0C} zYeQ_c1d9}YV=P6TQo$q{r6dI%$oZC66Q~Br8Sen+^2guwYc5V?eNnLc&t{BX=eV8mz z?^%^`{%aENXm_p;^Xt@B8?Z5yk33gf{(WM2R>c!hyAq6Eun1AWl{Y+2vaD7PQ9dn* z@4T(ZJ-sS1Hm(g7F+0?JS0w&76xK;b;_cC_3YNMQnFcoxNDPAEP7F`|h;|=PR(`jL zxX>&ubMsv7CKJ>Kngr1TtCsR@)&5Ys*_f#MkH@1oS&c3EQb(AIr(R&VJ&6be(Da6Kw|OS@-jC0GQ&tYo6>; z(k=SAS8sT|DWrL3`kj;b4=}!EN;$UhA$>!-)t zk3-^|_l9~djBfBy@;8TsKQh+2K~Mq3ap}LXcmmFYNg+FwUrIurKM$k>Nib#;il1u8 zdfq`nbR~K=|Ivp_o?xW7TkDgTY|tOp=C21aNNWkr5~)IhyNk~U%@%%-fFmTFZbLWa z>kr#;<-4C-Q)heHnf@DHx?fhFTh+hVeEr;|^A`NtnI;$HD!zTzvYF##JadKP=xc80 zMgO%c9A+Vk=JOM&;wYDf^X)r2pldAg^( zD-g}1ClZ@dj!#t6&hkMHR>YyRxYkS{CwcT>eS35&==}8G!l~Z7bv`b;l07LuYQG|5 zv&f%`26u@*2!@OSeWc6wTyaeJulo0H`MLF2FWcK8>B(o8*6%3j#g^EbBbgQrubP1) z1(z7!F>o^gMdMVpNLMCW>Vg#lD}hv6f976CRK3?96=!|)zBa>4{O zfdi=E!*_4wBT}&quz`mGut|W8!zKaNp~|=h=u#k)gC9I_AOM;d6O;>q9~eZ|xCgSS z|AE61)HfA0$Uz-baRv=G32pT2WglsA)zQb=SHc#Nx0hT~^2bQ?QnVc|!2F(-J E0ACR$bN~PV literal 416094 zcmW)mbx_pb*T+AsASvA?v2-IK-LW8`fQtwSNXODhDvdNOB`KXt!_pz$E$GrIA|=wX zu+R7T{deciz4x3sbI+OgyymT;sV*t?p8HV`aP?FK001xmKmY&+0B`_60ssmC(Er;7 zg8>K_fPn!x7(jvn6c|AN?B{v5(1zg0Q!IT!7u;<17I)!4g-)d00jfk z|9cb+2Ow|&1_$7900{?BZ~*{!&07n8yB!EH!=>LTWqW}mBfS~|53P7R& z6beB9FDEb>fS>^w8i1n#BpN`W0rdYT3IzjD2mplvP&fcZ0#FnHMFUU(3|6o5g&Fen5Dg~6b37!(PEqF_)o z3<|)ZU^o;4hr-}cI2?+ELs4)j8V&`JP%sh-K|*0jC>#kzBB3ZG6pe%eC@2^Og`l7? z6cmnvB2iEj3W`QS0W=hhhC4G3Jpc0p#XpY0|*F!fB^_NfItEW6o5bj z2mp)#gAoug0tQCF!3ZQ6fdV7YU<3d`fFTG71ObB};1C27f0KtGE7zhLdgJ9qg3=)DtK`>|t z27qC}Fbo8Sfx$3v7zPQ$pkNp@3$H3qiI2?n7V^DAm8jb;w7%&n8L1JJ? z3>=9;A~7f=293l3C=3{dfuJxj6b6pMAW;|;3WG*r05k@S#z4>*7#agdV~}VJ3XMUd zF{~IuUA5N+DoU@^L)eP8tofN;jab$}-)1D4=Y5UWs3_-Hrl|Sa z{GzDcWEg(HF?#fS=}eJ&$`+$mW5vrd?L4h`Evi5Im1?!TlVfS+Z_16n={_O!u0$bh z#~t4-L!FoF9X1=}UKk#mAU#*-;$yFzN20hya?!&G>Po|EQ&#nlzV+L~aP}9u+HDQL z#xtHdtxZTZY)$2>#4_u&BmaCaH>fn5Y;QXFS!XrweeYLqX;SUR{_qp=?(cfkCtQp` zj-=c6;3q!wPT979o8tvfU8m4er~9+DFMM*p-g+N?uMWWc4E)-DbGkQO`Eok2>+bSo zeLV4HQ1|`q_1}Z(>7Z|z2jGFrA{d+4-Xa8#x%H{d)DydxR!#h+CN8mRQAW-bmiF1< zjBFB{kxcq~@1s}}>@E4IW6CX~`I7gxqWOoeEn|g0XB5VX??Sc{Bu^!+5)~h~ixZT{ zrHT{PIiq)y)kOWQQ(npQlqBovOO>P;+D8BS0`>5-Nw-Lb5b$Kf^>#CDOEtCloSOTV z-PU{Qa&w+cIoN&mHPk4}^*PP_of~{fx0e@6t+iJW$SGZ3_*pb&uMjRl|EDO~Q0q@g zf~|B#=@*ZfKc)HJ^!sInU$pisa!aKVh=`h-=}M+v%q>Erwpn?|C0cWDIm=ngFx%>z z3*Os0t|`MTfi7K%_tqt}u|@);(tJnAc|)h8CX{XEQS(Z}=c;TXCGc@oqoFE+i>s(c z3|LQ*Tn(%j$Ie{2{cDk_D8VKY#c8q<;96V^W3}Tmh3M^3Tj#Xw=exjWg?v{ce%B6A zYQRJWXooe;y3TYz)(Mt ziN-03yPUHL$rQE&fl{N{@JC-VJV@H`TP$DJtZT91fHN(aqN(G*mKS`n215QD{w`RG zAWdX)crVwFxkIZaSaJ_HKRu_?Qi8Zl%zGL`4EGMTZ?>cw$Vn?nF$%_+uNm`v3f1~E zfy!_UThE@Z^q0A9!p*LkN1)&D{2;;h-GUVP_TQyt3Ag(tje)nx)~V+&xn5Jw1|Pl1 z(4Vc$-jH75HdX~ibeyP*66BHt`LckbaFA2p5u7ZXx_HI$l6s+qP3^B&Gg&b8p|FNJ zd2#s5G6n+3Yz~7di=wV;4LrH$6dy7dbMw7TMDn2zYmI>K;lK=NCYAqHm*_W^0$d@t zV;&2ey8sjgVd<1B zQqay|)3$FpV0_o)JfO|~^D0h7QL5A!F+Gye*NGIi&%S5e?$WNPmQ#lvq)~!rI8Bg` zjGrgxfY{t=yE#gQWv#WtkG%^dA|^#_fF5dfrN{l7M{k_B08;8Ri6b&%flwY2S z`9$65b7cRB2h7qu*3|z*3vN*uu0Hqm$&sDvBjagpo83-2~6C$vdjw8o?D{0hL( zxSEn&v5!`QHA3o3C=p;}$+rZI48qfNuu!VuV*s{(YAB)O4h?Cs8!gXB6P2EI1ih3} zOxKYJK@m4UIca}H1BUr=eS*Lv@<#s*Ft^)BPbVD9(H0ye>*u&OrJcsqShijNB=@O! z7v^-C)m_7@HmYR7n1+CNN6IZ78>@mJ2A$rWTKaUZi`V+JRj!?sUUeNt2>EZnSif0n z={y~D{d5tqes+5G?cvFZ|DB8lKx5Q%yebsBJidVzMD^k(xP_LPbd{}!fz;fTX0dXEm*@uvAnblVW*fX945blk%Q9!X1OScI6 zIN=Hp^>`+^5A!8SVA+0IkAbH+o{HSUHm;2{dsTmLMQvakguh605lxUyPj`uN(GF@=jk}8a`1~;B#}NAPi3eHZ z#G{%&F;y7aQ|zKQIyUr&MR$Z^qa_v|*P{j$){=g%OPW2tQxw}cu-`IeJ<|f%o6i|= z6tPkD?!Nkd6uA5bwNrEvIqW}^G|f0=I7!2EvY!=vdM8yfEdQs$quzx&*SoRh z(~*l^$IA0Te51vFq8F`98j3-%#M76SQbBN#cda&Sz9804Dr2JpH2zNnGy)whBg_6CBSW`YU!J^Wbn0wOZX9%`YFU(Y#lm;3R&)R3xFr6mL#HNK ze34RNaVqdf^C!Y(lO`@K-@7G?u%d$QzvKE1y{>>csWfZNJ;zlwdym6Mxk*s!M%d7Z zAERgatyc&yN^WMGz*dDgrrx%@{)1Am+}yLr)uf7SG#(Sf5{ykaIl=@x8*=(R>N$$G z>OY9{#Y2H#)~thG0oDqy?Kok{wv)5kcAMA^@2VSQJaNeWvX&l(2gQ`G^BpQRp#CJ|`oW zu)-7pBkEFQTLhZII8g;SQ#)?~MO$h%M(2F&DOLGqQHY(DLd&3@w>6)gr$m>Ei<;_N zl!Qj&dqR&Q*`f%xFm45XQdXj0+A9W+AuKqts;sSgag>FwBffECd#dBD?*S?9jki(C%O+#I3RN4!AQ}@HTXV> zeUMAQUX(y3X@iw1`&1~=J?ZHv4+T%MScHLUTCx)KwF<{;Ui=h+(PTb{*UubM#4$I? zf^;b|ekszLDWaJvviPZ-p0rNfWGu6!-6sm&n