From 4cf251eaac9c440fcbe3286ae20d56d254d815f6 Mon Sep 17 00:00:00 2001 From: Tomohito ANDO Date: Fri, 25 Aug 2023 11:17:45 +0900 Subject: [PATCH 01/15] fix(traffic_light_multi_camera_fusion): assign multiple regulatory element id for one traffic light (#4727) Signed-off-by: Tomohito Ando --- .../traffic_light_multi_camera_fusion/node.hpp | 2 +- .../src/node.cpp | 16 ++++++++++------ 2 files changed, 11 insertions(+), 7 deletions(-) diff --git a/perception/traffic_light_multi_camera_fusion/include/traffic_light_multi_camera_fusion/node.hpp b/perception/traffic_light_multi_camera_fusion/include/traffic_light_multi_camera_fusion/node.hpp index 4cd5569129a00..bdfd07ae54b28 100644 --- a/perception/traffic_light_multi_camera_fusion/include/traffic_light_multi_camera_fusion/node.hpp +++ b/perception/traffic_light_multi_camera_fusion/include/traffic_light_multi_camera_fusion/node.hpp @@ -113,7 +113,7 @@ class MultiCameraFusion : public rclcpp::Node /* the mapping from traffic light id (instance id) to regulatory element id (group id) */ - std::map traffic_light_id_to_regulatory_ele_id_; + std::map> traffic_light_id_to_regulatory_ele_id_; /* save record arrays by increasing timestamp order. use multiset in case there are multiple cameras publishing images at exactly the same time diff --git a/perception/traffic_light_multi_camera_fusion/src/node.cpp b/perception/traffic_light_multi_camera_fusion/src/node.cpp index 387b3ef1f6758..6c29be9858a9a 100644 --- a/perception/traffic_light_multi_camera_fusion/src/node.cpp +++ b/perception/traffic_light_multi_camera_fusion/src/node.cpp @@ -216,7 +216,7 @@ void MultiCameraFusion::mapCallback( auto lights = tl->trafficLights(); for (const auto & light : lights) { - traffic_light_id_to_regulatory_ele_id_[light.id()] = tl->id(); + traffic_light_id_to_regulatory_ele_id_[light.id()].emplace_back(tl->id()); } } } @@ -302,11 +302,15 @@ void MultiCameraFusion::groupFusion( if (traffic_light_id_to_regulatory_ele_id_.count(roi_id) == 0) { RCLCPP_WARN_STREAM( get_logger(), "Found Traffic Light Id = " << roi_id << " which is not defined in Map"); - } else { - /* - keep the best record for every regulatory element id - */ - IdType reg_ele_id = traffic_light_id_to_regulatory_ele_id_[p.second.roi.traffic_light_id]; + continue; + } + + /* + keep the best record for every regulatory element id + */ + const auto reg_ele_id_vec = + traffic_light_id_to_regulatory_ele_id_[p.second.roi.traffic_light_id]; + for (const auto & reg_ele_id : reg_ele_id_vec) { if ( grouped_record_map.count(reg_ele_id) == 0 || ::compareRecord(p.second, grouped_record_map[reg_ele_id]) >= 0) { From 5b5b416226a0a2ac982c5c33fd691372c7df8bc5 Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Fri, 25 Aug 2023 11:51:05 +0900 Subject: [PATCH 02/15] chore: do not display steer and velocity value when message is not subscribed yet (#4739) * chore: do not display steer and velocity value when message is not subscribed yet Signed-off-by: tomoya.kimura * chore: change msgs Signed-off-by: tomoya.kimura --------- Signed-off-by: tomoya.kimura --- .../tier4_vehicle_rviz_plugin/src/tools/console_meter.cpp | 6 +++++- .../tier4_vehicle_rviz_plugin/src/tools/steering_angle.cpp | 6 +++++- 2 files changed, 10 insertions(+), 2 deletions(-) diff --git a/common/tier4_vehicle_rviz_plugin/src/tools/console_meter.cpp b/common/tier4_vehicle_rviz_plugin/src/tools/console_meter.cpp index f13e971b4d6d6..5d3684d0351c6 100644 --- a/common/tier4_vehicle_rviz_plugin/src/tools/console_meter.cpp +++ b/common/tier4_vehicle_rviz_plugin/src/tools/console_meter.cpp @@ -150,7 +150,11 @@ void ConsoleMeterDisplay::update(float wall_dt, float ros_dt) font.setBold(true); painter.setFont(font); std::ostringstream velocity_ss; - velocity_ss << std::fixed << std::setprecision(2) << linear_x * 3.6 << "km/h"; + if (last_msg_ptr_) { + velocity_ss << std::fixed << std::setprecision(2) << linear_x * 3.6 << "km/h"; + } else { + velocity_ss << "Not received"; + } painter.drawText( 0, std::min(property_value_height_offset_->getInt(), h - 1), w, std::max(h - property_value_height_offset_->getInt(), 1), Qt::AlignCenter | Qt::AlignVCenter, diff --git a/common/tier4_vehicle_rviz_plugin/src/tools/steering_angle.cpp b/common/tier4_vehicle_rviz_plugin/src/tools/steering_angle.cpp index 18977367afbce..60a81e45c9c29 100644 --- a/common/tier4_vehicle_rviz_plugin/src/tools/steering_angle.cpp +++ b/common/tier4_vehicle_rviz_plugin/src/tools/steering_angle.cpp @@ -153,7 +153,11 @@ void SteeringAngleDisplay::update(float wall_dt, float ros_dt) font.setBold(true); painter.setFont(font); std::ostringstream steering_angle_ss; - steering_angle_ss << std::fixed << std::setprecision(1) << steering * 180.0 / M_PI << "deg"; + if (last_msg_ptr_) { + steering_angle_ss << std::fixed << std::setprecision(1) << steering * 180.0 / M_PI << "deg"; + } else { + steering_angle_ss << "Not received"; + } painter.drawText( 0, std::min(property_value_height_offset_->getInt(), h - 1), w, std::max(h - property_value_height_offset_->getInt(), 1), Qt::AlignCenter | Qt::AlignVCenter, From 59a5e29846cc1e7674eab21786b5d919aa7d4174 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 25 Aug 2023 13:14:40 +0900 Subject: [PATCH 03/15] chore(autoware_auto_perception_rviz_plugin): higher visibility of predicted path color (#4737) * chore(autoware_auto_perception_rviz_plugin): higher visibility of predicted path color Signed-off-by: Takayuki Murooka * change alpha Signed-off-by: Takayuki Murooka * update Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../object_polygon_display_base.hpp | 30 +++++++++---------- .../object_polygon_detail.cpp | 8 ++--- 2 files changed, 18 insertions(+), 20 deletions(-) diff --git a/common/autoware_auto_perception_rviz_plugin/include/object_detection/object_polygon_display_base.hpp b/common/autoware_auto_perception_rviz_plugin/include/object_detection/object_polygon_display_base.hpp index 48f7d18ce67a5..b20a835f80e39 100644 --- a/common/autoware_auto_perception_rviz_plugin/include/object_detection/object_polygon_display_base.hpp +++ b/common/autoware_auto_perception_rviz_plugin/include/object_detection/object_polygon_display_base.hpp @@ -346,9 +346,13 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC ObjectPolygonDisplayBase { std_msgs::msg::ColorRGBA sample_color; sample_color.r = 1.0; - sample_color.g = 0.0; - sample_color.b = 1.0; - colors.push_back(sample_color); // magenta + sample_color.g = 0.65; + sample_color.b = 0.0; + colors.push_back(sample_color); // orange + sample_color.r = 1.0; + sample_color.g = 1.0; + sample_color.b = 0.0; + colors.push_back(sample_color); // yellow sample_color.r = 0.69; sample_color.g = 1.0; sample_color.b = 0.18; @@ -361,22 +365,18 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC ObjectPolygonDisplayBase sample_color.g = 1.0; sample_color.b = 0.0; colors.push_back(sample_color); // chartreuse green - sample_color.r = 0.12; - sample_color.g = 0.56; - sample_color.b = 1.0; - colors.push_back(sample_color); // dodger blue sample_color.r = 0.0; sample_color.g = 1.0; sample_color.b = 1.0; colors.push_back(sample_color); // cyan - sample_color.r = 0.54; - sample_color.g = 0.168; - sample_color.b = 0.886; - colors.push_back(sample_color); // blueviolet - sample_color.r = 0.0; - sample_color.g = 1.0; - sample_color.b = 0.5; - colors.push_back(sample_color); // spring green + sample_color.r = 0.53; + sample_color.g = 0.81; + sample_color.b = 0.98; + colors.push_back(sample_color); // light skyblue + sample_color.r = 1.0; + sample_color.g = 0.41; + sample_color.b = 0.71; + colors.push_back(sample_color); // hot pink } double get_line_width() { return m_line_width_property.getFloat(); } diff --git a/common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp b/common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp index 73a524e130776..894e377a6f851 100644 --- a/common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp +++ b/common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp @@ -64,8 +64,7 @@ visualization_msgs::msg::Marker::SharedPtr get_path_confidence_marker_ptr( marker_ptr->color = path_confidence_color; marker_ptr->pose.position = predicted_path.path.back().position; marker_ptr->text = std::to_string(predicted_path.confidence); - marker_ptr->color.a = std::max( - static_cast(std::min(static_cast(predicted_path.confidence), 0.999)), 0.5); + marker_ptr->color.a = 0.5; return marker_ptr; } @@ -81,9 +80,8 @@ visualization_msgs::msg::Marker::SharedPtr get_predicted_path_marker_ptr( marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.2); marker_ptr->pose = initPose(); marker_ptr->color = predicted_path_color; - marker_ptr->color.a = std::max( - static_cast(std::min(static_cast(predicted_path.confidence), 0.999)), 0.5); - marker_ptr->scale.x = 0.03 * marker_ptr->color.a; + marker_ptr->color.a = 0.6; + marker_ptr->scale.x = 0.015; calc_path_line_list(predicted_path, marker_ptr->points, is_simple); for (size_t k = 0; k < marker_ptr->points.size(); ++k) { marker_ptr->points.at(k).z -= shape.dimensions.z / 2.0; From 6af6876fa550f372f79b9b91ac026132a6637ffb Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Fri, 25 Aug 2023 13:24:16 +0900 Subject: [PATCH 04/15] feat(motion_velocity_smoother.launch): add glog component (#4746) * use node instead of include Signed-off-by: Takamasa Horibe * use container & add glog component Signed-off-by: Takamasa Horibe --------- Signed-off-by: Takamasa Horibe --- .../scenario_planning.launch.xml | 28 +++++++++++++------ 1 file changed, 19 insertions(+), 9 deletions(-) diff --git a/launch/tier4_planning_launch/launch/scenario_planning/scenario_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/scenario_planning.launch.xml index 665bd82423ea6..b293c5836817d 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/scenario_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/scenario_planning.launch.xml @@ -24,15 +24,25 @@ - - - - - - - - - + + + + + + + + + + + + + + + + + + + From 72a4e29bb74cadae89e10246a8e2a9b927088db8 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Fri, 25 Aug 2023 13:25:39 +0900 Subject: [PATCH 05/15] feat(mission_planning.launch): add glog in mission planner (#4745) Signed-off-by: Takamasa Horibe --- .../mission_planning.launch.xml | 17 ++++++++++++++--- 1 file changed, 14 insertions(+), 3 deletions(-) diff --git a/launch/tier4_planning_launch/launch/mission_planning/mission_planning.launch.xml b/launch/tier4_planning_launch/launch/mission_planning/mission_planning.launch.xml index c1ace97b9788f..ec7545956e774 100644 --- a/launch/tier4_planning_launch/launch/mission_planning/mission_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/mission_planning/mission_planning.launch.xml @@ -1,7 +1,18 @@ - - - + + + + + + + + + + + + + + From c5a6f8094b5a7a5e19f4a7d8b9bd252a5a5371cd Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 25 Aug 2023 14:21:31 +0900 Subject: [PATCH 06/15] fix(crosswalk): guard invalid sharp angle stop point (#4750) fix(crosswalk): guard invalid stop point Signed-off-by: satoshi-ota --- .../behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index 64410c08a6f80..0edfa6167e999 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -1034,6 +1034,9 @@ void CrosswalkModule::setDistanceToStop( void CrosswalkModule::planGo( PathWithLaneId & ego_path, const std::optional & stop_factor) const { + if (!stop_factor.has_value()) { + return; + } // Plan slow down const auto target_velocity = calcTargetVelocity(stop_factor->stop_pose.position, ego_path); insertDecelPointWithDebugInfo( From 2a9fdb798873bb62f0c6b0889c0410e5e2d071ee Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Fri, 25 Aug 2023 16:30:45 +0900 Subject: [PATCH 07/15] fix(map_projection_loader): fix readme (#4753) Signed-off-by: kminoda --- map/map_projection_loader/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/map/map_projection_loader/README.md b/map/map_projection_loader/README.md index 63095a72e835e..e31db7890cf47 100644 --- a/map/map_projection_loader/README.md +++ b/map/map_projection_loader/README.md @@ -25,7 +25,7 @@ sample-map-rosbag ```yaml # map_projector_info.yaml -type: "Local" +type: "local" ``` ### Using MGRS From 343d718977d55a15e0bfe163532f625d28e996d2 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 25 Aug 2023 18:52:47 +0900 Subject: [PATCH 08/15] chore(behavior_path_planner): use RCLCPP_DEBUG for some frequent RCLCPP_WARN (#4757) Signed-off-by: Takayuki Murooka --- .../src/scene_module/avoidance/avoidance_module.cpp | 4 ++-- .../src/utils/path_shifter/path_shifter.cpp | 2 +- 2 files changed, 3 insertions(+), 3 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 70999f1504fee..ff5706c34bdc7 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 @@ -461,7 +461,7 @@ void AvoidanceModule::fillEgoStatus( if (isOutputPathLocked()) { data.safe_new_sl.clear(); data.candidate_path = helper_.getPreviousSplineShiftPath(); - RCLCPP_WARN_THROTTLE( + RCLCPP_DEBUG_THROTTLE( getLogger(), *clock_, 500, "this module is locked now. keep current path."); return; } @@ -2455,7 +2455,7 @@ bool AvoidanceModule::isValidShiftLine( constexpr double THRESHOLD = 0.1; const auto offset = std::abs(new_shift_length - helper_.getEgoShift()); if (offset > THRESHOLD) { - RCLCPP_WARN_THROTTLE( + RCLCPP_DEBUG_THROTTLE( getLogger(), *clock_, 1000, "new shift line is invalid. [HUGE OFFSET (%.2f)]", offset); return false; } diff --git a/planning/behavior_path_planner/src/utils/path_shifter/path_shifter.cpp b/planning/behavior_path_planner/src/utils/path_shifter/path_shifter.cpp index 653efff7058d2..9ca083af35c92 100644 --- a/planning/behavior_path_planner/src/utils/path_shifter/path_shifter.cpp +++ b/planning/behavior_path_planner/src/utils/path_shifter/path_shifter.cpp @@ -321,7 +321,7 @@ std::pair, std::vector> PathShifter::calcBaseLengths if (lateral_a_max < lateral_acc_limit_) { // no need to consider acceleration limit - RCLCPP_WARN_THROTTLE( + RCLCPP_DEBUG_THROTTLE( logger_, clock_, 3000, "No need to consider lateral acc limit. max: %f, limit: %f", lateral_a_max, lateral_acc_limit_); return getBaseLengthsWithoutAccelLimit(S, shift_length, v0, a, T, offset_back); From 4361c8f699e77a7e8319fd20d3dfaf93ea52bf69 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Fri, 25 Aug 2023 21:43:08 +0900 Subject: [PATCH 09/15] feat(behavior_path_planner): visualize ego predicted path (#4743) visualize ego predicted path Signed-off-by: kyoichi-sugahara --- .../marker_utils/utils.hpp | 4 ++ .../path_safety_checker/safety_check.hpp | 3 + .../src/marker_utils/utils.cpp | 55 +++++++++++++++++++ .../path_safety_checker/safety_check.cpp | 13 +++++ 4 files changed, 75 insertions(+) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/marker_utils/utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/marker_utils/utils.hpp index b3cb53ec18349..0fc10109240f9 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/marker_utils/utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/marker_utils/utils.hpp @@ -131,6 +131,10 @@ MarkerArray createObjectsMarkerArray( MarkerArray createDrivableLanesMarkerArray( const std::vector & drivable_lanes, std::string && ns); +MarkerArray createPredictedPathMarkerArray( + const PredictedPath & ego_predicted_path, const vehicle_info_util::VehicleInfo & vehicle_info, + std::string && ns, const int32_t & id, const float & r, const float & g, const float & b); + } // namespace marker_utils #endif // BEHAVIOR_PATH_PLANNER__MARKER_UTILS__UTILS_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/safety_check.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/safety_check.hpp index 6d9df7677ead5..f9903b24f42cb 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/safety_check.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/safety_check.hpp @@ -63,6 +63,9 @@ Polygon2d createExtendedPolygon( const Pose & obj_pose, const Shape & shape, const double lon_length, const double lat_margin, CollisionCheckDebug & debug); +PredictedPath convertToPredictedPath( + const std::vector & path, const double time_resolution); + double calcRssDistance( const double front_object_velocity, const double rear_object_velocity, const RSSparams & rss_params); diff --git a/planning/behavior_path_planner/src/marker_utils/utils.cpp b/planning/behavior_path_planner/src/marker_utils/utils.cpp index d8c87b6d1b291..40163f4f93d8a 100644 --- a/planning/behavior_path_planner/src/marker_utils/utils.cpp +++ b/planning/behavior_path_planner/src/marker_utils/utils.cpp @@ -408,4 +408,59 @@ MarkerArray createDrivableLanesMarkerArray( return msg; } +MarkerArray createPredictedPathMarkerArray( + const PredictedPath & predicted_path, const vehicle_info_util::VehicleInfo & vehicle_info, + std::string && ns, const int32_t & id, const float & r, const float & g, const float & b) +{ + if (predicted_path.path.empty()) { + return MarkerArray{}; + } + + const auto current_time = rclcpp::Clock{RCL_ROS_TIME}.now(); + MarkerArray msg; + + const auto & path = predicted_path.path; + + Marker marker = createDefaultMarker( + "map", current_time, ns, id, Marker::LINE_STRIP, createMarkerScale(0.1, 0.1, 0.1), + + createMarkerColor(r, g, b, 0.999)); + marker.lifetime = rclcpp::Duration::from_seconds(1.5); + + MarkerArray marker_array; + for (size_t i = 0; i < path.size(); ++i) { + marker.id = i + id; + marker.points.clear(); + + const auto & predicted_path_pose = path.at(i); + const double half_width = vehicle_info.vehicle_width_m / 2.0; + const double base_to_front = vehicle_info.vehicle_length_m - vehicle_info.rear_overhang_m; + const double base_to_rear = vehicle_info.rear_overhang_m; + + marker.points.push_back( + tier4_autoware_utils::calcOffsetPose(predicted_path_pose, base_to_front, -half_width, 0.0) + .position); + marker.points.push_back( + tier4_autoware_utils::calcOffsetPose(predicted_path_pose, base_to_front, half_width, 0.0) + .position); + marker.points.push_back( + tier4_autoware_utils::calcOffsetPose(predicted_path_pose, -base_to_rear, half_width, 0.0) + .position); + marker.points.push_back( + tier4_autoware_utils::calcOffsetPose(predicted_path_pose, -base_to_rear, -half_width, 0.0) + .position); + marker.points.push_back(marker.points.front()); + + marker_array.markers.push_back(marker); + } + return marker_array; + + marker.points.reserve(path.size()); + for (const auto & point : path) { + marker.points.push_back(point.position); + } + msg.markers.push_back(marker); + return msg; +} + } // namespace marker_utils diff --git a/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp b/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp index c6a68e108e7e1..7f3fe46c6b8ec 100644 --- a/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp +++ b/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp @@ -133,6 +133,19 @@ Polygon2d createExtendedPolygon( : tier4_autoware_utils::inverseClockwise(polygon); } +PredictedPath convertToPredictedPath( + const std::vector & path, const double time_resolution) +{ + PredictedPath predicted_path; + predicted_path.time_step = rclcpp::Duration::from_seconds(time_resolution); + predicted_path.path.resize(path.size()); + + for (size_t i = 0; i < path.size(); ++i) { + predicted_path.path.at(i) = path.at(i).pose; + } + return predicted_path; +} + double calcRssDistance( const double front_object_velocity, const double rear_object_velocity, const RSSparams & rss_params) From 692684f17158b8b4105618032de2006729303bf2 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 25 Aug 2023 22:56:39 +0900 Subject: [PATCH 10/15] chore(obstacle_cruise_planner): add maintainers (#4724) Signed-off-by: Takayuki Murooka --- planning/obstacle_cruise_planner/package.xml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/planning/obstacle_cruise_planner/package.xml b/planning/obstacle_cruise_planner/package.xml index 6cfbf9225dd7e..f482be8ebafe7 100644 --- a/planning/obstacle_cruise_planner/package.xml +++ b/planning/obstacle_cruise_planner/package.xml @@ -6,6 +6,8 @@ Takayuki Murooka Yutaka Shimizu + Kosuke Takeuchi + Satoshi Ota Apache License 2.0 From bbb69c6efb5a7a8561ac4cdf8368154917291619 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 25 Aug 2023 23:01:21 +0900 Subject: [PATCH 11/15] feat(obstacle_cruise_planner): add a option to suppress feasible stop check (#4723) * feat(obstacle_cruise_planner): add a option to suppress feasible stop check Signed-off-by: Takayuki Murooka * update config Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../config/obstacle_cruise_planner.param.yaml | 1 + .../include/obstacle_cruise_planner/node.hpp | 1 + .../planner_interface.hpp | 4 +- planning/obstacle_cruise_planner/src/node.cpp | 8 +++- .../src/planner_interface.cpp | 39 +++++++++++-------- 5 files changed, 33 insertions(+), 20 deletions(-) diff --git a/planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml b/planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml index e2012fab43ba4..08ebea4284bf1 100644 --- a/planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml +++ b/planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml @@ -20,6 +20,7 @@ nearest_dist_deviation_threshold: 3.0 # [m] for finding nearest index nearest_yaw_deviation_threshold: 1.57 # [rad] for finding nearest index min_behavior_stop_margin: 3.0 # [m] + suppress_sudden_obstacle_stop: false stop_obstacle_type: unknown: true diff --git a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp index 260a4c6400588..ac6684d163aea 100644 --- a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp +++ b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp @@ -100,6 +100,7 @@ class ObstacleCruisePlannerNode : public rclcpp::Node bool enable_debug_info_; bool enable_calculation_time_info_; double min_behavior_stop_margin_; + bool suppress_sudden_obstacle_stop_; std::vector stop_obstacle_types_; std::vector inside_cruise_obstacle_types_; diff --git a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/planner_interface.hpp b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/planner_interface.hpp index 9be6ec10e952e..c3fa364da269e 100644 --- a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/planner_interface.hpp +++ b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/planner_interface.hpp @@ -53,11 +53,12 @@ class PlannerInterface void setParam( const bool enable_debug_info, const bool enable_calculation_time_info, - const double min_behavior_stop_margin) + const double min_behavior_stop_margin, const bool suppress_sudden_obstacle_stop) { enable_debug_info_ = enable_debug_info; enable_calculation_time_info_ = enable_calculation_time_info; min_behavior_stop_margin_ = min_behavior_stop_margin; + suppress_sudden_obstacle_stop_ = suppress_sudden_obstacle_stop; } std::vector generateStopTrajectory( @@ -101,6 +102,7 @@ class PlannerInterface bool enable_calculation_time_info_{false}; LongitudinalInfo longitudinal_info_; double min_behavior_stop_margin_; + bool suppress_sudden_obstacle_stop_; // stop watch tier4_autoware_utils::StopWatch< diff --git a/planning/obstacle_cruise_planner/src/node.cpp b/planning/obstacle_cruise_planner/src/node.cpp index 70c0c687b2514..266e184a06a08 100644 --- a/planning/obstacle_cruise_planner/src/node.cpp +++ b/planning/obstacle_cruise_planner/src/node.cpp @@ -397,8 +397,11 @@ ObstacleCruisePlannerNode::ObstacleCruisePlannerNode(const rclcpp::NodeOptions & } min_behavior_stop_margin_ = declare_parameter("common.min_behavior_stop_margin"); + suppress_sudden_obstacle_stop_ = + declare_parameter("common.suppress_sudden_obstacle_stop"); planner_ptr_->setParam( - enable_debug_info_, enable_calculation_time_info_, min_behavior_stop_margin_); + enable_debug_info_, enable_calculation_time_info_, min_behavior_stop_margin_, + suppress_sudden_obstacle_stop_); } { // stop/cruise/slow down obstacle type @@ -436,7 +439,8 @@ rcl_interfaces::msg::SetParametersResult ObstacleCruisePlannerNode::onParam( tier4_autoware_utils::updateParam( parameters, "common.enable_calculation_time_info", enable_calculation_time_info_); planner_ptr_->setParam( - enable_debug_info_, enable_calculation_time_info_, min_behavior_stop_margin_); + enable_debug_info_, enable_calculation_time_info_, min_behavior_stop_margin_, + suppress_sudden_obstacle_stop_); tier4_autoware_utils::updateParam( parameters, "common.enable_slow_down_planning", enable_slow_down_planning_); diff --git a/planning/obstacle_cruise_planner/src/planner_interface.cpp b/planning/obstacle_cruise_planner/src/planner_interface.cpp index 4cf6bf9e23806..03cae6e6f9d88 100644 --- a/planning/obstacle_cruise_planner/src/planner_interface.cpp +++ b/planning/obstacle_cruise_planner/src/planner_interface.cpp @@ -300,26 +300,31 @@ std::vector PlannerInterface::generateStopTrajectory( return longitudinal_info_.safe_distance_margin; }(); - // Calculate feasible stop margin (Check the feasibility) - const double feasible_stop_dist = calcMinimumDistanceToStop( - planner_data.ego_vel, longitudinal_info_.limit_max_accel, - longitudinal_info_.limit_min_accel) + - dist_to_ego; - const double closest_obstacle_stop_dist = - closest_obstacle_dist - margin_from_obstacle - abs_ego_offset; - - bool will_collide_with_obstacle = false; - double feasible_margin_from_obstacle = margin_from_obstacle; - if (closest_obstacle_stop_dist < feasible_stop_dist) { - feasible_margin_from_obstacle = - margin_from_obstacle - (feasible_stop_dist - closest_obstacle_stop_dist); - will_collide_with_obstacle = true; - } + const auto [stop_margin_from_obstacle, will_collide_with_obstacle] = [&]() { + // Check feasibility to stop + if (suppress_sudden_obstacle_stop_) { + const double closest_obstacle_stop_dist = + closest_obstacle_dist - margin_from_obstacle - abs_ego_offset; + + // Calculate feasible stop margin (Check the feasibility) + const double feasible_stop_dist = calcMinimumDistanceToStop( + planner_data.ego_vel, longitudinal_info_.limit_max_accel, + longitudinal_info_.limit_min_accel) + + dist_to_ego; + + if (closest_obstacle_stop_dist < feasible_stop_dist) { + const auto feasible_margin_from_obstacle = + margin_from_obstacle - (feasible_stop_dist - closest_obstacle_stop_dist); + return std::make_pair(feasible_margin_from_obstacle, true); + } + } + return std::make_pair(margin_from_obstacle, false); + }(); // Generate Output Trajectory const double zero_vel_dist = [&]() { const double current_zero_vel_dist = - std::max(0.0, closest_obstacle_dist - abs_ego_offset - feasible_margin_from_obstacle); + std::max(0.0, closest_obstacle_dist - abs_ego_offset - stop_margin_from_obstacle); // Hold previous stop distance if necessary if ( @@ -378,7 +383,7 @@ std::vector PlannerInterface::generateStopTrajectory( StopPlanningDebugInfo::TYPE::STOP_CURRENT_OBSTACLE_VELOCITY, closest_stop_obstacle->velocity); stop_planning_debug_info_.set( - StopPlanningDebugInfo::TYPE::STOP_TARGET_OBSTACLE_DISTANCE, feasible_margin_from_obstacle); + StopPlanningDebugInfo::TYPE::STOP_TARGET_OBSTACLE_DISTANCE, stop_margin_from_obstacle); stop_planning_debug_info_.set(StopPlanningDebugInfo::TYPE::STOP_TARGET_VELOCITY, 0.0); stop_planning_debug_info_.set(StopPlanningDebugInfo::TYPE::STOP_TARGET_ACCELERATION, 0.0); From 4550e7acc799ac29884d4239d465868672983de5 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 25 Aug 2023 23:03:19 +0900 Subject: [PATCH 12/15] feat(crosswalk): add debug publisher of collision info (#4670) * feat(crosswalk): add debug publisher of collision info Signed-off-by: Takayuki Murooka * add plotter Signed-off-by: Takayuki Murooka * update doc Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../CMakeLists.txt | 5 + .../README.md | 10 + .../docs/time_to_collision_plot.png | Bin 0 -> 152214 bytes .../util.hpp | 3 +- .../package.xml | 1 + .../scripts/time_to_collision_plotter.py | 212 ++++++++++++++++++ .../src/debug.cpp | 6 +- .../src/manager.cpp | 2 +- .../src/scene_crosswalk.cpp | 30 ++- .../src/scene_crosswalk.hpp | 5 +- 10 files changed, 266 insertions(+), 8 deletions(-) create mode 100644 planning/behavior_velocity_crosswalk_module/docs/time_to_collision_plot.png create mode 100755 planning/behavior_velocity_crosswalk_module/scripts/time_to_collision_plotter.py diff --git a/planning/behavior_velocity_crosswalk_module/CMakeLists.txt b/planning/behavior_velocity_crosswalk_module/CMakeLists.txt index 118931780a92c..3217b3828b8d7 100644 --- a/planning/behavior_velocity_crosswalk_module/CMakeLists.txt +++ b/planning/behavior_velocity_crosswalk_module/CMakeLists.txt @@ -13,3 +13,8 @@ ament_auto_add_library(${PROJECT_NAME} SHARED ) ament_auto_package(INSTALL_TO_SHARE config) + +install(PROGRAMS + scripts/time_to_collision_plotter.py + DESTINATION lib/${PROJECT_NAME} +) diff --git a/planning/behavior_velocity_crosswalk_module/README.md b/planning/behavior_velocity_crosswalk_module/README.md index f85c472c6d856..5f82fe839fda6 100644 --- a/planning/behavior_velocity_crosswalk_module/README.md +++ b/planning/behavior_velocity_crosswalk_module/README.md @@ -218,6 +218,16 @@ When multiple crosswalks are nearby (such as intersection), this module may make ### Known Issues +### Debugging + +By `ros2 run behavior_velocity_crosswalk_module time_to_collision_plotter.py`, you can visualize the following figure of the ego and pedestrian's time to collision. +The label of each plot is `-`. + +
+ ![limitation](docs/time_to_collision_plot.png){width=1000} +
Plot of time to collision
+
+ ### References/External links [1] 佐藤 みなみ, 早坂 祥一, 清水 政行, 村野 隆彦, 横断歩行者に対するドライバのリスク回避行動のモデル化, 自動車技術会論文集, 2013, 44 巻, 3 号, p. 931-936. diff --git a/planning/behavior_velocity_crosswalk_module/docs/time_to_collision_plot.png b/planning/behavior_velocity_crosswalk_module/docs/time_to_collision_plot.png new file mode 100644 index 0000000000000000000000000000000000000000..71ce642f382bc25a1975f54485cb262f0a7e30e9 GIT binary patch literal 152214 zcmX_o1zgnK^Yzl*-3`(uEg+qObazNMh;%p7T~Z22OCt?ZA}vU#bcuAmcYWU9pU;Y0 z-`yK?XU?26L-cDEISf=%R0srup&&1<4uQa5Lm+TQ$cW$>6z*OH@E^Rpq=F_g`0+!w zi~^5IJY;k|G@PwH-kP~tLEbnyJ6f^3Tew+SIl0?7dz`>^iGerq+G^^0NV!>=dDuET zQES>dT7f4a5FRcb-tE=~F2UcqQ9N9~GfJtspa0GZdCs#P6~V>7^C>yC;hh%*LJd)n zmeBOhJ1_AQUvK&jE;c3#rR*{!vBRY29r#mIQ$JK!V|sde z+GR*#!xu86qN1+3wZ7KXjVhK)C~9gVjE|4E%aFmA#!XF6FRH9W*V57|tFBhrpGQC= zgh0~S^k{8gng1}*(?e-r&Y#$nzr6Qqr$|dnE6S%^7g}->(5^NlITJf<)NOTRSaNDE zJCK&zpJPe8ipRcO8aiu<-i`7%A+xHCrhXpWw@%$Ehi!|P;>*X!M}LJJLhX%@kN@H8 zS8|RFw8q9p-3}iUu_u2!S7r(*cxut81(uX>DMl9;7qp-85*CjlmYot zF5N{*#MW?AJ#I3lM#57`cvv**ue%7=+Rt$`D$yWI(&nl#Iq;J;IsB3Y(Y|*!D9P7FPxKa!Up5&VBv)Ed$lI9q@kuBo zg2_^uKk`yDL88BoY6$y%j3e!{?jZ~lv_&a_?N6F9O2Bw2zmFq*OY4Q0flHrkX%WJs zCsdNItk^)HRe@iyGUW>yTh}1vuG%NznUTP**l-bqKrb#qQ9hpJ!2koHZNSK&zNOU9 z5bveWc`X^ESJ^}Pg)k~DKjvzF8YjE&6I=O<@zgcCDOCQq3D7H%pj*59`E=)ikDq_a zPc&p#YPZmnSG(<5+U+d9wQ?Ct(grIltCC`n9YV6-AE}T8>NXMqCvvajrE)J4cnNvP zuqgOmmfjnm)CIbzPB^9dQkJ$YLaW1j$zcY5|FZBK-@}D7Lh{o$*fB}m`iiWKF*9hg zQP)vPUC>nsX1MxlT(eM$4WC5&Zz%S){l@R!360IsAxqBOvol0Dxb!+T$10xKmNN)V zYHQZ@#cWi~Pc z5uSy)OkO&@`itQ~;{r>~+1|h5 zdW1v2akxkhrk_Z3SdpqqsYtqcl82^Gnv#mqdD*GCdfFGgZZS0aT7I%xB_v^jLi;lT zW+Ys@*O7WVeh9VtKkMB?hE6(JX7BRVU9DLy7FqhAch`SV<&AG`8XePCW3nA`s!tye zx%bspWF^sJUq|gGuF-i6wzzIS1A`Zi1g40+hY0A+(><`!8ri2{4r2xv3xI`$KwX`1#J@qn;`tH~ z5ZE|4&_h3F>RF!o7c4SH1s~4juZmv$1{I5v+Yz&AaUSd9NP9oC$xyQUm?+f!IfoL9 zh(i*|BKu$>`+^h1A9at^kwdUihQW-cfgr&0oLhU{bSpva(_b zav`C~H6T)2vh5JfNZQ>r)6~%^E-QQHAmY+idKGj!mpwrUj;jZ7$K5~jL}occsgaYQ z)08|x#`FEGQzPr>ShZk<17D~yBY&a*V{(kLtyRP<#%vwW9Gn?ncmK=ZPE?FxfJ{Nm zHc|01WsUCn_^&qw@luhPJqH&RMyL|lw9v_i<Rk#|eYy&oS&W?43y4lCkaj4!&i+8SjO;>=1VKg&EquBU2>for@%2>F@BVC% zi!>g3BSr@|#nc?An+L|4-Tn!3b8|z?Z4NIRM;x3)C%5sPcU=1E@gXTABQoIOHvF+5 zCkG8;V{6+poWeA@v_yXU6phDpI;&%1w%X}G-xVl+d9s@D@grjz6-gl@)L%^Sa%8YN zyh8-x0>2hMCx6QKY>TqEq5>5}y=SbfeZYcz=Zbju(v)*J@R|=ZZN?>pKg|A$_6aL} zSNdTbO^oqGSVTlac>MO_z#?G9l81(l4vvJx|B+dh7;NU}*%+gCuW}>Bg`|{}(2WiA z)Qk*^sS*WZAvbzN4ARsYq1&sIgvW=w!44BCDY(m{#mFjyX7kN&@$>aoX!-^Q1L-Qe z$RNH+>;mWho>DYs_Os4sXmqocwzajDEK+7U?2Cl6c30ey*F1(fdvmtu_=OEGJsMf; zavmD3g&8Mr{MC#5`BL)K(HHnA4_)C^0dT*1@RsjpcHnFMkf~WVyo`B)YsJ3F8c6+`fuxxA1V$jUrBQK9VNB22s-coD3Oc$JfF$WN2W~p zGE3l_YJ|V)8s{5@@CE`u z@%`)DZ5 z9vPW#ct;&{=?#lT2UmBKQ&S;7e`+reiPDG_V6n5a?}8t9TSh1zF#Z!q%7@DN^%NF* z%m!kK`nKH)J3A@6o*quP1Ma<3)6&)-?@k8gsQgRz(Z7O^@%uX|*Yfmurv}#8{f7_| z^qp!ZCRiDx;ox!$aJ0R_Jh<#;p3UylClBs<^jd#Og1WDB;1Iv(i;^KAAk5dA!Tk?O z>Z$qIJ3R)$6eaA8iq@GcW|~eL_#~-T0#7!`kor8@f#9b|!z-N^bt@v~3S>QVzkZP< zo9~6Jp2*qTv+C>XW1}O^a>(I;-AWSN984IDAz-cbzw?5AQ&m-!Zl|9RN9z_Y`0f|i zYoXbM9MFRhiY0~&#!JF$ZF=)(+s4sx0D#Uqa8;#l9W3||opxnfOyy(8U-dFjr%qj@ z{`z&$pFeK@%p_*YjWw;R)d5AG#Vw&HL)=H@g!_gz)#JXZb&^u24XxH@9HS7kjmS^= z@WxN9Q7I{{sfoX#p`paHDB<@p!(bQ+-sv|oX8@2a>z+?v zGmA0$Ok*VbZ6r$h9B7}`X)k#Y`APyWHo3A=?M0F-Rn;18@#WX)jE1V&^v72%Tggf; z*QaLpw{uM!vcgi#*D=z^`X~T76U$(PW?D zoP2B1ftc5oHhY8ZLIc$dH=$r8?yBXQ7kOGOq|{eY4RcHJVqfLdl{~|%s%01#8Gd4F z3b!d!>g2V(lV6-HUBK;hf%(plyq3L>IcsO$T!D{%z!dJcIRho!-M=g_D5|)-^X7YR zpu|y%lAiC3M}qBmC9oWpC-QdVllTL3ob0kcni8x0F^IQT^SK@0zR4;cg8Qg;-}Bt5 zULarfgxUxPkVDpv9s}97l6@s{(+rf4ZBYUg<3&wgZcM4S*wE*FfH(Ow#PH~OvFIu% z7g;e1(|~C3t?;VJ$Zjlte7?@&Y(0`{WA9VJw;&j})BE#ri=`G<-6jXUg2ZJC3JP$K z+c%r%<||*{0psM2iH)tZ7{r7Injg7Br#AG})%27J zNbbMCOMpG~I-Cy%ArtDQ-FJS3_n5v0Bm4)@8vuBzq{vVQ=31rzU=ZYpEzRbS_nMeD zcH?4Gq0h2#3l?Rn(J_jQ?28*b=2oH_8J&uw;^=N79`pVx+^RM^6n?wuS;TB2zr4J> z)CDC7f68lTTQRVN??DjD=CiN$J~Q|5^4cKkx<>e@k{5Hd*!Nd2?wU>2c#kYcR{i5l13{_sCi8ZF%fapcb#Dvt^+FJB9Ix-S6 zY^nbB66$sxR7!s??JDQLAOUH0CbtD5G;k?r@gR(g-Lb(22Q8G^M!cjBdQ;#}2pwmq z|DDTTX~qWFW*G&A=!Mc!_J62{bmqMhcG%Bn?CjyoPC6ZY0))L=`Q&b@nJX4^(ezD+ zeGxrke%>{UjrFFXJvBy^LvHQMz*#7cY8xf{ohA8le6mI`QBsPfof{q+dg^D;`Q?T*6%}x{%m=rM?#y%*} zF|Ks@&T_o^0-PoiG`@~1oYM1;i`qtZ)A6cmYB-P^{VP7E>-h*>p>?LeY=p72 zIf597Z~)xkD_!3_1T6VqE!XFXYms9jc^xg3dXZ%JTJo$X1m4pTavH~7UV7c1JUwzc zbv<|uST^SawAJI-yc}WR+(7_6M_;|UAFl_+r_zn0{{i6i4_<~L6a49HXl!~T@MI0} zfq0H48NQS1iihva%vsZy;2KiaEYLK9@(C9;2Xe`I*u+hiU1d_&V&j*cuu6TmB{jMp zZXW^~nwv-6j!Ts?B1-b{Q93l&neM+^e_@-0MoB*ANSkA0XEs7KWAAl@C9g$CLANbr zj+QmpuebZ3?J`P5plBo}29;dM4ZeBViwyd&VY~v~JYm zGYV6!c5;~{U%hbrQ~Sz_ieyhA88+L2t#73nCX^b-wziLyc-oa-%+iEiS{Y*w$^`BH z#Fg5~e)=-eJJP%%<2&cWQ`#d_K36NgHT&wEq*+;6Lt|qyUS3UXJ9Eif?tSK@-kTWTv-!{fH`THhf>!H$<}pogRrW zQalNFA7TEq)^W8W1sspq)4jW)$E3{Pd-?7{sYsVe8KU)A&d!%IG6*ZaC!)D-Bg|m2 z|MTMrWfU3I4Jb+nzs76(gu54*1}H) zPe$|ooc2g6DW17{>GjOFBQGTm_Gy^b40|q3B0mtSQikd67eC_;G2DX4sg>qOf7LrY zI@;Iuc)^(qFcK8*aCH1tzd!B6vdc*0f6mWu{w9rF7FlcyqjlaPPz$npB9 z1tfVNp{9v^&%e~kc0ugd`l(4U7O|^C^O$s#oy3gyYH2xyQ#)qd|MWv;Bco(xx^+1{ zmHjNjl-wV+m>L1ak}F6WLcxq1CvZr5dV0xus*ahvqu;-$9_9i}l$^&(QpP7h9y<`C z^;tW7Yo$`}3rGqoz4UD5Ks2--%O*(nW7VlH$?|jkcTlpW?FJc;C5^6aMR9#aYpW{s z(|ysaW_E$^K88brK-$|8^0hVm&Wuf%8K8F8WhO{4lRF^C-0704cml(MD%Q2inY9Gm z4Y0M@SFBF;nPb*lTU+v8Vtm$r)O>1?Qij8 ztL@tZG?Oj|V=N=fO|DbUs4RB>_!|%)`s#@2-=ZO$OodSUWaap`?roM|J*g81$ zr|B3+16a6rx#&E&)apLVp}_mkb};@KHeBfiZgG7*F5rQknhi9_+=HtZbo~Ku9D{=J z(yu6~bglB;yP$ERwq@V@7IG^_>B?4L$r6=vEghXtY&U<-``)~_rx{?5)%g3MU8A~B!r<0$%GrbzR$*x=f{u|VfhZ@7%kBit z_go=7U})aEg^{n-)r-6oDgcID^AHAP8+_q200W{$p%%3b99!b5c)^qpN_VoWa=xv? zaawx1c~1y}*@oJlrJ0&q(ym1oJPYabXEWK0TW9qCl+4NI4#&p+{%~JcuDh5(?*;A_f5*H+Of}-&t=ydSDieN1AdyQ!_S{Ft>A$j|KT>}EK^ z0f8(jApv7Oo{s^6=4H{MA+KQq^v8v}E4+lV<(^$NOr^6r3|eidWeTUX%ka!v(V2ZY z^b-Tt$t0C_w*IMV#s7*zw~D{T5O0%`De`NQIi-n)#yIh_Mgz~gje3mB0QI&s6Yd@+ z8Fe-RfsBYvG#eY6Zjd0T3(FZ8D2PR5;?o$aC9Fi}7OoL%th`*yQF#OyC}*euZX zUvNnYQ+WPTB*!M0;~ljFk@jbPW_|2g;~{LvW8gqk`{46XrBH5t*BZK9Y6aEuSPNB_&M>l^C}DGu|v-Bwp+9-5DkU(I)pBL_p#2 zaGx`J3*~iM{!S@zzxhGlII5Nl@FEyoArLj7xt6>;)QD$7yPgBrtZ2@Ok|_<>Kz9{Z z-jT+tBddJG9IlB5zh&e33UPg@@XLLaq1SA+49o_2AhJ}ziV zpEfo%ef02CQBf&)HBTQiV6LF|2fzpgJDS$HJ^;MyY$j;|39){AP^07F%Z-zho=#{O z_;6ukZ{G*axd76wFiJKD)QI;BN~i-GiW%K50Alyhsv*%wT#V+$cm}2P zvNjr>L-Tl>vb4W3Kg|y>B9uCH-Qs3B8oQHyC=2wf+WeUZK6%(X+3qoz)s!EG)D#!f zm2Tc`d^D`nWg}!WYSa9CR^F)%Y5e_%n>1dx&4U>LA1HBQcCyl8mm!Tj|K$zVar=pw zrKRQCc;KUZ0Wl0XRR4(y^*sx&XsD>r#lsIP_(@mCL|HW~+P=JEA00uM?pM1b&oW#l zJH?vC{>kg^v@AJ66v+*lEq#KGl{H2BPdrJA?r2@=-%|X7gGz9?m23un5kUI5e3TEf2ntL_H#Ps`7XFTmM6d4JI>`{u09Ytfy7N?6I zzVD+sZUCDq-(s_)Vzq}@AiaaCs9++0R{kq{bS0-AwNq2yeazauKz@2i!pW(6*J7^5 zgwy9U$8ZNFA|`p19OXNBz|lP3-yp-of_0Oo!A3R(kJbb+6JGq0UvQfB6wa&tByekg>n!DX#Lqmc6y>3MR$j+9=R~z~VDSrGpJliM07F_{UX5P6 zTgq~IF>V9Taz24vnOH)z?jRT_RRU!z8b@h1Y8@B(?>DKQg2t?s-mx|k*8OsD5zYgo zV(dSyB;r)V7n%b6k+c=vi>9BR0mvmhlO0A$8_b+0EQ(tOkZ`K<3UH0>ZgcYsjDQ=7PbPTSItUr z_)hhCc$w#n?O1&0q#j{UMjZKu1%HmMMRk8k@`lour=?p0ya^GMbYjRb4C#x++8iJ< z(QGHDRWSBDlYt_7sQ&|s#|#IP6-b=bbadq0q2~cTz|Q$%e-_AR$RtB21*(oMJiW;H2mHY$hQnYHQ_2x{-OjUEp;(&BIw#TXV|-^?ZYY8TF&;${1M7R6O;{{2nL zttUg#2T)7Hq4SRYXU0l)V@G2(0T-+gBX@cYTMed}!j29Kr3?;)iF5sZf=|;Z34{OA zvtiTne|*LfPFVkGhP5t|uEOE)%Muwbt0s6RyY@b?lJhTT}y7MkDxY5~$nVr7=F&?m##8-HI$Fm&eo{ZRls zU6~;UP5STO)-P_hQXoMwHs!LnpyvJA%8fmN?-W#dD4PwV~aE$ z?tN-9sr+OGt0$S&^SZ&;c3IM%o{dg2S@}f3O?*?wX6@Ly@F^kiGdI8;7-6Cn>Ti09 z1RGqNP|nvZAQge$1Cm$^!0Kf};2gMclnvSxR2$41v(E1Lgl+vrZ^rfL=m=nQ4F5wQoxAU-l#eK)K|v1Ky*ZOW zihm3r7?et`V6ec7Hyrp!2VRb6%J-H$O5WJ;5C&UT=XIq2PjcS@RRdxCTgmfuQ8Trc zdQ;{f^Ov0>XS1&vSBo*^T>qY`k+8;KE?$n9pcY2VZ_ahor%{$rQZ=e8N>+US4BRWe zqA$bk3t(_eVUAOt?O2R2Qfdw!*HQR{Onfir|1yru&mkBP7G2)4;cV&7B%=Zk+}OA% zNu|Vi4QNodeZgekk>so_W;-0zL06zh6>jCv9i$Zs`SW!{&n$!)X4z4GhT4YxB<_TDzTPrJ-FMqmp!q4JW9s^ICh(F7s zj=ZUf-L%uTjI`!Oh2H+Eo^bi%V2;TjeOPoGCuif}@Gz`zJ!sah^rs;V;P?iBY61B5 z8kAU7dAK_>hwqu(Kp3f9*zPa+&;Oo!_dlFUV8g2cj{4V^H`BoH$-`tidD%!ALA@mjt z*?HWmYD2OWNuK^Xq~}A~X8#ByEnk0>7UQ-2@x|{2`x=Ca3k%X0=hgz*jIcsuP}`EL_z5KPLi06+}YIBRFcrToo-Ol@|*^?Zg{w+>oHs3 z9Ra|gut(U!%cZ}e9Up=CH#C&!P!w$WA6nC|0Q%rFP);Ms-U=;K*aDUa#k&3Zid=P! zOYfD;Ir-Gne9_I4Un$a-USE&5W;>>OwToKEsM^loX<*T({Lm!rosZ zOT2{4z8T6Tf5>X=BTOd zYxc3CxJZ@|PJoD#ZhXlHX^7E7Hd`hJp*eWiBQNPTmUc`B;^Idoj~;lFw)H9s^z}|zJuIjxSUT%k_7M!=s zod@pHu&B8ai7e5(KbG+O4D^6Jqq2KGQQZ zshWeb73Ok|bssM;(xgXHam8P~Y1FqO@H^x)<3WCHay(Gf)<$Y&Wd%x~k~?G{?^4+r z*GFGhJykckZ7Z_r*1l}?xnQ}1puiUpm#jSBKfjTVmKB{?S)sgj2Q;GPo>(0-YuBo3 zNKFpN4gk>u6$1bn0FnXH(4L@o=fBs1+!4`Z+FfnbUhA?h>37_Ma*WwDL$K#iXHp6|@B^jb01X3ol%^KnqW+o@SD z*LidmpLNccWvX@ANdVN-;U@dZ$jD?9=>P@{eRh;E?HSCIZz5&ar3S7as3-zEOP}@g z*DsWU@r)^T++ zmV&<{Qm90wK{FV_TkIr(OqiKV?tEaH&M3!ke&E)dCy< zO*{iGKAQw@w$wfWIzMudD)2?x)Ks>#0sJdQjd=%gu#Ki%nN7BGrDg_Njr{$5YUqek z^2h!cvpP`m`|^01_13S)6uYMLmIay)^4b4fiy(7?K<*FUh)??`JD>j^gS4sV*u6G1 zjB9HXhGy3E@Q&d0%qPxFBicoG$j@2LRoB$03bUs=f9Vl(AkOyq>z=Ji<~|$d`22Tq zgkWsCW*oi1&6Hx*ja#n_p+2EruYLw7hFomCK4D@PXF8KtI4xy~fes&7T&V{pt+1P; zASPmH3>)mEFd)z1A$~X887w-q?_1q>BDSCfXzwXR7>D0o9WTd%+JS#+=XwNL?VEAR z7iax=$+-sXpwpHs&}uI3fl&3*%eiCHlh)7K+miLv}HuMIEsfYKL#oJS$Tv z+nb1c2Kw`7t>GXuPK%7MdU)tEhN7NFa_E1yt3aNPypL~FjQwI`+hLQC*GRy+?88zC zGcouFgMt6xW9$-~W;Q4lBg6GGdZOjEnV`;n@eWrmfl{kIw}hFUeSj|EMF@bXK;$;y zX&n^wIwY=c{Y?t>da*>D-qO`z7_Ml% z^toFDwX6XT&Z~gZ5Eqz`#Usp|zE2Icik3YQ*nq==c>oEhz`q&DpW@Ia`Y6OunkiI+ zB9w#bhZ$3@H6XtMS+M*5=3K*WG#;uXaRW{E{>VA7uQ)*rxVt0qUziRgWM|HTG@tQFMWFh)mU)BHG@q=4zhwdC~iMYvhFp4iUahCC_H{N^KwvQul50Tm^Z;$>e2p_({I8cpAJrdp| zVQsqDFN@EfkWo1^2>2p1aBS<1?ZIy-Pspf}8})Qs^8}4E90wO$C4jWz?%Daj(4to( zg&o#eI72D%H=;kk4WAI-{QE9zJU`SdC|J-G5l(vbfa$GH1*I6}pplfWl5Lb2iOZYz7)7Y!SAAHnUUYgVh^8;a zH85ziXKq=X;8k&~ntCeI++6n>jO`fPNu!A=x`y|`lu6BLuR9Q%Mk*|aAnOU8f9HjP zAX(j_<&hai#U)3-RKbLuH3)LvPZ3$M3~^l|&ScDs?5@^_Zw`bB9gi$3qK%^xr<8k7 z-h)KtmpIWV2zgjJO15XJ>7?wr5?8E9#}d1SU|?VX)bOt!I0 zpSz>_jv~UpIb(wIV31k?g4ePg6qVgZuup+nz7rX3K6lg_CTuX_A1i3XpAS_A2gOkm8 zPJ1d~YhfUi34c*|rW@y|oqtW$E-s|MfLZMw#1+mT{UO=4e`Q8Gc@BrNbI~i}gbD?D zknV*>dmMB`jZSS^co1uh+6e)a;Dx^Q;^FT!3e_maE|#TLq5IKY@+=+Ue+!_fsQ6k# zgKqRLh8p=nioF$nQlONQ>hmm1Y^@S}>@Qe*ar@nIbjFMM0u71yRO1>_Tx?%-(UL1- zH_^9e>JC9I{6=-46vlZc)q>Kb=&1E<>mwnd(`k8iwJcB%cW*dZS*H!NISGcD-ehZ` zm4vU^!$uNKzE@ovL~$v5i5LKjMy^n@3kxxp65;Poc%qK7rE(91|W<(sQcA zZz`yI+CHPE*tI>HKdgmf(YIC09t$TE0J*ymq|cy#1K5 zZ#gpuhb*9yplLQO$Q`6jKGnpEM$8>(DWB?nC)E8;XsK7<8%9Z;H)Ao(kZ!(FEUl;- z1F_&duTPyper8Xa4j-%}&Fq{+Vb3C+XQ1W8iv(Ci}p}#jt0fjO2l> z*ngxkJ;TkE(J>4&GE^h8qA0SJ#%?Y|;M>J{|0Kbr-IqX=6v~bAqF=>DH%j|!Q2yXw zzWZyWdv8>|7E=E^B$Oh7huaG{>W;NhV{a_Thl@F^qVudSIEV_RcyNGojr5NKN(p!J zy>A$lVR0y%?RGibXox0E`r=DbaiJonqWx^X~dDxFWXPBglH{NPQ*oi;@nTyituEl zW;Tuo4+>rZ?u_W4h=T8W;6iu2zwa;+{99UPu(Tj(PHs;ThEQ)sIu4hn8y3~53zpQ5 z$BHsUG5v)^rTg4_89Wa9r7G{q6c2AI7@jf%R#1H$iU3~Zx6J*HMHeDMrq4EyZB)~i z|N5$Rm>TMD8X0agw^hhuWLm76%gW?uYsTeIQ=l+TZ6FVSN*8N4VEEg)jT}ZuE$lU3 zy=gd3>_kM~nv3|tDd}ww@eX;;1WB?lR&ShpQgFs(uokkZ*n+DVj~ezBo3x4Kdw8mh zB$)H>qYy|Z-xDgsPgpIZQ9@-IFBdpRF7nvN8qcf@lPS;p#gm@319%9rAm))OyVQ>& z-!lb?xvp9g_j(zl&o*`>k34&?pa7`PK5}{Y%6M)H{bXwoIJ6II_`Md>Dfz8=kcw8lob)$uf*7$t2_rV_^*x_(F3L77nMM!4{Jnh}*So0x(z zYJo*<|HH9xaiPF4;(a?+)a`vqh#`vDr)dRfU3=8&&XJlDsBVEsk8#IFkV__r=OjdD z+nk0|K3VXYZ78#TxuRviDO+x0|IO`}L?htTOlDjoPPN)=>966x{No!7U>({+sNQ-qLARJ=zlyID@q@EB-Eo3+uYa#@xajmgfnj+lKL&P5=-+rIA>FYZU7YjfMsFdJ^RjaNe$h)R$ z*dRV>T0Y%mxIUw;cNO~%3ED(1!X3L-)hVVcG;?!rPcM^azD9p|cg}jhe!^J2M~{B< zU`lQnwf49hSeIk?1_lxmFCIn}xB(AYLvlfe)W&--`c=6zDR=999jB7OcE>ncGktki zzkS-(z+%qcnechS=ctOy!{dYb*y#0rJ=z33=A&al;l=Hu>F(~!-+6DTch>I`x%UiR zNJz}8+CHBD*z;lYr5j&Gqjc&Xw#|T9r9jMB#d^RxIS{UHAci49DA4@3>N#T(>;_H! zUA&;Z1~t1G6r||lra4C=cSw&jyvWaUzd0Y35k+L5*g7)>b#XWh1>}1jy6Opm%ev-C z1(`F`es!7|w)7z`%%R!^R8{Ot*u8`z=0dEh+jn!uO#tn9u8d zgE-Zm=o0tjj)I75lEi8#yr`!Ai>K=+r<-C8n?{zjWQdh7<>Zg6r1`(m!kzR*inQZJ zaMF@(UOXh1VlZmx;BsI`ee{&+E@1BqS28}f@7I!ZENpE3CMG^OM4o}i^n!+=gwI1m14q3YR^K_#Y!g*IIZHgl5nPL1?zSTG zSbZFwILdRbMxgAhIS9&i_)yLSXW#jo1-?rJT`GrbaKZo4WCh9ZEiuH@MmTzH9g#Q^ zJ;Zi?PtD4grFL$?M!CbN0NPVA`HYiO&ccFjY!T!c9Fj0Zs+}lSluwUmxBQ z?S>7@S3Xy!%kQwWuS{%zr(KV-wMPoN%yNvi|-|tbj={vhi+{Zfyb< zvz2Sj>hC?mC9K=pegGOz?8jsG$QvOzJndd5> zk%;DnR%LT-f7Sck>p6N8j9D|;dHaH*JFJ9d7W$CD>580MwU*dOczD+%`;TWVux+c0 z2|aVm_*n2ut9{)Ax3~K@hT@%>TU1j&?t&*QQQKp!F12iY|DNr>A&MEMdJiLo2t)WT z!o{F%d~tuOFbj(r2;MQO}_aB$;|dld4K$DZM3;J zIGXBh!|f)~F+@`<#kl=Wdv&@yEBZwEXBP)bvBJ~ zvej`}Ld)fW6i14j)d*f%gX` z*_D`CE)Vw5P|!)o#V`dEowa+0$JLFW>oG~reZwZ87s$d{a%Kk@3uI(Wl=|MB`c zaUufTLQnXDCxsdrUZ0sKJVaW9m(BlrwRX+ux(-7EznG-h4B67>D>lVS~*Ip)H6?veYt(1Y2*NpwcR_?ja+>q;OzRvr&J%SBZIRA`~%J{pz39KJ;J`JErEB_3hrjE_(u6gCnbT*_ zVpv+M{PtbMY*e8ARV**u_REH~_S0Upx`2+hy=>V0T#*>+ThE63y4U6zhV zq`!8NrK?=^N0Bn-$Q}uVcUmNZ1a*H}gcM+X3+5;0?1X@H6;@W*EPs+u#`%H0xp@CV z60}{IO-1I^?G>HV86O~8{>@fEfsBc_qg_9837hy4^dKEaxW0y|r~FDp(e>`xzD3*h zMyy(D4jlDaN%6bOS>(2^P?`ZRUFJH^X0@m^ca=|glnIgizj5JVK73}F13eyfbxHbe zD3a#5NlugWx#VsfIA??hV&yaRp6XoXmunmIUvB zVO#LBbc4uURZ$C(#qTE?OPfA?csX@``*hppCcS{}WV@?qRonzqx9PgDN zbBi`(P|oD^54ES|x7`!fBmq4U)jzr61`BVp3uvD<8;7!=cs=fqWY!L(u+8~%K%r3) z{fzO|eaB}`xr4qy`Hg2cW;J}iM=8OejTF9TaNDhC+YO-fLi_#^67E4EIlVd z+@~@WpI;59nzT`uIwVQz!%Y3$@@ikt7Ucd--ns92;Io|mT^*INwt*`rLEKrD6@_Je z>R&CAkvg%DUJFf_*Q1ftAQ2a%%-AYg>moiC0SnX2cUzHjYvUy>gQ`Gpi6t z&DTGuPVGnhsR>jG1uxE@=aUE6?dpdLt}#e){MdhNJM-yi3GLQu^Y7$_^)e`NgH}I+E=DvI@eXW-zjceH^f;|VRg8R#S=*8X zJ#V1hW+W>vBdbxvuH=I6rGUEqkhLiY58JWhw;aVbLmiZW(|@#UyCZ@Dw$e*J#xtaE z{kUnt3&MmG)+pkygUIU?Ni|-C7rPGEW|fE1oiY>>KUX10VQmH3agp51kI8^H$UVTbd-h@AwUZ3mlJY`v=Mo zO4QH!_(1ur^nFc31Aalkt!>SYLH#ziejgUAH^_-$a% z)a+-M_eZG{4}M})&<;VrCQsHxU%P(&#p*I?vd<_G(!ikRyG}fifYby&*t?KNc0K$J zTzj}b&%fjD6en*JZ(r7Y0R!ni5}CMjg)6*6v*l=gwsEB1V{Cu9z!WpR2X+Tu0ZOO*Rwudl7ft zFwao}oRnqFZ4lT$UeXpK4THAYXdsD>&88!}H66t~v|)d|xo+O0m<$;=#m-;?-6H!8 zS7AFAf&5v@W>>?Y4&$z+xEL;=iz-lx(pXxAzb652%>{To4~--fnXXC3=IR308#hldj`}g(XhNx0 zpDo>Z5E9h49`%eK9T5&x)Pj~m+%rL1e&4HO1PExI(r>aS4w0ZHZoMGeP4k$F=448j_jj^wQamH3#jqG|uyh4zGm`EcBUJnY zn$30_%XOUHR1eBKbF4b zje4ghHkcVp=pcp7niOBY?AT5ogonI=*Q9MRDFOY7UG;Vulqo!kd&O1 zgroKBlHl_27aW9`&n|T&EouieGYo(~AmR$7HackWhI@k8?K2Rawx7v;vj(Lh-aC13 z!Cy5v10@>k;JvS|b$^%!-Ha$rww-dT&86c(312Zvl{a%=sgr%BD{NkAb3fBcBL;o5 zpdVNYD9|dRd~UFM91YJZh}GvlHkw$M&`;LHdjw#b)5z8{&>;-4l}BYDDmSQnp3Rt@O92ISPn09JDkWDR5Tlfrwyqg{50Cmg>?IKn+ znDUE)(h^+%Lx08rzhMuh^Jqdp{dFMc_iZMKgPud?>HkO7S4LI2c55%B1*Jtr=>`c= zK%}KxKu~It1}G(xi;xbb5d{G$0hJc%1}PP3q*J2ElaFEQiFEB+-$ z!XCqAepuE|OyEbPphT1hvL29n2G4Ju{1vIK=gNBTi?9JCw0vr-<&&cCMW5aH-JO>6 zE`~jZ`2TT%4r`r%S96Uk^;Wx`0`%l*q>EI@9^cbz{?sw+$Rr{{3*P6r84O-me3YuQ zo2EO9*AGg+u zSae>ngqHYQxn7vi+E-r27&e+Nj?9tifobPT8pE^99N-v5MaIOWAG$g23rrALP5>O^ z{kTQ?YdVp_4d2GnQOC}`U5|O!$I7x(jg$6uOFQ3bFj07#;!5i{KY#udb($v!UzCQ_ zvC|c5xrLoNkP!qwD1I0)s;8slcY8HBKH&AwmD2HWkQJyU3ZJv-{~`nK7!B~Hok}}( zPHqWjI(gm_oqi<*vV{P;)hjoTs1@B^m|2<3;N8+Ad2^c_;gOuN*(3WyeidmN{8zIBfdl$B#SRr}&uR zn3RLvR~6v7E>jwL5`WB!w# zFg@0}w#Q-2L0rR!JVp@I(3P&Zq_IBg*m13FDX+4@c4>aT4iqr2!5g3DWLr5J4n!JZ zPnKp25UAlmolxzKd)IQl`x2*1W7D|;|FbVXiTRkzMBPi2kBlF|WYyL$suvQ~zxCzf zuFSD?$3yS~xCwtFfFEkR^_yIVDf4xKAy0GT+uGM7SwHOlHdM8($k_EKdNg+JL6O`_ zG&tciF6acBhj1Lks(n2h@5||+&ZVrpZe_{p?J96F*6BP$a1@FX9gJu%8G%C zGr#co^JUFf4~lhg-!-KzO( zU0}G+9g5y_$Q-yJ&EEP^?VT?iM}<*y*Ct9)aJ3Xa{J9v{U<3{gklZoT$Ao5s)zNji zutmUa(^B`|y~#E2)5`hh^0#X#jX(s1s`yIa5b?&WL>`)J%!5fT0p8DChrqf}TH9R)T4umUUA^0k8*Usc#FCs z`Baqmq3Y1t54w|CyBS6o83{2I#2JsQ`6)we^Y7t$JzL=1S5Z}M9J8}N`%Nh=Vl?lj z_63Y^;yL;;t>1DWoiF;jaQ#1bJ@fE>oGIM6qVPIBLMoJ=+;UDq-ZeaoL1YZyK~*qq zaz`!UQ%T9qzqP&FCAD?%j&$C8pX`eQt-Ar91yEq?LJmR@q9%ogz( zUhU~s$h!KDlqRrQ(SX0SukX+jQY-`#e`051G-aRtk^PUfFn)Va7Gft}|9?!~N%Q)X zI=L911})U#e#B|S>caIqybrc}r?{!37Tynq`M)V0C>na}(<|hBC{Q+P{CtJwT0+R1 z4BS``b?iWwbppRteT%RP`<+LRvcC9|{oZ>xD%2@XRXXnFq1{q8YCH4yZ^Mf7bW;db z>TrPf%j>@Nj2HNf-a0)4v7gexTc?Mk6)!|V!0Z4f2phe1tA`KGn?q?X3O!UCTp7n~ zo#U%La+J3&J6x?4goq6z`+9uDHN;mj&pfJx1%Kj2=>eOo#Q!AOejtQl>tH65wHmCd z{udbnNiA}^l<(TE%@$%N2fD^y?ta_Vl72~?d;gjXB;(}be@HekI<$r_)L_h{BVYaV zTBclUXQ|nbx8koZ332xp@u{&XsCIL44KXWAUJH@DqoHv=zMWV!oQkb`CZVx~<09#z zWAWgXX>WJY)tS5Zt9e)02pil& z46H+D!z@rml4Op84}XXnxj)e_Xjppo9UO&fBNq3q@0JDQYH2iV*6I!J^ig_(f;5K% z+hnV|b9kKg#);Lh>v2;g(;X!4;6XkMn>oHgQP|C_HGa^u!Fz>g zp^uO275qkJ{K(efF;rNsqo8JZvlEDZ8>9q+&;P0&?UvRygO!Uqm+1kLh654?;;2_4jHgh0kr|?TKRSRoZ9;2R`(gIKAz)xK;@7DS;y8=x2qyKY!ce65WKe zh=0klf?u^rpW2SRD$VAS&KcoiEy_mrhtHouHo@a}&8OdgoqlInk%U{JLTNCAd5=m7|q=4NEJVD$a-YU@M+CszuX&8?UfNl7*ed_x#my00 zm-&6diW;fDfq@Rb18irirLQLGl@^#_w+|j(Q636;5b>ktHyCyOgno(QqP>qxvc=*U zY0BfDy60C{ODrrQ`XptB9{u~p56{__&t4e8Z2iO{H;t)4wzKlv>sDuzy$%*kh=(CP zg&MA~k1F?G6nY)Ik38>`xL;&Rob2}Z5(YYX>~e9ZZY~$4LOKOvyg_Y8N8WIWU_7`0 zIvi91M8~`!VFK64%ZAiD@(fEmu9O<9$}-~n98Zs5vz-p|A2)0%y-bd_cmH&cr(iBf zSu$7RQJZZ)2JN`Y(C7)=b(0)Y`ynd#cK)_;q%#X$52qe2Zn_oW;L} zEA8yW94Mui9W=(KTPjz1idkn=CD~7y>opHU_N~ODd3B!aO+crX#!eVevUsbcMJ~KM zO?{y}bYp@<2-G~f>duD+k!lvK3CXH&?r)K@^hH@qSpQm#d9J|Vy~}*tuHieowjuBD zn4(08Qu<~)n&5QTV|Q7m*6SGcVPFJrGDU|?NQepq*9ityQK2Iix#ewN=g!lM-|sC^ zT9pr)7UebkMymRTw;r^tpFU0S00)Q6z$T7%oyihqpexk<#C;vnYz2}rgmdY9GzEnj z60UM%r^Ib3xAY7OLYFSE@BOQfR}oQG7w!CGo3KB=bPFdY5rkKtJ)@XqydD3-l*v@! zyLkLnAAlYH03B0Qh|XhCmO6QMznt^_ zD3dn)%D;uZ1LW50&|?|)7Merm7X%nl#F@uX7XRU`D0vt4)P@g*9BO4W2Yf;gi*GGV zA5bE296e@T#>n}P)kQHU&YHv3+s!ucC+ltUt1k>?|5$ewF9QgBa_^8PpX&l7e3Y$L zEFq~=@8Lso1^=$>wL)tlr+F>pCm?}6Jo#0W6{8DIX&*l-G`AD^YMmL1RV9~0H!N+i zj(i;M>JLn>N_id==hv`QK}N6pwK-msb%Ag@!_&M3dsgJY+A8cJFL-$T^w`i~jqZ-N z+gp8BZSdlyeHUSqZTzfvF44GQ2s?eX3E3At!=}y$xx(Pu?dlfn{vzo`munOYU(%-suE3I@R6iNysba0X>{0p;; z+A!p?gp8=NmlFotrJtNGSG&3Dycjw?)!4iFgoNu_weZc7XxnIVd-V@OY38CTP=bc`>U}9${xO?|*w8|j-{I34~zrq;V z_8mh*Lx+xQrKT_@{JR~%1da&uqf4aN%E2*6K|>SpVyQnhCx=*iT3fx97f#%_1_a;MW3N7V7!-&Pr2GV4p-~lsZTjMU7wAf^H0)T zc#64{+4WdUOKYOvu5)YXvv}Ui$_w7z0b|;pFEQ6TC_ME(_sx2i0*9)Q-gWC<^5IZF zSc4k&7vA%1&b*?HA09uqp0C@7o(bj8VP$7$=5F^;GbVK;u-V?;ZoQm`lYKboPZe+E zh{Sl^H8doNX~Rpr=Grrc_y9*-#y$Clmz{6h*6cq-qVjCx2Oi%*67RY*RX4zTY_T#_ z(%RYC0??M+Rn7FS5AZ1=u+9ne3ruWm_-$=%qR;=nn!m{)=0t>am8)gb=MjJH{aP=H z8<)>PN1DCJ7>UKYLQ)ztV8=)%3(T`QYtUR#sj(x!+9a4~$b0(9xNV6)R@aaQSIb{xWRPR93E&`1rP?NPw(T zBO_FzTmp+t>$fgR%gJfmuf0;{x$Y}*^WD|N;h4C@1gb3$+0Q@8)i&IG`3JFkIT~4a zz%Gv}QxZZi3A|%Jh{e1L4V8#iah90O(MK~LJ`P>zdUXBW`?a|dYs1wKj0&%!y-Be# z4NI%5dbyp3j*i#eJv?yxPnU{1_!^l3NnU-h1Sx9tB(uqQV6_jvJ8}vyLNb(^RXA+WaoZ73wIS4nq$fqwsjKLG&Nc}LdR0#h05-`5v zktJ!&?Y`_9Kc;xe!6Zq)5u$wFEY0y&9wnCB!OGmvaEPStU9z?;b|dDl?Df!E4aTBc zloloYp-nFqj_oGx=h_^92+rnEc_$`ZHY>ccH%J%}QOZ?nbg5a^(mc8Gskb>^O0%O; z(TLE+%@2JK>z+Cv7s#gU?19GS<3#dIasp#E%yBYh|B4<<-kI2mp!AL}~5uHPi%R9QvGJ6AICM zRmZ!-!4VNHAnA7KQ5UJVEuDs-ih4+Ld@Xe}N#+WzE{^C_lg&V0GuT&@T*^AC$JEi5dQ{Y|hzGQ^PNBxt^F#{H#~!)u%wLqai4&dLyV zk5gd=PL~fNL1^Ax(86}+ZdZZu4N-z8*mtkAschR7o>GSMAC%_T=KaN?2WjJCdEIRKbX%K$yI~&$K#mli%!>^yZ zXmf5eYw;Jk=do$l!C4ZL(J>*A3ct^{+bzzr;GuuF#gWKGEYuTj5T8OC(MWRXxc8|9a!{Y3 z(-mGftWP#3Wz9kSAJR1T_4Pq&9T@`6So}=5iKJ2>0YOLGJ(^(8X@J23iQ$9P0$^Sy zXXDWdc6R(V*eMc#p#G(Uz{m}?dXl#dQvaI47GU3ZPrp2OTEF&yW^;4%Uk?w{5G@k< z(yKj(7;Ka@HCuuhyn?~IaTbyrZtaY+1QWGbUdKTpiddq6!jf+d2RbZIpFIm@P4D$V z|K*lv6vU}Z8CtqF$)R}JUPl7;UN$o=ts!%dev&~urSWLy{SdlA=_&y;yUe2!;R@pG z?AR-Fh7#;Q{Z03B^*#sudAeIcQ0~}ixyU0Wd{Lp!T4L@d&iu7LLQW}N#m7WMdpj#I zf#8s1P)7;c!+m|3Ls~&v{PI?QH=73S0;P`el~>!Q!PM3OH5CsR(+2OMt@zZHxe2)8!n9Uhw z#BKpd2!rP~1-Lc^0M$fV8UW#`;q(Q8`k&stnjU3;dc2no=`flSJF&wKU_rXTd;gzl z0OBFB9q1G02YT&Rpc6pQwckBGeh3o+X{ewsXhqo@ZjSWgB3g~8HYe~1%QgyT5~+yOYWwJ#uhbWNa?^{EO7f8unJYaFi!Jc}m2Ee=A)gVE(8Z zkDh8*CqAIOiy7RCKct^fu4-E;eQWVl!)Oq0fYHZ8|mDkDi?PrY7qfT09FBcb)ii(PLn0F@O zk@zJ;Q*$8GKQJ&2qd{|4idQHIZ{W(Bg1?~HTSN&DVSp$pDc6B0YP2oY8JF-4wujy~ z>bsS^j$p<&`o0#jR7n(?k5cXfQKnN$zNCjrLrQ-~Ji+n}{VN5BA;XH=YQ(Ji*#wTJ z(%vse=TI1xC-97WlMAUQNf{3eyYs%`eq3_Nm#ZQ)RIBerxY zM@=QYMW;(}PgS(3*tx3i6b^jR&KKIPfnF(T?@|l~<})za4c2&8Zb_03>W2CI&$y60pQ#-s_v9M|<&4kYN16B_yc{VRxxBL%}_AjodOM}{NX zZYs4uLj|{!+sHWF@(!I6d!|quuu$G3AcG)`{vvabDqlGs8yg#vV}j%-&CJbN41aru za~l}y#ngc%L2%ZAGY=RbxhN5H-oS_oJe|;d`A3?ByQ^cb^ODamA5W2##4C_TYu!=6 z*I9VPfNhgETzsUTWmPP1X5+rT7TS!fU{)p6Su4xq06u74{w}} zYjY$tB-+W^c1meiUNYdlN2~JW>TI3kOtN0$n}2`hgE?gs4s=mE+27XHuxdWs9Fa10L&#Z`BQrJo z9%76GDy9T-|8ZFO#BksXz(-N5*V1!*4o_PR(h+^|;#Ie&oE8N921kUr{JFr8f|vNy zg^t5pE>u@mW|_F&AH|ck?GM@9)ELZ5$_4ae{KXAzgI5GXKRE)S*}laVofT4hq-|`w zcH1^Wk)3znQ8Q$qc*M)&m9KAzBtOeXh7=KTV)tEomJ|&b>08)h6HP1+cNSP_VRR2sS^u-*{O6bqM^ToSo&CdD={PwpZ4i=|8Li4! z4`Z1x7;b;$A0Ky~9+AD_GhY1W*%)}P42A%!6`l01I$N?4Lm$e+(>bZr5Wom8LAF5M z*C##H46YlHCr1H19pm{cqCSA7(HR>XL&!Jt8M7G2pAUtgg+g$`P*H?vHTb3)%?klUY0M*Ca8rW7JsP@WODJ=Vw*J}r`s zaXX-Zcp9GGSzKI{yPE#(TmRDj$Z>%gr?!p*{Gr@5u8W=WIaJS@iy)Edflf@b+R@E- z>?V<(_xL(BPi$ID1*AXs1*)0%>O9FK*Rx5_&^8vdUo#BMZ!!9X_mG_imk)bHqai3L z2>sKZr%ZsB!TLTA*KI9^1iJNeYqe4Up2<1-E8v4GiHbPlvyqgNyBS2Yni_xM&R& z4#i7>a>W?O5PNy$dP3Bq`RKUHr-n_$Feg(|Qcv$c}+(vB|us?yT6wF0;dwzr*9VT#Pny++$V zi>1`IJ;ORO=^Y#%5fYG_-n{?(;luM&(^pe&e(5KGQ0wJUL;4%U)zX8tH$IO=jQ%& z`+~qsFww1*sLDL);?Q5;7?@J$##hlGIK$-_!BpCk!e5pn8L0J1Gkj#4ay|PE+=FUr zua>>+M@L74U%!?&GJ4;@LvsG)&9Ta*FO&HrIyPm>tj}SlMe-t$*v>J`mbzNP4duEQB=_2-%7xba@>wp%1IkNg6>2CW=~b z=gDUj6H5TOv>YRN1sZT-+(AyE@F?-z&Q5B|hz0a;ts3i3gsy++u(u<(v$0e3G`{+( zJeX^cd|Nse)fm^`!kun zI3+lnq!Hm-O`&Jg7|>)w3Rv?Oz0c1h6E(8dO0CL_GQJ3MaS?+A1B#qRm(`8SQOU{S zRaN4M!43t7AkH!8zYcd*g`G1cDny)mj+J3Grmsan^6Y9O&z#`4-*DVD=^^ zhU)8#iLC6IwDk1jAws4f00{*Gacu?^5E9pY;hF*KK?N-uBM9Tlik|Q&L<2(MxRpIF zkkhu%lZE(45xrzrntb+`FHPeoyCSu_M5Cp6pWFiG*AHkvgVa7sJPPi&YU~Kg zxNZ3K+12bkaev&yc9_`HcO7->`^Q#yi%SYAzU?|cDvIbD9`#G+`-z|9VrFQ^4^7hh ztjfx(T+)fTSK*ix{JC;iYCxBib;z=@5#l?1m6;#v2hP>2qqYpm=K?7NE-GM0EmVW; zDLo*>10MyMkBF}xK4kdkmlHi&Oz;vU?gatsL;IlR*ED+oICv8xH4V95=XWZbODYN~ zw`!7x(~10gR%vwUzKO}|a!G3-d-jg_4(pYDzZ)~Gcz&<>%V|k-=7@#g`VI5>j9-^t zon~04G!CSs2&@J+b^!Dl^7^OFyN>7tV z^S@JpFD3+^@NyAsfS5)?bb%biEg6ZNMY=U490JZ45=aOzrnlwF+)G0GI>51mz=q6g zQgspTyR>aM$`_%hhRC{L?Dr|TQ=j415vnh8dqFXMk0othbLM2J_q1!QH*>Jd#z#%Y zx*u%?zP@d_oSrojCYa0Ery9(VpUEueq!HJ4~mJ6{(2;F;J>cF z?Z)kJuK$LKY8m>)vVjVOp_Uk~r+ zQCnj)U!R=4{F)#nB;>JO{Hbc>aoV{oNe4$NjCr?*N~;9;dwhMG&FiO{!w`aV3Ir^7 z)YV@Plj>Y#^ z^@#NuIKT9=vin7ED*=nxfbeNz;JRT3M<8*EK$HBSHcMtWx3_B!j>faa9N(+laT^>O zmN-vYSW=q4a}-c(x9kj6)XC*`5t-V2VGrwehDGrURIuZ4Ue7H{22}~iHJ$Ph$&wy- zqw+?HpYcxcBtyTb_&uO#<7c7>p;c0+)M-^QZ)D=-Xt6&r>!dL+9AjR>UV}T%&cd+f zC-U99kmcp4Nd5-0geW)nob~Jlk7IuwWxht!*5^?ksoXmkjmlf_xV^9EQFAeT#bapP z2-7i zY-Mg?frQ3<&Z}r&se-aU2}8l2&Gi*HrGggUN#maZi7x{z4#Kb^S?^G~5bYB(X5D)J zcLF3G0eYWbs5s{|H8)SftRV|m1w?y5LlO!cv~hn8w1$wyXpH<>04*BUG`4vy`(gq|;5sCEPs>t0## z)gSe2kBKD}Fc@(!m@$wsc+*A-(l*SxL^Q(1x9%kjcXcrtezlKcVIV$rosH9vguNS; zs}&@`(#knF2m*P#0Qn^4d&hg@7O;)Lt4*SA1IKl$DFo$1!J<$H@yZZH-3*<^zgr8+ zs2IKXk;4zjc7%~{cj^ACqazF?d_0Jn%Y~5!QPLpu3azmdMgNxveu=gfZF4oxpFiIK z1Oxd{A&lfZus%rs7&FoTX@ce6)@h0x@V4ADPvocmj0!=O{^>-{lM%m z*K5MEuqsFrxQ$O@sN>*J*wHz1^NdzC86(fWg)&oJ$=qet-GGW8A(l1AyM_p}s?l`; zaA!EDjz)Y_x~Z zq3Ln-Cxd&hF(?hzbdVXLK4^m)l}uVgeq!Paj=cg*aOKBdi0$ z%>%wO`0W`T^4}b$|~^FzjE;MLpCrZcTkSb&i> zU^s_`56LReiJ4_h|F_X*PQ^n{P+}&1G&oMb*^~@@xDvy&PDy#ikK(q$O19K;q^e4mTxDO zW4COoYz7;)%)ZBI%oeSucY)q>`|kVOF6SZUGO6SFyYVH>`TgZ3(d8riOGOmz!BHN` z>$_ql_j&6z*9D_vVrZi7eHjs z2=`8NpXuQbATKV@n1VYIko%2pRsPhpv@`IH z{aXS6VgF!HnL@CoYo#N;$bbnfE<2J`2Mq@f3OW;io4oSx<@rbu5mLtZYOvhhjuAQT;bRyql_y#aE|gWB6w5Qx+^o=()BQ4%|W`|8RqN`N~53$p^e7EJzjBwZQo z_q9ZX3z@wy8slJs(bZiJsE;J9GoC2yHUc}=O3aX*ulCz1P-kX75Wbq3US_mCF zATaJ2&qB}3uN9ync$G|ceM4~-XAGU?bC#{bC^i~{f^eTa*988-c_*>b852!SGB{?` zw-o>khG~R)n1Kn|&+{WuglxFft|c?xBos;~vPi~}XW`rM3KE090qP#^nm}ZzBRqe_ z{v+X~ckkXIX`!&uV!Fr^IMK(pw%-{}v5N64kW?rSz(2kFJQG5lVBvCI2ZDU+k<{TO zNLeOlV2BtQF+#xn{4Het1YmqVAk|p&+PnRybP~Ym21NOY#6r1(D#u}YP;hyydf4p* zv>XL5mh_NM9ho`pyte3&@ka)dl7dfO0_0NPjBm~F7pdfV=Nf#1W`%W`5y@Gbw`|d( z?7y8VsFk%N+DOZpBP!o$Y0lwC14ms?Y4TUq_l4guj^kEwS=Av)4ug8%V>KHrS;F4_U#Puccm>f~ASp5Odkl1Rs*e14IUqklE-mOB%-}N9 zApY3(cpb85CIS69-|AptZZ2S2hq@x>)LO3oxo-;MrGiZITOg4Np&_n_yZ(0b0^$nc zIuPM7KK@j#d+fG~%%{PwmBAEH`B zZp#l#j6ih$8?hmJxq&P-gMPwr(V@p}#4?%sT}$|%lpZ(7$&Uep7OnJ(Dm(bJ&Qe=3 zapn`dLsW}d9I@Exnq4R}cy${UHUQ>94jAW84qs_V9oC8kj3J{6vNdknKhBkeEWu+OGZXqGa+q=62 zGjG*)iyW3vh`QbE_Xio255&OXqCn)OFt?ASc|%SY1QA96HKe({wF8lf4ZS%!aRwEP z)z#JiIAlm+Yien+fOMzd)+K}G&p8l;3|dA6KYRT;RqAdCBT?u4jysHCh<23R%%3Bb z(DjXba<`k$9bWsafdesNa+3w|Tw#`sEFbrT2GyLJi7Bq1bHpcj)?9w?u-y^FweZ{_ z%p7dcX=;sPae(G59X3?L#9wnncj0A$%mbAU38p96L)6BaoY(fTu5{lif{O+r)8ZE4 zIijolVq%v;EFDT8L!#bsjsbz^e%)T1KzGgWrc0O{iQwo=QCZvq);5 zMTA5kvW^Ey?n3z2i?0<>9}pD(FT5cH@B>BQ2jz0P+Von@u4`pwKJM!Q6dMj3zcUx# zXO+7~KRI%upO`+OAP*tA4yS~cUwxd1EP6S>$TtEYtXbYdwv3qA*bDJey#7qHlDpPLzQIhI=YWP{=n%|%8 zvI$YTx_Tc@)FgPbcuj)Ll$3W}FSphc1;I-u4HUmf%3}0wKjtsVL*EE8{dK`Xi}Y;| z8aAxa8axJj9s+B$n#4jUC^8hqyG@eV5sUmsc16OL)5e8`g-S5wDShIL2B;E3?vIn8 zD@HDtzyE#k*W*pw_!V??bhIL9Ij`@$`*r$9iq9yu#jAg5r?vNyIksT3YG2J* z0BWiF7CCfA#?cw3J^#QbuFRJB3@ADH@+`3m8PSoE(lL(2XQUMr2oMtW?Z5P21$Fgv z_Nf8RoNf6^er=V$h4_3@TRC>wwAAhgY7(J4&DnO@ig!G5k-cEkiV>B@DQ$$iQcLm6 z*D@~?FNmWrlDe7vqT>5A%YGtzcT=!zw$f*5dq6t#;DGLEfF?%OsQj{8VLQW_DK4|N zc-NzlYG~;qJ;&Uq+vGn9kUptzQPR**0D=fO>LFF)2XI@xKgJ_YtBpxX(S%-z$O5@U z>Vuk+9oKc-MxGh@ce{}a_q~U+2D;#Exy-HW3Vsw+e2EiBfArto`pvNltgMk&xLhhn z5Ww5MY?YJU#Sv}9sk$j$k4cBL!j=4_cx7Q(pO zxL3$7yo~g4+`V+cmkecYZjMkdP#vdXTc?i4EhgN=XjQgyyh$IVQLaK(o#3Tj(bjfb zW;lEo2E#er9EF8WE`VZZVN%YwZx(!md4tQi|%g6X0 z73!87x5S`G<*`#CfsRT+h81lSwcjp6=3l{mUcP9}+#BOSD#$S;CQeu^Nb3Ef<6fwd z?vO||yPQn)hly^CsJCg@-W(7wkbqPVbub1;GQ$$X7!J*k-A2AdI`Gl?3mkj41`4Z_ z7*}YlSovQudeE{KF{eILcp6|yFVYn+BHsCjJmpz_Zmv8m!W!@_?r909_sea(`%?Z) z=WW@>n-~g)6iD*;Ga^MR)Ry%(@?4I6hs!1N4wna)((_L&qt2k03kTvM<&Vv;Y?Fv+ zb&ZV8>SC!kx}e8%B>M5{%H65z@YBH}x#Eir?DfDL{awnBai&5b0GiC*>qN{mACQ-d z{?{s$HSnkG=xOlyNB)>zP0TzP>;w!2bw$S(o){!Q5ilm8$R;2O*H-qo&QOGz#3T70 zxBW(i11jxVdX(kE^Ejycxvy=l%Aw!@!x#GH+I?4^@l4$mT&BVnR!&vv&}#wcQro2G z=#dkQkqp~IwByA2Q=rf{4MRabZ`PZA_pN~08EqY%sOV^45IUjk&+iix7(Mw!ZO)*h zaGxEEh5DHW{N9Qc-W5s@yvcX)grgYi70Jy&XX3klo(;>)U(dne*%FZQ1`3T!W%5O) zw;-B=>+eSC4VIg1G&|>ZMD5p6pFSO`h)WQQqa!D%g7gw`fT9&ka%IZudst>9Hm>;sjk6xB zRg0#kV-##l)0BF62+*S_dYFcW5VOj`ONGHelg=#G6(1Xm_gVpY^u?uh;0$AsGc1?E zs8G-r<#M!zm5oenqAJ$Bz5M&pVpKwOs0By(bJwp672{Y|#w{&6aiJ#OH{>k4_thJ!s8|niQBRVv zoUClHW>pb$NLM*cjo0!rar$d#?u}g6|E9^Nnp>V(g+jz0s7?1hhXDhf=L9q~_xKz~ zttALi(Sf6|NVP&;>fz&(pu1WE8x4gmCZY-{ze^1|%dhY-Q(|DbulxI`ANFj*!WWltWk&XgpqZLm7UEq@g-!`SQCGOKL{{8gNr#jBTI_%kAk}%4_VO6#w}xYoQy3 z0+3XxCv&oDM_eOGEC5^P`o1)o*7FtoOIN&luqF!Cn-Ud&vL#p6k!a5mSxudpkzA!L znHPC>#vON5KN=mrv?P%ncT@FJ>x2#ZmFbb!hvDj*ZaS)y!oXDS2usg z;8FL)Xnp=^uOf+V3010Zfev8<|sniz)T283B?!I;1AN7<#-gy$gAJjcBy~V zDp(ge?SAN)*^a#)O3YDb{6m>SKb1iLFOFwvK-`$)hA<<`d*ZK;H%e!E=p6fP1z!1R z#IJ5S>e+lQmfP##Clf2x*IkZ^7SkA#ku%*HU6gLFoa!l#`3gXXYb#F34e~lGq_?(9FIO56wAT*^{9c|I{D{$;6ATw}V~d8Rwc$0>5b{)+1da>6me6n3IK#HjK}zLa{Lq*X z%nmP>R7QWn9?CkP8Y5{z&-Md6Z>!t2Nhkyi-{*M6;$5pPS7cLT~IwDBrj_zE}2)_K3#ATFb;F9A<(nJPYO@ zk8cq03bu`M=<^Xw-3KU|<|FV{ihwc|6&DLaJ;<7w{&?`?uY~XBYyQ3V4hc<;3%IJ| zn-O<>`F&s?)db8laG<671m^!&3&6;X9BviZ)_qaNQIp=B?ag3E2+iY3=1$axxysWR zOyMC(7MZymwjs%@gQ)Lo@?~taw`}!k+3>XsVTQ~~&o=IGl6Z&*SjJxVJixYzu=O~r zl$w*{>TlzCuCTsUx_3}Bt16lI_1@I|5#3CV4Fi4sxmb7Ju2LAv;wP_Q_P<~K2y`3% z=aPF-o32c4ifk1)h&O7m#3mlO_k(@^^&>?0$`u!c#s8j{`fgcOP3?|M{bRU|3JeS(DfXQ7K9k5u6C*KXmef2+$77J;RP^$age^7eAnwnu zhTY&*b&|a2=!8jO4I&`*L7g4$elwTagwniYZgEoS8+*hJbwuK$-QAdVQWj#};Ytjr z9J%b4!jh1XU};Q7UTbpqQ0(8`ZbQs&o`DwqcqA)-fQMV?8$t0((zE^wIfZq^3jz60 zwR=LftYd^=L0Kx|+Ov39eFU*l$2U_A8)S8xTRi!QwfR+6X3py+j#besV3CWnzO= zo`;yG>WvF=9qQ7dy^p|yCY#ASl;pzBJu_cX^{x{>@VW;!td{JDXrt9kj?W&T2E|e zq&+(^RI3ZcS}RBkfu$t&)#S{j4bhHJWj!k?S)=V`O(Io-#}LC_FGpP85*aNv9m*Vd zImV$;W?c|bP_nu)YI`QjrF65E%eHLoCQvO7WW_GC)Mp9Ajw|$sbyl!vuduxbUNUJOHn_11@A( z-G}>?+jpMj)-9O1e@H{r`;aPyJREQchQ2`QsF~ZX9{s4DK9PtNiS}dk&m8*|m}Jc# zMntJLCU~n}-PfVV%jWT}qS3p-;to_MojsaZKV6tx}s;l+WF zNESAd!7aLuosO{RcysM|F;Rlq6@UnYmx0`JITe+&ux2F$mQwk@x_=@1K7wF?rfCC` z6Dr?pE(om!M?KQsRrJm#uR-WVIq#qliSOY_x99EL8@M=N1|MyAd)Es6vE#=>X7ycp zN;L&yPg_$*GOesrQ&uRstJI#-Db)PXKv%wcg9d?R=Sf@K3V~le*SR>Q2*(%?;0+Pe zD{Iz4ww%69#`ajp&!5eR5zc-4F|6ET0>J?aSu(ynT*@EW!Fs?1Y$Pz_t{|zzL4iLQ z25LE2^1WKUXM(IvZJ6*5A+W!C;=ceMtr`70|T3WY<-7I`kmU<3F$n z$)ol^sKRM~v-#<6T8AyI&xbb)1Zi@#_G`2)08iNS@LNSBUQW|f3(5OW_x*4ynK4g| zUL|&I^N?i|O?X0jOr*;oB?+PhbXo)@<}B0AYM0&R2QW@gf;bme4b@AXY>>_QDf%-^ zYE|5FT{lJ5LH#KNx5|k7QZ8U$h*IqLpFdpgQjU=oponZ#IM#KHQx4I1ab#9ckvN)BnacMd!iUOnL ztw@t66*u5cW#r>KpQVu`JDaNVIPJ#88;{8Wf}Ytrz?&qtt3Es<;Ule#?cBFtYHXqP zF#kANG-mS!qYufYly_C~Mz`GDkYUEVf1&%1$+`mtrNhXkK^|%^ZfNVPH{aL+ia=-8 z0ifPH#>Pp-`YBnP#_)A9vR8{ZFW*O^j}b!}JQ4_z470IVCk)jj5aJ#L)Fpvy$>zrP zN2agFujEJw-3a6~#)SaU20>+I^LHI>?E>)W!GaM+&>Mn~5`-nX+k@I|;L-pUwXQL) z40-au`AL9_lT-R+9&<1JXNE}v-?_QmIfunwE*KmLrO!kVT>+6=4RC#BVspiMO4Jt1l;B%_(tc=&DxUX})%pddM;^IQ`ACP@<+w)yMB-Ctj zMg?9JTI0pPeRw|5(fxbu`l2)U_rs+oxZo;G{kJyS_a~Nk+K&%g6(S*fMK|rUc(Mwy zM4KeLj4vBY+40`R`uRrv`=Yq=^0bZC&+2zqQi7xP%{%Np8HSIA4RiG#Id-K;+G&$7 z%5bvoU8JG$Xy9%JtoE3smG-OlZoX5#qBo?i%7T0V9(+Y&N$-s}W2zb&pk-)5aA(ZE zBchE$U`E(W+%XFz90GU(B?a2l_fl&IEq(@+zj{bymA<-F@G5`({ZhRPe7C&9c4Nzq zCa`l8oQaFPOm^S~0|G(|jb_m8QiScx7y8Fs%z$MAQ4(Kc$IzCka8T{U^q!n$ z$Pa`)yq+}Fa}s~e@S_2D3|T4iFr~OIR*OJEL(ZCmg9GAxLbfL%83eHJz}_VAFc8^F zjYuXylun?LB6;n}Io2s6SRX@Bb+p+5HNG}+0{2SwKC;CF72XTE@Lb?{xvQ;>tP>-& zdW|&CsU(Q>p84Gsi}Q}p9l3H9{m&%_I@#lEb7H>hq{k-l@5f&7a9rOQO2+vxCuUdB!hrVd>sWew+eH(*86|@Lf8fjZcm41 z8hzL5r?$3y!nPy95V4UC>JY^J2#dDQR7gVOAUFSSXX;I2-4MRGNrDU9UH1s{dM79! z6Eo?4YA3RMXKOY|in4z*4+#pmD5na`i==)ZdNM`%KY#7ra!xF_su;`5*WKsi>B`Na z*gfB1^VI)OmEvY$Z=e*@K##@ZO3B2M9`!?U8 z$%?8FE-CzE14tFynf!^`+ZqHonQ+&Wr#JPt8o+4VYgBAvq>VLxrSN_qToP~ zho31&};5x?kpzQ3CpSDoT<5C1{tRr{q6y zhZ^4qA$_mDeG?Wx!A=i;eG)Tu#~eH%@(B9yZ!Ix1wU)~I#^I8@xk0CO$tPz|FWJxO z)wnGYSN3cq{Jrgio)&agoP@G6^-^L20)+5l+`}!t)tTP{_OeTJ#QfH3DnFVYn(_O* z_oC(E^M^^5H2K=q{V$Qa-7hdr=B=ka&m~zixaHCsAd=c1=iwOGW8dMoe|VmNf(6_3 zaTQbViK@2j}w(d?%pFDg!c|Ed-EaT4c)yqMkz5+`*w+?E6gfXAQpPa3JuJ zvlndkZ;>FJgnynbIVq0kTEOD(az7Y&9TDd8X0l(TSC!I3rJaup%d;ShZy0oLr)0;P zKOH^&Bs4G5fBg~T%Tn!ofzehKvJyK7;X1Ri?ihbo2A+)dH`+p*=u&+Py{PSh#-}PcttU@1 zk!@747bdK~Uk~EKE~j8NiQn*}R|m+?EY>UHUCxofiWkBzAVfuv>`Vk%Y1I4oysFlZ zEG zga~!><|EURZ=zYv7pO@ICk)qb^-poC(okZ;EnMR<=61yv678(C0hDGmG(qdL@!>6h zf!*D#bh@caWNFra^KrHBZ|Qa zfNG6J)t+2VvCjhVpi3bHgcRfomc*<71rUg|jf~V7LWzBeZmU^beTKhCx40nj ziqWzT4;Gl0hpCyLR>jeVUgH_CE-|s9)%PNbBlC!1RG9W9iC;8a76KU+#Pu1Zrw?RZ#dsFs!h0Y1Kk?sFEEM)hudgJqm#j#+p2s|7ud zRw<?nbN%17nSRk>OKUxgMDD<3&G?1de zfDWIHf&2iM6C0r};9iCAYx-vTdWJ^(PH(S=&Fv)v>wb7p{UnF5;pFQ*Pozlvav;2%2*w|5I%J*_ti8WWDz$Ck`x!qY_KX=nKGj~}~t7t|@D?4h4M2^`0!^he7 zm4P{S>_KtsG%Nvo15hk@kBRHG`eUy02M@5=ptPO)H4UJ zKbgp)~y52G<%Pwpiz3Gxpk?wAg?ha89kZuVn0qF+m?(PtgR9Z?Jq`SMMyWv~+^M3El z-m_=V_=6ezaj~wo)^(o8c|`B(9~?Qz;<&t;l6^Oo%!z`+@n;l`{@yP91T#rThD2#Y zju1;X@U{d=*kvbSCaQYxJ!Ks7o;r}liF)} z5(mdbovB)yz)%`q@n640*^uAVJOjU1Ct+)_eGuw{F~*`Xqjk6_FNnh2F(y{*G(bB5 zoQBgu+oA!{I#td z{08Vqp?53T7y!RG?W2w{`V)i#H5{5UAeO))OcnJO1WF@`($4`DlBgB43jkFBB9>SI zh6EZ?i6F=_NHSruYcL7Z*9z+|Q0xe{xIiCsz;|8jZ$7Xn=YykDmz7tY-J+(syV*g4 zt%Zh+I>y8#!e{Hv_0o7KGyMK0=@0B6p!F1yfFlhQbQm93gUTlXwjvSd30S%vt={(z zfN}0e9Rxo=_@78jd<>@Bce@+f)X^SA&(WwJ9I zT=tUk2Ou?GbTM96Ro#Bhin7531?vsxS4De%NVezGL$6-GVq8*Jbn$Hpa)O{$o&tq$G7a) zSDm{S>7rkRH~J7$a;pxsnvj&PAEUPW^#S&vef-eu!kV9-4@GBw7_<-r%C1Xx4pgOa zK?Zq2!asT|hXH}YHdJ+TumJJdszWE?=b)-X3IrcID7p&q1A=6z#|?y}bPntWKrYG$ zw;kX!W6Y-`=eL<~r9u3l5Bgma1aD8u{21MMB9RwPI#K(sDlGYkRkW^f5r$u3U2+A{ zYOJ?gYRVdQcP>_8G%m{6k zi88-qOA;j)o8+_M1!WU8FmeP}c919^Nh{)~;mtl46~4!1TDtt@TdVE~dM`8r76&r1 z%&lyqSyO77z5Ak7PY}`d7PNjKFVARiyvU9=pySQ43^Blbjt!2 zdj3%BKByuL>b(QhD|!3rLSqT8rG@)1ltVibe|OxB9%!G@^>(jM)zvksFb=0G@A?2H#nP#pN`}2B{v3@bUH67V;7=fBy-*xFLROs5W z`U<=T;Qzt~*{u(#q(4@>z#!kb4dn3pba&`#IT?>pf4hhxIW131i%|4u42rKD0bL2%)k9=P1%m3u`KKjP zEg%*UQx0sPp{-DflQ%7UU+D`J+Bq34|Mrwo)1b1O6Q0z-Fj}THbm50yKV8Y8w`D6J z913aC>{A<-7chzwf|3LQsS0ojk%3(f*%n#RbrANQdB@U69^$N$^RqJu1SD8GV6dQQ zflxU}`{#_=3_0Hd3vnSM{O6AX4(;MEcEft&$cK%>Q<)DC>|i*oltqtnc*tU+CQQG~ z?aX@TsvX6n1T?g7=23snUuV`^SuTQB0B=(hsOXNb=^5NaV2{L)rci9= zh!vI(%N*FQv@UJ5cAJ1{YJUkqfJ2D)wuyH`!@|u;h{=hPbLY$HvXKQyz|)&t@*OZj z1Eiw*k#6YuT6XOS&?Q*R*&@pceb%^zqRb#|6ygWyxP;(V6s^Q9-4l6YhgA(2p4jS+ z|E_`nF~b;=e4;HdKcs%&N0N>Jk$;t1@y~Ye@ZY<`S-)S5^|#t{mcp(W)VPKEm6vkd zPb0#3glVV_Gw52Tn|^KwY?#OJ3=-cIqB)TcRm3DM#4z;(=F2FNC9T#?aAOxPaXp%s zo@IA!%l`?nI*1ag=8ratF!x_Z{*cu2{~)~JetUXH6FH*%XZeoL#>P_W{Q+%zp%BE4 zFfdP3ljSA4(Trto^#Y8~Idv4G3wrKe?KvCTtgNN+;0)!H8?Mc*prx4Lmb>pe;$Ev} zeYZC0S!%h>smV!xRk?sJTsT*V|Jz%J1=&Ax+BaJbKi=y^q4X^p{8Fi_Q@i1bjp|cG76zdp(`gr) zZt1-8X059yf1V)vY7x8?J`?-}6eyuWFi?loW2SSHK8x&DV;70lC?u zC3^&_C;@P&GzfzP0M0+hY*qih!25byE!2;-&$~{fUjJSNj6SQtWxAWda^)L+b>N z0+$&m{{2}x?OzhqyT)YpDDWdM*&Usjgn7hVlDGUPaq+d;>bktN?~xN#YOs8C*8jLd zwI}GXd^arkoC_%e_gz)lQsW9~{U>7&MxH0xbuUxkvc6otU%kpd%eu3*f+?Rg3GW8?GdF0C8B#+-eGzRIZK_yHD8 z1!m%3}JY%M&7Snhw8smMul>LIWZHi^wJdi4>;V zA)}Ct688>1pL(S-40%=b_Kfdm;#||0{lz-YhKazbr@udF6ybxVb^n(OfF??*K(A4J zdc9_KSB)osEr#Hh`Y=$XSi>cO$%+?vhpO_L9A*jx_gOK)0thO;B+ z$vt6FPEkIbJ+sQpwRvBU(S$zr^r99ix}Lq5m|usk7d9>_v#v-2{El zkwhrcp~Zg0Y-AJfrzBk5VaIiH#3uIpBVC3!3vcf7_|}mwuZn=~J+(<+4_H(vH5gO~ zQ04o7U3$?CO6KyoXZC>Q7V7V}ZYOXms$vYi6nZa{6C!X?>8=}W?u>Amn3x@wre^XE zR?NW&vFjIeaojF7G6oc|ja8b&l>7bkcNBB7lcxth^OnGnjH_VH1`cOUM50fm(skD| zGg<)-vhy6-(uXZfr}YqJ%_HG~QnP7pZ_ls5smW)hOkha9BIH$Qb_wDT1d5 z!NFeiG}n)Y58)RPVjg4`d!MFY<3qs7;+EwFtrggwUB z^Y&^BZUw1-Em)5VPlUodQCsI^MgHAs4Jj^ol^#u&In7gW8cx~AA{HDRAHjLD6=>;Z zD|kk}5HcLe-}NvWFwe||<gN&$&j1|ZR- z#3jNgmjzW%>rC*s0N4+&aC4a%AWZ(-i^9$^VSf@;#NWTe7Ob~6Voi$Au=@*<; zOR<4t{57`Mv*8Zjn1dD^;TOnQ`nAu`P%vQ%P(q zaaZuD`Ar85v45}-LW-|mYseb?HEfhlzflp5^(rvFp3I^#+h%pGU#%ii}R?fjC{S(%a-CDb-P$wlGlUrLU?MgMrC0X zy`f1n;3PDDDCL*N*%b9LX1^f~y{F$tQfVB^L3T>Uw8Us2q#exuXg z!voQy*;B7Dhx?E|@PfSgtq3Pd=k+gv`m9$t5l(@o`gPcVarl2(!1}=^_hynI%$Y#> zk*F9B7%Jed<533?~{EqG^>nkjnw9vUnYIw2mEH zVp}j21V;v732YS}_U zz^Jp0VlhcT0e#0*Tr%l zHudQ^uz!4J!dR~^N#5vR5ev&EBi@$0FqDn%qX)bfAFffm5S1qq|EdB7ILjZzF*{C! zpNB%aFv}v$x{4o7a7Y8*q-N#94=eT&FN*b5KeWq z3yFx!i_-C6YFNkt)pP|QMSVqpqx9+&qLzm}C4YXp`+)0RxW~mwQ4XoDZtqVY8O5FQ z8>7qZ4}4)`=V%jC-_-W{3Mr`2&@sLs@ii@VxAy$P!c@fa5t;U$XaEJQdNeb>>Q*yE zvc@ZAU*X1NgpzK=O<5v1eAAR`#H5-ZDgCTu8}VLr#+r0Q!neCx49I%@0s>-~Pau8i zvdr&gnUeuM;y<61wuiH4)8nPig{DETm6)S56-Sbl^$+p5^e#9;DvQ6AtF3fWxx_=% z+=gEi79O~#GCFq(crtjqC>k@o;IQD9vZ$XJK1fr0gUKBdjFRG?tZQ69%44e>!b78S zxR}WwwnZ~Mm25NDRCylqdy`hX=13?0;a)g~e4**brS4!2i}!=~N(vA~g@8Th2h`U0 zH(veEPITj*uo5mmK07KO*t3I^V|G>&jBr4h$oE^Zfz!9Txh_H!E zc>#YushhD^C6_Hf9F5Mo)${`Eu~$N$_{w$Y!J+`I!itATzxw&d2R5!zZXw)97W#)s z4cWhlPJf)qk=N+4SY%X3hO{F@GRhOy)*d2K9T`_tXs$MEFR$Ay`tQH9-X?xh3dn(ghy$L(o5D&wv%z0f-whR1?jlj4iil-HVoAKLw$Y7 zaxrX)#Gw}k#_qjB%N;|&=vyv0Ch^fP{7csU>~ww9L_x`5>mt9QGru4NHGNsP%}#{W z1&RG>n^thf#Zl@QUHE!pCpKCBdlI*hBqi}*9B$s#(yw#Ysig?^GTI0d71Emq)SbOb z8wiEs6by!f2O`e1o&rLAU31kJ^Yfc%+K5cJ0TXsA?-A+pi)xd~7tXlN3TCAzym{kB zI&Q;S2>-!GPTi00{knM&)okNyv^Ek6%IcMiMIgMg820H0m z)|Qm8#Xy<>RUe1GSBfQ(n$fCk8nU`JP0h^(V{;>3+uT57{L1feq2B3eQ6O%WnS!-W z^Y4@ivSiUa`|=X|!RY{u>6=j`(LU-NUwA*U+ua;4kB`5M?wRnxj@je-npWyRM|?7g z+(94OtyUkOjsEy>)vh{a5Dr$v)I{C0b8OOpkupM58}g=^_g7tAjf=P8@IrQ48sk6j z&ch|;eUs;#!u#3%I!VI) z+U_pb5NPz##J_o)sRnXzw7y>$2zMuXr78Zn zxi@ocGoxWf(c*4N8FC+!`Z20RbB_|Og5?v~c`FMf>~19NqSbWD1L@T?MErkLl-jj&-1Z5($akd=~4|DNlCb|9dh<`CF9T@cwS) zWFzN+|M;Hq3r~`^KTBU6SQP$|oOTg!mBS)r_y8{HA;(289As%6XFA+eXrT9 ztLGg*WCNGceiC19<@9)?M|rN@dU~wN>O9qlIC#FEk<<~EK)KeVsjgrCRD z>t>GYb#KP9{NM$(DBRkx=pVn2j<7?Q5#|~HaFJ2N28)&{g5FQKo>Sf>b`nrfbsxCg z$7`gp&Cp<3Wtms=6fUiBByA>ir%uhsetG#xFpxT#DoszrAScv0xPd?G->+ALnnxX8 z0jjNm!e@=+H^Z*2oluWnuuQ-!3k^C#gxZd#WY#caA)9D#?Dlzj01xDoj%Lw55%Sg$ zvHPx^(~TVA-qroKt?@0T(qlbilpdXF)9F5Ki^;)UNIK(GiyRwsgz#em*Mb&-OaONeN z<6HTun(Qs-g;f@9#Hi=)8j{W>EkEi%(NK_+`*FY@k{yQn1B;?X|p zEkWED?6G>u(=R4twTYYRR~P$-Edr+fDP@c5@kdyR&L!Ms8tKf}>VRN|f)rIKnZwef zZKc=X029(F0XSFQ-rmBOlj=~?sMpocobHX&Z!N<9xrKYFDW10^Ki+9*bW>xB{Xsfz zdgUjy;za*^y6DTI1daxcibC0@KIG$9Hi_BRJbdYKc-(y$+4AR<_9D_pIPB`S`qPLDWzjbv;A>9r<-!MU1GCcBAazwcY78gmfJ_(g_WejegiF5RY zCD3z;VtyhabtnJv`Pp!B1iChrGlMfvF7C;j19}Ke>dT5%nN^eJU3E>m|1Hu>%95*M zy%d3m=|OAul1^9Gblx2THE)k4{`t3_%HP30V2(0= zYNx`^R8srHtmX|Xp%5=G+<#_w+NGMgKQ9o}s`I9x(*pPi-69Nx^s;Z<}xr@W@<$6HeD0!b^@lAn{Wp(ZL-odvK zOc&pr>?pK=8DXT+Zs1yBebb|b9awa zwV<1y5*4MNZnz(C;M7>bE$o%c@G1PqC(69En3W0hgjFYglHb5Gdh9p`lqX;!2Xiyq zE83&3D$;$l)a(un3II02cy}jy;*TlaCi+>B=61njjazVXa2GzBf;aN*nh3 zXP>$^YZWXb(?iYP4*lS7rG<=dBCpY;rB@;g(v!WlOzfC3_ueL-4D`1;E4lq-T&dM5 ze@U8v6VZ+HsDmu(Pa)t4wqt_goK~N+Zbf0d=fDC3ZH|tkszL861%K9l)tnAkH4`(# zO}>srb+O>(Ww_JlF?rd{KtRp>|*Uj6Y^~~2d zX~*}<>&?Os8tDL4iizcE1d7dUaSC}fcS*a_7h^iR-mjc%8_Q;B_WA*kd$ zpp1Z)Z-7Wi*E{RYho{ScnoJH%t6q?jz5(=mk{@|f*4luCQD7nKzM41U`0tk>b+1xV z8I$l1vSQ3t9ov|zDg{>IS4YXC<(bx!Gi#~_iwEq+5_+l|p4BUO%kQeHCsx~Hzs^^b zx?10rR_Ne6d2Zm;u;L?1>HodfieJRY{rFVyc2{4gUEK6juqVnrf&OON@_ILx{C;e2AM$H*#58id5r2Os zkQHa(r8t&ybUTb-9?!XQU+UIjQLFQrp9Bo+o*cJJIXz5cOrznej#7xhZ%MaIl3+^c(ti(2KlX z1GRfuu&Ai+B>k#=@^bW4F2B=U<8^Id-kc&mxP7$vR$76dU-_cy198=yV71OGB4WX} zlUx!KpF>smCCW-5R*4!&zpaFawxb2h9BI6GckUcLj) zv!jp5$?O^*o&G|ii()4{=V~gPNS{xldbOKBvWjGQ+?=$KudU_)p^|W zR6f27xSR9>KZ8L)+WN0PU07J|+1)+MzDPq^)&|%imYG6DAg|3KU+eS1HAlwZOhNDP z5b|4LwSZ;50OW0lRPB)kqwalcc9~op(8o3`YRRmKfX@YR%L+wNDY)zCSAeO|sqfQG}U2B!c?R+FE;V5!r9f ztY`lmbxezYcx6W2wns*PEaFRTwq)Nbk+1+bw{HAW5u;yYIqbORm7$G*oH4v|J>yj25 zwU~fJFlSTu%lDXB=R|-c`WLt=NyL0I7wnp&04sq+A)bhow5XVF{8a%?un{tR{|Dpp z5vCR`4Gjc8r^SBuXV*ABy~DSe?}rOo-OZEX5Z$cDF#n&^6&{b|VPp^m^VMRbeq?-?Up zxc5Prpz8EA?|4g7L?Dt+`qir|NBX%9KHV2M@B=ooD#d`tP_0wS^mBszA~s`sRx`%yB6`5RF(u-Z+kM`vc_fYTi`ODX5^z~UCPQVAtf;fzfIe-eiAmUyEvFk0OC z3l4pD;mFsO4Bg-p#)9xL)U|YbFaA2SDY3r#Rm=O^_9I{3FM0akCnH|&W9Ak88I2uR zIYfoCuMJP_E4Jk`hd&J4Cv)ee*3f9Hm3V(4BphL{tXb^m!I63S?xQ0n*E6YxsAl)^ z^_lVhwks^h&GhoE1aX?!Y)Q?cYyM8J^t0J_$?(R*!i5-ml3dwW*vEO0_ejn`I|%yU zdygX*V(>7GGVK=#F*-Bp#r4zG-3GswvCdoSuwxIrH{|Tw5sy}^n3oSx9<(;MvnZvm?oOW@TjLx4gXk`=IT8Yzznt=DK@+kkF#~a!53n!l>1sF&% z6n6Ybh)r6|>{b2bEe+Q*_^&bbm>2%nYKnMS=AV7`XKRQQ#Z^xByaRf0yChnS#zvgP zEAW#EJJu*RvUKzkd8+oWAuHE^ZLheqyRVgk%(TPCjAU1S5hsYf@L@;Skk#ZR8q<3D zp*r6`LY<7w6E7yR(TZoed*Rw`5k9bg%e-jA#n8g-MvzaJ9>TZKl)7&oM_*|0^fo-+ zi#9h|vK(yJzM}SiMOSWY+x~&H37KTiTNV{Igk;6@4wJEZASabjp3}33L&R+ ztTZ>`wK1P zug@423s~>jz{dw-@-0}LB2?ndA*s*)*6pN$J0~w;kELI3p+tc{RxanihSb#@qK_u( z{>-r-j3>Exsf|Yi$Wzh$i{|Bd)ubUz(%Mve2u2(q@(uTYMIeOpw5djEMo8dlr^uof zpx=%nwh+Nh>`Fd$EnsYx2zF@cOL_DDZTw#@z+<9C|De|tucdyR7QT9V_l~Lsq+T~6 zc~`0b?+cg$l+LLL`1E;Bo{H^!t@ZrZT}(f-H3(SC&~pa5A**4Lr#!Cs=tZJ-oE&Dr=m8sDtsbD(6vO{{Ut%Xp-ym{%MY!VcdU{f^8uq3 zY^8cRwhy%_r}XDbMapj#Km5})(Onv{$9#DIA0CARa0um)mJr67t@y0i3=G~ch}(b? zh{8jRj3|+@`Rro=UW7VCR>a_E+=)#gQjS7NQPVsYE7Da1^)ns{te{b=I(f(KAw0}B zTRun@-%}=1VIH$Wx4e|)u^hGhH6~&WQF+gyXelM?Y)l?Z3vbwJ*|@qkl#wy#NKxGt z)mEVp-;h7%K>OxGn+1m;BFNL=Y>Vpt!H3+Z4O3Wd?cm+_g=rkSV?=ugi3?sLZGCgB ze0C`Ux~S}rpkU@%nwj{C04b~0?4C+`4YE}QVP3BkMb{Lng^QF-^v})`y(#(0(v_qp zDdEvcxoGzqTtfnv?7tQc#~!r=!=zV$2F`TA?GR*q)o0}8n=Sm_NQjU9u5s{Pc z$cf!y3%MR`0`I|(;1ekfB7G26D#c?}1xZMMR82eW%KuyTH1xWO@Ve-{h5+PGxVJkj z;;Vsy!uj}jIv;gHg{5HpbvAv#*PwDascVTt%aoQq{J6lc@b>J&W|t7x2?16j5yKPn za{40}9;BFCtA=%a>oodd?9vk>3->Vrqk!?}ll!(c^?UZhjN%VB2}J2LP9EZw^3NKS zc{6EL^_)|x(pPQ%#@(nTee9gc79in8*`%CYnu$2?LpFTpA zLiS3VCC-#HjmE3>q44e_d*q+5?>;Uxm)hwL{vv1d2xOGWDdcT8duZcBPz1psNHeuB^;gG4`$3nT&QG6^P_GbO9`dSHA>t=hHuKzVV*F z#e~4+CIwI+poFx@6N^}01bzAF%ycc9r0#WQ;TJZ=`z!mJM&(LE`l3H)L*1KBUHYuQ zwACwA^za7d_Xa(3y({;`@=&dKYQhs1DIIP!|Cp;WpSYV0b6zkX&kTEhR%W03b5eBX zQ9@D9(6oSLW=$L8_t667h`g`+4i?rdjk{BV=rF>w+#;_D+YmF zFJQtHmw$8)tQDa?wl6R+)O2+Rp@1!{zqssvgU2NkA-e$$7IIhj+s zBL?cVI(`LA$X#>NXpCY#^-LAe`x2v*-?fL_3=p>c88NtdX^)P1x~Q776SdOzu24gZ zP;qkYy_M5<%yMWZjoyDxvPzm|OaaQFU2{xQH4V)v@9N9SvTf0}kG>xq_KIi7{D zy!s=AOS6l&Jkic*BmwfPnLOTI%hDcS z<4*coLq)j+_Lr#2%)~Gaj&_M}s~$p%@Zjn_<3Z?;=Dr+>O^VfkkIFa6JPGH<0fFt{@--Xa|lX;NIa}U@+g@ z=r44h-E;0y{+c94;YgM;AARQ4q{rqZN)Bu$fLs8MgNLUJL|UEmMgGzQLf1tQ^C-Ug zFd#rjbanGiy1t&|6%AQ_CA)!+dlfvE_QmpYe$o|w z@u$y6sgBUj2^mpIm@s0e%@|{<4tiXSTjUV0cXK5Zy{%7)6iiRQ#J})|YNF<&xsS=? zX#7m!xGfH+yIwz?e90Z}sc0RVUzPiY&u`)Mjf+a7siiin?a zib`Y3aq1V2@65tjRCt^J92R>C7e4(!(7YqQ*Vz}SbOa6#ZuZdS?{=S45KB`wm?Q5# z4#*tzn^E7GCFX;%#^}PrE9x9I+mW4fnTeRQ#x}28F1vb9Z4^<^9RQmVKY8sV@TwtL z)Ni(ORJq1>oCOPZxSuSn_%bG*<}@c4ceupAloktn(B8c#5*hRTOpPowN}$1I76h*p8&vHBNVSbyb^fRW1Y>J8X@1~8dvpc>t;?t7pIUIP8t8k9O6buG!|FbZ0NLB~l zho08#MY-}UeIjWB_My(bh~SzzL89Um@}o#q-Ya^>p)9#InRz7HQFx%$tg0ZBRO%A7DgcigPhY6&#Q=z1ShFr26Sv1$O zlXrX#D8azY71uAu`@j@BOaee=1`@efY}!jsS%X}*FvL&qwY1K=N4(=Om%qIBy`1sw zj`2Ms!94H~&q83sbzbgbub|B$F~v&c24BJdi|81osr3i);N-pDKfwuoxko6}qAm{Y}ey#6LjpP>*S+A`q!4r*jyU0=(Q z+bf|o-Y_=1G(&UQyYzC{$Fw*DM%Emv>{mo`spaEo&F>7OMhsJ8wh&RaXvbu zyknAtLR#^P$KB^k$37{*_@~5Ij~=ndgXmL%&0_E03y~ z8*jkDPx=2tsWXYr-oCG3ZmkISN=I%F4|+|I2v_iokU$(k8(W9KNUP{sqxFFO_Mi6SIT}>o-=A)nnF1o%+R=y>{diRfE%b+4&o9!^E zz7f2P!W}l;F|8|LXi*Dl&`ASX+5a!He0uM6%t(dB(*1o}12VgC==D5zY|NJ?@Z}B< zQ|!#0M&V*n9j^TK=NwXn5G*fqdGO))i-kUWLFckmNQ@+K;(R1uio5E=NAb?%Sg zg6C#ibbL*Caak2WJLn>jc%;dtbUBewl#TVJD8z9V5$_|84P(A?()Ri6IOCkgGT&4q z+oz5l2mWuBl{=uE1yop5D5=S|eyIm4x(3g1aRDH;lB*hceC37jeL)S?r<}5HWIPVM zFZT_*_wieBG`4U!(E2pw5WWq4*>R_+6beCUBM7HYV3oO;2Dc^nPUIGHG_9uR?;H=X zJjFS&N{p;-1-v_L+bB~K-uY6#Pq}LQ@w)BV=qVnDG}cJ}=2jPvQ0Y8{@ch=XG2wgf za@f#a5F9@f0{9E%+C=$tc9mvxROMU4sgp+G-g)T$W8vkkSCavif7l@JOHwwq(2X!L z*Hd*D^(6yF#6g`C7<2XP3}ny`f%ujfgUXVhKYy+l?|N8#<6|MMnvHY`w? z@^fbx2leZuK{5qOLaV^Vy!AFugt-ot_72->hJ#8r-1v@DY+zB43@qMG&sd}Xv)kSm zy@{{hPB|m5*XXYQ%qXEmZb|2_utzCnzUnYZC(hWNo9#?eN||d0vS-bM{z!H&cgmsW z$!?J~c}>P`fj%yFqz!v|c@?hyluDGQ;C5#_aL!wwli(|Pi}6*{xwF$Q>MLWt9Oo)n z?&`SyG(VKUysOhaV)&YU<{66bF>s7fr1Cu|%}c*1R5YU;H^Y|n*mFfEmjk32at+l3 z1#cp5-qymx;nl7?c+pxIoxEz43ON4a;xDGL@Dl&$!>@H{j+~r(cRdwHv%<(PoL97` zcBeYh^oLa`7Jh3Xwf?z-mBigU=)9ytefRb4UYj?LS>Rju0B1{UoAs;(`<*Rs&ql|~ z@cBVTqKVU|8@mXYu7PHh-$X0EO(hVOI{?2_6M7aZ?{~) zr@h;C`mTIjB-IFrUPqT#72Ve5tn*Dt@%Er)99Uo;ahgMIbtJB!#QLTHY8&pI;qNUk zByjkA>~XzR4>gc$iasrQ0F1e(Uma|B844^s|Lmv?@V8XBHKwrE?7lI?@bbvBgfNf&>W<-i7L`tfFa|RQWQ0_!x)AayERYWPa zzVCdUtBjBXW?WkXPCKp=5+}nRoLU)E20b-0h1c)_e@1J4MCj$-I3C{d)}~NlA*0HV z^r&3e9AMKn(gux`bnGOwO;EU&>MA}YSqB`e>7wJ7eS)~1Z-3Mo@dWtUJ9mw=xF0rJ z1l|eSPxD$HZ9iHCH_o+YMs>IZl^AT-M} zzhADA-LPh*qXyRtuz&9EJfcYi^1*uzh?o8E*(mOgP~ZpQ8dsLDeJ|j^)2V zAx@fk(Ta21c3xB$I=kSw%4NU2_%|6YrEyZTv#2h;Cc!IK?}C@_YnqFa0PUSop3Qas z@&Ml>s3SBlwsGP3Ya|&j*3HR~^XMs;F-JjUFGYU6R_{c* z+prOb{chgIm?wz;c+$~WxLM(RfM?~a?$NfSt;oW~PQyE~f#z*0lvi=vN|9=d{R%A2 zORZ*&JH z67$s{O*j<9-Sn0?Ozpe=KbY+rh7Fg6io5;smG9NOpnb}9SC!B+_T>!t=LU`97UqxcwMc&x2$fkJX$YP`CWo|oqVP@zqEZ7n@02a6fn51 ztYL~zc&TY=8`Yv8keJT`M{UR++6JQP2ziOKIi;7+F1}I~ANQP?Y|x{LeTem`xK;o6 zeZ;`I|7Pd-xU{rGos{|bp;%CO3eA47XL|ab5HIPYsL@~BmBtDY!n@)MHQdOHGLhn` zZI-)r&-4BSmwHeltr16JtTOEI7*Yw;C;nCnW;xtk7#zC&`nQZFF(yj#?e2vEm6@@5 z{XzuY?dId}lRqOSiY~ZupTb8z?sr++hWfD5BTsbiIoALyf*^%faAu%)49k$C;&CaX ztTeHu`MaAR-k$GaL{w5ix}-%Kq@_RN}@wX~~PYj-n${MZ;TC8|#;?$5`xwz0@GFcBL&zZU~| zQSq65ebhLtKf|Q*rF#2iu!pG?0j&3N6`M4A0Spj!n>Y=w%{Fk>%_C z{;F5KFk__mIgU*JgpDD#C-z=XUt&B*6VPNf9m03TX4+g4cK=cI@Se1IBVD7}_{fp1 z-DSn5YpHY7Y0Y_hlUl@d^~JC5(pd=29V=*@GiMNx%l-+usn&_b5dQeId%~LKO(F}i z-4p7@tD~Bd>D^!;CzD%L#M)b;40>9A5mibZL=lcfosRGl{O)^)Ef$bYv%lHU#NwJw z7wwDk{ELSn3ObXIt*+Vn#DzqW2O;&9zC(;hHu|)R9*|ajBYR z&0@ZtiM9$iq0ob;da-IISP1cGC{k$Cs4uMN{;o~nsa1-ylfT5HR$5c`>3KdoHfPYU zbwG^OUa+TuT2yI%7|&H6!XikRQ2kEv{8tL&HV59tOhK#=e4{iyZlXh{lCBOLv7UXc zI9|DcXY-Em51+`N8YIvBy0j|Jdd&-3eb#1H-O^u9NBlDH4sxjiQG8a#CsE=5wU<*} zbYoIo1j+`aKm1bWE_d+AwkH0Q&rqTcjzx;$4zG7dZNjifFH0|WbTwpE=JQ$N;vqVk zs@n*Ehfi~9VQ!pF@96bOK~PXq=G88e`TJ-125LVB6BUw#(VZoqJ1Nl7u6jy z?}uW^?-^|}4@|m>wN@t z9$3X;y7EvXUsSEV9J(*j;Ua$G70bP1xw@dI2k>tJ8^mze{IH3mRi`AGkLO*A8QdsH z{=BQn4F~my$)|eM`jo060;jeUEMNuMEN?2R?I?eFMV{jcH~bt^LK(uMQKndqANQ8B%xFJGNTK0QYiPUJav{fM(Jfn-q|YpN1Eb3I z{T)LC;7U`f)7djW&EkBXF>N1sKR<~xyMH4);6rG zGJJ4;USC+~LfoOaTq+yp3;6ljXO3UxFtD8Z#) z(S8j2^>?~byh|EoRcVl#RtYgMKh-3wzzaJ*;A9#-QA|}jbyM4^pnU~p)ZKfxv;XDD zszvsP9ot=D7|g5NDdoCK7Qwp{g)%Mk3c2B!+MfTY=D{8S@kS zNDPOxUc-`{a7!khBToZxYzGIwyYstVnCv$wM|uAK&65c_vo~bTc1vd*`4fpL@|Bw> zt+$nBYMfS*>RG^5++HLHc=jsQg}6uY0bVV_3a&&$QlQ=#D0f!pb>ji}Rr=Yy4uk58 zY3$#tIX#a}`ThMw@w1f1El42Qk^f>oQ_-EE1ATeahw$@;Fu+V080|SpDZEhKl7C;)Xf?3Lp+rg~zy3godeI|;SE8(zfm2hP-)A4dc z9})5}@w{0CZ3zQjU=~7sx>>W}`Ff&O)@*Dh0<%~o%=Y>XTm(V(r1vR+S7tK3BLuSg z2NrAFnMP+5Sbj0oMfo4ynABhtJAD^vcTix77V}X2F}%3~qGVmwQYOWDwKTz(?#g?h z4D0AZxEVRZpO`%q4FPi3;mz#$z{!9ei&7gr3FKv4=zIMaLN*VSo_kqi zJud_(_EBM@9=)})VghaXqIbD$_I4su^`!c39cxs0`??Aqp?d3dlTmQI|Vods9MS`URBIZ*8|hKXi^ zoMKf92t2m5wCFGljeu5gr8j_Atme2+0MW+g^{2Jfcd7@6mQok(&2Uc3=n$D>O?g@r zg9ZGDkK$)P#l1$spf2;k?#8iAKCKgjU_eUtEqW_1&wOZK>s2^*-HRc~M)kDM`eMuQ zz;7icOwXH&=`dtWGtwVBWx0m~R`%jF`9Q1So}K+9B~AZ3 zfOj8Joijd}-7rXS>;4m1Ne#^jP1Rd{YK)h^d?FUH0}DHw%qIB8%0h7Cg|j(Im*zXI*)!9*M;U35tv*- zjgu4U4W@!vA64j}OQHI3{ep8fPyHF?S80r zeuF^VR*&jgFWe={4AbLM)S%C@ydHY%z&C0pvi*mf0+TUohx0-QG;<)oWTI+t@0!NP zUBwQy9)@&>&td?0l6Sl6{ngQ|*D39t=`JA@;XwN#u29EMqvmIrQ_vg_GqPj`;}4= z5Ohk@f~}*c6c>j9sSw{ab?jVf$L^{gm-C%ZuN0g==28kbrq5a_ynv<o#cIE}K0HA>dZA3K5TD^9yvE0Y zNtV@AvDOerzmzGRtiYgZ+9+!;4|-kN83cpIMs7tHEHI7Ohg>|@s+rf#({nxg_6cnN z(z(7B7d0^C910>}IoSQKtTShYOQJbJW;fHy%qICUA1YgFmgH(3r_6%9$xMd9o zS*V_wGrs-_9n<8f{}Ihjsfp(sGENJ^PU$0ZuJ?=`wy&9s;SfK{k0P})%(J?TsHzH3 z#L7uhske6~C2VJJs)ETQHerdBjLaC|k2|}1|!gT?@0iq7R2{=_2+dbTWe;32q9x9_1uc~Kh z+jeN9E9Yak!YFzygb{ACx+m{Uhn-~A4>BX>WZy5fMZEe!Pn(oN#^<~h30kXB8GV2l z=?^d|p|n=NF0_y1p!m}@64z_hH+kfDpzJYSg9Bgj>sfl(kzqlgt(o|Tc2b7fkV51< zA>Mc=tN^^UXWzTwhA%Ij-m!5PIikpAM#%(HG#ysT$HI0jI}|@%F7gtbu4?l_{n+$x zayNSDrDPcQmHxh-)qzOTVUBB}f86NGtm$T`>poV0n#M*hqj1oceg0fpaCP;E6zyRo z3@z6kEpFyyCpSJ6ff zj69RNe#gc0kDpv-B$>vPeTdu2vWiSC7+K{6lT#r4nE=H8)bCaI(u$2ylCOOaI=rtt z0M$CHZf#_A>%(8|xXdEr9*UHmiGW5CFqLdc{DE ziSy8nLI;#Ue1cY*%dcf8f-YHYsrff+x()4ik88&aaST2b5lx-=CvtTJ#)`j5Cd(H| z*8$5{C+S`!dEJdx*F~EQsdK=CO5j6sWh}S1w?CE`J~9KOntFO@bQOmUwL_W0KpM zBxK#{EJG5USWdPatEvpqDpa^Ve6|>cRP)`~P2?hI5551wb_@qgFL(b0%eug}dgy8O z_abY-qw3^qnwu_HrAGZ@$n&*K7cV$*fC7fw(*N2h`zIlf%Gl_sTj#^}XccIn9#pqN@~NzSQs>I7);t|*zCdQ>Ojm_5?+1Oj&6?v32cIag%3@VlM|CMU z(Gb2~+m5WpD`o=OuDU?EoD8E6)Y<3Zz1z?~N)#3oGo0iqqAMnmDyT`Y1lcyGo4IDfN^~|0;O0 zDq!x?gg(I!)@;RYdf|_VPwu+9>l@fZ#a8JvlkgVV>UI~V;p|_fHp~mLhTaG#Zw-@hjPWjV-0OCQ~^l8>@jk?`};#Kc5QHxmP9>B>Ix-qXl$$`>L}g&laEGK(?En+ zrwyKhgUT2MhQv9zxuecRYPm?{Rd=MrX=#&Fj0ZwqNb-8b)SS{p zI%@L`_z!*$>IZ$a%BakZBJP(11@!OjtS~4G z^q5RK<~SA?{)3@OM>xYebAUA zsXvc4NdF2Sx%NZB9slDUBim0H6@+%i$mCg3dU5m(NSfOPG5L(LCtdsHfh?B<@{@G& zaELb{6GBM}zGVwJ7x}T+W)}p9_@w>n{T(JlQS_^@ex}Uq8ITt4+`7%Ay*yFKRyjqh z04-tnty(wjG>sP#v}pOG-C+6=)bXbYbqO&ak7}j;vr=#m(15mOfp%3W8+20^vMH-? zxIfo$-z@^`@smu)u@HXO^$F1?8mHVE`mqmVT)p(P$#3N$ z+l4Wb1OcR=2J~60&`m?lNN}IJ-i1kJ(b66#5zZ6@kMJU=x%JDV25pyM6nsdpg&~Cv zZ%wkzlN^R$Z+Z~x$X{RnfvLAjh-@uKvV|i*n)?P2r0{3WZi>*ycwJzD4Pg^b@g59M zk;>?S@w&c(a6O-H@xmjWpv9TJ6u-uP~!&@V!7YMz@9b{Wi7Y6ak0oZS8{R zM;}0aufqz9xmB@jP;YpL0m`7`u>a{ul3_Ag;kwd|yp)aQ*a zhNwT1pjEj(O!=%YYekN$g%#lR>-DHwxbNhXilk0wL^y=|BIi%?kxSdHjdk1|L@hnF zgzqSc4Yw;>ghU#(W=EUP+-0CB*0gM2@T{h%-l7s`Z|C8wA4w1(_N`es7PwQD1-{+C zou_&{D$rG<7bGMyOjKj@^I@~LihQ~}^PLXQUYUEa>36I-@o$12-oBhp7tf=c9Tx#m zL3lZ+@k*5t0v>=xz%X_J*$V!qahrX9v+peeCW(BpJ^!;e{Pz2TJ(yLzmn!#LVN!wU zQ3w}5JC78&gz|O6Gf^m-c34;jeUn|hE?M!^Paf!un5U)n^CvfSs-0vqT^I)0|q4tdEB5^e3UmN#&GIEk8*B=-VD~<_4cr5C1iq7$B=q=p9 z#^x`_ssLI0KQSFD3RtHSB@o|H6uBwS8OvdxQL$y!uMa*B#vRYN+-Dj3Q#BWNawL9( zFb4L;QGa1mp8f2BJxCn{iWr|N$hZ}IYLdn+hgsbe@cJWxvKnsv>cbC{us|_>mVTm> zYdsu~-?b@-=bG6=LbWrm&g`-UA?ecL;Ds3;OZxcC1@u0od*8St-8a_gmAo)Yj1_Uj z8p5fTbhDwDyGnl5I`qh=oB>Sly45`KW9pAm`HYC3P{`)=fE)A0VF2V#@Ny%4(B>&7 zrnomNLUa^m9z;N@q(!L^gK^->MQ)cx0`C^k@3%>bt@;Kqi!SG8Ck0wOqtSb){?s9_ zfBh5(^RaBDuZH(*0GNp#ka1K!+bq6%o&|>A`x{$?;{On7=~?xZyZjOGdx$t>RUzK0Fq>#3lL`)&#LmiB@X zCiffydPIQ%)kpr$qW(4Wtr-=5d+P->e=x>0lw#{iiHJJ+y6EkOH=QKCy%2K8xi9Y# za?2KO&=46;D|~wxcD(1>Shuka-lBhYghvQQSpf~U8z7H1Y)$$JiIR9l#E9^MUT(v4 z{zj;HZgvXMZGIOneAgk9*jf?yG9ycBhz|CSEH-j?jq&1bA{=5{<`3$A!?svn`W{RJ zA<1ufy%GkpTtU5kmOTi1hOYePFP|7qYW$prQy2aHh5NDKIe#@5FucipQ6tTIjy~+I zxW}X^^%)qNdOkPXx)S0|ui0eL7G13+jr4QxllR^k_xaktFQ~*)!#?zW*c1=vJdzX` zvR1P;t4V$A&m5<7`QoH+5zno}904^6F>H5iY)n!_vVcHAi&<`bltWh|fJf*3sWthO z68QtMoq+6GmP;J=kyVIw8|&mOt+X}f`)()R6W`a2lcS-@O(!jl52;sc?*`$~+g8C` zMWl>XSr*Sa1G*W)ZG0a;YorfuHAl6JhOU!RIH_4@Ym z=Y{H|uQlPn6gGH=d#R5yK9BUoZZ$x=xXk7VeZ20yrU;pF>+p~L$*aM;rAOwc2G@;V ze*1TI7_)YLIJLc@n~k^O0~GwIb~ays`mSAbU7Eq(Q_Cw6tr%-ksU!#q@fua|&^Ex8 zR%_af`;&x#R0b$fNP2sF>-A^X7k>Tvb)y5oubguMjA+6EEq?%Q;mCw@b5?h6Z!cp3 z7-0P8#8MuE%1jU|?l<0OicI!|ma4fxZzyyqm2@(VR7mIdJ2Fe^5B1@*FQpAV-~4SQ zCv_X|e>QMDB`x@{q@R2Zhmffenvms9+|D^5Q!S~uJ?^b|y3eXou`e12d!ru7e- zni#$LYpEUM-!*}mj+mf@iFiIFyj`>567fQr&3IN$l6BXqa7qf}xH%w=@o(pYbP(Sr zKVW)DGg^N>Mdba7$VWu@?Zw{?)WX?7@R8u&ca)28g7W2I^Z8o2gJIsKtExKo+jD)w zO{t!EQB2Jolp~hZNKIy}lk-OUOi%z(T!qfJC80BeA&^NBs=Vduh1r1yMI&1MmscMo z4o1hv^P?94+l5bQn?UpN{6w2sAaYup? zuJ>&-U_Rw^k})`d_jrXuYe0jv=D3@v>ZS>~isHxF3g_%GS?#*Qb2yc64$Ec*E_@C;+=q4CX-Iv$9HC+YjEtYv|KI zMJPJMi+|?bB^HM*ac)hnJToldQ8xRvQ7_%I$=e)!2Nl_^d;Bi_0ao>1d3qv-A^$41 z_0U%oqdN%GnWFc%n#8&Tb9snoQ}g;uGq>>(3x6>+okx(n3(Bm!Ga?e`O2XCcDXX0K zZ5iSrUca5s&MV{YUQil1zBAjOTaIVlxe04@uo@bA`CtlJe)v-j9=iJ55>!26w}<`# zL9f{!uJQEsk=2&*@l-j6+M3x8+nA|T(cFfnD3GcA*fhvO(kk?U9#+CYEHCe^=!#((zX*nzzBr&8nV@t zl-{bVN0Y!A)S!oMFRIz&6+N}zd}CaQm_I_Nx_m)Jxv+do3S!4x4 zcC30YvUBh6MWg+jb@a-vP=c0Z0jXmNbuy7_`Y4f_1m9ATh|6xsRxwFeL|GrZ;O3ir zJ)4z>PfJf%qy*z(Mi4Iyw8m@BHGI2)>rQKSQucX-mRwQGrjrb5{&xnG&;FzQ1+zS} zwY8ia&^fnCa#u+~n5{VjDJ1=4(_s38QYu?FM#S}P#@Be83A7ZOvuw<9Ta^b#-^kZ->8=T3(ALC-yrtw29jYr^l?0oeR>r-*`vndCh8z7(A~w z$Vl$LJ)yWhyU_|aoo(sg``fl5&_-Vj@2iBq&v~QUQKOE_5NdU?Y3CjG&PmvYO3IAbK-dE5%b>Y2 zfU{;?rfn=2=*1P4n}y5Tf+r34)F;NZG3n|kGvbOTjHruq{c>64gXOsfVd}=c2&{njY5v+>wcTO8Q)*mPo8S`%1=Uz&^oMli^(cck7FxEUXbPb zd3oZ6^fv(6z^2{%`uIBieDKYYK06WN&y`-0Q8lL+v-Q?3)QmQ}(|jotvfo6E~9#X-Pxt0)Mh8c2>%|Nd#+Y zm6?V6HgTl~c@GgxjjOK3w-Ge94=Ym%1nHk0+)}()M<{MJ-ysz$t{;)w8t#?a9k$dR zZ^kdz_+j7l0>PMj5CAcpeB0`eMf#6E-VAO--|))jP(6Hr*fSO1vn1)yc#{1wBCv1E zyvVLOP4ScXl$1ZM#Cb6SJO|VD_?r*ecy&7{^PlKFJ{!>yHhG!s>JugV*X;LA1?Djo z@0ytHQ1V1euII}t_h7REtbR>Wv1GSL%c0|dD9N3MFAOE$Z?ZR_CW`}`nvoOXyYV!$ zyD&SCr>Fa=iqb(D+`CEFU0U@PVJ3KO>OP*N4(qO%zhomY z+dlMw63t9cR_~$|wp$b2E(qHanWU_Jn?GJAJS(}PkQmYPz!ICj#w%=b>FT}4SeR`r zvs$O}#TGr`Og+B*;-xk@UTMRt)a%++^O*Sun(7o;g2m{ESrXKplhr4KFbeDapGZ4- z0zFg_Kj^iz?8!08ccN>X$UE5N75}b&d)xWm9ndzrezN;C@!PB*m@X6lpVseONqAm+dm~uzk%B;qdfIAN*2vjoP7geQ`rqf4MwbpH~wAU*qBy zCSnZY^u-o>E8wVTF*w?{f}6&+Y0ejL%GNRUcX3#KS3;`^$8NV`SC9XMY#H|(%>LrF zV;cHp;E9K6Y%ip3d)3yJ$-V8+ZgTg>&tk3?1zQuA3&=aFIA+B5oOYL4HKpx-dvsIetb5&cwiMkAV|GyMhb-nBfjx z>z{p>I#yNO^3%%6sX zesVkH}TPV1+h<$!Tex;QLPNme4udu@X80Xvs{+?S!b&d$Qp$d*;sa z^$-4MSnJO_@7DS+jxt`bAQOt7{Dxz5Z8`D7PYdn*unvF*X&dlrbTha&3f1n=+Rq=M ztP9^zMcs=CRJQ5q4}jeJ2n$1(R*pa~OnYU0~ zCvOpFyd&ieAcWrS=ZT;S*Qt@SHn7WcCN~aUC>N1I4 zD&;8(;l+@8o6C)qCPg&FQ?Ea5zS4ymn(22IUFFLaDZ91pttifQMQomo^7&rVZDoYt zlmXpTz`o&$z09|7nj_7wl?WH`hJ$=i!`;bX0W!ZfOZa|DvWEdMqfx;2iPe)yqsb_L-oW{@!{8>#V*Q>&YnF}%(egBaau8PkWgZE*@G-yMNU=d#3IM&BeFg9qRaOXZ5N}#qB@&Pa~*s_#`DNe{c0cb z{h_Rhp*EKoLAEvtu(K z%l~Q;jUIZGn($8912;dH2Bb>HY?_sr1BAYQz!rI6z&NcQ;_ zpEBVrn}NK5UJEQ%%w!EkxUxECOu5;?^+ErXse_X($XfyaP=kwJDo!rHcai{ev|(W2q*cR>>Cj|L(dTfg<)^etMj(2kpX*N2DHk4%g& zrFL64ULE&@rLc)K(Gw5~sFX@emHeL3rHq15f3M85q14zv)sSK514Ux*!V%wdw1 z0a!&r-mIj56~TV6UqYRouIf8|5Jhov*GT8FWK#FGdU85il$-rBu8oluIsR-O9HbnO z2n00^m`=+bFZjc!Lw+h+*rmC+*JwHM#ynW&CH%zg<@5lJ+70`W@vl$J6 zRX>8b)af=0{dX|mDV_F`j!Nv5EeDW8`_OF`ce{QoPM3O)a3usN6aJQP#p!jHXMUqS zvuO!;mZUk4k;B_O{fvR|uMYdbr}O?6{+LXS1&M1)cZIy{_4SPXE!W*^%HKj7xqCrb z4s5FCorEk<#Jj(2cgSF`b^f7NxJMPHihxt#``7Hosxtqr{^N5|V6`~k?ecABkcDAA z5;itYjlKUKo9OpH;*IBA@EI;hgfbh7C*o74V~-=&ZR*o^?M~O@`P;d*%0MpM%~NS+=7ZncrIR|Bv0)>Rt>Qy!5>v4dFP&&s z1fs$T@Q&Qog^wPW7@oZn{q3QKXam;wpV`QrNvdUP?o;{zky01mOtB&Lte^-OJueuh#F^)o} z@`QKm;YG@#aJ>BF`oDdCkoM!<{Ud6GlTkzJH5~r!}WJm5O9zI|z%_XRFoz zjRXH#z~Bc__`oXZVVde`n&zaDVu|gtOqT|E#7T zM5eCrbr>7TR7!E1;r5B++T~3K;wC0B5d$G7pa;G}?;!;mI-+#}gfiR;1h#3jc7%9MZ@&k329YnnU^LH4 z9kAZ*H3kYIM}yR^O)BS@IG<;lzf6_$FGRVgbalPv@}a`qD?Obj5;t#bI?sQ!`EhW3 z1)0(4&ti*FyE=$M+TC}&r&y8f)|8cGOp#VvmDV5S!mNTf2RD)z=WcIwDLyg%XG*J&+J!i4(PpuH{ZeeQCsXN9%K_P0m?vuSK6 zm+QZ{3Q=$PXVKni>lPm$|1*EYAA^+Md{XoA^vv?DzBuk6@Ji*DA!?b{9_V{V!eHZv ziT`bnTA^OQ1_f&H=n|@CiJv@FIX$cf9pKq1qt#;9{yQsNWYObsLMP#-F62VBl7AP> zFxPKjPPuZNl-xD`p;IGc+%ZhAU!z`cPnf{marf2AG!K-kC{U~Db|c3lKEE`&QI|Uu zE#TpwyrH~lbJq&(2AHaLH}-jnIcuFR?u}QT6F(WpQ-s!90ZN~<8<`C@EH;+-&~eds zPCviCzP@EW^h|S*YRs618A&L4tqf?GUk*lx|?T9>C7+cRFiRb}0qB$LY! zWkvGrb>^DmYh_D!8bo-Gm@um9@dI*y$aGfNQ}na)s`-Pk{z)EaxrcVHSpR`z$eXa{>~7d;)^XtLu1PyU;B`qtx`@pMlo(J2icofo!a&G=5$W=`aOdn0dTkUio}| z~r)<310#Jn7&LL1Ou0^u01#j3h{p{FE6lk#z7Ysu}wm z^*>^eWp+EO#dpNS&2V6x<0YaYBtwb10P{BypCK*H`(R^LT@IGB&lfhsom}e+2dbQZ z;+vS}sDer2{L1)#MMmOTT3LNVu1msPH%v`GkVktzg+Ukflf7JveTw}z_@avbUmg}F zI#c$~4>K|`8G$I#vU7Y^eKzJXgePA9|8_<1tG?maH@l6Y21zyKE-nUrz>+b#t}&1B zj!W9w=+|L(G5WWUE|0$LzQ|Aisfc!jCsUp6>#;bYNT4D>?Upf&?FtFh8oKs+c?sDO zp*X^lCX;|BvSKfVkfG_Ip5t{WCM;b1z*U7G3ik3sLKMIBD3DV(zyl*{gD#ltZI;dO z2ne2T$mEzaEb4Gk=~lC|i-?Hi9DU$Z(9cDR-2Z%+p4joj(p3;#Kg3*d}~YDkB9j__TP0qf(#}7&xg$tlI*#|6m|w}YG+gbZa?HFKeB+? zfh+oPk9A|{2+O9^%vJ0Vfn2W~K(1k8GtjP6C}l8@ea@l9>>?*$F>BeY=2M?)l=T=2 zDOz(|Xfz8|ajZrqJ>WgpR^4=>txkm$e;wx64d@t$QM3ZLSI}Xv4qa`7=aWf0Jg`ayEK?FlqhuBgXTC`}qCd z^2W`@gl^!BAXqqD%{skGDK3j#C1r8cI4UTGq(_jtkg^f?^~uvgHclM?)KQb%LdrV@ z+z6Lz!xYbgCEH9;t0Lt}878@($%fSPfDm-_<21CRDbB(DY?*ADwk>+LvZ$q_4N+kb zfi8SJ5)$r8c_P5#g9je_HQ&BJh<(tHnwwy z6m#cDrAVC&7IYQ4YNzu^Bfj+8R>|H&J^%Pd-HdrpE#0hC$WDAD|3m2dsY|1M*iz3x8dkVZYA8nnmCIJ}Z8TxkNslkyUm!vRzZ% zvSG!?@bB@?VzDmu{$^b$j3F+spU)bPk2-*ewGt#y;L$CS>I4yt`mP1j4FQ`TW@}b= zu}BP`qp4l8Xz`XpzOCGSGFY`Q+b?x&b_x34v3Uoc6l0I|e zabE+$TTwJy(nwQriY-5klk!pbC~ofu)K%Lq8XKm%j^t#y+izA>)($yL(2>y8G0L`| zs#wabnxClxuNdhLfyPu0DWV;V=3hth^pVkuw0U0ED#O7pI-ISU*#R(L3WkU(00ap8L|0i zPq1XxwqyD5Wco}0{`qk_#Z69?qS!xnbdqv+yMHH1XuxEWG3~cu0dmc9z3paR2CN(S zAMLJeUnMw)3IliM(s5<@sHQ|wQQWd5>0SW?2(sAsrWLl?F$!CliTY6pAm&T}ZT#9@ z6)h`i-_}u)K!$^QGDNR0FVp^Jh+a2@gM)a#rYxaQur;?~I;Z$L;j+8`kSDQi+NrX| zF=TxHg+-G^VyI+dC}vr*V>a@>tFdbM572bxz-~a>(JR(r-~)y7%u=kI5ykzpOf)@(+@xr5ca%N zgFG}Sv(<>LEO@W4>}xh^^i@Xqlgq3Dff8BHN>4)5WbrL&*WEeLYvt#la0sv&zX_s= zuplOeYzFESkqHGZlVz8F+p6#TZbp|}>Xbeyna#7!C|pwADV1wt4gIv)K9)iDv6chr z6}}y|dvtPXi3S3qU${q_gCSNcntMMN_n~S_k~ftT8P-GB!~NfNqxO%aR0QeBTqf@5 zG=Ow8VD^}jAd`z3f6NnXE8o31>&pR2nCx^qW@WWuZ2JizHfy}J(|kJm$j=iz)GJxr zcK3gbx9C(3lI4tcv)eY3AaTL;ccRUM%N*Ll4+ur!nkvz@NL!|}=EU94kiP!xkBMp8 zS!)Tl&24w}dNKbt%~$-JAE@h2G=Kc?;hlj26^L2ZN;+Ps*y#f|6GXs54Fuc+S_W0J zr&9l%HEef+P~|}kx0Sl8etZn`OqQ5 z93puoh@eHhmYm^_Sl$bniQHXn9nB4%afw@|S2&nd#SQ8A%6QRZ#%>Q>sC%1I!V_EV zojy*zD9BVMY2su-KAXt*LnquQ@Zv~1yg1eh)ZAlT_&6;W+J}V#0UzTouyRRW`_DKm z|LXDawGhj0bBKB6mJ8ED#F@_jl2Y>djFA)`9RPG(yv%(3$n#r`8XCk-G zZ{eTCSxp_1!2gmla?=0iq>Bfkb4}JE<$D`Wlg)O@jM)(k!pf5(y@oiT{taHnk-Iaz zkG}__OYK3au~NGbZPt7+>i-rgqHn7;(2=SJ{Wco2ehZuS=XL^7X zCb~cInWK?<2on(A*{mH{6mpWdPhrQHz%;d zLl(B^|6jUsfr^EQ3~cyQ{!Rn!6g+bU{vP)xv-)lNRhj3Pw-cMX{5T+D0AQk#hgk#3 z5p>Cty0IWoHeTk?M4_o{#gklkoj?5-b;FBz(o(}~2i~N3XL?JXZBt`O!lV1g6@HBr zB`HAvJU}|X=zAQ`j!Nt6od|;2&PWhJKY@T3OIL*HziW++vw5DRo_`83j6BDS$43rW zbR#Ow$aLZZ{vH6?8|9r3#ysU&5bfk0YE=l5EnL}_>vRq4691(awyg;fg}V*(EjzwR zPwp@SX*FOBb&@xq00V8cWM^GIA)!%GQ5D*4~{LgKrc}BAL--8!d zd5>3i8l+N_hP?7o8(aWT8@%n3zt1!pQkyCO@QcCv6qi}}^P{$WHPa$T3GJE#248XwueD$<-#LLX5-+uzG zxt}0yJW2Bg!&mRVCaG83vz@rC-n@NPOOaPdmRJ{VX2S_W-G$dG3>_gnjQs(SZk|ag z@Mya=ueUgR&E0Wmm=(Vk%v9qY8->W^?|C&OnQBw6FtPGFUA!3%9Y6RdyQ3P&+b&!J zxs`q>7%Nf`r5)U_Lf`_lwR}Jp}#AJgMf{ zpd0oU6r}%snhUWvXr;&qIEq(-#s!6K@{1-n*Qu>ejxXM7IZNy?eARp3!*}WNX>wdV zZ)scgQS#rp|Jg`Vrmt28?I)coZ7c+&#scc~67Yvpiijlt{VUhq(=)2XrUe}J)>ZfT zJI~%HIK`}a+4Kqmo~2$#fnXl zrEp|mvvWZlsjdr9MTqrhj>1e|kXk#8@I*w{Fb%@+3|>v*FLUCT4Czm4MRhkcH;Z!5 zXoHsooYoBJpd1+=KaaQCwE2~H!LR#={{OzS8L|FU7@S?{K{{*PgvKa6(`8y>J|UJ# z&39_9ffLrm30v-Dlih|5*}#do$d)=ZBOgWt$U$6c!}|$ZU@eC^E5o*{Re!!obYJOR!1s?+mrR%Yf5@V|gs5G4eo*qo_6@EJeO{{z4Y$xf%C+b~UC z`dnW_xF=M!?4t;G6H^;_Dr7#y3K2QX${-Qh1Ua~h0hrWC2N-Mba{Pqf7e$NFLar&q z#1b`C8#UNm7y}a%M&8!2?IQl7pZcM5t%SyZ(U15(D%N$1D}kN)w0#8zCqLYw{VS#NP<%c=B#2_HP48ts7D`c`gbX=bWvoX9T{SigFg{JKif z2Yw(5{DaT`a<|JIdwkD^$*lZYU+oVc23IFN28YxSoasg|OgzklzK|Scj%$=G?ATJ) z{@i~N@#Egr2`F_DG998K9B#aZ`ic*wN-n!PcV^UQ?F(y_+vu0*bn-uM6bM_)+sJCS z5vn!OPdobk&jI+U@AzTVcu=nl_l;u|7HzWHnCQ_iG7{D`E0tm#PmR8%T$xU*%aQL~ z@A+$SP9&3G)Qj~ITK`y5AgF)wL_)1=Tra-}M0}qGGzPhEpvTtL=x}?{Y1gR6u*Y>E ziUh4Cb2aF~lmCAzEyUzh@)!ji+Z`#}V&(tG*;|H1-FIEXD2h^IAs}@cph!tKs3;hO zh;)p!G)U)&2uLg4ASx*!-9t&Y2t#*w&kRF6d(P{=?&tmRe0q=L#+YP|)l*zT1EEw#BK%oTVD|+!DRVq0wj6lCD!RC3>y$GdG9_ine*RzEvQ~ zRL6Qb`-uRyvlLfU`sB#=FnJsExo9Jm>+Tn_|MCZm4H2Kah1djssbCJpE7Vnreg2e8 zolYG0rO&a6bo&Bybfw%a&Ed}*(CA!n$&t&%X;b1v3+)>mer|A&z2qMerP+R%qJoZj zt6wg5@#f=^Ec0T`O3&0IFxq0^M_*S=%y}HKKlTRFh&F^L3x_P;zy9B$)>=u^j?irq z|57iV_cd<_M!QR}wDfIAjgO2xYri4--9zYQ zBU-Q4q;$ln-1on=@kYLxhJ!Ezv=7bIlxkl;It>4#nAycwRV0;>rKpup%bmu#;(g5; z4)L=-?!8=N?*~B?fKeSI4ex6UUjMHaK=T_Jt|+G>{nekpsyYb5;Pk? z69ot97vW}aS@1E*Jw#NVN^YMEvr#Ndsb06(`^^m>p#ldw!5V*c zxH!91@rTYg*-+!g0P5vt*-)k@>3v%reBBwP5<4Ayi}s=rDlwd6Kn{Hdaq#8$bm%pi zn!M+f9dP1{Qs5%qC}s|_b8rOVaV4^(7+2Abz~6vI0)`C7CShjbM+;=W5E3QBJ%VTD z-fW<3w$)F-?P;vuO6Pfvr)5{8#>)ndC6S7_I0(w(Snn2~{UB*zo%|m3H7v}YSiPQR zDO{_fGeqS&W5%4kt-3oq!Q1H_{CR(NsW`i!Ak2@+^;7RRSw5rZ&GDTF1ui@DTT_0_ zyk>th6eQLo)pWm1BmsI#yBYDIBRYP-c*@sl>9?TDyEfxiXvHCp>o2=y8QG6L)uGc2 z*Vh|ewX94u;3S;kF3AU$`@P7Xta`20_*2vwIOb^EsDK@$-OmS@KMi*zw}-P~Bratf z9a|lJ4VaNerw{?oq4{({`KKpW!GZ8Aw5MINCLHBniEKl&iDE5_QDz}=zJ0t-EWX7w zo~%q9Qjk56UbM7N^&FqOO-?m8E=H#TT)}5Gl zq!pK{+VutX=bt~KQsVB*e=}``>EY(2TA!!fcoePp(bvf1#vqW)lxM!g*{N6&c;ag2 z?O1efQ{ggC3G3YbVV%ywgL_;8QGnX{n6zF80_~(l7Ixq1s=<%$`QJH4 z2a%p4Pi4|V52{5KR)+Iv_yNY~4kLBfx3!Hej+iqcbH3|v3V_NYW5v3cmltpLlIZ-K zCO>s>|Ban&gxn&=|f4>d7i5M{_tN4J%rvO+J!hED1 z9R-aGV|RD$tsq|M0)ueM_yVY34o7N^=)qy{+_ba~!v*goF!^Q9+*V(?GXPEG~0ta{lcu3vN+ zLyyW3`&7G8v(8I7ss=Cze5gJiub}6d44=CWy4x zrhRGo;NC+-u(Bt-d)tJs{yb0W_cXfBUa&BuU#y9nVLoXg#K3`@6k6Afli7XqVI^7_ zelonGt;5CU8s+a;tgE(26eV%DXPQG7uv@jpC6HB~Te&U@JBT93M-wNBQYW}>g2BG{ zcFQde&7zD-#4E7!hnvfFM=@#EsRqxuQMGe{;Go~q)|LuRztc02#RrUm6Q#3q^a9f3p#va&T>Vzq2WNm$4fY3H=O}1CR+*-F0E}M@tcas=Y zzWY_T#}c1)AC9J%jc{JSReFj5Zh-*OjFTQ({P^hp@3fnF6)}HC`~`|;EB`B;8u@T) zXgL(;4jdNrtp-`a^}05Z8Nr`xc}VdfXPVq3#j$$VXR_dqF`ANum}N0=Fx9+pX!dOI z#YgsD;JLh3I$_-M`No5ktc@rwtEp@fJM6ZJO)i?im&3`CD&_CJPChq+;xR> zcVUEw@E$Y;(KW;gm=B^n+EE?X>fu9-;VjEQruw5v&=kQk)LW%nO`^ArT`#7|nr%LBb$6d`UL-BigNcsOv zOWK~eIigXU21C2b8xoAWeVIdI&zZLGs zFit(@$S7Rl{~GIwpuXTI?ZI=xRH_3DGw8kr;Fw}#{(7Y z)b5YYUot@JI3-?RKP8tyi_O`U7aIHS>oz;SA6(3XAn4wQ$n#Qu{rU_^7Jb{=8@_HmC6VgYI`ne;Q*RX8i;N`F zoCfTmBY~>`S`yOXpDXPh{@B43)iDDvGt~H>&k>jQ_xY?5v*TG(2$5zWKrurv&WuWKZ5kXJd$#mX>IPW%d{<+KdbH!NfdGF1DVSO1$>_vvBa-nyfiqsewInQ%u!OoziWW zoT&!Ca~>9g@u!4gQNFYb0k8ch>X{e#)-q4BD@>ZtJv}8^@;q7wayFDj3z5YSed8Gi z{|7k!cV3sLm3H+|c@6D;PQ}G|7x#Rtew8fj)sVZ!TMuorb9n>1=fz}KVm8UU56nLI zsjTUAKd4kC%63q1c3MtFy{e{BK$0H}kEH^0m%8vhjl{FZ17ge@tk%xb^5{QK56%9l z+Eyi=)7JKU*Hr@S<%6-n;e`2bA48KrM0K8Hv?rQ5h1c#;O2EeGGqd=%3`WraP$kel z|G@qXUtd+BzI3;i{wbPl(mteaEkv8*KJ8mA`^Xx<_V#u+hbB|ue>F=UgoFFn$Qq=h zhPHE6a;(O`+M`kUZdM3A0Qeff&d8&lN1?vHB+#0DhhBd+E#7Jxk~Gcxy0Z3sxZS(2(99C8U4L@eee$MsWT@QEq;jFydIBYgaak{4=vlJYhDCQC zF>b=Ss|!EkKTtNpvQb4>eHoJ!GI)7Jxu~5tVvep&>-G`nnZI0PfGkMcd0g2s3uxIK z*mush63@c2nq9N{uCV=Od1DlysZ{@7POq->h>!PBUKJL%5}Xm)mwERe@5T3tT#M&? z$5ZRN>Tr&Gr*h&b1YAq(b{CZh zr+_4Ok{A+c_23kkcU-_cnSrBl7TnY&2*L3~LqpgjPw=^rv$V9VY!^cvtyvSCI(VQ1 z@;sbjo_SY}-AO*_fS>0^$ObvXIY^l94pRR`GXnV+B}TV{ldf86{M&igeY=d^E45M7 z8!kv1;87NilZb?AhYvrh$0g74gLf$8KP~BL4_uvKsIsQRhLz>n(>WE5E@NWR>fEC( zd-&dg_r}5=30&65DVev_h~@I|K`r`Bf!jVg)4;C4PPmYa$*5bZX&s|5T9o9aracvA zy><6S+e9-Chx0JIBpXjAsgVm$L-j(J*v2fJsWYoXg>X3oMC|5mV6rH%Tj;uwJsB1j zre12r2z5srd9()&W@37hE7|)I>zYJ0gh%A^vYA!onxHE9gY}!u5&o4n_B;zr8608m z5RW|y39y8ekdAnv&^(Vda|Utemx)Fu`RasOrfeoe%o&2A%9qmOo#$gsu&`*HeH@i7 z263@|V^#}<+YH6;=8I@9BRKEHVH9&;Ge-ns%b@cII66kcO;8G3M->CdJrX}M;XM0A z)){I?rH3xzkgU3^;s$Ljz*fch>0TkW$brwxSzMu-`ruSh`coBK38mfz7?C?yrPeHus`a_U23FZXj6_lkbmsYhas$#B>9NL#?yAo3F&py=iorTsJ1xkyUZ0d`1@$qWj>LG|RUa6N{V9BfG8+ zObCy}5MsBHylLW14jhxR-<`0&cVWMMMJ4xxzYl!=m^&}r6gojxu>l4<8QIw@n=v{( zATT1R;h_^|yLg?h06yP}Ra6ni)u2u@507!;+C5Uz?c`1Hq1lb`3&; zEzWGk*}N~+ymSP*r1fCCOK>v?pZH;RA@{}NQ<`sM2Iws-r-t91yJ^IPXdjJSh_<@= ztM+w=CcfX@b}>LXNEiXH9SNH@*@2Le%fYLi3b%9br0Zo$pHYPwY}DQl8@b169pimu9aDjG zb`%|s3jhH#xpBOls&w63X0jZyL}H5n2L}37cD|Icln-#~I%Z7ms>E85)Ev&OP`*qE zW^wY1j!elWt(cpVTmxDT29~L;lP~fQ%3FqQTWG43gr@2_{xgC4cl!sN(o6A04F{l- z$Z-D`rF2z?lN=_QGyq|t&v6nq=T1nn@T1g;_}VeN)7erR9e+)5l%Ar)T#b11rzPvS z9j9D2_l*XvKyJH7zkkpJkXYZ}oQ>t>6}y0i{Un}ye%35s=*wE33c$hgrO02JetU!Of`9(3P44p=PNfg|Q<81*!bzBc zM*{VKaWDq9wX(K^>fE9k-*0D3pRaJ7`59(qbauoaB)Dd_etfg96} zz|GVp{Yj!Wf6o510(*1f)LthKDJEjZ&)3CLGDMHv1_|QIk`A3#p!W;t$;$cjBianb zl32{29(JnLORk%Gd);yOS{9BM+ng_PI1=|QdjSg1-nUL?t=?`q;?$p0Bl>Y@mka5k z#BP*pk}^5dpf&LSt!J1l)=EHyk`N_8nDo!>T&kN^!VM_xCH0F25w=c|<8@CfKN{>U z_k)>Y=19#U&j$|lMIAK_4Uso!t$%Sj9Sse-*x1-=kL!;p&eJvYZO$w>JN&b#S@iZ2 z5h21@RFSVCM=)z;^!sg=FJ^^yv(849&3y54MMWjkJH?j43=;3I$|^EYjdI`cQflzE zn}5pa5KI{)68^xYpG{NW-6NoG@B=+3h;)lWV(WWXGb0vPgL3kwUm36^t82rmLWXLo zDVvJBayK$r=f}$gbgif&fYpHOY)D<1-a8msVz?4LBjYK#kYd&y{Fn}%a>#pkc#G0Fu)Nc<=|1Ml zO*1%SA55NwMDn${LPC*!%)h+6Y$KYuTr>0N(>ksXc^tu<<969wxBIA+dm$tDiN{yR zSsyhzw*`IFR^t;3b}oIH^+xf%d3HvoonDpfa*RKsxcrE`FRgDCJo%d&Vh=-A< zdcEzp;5IsPo(Sd#2+v=g20)n6uU%=>^cbDCb<)oefMCO<(Dl8_}z zy>*<#s#v9%iGG`nyT+;cSWi!H&b%@a!;mkSVZ4z9BMv?>036R^H)RYk5~_EA4b)je#3j+ z#kdnWZS{6Cw_M0JBb5TWXEi1qshE^h%OQKN;og;+)aA&Ut>&7V&Kz{7-t2U|^J>z@ z{U!Ex;my@RIdxC=Z#7rdr#BaqlbUUgPfW+YUjOHQd|qKr1t96Y8`)+%W&8Iq`u!Kg zFW$|mkX^`~J^H@YA?c(JI)d2ziy&_+a*=}-xjqtNr_z$sUOx0=q}T{Sot$fdi6mOr zq(_@YJ*s-{p&M{T4b{Q>O5)$69 z#ljAUf8Srg5edw$SO_H7-~C@TPU;E=DJkGfp8^8Nvc`(d%1nAzGIJ|8^#xei%5-?S z-8g6_Jj8ZPI`o@_YCfd@@JaTZLk!_?4+YMPujS5-)SOUeCu6B&O_w-4H}OR7d(l+i z`j$5FN9vb5e&YT_yKDz{##py|2MnaJ(D#<~%aEOkq%2?lSrc)_U4b5G*;l#(eY1#dR7cAdEiq2)21Z1SQnm9#bQXOG+{y5dG>UuPcEM{E$0$o)AKWlsghPWX7M>la`?+|_%D6g z=#y8?E^d&bBGxJDcb}qNbHt~doc^!ASq+GwzR}?<)Oq^j26FBcEf2{*t6n(~qA9sw zZ!G2;r7L7@xOMx9iB>1M@EPY%xz`He*b&oNRhd=$;j;OhF*)NW-ipMQA>U+;Hy5+4 zZF|>BCxLvKD(>zX@tcajG^#qH)IwvbmHTL@E1Stq7SDI)oM>SqL%t^YKe)z|6xjX> z(2@(XGS&CWjOpaeyl>3Vlx4fPoHZgoZ|*7Ol#B>avVN{tBk^s_?iZSgf^4=ZPC@8p z^6c%ph}xIr{Meufp$o*m4~L%+-4=Mw`<-VSlV2C{aON}lLdw3m{OLKx_S~^ABbG;g zCv~rr!wa9a-ezHaXSrvRkR^FG?!7hmz4UbD-m&~et#I(kzBor2f7FA@%i$%Lov%In zw?9#-@J6A?r9u&t-esl{x6q8+BY`Ao5kej6LXB%J?AXZUMd_g!hoLpKV9u?U*aW zRVrE?tIvvFTJk8vf9B6EF`Tc;&b`?#>%|Wvil_NB^^aIcQ$NOVa&|7tlN4`Tq%36| zl}K$ncPXhk$#{r4WPQlWTDNqjG)Xy*{Y1S+;y5=EzfXJPT}>&Wxg_DLnFvL%{7~t; ze4B*CyAIqBBIw*6{eA|e62?I|Q~lv3CnG0sm3xtn%J)K`%1*r(P?R`T`;oeI`Z`Zo zu{G-Q-(37sANQ|GzlpDDsH6hrJNb9gZPHL7(Z^V)YX}F%iy6!KaWz`JSAf zHByV>RXMt-J#607LdrQjyXy8bTJ?c`%JRI#29K`J-d%G6atXj3M7J9gzE*kuVqFw8 zTJrrAGG%k=Kf8ANhSh%g((xh&_mwT>8?70cN&@m)QcNOB@h4pLRq~AE>HTlh8Z8=T z{Sizy`>PsZ;o+uMrcK}w8)xxj-9l$H$@>0zbe8x<>86*)fiAV(lYx&j=kd#9h`GM% zW2HP7I56k4yrWgk*YE{`-1u46jNR_0y!foLqRWN zo*l}4gbDpen94#ZrO$IcP((U&$mu#o-ABvLTE&kTR0WX>z3W+jMSIRfGwuHxMF!WkVS1 z-rWEE<;%lIk3PJ1rThn|D##87jzRd{?0ML4kj}F?m3}02;boL_BQrFwj6CHMv)nLEiU(ht5p?9S75^`aT~pvQkU+-DYRGr+i?drwy$Zn}pf!Vb*ToSCdG zWBYFLX^0TcHby+? zMbA#T05!t+0<`ItOv;8mb}HNn=HddS{4+nOt9g2|=yS>B&-bFz?Bs#`4P;YJ`}MBz zd4MDJ*|Q%1St+F81sf@>yJUjGoo6@b85?Uq$HaVUHB2okihxhb5rys2xUBz=d7fFG z7#E|I*TVQQd3W^@jTz!Z%mq;`eWab$*<~$gIlE07j$QDoUOs&RaLT{)wQ79A11mqFH=)J^hJReOcMBxAs1MOdI~hSwZSjl;;0mEdb}9{p$s5LHw3; zs+gK3^+e|KgT`zNc}8s#X%+)TLNLztUDIsbESj)R`uiUi6&>Puccjmvq>;BC&=Z7B zouz!_Ua*^n`<}&mg5517{;h1!f?aQdd2WR>8MAvu ze0Q>2Y)8?qU?9I7$t~y)#rMMfuw9GhA40ASTe11Lmjn%1iVdIDT5#z*?_>TZ? z9yYezcIrQUq8D_Ef2x`Tmh7#6B(R!?@T-#}-B-<3Z;fD6{{Fw(pQ0iaw=v7s;Mrko zq_oEgjuXkk?(zM=wrl$bQP9cuWg;046zThL0h5+?rslHBYdhhQ+1TdvO6=|u4J~Gl zg>Y~PAP#tIurqc+E;~{@r$zsnL+@y;#y0j!NpurC{hV})Ix0)%q7aSdo~Q6pRD=(C zz4-LwN7aM85v%n=#%6D(e0#n5dfRQhzmECP=l6{MVThi&*D=4YvW4>t{!ma*mSo`6 z-%p8(^-4W?nT5-ZvGsYqxpz(qKhzx~=^+Z;{`d5ByLQe}o6R?yKS`kScvDF}m60KV z1Q2bvwPL{hN*fHUp_Y%1YD18Bd3kx&b{jjRBy2l_*@ii28%E!?b1pZ->k0wuD-`sC z(D%~V#>ZVu-C?*O`?6nGyuSLW>L{$9uf6Vdw;s~57{Vz^Ijcw~Ku4;v}pe{fpS6OSj--l~<{#N*b|g2k(*=!lrg49-%G=EFv+Te5D#xUoU* zr;tk412W;6X6sYGMhxoRa(^`3Lmj6Us<^v`Kg^llp<*1`^8R>{akvzje8&B#4*c_R z^FlR*h!JO?-ZovU3Fsp~KYs?s1yDXLuxOoE6vgX+A^#0oo3X%s!X$es6c429yAjJ$ zTcDr_Ikf8)D_mC9d#Z4>-TL=BEXt3RSQ^xQI7^s%`<9&d`qjK8YxEn*>_v5YMuO=0 zKCIh;9coE=H?VCV)_1_$CIXljpxQrIb{>;H);hxa(0lH=zG$fl40sQU|Ys;#bG@98=extsR>(Am+vVUlzXkDii zR?uWP^V+*$+Go&wXqO+X94^yiQqfC1w7cqlx0P)x0=8l`+%Y9$Wun&i=t~YGeeD*U zD>Kg|Pbf+&zmYa`&|##qcJ}oX5^o?rNv;+P4b76Ikvfj`C{Wn9yi9z?u>Tj;i-+H> zGSpA?j;~Y)Ogk3eO)ZjIRxz~>90<6%{G;TomzD+RS*^@6l_#SQ9(*7RppAOa^5_w- zhKa-irun`!tJ|Zf*v%?LUR6s6E{Sh~F2XR$C2ERhr~e5X15T^&Ayul!uyX23dgfgj zWhFU(*%x1=S#-BPXDGkyHr(=IS3bx7#N5ohM>b(?=k7zv8x_81u=TYBJ`>n>T1j_d z!gG4K-3~T0zktTA#Te_ulS<&WJCY>gFWr*)Wi=)WgRS#iq?%^cdH^+h8GN@!fg!21 zFNI!f7|Y?NpOhi|6^XsSgkkUkSQ-N57Y(fY*G2&~9S7V3Sd?OqhV(Vq!q(j4#lNDWEMZ;O;Z~m)IsmMKVn+sZvU>M4`epZJ#TX%DjJr6jA zUH{DkAv`17s7ZYNj5uz=;c)h#e9=Kv@_;uq6eZec?}4PdYr^;Q&|4tQx!QeAq^l;D zl|;hVWc?*u=UPh08Js=N%?lOXXu?}871-^OW-)kqhQ4I7ldhlBZ9Du1)3p1I8cN?A zCsHp-NlA$qMBaUzp4QJTn+~YG9^U$!Kn+3cZyV5|W2+95_*Fh8fag>2xlkcgiQN^_ zucYs+Qr%yY{RddMJDo8+-gJD%MHNkkykDXQTm>J%+mdY#nM4SpUyf_TjvH%0tn2k> zsknoXfP!iCkiHm%OFelADFUNTbb#6DhM&}_tSCXPKC|blQRU17wCuz5K7x4U_1-Fd zItY~V;l2{_U#A3S1zhEe#_(4ko!P;RfRJjn_<2;EP>GU;vbPK|f^jxaY_GN7f#G>-{x{ZpV%IZFrH4 zyO^ zGwuD2c@tfZTwBXIe~A}*IgNY`^^U0V@#lHUDv_?GrOnJj^(p4OH@39_ED44MRrm+X zX2V_(s;2z&=bQ9-P_8!9rH=gn{(WuS5mN{8#0qk99U>Cz;ABF3{|(W};eu58a#r?B zl}KPGgMjh5xA}Dx2xJ1qLJ0T(IaUhvLN!2wY1?%Qc&%_iu84s7z%SQ5Gq3_{+Ma87 zfig-sw}`qWFbpChB8SJA8WVJ`4k+>LhD$Fl6#BB1S0@%nyYv+k#RSVFRa@VnISU3r+wRLcpS8%zB3S& z(tM2T+!5Baznr5Qn0l9pqN|Nn^yY`Sg99swW73f2#nwhQF3^d2dngbu?OBmLSz^mW zry5?6ahmM28aBc#ul@>NeH!UqjN;Xif6~4o?Q_vGoCpyEIz7+&XoP2LGc$5@R((e3 zX;xMVE-mxh0ucHip9EezYo(^5@+C5|KPksaJ+d&sTEU}%8HFX@V06iA-Rd>{hMW6Q zvl`XB9=NI?#+4U1v%jyHS+U=Z-foGIjfoM-Uu%5yk@Sg5#yizZMnN~(1<9*bJ+Ger zTUkxvwz|fI93`%)3VUjRK4OF&Yj3bc4NFYy1Ze<)X^VyX0jN)%ecH1gAUEYsj*p(b zcrmk*S7Qu?lt4y1fe0mm3BNhjz#!%r6ihEv0Gg&MU2c$*{XN#{>$IXp_LMmQG0Goec8TKl%H^+g}`;dH3Vn*iPdH zv*Lnxb8Ya*UVNg&v+QxydXR2(-?PPrNSjH>Wdcc4B*=You}?Pmtb28ID)q$1){Gy; z!j3g&C%)#8c|*K743ALnLQC)dbi-46t~(a4zB#Kn!#=Us!Ps^s@264cOpX4?4vOl- z$^K}d`}SV+!%%8H{;i2@wS3D7-Q0L#pBm)$4I-)IZ4dPJ$^`0QCgLuSnSi&fqIBE9) zu>t5Vyznnxyofhk6o`n58n~^Mmt!Z#sys>gO7Z@Z+~dVtF%csE&0H=Vi!n+jw+H@i zNAO(Y7^V$=X#Njpg@HB6Oy?G(WI9ji^p}4E&Xe|cnJI`Vgww^h)_(N*-u(Sr|5LGH z6hR0;<}RiG`+QRf;|mb*5!7NJ1|V@i!d%a#<9~Y*YRFt5H|ovqV(*%30zutTFq;k% z5UAMxsdpi#n2;~$L!*1XcDX+rsyxLxDkj6t$vOsMoA=;clnm@x5PM!#SZeA`g8W7T zGui;(2r&j%LHlPrJw&AnIt=(Bl=u3mAKB|RgpC55gxPmItzfx-cAMQSi%xVy1`4Ze zfZ{f;6h9)40ajSr_EGQvX5;t5#QH+4Nz$pwuyY%F%Z=X#t7p+wHG6sDyGSIts9Mby zeH7|M(qDnmwehCog3F)Zt!)eO*fMALSnl?vyv`W2$WBU8BGxuY-(=NaX4 z0|vPA`=)=sue;n_s7>Mfd^Ps(^wzgXSzPkkNrRBl#GBy!?al9g<<=`6;vTp@xfLPG z_Zy1H?!IKnPPHEhy@B}Hail1fg7fF6(uRfTQIB^*m?~Q;_FV0{z)IcOm?K*6%OqQi ze`V=n?q7WWT$V-A}=D=F-_y zmWEbHT;y;w?S4_^x#^&QPHxgK*=#tLGTi#!xaKO4NgnPd{8n#<9*PI}5q<{0?Ir0j zU!wav-F&BWjIKu{B`Ltu?013D%(fHs**vrq z45IcKW2aEixJ^4&p8E9Z(|PeI-8`x@7$V;bjARcUK0M`pj%wcjPSTt0*;WqSReb3I zC^A{^-3x$$eiQVk0WB@_NLEtlIQz|vKxYC;6ou%6wc^_@j+-@gYiu=&1;23x2VB=_ z?Q5jWh5No4UHWy@ULB;9|Jj-*kBn>+hdw3De-B4;mU45vkUQ*nFlX^XLg(#5R+d8U z35@lUFS7cHyLSl*5;v)%P*vf>O@)N#djxG?Bv+clAsG>(lgBCJo!{zVWkB&aam3-9 zaC{?r2ojR~0-eNJ+4`ub8J@l8rWl2yOPJK4`#kxFm6i3g0|+GG^FDw+#%AgfoXJfo z54~yO-3IONEneO*LJkO(_5x@j>p+V7`-&nF>KRfwU13hB21hA%&>ISJ*5kUGOJw@F6r-2()0Ia%`@%LTdN@^-UGto7p_&6zrVzGOWo;6^xiT%wqLepI#V%8 zf2rt4j_yf$V)s_hZ@;Gja?_1E+y#qkPb^TTe6Bf6(dfpW?_Wpb+}M?T?@DrEW134P z6pSrcZ@rRvsjAj=YeTC3s03eLH1Xqa`O2VH6%93Y==9W-6SMKaXAO>c6h$ez^H>>A zoE+ilc*w_eG^un=QM03^=u1L|Xk9^Q)F~TuOeGdQh1_aW%lozJ*WTja{q<*VkaW71 zC-I1SVs?o6Ii2=tf0R%x@?cp}d~<-<0%gmm)O2?MMAYpk_9CH(ZQ(0?cT)Qnhl{yu zCXich>-0{{fvg;43G9y*m0$Z5RPbu+(!}P+&fcEAXcDrrX6bV~Sf=mCkAknMRaFVl z_n$K=6DmQTc#c{*Wt(4b@9MI8Hvy`=EoX7S=EK9oiEH7e(G;O_b8}mNYn{Y9tEl9w zbHIRJXwZBiO(BuⅇYSz}RaSB*|{XEpWF|`gppn?X@6Bn-q=5Xv-w#*R_bSyEv(^ zq?nJ*D|$W1@%J*{z8(ZyYOjjp#n5P0ZWYbQ0Q7{x$rpEDV~ok}*oi+31H1G!H@LV$ zt^_l2OQps|J6W@A&0NuD6!;|MXZlj+HlKZ$vd z!$m201f*5YcgCNqRYV>rFR!c+B(|9u8MVfRTTl+q2vBg}z55_rLMuSf^v~_%?dY1# ziIbxVLQ2By?Cd6})btC7Dvm@P{x+Xw=9`;idx#l>hsP-h<;{4ayF1q$MR!><)CCO+Yyt$F{uCF+jQn8<+wtDyqXnXE3e^%> zrBvDEIm4!d=ehXipJ}BRIcq&Hu_L)>YQDK!$qfcz*dHlcl5B?N{ za%$RZ8uXN|cO7k?AW#-GyZ=|d|n1g3Jwgh}{dKRFZW2k|@{3b$Nq-)Ku<$MsG! z7rRM4vM;`8LQNe)cKO!jR{3@oPEq+bTl{1Bq?;moKNVlJDKNTkjA$3J_h+!J+-NprAlYSMf#{&GF@O@6R&9o8YYY2L| z3pR1xM$J06vg$C5OY?sjjVh+v^z&^Fo$+oz$a@(`H+{Syu%q`aKL#9vLW2>T#m#m+m8=Py-(Lk zy#Hc)OX;}SNyF=S)$E*x&!N4?UjBLbFbIfpn^bqe!hCc zmV|{u-@VD%vudeXt|g)NV+ZNsuM;YNfku5Etr(XnIjFNl@%>HCE6!ZZHZEZOqP$Oe zPJ!`F=eU4Zv)b#k>1h9knaP4v(OV07Cmo^3+qYPa6%5}E7^WF2nmXlG_U)zP#?~kD z@v~NKEA2|J&-yh#w6$C@-GT@0C*~-Mhr>m^a{tC-H9OY?IA<^G1x-#z1hy6!J`=HG zE&v#et9tiOt>wvNI>0WG@M3TEt04%>3gAcd44$+b6T!y-*ih}6*oKus=DG%_ROE@7U8 z>5tePDu%3sg8;$)oJwN%BKR(Xcu*qaN0T&_#A79;OFQ$O(%Jp*@N1=f<^vq7j`;GL z_m2`xuJ4bK7l)1J?)R#>$dx|^y$J+hyTOg%NN-AB>jJ;XqkSSS_h^w3IEC1-v+3(9+DI^TSzk^8O(05{rr}U*zG3rwt>IWxo%ouU@>t0Rs(#7Fu}rSCm_u@zTvGx)OOz+bUx4lU zA*VKy!fb8QX3u#o@XTqq2Z~iqVXcEMj+Km=Dwp;05ZY1!<^gPZVk2j;wVA{Z%}IV! zO;+|zC~f3YjYg{__^E!IJKcU3T9fRsywekEBH4F;(e!lx;kF5WQNTU5{7}tKZ`w!Q zAm{4qvnT%yyyXv)qlXT3-MHZ=C9OS)r0~JRN$ltEH%0}w1qTk_Qi^PeR7IX#Bk~R> zvHQ7As}c2+6>-cfT{zysG8FyG`H#MC#Xbv)<0x!Hu{5vTR@atED7eg@S$mWC-Q{=p z7b#wget1y}r-E)jy*$Vu3KPiQ_o0zyLDW&8|g z(&E}gM4$`_Z^Fo}^zrDqpJND;gw8=_-%|0}E=9VetJv)h#^LhdxBBba1TG+d0kWMGoJvcs+uG$Q~ zZLDAD&e77w5DXT`g?K)A;&Jw92CuBH(n6kGQya~Kc=cN6cgPhn z!kv@qLi=rWDLHL7eHC(s8DuuOYvF0*rSVpz-^tjVo0S%7q<*62NR04vuc+J^bbZUt zn&@A&xPSDZBdF7GJL-lyG8G4)GZnQ@iK(J%2VUABNVyq$=CGfJE%5JW@1#e|w8RpY`0 zb;smjH%*0xvbabF=2Ae9PCu0FUMrU$z=oP)qQ8zI2ENw5K^WyNI{)VU+_=#DYWAhS zn)vPI2**ToM=UQc&cJ5R0%!Hko5Jm+G9WH4POw{S_RrVQ`=8Cts>AL^?Cnizy0xzK zR1e1uaI#d~&+L0PL@zXl?Bp*;`rwT&8KR4lW z|Kcy+mCmaBGiQ^IcTKI1@HsJi#%Y-3F7GQ$7CZSgL0Ywa$r7EmcsQCaOvkb()ur$e z*)(T}32S(Soweqw{VBv}-olZ#7cUdsj`8MbyVy8BU44jKky2jCg$5L$6QR%%*Al?4w&_=md~<}_TP$`xXxy7QxPc}{ zP0^TRa^{8@yHhjBh_8@ruSRy4xIJ1lP-Zq5l5H=;6~{jdd_Dus-u7tM!iNElgkPUc zoW$GBCr~oaUz2GaTfT_Ln}xuE2-7fAV_$AHY45eX>ABZqY*$sjBHfWt7S8X^U43-k z*0TUy3}X5G62+YM;r>}_l<091?j3yT7B=r}Z#%Ee?YZx&=*FYBP4-Nk5`ObJ-5n-Q z?;3ZS@AidOS|pFyJ&~=?XWnhA7$am7$oO3PpYqJ9U%^RSeUuJk0(Aq1{8RSDOuM8i z7t)Etd#?_3-}w9Vz2e8JAAL~;_QQWv(Yt{w&C4sQ=d2c}@tzu{urBzf{(+~{+J@*M z_Ew+FHk$r;c$Ft`s2=X5kQ;@&vTbtmmV06Ie==B1C15$0d2v_f|L>E!gO8%H#5Kev%m0NV-HK4je{)TC0|Tb zS<3jmUKD;gw!Zea*LRs8BnSGSBodZN3_aQ(F0g1AuEkK^S&=-hO*JNVJGQ8v|KRxG zrJ^J<6ct5cUG%qEvFK;HuDhf6rRb6V`SST|yjWLnPwRJ%HtGpyXYyv<7phP9AKQ4%oeoiBG{L2}x5{_2@Cg={ma=|aya_LxvP1eO z-p4$=4!2{YI#TMmfNJhiq{OfJ&ljttt)TDUU)V@T-#6g?wcb%nc~UVykkGwK?fB}C zvZ%Z63!r8`!Qqw9FPgFErQgKmF2+}|hbv*>M(mOnuWJ%o^|0Z~ z(;c=!-L&2Hq`W#WKcQ0eM67DcJZFC|Tr>z+TC)TJ^7&K8ljFEy>pU@R;rejA#{wdq zKdyG<&tDxQ=gV!sW>a2`qpmSnWGkw^IHWUYVd4yE4jk%n{cV+}8dx)sCe~(8xgLVq z+@TuD=zHrPj2(WPot}A5*5J=W_tTo*A+M|RFmDhXeblLy&j`O6TGyEqzAU44mD`^C zEP6zSJkLr{`7VZ?G{U*au)O;56B%VKC&!mh8op9DYEnMAPPvqIownrCa}9Ua2NUb2 z6`F0;*Y$T%&lzjJ{Z|X{4?;0&sYE4iIEl36(Z|zte0M?oJBv++tVipLX+1j7=klW9B_z;YqGS3U(Bgx47PfiiK5q zxVR^ucuZ!erTJD@6k0EF-k|m4ExFZ{DPenYk-pE~XHot#!LaBOFCa*%%QpdLXnEG6 z_h{hEK{JL*E*CuNZ9O5wkU;f;FrIXMj~6LoWk7jnk)+MZkA;}O5>;&OQ)tK5*Z=ye z^7Q}K*sFgBZ~q@YLCp!T~p2a#V1Mm(*${%t4eic(u_(oOf5mr zm>YywgqMo%Xcl?k9gVvZoJ=nMAKNfkQ;4WRGAnC)w@=Y-%7;duHx{;l^?}ZOXb!~XnO1iq^U(r)JrQ`Z*!^MZNzw|vL;}dYM_KWT}>Vu`qN@1miblry*sVH&O zWUa|jx@WRkH}q2yc~U*Vi@8p6;b^6vtuL?8sDiO`ntYFUY=1L)Nstw2-eJZ6d`KVJ zEt`Ua+m7jpUZljapGCY@%Pe*^V^3~ts%mMyfZv9&>jqOs#qvF{gE)67mUQlun zcm7hYg&@6ZwhHTG$$zX&7Pwx>1&Ja{+b-h=F3 zURDDN1HPs(hDeUO>X#{5lUZxHJcZpw({=#opFVpwRZq@63sBQ{xJx!2OZKU~Z|}!; zp@w+lJKq*-N*-fpjPo#XDU?-Jn?O{c=`jjJ>HRmgM8~*p@ zZl}c8^5gSZD_Q&|t`H05d8y&f<2z4Dl0mFswV)&p6MJg^Te<|{nB%P@fBwh&`z4R1 z*G1K%dUrzcJK=AFmJ8YmjQszb$}{BU(W^g`nwp9o>h^2`(F$<3$w#XucLN^5Z(4}f z2D2$OT^AM&4UHVheV~Ixz@~v-$jb2OV9&W)7i0hr!N7oI9IR1lX(mU0=@AQ!*u(FaQDxme#QZG(*NwKMY zaPtV1y49WBxo~18M;A59pKZO~!-^^XUTjfkliEHJXtGMNFGBepT}gNKM|zcRV3-K) zn3rPwPwqc&pQ`oO{t6z}Jyu~S%lHOJrBUsh3+47f0#CWZE;6#5pb7h1f^f@p)fAK* zE&DEG^czN%=N`|L;-8OD)eCKDdY=Ecd9}ecyH&p8~Jk$wN08ppUL?@`XCEV<4VT zMjtlaZX4VQH!gahG*5Kec@!VfAA4imqcl(5)``4~bR7ayNJ zNe2)hp!c47&!O&oU@MU;uas0n?*TBcBDxot!1WE()u?7r2WK9*xw+k9pErV00B;xt2-5-Kq@YyG#VkYPc2vF8t%i4?u*mW?@HxPk|Q900F-c z!t1{TGkg!Jky`<VQp!b=UXGg8>VGpH@!UI9M} zVPPL>qRXDM80kJgl#z~U^Y6oZTTMsCfF3r?FOf2{!uuA_a= z@z5$}+wg-clSB_?nWq8Yh`j_5wXJ{GJIJf$9gQ0K_#V&3sD{Y24RzUOeEIUF;K^?&*@#Nr`aV!60WSN^f@RhXw0%tjdRY&dN1zCF{Q zn`}%|+XRpx3L*L-Hz4SeJK@}dl?1D_begI_Qv#w?PDy$9$c%vDS`VnrC45gsApR{N z3S(rUe&`q7DYN?YTKTE)WHnqV)epb60X~N82MD6b?F=`=h0lnJ83fP9o^$6JyjGZi zR)Y{+5Tg}LJLDgbV=w-Q!Js4wkw?S*+AA=Ytq})jM78~fiE3^G)Sj5@zwY{;ZBJ(7 zX~ki;vQ@ zAMq6IeKi^Xo{+TfhxJ?qJgxbn!n}{E05O2>Z&MTBa0m#V@v9QW`SA1ls~6!pBHs^P zrlF_*DXR$sm|W$65$cU2EQa%!C@MV-%f{aU0TPU{hUZ^^Pfdm6TpPi*MyMt;1Xf~t zoaPg#8X0_N>g0z-aSuhsd&jSMSl66CtQc~-=uJKG5U zsE-rot^4}(_fwhnPtlseY!`%oUULZ%qwUx$+m3Rcap4+1AMj>XjCaIdyE>-$=; zu*qgvplr=gxy#LtRF1=6h3A54l2o6kbNpQ;dhLb6InObtk6u^Ig}VeLeMNAHabTHX zKbgt}cxM-_iu;Y2X%6_m_gfHu`ojnyOuoalku3o`q5Gbt18hBcecvv%$UJZ~ssDbu zBRhzFGN9n<>iWFZ(&-Y@ol+}cUV5yTM_S~%ymvV=UL{xz3;(uY>PN| zgyys{3|J?`vpq^a3Gl307L(4CEhzgl7<@Ny(@kBrdE~)OD^7<;vp*dL;DIg3_$-s0 zTMMrk(xf$>b4|OaadTK4N@YllN!6p{0poM@N`nSlD>P6nIxI5BdZHtnUsu^wGXLuR zR(6pbK2X-1DiXuZGvP`pb+O(xJ1$yH?^&G?;S&U0_O^PlC6kwRv(ME#{ykv^+xMvp zH!5HA1gnNd#WPxtj~pFh13&Z`!5>${0w&xhTSfN+C49-8{=z^SYI7?74`$F7m6_rSPg!us4Y`Y_5O$^a%w>=kQTSXXp8| zbZ}9Jb)RG8R2o;oPQRWxUVFzx6(X3+FIo9NSIOEbUMhKq#sA;zPRgxcGq-@7 z@PoPt^)2nsTxcHF7D{$xgy|#ypZ7qTC=czRvZg~CC|!JKJylaFHKY&7K*j8E_yrml zb(__bFQ!aPOrpQ?jtB*VF;9x00y?0B{8rrUy4+e2PQ7Cv2g6{CO)j$HFo_&|6ZK?gZcaPN0C$$Wq+!S&tIHpvTJR}{4&Y&rF-8r z@xHN6x59`^lFP%tLI%n8u-LHToVN1YTsbSTO)n0QAa5QV)O!2-m#QZn%z;>PD+)Lc z=coN3=}f)u@AuA*Has$NX|{D1M*-F@dmH)!I+8rfQEFCz4Ql7y&ZRrLmOHY_O2qnX zMHv1M-&?A`PibtadhGaT$BzvTt_n$Lh?~4wr?Y6i+9S8|Ie_A_#%-+#nheFTo6nhA zgCEiJGNjXw^B(Nexm0*-g%OW4}xm!`wGwIsy@WuiF_N6cgzrHMr} z9}El4jp2$g1cg7AcO(eSbu5xok$&alMN)4oK4D9lG|H{Tgg|$2K*-rHfwwa z?)_o%>srb`XK*qqx2s5*6M)~M_TTE(v(X7>0PJ`Op&hA>jYl=K<|axLnXrA)iNVQ} z4ryEhpHW;i8MdNg+S{5MHn(HySZQPtYndpW4ewstlBp}9g|VJ>OWeYNM4 znc|E0Y92=y@k!HS^h!H53nABf%|9bM`gX!!nMD zk^I=~UGGf8pT|C?>H5_a_lb@)+*sZxi?%8wxbmj^DTDWt+h~5w*+`o8D`OP~YOEWl z9_pW(U9=Okmv#JE7~+F%{P#r4jp*L|WS-u|T*bnxvEMxRd?ns^XG4=}^6IH1S>iXtNz7 z@il$E0;#o=0qj4=veI|##qSs2c2ZpB>=O&{vidXGCvk9}KleIq(B`%%p3KE4CZ~im zSF*Q{PK238nq4aF-04EP72=$~gdIEy{Dh(CK10?0rGM_;gq@i3L7IdrrjPGXz1up_ zMol3;l$6p6TU@joFI@tdZW#>wu7GVJupV4ihO#IIAJ2zzl2Q(6^gbo~#FKhe--y8QuqmCcWzc}jl$ z`s#zPtFiBU`>&`_JP{Y9|%4Wsg4fdXv|f zJ@TXwJL=~09p^dq+6@-^?O&Rm79yq^BUjEIC31Rc4m6(Y9o%Bs&BgNZlE>r9%`DlA z`7zm~)87+(Wpl0DzLa%c^+IQ$Pwp^Rh*8Ak!w2JZtFnBj*j&S#frzCX&~&G)1e$P2 z*#%A8p0#Yk$G!qde7gVHV`wUV-MFfn#A^!n^G_#rb#+M=Ntw}CuMwz^r7=TKr)Myb%52vd6L9qA#lBw%@a#`q65}5irLV|& zdwjY>epRQ!+!sUWPsi7Z4Nlt%mawSL@Yy@bOB^Np&2 z67qwLkALASgAaaU?pl7>^VXGze$0+XfFy`GWw{?4 zmgx1>IxQIV&t6GYOHu3B5G0X%h8;Z*+%h}`-IdGZ8Aw7P)Vcp}tH=VY_6>N#ABsqQFNteeXrb6>7qr(;0cyK)&wI^R4Vl zLpq7({B8mK%#Kkb`6ORIr2mpWra79wGS;~u#@U~=%AUk+=vezAU-DZFfj_oMyImc= zkWSa*fB_rNl2(()J(C^@Ie*e4S$aEWDGA}&4LuexBbv&|O?_VNPjrQ^FPNktY#0H7=*Grt zs3^Lta>m9C=g&Xr&I2m{Tc-uZEkL8K%A7!(S8mZ8*RpByYo4+Z<|fn0_@uy(d>_ov zfS)*;a?v=Fp=LrS7kP}|zAtb?S6A^(q=jLZ1mpy4e@mcyz_~y{R3FCtgCan>QqLl+ zE;v6C=oz12#J85TZg=g8;wfN|m<$onTE6sxD>aZS^~Ka8jm^>oMTl7?tH&L#pEpHK z&VQOJ$9w-dz$cPp`!vwE{{Zjd$0c`SV(Q)}Ms7O#FCR(mjfIK{kX8(cI({a9TBAug zQ6;2eF14AB}ViqTwed`AqVq!U%`bQ zf>Aa-G}ni=to;gkkKe3zIq+GF^(?;^aJQ3!o81M#I$2zwC`4=VdDBulaT1pO*@;G9eM!4 z6Zc^}+Wf`6Q{_zM!tI?^10k_otkZUgaL9tHO7M58?aK4Zdt%;;!hXI6dZ_HX$sbk7=P9X=}1aH_L? zZ#hEU!ZcTA!+pzfO*YkMShSLA3JYv$zu=mDo`#I>me-1C-rRwTaJCY+&Cge(n|T3e z5t4e77Psu}@sl_&vFG6A^-*(uD?ENEub%u)wTw~)pq1qJ#{YU^ z=#&DFahJj^vbS&ayIx1P(%31KCHfB_$kab*&wS}a;@>w<=0D=&|Hjyb+Pi;vX`4;b z5BujnP3f7oskkKFrbL-(IbUgo4PyygWSQuNiu@xcd<{w#y_x#rY7q|me$^h+I;A-k$vg9Qscmqd)C-Gre*!+@a?FDM*mcEJ~<4_J$X-%>*_x#|0!C=`GTRzeC5$B#KZr61 zSWVbWc*w@>U;44kgao#Czbxz7UAl!^M94dzl%Z>~WyvG|GI2*|9y+sd&Z3d#UxdR z-LJKbr^?c1_To!H%qc{ig<>!sD4{>{SSiwmd~zOj|Zl0 z{gtukJ(JjWttQMc$;X@6S(9X#U9%43CyE2G$3UYIn?hBt=6di7&A(r$xlovuS%``s z==c)xHbVXKEi(&i5&6F@?f(!{0E$C8UJ?Rs?s28xU5QbhOu)EKW2>LbEZd*kyKu-F zDBz<+2wAoT_#y1NMjQA<7-a&BGevP_9_$X5#oZ&LxBBVnU=cjJiK zV$Xr!Q})Z+Mt*gjw9J{?gFB0J&;$a`pS9=@jWR&lh8Rg*f-Xv@;rxJJo65C`7S`!> zn##FQmGiHUjOC?;lxw6^4PWvMCmQ=?wQ6l!@1`{Nk;#SfzsbkVv(?ZtxTgY22B68c zDhCR!%OBlVL{0*SzfCC-v#V>N+R?{Md`3a#8fi7YZd}O@`-)6!DazTsW7ueQm(X87A}=%)t7ySm-ywu z>3b{(TpU=FOA^xRuqG|5Zo~au4cv2vx{13o1J%{Q(H@p zP3`R$QF`;+uX9EvHS4O%?M%LhQW zzLCFz_by)O>=K=Nm?gb=Rxa z-EwrvhHM4LlP=J^(3)wv+CMO^O4!l6ea~f!cEd_NZ|~L5k^&R#vH3EUNCn6f>GhjT79P^f=3TMWx6Qn$M! zb5F0vb84mZO{x5yb7eCTcOEG&uj(%fYU^gDS=Kw$Tzc0_rOj49eT)4|c=cZ(a-wys z{Pt=wE3Bq$SfEmvO6=d&G;OzfhoJ=Ny5Of_JQ;fhA>8soo0hfRxXeof!B?mvjAUNP z4b!}6`et9@D$#P`zR1&eX&U#6#@&uj)7V-?i3t{`3y9<@+vc1!?+di#c=g=s?@Y2` z0f9pRGTpi@xZmoM#WoI8TX$W;D)$!5cM$Z@3UiP*ZlbO!Fi+&ys(g`)_;| zdqy<<@w#$N$HGrWNx(pdqxRIMb>`NDyR#0e|IE{K4cos8%V&SxKGzuauxxPUgRo`8 zZxQhMd9;gkuti0iRT)%Wr4gbKngtS7klk{{ay@l6jC|w!{vqO>k!1lO1gOX2+uGV@ zX2OZGN&oKi1_9a<{hX|Z@7ZhDqTFu{Zt|97EkkqfKezQ2I))2?%%f>@s8c250Mx=Z z+VfR_tR_?wY%zgdlJLopsZBo*UVDarMtSm=^bwxAx8t9t&_n#Qoy3*uKf8tw$q638 zSM&O~{6mbC0Fe*fOTW1bDy!gZZdi+!C&w5aDP~@O@pyFJ*N0+olYw;$(3*g07dtZd z@JIy2$wIb1G=Oq`m8|L~nP!d*9$x+uIB0kebEqJTCi3Ki>*U~d>ztgCK-%Y#k(~}T z86%?4R_u{e_$;l$RzUXvm!KwmvS?nnB@?R*)1fT9y+nKa$M4nse2HmpZeVNtB-l5= zH$Kn3POl?nXf0&^Nx^JLQg#m?rKKosP!jBw9Ac1{ELlUD3^|c*gcl!s6U95(kgu8T znIoAar>AKvB1Gn5_r;E*x>F816lmU}sRUQ6^0__9$rW_Ngjd6a)`e(Y(NwM-FYr?$ z4P0sPjdc~YS{@Fmgq0(G6`+s76@`EyllO>WV89mVNJ&8fj*rRfVHEwPV$o6Zr%f(Q z)c55O!r(<>cVo}-fjb1VO!_HIj+U}xX*f-mL>NjymtMlD@gE!|2QeC#HH zmi&P50e!zqXOvD-AnGJ+L>EsV$$WZT9C({!s~r z3ARZ|5rG1RDjF{}2|drk;tR$=6p`5Ar~n*^&7Dk4Ek*iRcIjAbdc`J+62-v2_0Bmx z$68&-{EB(=v|*SDt3nE4@JMe3!@h?w*ddO`{og zdgkG{x&(x}1R6EXrIZi4+}00}GU57a0|)xs=!~!tgr>|Jcd|=Yx052tZAA13nF7mr z+-lL|nVWCYE)x48{f3KDgvMjLHxdd9btJh9oONRv(vWPQRe?RoaJ6V;p>tJBlZ<>b zRjtt=FN6lZLP8{yDa+=6cHS()5NTGENxsv%t~;1;aC)}SZL4{=VzLOkw4~6Mamf19 zI_wubwXm(u2mH^7<_+N-aP^aCN3U6@I=sE9s^>j!E2=M5Q)0a2-XQogqM5h4dLcz_ zAE(4}Uj^Xlhu@mhfC5wl_SYdGdPX|jrSH#9TXz3>RMcm>00&CSeFKOYpq!W=zImDL zACb5WCJ{Y3cujp8Dfc-MX=ooqWKwCeU6G!eY(#XHFC$kXy#v#8mECM^3& zv1xX7b<&@~nY56bcQbx2_zzmJ$M=fe?MY94Mnpk+@fja)7rs`$?o^>3QO8K99wE2= zCgs4exqr2`ccIzX$lhkQb(YF|1?%;2PF11=(M-mR7OA}P(y7YAslQKt3k}4?xb<9n zZ1wnksU81=^aJ&nn7ZZW>qq;mBfCI5BlP+R9rOEwRE^P~`+L-5$8gP)2*i)#K(CQ` zCExw}b7u292E`)c6XlbXWNE^yI9D-VPO&gE*BhoUGWbWc;2Jd- zcaE>P`rm&=CgjssB+DMS_9N+pR3ReTzJBpKO{C%)ku}*dzqk@exyZo!oBjt?qDs*I zeyjj*JwPqI#*I|#pG&Y%#rJ9mypOgz!HRkpEOw%}jhVS{0-m_5O4UC!>Iv;@dDel0 z@ij^njb0>VV`BpnWE*tl`P?|stjs2pu14;ZL>QGU&$8IS~y!O0@}&6_t&(bqk97?JTWGLsIC zyNaNozdz&xAs9se85gt|g(mxlUhc>AEv6)1z4Y$N0~R*+pk8TaX570E``NNvBP@Cp zGs6yrhI^DN%)6~cRJ{Ihx}o-CF9@<9%XNIpRefvON8tk+JVcG<2y=iD2mf+{x1O@{ z@>rifotADSCMCh(j9}TpuRz-pp@}@o8jEsW)nj&gJmGXpkCdH5qswR0XGKJ^dVz#k zOKFew2z+#269k2#t*Z1x>_-x-8ou?3O8R&geY3)UMc8ic)3g0`Lu?llN3M0ktdF(C ze<$rxC_)lx8q8Bq3;+7=0SgDmh3)2_{6Hc(lpSoSEL0|X#>A5b%)yW0+D#YAG);hFu$E~#{D zD~+Jt-Hqk`#(lgPelcGM_hQ)ajjFQY*!MOfG`&2(+sJv2<#d1(>+J08xHVNL8x6X( z?K>soqobo`g=ONfLynJ+WeAxITqow%n^>>n>j994Y zbapXr{J0qWP^q8ctM~~eOPe$%(;TZF9$2lOZ##P0(SFV()Yje}5F&h-Hh?W{1w#go zS8}3HA5PY}a8U5-GrD`CbId#@w8rm-@Ox9fVby5;wQ(|JTNxU2Q;D92n0Pqlz8$}o zCynyU(hvdrdhAp@?!G0(C4Xv`SFi2f1*t!GD6bwr4Odp&Emsg%a&>c?gZ9tNI7}l0 zV$)6V90d3HozdGG$cTd*@R6YbR1R9b2wHK1nrZi!N3USO6EhFbC0enEC=}w8R0~cm zJ1~$4A^9T8@25r$?xtXAV19N$9Qlm#qV=YYLUhiByH0m|R6oi)yH<>v5)%_ga>1I! zQqfolvtswK8a>Bt5wB|iIkRl^yGi>{Z3Sk&wlKvIIytk`FXxo}Oy3%u>N47j(7=K# zk!d-apErp?-2TF!Ki4ue#6#&fxbwl^cVUhVGcz-$iO=qN(5(k6$Fn0gK`A0OBtX3h zt*w2&G~m_502Y)#y+AYQxn5GUGhtVjm7jkRVrv_0BQ0%h;qNAwhaKS*!|Bmf$QP7y z5wo)TXyF_k8rnv3&n2wwzql=Ara~_JNo!LvU_OtFNEUI}hpoz-;i*ui$E>*8xG_1sPYnu^BzfVD zE0>EVhbm5FuNR5E#0!%ls70X~gw-q1nK$d(g5u|W?xD^p-doKT(zj>!Yb8ranPtg- zvPfcRy>1iOX}YW4eM_4|nVy1}IM(8t5k>I~3v*GY%A=jl7%sE(Jnnc6s+_L*^e;g}3f}wp!Vf zw0RcqTB7$g-z+ZNu$RJ!`3boXn(W3yb=nv8FEh3CHB+=hp(Tjs%6?7oJTz3vS#670 z>ycUI>I*E+_sLYN_lg`}w4Fy0#R;Rz-4feKNqv}q0%sN(og^YE+PdU?@bw6uo(dVc z)_o@&{>m5kOx+A(=`$i5JFc-7lI9}6l#>xzA8cX6mkxpQ1SQeq8`wlw3iG>Wa_#HU zbKy8L#J_i={X3%l_F0hay1Kd=)64J2${gPdD}^~^vx$D0i{HCuL6%F&BrQhoOnrxt zk(v1iCl^=iw%?IdK|5nM%KV`?vnb2hqw!0X6w`RJPh`a^QWT|>@8k?;zIkJ%GtNlE zQ^1Awr|Cg}1{$$q+eIdgA%j1134%Ch_38CQUcMyG4Q(48E$A6uypg-JE!T=hqg$g& z>d+!7v6ZX!bn1+1N%?z~t0X}ccdtA!oofri+A@bU$Rc^Pim@GDDiQf9HEqZXg`sT-ejNVV%_PHSCvDE=) zew=VQVYFI^W=(&JN?0LVolNk!E2yLQ=lyX{+o)Q;01i^(&~g-Yb5 z4Tq83-!uix zQX%ScXMrhkf`#kBq~IY7%=?4MfpZz5z&PCnzUVAK;_a0-BbhqfKQ~O?Sw*5_i6i-n z+QZ*$vFEdlajNhI=;c^S@k4|px>iyL3{341IkYVQRkOtdAFEV+q2$p&)QMXWCY5!5 zEiPvFgPdb}tAxti94POvi{X0>DtU8&<$6t1xqNWNqZ#?jXB(RDe-CW*I)1ztd^gF~ z!o502T4=DT{g6CjQ&EKaMPs)Z^$W-Sq0aEUzErtu6CIzG;_TW_Di+KFG>Y7!HEnDk zuEihIiV>)e>|D^gLF167gglRs>%TBSSn;L7LjYKklMgb~*v$i?<V_>qVKnTDa+n+^;!mgZyu|!1nq_47w8mSU)B%l zPYNy`uy;ub8n14=v-kP^XYVRMHR@4LSrcjbPahl!3uo7tQ#j3A7>5m`_T`1Qhnd%9 zt2-~MT4Z~7i_5zSaD-7tfUi!`w~HuJpX|co;snWa%)L~6imv)nF*Ir6zZQL7cfLMI zWxWOa1q&=IzSn!B7d>oNSKApzNS?hfqa~yHh>9_PBwOYDYIH7!P@?Y3`;=K)mNxNA ziNdY2Sp)OsnFS3vLa{0)4vMiEPlQ4w>2m{{ux4;PoLo*u=F-%tAjd8TZl*@~ZH z4(%2R7(&eF7jjZdv&@sn)9G`RLIbew)KGo}PQz0m8OoOE$(QKmKyXKTM-Y~JwqNmc z(A3imeI5zk4O%an>^&DCNi+0_4pn5!&i2t+7QbMs6>dm8yj%qw2u>2_ zT}ulKyxKH!A7-z!ljXnr4ZI$^+JY`IUBs06y?+}S>6lWHSQwau+UJSMe5?#LkO#RYTYfjwXlprusOvV91UeE>R%gr^W1agDi&(x z$WAu)!a=k*Z=IJ^wyQ1slCogb6v9d(^Xwpsf&_H9b67#6J2hl@))93-$t*XfF7 z(c0@Gy-#=xax!CQPu*O(U_V(1QkCCt4e*c}J@MEE%D zap>*Nzqf|g&<~w$V&W6kMB$T)0XyuN`EQzNmNMzU(+w`|5Lq&!TI_$Pt>*pjl5dCL zjAJ(65k`VWi+Ir|5sZ3#X33XjU&QAt7`zEz^!JB8kC1m#6snl7 z`0_WOz5rKC?E7AxsP@D=K6jU^dn}#^o|2{E0V0wliN~A))d7L(1vN2JVY4eS841x&!wV8fV%ifep$}12 zS6KH~O)riWFOJ2JC0oz#t&hw5D`}0K9%lZ$cC=biH|b=~GR+fa6LI4$ z4{c~D>Xo_#J;BFR(F-WY_5Ljvy7MDiEYb3%mK40AUWWAa&!;*JUESTIj_uf2S6wBc zNVu^k7{Ea4<7XwDN_6@1wyzA?pcDFO*F*7~&Zz)T-D_5sALaCXD9D`8YLVNK1Ig3A z6ejehV5(-=-%U+LJ^2{HyS-Pe=FwJM+Dx#(QTrt6g^Y4T7Kv+MU8Ta2TFCh{$2(+J zirlf}^f)bPti>DUEoc4BN@zxLCR{62Z^o)q&(=OWKY{-lHM3cE(|F}zk^Jd_hpfFr z7h2(*eucxLLq_mf6t*4NW`H8p>8$<}Q5*zikANx2B2AAAE@Sy}P)H(4)YS_o6W zQvdcLH>?ABn4{C@>eQlsz4n0+$;2+KxK<7#1G%UN<=90>p-O5XtsCk{$?E&WT;oW= z{(TX{k>dwyc4xSK=8xBeaUPi@Q?wg%C*k_e0q=MYk{5K`gJ&g$t2ex3*;MV%_qY!+cm-S6Cx zvCe`%19P^Nps%+V0|nk}UKvN~hmdfeY}&EK;liUh1dcQ#7Z(ny9NaR(a+qkSWr>Cy zY;Go(T%vZ`a-Xtr6P|Q}@PUqlV815K{6k7Zn8)0Y2}F1?lS2VyRivl&G^0Eu<(q%b zqFJ5XBn`JV0)M^4cWzm9WabyfG@_tfBz|Hzv;OQ+@bZgS{OF#gm{ud=6--nJmS%*H zZK-kD<#O9HkNLsdo6A6n`4k;M3~$RF>}d&)UvX-tZdyTFlci-N$m2pGyZ{5jpsr=j zj*BA!-l$OPO>|E7$SSI~=o5+&3N&O$;1i7xAIb}aNQxp%%(ZpI7e8F2A}8_l+?M<1 zXEZmzzAwRMTmQ<@H-7Y;)Dv`~)a0^KlKeP(=J%IvSj*zks^3cB(+Cno=Icda?Hq*4 zt)(6Bu^wLgrmB&9x#$;X%8pTEC^9b%#A)*|@#`E4F|axY1FKLN@Q(Z)2Dc?h$l*R{ znsnlTIutUfP(4LLe`cieP*GOKfn0_i@+`7vu99iuIJx8NStF~BVR<0j@{E3G@}4Gz zRXG&vL%8<5S_r8oMhu3N+_?&~DZ8Bla$+TIu3@VxEL1}1jqr)4M?My;X1bWgVhvI^ z^TVGpt1LA+pf{-{%JEQ)cRmOiB(v}Gm;Bgc{e@Z3rcpGeLf>XtR8SBr`7EXlau>hD zcNueEA7q?I!Qenjq>AzT5uY&|uOZV4)YDz4O_b@Ff>>ZTz?J3TEe>lxy;(cls~w_% zMw3xo3l#lNNgZ%wo4aX-+|rCABcvzHKW$$f~|XR&4N5=<9$VvQf5hqVK8nOAPZ)Yq)WK25LG)& zHG{y~1(6$9aY`>}(XxkBRZxV-x9PZk**y&Q_P+nSp%$o!C31wl>3_xb*AIvp8^E3Tz#EKnu6# zr&U+P^ZL}@ALP5Np}}oI(>6DA>WE{1D3QG;W4syP?rsRrH|(ufG-o4z!YJ+Y!%5pE zi59)py~q6(Ey_P4(M`;m&3wvWUd3_Ei^j%Nak|*a&0U!()jG>`#-cG zB?@Z2-vXDv6BOc@s10|iv%TwoNWlS!fg7OxVQWY5_gxr&e6x|lv41wcI&e{r50?JN{wITB7jfZ%KUvE#@_fQn%P+!%M8+>P+!7<$3O6OXaGQ0N< z#xI{!R^BQsm~Qa+xmgb=WGCQp7pC%tt#<(bJ@|SEmPw|7Lk+DTz-Y}t<2&r}Ow!WR zkDNYzskmxyz2*?0k|k%V!UUuzqTKrdNl-d#BCF!F&+vjcf6QxOgNubmjhK_KUJ;*Y zy?ys-1$Kr2zfsvEaN#i>Z|;+2I%_?bkzwR}Foq>_*-kNsSU43A2S>h4VQ6eD2xM&F z;|a8CERE~GMF4iWAU$JS)n;4eWkNU}tTylXznAYg%A_$w?$DT zBZvB{7Es<^xb^@hdLDNQ_%W$Wi3q2CR zz>ItQb{_N1c&tP@HaC4JqeLzuio~nbzst0o)(my?T zdF2uIlNxlS9j~EeLSUE-4U$jj-Cg~8(b*qdQ)|~t8#M3U4TCM!k;m19VodH6dN4o- z<47Hb%yqcQb-39RyW&(GvpT0RUyfj>DTV;vVx2AW_kuyo-#=i`vc{?In6Y+yVbRRz zcQbo^x_MoBKPUinf)w~CIPhXg@$oFZzS6x-p!+ig&r~J#!{6~VvP7E3#!*m(g%L3s z5yX!@17ut~`!0i-7_#(fJLUdsOZx2V8&5%X>l?7 z@#Cw2W5%SWBA^>73`s(UV`Jrwguzf-)D1v6;ReA#@!TmzLtP2R1Sk};Bc37;3~Cy< zN{*+u{X%~Ha7K~|mZ;|)rtpj)yL5X^qfnp#aO=ZvHh|Jez&#vrHe3uCDoq&HF|%Zg z9mDKK#6qOyjZMJ2UNfC4&hmPknHLnX@H!y6+1+U;TmUQ(C$&(f{u;80AUBlEUhpvr z+=if1dpKd&R3^PXTLOb+q2Nmpe=A|$6(O^{InzWtZs>xKIy$z0T&5u{DJi)Vc=;C! zA0L0nT7;9IzpL5zr=Z8y6mhr0*^=wkVJPtA9T_>8LjK}6vTt6$em3TfmL0f4F8+no z`$zbK;}UsD$52>o9M6*J!2u?)LCKLhFAFLegqU*o6`-Hh!r?uD<{hyKL_p&ErWiC zSGKP+k~Krc4<)1{uKFVTA~V#xyWHQ{FOx#SeBTuI_RdP$7akrSa}xBq_M=q%GI^|) zYsY?&n>-&RCq`}f)!I2ijKxyVJYYS6r}q{SD((fvw4Qy$c(Nd&Q2BVz3YiQM8Wq(A zL)&-Y;R51d4t)6Ib(25bZl0`JQ1aPI*~JniK8Y(PQPX%ifHVZOi1u{0A#Wz5yB0>+ zWE>4?=d)YRgNf1#YeZdOf2?s&sx-glO^HbVfJfTWYC(ubl^VK zTDt+60kL+7)7Nk#e!65rqYRxgC8`|j01cR8SXfjP8y}BIPC>=}E?eLnf=Ix8rYWDj z{@>N#;H*Ju)^v_IR)>!Ng26{V2=_>}1#9b6C{fT3xdHR_*$Hp-Qvte3Cl>yM=)&+4 z1$Hb&!H+^jOB45U37BSA4!q!NTaX&XqVl7&o1@jjmQ?B*C|{vi3iZp-?4mFtwy84k zfoZzGtNr1>fro0ht%=WJ{6BF9GBYGv*S1yBdx%Kh5-yP632Quz`1!u6kSvX~%l(am zkB=j7-J;!OsbYNS@$u`o7bAUOe9-VCS_Fdt|B7?SbO4AL&|X2Mss)2&-5jnDPsqq~ z38K-T&9`Oa>u`2scR2?*74-}${-#=TL{L#;j)T`A#$XaY35W*XT9ZsjY5D}Slzd=uY@!p>kkLGfKw1^d3C}>{Tjs!snbzP-gzc( zR-@2Oa)GR2aj6C+6pA@QD{(%SmX@4+e25zP!mpp%!?i_6>S-kJZzU^+z_FQjpR}(9 zaT{Q|T~G4pYeqhY?SFBF7c)29m*}x*)tym?D~P2V&T&h7p|tqpPA62+PkRqbjo`+^ z;*}$Dj>Q%m7de}4+!JmY4ewIDqRxWbd8|=g9)Y@hHdUmk+IS!HDvHZSGNrJAK-Eon z9JaNb;UC3vGfIhwIII&8hb|o~SnyQpD?%K01lnfWNaKMS*Axk*Hn12HseX zS6`WXy?2NtaDOba!HvK1Vc6{oHR+SocD$b}Y2^t#Q|mjCRxP1rA~gLe)2h79rTxnS zzr5G3Lj|*v6~aK{h^q#YN<<=!!_4gOQcIV=T^!PDE9a*z^WAb#UR{oW%$cGaZls`k zxRDCv8M7aGvIjcMG^X;^VRYn%2Ji{*U%>O?J{F<5HH0@wrM6u?4fgZ3l__~IqA@8U zX_f>L|qp2 zRy@a{tZ$(9o;&Ia47>A+Os3!{21nx^;SWni-am<}FR1ZpL zmEC9}j2> z7?jUZ?&yu*Iykr8u*YU2kwRH#&NO@8_E z?ENoGp7{mR?uWLKJjdN<0(U1AhbF1?ArtLySsgJ;SkTe%Mce*ZqZk0q*}ehqre ztjHQmra469WY3k?Xj%vf2_cg_7~QBASsF&7*j-4;oX;aYVE{ZddB*+)eiC!%XeFA5 zz4#1iI4AI{$+T7?E=Rxq9H0Hoq%;(DpYpd%%Pf}YYpO~iJ#fJ=6|ORcI$$QOfs6|J zW@`#W=PC~?v%7}_i)(q+lwLex70o*jTPOCOl@&YqG3OElau)A9^ya=Dv5CVFYECnc z{?u~y#`()A*KSKA_W&f1cYfb^xbbAt=y9j7LE>-w{HnwGg#}aLRCGg4O6A0vvH@Wv zJ2+D0Y3b?)!K46cnn-L&*H_%OTE?CiACq1t^+A7I`9Diu=0&)|00%*1m_aSnGceEv zr6kgZO_vHPHy_YAl4=LBI{nDuW}>YO_(T=7hhyc^%i}rU01bzjvBrxJU&?=DS+{> zqoU{KJ2k(tupe`7d`)u~c|l9e6^)iv!EhG2`Zqt!#-NvURazqoZ3}qNBwf9Dn!)2; zVLjgLTHBTTYx>R0r1ULc2N&1(J*7W$>kiVJVxVcj{(39pI!PWmy_$zgzi{8}v7EALr)g!j)j@JV>}m-aYq$C%A9!9O`3*4$GBR+>1rNRuTIE*Qm=)t4C zWKHAeWi>O(&5$;;pRl%_`$i?0G<_MBG4=ETnpdo7b*&lb$=>HGklA--3! zH_-=$^m8JS1Q2{}ZEf42?g|9o6h5>N$5%_EM^7v!mA03+^|5~}rH-WN zXh4iwr0jcQp&xRx7^v6r-udT<*w3n3yVU+*mKCih!Kg zL&?86j&;X>9tpESv(HtIr8pA>G&d3Tm3sA(w@S}~Dg@Ls0{HLsv3{e1o+g?<`I3s| zAL2QcToV3dyC+wAGKvX!koJu>+7w`sMQdlE3H&P#0(z$ETreEH_+#}`rbt5!`MaT! z_Vz66rQlU_x`e3SS;yOl;+@3&5!^bGU_Xj9|d&cpe6{SO)WSRz=R3D?m%E1Ux~$+=Q;>TuKY zi$^Bj&A#a8KO^&G_NzpPEbW9!GKoxH$*{ReFh#?yVFZLKWTFwW6PT}DAw_B4xf25O zPw+tZ7AH|Zv;@o!p_-QOm9lxmNP7Jue<#Hl!X5godyyel0tTr>S5yeIAE6Peq((4i zKYrg3J&$vMp0fQz!}CZV_%0HSHS1UsbOia#ELxJ=Ds<9Lc(?fa;VN#ax?>y}_W0!3 z^P5AZTP2eiJB7G$1J&DMAy1F-pF@^5PU|%etxx4IXcd&nJ-db(bQ`zabr}Ck{ld0p zfllq}>7zNHvGWPOhg|0_ro>2L)bO5&ogGHoAI}%v?&+i6j=W7?AXjOCA0+n__UfoO zRc4g7x#1^?6}x@p)$PUk0t?=eZu|dYGUTUZkH~oP=-Uoo;zG#G)E zlimCfJ=c+J68hVo&<;x7K!-bAi76sZB<`DMwcmDu;KBLIP>@|HSQ6RZz!o%z)VZg> zKS-}ANR2(vxU3rp0p(Dn6|`ScW-r3oOmcsX&SSjJb=l^v&A$lUCkAi`Qsg5YPUj>6 zlYzzbPzK+9EznPxw*N1#-a4wv?E4?5yAe>j1VOqRl&he$D526IDvcoB4N}q}Ap$B5 z(%oIs(j_1b5)$&=*ZI8v`2E(JShHqep8MQ$_SxrEdtS!d!w##1CeKz(H{?~oJ#_@& zK=w?q1M9JSY?or)uHSoPOvbkIbFu9UuPxxh4b_iWV)1TTKdrmQur(Kg5sqc=g2D6n zNk--uQWSNI&+@;juKm_=jmmi7Ey0Pm#*-?qCoc^kvWFk)+U>!t@_Gu&Jj|PdYjQjZ zt*iD%-~HW%L`3h9V3=l`e{5*>K0S5*oHhE{; zTsN~X=JI;)lb)qAfpv`$M?-@xks0=J*x4nKso%{xl#CL)y-%q{YXs&4`Qq1$dYdD> zF0MdChex{$cV(OX(n;r!bp}rCi z!@nkfm024bow&=Bz{0^qS{~^7`*&i=?;08n4ZV=$Gq?gyd@QNPMKKg|%z)Q{T$O9L zd8QLuzO-4BT$(P_y<)z2f^PBBo>lAk?WaF8fj zuJIhock8p_a*Msc}^ z>B=Q7cGOPw^7Sh$lu1{vsNPjEmnDp^uusCMNT_(_rs?o=TLZ5t5hmxUF4h}Zx4%oF zN7xNNNfh+J!e|aKnKnSIMiVnuVQk4Zq6bXO2l+0wC+e%C+*lF2`b#5rwfF+Z7o|5J ztxqlN&K5hvorJ$Q)K`D-xH`0y|L#2Pll~*ov34o>PC*v2??aXOu%~S%*GX;>Mb)E} zMu8BEwaYv8Twv(im8SdAuXMhh2uY(xV`|myOSJAo8~?u5yTcR##rSfO(r8rrUUVO} ztw6EXPlVD%_w(FIOa#j@`f_4~7%`HoMAzI!7`Ku&j64=0?WzMry-~@@Kg`|C&DoKG zhZys>Zv6kWB!K1o(`SDQFZOP ziAhGZWljEcfvjxCLR6qkt9hH*G`+a zJ@%Zz?`M;zgXaO!W9==4@0XEx*;wU3x-cWT+cGuopXlaAq$eE}FG*8SRFASfrTVGh ziiz1$H8Ej6pfJYVFus?Gm0jNR#3{4v2VZ6HyM0QU$G+a;N3Ly8(gJ7xSUJ#2`s-cI z1l_b~4BGX&y0djv#O`g=Aj+a)UWTdS%R9-}%}&pw%Eo+$1WQ?LY<&D~)_y?`$jCja z{`^ddPD;XsD>ckR{9QW%6A%OX`jkJ9y+)476LWlh${`HlZSpX@2(VueLli^YYx>fA zU)bCr00ec>#;Xy2Q8yj{!jq6!apuM(L35%Y3z9#iF>YDfzw8Oms~(cr#xZ7``4RKI z8lZ(yPF+@c3U?K-3#-nkFD|OD+AzXMyNTFWP`+;wnNDqWl}?dP4|%8ke9>3)^XW>D zX%}V`I^*%zn9)*=knKWropbe zSsQ3i1;%X6%$r|qAaV=ngiD6SXsOVF>kL*^@zbXWkuMqk{4Nwx`8<$rgKIN@@@b@&ck{o(Y7KPb7MVgxKLRZc-xC@`oHk+Hv#JUcs!jBA6n9*!K|IsbPa z#(Oz~n5YCoZXp8}7pW#h){|6eH%b^+fv$hJ(CmjSGW(FFy9`-Btw^Q}%*vy~QUkLoI zGsXRRvEjA%pp3vbA9uMhHNfxe{>91B$x;VPO0hamtHGlfb&Fk8lv~e596U~W8r&x8 zi{GXg@_mpuzQaRibBa2!?SXD?ev`R&1+TBl23=x}vPH*@+WsEvBm9TMBN~wppOAkn zR8*MrQ)}WkXZvxx2lbBJqrY5YA4DEIrpx!PINvgTa@}V4j^#%9=gA|^r-C3D=s1fR zDs-jQ+b)0kZo@}fGyDhsxrX|0vC)%D6ph@0<(`ilUHx>Chg1VB=f5m$|7H)ZLffX_L=!{zK*#q$6gkDkc;kCE`VKh;D&&>6d0ljREkM8n zHcH*!vrR=MrB;KhGi~JXSK7V0a2iqL{iSxDN^3e4Lzq#5RPTvc&jgFkyN~3awvGR% z1$(MYeGqdHO&!w{3Nn0VG8Lc%AdaYlh%}rs#_ey`$>L>XLn+yO!;zNd=^>?5i38qq zk=sNJ;=xx%J(zc7Y@_{K7n^#o&hZ9PrNe?4+;Jp6P+D=jrkE0oAp#EGOD(db;A zf|6Qa-){}k>*A@VC=a??t#ADD*Wz=G!0^G*T5*aBiuYF!uY0DJ%xtrcvhg}rr>*l> zft~bT1WvPdRGy_TxN|5~=?>0^mTecm82m+>zN(1ZZviNyjj~9Ky^xonXZKXwA#4+T zD9O!TFnIj!+c&08OHm=AQ}+QF&;+b`9dUt{WN24VuGUv%NpP7uj7o@wD+AJqP)j$o z=~E%{g#}j@(sZLGFg|7=|4sPg@&;;T?kqQVoJ4F!2ZjMo^*1xeVkU+xadTMENSUre zzbJV^TNGK0?|&LUCRO1*317I5WZoz7?zq1&#I&$y)buh|;^Q6!72~1+h)WH@1djk? z>tYA$4yB28o-eScnXj1&4N_xKGYnSsG&MCF@#>WZ507a7=b!QY_Na zbkN2|JEg$1&$)WH63{^28BBq6wDdP9h7dv|pC*sINST+RQt_Z*6QezOA_rQkG$I5- zkxutCN!m^1pRmU7)-C>OD%WIP%R45Pu6`%m z03`#e{p#u}P)1SRrbw~CKFkX;JU`w(g}Vtd37bVif*Nd0MJLoiJ^ohh!}M05cfmmF zuR*;W1|g^mAO>nL)T`YC&xihBDv((rSlDpn$X*M^gkK%oTm?e(@HI-xyG0Y|D3I&q z2gPebMsE`+N8k>RRlC8n@jn9v8VbGFg&lH!+9{~%w=P#5;C%&$)mFXzpkK6mh`$NZ zq+>&a99R4GybT$jF9)+-Wi+4n>WBT`gy8 z#&Rw6po<~F$ec&gGbl5y0+1)pah(85hl>)X&r<=)vi&9;P$1{Xld8i3NxPqYH^7?d z4l1@PNWN|U`;0d=7fIzeG z7YV>7YzwwSzF%+ zAggg3`h-*h_};JGf7cPVU8SeD)0TFh#qlu$kyYmY$38YL&Th7zgzA=`NT^;R(}}`p z+Knv5ms~C~a)$41oPqLq30E>_aK!KWlIH?Jy--Ng?Cs}uA zf<|2nl5KsF#A5D<-2?ACdxs{Z+&aZ5>7HjCeJ=#rloP!n?g}}|9EQTSl;%&_J@U7F47mKICsg6gdHYr>)_~0D{!=$G2C`AQ}Qp z8u^1SN>IkemtQzp4fX7MOs9GDWowkd4KVz}2VT+sv07ns0K6uAxa|g4LAcz#C z3SU~UlP~@*4~zj!2DaouYal8g@LrH)Zww_H5UnCcoV)2BAf!>v)%@56kJrWUW7;Pa zFQbAoIMlv!+1?wAG=O<<>DXOf<(dvPHFb;i7hE+8h8TB`eQkBp0{wbw81&xagO07P zq2bfh^Kduoyx}am=$RJYxIjcXPn0|l7A+qjGs;$I}BqTNmh-VIeK41X$?Ld9>59;j}^^eDcc2W<%Xpa11NU=tQrn zq>2Hq%#a{K@X@;+_Qf?W_|%o}c~g;0`}nvPGVlsI%ounlAf!YsyCLS-BTZNN1-Glu zL3^j$^pV1SgwWf`WF?fLS4*;<*QBImi&|X1@<17>fkIaTBI1AV{-co?t+zfgtrU*? zr7#KAn(7WmRpNuLWU#{l?T7_OCJ^Tc6YGq4O#_#wj;$14Rusc9X1y3ly{-912B@-| zqNXMwV*l@r({pq0I380|dnaC(%QI`&7kg=C6$dSZcN?@2n0a#rHE{AoOVAF3Spu3C zX9Gd_JhJdL27|L7c?vu2&dHoZF9mcC0zvj`=dD^t!B@2BJd7-U6mEx6B%D!ll&^1x^#cT6Mm? z$INb6SONH2py5Gkb>Wi6!p4RLF_Cl!lR$HOzWWH@9-htYtlT|Jb-iuRepG4%f(lHi zf$x`sEZ(_bGE96YbW79H`=ClC^2GgOYZ_D~s3uzHF z41*hB-$FOCuy*cta9Fry|A}b1^pAik%VeV#wY1u*e$_?lGBuc57JRUWK+9y~=Hw(w z4`J&-l*9kgLr<@X$^a$Zi|AW97!SzFkojS|tmJ`qB?C5x#0S-1 z>WI!pI%Zd>zr!OVBQ|boYQ%HS%Y^^^F1@$4ZXfFXuxI1k9z1{zJMn{snfje-E|8PK zclE0XW(7Bv1T+ zjtzGE(B>9~YN~DJ@>>U#si_^Ltd;sHkkenKv)Vbhsj>|V*v>jm7y-DV`0(MuP8dWhtEv)#Z1v{5 zC{SNkO>-z&nh>SXA2{cHT6Dzzdj${{FZ{2O1pR|R z;V*Dgtxy4*ez@k7!{$_;rgaHZ!6z z$b5EK-D=Ft7kU1oCHMaX3f`II^H;R@F+Sgf81G)pqlX0FeFzIdu`*X<(B-Zfsb0 zu0DktnGo46{r+xeH4E&!6^gAV?tbM|g3VOSL<}+ne$5LW?$Ax6c<;KeNy?`=fu&Yv z4XUUeR|~Xs)bEF#OXw=|dOu8tMJ7maGJjk^nk1Mj)eDxEqX;IL+qOU&>%Gl-7{GE?2a~G3!Xe_+8QYV9O<0%$7dPLDjrn7fVL6(sw7LeW4i}uP zoN=QXaD&1^Dj8;^p1A)jb=Mk=;1oq#jYa32(NTbp^#N0a6htlRR9N2dygHu`dux!= z9|+-I%Rboj*WY$207?XXE^>(I7L>$Ei)RH|iOM74iGDpAfI5m5)u_`ptYk8?>L7`vS&mZ z$TUruGL~&7j0?4P3^>Q7mu{Yf`uNnD(??yq3>0%SrpX=LcyAG7*UZ)cLP0&=gl-I z=zmA&h-f9TXvLQb7e-$DAR8elXew!rCvXa98t3piaA(vV_g%kt_wVTBB;!=QoAy4Y zWW{>uI?Ntw1F{wutWVH>yH)Z&{f2||;?M7{*;gYC>`0Tl`mM9S!-bGa0nXOBOa{QL z5HQ{fV%zHF#lh_o2o{b%(mYVr!!SR8g?96YC6WN6#s}XZ3L`iZw9~{e*--N)9usSi zuQW%p++9~5HS<+7g;jT%Gu8J&QajcSz9f9`&%?MYxke8xzf3i?YPbm_=W>G&2<(;+ z^hJVvkQ?!_rY0Fz<`>I|QLKbNKe?*G z?eGZwA_XWyLq+YNJ;mWsDXs@b)5LzB#<~i%h4E%Ds3CqGp6z!sbS_8A%3#4>)TnxG zfzI>Xwx}{!3tfVaF^13!%G)0WzD5oBU`mh^UyDku|VAUQ=~-^&ZLf8I*aW zy_=njzTAN{DGJ3;rYXtWnMKxFl_yBV&R#rU{}PtYX{_ zAB&}^>n8f2P`c~C`I7{xE0+;Y;=0^ay(Q8-S$*tkH#1K0eEiu>tKmW|y=2#)spp+G z_gM|C zv*3+F?h_nSZkR>28M>2`hcZt_&A_k*x?;wHf`Yo^@**?n>c3S~*tb(?M=7)QN=w1< zu^g}5GNP7ZKhqkNSw3dE^CejU@k#31Ow81&enb8m!;ccHsR2jEPr(^n`gU{Qj^!}< zP3TWhu%fQjTwV2yJW0~9;T2=G4tdfqBK!RpA60T=-4vNeuBBMzBhCcfagln)3-Fal z7I|H6vXARQT5y{&|J1o9f6-)= zXWw8***ASZdU`#xnU40?luC{bm2f6)QfqDeUQ9@zr9I{R!%ajXyw-O-}btz4QW;k3l>|~t}Mo9~7m}v7_9QE$Lm3t!PJL1CA z{Zl*coTZ0)WOi1?+xe`PYngJ$bJ_hbkrJY)6;bx zOLO%ycV!n_;`f#oThYK@EDzlejCIG`+)n9Fb@!ydZqs_OymFuDsCa{s!ehKuH^Ftt zp0H{v8Ap+J1~b`kCH!6yQvttILY+dL}Pqx%y?Qv$4~=@fRg@W`R0v- zQq2gH+UW0LO_rP3G9fP$1An-dP7$C_u?{EW$S2hKl|05v^EmT&$BM4b_kTeHRRei< zB`=~_cy_lErm4LN<$neT)~JqsW< z?F_n3v&~ew(T=y*UHWz91&zYLVq@QZlTG^1XL0<{O|IT0kjSq=k>LjH-RtT}VNlUZ1C;cj;iSH3rd5Ye50xjgcBdu`aNiW<-xn8+pu$vxUB`JWPrn_S zv;mKkSp_dI*$I6&tLh+5=Dg;j1~l0^4C`8ByK};=!093%Zm&wA<@cd+y-7`T=){SA z^^Thv)w;+6ABR}2E}b!6B-z)AE#7<|Jn@L`ldWZEU#0mJc_exMBU_uCY@HTKm)a$} zyO|{Kjx{Or*l6t^n0`;4$>bE%r3VxeqJat$t!wc1xHBU?woKetZyPN7;`4wdI~k@> z@l-9KHNZYN3{i9Uov8aMjPyawz{tK;`mbHTCMxOvZpQH0+b*7;%3N&1)Csj#+S%3| zT(qjA54MNTm=cn`&a<}b8P1%zJsZvOM$n`#8HUbN0(M31Q7Sx$Juhv-WOMTs@1O(` zHMbJClB*@=*GCWq-|v-%BBh%jXTQi1mo-KsQFwWhYqBCww1^Pqm%Ue9n@f@?_-2

MYOHZuQ56+xr^SC1C=H~2)jkI7W zogRO`$Te8FU@H9xSua1%z~h9x+cmw){m>E3A~-0|$jm+@ogNfq?Ol}Gu;+nw(o`nv zcYZ}$apk^vzWS(mS#`3O;_vwtmvw6E`NGezg>+B+M}A?`PM7#fgEm)!}vJ1aIwq5HU7hg z53BSYzPFkx{RbpAxn%Z3)P^P|L`w>xMSx`%0V|Kj8?F#TfH)O0h33;u?SDU%KH;`x zaC`J&$;-q37yr+hK@MrJy-hYZ+e|j|>oDm%U>AEqrH69ngiq>kYruBGV3I znx9a*l9TmmA8oH-qul&F(cYe3>TM&xp!1uMsMyWaTl#I_Ty6;n)&m&lgTo3VmLWcVZvzY+aIsKm6rqBq~CBpyNkvr zBGO@SIc5;&@`>4^DUd25?dpJ+Dt=bPWhZKpe)1q2Gi~ehbb##nNPzi>%f|P^pax7o zH!5eR+NxvlHZa$CxDSAgCHq2s%6MJyGC)Uw7gPD$T%R`j~=Gisj- zj=ag`ZQoYf)cID~ zjLX^wsjG`aj5|%>{22g0RtxNaKgjknYW(x!#N7LKA2dDjwtxEINdmbqCrxJBr z(nG&LR-YWc(KK+nB9^kdeKCH%#;~>`etw`^bzZbcC)(d=VCUw2`1ktGxd821d6Mkj z`yyUTS@_5jEG%pmMY)|A$3K3=masFIKD}1tGB$dV zAFH$TOW{{zQ_Gb$FT>~?*Loc!B_!5&c6d%~Ut|+B+@-I954p^7N#y=d z(MA_$I9Yqw*9mGs<zcol+^y& zoAh&9dHL)e>C4N@Ixr%pz0xMt<-9W|m3FT2S-d-TM&_cR`ULl0Usgik{2%5jyY(7| zw2R@Ha|-kqI(xrleF%Aden;UR^s}c3MQ)q7_Rd=%*Er>P`$S4?$i!dH(}LdqP07L} zp`4_SJT{uVfZf(+zZ{`S#CAqsLxDr+<6NR}(0jHjLvM6Ur~w#e~O5z8Fa* zbP`Xqj!!HFa32_jrCLP4Q9`XrwTM@)di?R(bEn?|1rDOmasJ-3JRnU`XZB@qwAG`+ z`KgjDPV!Weu8oN9>kQGiyzYm$MxMYe0J(Ba1+od!cs(|h2nYz2>yD)&x2LK2HyVOz z8;v(C^65QmNnY0O?lOtXGuMaDvo>dQQS9Q-!ZvyAHi1qlb;L4R zZ?Wx`}OQkl81E%_pG&pZ+v3DQo9vWy|fWAap9hJ7^366DABXr8a{p~c8=$~Qo9!u*@8b$ z5U(kraO*Xi>mujmvs>kM2n(j?gw~^5no{XBLHjIGH&CYoj(CMS zgNyv|uZS;JIIB*=Y&)hitOExgdkn^Tij*#y3JlE>);h^c5Qc}740}B!jeeps`^Kz# zrG=!8F+{hes%rmMMGAW{+Lm+T^U2s=BEkrAJABbD_PC)J%!X7vAtsL8@7^(_9=W4Z z1|Z(8-z}B$OtW_npt1~pR+kcm$Lxm`KuYEc~|z=C-i z?`@_#!ge{zn!#-Lcns%Bzxsqx=^BdaAFD}sZUJU56@@O8zBK=z?aOmaZ#pL0#wTC=1;nt4yZDOu^ZclvI0 zshNdyx7&xJHX>?m(!0kkY_N}P$Vhc1MQrB!)*#Xj?h@nP93_&2+1T*~TfPYc5gYxYNZS>3K_j6g7yCzcMgiQpWBgih?NyE`F+psQNPUGP{dnOusDb z#R6~)yaU!;CNsSQ`kL8GuZ7-lk9&yPaFYZBmEp7rJNVkG%2k#BX#rk;`o1B=@TW^b zk(CTZ^XD3Qw3+R3P@nxb{J*~@BP#96bSd*T?!C~>*PMSDKXux$kwJr@=@%L^cwWNZ zPwUa3jYFWyd0RC7JZ*XuvnV(+{t<#lf z@ckzdx0y@F0d7H#FwTbi55>!(=_dRe>0Yf5xRkvMhv*|5IJ<|2NTL%7-$pza!O!Hn zVdHPf6QUxF(*3Es3*XnfIob~Bn{IJsiH#wrl_7A&u>DF1?(9EgL`ac#44QZS4D4PT z5gR2JBhv3+i8~6(xF7$B9=h*>Nte@W3xLslk=qd3nziVGFB;igDTWA~npR&!cW-wK ztF{c>-#02Y7Bfn3Rj7Heb`H3v}OrZq7d%^d(U z3f6SqxMd=OMEjYX9Q(+J2n1*I&;FFD8b{dGOcucb-E*6rABXX}oL{+1Hg&Q|CmR9W z{HadHmyu6Jw56YqqjsQ_D|F-}JYtu94_(mao6Cr$B*%@xI*JACg|$Q4EonuNKi(ZJ zW-^KH*1_;m<4MqqALQ-rBoaTgdCU~rFVf>t239Sz9t(;;K*2l?_Ca;t;-9SO7aCq) z_x}3z-$NnBzjoiOAu^oiz_AyLAdXkKik4^X?066nPL8WkjH8@8%h=S>QqlLQZ!j;S zGSTFzmXUSicaiq$zkL>rIEoYz9|qo;xaeB)DzL?5Ha0eb$bz)Vbl+;uoj`>uArZ|z zugzTcT=$KW>34y7))Zho7W2ynn5o0<0sel|N+`-T^70b6%F($JxNBqy7U7CB7~B`E^YAjhC-X^k%UFgE~JK;w}fG9sIdyBYGht zooAa>8Z~U*?EH%{L`Nx;rO0KzPTSd6nBU6)<+1k7&xH@YF}JO@h1f=fMn!FV5PoURDxg~UR(3bXQolK_@f&WTt#QAaeX)zH!N5o@#}>84wR*xLCkO_LV>l&SzFuCO}5QSedHK zkLl@N&_m|rPeVF&+M3-;SG4ZnVF0hY&yOEJLbB`YFa14olS-(a>lDKf0+ADtMqZPvYZc5 zHr*4ikdAiIp6SFmagRw-;3IWTOieOZ!9c^Ga%*16uYc53obwgW*W0p#osp3&#PAuO zS^oVvO1>1eY_mNM8^gGVtYmd7H+hjIPOxEqW=7d&cT{K+4E^MI0bsRGJgSOT^jBoH zzuU62uevIWDFAR zKMg%^HC@ytH>=G)VWX>?)X1v(C?;y4KGO*#Q7B`2C!ze44(5cu;nB&qq4lBs5hXf; zv9wc$z%Et*sVGE=(_7~99z*O0C?}B>v*Tn?a#spDFO6f<6LLQfdbAtJCL9w?f|;4~ z;@9qICnTBg{#nb+xequQsrcKTxfpwU?_f=Nt1Yw9i4O=?JnLJXr(L)1$V8gxl81Ho zrO2e~^Q(8YNyL~fbW=(vJtz-3iD-$utEKK((q zxP*(sI2&?>0vQPOa0N&i>5%~hbCC2eC?L=Rk|v_W?>~BZYAub=Bi&b60Bu9&Mk9l? z?U%zv59)V4BH?E%o-^D*n702zOcm&TI_U+Arl*RyBFik zmyz+-iz{8WCaTEJ2ibu)uCKF`t>9Mk$hWdUKyRt%?ADk$vyv6)F)fiCOlxAsbKfV% zU^S^*lipnf^{9}Dh&|-PA1wG0tB(3JNIBc~=rsb;dvKV3l`4B)Cc6wlC=!4RyC3Bl ztU~+|_k;oosqSz`hv6W7Of`1TBspm`d2U%*45;zTk%;SOF>C`ifv%=Kz2AgCCyN*R zb$nFjdY8{{baZrl{`!zlObk)7BEs0z;xJC=LMhJ97$=32=xxO0Y5vuoJ5Rk|QX@}E zUCgPgBIF*+${~ll?4T{1QZhkpZLN##^yRnoPdSmy_iBFY-1PjN#nAufFHAUqHY!XDUf2)qOPSd(= zsIyQ{@U|hkr_o$}NMV(Z_l7eK#=@Eh+Pp&-w?9h1c)oG@&dPl{N-!=@#*D+9OWh`r!W&T!i2yd(-u?K`|{=k5$@MKgd z{1k$bX9bIZC|vVNT*fu0+ZY>c$*->o{0`lhIo$d5wzi|q!M*)2t=yB3p}@qSo{D{W zO-|_`&vR#i_s`lj-C*Oa@P`=$GQjiPqo(njtyK{(w8{f21rZ-lZP^tvv|1Rnm3D7C zW{aP+N``@2o+RRjCi?_BS8pref}Q+?0$iHO7SlxWW{W{h5pweRp+|(9H>f!QF&7cB zM)N~mIdl=kHdr9XFq{^tF!3`ZwO3k8P0UiunJUgqk`EfSHQ`?0*vPE+cpXy11Nv?R z<*fw2H2TT%UW`A<$&A$8$dU$6qm^Ys&z*=5kXm6&1F5An^QxYH}rso zGW>m+rfHrr>-~jTO;sl9X=P4F!yn=Yo}rdlb?)ySex$Y%23)77&mDR}_2$fQX@+@K zi)*C7pN1cKs0R0C=|t4NVW*YAC@%*>6n4@VM+b*ukRc$iJT-TZpHKELW9w@ATjHw5X`bc1Yb!P+J$%B8uxY(rLNDvCOPSjh{Z!Y24|Gx zoq#|rkgs)eAWH%Q5uukS`t9@so{#vv6OICN8(Bn>Mb+3b zdb;^T^U0tGgYtzOgDTqcDy;rA5hRbW(jN!gJAJo$^(x7^@ZY1yV4(g!ZfPY>>8n@A z`7td#0Rj=OMo9Z`9E$5Px+6o?!BgIg`S6nG`^LpePL=Xb2kAcf%7+I@?lE(3QrluD z+NDbv<9Y;z0|q-wEyqQL7$0$PX2%r%M7H`I*KhFax=Bm36;F)kAiEn5hPbtd*!S!Nh>&c*5|&^h+N zOgn^&9rF~v&HmmOnYGgxCyzK@T0ZW82M+G?H=fG3TErHIaDWPKUzA52k&HNrkF;x} zmiv$HFN&d}ZYbmRiX1h4;S6J>0S~5X-`e|7qadvvy`zWlEt2U0JW%G&KtwM@D3s=k z*JAYVYO<;xQplCJ^bSN7Z<>bs{ zK@b23$6DJqbIcLN(koQ)yG-fow-C(wonSt@n<<8}sAxKVNk{CC{rxWl5MQ4(52XKa@_f-Y@iFCi zkquKCj)|mdrm1MS6)%rA$NXD~Zw(#9e*{PCzE9WJf{|tL`A_2*9 zKzGPJrHMBi&}xXO!Pq%Dd7TnCLJGsh)x&^-7eqVUPZz&|_s5hoWcS?kjiZCslYIxp zOoA`8(CPN5TyerTJVrw;Kqz#)EjZ=6y?$>kFHzURR(e*#g@8Buhfd1~_1Y;0_*gKVFNhKuxw7x*4fAs>F<1K3%IPLH!! z!R;9ZD#$)WR~&dB;j6S%l7Ss|wzPBctEz}qY*ZuBK(nM<`Y0HvunU~s-S2eb?9Peq zibRlix*1pE(qf@{k^qRZ?=Q$t#3AnR(hR#Z6xsMn`%|dgKrX1S1VqX9GneN~)KA0< zksDz@Q3{*E+l)@SSHEe1MZA=b|8=U=n|*tpYJ{X#6iYGI&zW)Aa*B_det{-NS`7d8))U2Cqg{Q?h?IUL1rH~df2p$VpcKr$tEk&032#@-6&&p&Gq!c_ z65|`f4ymBdFL6byC0R(hdBaBAiD5WVMT90X9B-|Hn`U0NK^YNEUNHGm{$>q)ft|O~ zMf(Nm-AUj!xnzgjU|l^E|L$kO%5b9Sis%m{cYVZnPaoHbcN`mbIVlRu-aCuvOR2{u z36c2pXxYD2!SQEtljE$(ISO-Lo3an$-y^qEU-#~$_p_Q-CJ&Dw`uvsi-yx$);5Zyd z{;Fu&c1w~<@Wk>u149avpS97OrGSZm&w0e;lYWq}R%21}O5UNv#C*(Do>RG``@ZdLXBIyVyT3n!rW(1Zl|HH8+!Uj4NN1rfVXLQD80)|ZYV{Vq${ZhS&HSU5 zv~Ahat4fIRw2HQ8%Cv0io~L(tW_7j8n9xjAyCx*72j^e^BL!Y~`o`5p%B8Rdmo7mAyv)VNJd6h)~QlI zdR5D^R6`YcNCMHprnFksKwMBj^4*3P;L&K4@4pBcrXx^IAIX@EGddm}u`WG%_bx(R zQ&WEKkO{|jmd`T^l`&mSbxNAbJE@EKK;QmsKa#A}g3-H)SXrGv@tWAEihlGfhY(Qm zQgk0GSIkAw@ktSEPNej~7Jxz*=^&wY5>4L`^MHs}s%dil`f}EdkEB7)`98L7A`d($ z#Z=vU8VWJLjH2TBzS>pM2wu+q&H=el%{#NwkZg|96|E>qyH0IpYx}ZWCade=_wV0Z zn*Fd*k;~u{8lAXtj~y|+ke(e9=VG>aP%X(H+ShSn{LRuCS4=^%?X{g{(63)&i;9WL zY)WEeAFdd~)Sqc9>FLQvjC4RV6>UqQdJAD?#jSu9nL6|)B;VoRn`*z#Aevo;)XGGc z7v|;V0mAlVz-Ic}x`%NIXPSpALt%=MrIf;D4JGq1ZM3aFhn@(Yu6vls2Fb=J1tBsf z>hSl2;{pQC!SV`d-+lb7xbqFx`4d>e^5tqQ$)GYHO8qD1cn3@4ls1kAx!6kIp_NrJ zCDbKk)kxfzNzZPOiJ%!EAyg>lPO)TD>iY0)P`NW{yFSamm2yKP-8ny^>F{&t1lciA zio-+25v}M!<}-tHC$yf^8=ZSh_q0U*y&_BBjK>kv)A(a!Lvw{d3&EEjO73kEge#6~ zFCMAG6&Rod7Ri+w*3K9qt+8e7S3e)l_kI%8slr(KDW%JUt=iRGD$N{CVlC#MUWQZ4 zLnbytdyFmn96GtR7{B~0AfE(QH7OA)qR)Ew?ev1&Wf&Rd zWr)?EDfXnu3J)G0tQ-Mu|?f0{k;Ga~Wssdh%8^Ny*DZ2MIqKJfmka@n$AQ zi!LsfwN-w?+t;-g-Yc`=x-+~;ye4F!WCQw@ zIVg7V4NlR_(>+8$Tn)o(?0|R$BmJ@XNi}%;`sot0;@8sLtds6@!x|%LT5R3xV%a-g z&LODGl1FZ7(&+3LyPg-P#AM!9ZdKMe(-r%5b-Fexc&nIixa3Gy7;$iF7pp5jOm;%I zQYvNHi*fQ?R9TEx=ISdg@eqgEYvG&cd=JpOiq$meD;bRy+wtha9E-%b!WrbnOebhK(&#BnSyXN}3B zojAE=={sX-Q<_c0G{s=r&DgttR+wk-SC1nHObgo}88^(gT~}){!VQ(>*Z{b06fC z5)gd4aZu+H>B#t4$-?vW`hBKS0gk51p68G-eepY2cD3PrC##^qYWO_eZKrw$JYHoD z3?YbM1aqe#f>hTmbhS#-DVYbR_GDBwBHNf>%Qck4I`Jj@*E~r&-wL!XQBvX_@9bn2 zRuFaKl7^hMkt|krNdm)gn7;Ep6YYIX<-xeRxkCz~bC%g&U zaW?TB*4248zdkvBBLxzmo4$+-VA%U9dvz#_+|vMwF7wl^f%rH#J9`x)QWc?<7fl*d zGBILOvs6*;vmEXgN^N zxP+v_EIQ;FVx+w*6%!-i&zbvsj>zW&t%GjP`k~(54ms(=B`l98R=QreOYy3Rq})uZ z==y`;AU8LWDGfF04fUO*}IJ50Gx`Ws6_^ zBaDV=3+oSDGbl>)@RwKKo*w^bnLpe=_%oO~RcjWxFgx$`swrR&-Avg4GuAlYbh>vVQ|2b0aw_bkrg<|BF>XLW% z@}Az_qyqy4cod6t1UEFC&L5S#U85xyN2`{ny)<9rWwF!6{oKI?Zv0rlzxR55#k7mb zsJwwsnOEa6o*yY1@K;4(SChe>_o6_vOWz0qZKB08Vc_f~(xnc91GLGXcJ@NO`qw&2 z3P|e;v+L0_czEIiH(Gej^L?Ij;9p}uIMMj}!1U^cs~2t&%9qhx;>Ft%qw3ko|NhW{ zHCX43m(_=ClmDtM-I2(VJy;sEq5?Rzr)j|HIIh7NVUAm0H~nj3aYM+w#u=Mi_WSr> z$XHoD$c>@9dBuIj8;VAUO9FL9h|mO4(`dPrlVSq3_n7CaYWtU;g{^?84S9k}N-}sB z6yG>J%wx(SZ8SW6d4jb?oFqdZK|ZYk&eV=hZ(HydH+*bX;ExnWDMgvY zx3AX~h7LzOzN#daBug7|r^Mu~vh7swg{>2Fck&B7G+96RhO{S%C-BiXF%rJq$5*#} zD1PVd+h1H7QwxR3;@%xQiH{Xfe=+>$M4G-wS`&hyIca}!2?3h92%eg&Z(RWa^RL7d z9RZ9}gHLp>G)jt#LH@xTzm&L?!rt4Xl)M%~)kyeEVM06kxUYS!NY#9(kG#`AiJ~iyOX=$EV0@f1-5>@c&r!8sc%$*y-WZ#vE7JS9?nnv zTvsPdXnJpNPd>oOrR99;u>uY9QWqwCJg}e+;mlQE|Gw245L3Rs6gf~{nU+AkaPhW@ z#`&252e;ickI8{+{BI9nGYw8|O5L@Lq|<&=Mw5S8`pJYC>T2yhjuG<$X8+OA*Myg2 znw$CZnNOs>t9)!fm0}paYUm_x&)+v;y~vuQ%uU3bh~T8HY)Hw; z>B6^3$tmfm{HN%@dKRLU7{vQW_RR3iKW2}njW;*YPp1!;EHG8&#KK$Ev*z%M3oLNj zz@r_Qx!TY613iGn^t*qX!ZqcLzhg=IX)s(l6gH!aHB5W(zgmDI1XV+HoD-}1d@|t# z8+D>`c7U%>@7L5~L6~+`f^xo1otoC%Su;q~k^@q94ZX?|o} zLN!rp9`~C0ll2;zhB3#7fyw*v4&JGugk`2t4|@vm7YEKaK=p_0=Q|0kO3`#cVPZJzbY+rMcl{>aHryb!fye#S^i zOO;2viBZqV5=2?IV>MevQEe8oU)O`>sp2DN=qcyuspK4x$`D!M-QY>5ERs~LZ8c+G zXEk@$N=qz*CP)y%sjX3K-7;Q7t;q(9z=2i>A1W8HzP|pU^%6m})aj82D&Q7%eOIh> zt3d5hs^X;gK2f8sY>_FY8eVhrc7Vh6@|(h@6co2>ZSLhaUy9{;XCkYLH2@SQLrn0e zc3gHo*N@I$sLE(@5@E-;-uNgP{c^0zscz>>Ihji7U#3UnS3IAzgp}auTAW?IUIK!NQec=h>K$(b+jcr zaN9uoO&ancj1fIC^JM(CwLd=IZOQpB_SP1J8!P`Z3LoWl|CSi2Z|}@*W3|%bM=eMc zu}oaRXwapqzI+`w_}-zpLY1gb*xa3bOTGKo2ts)G_8Uq}bhjQtMsyM(_k5WL?Stp7 zVTNG+%6$-iJ7j<%nmK&tNbp;U$kT~G2yTG@J$1|~b@>xi^M!AIf62SPc|Thn-%spc zgwXPJSX)#~`<{WBS%QTtZ*&4;Rhd+-Ld+G%KQ$@*$~$Yl40*~+iF$+9$3dUrP5|Yl zf!@!QYVo1+zVpyFAOEe)^5Wv1{i}aXmcq9!3#5iH1+iBl1F2bA{y{-Og^?~`H^<Huf;pI zht1$26jTM@#eK2%C80A6=zKP{S~LX$8P$9D4m^aAG^X~w7ty)Q#5E?b;9iqH#=RZ0 z2hr^zI(Ng19`5V6PlmSdzr%+NsgTQQ%mgk39EJFLA3U(SZt2tBe#(L+Adqhq8Euu9 z0k=f}5-1e*xL!A{aXC8L>Gp6tO4Fh4{=mtF>2_SYspp1CqJol_pFG~owWFM{IA09b z=wmoIXnEer^H_T?BMe7ec?9yP7;Z}IZ<%rQCammLRMy|N-jKaJSN;W+kbMm^&Gs&B=+Ec~431+LS zzZO!&T2aAMv0G|kpv_XJSA7KKEjlm#a5 z$1Ca$X6Iaunow5#lcBj;S5W)RyzR~!Az>RuJEjJ?2K?3yO-9ubW?|CKTJy6oQ2rIPXE&As5EbG ztKW15!yQhCjEuWgHFm5j7G9SxRL@Y(pZn)I(~mis8N|Rbprd{_^u1X--(}tEqja}x zx5=+gHrG8S`yQvx0@j)_iZp%wOJ^rNQ(yf%EhhGIm;6TTCQJrNdYlI2KT3voTa4(; zubl7Y`QW?$xTQb>T@t=;xXh1{sN+tYm0bQw?6UGEb@tEqolckJn&Zl7p^hF`%njF4 z2iL8pc`Hhu`&DB5MG2hI_T1yzLHi}8(R)hdJVtmMHhRt?^b z=1_dI5RVi5Q1fMq;4aO?Enp3P6fXWF-STz0}o#*C}+LM0A-+@dOE_^v={qh7p$t~4nH zhq@VTV1}ohk!~mARwsKaQ!DB|M!9TOBVHo&6Se+o+URb6o|iFQ=N~Y%y39wL&t5ud zQjf~3-`D!%ny>R2#e$2*qLL*jLQ0Xm>ulLav(-Hx(k@sdsoZ)WwtF&^*R;v{K_8 zS%vHEGv#-?vt&pOXMBAAg!(LBIZc@wK~V}pki0BWXyvRxcP?ZfbFFN%j9Cp$;7~NH zIZ5&R2sg z>FV>-6qAWlQ=+KK$BesqL-qT^x;!q|%CPhbyk^#Q&e}|E+={U`LW)`v6gEg#WHc$b7ISuL!!1lU-wsbm~MM)l+vQ@hdW&@ytVrA z)jADDsHIHekG?+9<76C(iwD{|uzx3GCSog~-N#OuOQm0sbUglseBS4ZwW6NS{eGI} z_|jF88!@MP*qg=QqDFJb%{W>rPi;e+w}b3DA2y3qa}vZXFK4XuExnZ3(5|$N-VNXB zjya0vl98mW*%Tq_=RedAy?hW+8f6_`&fxOt0~fpIS>OI{6wYx8m$}0H2Ai^QHy@7R zUPi{s2l@(C)%g`GOZTOK2dSo&dco0mzmSe$gc8FcJugRhW_2-Gaxlp`l>GIoEVp$* zW^hu~PFOwRP_k23YJnGw+urfIUChm?@`carWltOn5NSMIpeP#mB8d=efmd2B zCpTk`o7k86!XD?%UELejtma&Bc*C{JNct*^b*vj%oMn5z!+tk!%L(7z_=SNyu9}}= zIZU+vy#oV}#l?N*r@&j@1SPNB^e0c@!dd&rr(r+2fKf^bC?Dx8?ov5+T@+=gnx#Ig z)1IkXQ7yt6a-L9mJmI*qyMKdRkE+i(Gpp-@%>Hj9c4DDZgHZIHR=Us0CSGuNMr1x$ zl_C0DMh5#)W9#Tu|E_rYijR3;wNA0)WGoWin6l{kF zYIi$Td~k26i@QPMcC_VhyQ&WD({Y=~a{S%Byap*X&E^wvH|@gnpzC-sU*=6pqh|z9 z?mKV!>vDO5H92_i9P05!!_{Tn(!U&QchbYW;mSOP&_Uhqu`q&kS~8)UN|*DUify>{ z%wriY?K%EaYa(7=>-2ByA>yf~JJTdF62Z+aQY-5<6Jh<;n_flK$8Z(~M!0JX4EqHS z>PAXID3+awhm$j!X`oH2pv0)~)pJe*Dttku*W5gpdW3{*DqplFe?D28_*{PSXPuK% zy^!{xI(qj!(MS3tEd|%R>lgQvUw)swn5t4-Q}b;-S})bqYP)SdD`R*Jy;CvMq-SF7 zaHxhwfSQa=eTdawc!@O6Def@SWeP{;$NFMT2y=%vj_X0g{F&d%XTpiEeb2ccFpk+L zwZ$`WEe(Hb(T$Z{$LAtrvWkv3xQhx! z@5;+Bc`M?v0iBnE&NXt)$HjTk zj+_}!8yXnW_ct4KbMu3OGUB8jM@X^gRkPn_6&0PYvg&3_nNB#(E*A&oVg@PG!ihsl zqS&)eJ!zEjFRllaOOHvqRO4|r<2It)Fo0;Y>K}*>D%I$IgX_96qIE+}8js^_o}0mZ zzw^Po(RsX6r_0Aca+$vEJeMx#HR^}@>*3aRk@HiP+mdB7ctmBtiaRLIBWsvlN)k>x zIfN(5`!+<>=j6;=QSoS;#T-;CyDg=>!ia{g zH`lMvdUMV#`e8&y>>*0WBr6${{0nL#b0^Tu*#pXp2m_z+u4EU@p9=kg>M9=it?!eh zSm*6F&_TJK2a#)n8@F}B+oFuqG;0$JdT-f|9yNoY za>DstnHgo3+_L)b3p}aJT+yB#EDy#l{5Oan$Rx?`*zmGzu7^5rhw64$uH?p?k148~ zRJ4LSnP*yIQoq|JyPt?3jr%<-kBiLl%9WH!>Zl9LE!5om62Jd&5yc+&332YsJx*ds zJgivhbb{MN-*@8Xd83ZmhSbf_eIr$M*AvDZjWU$QZHf;EK!{;8em^Rp0{kkG(6O*h zu|x#`m|rK$ApU``*!n?iPhEzir>U~Cgen!9Q@@rwdrl@bBu*0f_)7$t$vr*#NrUj+2uMRG5dyUJ^RUU&Wb4haQc|C{wG z=27n}T`KljZ~Pc_>FqnU>QpYV9!^M1SC~W~BA~j1z&~!1w`s9lc=#-*vyS z7KPE-DbR7qi--3%;<$Rf;0aH8?uH#FbW@68QT+hjM5f2>CYlbmW(u_12r(3M!Dd9{ z=Er}=rr>!|QRrA|YJ;;MFL>|DrG*|=6P&kY;__v7dEff(&?G`X{to{{%;=y7A1VH4 zMTL_5ziDYDMN>w-p$Aa1)9N%G+xW|E5^8PI=3z2DM$*k_KWG9;!^TFyTDALWbPaxe znX@^9TqC=^!U{1At5Pr$q8<16|B8O>i(+0 zJB351l4fdWKf{~9o-{o15#ytc>K54Al0V{(mzq@h?PGCC`Z$DjhV9J z9wVb_UiPYPw^-^|t(Kps&g~U$HM>bADymX3SsUZWdZPH5<&v%wPsFbKQaX#J#FsMF zu@(5=L=P}+yMXDen|kt@4TRR^bLo2$RWe5y{mpSt zQrzOO21T&+DwIJ}@sU`w$l~;a5^Bb_-KYNRGz6(+q!YbcLHlByI>zHpz&U}Qj&7|U z3n-Of8X2u%k2}KM5#oy73#O)~H>l0Dw4edBUSLl_QISVnehzJjm(hP|Iz8xUGZ8j$(VELnlP^7kp~`shxZ_ z@OzQhuWx|pQF<#O~_xi@+RQa9O^n@h@{ z9H!j(-?zXw$~Qy}3F*`#6_@Z75l@=~pfk+_ay;@LVj{ix;EO>l@kQ;gUvE~~TkFRd zbAJU9@5Q5g+43=ZcYX>FEFPwp^M~E{_bd4Uw3|}#3HFsU{oP4Wd7((RGsfuB|2{67 zG-&BlB4;TJ{0(hyR6VQQ|NWbrK}&=LWZtEv-25;AMAa!8(=D;r2S32~5Dmf+PJ=?ot+PB8W#>%J?g4ibM{LRnL zTu|^N-%rhY zai@{Rt2JGFgyVYU1$KydF{z+A#;+ zARipz8Q9s`p>Y43Ip`Pt`o^qf`LNE%kfI7#g;hdp+SX@xZ7*vJ2MCNY`J+*j-Q(xy zKLH78Z)gQDoU(W^uV**A=W|7ewc*Lz6ssPpuOgG*}9SYF7GxR{*e;{7RIaSDdz-*)SK;ion_{?Xc78d zpmse-gsG7RDYN?e`pMPR0L&{lZr;Ct6_lbiBU2tce*E|VIy=HsaE5>VY8VukDwD5 zo87vK_2Lh-E96|Ba*RzN;`K2+oL;kuQ*nIatuoQ=XP#oTb)fWoMd|IhzLiTPt9mnJ zLNRaOzRknOH{C>{J}Yu0CMP_COh)>=H0Kxw>1GJQXtfK!;K`;apx@g(PJfue?x;D; z5f>c@&oA~S*+bW9i{<{ijm^zp)6*}3|0JXmbiQM2;284pqdQ2O)84%KX!WJ_{Q7w1 z;$RLrSYt?YyG_C{5S{bhG7GH&slMpe)~DIffR;%iyB7NQA~FR?TV)siCx5jPMR~04eFyXv&<+sBE<#$j}K)ECB{NdVy zQn4X1_~ToaHa11j9-=sp+jQ&_2?@z928OR7M@}oBLXA)L@R7d$oxz+pKA^ewK{cpb z?8%e*jt(5?s3tc)KQlw8ChTawJu87r#(u#A^9uS4M;Evi)c}4paH#~Q0`DA-!L#h3>lIp(4oGfY?vcw;{t{Xx}(ZhnjCJ=*+cjGFE8#$ zr#2*I8eP-Y)kV7Af?RsSa*gUMm=!NZf~@-{BKuTeVXY^jN%>Q0=|(Bms$|<^_|+3OnXg><*(^Yzk>B48UWG9A zR_#x?QNxRf)VQ8DvOG?+T^se9oYeRZVj|`i7Q!!HT!p!~ZL7>TP~~Jt@zDONVxHPX z6evjJK@Z!O+IJX_bEWr9$I9Np2`}EK0GqSBI?~5HVdegFpAxE(6jakddJzj+Vb+H$T4ogX-$%e;Uc}Sfr6v?10-G;Tf+Q&hnvLbrxgmsX0W1JnaGX6W+<;t z(k1;5YeD;jHCshRMR-?u5!bM=Fpc@n=*8bv{G+92$fNfr&d*3BBqX2%=+(+=ah0y8 zd0qsCOqWe+WRY3$ z+$WaV;01T58J4X0JpN%FoQ;6e30LyK8=Qod6mfn50iMvE79PoBdzUXVCdMCHS5Ly_ zX?#Sq4^9ozm>dvE!&HM$Z;{^f0;yZHbjdI7Os=hUu?YUmkn$q@@{?YKjf(Pxc7Av;o4WgUn2(CfyFSv0-q&iz zMLp8cxcMxW=iNY-;)6-Luaa={s_xgX7&Pi7X_$Y)_^Cl0N7`b~{~mE^yY(V~i*S+ppx5{zw$X3ZN3W@j$op{vqdm zP75n53{;U@&s}EbMqdIt^O@!=U;sbM@2jb(P*_@7(S)|i{aw}r=(FFc>Cy>ku?}kG zRwwLypYHRdN>%*16Ni>?*WAX2sPaOnb~`vku(h%oig{FgF#m655B>wQ$(hz^$;lU> z_k0sH1vg*(LGw+&S7h~*b*|Y&b(#4TbW9DEr-miDbmhupOH20b92qAWFVpb~8hZN2 zYb79sR1csl`GfTa^yQWI5v=YuCxiHL}Fp1Jt=T0c*Gar552 zE^RI-zbEwP^>jjsTen^6isdDObNK{7I3V)(;0#0(UugVHmH_Xjw^4I02)7nLsJopK z17ga|r2#(#KG0t!&J^5{g3_z}w+-IrAYtoYjH%Zd^$r#kpg%g@lYm-?#R@>*K3la? zVfClA?&f42B7gvsJ_(zzNUvuaG(PJfd~9OLQJ{Kg?_P6$_GWJnc%6^2u>nw-CIZ*_ z8t{e0#4h8EY5uPkKjavR z!hTVx+Tbu5y|%YJK$Nw5BV&Cd-&x*fSRa^xZ0jqgwRPAtq z7NQsg0UlN`wNP`|-B;%O>#El4V`LCd`9N-0iGJv*{7|Vz9r`M?>wL6SVWLAR=v-Fs z6jG46zVV}9-p&OS75)kl!6@Dy?JjNZ>@*-!m0zKQv}U-p7=sAu9CzgUwV(G4dIh3} zxV(vVMtFo@$FkazX*YIGoyr1^zI)dX5N6ulSE(8>YR$+*D~LfgBX43`t*|=)G}war zxeuz|zhSE&Iy&&O8Gy6I^3m#q2o3B-Jixo~Pf1D1 z=H6Zt$SZ7aPKg#sy}C<%BBz5$RoHKSdDfHg`7^d(@*ge2&-H0AqG^cWZSLhXdm2eR zd&YH8Zo~+fZlh{HzMC5PxTh2Y^t4ji-T&SppdVak!0M{8N{uTe4hak5NP?A%bp2En z0>M*%0RW1Jhi7ifb=DLBiZD~t)3ml^PjVb~=JkJkdH3HF>+#Ew>5-!GbV6nnx3jw& z4?rXYYV~m91AqK@(b(9Cx^tx)U=Xglx;ogTBwl};scz(r52=kWZ*LeMtBRjtqi^^AWb8$ zRSU*c6wKr5>grVz62-S--0=3`X~m0lyC!F6J^u^ibGZD(-a{yXh8(OL9Qy8HrL;h4 zHN094pabbc`}@#y|2;4m^%E1+KqT}Y469W+(tywfIII@~_;M7z#LK_oo;omW6ciMQ zo+scCEs&Hlx3co^_s0R%ZK>j!g@uKgs{P-{A3(h7Dd=*9K;iJg-w>Uk9sy9hMR?h9 zZ}}n$0+dVm_&#ZAw~>L9lKLX{!;xZ&7X+?AK!_Or^k!&V|8gbxCpiBY5UlX<^CQo0 z@W8^)e5k8D$4^ZHflRbCCLkqnEYb;rRXnOhGkMRLA(Ub zA>IWC46`N5jCxtp(>} zesLJ%+`fDL9C}2<%O5J!p{C zA!W15Yc;O{fnAyNAv-!cI-^PlEG(Pts#0T9(-b@p*&Ud86iPI$hj6cxO|$V5g1RuU z@WdcI0Kw^`tvv_WL|eN{uMpKt5*C$5+S<2Z`8Wh^A*k8h-4(O9FUve@SAp=w?PLoJ zaWK$@8NB8dQV#vA&;=X;IS^e;_dOSC%6OHA3iHlGfH-uH2WR2|UF(r9Z;Q~RJEb@Q zl!H;`leK6te5AK^=FlN@j6h@*k!ipsy^qSP`f~%M$?_yuPKRpFya0Q4CJ0eSvZ($= zeap+(D0_&!5b+uggP#{JU%q^BxR780PaK$VkU0had;q?)K)3702>=XVKR;m~JW3A1 z5&$=%K6p*g;2Rk&pr~n3J0Rt?Odg#9kMA87MT+>`187)@{5`b%KF^SM0h&l&_Rcj_ z?Z;r;%mX$J)fzE`S5guw!$NUsk~|WVi|b2!t_AnX;q6!r8-uNBtC-4MO;sP zZ!ZCKcD#g*jgI2sm+0bDQCz0ADF&>9u{LkK(su`R%xJ4~1+p5mlBSJ-XfeX*9^g0nFLA&VGH3mOWE-hr?nAS27bMlVi* zC}e)#+x7IQZgB8A=+dx$-+bTPLIwAz7J3p|z+uR}-Gq5XFq^061y4`UbhQl#*y>(K1qai$) zdxgsQ?Yz>;N~aXJ1vpI=wX&+T>~3DGt54iR1B6=_i#=`Lx%6D}zo%Oh*j#qmy>LA1(o?_*e)Cy*&nWPEx6 zO(*gJaNN3eD?R5`n#2f7BGh80c?!H30#d(MRlU{I^I=h~K==g1V4_@Qz$ssVo}t=7 z@<8rr7|6$I!IPA}=@V3+9T`c-aOJeW&P>Yi&Rm8AVQy#F0$75PBCBFZCUl$sVq{pD zT!mA9Rh3J4OXhNU@kq!pFf4FT5TzKf`S*3&uOS2zxB`8zq4Ywl$eJpKe-i6g7f3^&!oMj?5ytS?EU0|S$ z*HAH_q3}WUM>+Ap5(`83ZHR&lg9R+6FN~I$WNq<4HqyJQN&qfHq;H)86GOwxt879S zehz)jJ%C^ad8=1RE7t(>%z*k@L!nNG`D`me>_Z1aa6donO}#|k0e3oJ0#;PS)zvj+ z2 ze^!;VRmutBe=$+WSpqcE05Jz_;rB4cf5$NzY|^v%hkgiw)YjH^01heNXoy9=1#sG_ zw@ya{jGhbt&;c-tiE@ln3kz6Zti#v^1(A6z109aQ3fQ}bUeF(9a(k`=I6radCsRDG zH*mPwfL~xXA&Bf{U>{%&UWC_$fc-@@AVJYK&eQ)r*pfu4NET8)>pLKfib%wOAP735 zB?ba$Nn5-uEG+q@r7a+`VX-qWGrO>WfkGlau)hdsfW3BbFcTaC0VlrT!J`=q0D{55 zL21GdXNIgnJP-Fv_E7Gy)%x?)slnwoCAgjW0n@1kivTvqI&f$LL(+~?4RTFqCp*s( z$cum=SUor}oYgF7XlO{x4=Oaz5(ER;w3@#_96u0b4Sf%m$dNF`iq1IutwdZKpxoA3 z=dC7^zvmESIlh_vx{hERpkxu^8I?j;f@}aJIz^DKQkA2P*JF7Mbo9R-7rZq9e(-el zph7XVz7BRj)*2APVqY3QY$|`CXtaQ!+}z*CLUn%T#2FkML=FYG7quie9xmfy_e#4B z+B$RXYgmt@m!y^2a%!FB~D7ld{}I2#0` z0jDDZK!8c$9LB!|_Xnq-GqEU)m<>Ygfg83+s9)`JY`)M<2|h^UU~>w=3<}vwvROtZ zV`Xe$rF;-R<>pNga-?d6Nt=R>NLx0*;0r@)@JEt3{_e^UK6r}ZY8R)RZW%F~Avi`z zri}6b4VEy!Ff)2P$u6wi{~)kep3O6rgS|u=qyb^SD+l38OIpH^UJF&BX#K8i6~1t~B=fb^O?o#Xbrj zdt@0p_%wUtN~JpO+i=-aZ>_Eh#@_EnGw=t zy@GzOqL5hvPtgUW5DL-svi&ckBD<8HE0Q>w&O#8)EJe{p415L>@%lH$VfrzGhKYwX z!%R9$G{;H+69m7s`QLiSw*QxQ3Bk65i0{=c>kVbbf2l)li(Iv;4?s6UCWc*-Vt~`k zprosjMVLbpe`owf<4@&n{ai?p!8{Qt18cmVZW~AU^#f0)lvt|BfsQA=?MC=`faibT zkPHCb+gVKB*WX`MNhxYr=PH4G+fQ+;i~oY_R@yiLrwFYIF_1gChJ25{e)@3AM*{mW zB-_Yt1^PoM6e}xhPC|qE2K9eGqbZT{5?O7-di-vc;9%)!C)sMqJW(mZz!?7b+_~A= zn@mjp@aO^GpdfD*mIX(!j2xc(x4fOsk*Ec}uCD=NCV{MG5(zPJ6N?}%-R*#~&-~HS z&AlpD{!LIw6Q9$c>|y$=(HFc#&>(TOci{WfTBIxu$r?7L|8J(lz4F2rcQxt7I7zNwZ!Q=!{NL~+ zqoX0wD8}$uX)>OMnyko}{5DK5zArTR8s+624h*@VA@Ujd1{OW{q z*X&sk%k@mRtUtzSsLCv_tOWWP*?jHY-Iypy4-dSsw&oBOr2UEG?Zo*XS+jVKgNFx6 zLfTL|PvFIZ1qsiTV78pA@GvfjOTOh^8`)^8o&uTzD@#d{t5ViP9 ze}b?ANT{J1x}>Hnj|0>n9pepGIdNaZ_8Lx!q98B8xeq!0Z)}T)a1IPZ7U*YO*8}$ajd;kMA_))A0 zPGf3jMk{~EfR2$7TitocK>zzA~Kyet+AcH6K%XZh7KQwko`4)Q z+ej9wk1~~(4j4|k8vW4Q`4$&&sJH5&tRfv(X6koW46kOm)^(n*M)fBrC+2hQ#K1>S zfeRlx7K#9Qr3L^Qmm$Ihtd68^ey$vTlNB5zLPiHZGHYiG4(b-PER(ym-!26rgWNW^S5SZKzv@prQpf0KLv1s#I~@8 zhqVra?xWp)9?xOj2FA{Y);PZo4Al5!8Oy+6lC^|au+P}0DBY{et(hxh zp>5jU%q_5x6l38ID&9K7Se5b%)@gx5i8@&ZJFK&Zb3K`zK*XD_osQUePWK+5*Dc>y58XU3-w zq1FpRzeHO%5dQ{VAa$SsfGeO%#hDwKnnp(chz1*s27>M2Q5Ph@M$`ufW{`xYum|Q_ zP~t*jMTTdwzOZy(06X&Kz`eew6OeLD=3kwC;9~GA$7t7n{kznh1+$_X>E=K$yaa-b zfsLbMXD0+9y9+1;>TsL=zJSVBuc3l%GBm==gtHHuc5-Pcqi83L)AhuDckP$rj6)Ol zAuw{9nwlRWF9=Eh$<3(-lsm8{njnOx59~%xLsjVQ=b2tk5OIQdysFp4tpEyMLO798 z4;|PcWsd)agLD;e93Uu#Br8`){U9Xma@kx;YAT{Q|C%z(YM~p!*GAT^E=b^y2r7Mq zm6rYqJm*$D4y&&!W{C3J*4r#uD|(5$S2Fi@$cANA?~nDdVmjO8oBZNJkSD}8|6o3d zg4dm&^qfzEh<0X6`04jtMx6az^%^`NTI1rxLxCQ=q1w7IGlM}*O$`EeZ){?Uimc*l z$bvt7cn&?X$@F(gm{Abhb<&E3&=XBmltv_fdJ~ze|*m` zm1BfsP{tGf)`&G@ zeh3F)Q6(iMQ78okg~j0lx(eI1%)KpKiS(kAh4(<1XwEbTlCo=GfxmePAFzLR<%&sY)PX5{58@{2gQ)&eFo#IowE5?cf(wMsbWrFA(RzMS zk?6+nDuSz5Urd$jR1$(IkQRnrfSly1DagEw=}KHWY(FcE#T9*>T$7*}@Hj#Sied7V zs9qZ6z$C?dHklPUpY+X*Kr-PFMWT>;vVTOSKT`byMUQ(?$hn6=su^DVK3I~0+>&}- z@?u%#GQ~cjVou0mgDP4|_X5(TwmFzuePx9u%eV|HEZ0TJwo3qII5h~PXEHY2hFs0S zLVb575rgy(dqKb11TQTkK10><^vql!Ws$Jeuyp*pL*LDnn~wJOlW7UAKaU;Y_yjb8 zA?O9~v^rM)3h-U$r~A45X1^bbJ$`I4?a|r@dtH>Eh#xarrD5>q*!VcvrUAmsDwUbj zKqvtHg8niC(GSG6%xzbP*`Vw1B!u@(5U(TLF|$h9)t-2PEQ`s#cBZ_=TVv!8bOQ$Y zGhKna!Ne!d`VJ~~VZ)0INtAKJ zdgk;fhl96Eg#JH#yb8(y1nZ!ZByFo2-U8uOQ9wOnKq6KuOUrbm@bO+bBxN9vt(x>1 z%zH3!M@D1v2_DW8AsePSfJ`5Hx+*NNvak$F4BKu_3L{=C%Zdf6F4lgP=Jg!{JNacm_xh;0 zxp{4KAUPXkACZz0)DIvXaj70Etyu`2pF98t=rU>%5++`p4-p~;W&-Wbm3^>&0nLG& zc`ZM(l^-DaiJH?tYViZlk~I~Mj&q&)$58>40yue1mH?%0 zNH=rz>GS6g;DToWC%(43$kK#D5fDg-3Cjum1`-;IeSH$B?H0hm_Jso&e*XNq?H0jO zG{AKLH(>nA8*-_X)TLNXlVz8v7047doR$^0uz%83s$Y+EWw)isW`C(s>Xuh_F`AcV z%zwlr{#+m$9n)Ff+|sfhk#wGIBT{CK`Hys2I*_NAAl^O%n+F@+ zFqqe7IgD{KR5FEl9XLlmn7lOX{q~?KLw2A&7?j9>!pgyR zCFe3uFWSRm>VuU42qTare3)d(Fok_u#il;q``vF-pM(Sh8P&Kx+&~b4^ zAW?So_kaLgD7#^wq+@pn5Y{?p>Fvy?>!d+vjE{;EAb%8nH6R^NgwG3wY7htkFYA4u z%5l2U?=|%dfC6GJmmd+u#hf2Le8|K-q!MsMa2qOpGp&TbHbQY^3-Vu^pjWB^#~kzW z{soa%Znv|O*Hsa!71oHK*@P*SBVR{D>W5OF#eD!X38~z}-_AQSknYxmihg9X!S+K8 zIV~rr{8~9uf(Zb2YI*tf3}5lU7hw!&S;X(i?<()vB`OHys$t8=qQXLCQ?AECPFi;g zNGwt=W76rFnI@>zrM(nmc7L|73W(8frkM_Hw6rD;Pg5=}U3)nbXDML^lJW8h4<@sc z5LzCn;fp9pH_$RNN-ivb3(nx01qD|&NFCd_g4`$669Ve{{beft3z(q;Xg_bbH#Rw` z0h2Ja$O}0N43vB;R+#A#@QNyPJMn@p$oAEO1Qyg*zUlJ6r*(F6_!q(%L5E9724<}7 z!jQ$hL!zUhlnfUFV6qn@l(sX|)1I7KJyvQAlX>TXZXfBf*klzC4R7h^IpQ!_!BP0{+A-4)ty%F)YDjZ$NNGQ0B zLro|0j;yTDZQiJJx1*b--ni0QRwC=>H59`^UJroQgG|!0iF40u>nqNuCBcA{k%5;h#h!&jj;3L*5Mtm*>P-$C^hI)Km&`PNdXv@bTTf>=#$ zW(KK50%|v-UCRbiuTLs(1B)7B>)9;;C!Q=K{}5B$)~}J%dh@Ebu8u{O09~VdPoo_1 z_9@ivlCo)fs&(@Nj7h@TcmHWt$f{bAZ2QL5Rd9P}M^;58yJ!cLMh3Wv1ksT?$pd#8lky0s~6+I#79)^}Qw)U?4;xf3=v^7D|DbL1QW>COsjo0 z6R^dkVDF)@${PY?_zx7;O&MYc%1}DNNm5*SwhKk>j~=1;Y**8FDzc^_p$9t&LU<9I zUts5oU0p}^UV=xpQ3LZ3LZhRrTi@3gs_HC8OCVAW7AUtvT68MqGebo2$uVp2MA#JyF-ye<=k>dR$etWSTcz5kpymD^^svtP?3Fsh4C99$Os`` z1nLHC_=2ED(AmYsMh-6NgxEv)c8i5(80X5BxmFhWj;=15RYK{(A9bQA6w{D1t0lc0 zrT^uFf1rKYIsoc_Ts{V``Ve;QbRRy9AMO@tuq!ywAMAHCxP3+1( zQsFBCDDf>wz5~hYr}`{zi7uT18ZL2-vd}|0#k=k}{+03@w3*L612+?O~E;y~u z(`5?aXI!I+6DgC*_0z0X3?iiorjL&dI4K5KkdR1h zV{~VGn{e+WwOw)*9li-LaQKfVaj|AP78X1L0)oE@5XiNKFwwFzD=MyW6W>)e%Cn{m zj2f@`K(#Kr_Fqj?W=bLK7i|?!wsF`n;8K7xlFYrHU&+jElCA=q2AA^Twab3q<4--T z;Ti_`9vD1rra$CzkQ1CyIPMIUO5@IA2Wdt=frMvR4Qdr_T@utKrLf|5ir_;$t!tF|ScGw@PXbJb5rL^%LCcpHw#zsTky2X&M)q}32f<=v7 zZh>UE1|?5@ng+rNAjb*UAqqbVCfN2A zKi(&)tk0083z~WDizN0IuJe9n3V909^y?8H6z(?~GK)jqPj|cklP#H;og!S zxcZ`f|J}QHD0isz4Pm0mq*Q%o4-f!^1%6LPv4r?B@~0v(093kISVsoL-w#@uoOH*D zJQHgl$XXpOdUTy^Gh9cfiQ$Q;Ayh_yoor(9c$x=C2#5%8INrWM6beHnN)p(-6YlU! zDXPx(=`29o_Q?tU(E1_XoO#0M^tee9mvpnRRX#+CnQM}1qDlPdcF5B*Oj>16$T-0k z@V8tUyjNCH@f8Zd%4}95hUcyh_zG5Y`vnKLfDcDb7n19vPVmL`5T+($GW{a_S;@E- z>;CM6Zzm_tNEyri`Zy6(XjZj%bcljEY-I6h{X)7La`)!~E0q^ZHAH}mYZPMIq&gS^ zK+~(*$%JKPk^jB56u|d3UtGRm(H;L_ft(-H<;V`oC?Oo32BZt6bIFPjA|e18QV?YQ zP5vakkglTOvwjL8RHlxvA9|vHPeX$TYpJ={1QsGxp&mL$*mKk8$TC8yFx|waNh}jr;x`m-1IAbAZ{K24x}`u-rS+jW#Hp zV>c7|5*ZPJ352Em59BvqA~cpZ+L@lFU>>m8i`XI9^RA;Z@Ip(#)Tu$!9!`4$z5|?I z9dKEIm!9S!cmUk`=P@%&zh$H<8#0+-t%#9I*lAD4xdIsU$=z$%Km^Dusza7$+3Arh z>(fz2A#d`cV?{6(uNvI*Zj3r>wO)PUWVi8~^MhFlbQIn<{r$a-O_iPW)uHQqn7D{0 zm1euP`<`qnV7E|1LrE2HYtt}Nx38oY=#PH8%YV?iIyX00*VJ?oPHqdhnkE*X)|*hh zjU+jNhybt@UI$02Bw=bWjJ+%PQGFYu;>8lnphgN%l@Vp8i1g=f#jK?w8RfK z?r*kXIw>fa<%LAW9I^uNgA?Ix+E0l804X!2`z$D(Qwdupk*dXlQ6;JErZ8&bUoiPE$X(n>ljq`JCndT=IQC@8@~n z_j#T-0UfEvC`?H2>sWd~~9>TdL5^zXDN;Nm2qIZI2pC99oY=)iGUU@f0g9M2+i%d{2~J_^56^U)AIsSG7B_@cRf+hlDu-X-;7hE*)4yNdsmEkYx^WU3 zHuQMb#z-3$H#{T~9vqz`v*sB(n?!7iE#9(QT;`_zDtb4!IciA9I9Ma~((6)f^id#` z9k#c($yZRrWI%LoP>h70kyRpz6ud;uzXr$6o~2d%PtN3-d-F!CxI}8SFEhEj37Mrz zb>Z^#tc<6O#}4S}HXIj{q86NJ{D*rFI{gx@nz;n)6U0*6Rr&a^C~`^Rx}eHXc?L*6 zD|dJ61?UzP7o*7Kft${2ckJF{&Js<|ddEIO-5sqM`wr#bJ0jwPm)R%|hLtI<*h+Z_ z1gx?Wa`&p5nmB{5AJY|qa?3K~&D%ZFLU)Q;qHKa9lZ7tQZB-u)L~wy_5r1P>*fhWe zG0eL#P)?=+3rBy_u(ZlGN1A?;Z-hhPW|TA3E&c7E_X;VG0LioSp*prSoLb;KbwjVE z{q)FQLJqpj;|W^l`f|{-p|J-j(r_5lYZwqsn%5H~lx$d*v=1LfUfutW7edM8*S+el zZMfA2yd|IdL-WdCl7hv3UyNO^iafk?yI+V>TlK~|MfI{zG#XOZLW7zeS2~v6U2^|! z{4(vmU9BmsSCOM z;NYrGdX_J0Q>}hAW?eOGyM{$ znfwBV@&U=CCeX3)@}}YL(p+a}ABdr{*aehu^fX91Oi&%C;P$A*4=IxRAxs~vhwT&K zgO;lG5VO?ht=yidYxKU+xeT7NCOcS_G{{{!!(y9EFM literal 0 HcmV?d00001 diff --git a/planning/behavior_velocity_crosswalk_module/include/behavior_velocity_crosswalk_module/util.hpp b/planning/behavior_velocity_crosswalk_module/include/behavior_velocity_crosswalk_module/util.hpp index 578ae66e40006..dfe682d0aa0c9 100644 --- a/planning/behavior_velocity_crosswalk_module/include/behavior_velocity_crosswalk_module/util.hpp +++ b/planning/behavior_velocity_crosswalk_module/include/behavior_velocity_crosswalk_module/util.hpp @@ -26,6 +26,7 @@ #include #include #include +#include #include #include @@ -73,7 +74,7 @@ struct DebugData std::optional range_near_point{std::nullopt}; std::optional range_far_point{std::nullopt}; - std::vector> collision_points; + std::vector> collision_points; std::vector stop_poses; std::vector slow_poses; diff --git a/planning/behavior_velocity_crosswalk_module/package.xml b/planning/behavior_velocity_crosswalk_module/package.xml index d5ef92a4c097d..75f96c9194aef 100644 --- a/planning/behavior_velocity_crosswalk_module/package.xml +++ b/planning/behavior_velocity_crosswalk_module/package.xml @@ -34,6 +34,7 @@ sensor_msgs tier4_api_msgs tier4_autoware_utils + tier4_debug_msgs vehicle_info_util visualization_msgs diff --git a/planning/behavior_velocity_crosswalk_module/scripts/time_to_collision_plotter.py b/planning/behavior_velocity_crosswalk_module/scripts/time_to_collision_plotter.py new file mode 100755 index 0000000000000..5093683e17c22 --- /dev/null +++ b/planning/behavior_velocity_crosswalk_module/scripts/time_to_collision_plotter.py @@ -0,0 +1,212 @@ +#!/usr/bin/env python3 + +# Copyright 2023 TIER IV, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import argparse +from collections import deque +from copy import deepcopy + +from ament_index_python.packages import get_package_share_directory +import matplotlib.pyplot as plt +import rclpy +from rclpy.node import Node +from tier4_debug_msgs.msg import StringStamped +import yaml + + +def expand_margin(x_vec, y_vec, min_x=0.0, max_x=10.0): + expanded_x_vec = deepcopy(x_vec) + expanded_y_vec = deepcopy(y_vec) + + if min_x < expanded_x_vec[0]: + expanded_x_vec = [min_x] + expanded_x_vec + min_y = expanded_y_vec[0] + min_x - expanded_x_vec[0] + expanded_y_vec = [min_y] + expanded_y_vec + + if expanded_x_vec[-1] < max_x: + expanded_x_vec.append(max_x) + max_y = expanded_y_vec[-1] + max_x - expanded_x_vec[-2] + expanded_y_vec.append(max_y) + + return expanded_x_vec, expanded_y_vec + + +class CollisionInfo: + def __init__(self, module_id, obj_id, ttc, ttv, state): + self.module_id = module_id + self.obj_id = obj_id + self.ttc = ttc + self.ttv = ttv + self.state = state + + +class TimeToCollisionPlotter(Node): + def __init__(self, args): + super().__init__("time_to_collision_plotter") + + self.depth = args.depth + + self.sub_calculation_cost = self.create_subscription( + StringStamped, + "/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/collision_info", + self.on_collision_info, + 1, + ) + + self.time_to_collision_hist = {} + self.max_hist_size = args.depth + + crosswalk_config = ( + get_package_share_directory("autoware_launch") + + "/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml" + ) + with open(crosswalk_config) as f: + crosswalk_config_obj = yaml.safe_load(f)["/**"]["ros__parameters"] + + ego_pass_first_x = crosswalk_config_obj["crosswalk"]["pass_judge"][ + "ego_pass_first_margin_x" + ] + ego_pass_first_y = crosswalk_config_obj["crosswalk"]["pass_judge"][ + "ego_pass_first_margin_y" + ] + self.ego_pass_first_margin = [ego_pass_first_x, ego_pass_first_y] + + ego_pass_later_x = crosswalk_config_obj["crosswalk"]["pass_judge"][ + "ego_pass_later_margin_x" + ] + ego_pass_later_y = crosswalk_config_obj["crosswalk"]["pass_judge"][ + "ego_pass_later_margin_y" + ] + self.ego_pass_later_margin = [ego_pass_later_x, ego_pass_later_y] + + plt.ion() + _, self.ax = plt.subplots() + plt.show() + plt.connect("key_press_event", self.on_key) + + self.timer = self.create_timer(0.3, self.on_timer) + + def on_key(self, event): + if event.key == "c": + self.time_to_collision_hist = {} + + def on_collision_info(self, msg): + collision_info_data_vec = [] + collision_info_str_vec = msg.data[:-1].split(",") + if len(collision_info_str_vec) < 5: + return + + for i in range(int(len(collision_info_str_vec) / 5)): + collision_info_data_vec.append(CollisionInfo(*collision_info_str_vec[i : i + 5])) + + # memorize data in the history dictionary + for collision_info_data in collision_info_data_vec: + uuid = collision_info_data.module_id + collision_info_data.obj_id + if uuid not in self.time_to_collision_hist: + self.time_to_collision_hist[uuid] = deque([]) + + self.time_to_collision_hist[uuid].append( + [float(collision_info_data.ttv), float(collision_info_data.ttc)] + ) + + def on_timer(self): + # make the size of history not exceed the maximum value + for uuid in self.time_to_collision_hist: + while self.max_hist_size < len(self.time_to_collision_hist[uuid]): + self.time_to_collision_hist[uuid].popleft() + + plt.cla() + + # plot "ego_pass_later" border + ego_pass_later_x = [] + ego_pass_later_y = [] + for i in range(len(self.ego_pass_later_margin[0])): + ego_pass_later_x.append(self.ego_pass_later_margin[0][i]) + ego_pass_later_y.append(self.ego_pass_later_margin[1][i]) + expanded_ego_pass_later_x, expanded_ego_pass_later_y = expand_margin( + ego_pass_later_x, ego_pass_later_y + ) + plt.fill_between( + expanded_ego_pass_later_x, + expanded_ego_pass_later_y, + [expanded_ego_pass_later_y[-1] for i in expanded_ego_pass_later_y], + alpha=0.2, + color="green", + ) + + # plot "ego_pass_first" border + ego_pass_first_x = [] + ego_pass_first_y = [] + for i in range(len(self.ego_pass_first_margin[0])): + ego_pass_first_x.append(self.ego_pass_first_margin[0][i]) + ego_pass_first_y.append(self.ego_pass_first_margin[1][i]) + expanded_ego_pass_first_x, expanded_ego_pass_first_y = expand_margin( + ego_pass_first_x, ego_pass_first_y + ) + plt.fill_between( + expanded_ego_pass_first_y, + [expanded_ego_pass_first_x[0] for i in expanded_ego_pass_first_x], + expanded_ego_pass_first_x, + alpha=0.2, + color="blue", + ) + plt.text( + expanded_ego_pass_later_x[0], + expanded_ego_pass_later_y[-1], + "Ego passes later.", + va="top", + ha="left", + color="green", + ) + plt.text( + expanded_ego_pass_first_y[-1], + expanded_ego_pass_first_x[0], + "Ego passes first.", + va="bottom", + ha="right", + color="blue", + ) + plt.text(0, 0, "Ego yields.", va="bottom", ha="left", color="red") + + # plot history + for uuid in self.time_to_collision_hist: + hist = self.time_to_collision_hist[uuid] + plt.plot( + [val[0] for val in hist], + [val[1] for val in hist], + label=uuid[0:4] + "-" + uuid[4:8], + ) + + plt.legend() + plt.draw() + plt.title("Time to collision") + plt.xlabel("Pedestrian's time to collision") + plt.ylabel("Ego's time to collision") + plt.pause(0.01) + + +if __name__ == "__main__": + parser = argparse.ArgumentParser() + parser.add_argument( + "-d", + "--depth", + type=float, + default=100, + ) + args = parser.parse_args() + + rclpy.init() + node = TimeToCollisionPlotter(args) + rclpy.spin(node) diff --git a/planning/behavior_velocity_crosswalk_module/src/debug.cpp b/planning/behavior_velocity_crosswalk_module/src/debug.cpp index 409898233cbbe..a5bc3ebf72179 100644 --- a/planning/behavior_velocity_crosswalk_module/src/debug.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/debug.cpp @@ -44,8 +44,8 @@ visualization_msgs::msg::MarkerArray createCrosswalkMarkers( { for (size_t i = 0; i < debug_data.collision_points.size(); ++i) { const auto & collision_point = debug_data.collision_points.at(i); - const auto & point = collision_point.first; - const auto & state = collision_point.second; + const auto & point = std::get<1>(collision_point); + const auto & state = std::get<2>(collision_point); auto marker = createDefaultMarker( "map", now, "collision point state", uid + i++, Marker::TEXT_VIEW_FACING, @@ -134,7 +134,7 @@ visualization_msgs::msg::MarkerArray createCrosswalkMarkers( "map", now, "collision point", uid, Marker::POINTS, createMarkerScale(0.25, 0.25, 0.0), createMarkerColor(1.0, 0.0, 1.0, 0.999)); for (const auto & collision_point : debug_data.collision_points) { - marker.points.push_back(collision_point.first.collision_point); + marker.points.push_back(std::get<1>(collision_point).collision_point); } msg.markers.push_back(marker); } diff --git a/planning/behavior_velocity_crosswalk_module/src/manager.cpp b/planning/behavior_velocity_crosswalk_module/src/manager.cpp index 992d1c48eb9f4..96e4e873ce111 100644 --- a/planning/behavior_velocity_crosswalk_module/src/manager.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/manager.cpp @@ -129,7 +129,7 @@ void CrosswalkModuleManager::launchNewModules(const PathWithLaneId & path) const auto lanelet_map_ptr = planner_data_->route_handler_->getLaneletMapPtr(); registerModule(std::make_shared( - id, lanelet_map_ptr, p, *opt_use_regulatory_element_, logger, clock_)); + node_, id, lanelet_map_ptr, p, *opt_use_regulatory_element_, logger, clock_)); generateUUID(id); updateRTCStatus(getUUID(id), true, std::numeric_limits::lowest(), path.header.stamp); }; diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index 0edfa6167e999..3b69b74c53d80 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -25,6 +25,7 @@ #include #include #include +#include #include namespace behavior_velocity_planner @@ -164,10 +165,27 @@ std::optional toStdOptional( } return std::nullopt; } + +tier4_debug_msgs::msg::StringStamped createStringStampedMessage( + const rclcpp::Time & now, const int64_t module_id_, + const std::vector> & collision_points) +{ + tier4_debug_msgs::msg::StringStamped msg; + msg.stamp = now; + for (const auto & collision_point : collision_points) { + std::stringstream ss; + ss << module_id_ << "," << std::get<0>(collision_point).substr(0, 4) << "," + << std::get<1>(collision_point).time_to_collision << "," + << std::get<1>(collision_point).time_to_vehicle << "," + << static_cast(std::get<2>(collision_point)) << ","; + msg.data += ss.str(); + } + return msg; +} } // namespace CrosswalkModule::CrosswalkModule( - const int64_t module_id, const lanelet::LaneletMapPtr & lanelet_map_ptr, + rclcpp::Node & node, const int64_t module_id, const lanelet::LaneletMapPtr & lanelet_map_ptr, const PlannerParam & planner_param, const bool use_regulatory_element, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock) : SceneModuleInterface(module_id, logger, clock), @@ -190,6 +208,9 @@ CrosswalkModule::CrosswalkModule( } crosswalk_ = lanelet_map_ptr->laneletLayer.get(module_id); } + + collision_info_pub_ = + node.create_publisher("~/debug/collision_info", 1); } bool CrosswalkModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) @@ -264,6 +285,10 @@ bool CrosswalkModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto } recordTime(4); + const auto collision_info_msg = + createStringStampedMessage(clock_->now(), module_id_, debug_data_.collision_points); + collision_info_pub_->publish(collision_info_msg); + return true; } @@ -882,7 +907,8 @@ void CrosswalkModule::updateObjectState( if (collision_point) { const auto collision_state = object_info_manager_.getCollisionState(obj_uuid); - debug_data_.collision_points.push_back(std::make_pair(*collision_point, collision_state)); + debug_data_.collision_points.push_back( + std::make_tuple(obj_uuid, *collision_point, collision_state)); } } object_info_manager_.finalize(); diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp index 961126bf4bca1..edff62371f6b4 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp @@ -26,6 +26,7 @@ #include #include +#include #include #include @@ -257,7 +258,7 @@ class CrosswalkModule : public SceneModuleInterface }; CrosswalkModule( - const int64_t module_id, const lanelet::LaneletMapPtr & lanelet_map_ptr, + rclcpp::Node & node, const int64_t module_id, const lanelet::LaneletMapPtr & lanelet_map_ptr, const PlannerParam & planner_param, const bool use_regulatory_element, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock); @@ -360,6 +361,8 @@ class CrosswalkModule : public SceneModuleInterface const int64_t module_id_; + rclcpp::Publisher::SharedPtr collision_info_pub_; + lanelet::ConstLanelet crosswalk_; lanelet::ConstLineStrings3d stop_lines_; From f42f760620a88b8008ae478d3143accff1576184 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Fri, 25 Aug 2023 23:14:18 +0900 Subject: [PATCH 13/15] feat(behavior_path_planner): update filter objects by velocity (#4742) --- .../path_safety_checker/objects_filtering.hpp | 35 +++++++++++++------ .../path_safety_checker/objects_filtering.cpp | 16 ++++++--- 2 files changed, 35 insertions(+), 16 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/objects_filtering.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/objects_filtering.hpp index b4575eb4d3b7e..8a3b7094c69d1 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/objects_filtering.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/objects_filtering.hpp @@ -55,24 +55,37 @@ PredictedObjects filterObjects( const std::shared_ptr & params); /** - * @brief Filter objects based on their velocity. + * @brief Filters objects based on their velocity. * - * @param objects The predicted objects to filter. - * @param lim_v Velocity limit for filtering. - * @return PredictedObjects The filtered objects. + * Depending on the remove_above_threshold parameter, this function either removes objects with + * velocities above the given threshold or only keeps those objects. It uses the helper function + * filterObjectsByVelocity() to do the actual filtering. + * + * @param objects The objects to be filtered. + * @param velocity_threshold The velocity threshold for the filtering. + * @param remove_above_threshold If true, objects with velocities above the threshold are removed. + * If false, only objects with velocities above the threshold are + * kept. + * @return A new collection of objects that have been filtered according to the rules. */ -PredictedObjects filterObjectsByVelocity(const PredictedObjects & objects, double lim_v); +PredictedObjects filterObjectsByVelocity( + const PredictedObjects & objects, const double velocity_threshold, + const bool remove_above_threshold = true); /** - * @brief Filter objects based on a velocity range. + * @brief Helper function to filter objects based on their velocity. * - * @param objects The predicted objects to filter. - * @param min_v Minimum velocity for filtering. - * @param max_v Maximum velocity for filtering. - * @return PredictedObjects The filtered objects. + * This function iterates over all objects and calculates their velocity norm. If the velocity norm + * is within the velocity_threshold and max_velocity range, the object is added to a new collection. + * This new collection is then returned. + * + * @param objects The objects to be filtered. + * @param velocity_threshold The minimum velocity for an object to be included in the output. + * @param max_velocity The maximum velocity for an object to be included in the output. + * @return A new collection of objects that have been filtered according to the rules. */ PredictedObjects filterObjectsByVelocity( - const PredictedObjects & objects, double min_v, double max_v); + const PredictedObjects & objects, double velocity_threshold, double max_velocity); /** * @brief Filter objects based on their position relative to a current_pose. diff --git a/planning/behavior_path_planner/src/utils/path_safety_checker/objects_filtering.cpp b/planning/behavior_path_planner/src/utils/path_safety_checker/objects_filtering.cpp index 33afe0fe6642f..a775e7c16efed 100644 --- a/planning/behavior_path_planner/src/utils/path_safety_checker/objects_filtering.cpp +++ b/planning/behavior_path_planner/src/utils/path_safety_checker/objects_filtering.cpp @@ -37,7 +37,7 @@ PredictedObjects filterObjects( PredictedObjects filtered_objects; - filtered_objects = filterObjectsByVelocity(*objects, ignore_object_velocity_threshold); + filtered_objects = filterObjectsByVelocity(*objects, ignore_object_velocity_threshold, false); filterObjectsByClass(filtered_objects, target_object_types); @@ -51,13 +51,19 @@ PredictedObjects filterObjects( return filtered_objects; } -PredictedObjects filterObjectsByVelocity(const PredictedObjects & objects, double lim_v) +PredictedObjects filterObjectsByVelocity( + const PredictedObjects & objects, const double velocity_threshold, + const bool remove_above_threshold) { - return filterObjectsByVelocity(objects, -lim_v, lim_v); + if (remove_above_threshold) { + return filterObjectsByVelocity(objects, -velocity_threshold, velocity_threshold); + } else { + return filterObjectsByVelocity(objects, velocity_threshold, std::numeric_limits::max()); + } } PredictedObjects filterObjectsByVelocity( - const PredictedObjects & objects, double min_v, double max_v) + const PredictedObjects & objects, double velocity_threshold, double max_velocity) { PredictedObjects filtered; filtered.header = objects.header; @@ -65,7 +71,7 @@ PredictedObjects filterObjectsByVelocity( const auto v_norm = std::hypot( obj.kinematics.initial_twist_with_covariance.twist.linear.x, obj.kinematics.initial_twist_with_covariance.twist.linear.y); - if (min_v < v_norm && v_norm < max_v) { + if (velocity_threshold < v_norm && v_norm < max_velocity) { filtered.objects.push_back(obj); } } From febb7d556ef94e0273e5a3f6d218404abe36c0be Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Fri, 25 Aug 2023 23:44:12 +0900 Subject: [PATCH 14/15] refactor(map_based_prediction): move hard coded declare parameters to yaml file (#4756) * move hard coded declare parameters to yaml file Signed-off-by: yoshiri * style(pre-commit): autofix --------- Signed-off-by: yoshiri Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../config/map_based_prediction.param.yaml | 3 ++ .../src/map_based_prediction_node.cpp | 42 +++++++++---------- 2 files changed, 23 insertions(+), 22 deletions(-) diff --git a/perception/map_based_prediction/config/map_based_prediction.param.yaml b/perception/map_based_prediction/config/map_based_prediction.param.yaml index cb9a61b600e43..1f6def24912a2 100644 --- a/perception/map_based_prediction/config/map_based_prediction.param.yaml +++ b/perception/map_based_prediction/config/map_based_prediction.param.yaml @@ -11,7 +11,10 @@ sigma_yaw_angle_deg: 5.0 #[angle degree] object_buffer_time_length: 2.0 #[s] history_time_length: 1.0 #[s] + # parameter for shoulder lane prediction + prediction_time_horizon_rate_for_validate_shoulder_lane_length: 0.8 + # parameters for lc prediction lane_change_detection: method: "lat_diff_distance" # choose from "lat_diff_distance" or "time_to_change_lane" time_to_change_lane: diff --git a/perception/map_based_prediction/src/map_based_prediction_node.cpp b/perception/map_based_prediction/src/map_based_prediction_node.cpp index be6327cf5c01a..8d633dbd5af64 100644 --- a/perception/map_based_prediction/src/map_based_prediction_node.cpp +++ b/perception/map_based_prediction/src/map_based_prediction_node.cpp @@ -639,33 +639,31 @@ lanelet::Lanelets getLeftOppositeLanelets( MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_options) : Node("map_based_prediction", node_options), debug_accumulated_time_(0.0) { - enable_delay_compensation_ = declare_parameter("enable_delay_compensation", true); - prediction_time_horizon_ = declare_parameter("prediction_time_horizon", 10.0); - prediction_sampling_time_interval_ = declare_parameter("prediction_sampling_delta_time", 0.5); + enable_delay_compensation_ = declare_parameter("enable_delay_compensation"); + prediction_time_horizon_ = declare_parameter("prediction_time_horizon"); + prediction_sampling_time_interval_ = declare_parameter("prediction_sampling_delta_time"); min_velocity_for_map_based_prediction_ = - declare_parameter("min_velocity_for_map_based_prediction", 1.0); - min_crosswalk_user_velocity_ = declare_parameter("min_crosswalk_user_velocity", 1.0); + declare_parameter("min_velocity_for_map_based_prediction"); + min_crosswalk_user_velocity_ = declare_parameter("min_crosswalk_user_velocity"); dist_threshold_for_searching_lanelet_ = - declare_parameter("dist_threshold_for_searching_lanelet", 3.0); + declare_parameter("dist_threshold_for_searching_lanelet"); delta_yaw_threshold_for_searching_lanelet_ = - declare_parameter("delta_yaw_threshold_for_searching_lanelet", 0.785); - sigma_lateral_offset_ = declare_parameter("sigma_lateral_offset", 0.5); - sigma_yaw_angle_deg_ = declare_parameter("sigma_yaw_angle_deg", 5.0); - object_buffer_time_length_ = declare_parameter("object_buffer_time_length", 2.0); - history_time_length_ = declare_parameter("history_time_length", 1.0); + declare_parameter("delta_yaw_threshold_for_searching_lanelet"); + sigma_lateral_offset_ = declare_parameter("sigma_lateral_offset"); + sigma_yaw_angle_deg_ = declare_parameter("sigma_yaw_angle_deg"); + object_buffer_time_length_ = declare_parameter("object_buffer_time_length"); + history_time_length_ = declare_parameter("history_time_length"); { // lane change detection lane_change_detection_method_ = declare_parameter("lane_change_detection.method"); // lane change detection by time_to_change_lane - dist_threshold_to_bound_ = declare_parameter( - "lane_change_detection.time_to_change_lane.dist_threshold_for_lane_change_detection", - 1.0); // 1m - time_threshold_to_bound_ = declare_parameter( - "lane_change_detection.time_to_change_lane.time_threshold_for_lane_change_detection", - 5.0); // 5 sec - cutoff_freq_of_velocity_lpf_ = declare_parameter( - "lane_change_detection.time_to_change_lane.cutoff_freq_of_velocity_for_lane_change_detection", - 0.1); // 0.1Hz + dist_threshold_to_bound_ = declare_parameter( + "lane_change_detection.time_to_change_lane.dist_threshold_for_lane_change_detection"); // 1m + time_threshold_to_bound_ = declare_parameter( + "lane_change_detection.time_to_change_lane.time_threshold_for_lane_change_detection"); + cutoff_freq_of_velocity_lpf_ = declare_parameter( + "lane_change_detection.time_to_change_lane.cutoff_freq_of_velocity_for_lane_change_" + "detection"); // lane change detection by lat_diff_distance dist_ratio_threshold_to_left_bound_ = declare_parameter( @@ -680,11 +678,11 @@ MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_ num_continuous_state_transition_ = declare_parameter("lane_change_detection.num_continuous_state_transition"); } - reference_path_resolution_ = declare_parameter("reference_path_resolution", 0.5); + reference_path_resolution_ = declare_parameter("reference_path_resolution"); /* prediction path will disabled when the estimated path length exceeds lanelet length. This * parameter control the estimated path length = vx * th * (rate) */ prediction_time_horizon_rate_for_validate_lane_length_ = - declare_parameter("prediction_time_horizon_rate_for_validate_lane_length", 0.8); + declare_parameter("prediction_time_horizon_rate_for_validate_shoulder_lane_length"); path_generator_ = std::make_shared( prediction_time_horizon_, prediction_sampling_time_interval_, min_crosswalk_user_velocity_); From a1584619bc5974c11f99acfc06e1e9bd158e9067 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Sun, 27 Aug 2023 21:50:20 +0900 Subject: [PATCH 15/15] feat(safety_check): add hysteresis factor in safety check logic (#4735) * feat(safety_check): add hysteresis factor Signed-off-by: satoshi-ota * feat(lane_change): add hysteresis factor Signed-off-by: satoshi-ota * feat(avoidance): add hysteresis factor Signed-off-by: satoshi-ota * feat(avoidance): add time series hysteresis Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../config/avoidance/avoidance.param.yaml | 3 ++- .../scene_module/avoidance/avoidance_module.hpp | 4 ++++ .../utils/avoidance/avoidance_module_data.hpp | 3 ++- .../utils/path_safety_checker/safety_check.hpp | 2 +- .../src/scene_module/avoidance/avoidance_module.cpp | 11 +++++++++-- .../src/scene_module/avoidance/manager.cpp | 5 +++-- .../src/scene_module/lane_change/manager.cpp | 4 ++-- .../src/scene_module/lane_change/normal.cpp | 2 +- .../src/utils/avoidance/utils.cpp | 2 +- .../src/utils/path_safety_checker/safety_check.cpp | 6 +++--- 10 files changed, 28 insertions(+), 14 deletions(-) diff --git a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml index 9ecc1a63b55b0..26f53cc91c4cf 100644 --- a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml +++ b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml @@ -142,7 +142,8 @@ time_resolution: 0.5 # [s] time_horizon: 10.0 # [s] safety_check_backward_distance: 100.0 # [m] - safety_check_hysteresis_factor: 2.0 # [-] + hysteresis_factor_expand_rate: 2.0 # [-] + hysteresis_factor_safe_count: 10 # [-] # rss parameters expected_front_deceleration: -1.0 # [m/ss] expected_rear_deceleration: -1.0 # [m/ss] diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp index 7889e91767155..096ae61a9432e 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp @@ -556,6 +556,8 @@ class AvoidanceModule : public SceneModuleInterface bool arrived_path_end_{false}; + bool safe_{true}; + std::shared_ptr parameters_; helper::avoidance::AvoidanceHelper helper_; @@ -576,6 +578,8 @@ class AvoidanceModule : public SceneModuleInterface ObjectDataArray registered_objects_; + mutable size_t safe_count_{0}; + mutable ObjectDataArray ego_stopped_objects_; mutable ObjectDataArray stopped_objects_; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp index 1f47b804e185b..5484ef834a177 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp @@ -194,7 +194,8 @@ struct AvoidanceParameters double safety_check_backward_distance; // transit hysteresis (unsafe to safe) - double safety_check_hysteresis_factor; + size_t hysteresis_factor_safe_count; + double hysteresis_factor_expand_rate; // keep target velocity in yield maneuver double yield_velocity; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/safety_check.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/safety_check.hpp index f9903b24f42cb..79947d826ed10 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/safety_check.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/safety_check.hpp @@ -101,7 +101,7 @@ bool checkCollision( const ExtendedPredictedObject & target_object, const PredictedPathWithPolygon & target_object_path, const BehaviorPathPlannerParameters & common_parameters, const RSSparams & rss_parameters, - CollisionCheckDebug & debug); + const double hysteresis_factor, CollisionCheckDebug & debug); /** * @brief Check collision between ego path footprints with extra longitudinal stopping margin and 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 ff5706c34bdc7..e0c79a46d731e 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 @@ -1869,6 +1869,8 @@ bool AvoidanceModule::isSafePath( return true; } + const auto hysteresis_factor = safe_ ? 1.0 : parameters_->hysteresis_factor_expand_rate; + const auto safety_check_target_objects = utils::avoidance::getSafetyCheckTargetObjects( avoid_data_, planner_data_, parameters_, is_right_shift.value()); @@ -1879,13 +1881,16 @@ bool AvoidanceModule::isSafePath( CollisionCheckDebug collision{}; if (!utils::path_safety_checker::checkCollision( shifted_path.path, ego_predicted_path, object, obj_path, p, parameters_->rss_params, - collision)) { + hysteresis_factor, collision)) { + safe_count_ = 0; return false; } } } - return true; + safe_count_++; + + return safe_ || safe_count_ > parameters_->hysteresis_factor_safe_count; } void AvoidanceModule::generateExtendedDrivableArea(BehaviorModuleOutput & output) const @@ -2505,6 +2510,8 @@ void AvoidanceModule::updateData() // update rtc status. updateRTCData(); + + safe_ = avoid_data_.safe; } void AvoidanceModule::processOnEntry() diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp index c13c237673625..2d4a6b9c42b98 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp @@ -145,8 +145,9 @@ AvoidanceModuleManager::AvoidanceModuleManager( p.safety_check_time_resolution = get_parameter(node, ns + "time_resolution"); p.safety_check_backward_distance = get_parameter(node, ns + "safety_check_backward_distance"); - p.safety_check_hysteresis_factor = - get_parameter(node, ns + "safety_check_hysteresis_factor"); + p.hysteresis_factor_expand_rate = + get_parameter(node, ns + "hysteresis_factor_expand_rate"); + p.hysteresis_factor_safe_count = get_parameter(node, ns + "hysteresis_factor_safe_count"); } // safety check rss params diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp index f392ef6a26e22..31aab9da87e2a 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp @@ -288,8 +288,8 @@ AvoidanceByLaneChangeModuleManager::AvoidanceByLaneChangeModuleManager( // safety check { std::string ns = "avoidance.safety_check."; - p.safety_check_hysteresis_factor = - get_parameter(node, ns + "safety_check_hysteresis_factor"); + p.hysteresis_factor_expand_rate = + get_parameter(node, ns + "hysteresis_factor_expand_rate"); } avoidance_parameters_ = std::make_shared(p); diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp index 3db3e049c3c81..251720f4202d5 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp @@ -1380,7 +1380,7 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe( obj, lane_change_parameters_->use_all_predicted_path); for (const auto & obj_path : obj_predicted_paths) { if (!utils::path_safety_checker::checkCollision( - path, ego_predicted_path, obj, obj_path, common_parameters, rss_params, + path, ego_predicted_path, obj, obj_path, common_parameters, rss_params, 1.0, current_debug_data.second)) { path_safety_status.is_safe = false; updateDebugInfo(current_debug_data, path_safety_status.is_safe); diff --git a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp index 4cbfebef07a39..c1a883d7a9b82 100644 --- a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp +++ b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp @@ -771,7 +771,7 @@ void fillAvoidanceNecessity( } // TRUE -> ? (check with hysteresis factor) - object_data.avoid_required = check_necessity(parameters->safety_check_hysteresis_factor); + object_data.avoid_required = check_necessity(parameters->hysteresis_factor_expand_rate); } void fillObjectStoppableJudge( diff --git a/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp b/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp index 7f3fe46c6b8ec..579862de93865 100644 --- a/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp +++ b/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp @@ -232,7 +232,7 @@ bool checkCollision( const ExtendedPredictedObject & target_object, const PredictedPathWithPolygon & target_object_path, const BehaviorPathPlannerParameters & common_parameters, const RSSparams & rss_parameters, - CollisionCheckDebug & debug) + double hysteresis_factor, CollisionCheckDebug & debug) { debug.lerped_path.reserve(target_object_path.path.size()); @@ -286,8 +286,8 @@ bool checkCollision( const auto min_lon_length = calcMinimumLongitudinalLength(front_object_velocity, rear_object_velocity, rss_parameters); - const auto & lon_offset = std::max(rss_dist, min_lon_length); - const auto & lat_margin = rss_parameters.lateral_distance_max_threshold; + const auto & lon_offset = std::max(rss_dist, min_lon_length) * hysteresis_factor; + const auto & lat_margin = rss_parameters.lateral_distance_max_threshold * hysteresis_factor; const auto & extended_ego_polygon = is_object_front ? createExtendedPolygon(ego_pose, ego_vehicle_info, lon_offset, lat_margin, debug)