From 0c7ef9863fc95918731abee39375fc7779fd4976 Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Tue, 17 Oct 2023 15:02:11 +0900 Subject: [PATCH 001/202] feat(ndt_scan_matcher): add initial_to_result_relative_pose (#5319) Added initial_to_result_relative_pose Signed-off-by: Shintaro Sakoda --- localization/ndt_scan_matcher/README.md | 1 + .../ndt_scan_matcher/ndt_scan_matcher_core.hpp | 4 +++- .../ndt_scan_matcher/src/ndt_scan_matcher_core.cpp | 13 +++++++++++-- 3 files changed, 15 insertions(+), 3 deletions(-) diff --git a/localization/ndt_scan_matcher/README.md b/localization/ndt_scan_matcher/README.md index 1f7779890f89a..e210d3a28796f 100644 --- a/localization/ndt_scan_matcher/README.md +++ b/localization/ndt_scan_matcher/README.md @@ -38,6 +38,7 @@ One optional function is regularization. Please see the regularization chapter i | `transform_probability` | `tier4_debug_msgs::msg::Float32Stamped` | [debug topic] score of scan matching | | `no_ground_transform_probability` | `tier4_debug_msgs::msg::Float32Stamped` | [debug topic] score of scan matching based on de-grounded LiDAR scan | | `iteration_num` | `tier4_debug_msgs::msg::Int32Stamped` | [debug topic] number of scan matching iterations | +| `initial_to_result_relative_pose` | `geometry_msgs::msg::PoseStamped` | [debug topic] relative pose between the initial point and the convergence point | | `initial_to_result_distance` | `tier4_debug_msgs::msg::Float32Stamped` | [debug topic] distance difference between the initial point and the convergence point [m] | | `initial_to_result_distance_old` | `tier4_debug_msgs::msg::Float32Stamped` | [debug topic] distance difference between the older of the two initial points used in linear interpolation and the convergence point [m] | | `initial_to_result_distance_new` | `tier4_debug_msgs::msg::Float32Stamped` | [debug topic] distance difference between the newer of the two initial points used in linear interpolation and the convergence point [m] | diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp index fc4015aede059..a07eb9cd5c8d0 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp @@ -111,7 +111,7 @@ class NDTScanMatcher : public rclcpp::Node const pcl::shared_ptr> & sensor_points_in_map_ptr); void publish_marker( const rclcpp::Time & sensor_ros_time, const std::vector & pose_array); - void publish_initial_to_result_distances( + void publish_initial_to_result( const rclcpp::Time & sensor_ros_time, const geometry_msgs::msg::Pose & result_pose_msg, const geometry_msgs::msg::PoseWithCovarianceStamped & initial_pose_cov_msg, const geometry_msgs::msg::PoseWithCovarianceStamped & initial_pose_old_msg, @@ -150,6 +150,8 @@ class NDTScanMatcher : public rclcpp::Node rclcpp::Publisher::SharedPtr no_ground_nearest_voxel_transformation_likelihood_pub_; rclcpp::Publisher::SharedPtr iteration_num_pub_; + rclcpp::Publisher::SharedPtr + initial_to_result_relative_pose_pub_; rclcpp::Publisher::SharedPtr initial_to_result_distance_pub_; rclcpp::Publisher::SharedPtr diff --git a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp index 238e5c6be89bc..25033c8c83c01 100644 --- a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp +++ b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp @@ -205,6 +205,8 @@ NDTScanMatcher::NDTScanMatcher() "no_ground_nearest_voxel_transformation_likelihood", 10); iteration_num_pub_ = this->create_publisher("iteration_num", 10); + initial_to_result_relative_pose_pub_ = + this->create_publisher("initial_to_result_relative_pose", 10); initial_to_result_distance_pub_ = this->create_publisher("initial_to_result_distance", 10); initial_to_result_distance_old_pub_ = @@ -487,7 +489,7 @@ void NDTScanMatcher::callback_sensor_points( publish_tf(sensor_ros_time, result_pose_msg); publish_pose(sensor_ros_time, result_pose_msg, is_converged); publish_marker(sensor_ros_time, transformation_msg_array); - publish_initial_to_result_distances( + publish_initial_to_result( sensor_ros_time, result_pose_msg, interpolator.get_current_pose(), interpolator.get_old_pose(), interpolator.get_new_pose()); @@ -628,12 +630,19 @@ void NDTScanMatcher::publish_marker( ndt_marker_pub_->publish(marker_array); } -void NDTScanMatcher::publish_initial_to_result_distances( +void NDTScanMatcher::publish_initial_to_result( const rclcpp::Time & sensor_ros_time, const geometry_msgs::msg::Pose & result_pose_msg, const geometry_msgs::msg::PoseWithCovarianceStamped & initial_pose_cov_msg, const geometry_msgs::msg::PoseWithCovarianceStamped & initial_pose_old_msg, const geometry_msgs::msg::PoseWithCovarianceStamped & initial_pose_new_msg) { + geometry_msgs::msg::PoseStamped initial_to_result_relative_pose_stamped; + initial_to_result_relative_pose_stamped.pose = + tier4_autoware_utils::inverseTransformPose(result_pose_msg, initial_pose_cov_msg.pose.pose); + initial_to_result_relative_pose_stamped.header.stamp = sensor_ros_time; + initial_to_result_relative_pose_stamped.header.frame_id = map_frame_; + initial_to_result_relative_pose_pub_->publish(initial_to_result_relative_pose_stamped); + const auto initial_to_result_distance = static_cast(norm(initial_pose_cov_msg.pose.pose.position, result_pose_msg.position)); initial_to_result_distance_pub_->publish( From d38beae3097fe614806f0b900b7b6417291c5c10 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Tue, 17 Oct 2023 17:27:32 +0900 Subject: [PATCH 002/202] fix(tracking_object_merger): fix unintended error in radar tracking merger (#5328) * fix: fix tracking merger node Signed-off-by: yoshiri * fix: unintended condition setting Signed-off-by: yoshiri --------- Signed-off-by: yoshiri --- .../camera_lidar_radar_fusion_based_detection.launch.xml | 2 +- .../include/tracking_object_merger/utils/utils.hpp | 4 ++++ 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml index 7d0988635fb10..07640495a5e19 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml @@ -411,7 +411,7 @@ - + diff --git a/perception/tracking_object_merger/include/tracking_object_merger/utils/utils.hpp b/perception/tracking_object_merger/include/tracking_object_merger/utils/utils.hpp index 013040d15bded..bc6dfef9b80bf 100644 --- a/perception/tracking_object_merger/include/tracking_object_merger/utils/utils.hpp +++ b/perception/tracking_object_merger/include/tracking_object_merger/utils/utils.hpp @@ -27,8 +27,12 @@ #include #include #include +#include #include +#include +#include +#include #include #include From 08f6b8de901ca70df1705d420df0b596958e0794 Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Tue, 17 Oct 2023 17:54:34 +0900 Subject: [PATCH 003/202] chore(autonmous_emergency_braking): add maintainer (#5331) Signed-off-by: tomoya.kimura --- control/autonomous_emergency_braking/package.xml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/control/autonomous_emergency_braking/package.xml b/control/autonomous_emergency_braking/package.xml index 4f2ad6c50a9b3..5dc65cb243bfc 100644 --- a/control/autonomous_emergency_braking/package.xml +++ b/control/autonomous_emergency_braking/package.xml @@ -6,6 +6,8 @@ Autonomous Emergency Braking package as a ROS 2 node Yutaka Shimizu Takamasa Horibe + Tomoya Kimura + Apache License 2.0 ament_cmake From 076319bef0e92f23497b05be1e7f9e8de9bdebef Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Tue, 17 Oct 2023 09:08:14 +0000 Subject: [PATCH 004/202] chore: update CODEOWNERS (#5184) Signed-off-by: GitHub Co-authored-by: github-actions --- .github/CODEOWNERS | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index f9983f0fccc3f..9de27f82ffcef 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -56,7 +56,7 @@ common/traffic_light_recognition_marker_publisher/** shumpei.wakabayashi@tier4.j common/traffic_light_utils/** mingyu.li@tier4.jp shunsuke.miura@tier4.jp common/trtexec_vendor/** daisuke.nishimatsu@tier4.jp yusuke.muramatsu@tier4.jp common/tvm_utility/** ambroise.vincent@arm.com xinyu.wang@tier4.jp -control/autonomous_emergency_braking/** takamasa.horibe@tier4.jp yutaka.shimizu@tier4.jp +control/autonomous_emergency_braking/** takamasa.horibe@tier4.jp tomoya.kimura@tier4.jp yutaka.shimizu@tier4.jp control/control_performance_analysis/** berkay@leodrive.ai fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp control/control_validator/** kyoichi.sugahara@tier4.jp makoto.kurihara@tier4.jp takamasa.horibe@tier4.jp control/external_cmd_selector/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp @@ -66,6 +66,7 @@ control/mpc_lateral_controller/** takamasa.horibe@tier4.jp takayuki.murooka@tier control/obstacle_collision_checker/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp control/operation_mode_transition_manager/** takamasa.horibe@tier4.jp tomoya.kimura@tier4.jp control/pid_longitudinal_controller/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp +control/predicted_path_checker/** berkay@leodrive.ai control/pure_pursuit/** takamasa.horibe@tier4.jp control/shift_decider/** takamasa.horibe@tier4.jp control/trajectory_follower_base/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp @@ -140,6 +141,7 @@ perception/simple_object_merger/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4. perception/tensorrt_classifier/** mingyu.li@tier4.jp perception/tensorrt_yolo/** daisuke.nishimatsu@tier4.jp perception/tensorrt_yolox/** daisuke.nishimatsu@tier4.jp dan.umeda@tier4.jp manato.hirabayashi@tier4.jp +perception/tracking_object_merger/** yoshi.ri@tier4.jp yukihiro.saito@tier4.jp perception/traffic_light_arbiter/** kenzo.lobos@tier4.jp shunsuke.miura@tier4.jp perception/traffic_light_classifier/** shunsuke.miura@tier4.jp yukihiro.saito@tier4.jp perception/traffic_light_fine_detector/** shunsuke.miura@tier4.jp tao.zhong@tier4.jp @@ -181,7 +183,6 @@ planning/planning_debug_tools/** taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp planning/planning_test_utils/** kyoichi.sugahara@tier4.jp takamasa.horibe@tier4.jp planning/planning_validator/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp planning/route_handler/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp mamoru.sobue@tier4.jp takayuki.murooka@tier4.jp yutaka.shimizu@tier4.jp zulfaqar.azmi@tier4.jp -planning/rtc_auto_mode_manager/** fumiya.watanabe@tier4.jp taiki.tanaka@tier4.jp planning/rtc_interface/** fumiya.watanabe@tier4.jp taiki.tanaka@tier4.jp planning/rtc_replayer/** fumiya.watanabe@tier4.jp taiki.tanaka@tier4.jp planning/sampling_based_planner/bezier_sampler/** maxime.clement@tier4.jp @@ -215,6 +216,7 @@ system/default_ad_api_helpers/ad_api_visualizers/** isamu.takagi@tier4.jp kahhoo system/default_ad_api_helpers/automatic_pose_initializer/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp system/dummy_diag_publisher/** akihiro.sakurai@tier4.jp fumihito.ito@tier4.jp system/dummy_infrastructure/** ryohsuke.mitsudome@tier4.jp +system/duplicated_node_checker/** shumpei.wakabayashi@tier4.jp uken.ryu@tier4.jp system/emergency_handler/** makoto.kurihara@tier4.jp system/mrm_comfortable_stop_operator/** makoto.kurihara@tier4.jp system/mrm_emergency_stop_operator/** makoto.kurihara@tier4.jp From 8453525fcc9dace38b0780d791e890ce2a2461b1 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Tue, 17 Oct 2023 18:36:20 +0900 Subject: [PATCH 005/202] fix(AEB): failure due to an empty path (#5329) Signed-off-by: Takamasa Horibe Co-authored-by: Tomoya Kimura --- control/autonomous_emergency_braking/src/node.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/control/autonomous_emergency_braking/src/node.cpp b/control/autonomous_emergency_braking/src/node.cpp index e68dff6b0ec1d..0ccc9bc4a3dae 100644 --- a/control/autonomous_emergency_braking/src/node.cpp +++ b/control/autonomous_emergency_braking/src/node.cpp @@ -432,6 +432,10 @@ void AEB::generateEgoPath( const Trajectory & predicted_traj, Path & path, std::vector & polygons) { + if (predicted_traj.points.empty()) { + return; + } + geometry_msgs::msg::TransformStamped transform_stamped{}; try { transform_stamped = tf_buffer_.lookupTransform( From b71b04e52e62eb23b2affb6fdcf1bab59b1de298 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 17 Oct 2023 19:08:42 +0900 Subject: [PATCH 006/202] feat(avoidance): make detection area dynamically (#5303) Signed-off-by: satoshi-ota --- .../config/avoidance/avoidance.param.yaml | 9 +++++++-- .../utils/avoidance/avoidance_module_data.hpp | 6 +++--- .../utils/avoidance/helper.hpp | 16 ++++++++++++++++ .../utils/avoidance/utils.hpp | 2 +- .../scene_module/avoidance/avoidance_module.cpp | 7 ++++--- .../src/scene_module/avoidance/manager.cpp | 15 +++++++++++---- .../src/scene_module/lane_change/manager.cpp | 15 +++++++++++---- .../src/utils/avoidance/utils.cpp | 8 ++++---- 8 files changed, 57 insertions(+), 21 deletions(-) diff --git a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml index 2b38536341d7c..25e42d20d144a 100644 --- a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml +++ b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml @@ -118,8 +118,6 @@ object_ignore_section_crosswalk_in_front_distance: 30.0 # [m] object_ignore_section_crosswalk_behind_distance: 30.0 # [m] # detection range - object_check_forward_distance: 150.0 # [m] - object_check_backward_distance: 2.0 # [m] object_check_goal_distance: 20.0 # [m] # filtering parking objects threshold_distance_object_is_on_center: 1.0 # [m] @@ -128,6 +126,13 @@ # lost object compensation object_last_seen_threshold: 2.0 + # detection area generation parameters + detection_area: + static: true # [-] + min_forward_distance: 50.0 # [m] + max_forward_distance: 150.0 # [m] + backward_distance: 10.0 # [m] + # For safety check safety_check: # safety check configuration 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 5ba0085ded5b7..d04b35a3b185b 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 @@ -145,9 +145,9 @@ struct AvoidanceParameters double object_ignore_section_crosswalk_behind_distance{0.0}; // distance to avoid object detection - double object_check_forward_distance{0.0}; - - // continue to detect backward vehicles as avoidance targets until they are this distance away + bool use_static_detection_area{true}; + double object_check_min_forward_distance{0.0}; + double object_check_max_forward_distance{0.0}; double object_check_backward_distance{0.0}; // if the distance between object and goal position is less than this parameter, the module ignore diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/helper.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/helper.hpp index 77fe2e29c4978..11388dd6bb74a 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/helper.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/helper.hpp @@ -173,6 +173,22 @@ class AvoidanceHelper : std::max(shift_length, getRightShiftBound()); } + double getForwardDetectionRange() const + { + if (parameters_->use_static_detection_area) { + return parameters_->object_check_max_forward_distance; + } + + const auto max_shift_length = std::max( + std::abs(parameters_->max_right_shift_length), std::abs(parameters_->max_left_shift_length)); + const auto dynamic_distance = PathShifter::calcLongitudinalDistFromJerk( + max_shift_length, getLateralMinJerkLimit(), getEgoSpeed()); + + return std::clamp( + 1.5 * dynamic_distance, parameters_->object_check_min_forward_distance, + parameters_->object_check_max_forward_distance); + } + void alignShiftLinesOrder(AvoidLineArray & lines, const bool align_shift_length = true) const { if (lines.empty()) { diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp index f14e523d0619b..8cb09cd47b444 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp @@ -167,7 +167,7 @@ std::vector getSafetyCheckTargetObjects( std::pair separateObjectsByPath( const PathWithLaneId & path, const std::shared_ptr & planner_data, const AvoidancePlanningData & data, const std::shared_ptr & parameters, - const bool is_running, DebugData & debug); + const double object_check_forward_distance, const bool is_running, DebugData & debug); DrivableLanes generateExpandDrivableLanes( const lanelet::ConstLanelet & lanelet, const std::shared_ptr & planner_data, 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 c94406e466219..b4b0a871eec62 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 @@ -322,11 +322,12 @@ void AvoidanceModule::fillAvoidanceTargetObjects( getCurrentStatus() == ModuleStatus::WAITING_APPROVAL; // Separate dynamic objects based on whether they are inside or outside of the expanded lanelets. + const auto sparse_resample_path = utils::resamplePathWithSpline( + helper_.getPreviousSplineShiftPath().path, parameters_->resample_interval_for_output); const auto [object_within_target_lane, object_outside_target_lane] = utils::avoidance::separateObjectsByPath( - utils::resamplePathWithSpline( - helper_.getPreviousSplineShiftPath().path, parameters_->resample_interval_for_output), - planner_data_, data, parameters_, is_running, debug); + sparse_resample_path, planner_data_, data, parameters_, helper_.getForwardDetectionRange(), + is_running, debug); for (const auto & object : object_outside_target_lane.objects) { ObjectData other_object; 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 500ebe873a2d8..763cf17890721 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp @@ -114,10 +114,6 @@ AvoidanceModuleManager::AvoidanceModuleManager( *node, ns + "object_ignore_section_crosswalk_in_front_distance"); p.object_ignore_section_crosswalk_behind_distance = getOrDeclareParameter(*node, ns + "object_ignore_section_crosswalk_behind_distance"); - p.object_check_forward_distance = - getOrDeclareParameter(*node, ns + "object_check_forward_distance"); - p.object_check_backward_distance = - getOrDeclareParameter(*node, ns + "object_check_backward_distance"); p.object_check_goal_distance = getOrDeclareParameter(*node, ns + "object_check_goal_distance"); p.threshold_distance_object_is_on_center = @@ -130,6 +126,17 @@ AvoidanceModuleManager::AvoidanceModuleManager( getOrDeclareParameter(*node, ns + "object_last_seen_threshold"); } + { + std::string ns = "avoidance.target_filtering.detection_area."; + p.use_static_detection_area = getOrDeclareParameter(*node, ns + "static"); + p.object_check_min_forward_distance = + getOrDeclareParameter(*node, ns + "min_forward_distance"); + p.object_check_max_forward_distance = + getOrDeclareParameter(*node, ns + "max_forward_distance"); + p.object_check_backward_distance = + getOrDeclareParameter(*node, ns + "backward_distance"); + } + // safety check general params { std::string ns = "avoidance.safety_check."; 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 3d7cf07308a79..c6995ada1bfa6 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 @@ -329,10 +329,6 @@ AvoidanceByLaneChangeModuleManager::AvoidanceByLaneChangeModuleManager( *node, ns + "object_ignore_section_crosswalk_in_front_distance"); p.object_ignore_section_crosswalk_behind_distance = getOrDeclareParameter(*node, ns + "object_ignore_section_crosswalk_behind_distance"); - p.object_check_forward_distance = - getOrDeclareParameter(*node, ns + "object_check_forward_distance"); - p.object_check_backward_distance = - getOrDeclareParameter(*node, ns + "object_check_backward_distance"); p.object_check_goal_distance = getOrDeclareParameter(*node, ns + "object_check_goal_distance"); p.threshold_distance_object_is_on_center = @@ -345,6 +341,17 @@ AvoidanceByLaneChangeModuleManager::AvoidanceByLaneChangeModuleManager( getOrDeclareParameter(*node, ns + "object_last_seen_threshold"); } + { + std::string ns = "avoidance.target_filtering.detection_area."; + p.use_static_detection_area = getOrDeclareParameter(*node, ns + "static"); + p.object_check_min_forward_distance = + getOrDeclareParameter(*node, ns + "min_forward_distance"); + p.object_check_max_forward_distance = + getOrDeclareParameter(*node, ns + "max_forward_distance"); + p.object_check_backward_distance = + getOrDeclareParameter(*node, ns + "backward_distance"); + } + // safety check { std::string ns = "avoidance.safety_check."; diff --git a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp index 232ab5769f0c7..8fb30a28f1272 100644 --- a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp +++ b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp @@ -991,7 +991,7 @@ void filterTargetObjects( data.other_objects.push_back(o); continue; } - if (o.longitudinal > parameters->object_check_forward_distance) { + if (o.longitudinal > parameters->object_check_max_forward_distance) { o.reason = AvoidanceDebugFactor::OBJECT_IS_IN_FRONT_THRESHOLD; data.other_objects.push_back(o); continue; @@ -1479,7 +1479,7 @@ lanelet::ConstLanelets getAdjacentLane( const std::shared_ptr & parameters, const bool is_right_shift) { const auto & rh = planner_data->route_handler; - const auto & forward_distance = parameters->object_check_forward_distance; + const auto & forward_distance = parameters->object_check_max_forward_distance; const auto & backward_distance = parameters->safety_check_backward_distance; const auto & vehicle_pose = planner_data->self_odometry->pose.pose; @@ -1619,7 +1619,7 @@ std::vector getSafetyCheckTargetObjects( std::pair separateObjectsByPath( const PathWithLaneId & path, const std::shared_ptr & planner_data, const AvoidancePlanningData & data, const std::shared_ptr & parameters, - const bool is_running, DebugData & debug) + const double object_check_forward_distance, const bool is_running, DebugData & debug) { PredictedObjects target_objects; PredictedObjects other_objects; @@ -1642,7 +1642,7 @@ std::pair separateObjectsByPath( const auto & p_ego_back = path.points.at(i + 1).point.pose; const auto distance_from_ego = calcSignedArcLength(path.points, ego_idx, i); - if (distance_from_ego > parameters->object_check_forward_distance) { + if (distance_from_ego > object_check_forward_distance) { break; } From 86a59542d1ef6ec24e168832f9c35bfa2af66e73 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Tue, 17 Oct 2023 21:55:26 +0900 Subject: [PATCH 007/202] fix(drivable_area_expansion): fix max_arc_length parameter and extra_arc_length parameters (#5333) Signed-off-by: Maxime CLEMENT --- .../drivable_area_expansion.cpp | 29 ++++++++++++------- 1 file changed, 19 insertions(+), 10 deletions(-) diff --git a/planning/behavior_path_planner/src/utils/drivable_area_expansion/drivable_area_expansion.cpp b/planning/behavior_path_planner/src/utils/drivable_area_expansion/drivable_area_expansion.cpp index 44dddb57e726e..25cf917d27135 100644 --- a/planning/behavior_path_planner/src/utils/drivable_area_expansion/drivable_area_expansion.cpp +++ b/planning/behavior_path_planner/src/utils/drivable_area_expansion/drivable_area_expansion.cpp @@ -74,14 +74,21 @@ void reuse_previous_poses( if (cropped_poses.empty()) { const auto resampled_path_points = motion_utils::resamplePath(path, params.resample_interval, true, true, false).points; - for (const auto & p : resampled_path_points) cropped_poses.push_back(p.point.pose); - } else if (!path.points.empty()) { + const auto cropped_path = + params.max_path_arc_length <= 0.0 + ? resampled_path_points + : motion_utils::cropForwardPoints( + resampled_path_points, resampled_path_points.front().point.pose.position, 0, + params.max_path_arc_length); + for (const auto & p : cropped_path) cropped_poses.push_back(p.point.pose); + } else { const auto initial_arc_length = motion_utils::calcArcLength(cropped_poses); const auto max_path_arc_length = motion_utils::calcArcLength(path.points); const auto first_arc_length = motion_utils::calcSignedArcLength( path.points, path.points.front().point.pose.position, cropped_poses.back().position); for (auto arc_length = first_arc_length + params.resample_interval; - initial_arc_length + (arc_length - first_arc_length) <= params.max_path_arc_length && + (params.max_path_arc_length <= 0.0 || + initial_arc_length + (arc_length - first_arc_length) <= params.max_path_arc_length) && arc_length <= max_path_arc_length; arc_length += params.resample_interval) cropped_poses.push_back(motion_utils::calcInterpolatedPose(path.points, arc_length)); @@ -129,7 +136,8 @@ std::vector calculate_minimum_expansions( auto arc_length = tier4_autoware_utils::calcDistance2d(*intersection_point, bound[bound_idx + 1]); for (auto up_bound_idx = bound_idx + 2; up_bound_idx < bound.size(); ++up_bound_idx) { - tier4_autoware_utils::calcDistance2d(bound[bound_idx - 1], bound[bound_idx]); + arc_length += + tier4_autoware_utils::calcDistance2d(bound[up_bound_idx - 1], bound[up_bound_idx]); if (arc_length > params.extra_arc_length) break; minimum_expansions[up_bound_idx] = std::max(minimum_expansions[up_bound_idx], dist); } @@ -200,11 +208,11 @@ void expand_bound( LineString2d path_ls; for (const auto & p : path_poses) path_ls.push_back(convert_point(p.position)); for (auto idx = 0LU; idx < bound.size(); ++idx) { - const auto bound_p = convert_point(bound[idx]); - const auto projection = point_to_linestring_projection(bound_p, path_ls); - const auto expansion_ratio = - (expansions[idx] + std::abs(projection.distance)) / std::abs(projection.distance); - if (expansion_ratio > 1.0) { + if (expansions[idx] > 0.0) { + const auto bound_p = convert_point(bound[idx]); + const auto projection = point_to_linestring_projection(bound_p, path_ls); + const auto expansion_ratio = + (expansions[idx] + std::abs(projection.distance)) / std::abs(projection.distance); const auto & path_p = projection.projected_point; const auto expanded_p = lerp_point(path_p, bound_p, expansion_ratio); bound[idx].x = expanded_p.x(); @@ -267,6 +275,7 @@ void expand_drivable_area( stop_watch.tic("crop"); std::vector path_poses = planner_data->drivable_area_expansion_prev_path_poses; std::vector curvatures = planner_data->drivable_area_expansion_prev_curvatures; + reuse_previous_poses( path, path_poses, curvatures, planner_data->self_odometry->pose.pose.position, params); const auto crop_ms = stop_watch.toc("crop"); @@ -299,6 +308,7 @@ void expand_drivable_area( apply_bound_change_rate_limit(left_expansions, path.left_bound, params.max_bound_rate); apply_bound_change_rate_limit(right_expansions, path.right_bound, params.max_bound_rate); const auto smooth_ms = stop_watch.toc("smooth"); + // TODO(Maxime): limit the distances based on the total width (left + right < min_lane_width) stop_watch.tic("expand"); expand_bound(path.left_bound, path_poses, left_expansions); @@ -312,7 +322,6 @@ void expand_drivable_area( "%2.2f\n\tMaximum expansion: %2.2f\n\tSmoothing: %2.2f\n\tExpansion: %2.2f\n\n", total_ms, preprocessing_ms, crop_ms, curvature_expansion_ms, max_dist_ms, smooth_ms, expand_ms); - planner_data->drivable_area_expansion_prev_path_poses = path_poses; planner_data->drivable_area_expansion_prev_curvatures = curvatures; } From c65bccd981cae83eac8f4b85d688d297db49ad1b Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Tue, 17 Oct 2023 22:04:11 +0900 Subject: [PATCH 008/202] refactor(map_based_prediction): to improve readability. Possibly (unlikely) performance improvements (#5261) * refactor to improve readability. Possibly (unlikely) performance Signed-off-by: Daniel Sanchez * Use ternary operator to make the code more readable Signed-off-by: Daniel Sanchez Co-authored-by: Takamasa Horibe * Add const to curr lanelets and pred. object crosswalk Signed-off-by: Daniel Sanchez * remove redundant breaks in switch table Signed-off-by: Daniel Sanchez * change magic numbers to autoware function kph -> mps Signed-off-by: Daniel Sanchez * simplify code by returning on false condition, change ifelse to switch Signed-off-by: Daniel Sanchez --------- Signed-off-by: Daniel Sanchez Co-authored-by: Takamasa Horibe --- .../src/map_based_prediction_node.cpp | 322 +++++++++--------- 1 file changed, 156 insertions(+), 166 deletions(-) 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 58356f4f96ed6..745bccf6dbabe 100644 --- a/perception/map_based_prediction/src/map_based_prediction_node.cpp +++ b/perception/map_based_prediction/src/map_based_prediction_node.cpp @@ -23,6 +23,7 @@ #include #include #include +#include #include #include @@ -369,17 +370,13 @@ bool withinLanelet( boost::geometry::correct(polygon); bool with_in_polygon = boost::geometry::within(p_object, polygon); - if (!use_yaw_information) { - return with_in_polygon; - } else { - // use yaw angle to compare - const double abs_yaw_diff = calcAbsYawDiffBetweenLaneletAndObject(object, lanelet); - if (abs_yaw_diff < yaw_threshold) { - return with_in_polygon; - } else { - return false; - } - } + if (!use_yaw_information) return with_in_polygon; + + // use yaw angle to compare + const double abs_yaw_diff = calcAbsYawDiffBetweenLaneletAndObject(object, lanelet); + if (abs_yaw_diff < yaw_threshold) return with_in_polygon; + + return false; } bool withinRoadLanelet( @@ -594,53 +591,53 @@ ObjectClassification::_label_type changeLabelForPrediction( const lanelet::LaneletMapPtr & lanelet_map_ptr_) { // for car like vehicle do not change labels - if ( - label == ObjectClassification::CAR || label == ObjectClassification::BUS || - label == ObjectClassification::TRUCK || label == ObjectClassification::TRAILER || - label == ObjectClassification::UNKNOWN) { - return label; - } else if ( // for bicycle and motorcycle - label == ObjectClassification::MOTORCYCLE || label == ObjectClassification::BICYCLE) { - // if object is within road lanelet and satisfies yaw constraints - const bool within_road_lanelet = withinRoadLanelet(object, lanelet_map_ptr_, true); - const float high_speed_threshold = 25.0 / 18.0 * 5.0; // High speed bicycle 25 km/h - // calc abs speed from x and y velocity - const double abs_speed = std::hypot( - object.kinematics.twist_with_covariance.twist.linear.x, - object.kinematics.twist_with_covariance.twist.linear.y); - const bool high_speed_object = abs_speed > high_speed_threshold; - - // if the object is within lanelet, do the same estimation with vehicle - if (within_road_lanelet) { - return ObjectClassification::MOTORCYCLE; - } else if (high_speed_object) { + switch (label) { + case ObjectClassification::CAR: + case ObjectClassification::BUS: + case ObjectClassification::TRUCK: + case ObjectClassification::TRAILER: + case ObjectClassification::UNKNOWN: + return label; + + case ObjectClassification::MOTORCYCLE: + case ObjectClassification::BICYCLE: { // if object is within road lanelet and satisfies yaw + // constraints + const bool within_road_lanelet = withinRoadLanelet(object, lanelet_map_ptr_, true); + const float high_speed_threshold = + tier4_autoware_utils::kmph2mps(25.0); // High speed bicycle 25 km/h + // calc abs speed from x and y velocity + const double abs_speed = std::hypot( + object.kinematics.twist_with_covariance.twist.linear.x, + object.kinematics.twist_with_covariance.twist.linear.y); + const bool high_speed_object = abs_speed > high_speed_threshold; + + // if the object is within lanelet, do the same estimation with vehicle + if (within_road_lanelet) return ObjectClassification::MOTORCYCLE; // high speed object outside road lanelet will move like unknown object // return ObjectClassification::UNKNOWN; // temporary disabled - return label; - } else { + if (high_speed_object) return label; // Do nothing for now return ObjectClassification::BICYCLE; } - } else if (label == ObjectClassification::PEDESTRIAN) { - const bool within_road_lanelet = withinRoadLanelet(object, lanelet_map_ptr_, true); - const float max_velocity_for_human_mps = - 25.0 / 18.0 * 5.0; // Max human being motion speed is 25km/h - const double abs_speed = std::hypot( - object.kinematics.twist_with_covariance.twist.linear.x, - object.kinematics.twist_with_covariance.twist.linear.y); - const bool high_speed_object = abs_speed > max_velocity_for_human_mps; - // fast, human-like object: like segway - if (within_road_lanelet && high_speed_object) { - return label; // currently do nothing + + case ObjectClassification::PEDESTRIAN: { + const bool within_road_lanelet = withinRoadLanelet(object, lanelet_map_ptr_, true); + const float max_velocity_for_human_mps = + tier4_autoware_utils::kmph2mps(25.0); // Max human being motion speed is 25km/h + const double abs_speed = std::hypot( + object.kinematics.twist_with_covariance.twist.linear.x, + object.kinematics.twist_with_covariance.twist.linear.y); + const bool high_speed_object = abs_speed > max_velocity_for_human_mps; + // fast, human-like object: like segway + if (within_road_lanelet && high_speed_object) return label; // currently do nothing // return ObjectClassification::MOTORCYCLE; - } else if (high_speed_object) { - return label; // currently do nothing + if (high_speed_object) return label; // currently do nothing // fast human outside road lanelet will move like unknown object // return ObjectClassification::UNKNOWN; - } else { return label; } - } else { - return label; + + default: + return label; } } @@ -850,102 +847,99 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt const auto & label_ = transformed_object.classification.front().label; const auto label = changeLabelForPrediction(label_, object, lanelet_map_ptr_); - // For crosswalk user - if (label == ObjectClassification::PEDESTRIAN || label == ObjectClassification::BICYCLE) { - const auto predicted_object = getPredictedObjectAsCrosswalkUser(transformed_object); - output.objects.push_back(predicted_object); - // For road user - } else if ( - label == ObjectClassification::CAR || label == ObjectClassification::BUS || - label == ObjectClassification::TRAILER || label == ObjectClassification::MOTORCYCLE || - label == ObjectClassification::TRUCK) { - // Update object yaw and velocity - updateObjectData(transformed_object); - - // Get Closest Lanelet - const auto current_lanelets = getCurrentLanelets(transformed_object); - - // Update Objects History - updateObjectsHistory(output.header, transformed_object, current_lanelets); - - // For off lane obstacles - if (current_lanelets.empty()) { - PredictedPath predicted_path = - path_generator_->generatePathForOffLaneVehicle(transformed_object); - predicted_path.confidence = 1.0; - if (predicted_path.path.empty()) { - continue; - } - - auto predicted_object = convertToPredictedObject(transformed_object); - predicted_object.kinematics.predicted_paths.push_back(predicted_path); - output.objects.push_back(predicted_object); - continue; + switch (label) { + case ObjectClassification::PEDESTRIAN: + case ObjectClassification::BICYCLE: { + const auto predicted_object_crosswalk = + getPredictedObjectAsCrosswalkUser(transformed_object); + output.objects.push_back(predicted_object_crosswalk); + break; } - - // For too-slow vehicle - const double abs_obj_speed = std::hypot( - transformed_object.kinematics.twist_with_covariance.twist.linear.x, - transformed_object.kinematics.twist_with_covariance.twist.linear.y); - if (std::fabs(abs_obj_speed) < min_velocity_for_map_based_prediction_) { - PredictedPath predicted_path = - path_generator_->generatePathForLowSpeedVehicle(transformed_object); - predicted_path.confidence = 1.0; - if (predicted_path.path.empty()) { - continue; + case ObjectClassification::CAR: + case ObjectClassification::BUS: + case ObjectClassification::TRAILER: + case ObjectClassification::MOTORCYCLE: + case ObjectClassification::TRUCK: { + // Update object yaw and velocity + updateObjectData(transformed_object); + + // Get Closest Lanelet + const auto current_lanelets = getCurrentLanelets(transformed_object); + + // Update Objects History + updateObjectsHistory(output.header, transformed_object, current_lanelets); + + // For off lane obstacles + if (current_lanelets.empty()) { + PredictedPath predicted_path = + path_generator_->generatePathForOffLaneVehicle(transformed_object); + predicted_path.confidence = 1.0; + if (predicted_path.path.empty()) break; + + auto predicted_object_vehicle = convertToPredictedObject(transformed_object); + predicted_object_vehicle.kinematics.predicted_paths.push_back(predicted_path); + output.objects.push_back(predicted_object_vehicle); + break; } - auto predicted_object = convertToPredictedObject(transformed_object); - predicted_object.kinematics.predicted_paths.push_back(predicted_path); - output.objects.push_back(predicted_object); - continue; - } - - // Get Predicted Reference Path for Each Maneuver and current lanelets - // return: - const auto ref_paths = - getPredictedReferencePath(transformed_object, current_lanelets, objects_detected_time); - - // If predicted reference path is empty, assume this object is out of the lane - if (ref_paths.empty()) { - PredictedPath predicted_path = - path_generator_->generatePathForLowSpeedVehicle(transformed_object); - predicted_path.confidence = 1.0; - if (predicted_path.path.empty()) { - continue; + // For too-slow vehicle + const double abs_obj_speed = std::hypot( + transformed_object.kinematics.twist_with_covariance.twist.linear.x, + transformed_object.kinematics.twist_with_covariance.twist.linear.y); + if (std::fabs(abs_obj_speed) < min_velocity_for_map_based_prediction_) { + PredictedPath predicted_path = + path_generator_->generatePathForLowSpeedVehicle(transformed_object); + predicted_path.confidence = 1.0; + if (predicted_path.path.empty()) break; + + auto predicted_slow_object = convertToPredictedObject(transformed_object); + predicted_slow_object.kinematics.predicted_paths.push_back(predicted_path); + output.objects.push_back(predicted_slow_object); + break; } - auto predicted_object = convertToPredictedObject(transformed_object); - predicted_object.kinematics.predicted_paths.push_back(predicted_path); - output.objects.push_back(predicted_object); - continue; - } + // Get Predicted Reference Path for Each Maneuver and current lanelets + // return: + const auto ref_paths = + getPredictedReferencePath(transformed_object, current_lanelets, objects_detected_time); + + // If predicted reference path is empty, assume this object is out of the lane + if (ref_paths.empty()) { + PredictedPath predicted_path = + path_generator_->generatePathForLowSpeedVehicle(transformed_object); + predicted_path.confidence = 1.0; + if (predicted_path.path.empty()) break; + + auto predicted_object_out_of_lane = convertToPredictedObject(transformed_object); + predicted_object_out_of_lane.kinematics.predicted_paths.push_back(predicted_path); + output.objects.push_back(predicted_object_out_of_lane); + break; + } - // Get Debug Marker for On Lane Vehicles - const auto max_prob_path = std::max_element( - ref_paths.begin(), ref_paths.end(), - [](const PredictedRefPath & a, const PredictedRefPath & b) { - return a.probability < b.probability; - }); - const auto debug_marker = - getDebugMarker(object, max_prob_path->maneuver, debug_markers.markers.size()); - debug_markers.markers.push_back(debug_marker); - - // Generate Predicted Path - std::vector predicted_paths; - for (const auto & ref_path : ref_paths) { - PredictedPath predicted_path = - path_generator_->generatePathForOnLaneVehicle(transformed_object, ref_path.path); - if (predicted_path.path.empty()) { - continue; + // Get Debug Marker for On Lane Vehicles + const auto max_prob_path = std::max_element( + ref_paths.begin(), ref_paths.end(), + [](const PredictedRefPath & a, const PredictedRefPath & b) { + return a.probability < b.probability; + }); + const auto debug_marker = + getDebugMarker(object, max_prob_path->maneuver, debug_markers.markers.size()); + debug_markers.markers.push_back(debug_marker); + + // Generate Predicted Path + std::vector predicted_paths; + for (const auto & ref_path : ref_paths) { + PredictedPath predicted_path = + path_generator_->generatePathForOnLaneVehicle(transformed_object, ref_path.path); + if (predicted_path.path.empty()) { + continue; + } + predicted_path.confidence = ref_path.probability; + predicted_paths.push_back(predicted_path); } - predicted_path.confidence = ref_path.probability; - predicted_paths.push_back(predicted_path); - } + // Normalize Path Confidence and output the predicted object - // Normalize Path Confidence and output the predicted object - { float sum_confidence = 0.0; for (const auto & predicted_path : predicted_paths) { sum_confidence += predicted_path.confidence; @@ -953,25 +947,25 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt const float min_sum_confidence_value = 1e-3; sum_confidence = std::max(sum_confidence, min_sum_confidence_value); + auto predicted_object = convertToPredictedObject(transformed_object); + for (auto & predicted_path : predicted_paths) { predicted_path.confidence = predicted_path.confidence / sum_confidence; - } - - auto predicted_object = convertToPredictedObject(transformed_object); - for (const auto & predicted_path : predicted_paths) { predicted_object.kinematics.predicted_paths.push_back(predicted_path); } output.objects.push_back(predicted_object); + break; } - // For unknown object - } else { - auto predicted_object = convertToPredictedObject(transformed_object); - PredictedPath predicted_path = - path_generator_->generatePathForNonVehicleObject(transformed_object); - predicted_path.confidence = 1.0; + default: { + auto predicted_unknown_object = convertToPredictedObject(transformed_object); + PredictedPath predicted_path = + path_generator_->generatePathForNonVehicleObject(transformed_object); + predicted_path.confidence = 1.0; - predicted_object.kinematics.predicted_paths.push_back(predicted_path); - output.objects.push_back(predicted_object); + predicted_unknown_object.kinematics.predicted_paths.push_back(predicted_path); + output.objects.push_back(predicted_unknown_object); + break; + } } } @@ -1114,26 +1108,28 @@ void MapBasedPredictionNode::updateObjectData(TrackedObject & object) object_pose, object_twist.linear.x * 0.1, object_twist.linear.y * 0.1, 0.0); // assumption: the object vx is much larger than vy - if (object.kinematics.twist_with_covariance.twist.linear.x < 0.0) { - if ( - object.kinematics.orientation_availability == - autoware_auto_perception_msgs::msg::DetectedObjectKinematics::SIGN_UNKNOWN) { + if (object.kinematics.twist_with_covariance.twist.linear.x >= 0.0) return; + + switch (object.kinematics.orientation_availability) { + case autoware_auto_perception_msgs::msg::DetectedObjectKinematics::SIGN_UNKNOWN: { const auto original_yaw = tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation); // flip the angle object.kinematics.pose_with_covariance.pose.orientation = tier4_autoware_utils::createQuaternionFromYaw(tier4_autoware_utils::pi + original_yaw); - } else { + break; + } + default: { const auto updated_object_yaw = tier4_autoware_utils::calcAzimuthAngle(object_pose.position, future_object_pose.position); object.kinematics.pose_with_covariance.pose.orientation = tier4_autoware_utils::createQuaternionFromYaw(updated_object_yaw); + break; } - - object.kinematics.twist_with_covariance.twist.linear.x *= -1.0; - object.kinematics.twist_with_covariance.twist.linear.y *= -1.0; } + object.kinematics.twist_with_covariance.twist.linear.x *= -1.0; + object.kinematics.twist_with_covariance.twist.linear.y *= -1.0; return; } @@ -1864,16 +1860,10 @@ ManeuverProbability MapBasedPredictionNode::calculateManeuverProbability( constexpr float LC_PROB = 1.0; // probability for left lane change constexpr float RC_PROB = 1.0; // probability for right lane change lane_follow_probability = 0.0; - if (!left_paths.empty() && right_paths.empty()) { - left_lane_change_probability = LC_PROB; - right_lane_change_probability = 0.0; - } else if (left_paths.empty() && !right_paths.empty()) { - left_lane_change_probability = 0.0; - right_lane_change_probability = RC_PROB; - } else { - left_lane_change_probability = LC_PROB; - right_lane_change_probability = RC_PROB; - } + + // If the given lane is empty, the probability goes to 0 + left_lane_change_probability = left_paths.empty() ? 0.0 : LC_PROB; + right_lane_change_probability = right_paths.empty() ? 0.0 : RC_PROB; } const float MIN_PROBABILITY = 1e-3; From b3bdedc584682fe6ab6310af4792312c36521e74 Mon Sep 17 00:00:00 2001 From: beyzanurkaya <32412808+beyzanurkaya@users.noreply.github.com> Date: Wed, 18 Oct 2023 00:40:26 +0300 Subject: [PATCH 009/202] fix(obstacle_avoidance_planner): fix lateral calculations (#4292) * use right_overhang and left_overhang for lateral calculation Signed-off-by: beyza * style(pre-commit): autofix * update debug_marker.cpp * style(pre-commit): autofix --------- Signed-off-by: beyza Co-authored-by: beyza Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../src/debug_marker.cpp | 56 +++++++++++-------- .../src/mpt_optimizer.cpp | 17 ++++-- 2 files changed, 43 insertions(+), 30 deletions(-) diff --git a/planning/obstacle_avoidance_planner/src/debug_marker.cpp b/planning/obstacle_avoidance_planner/src/debug_marker.cpp index 8bf46c697104a..2f8babf103877 100644 --- a/planning/obstacle_avoidance_planner/src/debug_marker.cpp +++ b/planning/obstacle_avoidance_planner/src/debug_marker.cpp @@ -47,21 +47,22 @@ MarkerArray getFootprintsMarkerArray( const auto & traj_point = mpt_traj.at(i); - const double half_width = vehicle_info.vehicle_width_m / 2.0; + const double base_to_right = (vehicle_info.wheel_tread_m / 2.0) + vehicle_info.right_overhang_m; + const double base_to_left = (vehicle_info.wheel_tread_m / 2.0) + vehicle_info.left_overhang_m; 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(traj_point.pose, base_to_front, -half_width, 0.0) + tier4_autoware_utils::calcOffsetPose(traj_point.pose, base_to_front, base_to_left, 0.0) .position); marker.points.push_back( - tier4_autoware_utils::calcOffsetPose(traj_point.pose, base_to_front, half_width, 0.0) + tier4_autoware_utils::calcOffsetPose(traj_point.pose, base_to_front, -base_to_right, 0.0) .position); marker.points.push_back( - tier4_autoware_utils::calcOffsetPose(traj_point.pose, -base_to_rear, half_width, 0.0) + tier4_autoware_utils::calcOffsetPose(traj_point.pose, -base_to_rear, -base_to_right, 0.0) .position); marker.points.push_back( - tier4_autoware_utils::calcOffsetPose(traj_point.pose, -base_to_rear, -half_width, 0.0) + tier4_autoware_utils::calcOffsetPose(traj_point.pose, -base_to_rear, base_to_left, 0.0) .position); marker.points.push_back(marker.points.front()); @@ -71,8 +72,8 @@ MarkerArray getFootprintsMarkerArray( } MarkerArray getBoundsWidthMarkerArray( - const std::vector & ref_points, const double vehicle_width, - const size_t sampling_num) + const std::vector & ref_points, + const vehicle_info_util::VehicleInfo & vehicle_info, const size_t sampling_num) { const auto current_time = rclcpp::Clock().now(); MarkerArray marker_array; @@ -105,8 +106,10 @@ MarkerArray getBoundsWidthMarkerArray( } const geometry_msgs::msg::Pose & pose = ref_points.at(i).pose_on_constraints.at(bound_idx); + const double base_to_right = + (vehicle_info.wheel_tread_m / 2.0) + vehicle_info.right_overhang_m; const double lb_y = - ref_points.at(i).bounds_on_constraints.at(bound_idx).lower_bound - vehicle_width / 2.0; + ref_points.at(i).bounds_on_constraints.at(bound_idx).lower_bound - base_to_right; const auto lb = tier4_autoware_utils::calcOffsetPose(pose, 0.0, lb_y, 0.0).position; lb_marker.points.push_back(pose.position); @@ -125,8 +128,10 @@ MarkerArray getBoundsWidthMarkerArray( } const geometry_msgs::msg::Pose & pose = ref_points.at(i).pose_on_constraints.at(bound_idx); + const double base_to_left = + (vehicle_info.wheel_tread_m / 2.0) + vehicle_info.left_overhang_m; const double ub_y = - ref_points.at(i).bounds_on_constraints.at(bound_idx).upper_bound + vehicle_width / 2.0; + ref_points.at(i).bounds_on_constraints.at(bound_idx).upper_bound + base_to_left; const auto ub = tier4_autoware_utils::calcOffsetPose(pose, 0.0, ub_y, 0.0).position; ub_marker.points.push_back(pose.position); @@ -140,7 +145,8 @@ MarkerArray getBoundsWidthMarkerArray( } MarkerArray getBoundsLineMarkerArray( - const std::vector & ref_points, const double vehicle_width) + const std::vector & ref_points, + const vehicle_info_util::VehicleInfo & vehicle_info) { MarkerArray marker_array; @@ -158,12 +164,13 @@ MarkerArray getBoundsLineMarkerArray( for (size_t i = 0; i < ref_points.size(); i++) { const geometry_msgs::msg::Pose & pose = ref_points.at(i).pose; - - const double ub_y = ref_points.at(i).bounds.upper_bound + vehicle_width / 2.0; + const double base_to_right = (vehicle_info.wheel_tread_m / 2.0) + vehicle_info.right_overhang_m; + const double base_to_left = (vehicle_info.wheel_tread_m / 2.0) + vehicle_info.left_overhang_m; + const double ub_y = ref_points.at(i).bounds.upper_bound + base_to_left; const auto ub = tier4_autoware_utils::calcOffsetPose(pose, 0.0, ub_y, 0.0).position; ub_marker.points.push_back(ub); - const double lb_y = ref_points.at(i).bounds.lower_bound - vehicle_width / 2.0; + const double lb_y = ref_points.at(i).bounds.lower_bound - base_to_right; const auto lb = tier4_autoware_utils::calcOffsetPose(pose, 0.0, lb_y, 0.0).position; lb_marker.points.push_back(lb); } @@ -175,8 +182,9 @@ MarkerArray getBoundsLineMarkerArray( MarkerArray getVehicleCircleLinesMarkerArray( const std::vector & ref_points, - const std::vector & vehicle_circle_longitudinal_offsets, const double vehicle_width, - const size_t sampling_num, const std::string & ns) + const std::vector & vehicle_circle_longitudinal_offsets, + const vehicle_info_util::VehicleInfo & vehicle_info, const size_t sampling_num, + const std::string & ns) { const auto current_time = rclcpp::Clock().now(); MarkerArray msg; @@ -206,11 +214,13 @@ MarkerArray getVehicleCircleLinesMarkerArray( auto base_pose = tier4_autoware_utils::calcOffsetPose(pose_with_deviation, d, 0.0, 0.0); base_pose.orientation = tier4_autoware_utils::createQuaternionFromYaw(ref_point.getYaw() + ref_point.alpha); - + const double base_to_right = + (vehicle_info.wheel_tread_m / 2.0) + vehicle_info.right_overhang_m; + const double base_to_left = (vehicle_info.wheel_tread_m / 2.0) + vehicle_info.left_overhang_m; const auto ub = - tier4_autoware_utils::calcOffsetPose(base_pose, 0.0, vehicle_width / 2.0, 0.0).position; + tier4_autoware_utils::calcOffsetPose(base_pose, 0.0, base_to_left, 0.0).position; const auto lb = - tier4_autoware_utils::calcOffsetPose(base_pose, 0.0, -vehicle_width / 2.0, 0.0).position; + tier4_autoware_utils::calcOffsetPose(base_pose, 0.0, -base_to_right, 0.0).position; marker.points.push_back(ub); marker.points.push_back(lb); @@ -368,13 +378,12 @@ MarkerArray getDebugMarker( MarkerArray marker_array; // bounds line - appendMarkerArray( - getBoundsLineMarkerArray(debug_data.ref_points, vehicle_info.vehicle_width_m), &marker_array); + appendMarkerArray(getBoundsLineMarkerArray(debug_data.ref_points, vehicle_info), &marker_array); // bounds width appendMarkerArray( getBoundsWidthMarkerArray( - debug_data.ref_points, vehicle_info.vehicle_width_m, debug_data.mpt_visualize_sampling_num), + debug_data.ref_points, vehicle_info, debug_data.mpt_visualize_sampling_num), &marker_array); // current vehicle circles @@ -404,9 +413,8 @@ MarkerArray getDebugMarker( // vehicle circle line appendMarkerArray( getVehicleCircleLinesMarkerArray( - debug_data.ref_points, debug_data.vehicle_circle_longitudinal_offsets, - vehicle_info.vehicle_width_m, debug_data.mpt_visualize_sampling_num, - "vehicle_circle_lines"), + debug_data.ref_points, debug_data.vehicle_circle_longitudinal_offsets, vehicle_info, + debug_data.mpt_visualize_sampling_num, "vehicle_circle_lines"), &marker_array); // footprint by drivable area diff --git a/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp b/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp index 359485fadcfff..765136b3cf6f6 100644 --- a/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp +++ b/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp @@ -36,9 +36,11 @@ std::tuple, std::vector> calcVehicleCirclesByUniform const vehicle_info_util::VehicleInfo & vehicle_info, const size_t circle_num, const double radius_ratio) { + const double lateral_offset = + abs(vehicle_info.right_overhang_m - vehicle_info.left_overhang_m) / 2.0; const double radius = std::hypot( vehicle_info.vehicle_length_m / static_cast(circle_num) / 2.0, - vehicle_info.vehicle_width_m / 2.0) * + vehicle_info.vehicle_width_m / 2.0 + lateral_offset) * radius_ratio; const std::vector radiuses(circle_num, radius); @@ -59,16 +61,18 @@ std::tuple, std::vector> calcVehicleCirclesByBicycle if (circle_num < 2) { throw std::invalid_argument("circle_num is less than 2."); } - + const double lateral_offset = + abs(vehicle_info.right_overhang_m - vehicle_info.left_overhang_m) / 2.0; // 1st circle (rear wheel) - const double rear_radius = vehicle_info.vehicle_width_m / 2.0 * rear_radius_ratio; + const double rear_radius = + vehicle_info.vehicle_width_m / 2.0 + lateral_offset * rear_radius_ratio; const double rear_lon_offset = 0.0; // 2nd circle (front wheel) const double front_radius = std::hypot( vehicle_info.vehicle_length_m / static_cast(circle_num) / 2.0, - vehicle_info.vehicle_width_m / 2.0) * + vehicle_info.vehicle_width_m / 2.0 + lateral_offset) * front_radius_ratio; const double unit_lon_length = vehicle_info.vehicle_length_m / static_cast(circle_num); @@ -84,8 +88,9 @@ std::tuple, std::vector> calcVehicleCirclesByFitting if (circle_num < 2) { throw std::invalid_argument("circle_num is less than 2."); } - - const double radius = vehicle_info.vehicle_width_m / 2.0; + const double lateral_offset = + abs(vehicle_info.right_overhang_m - vehicle_info.left_overhang_m) / 2.0; + const double radius = vehicle_info.vehicle_width_m / 2.0 + lateral_offset; std::vector radiuses(circle_num, radius); const double unit_lon_length = From 5c220226e06f94416ee7794ae40a165a76680799 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 18 Oct 2023 09:54:51 +0900 Subject: [PATCH 010/202] fix(lane_change): detect stuck in current lane termianl (#5337) * feat(lane_change): detect stuck in current lane termianl Signed-off-by: kosuke55 * rename func Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 --- .../scene_module/lane_change/normal.hpp | 4 +- .../src/scene_module/lane_change/normal.cpp | 37 ++++++++++++++----- 2 files changed, 30 insertions(+), 11 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp index 8400cf8c40afd..54883489f2fe6 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp @@ -158,10 +158,10 @@ class NormalLaneChange : public LaneChangeBase //! @brief Check if the ego vehicle is in stuck by a stationary obstacle. //! @param obstacle_check_distance Distance to check ahead for any objects that might be //! obstructing ego path. It makes sense to use values like the maximum lane change distance. - bool isVehicleStuckByObstacle( + bool isVehicleStuck( const lanelet::ConstLanelets & current_lanes, const double obstacle_check_distance) const; - bool isVehicleStuckByObstacle(const lanelet::ConstLanelets & current_lanes) const; + bool isVehicleStuck(const lanelet::ConstLanelets & current_lanes) const; double calcMaximumLaneChangeLength( const lanelet::ConstLanelet & current_terminal_lanelet, const double max_acc) const; 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 3a2903cb01e9e..ce07cda882692 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 @@ -83,7 +83,7 @@ std::pair NormalLaneChange::getSafePath(LaneChangePath & safe_path) // find candidate paths LaneChangePaths valid_paths{}; - const bool is_stuck = isVehicleStuckByObstacle(current_lanes); + const bool is_stuck = isVehicleStuck(current_lanes); bool found_safe_path = getLaneChangePaths( current_lanes, target_lanes, direction_, &valid_paths, lane_change_parameters_->rss_params, is_stuck); @@ -670,7 +670,7 @@ std::vector NormalLaneChange::sampleLongitudinalAccValues( } // If the ego is in stuck, sampling all possible accelerations to find avoiding path. - if (isVehicleStuckByObstacle(current_lanes)) { + if (isVehicleStuck(current_lanes)) { auto clock = rclcpp::Clock(RCL_ROS_TIME); RCLCPP_INFO_THROTTLE( logger_, clock, 1000, "Vehicle is in stuck. Sample all possible acc: [%f ~ %f]", min_acc, @@ -1333,7 +1333,7 @@ PathSafetyStatus NormalLaneChange::isApprovedPathSafe() const debug_filtered_objects_ = target_objects; CollisionCheckDebugMap debug_data; - const bool is_stuck = isVehicleStuckByObstacle(current_lanes); + const bool is_stuck = isVehicleStuck(current_lanes); const auto safety_status = isLaneChangePathSafe( path, target_objects, lane_change_parameters_->rss_params_for_abort, is_stuck, debug_data); { @@ -1674,8 +1674,8 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe( return path_safety_status; } -// Check if the ego vehicle is in stuck by a stationary obstacle. -bool NormalLaneChange::isVehicleStuckByObstacle( +// Check if the ego vehicle is in stuck by a stationary obstacle or by the terminal of current lanes +bool NormalLaneChange::isVehicleStuck( const lanelet::ConstLanelets & current_lanes, const double obstacle_check_distance) const { // Ego is still moving, not in stuck @@ -1709,12 +1709,31 @@ bool NormalLaneChange::isVehicleStuckByObstacle( } } - // No stationary objects found in obstacle_check_distance - RCLCPP_DEBUG(logger_, "No stationary objects found in obstacle_check_distance"); + // Check if Ego is in terminal of current lanes + const auto & route_handler = getRouteHandler(); + const double distance_to_terminal = + route_handler->isInGoalRouteSection(current_lanes.back()) + ? utils::getSignedDistance(getEgoPose(), route_handler->getGoalPose(), current_lanes) + : utils::getDistanceToEndOfLane(getEgoPose(), current_lanes); + const auto shift_intervals = + route_handler->getLateralIntervalsToPreferredLane(current_lanes.back()); + const double lane_change_buffer = + utils::calcMinimumLaneChangeLength(getCommonParam(), shift_intervals, 0.0); + const double stop_point_buffer = getCommonParam().backward_length_buffer_for_end_of_lane; + const double terminal_judge_buffer = lane_change_buffer + stop_point_buffer + 1.0; + if (distance_to_terminal < terminal_judge_buffer) { + return true; + } + + // No stationary objects found in obstacle_check_distance and Ego is not in terminal of current + RCLCPP_DEBUG( + logger_, + "No stationary objects found in obstacle_check_distance and Ego is not in " + "terminal of current lanes"); return false; } -bool NormalLaneChange::isVehicleStuckByObstacle(const lanelet::ConstLanelets & current_lanes) const +bool NormalLaneChange::isVehicleStuck(const lanelet::ConstLanelets & current_lanes) const { if (current_lanes.empty()) { return false; // can not check @@ -1736,7 +1755,7 @@ bool NormalLaneChange::isVehicleStuckByObstacle(const lanelet::ConstLanelets & c getCommonParam().base_link2front + DETECTION_DISTANCE_MARGIN; RCLCPP_DEBUG(logger_, "max_lane_change_length: %f, max_acc: %f", max_lane_change_length, max_acc); - return isVehicleStuckByObstacle(current_lanes, detection_distance); + return isVehicleStuck(current_lanes, detection_distance); } void NormalLaneChange::setStopPose(const Pose & stop_pose) From 16217e849b65047525c2c080cfca9ab77149f788 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Wed, 18 Oct 2023 10:27:17 +0900 Subject: [PATCH 011/202] fix(intersection): fix misuse of original path index to interpolated path (#5334) Signed-off-by: Mamoru Sobue --- .../src/util.cpp | 15 ++++++++++++++- 1 file changed, 14 insertions(+), 1 deletion(-) diff --git a/planning/behavior_velocity_intersection_module/src/util.cpp b/planning/behavior_velocity_intersection_module/src/util.cpp index 08c818c2e49ce..bd31f758f6d0d 100644 --- a/planning/behavior_velocity_intersection_module/src/util.cpp +++ b/planning/behavior_velocity_intersection_module/src/util.cpp @@ -1327,6 +1327,19 @@ TimeDistanceArray calcIntersectionPassingTime( dist_sum = 0.0; double passing_time = time_delay; time_distance_array.emplace_back(passing_time, dist_sum); + + // NOTE: `reference_path` is resampled in `reference_smoothed_path`, so + // `last_intersection_stop_line_candidate_idx` makes no sense + const auto last_intersection_stop_line_candidate_point_orig = + path.points.at(last_intersection_stop_line_candidate_idx).point.pose; + const auto last_intersection_stop_line_candidate_nearest_ind_opt = motion_utils::findNearestIndex( + smoothed_reference_path.points, last_intersection_stop_line_candidate_point_orig, 3.0, M_PI_4); + if (!last_intersection_stop_line_candidate_nearest_ind_opt) { + return time_distance_array; + } + const auto last_intersection_stop_line_candidate_nearest_ind = + last_intersection_stop_line_candidate_nearest_ind_opt.value(); + for (size_t i = 1; i < smoothed_reference_path.points.size(); ++i) { const auto & p1 = smoothed_reference_path.points.at(i - 1); const auto & p2 = smoothed_reference_path.points.at(i); @@ -1338,7 +1351,7 @@ TimeDistanceArray calcIntersectionPassingTime( const double average_velocity = (p1.point.longitudinal_velocity_mps + p2.point.longitudinal_velocity_mps) / 2.0; const double minimum_ego_velocity_division = - (use_upstream_velocity && i > last_intersection_stop_line_candidate_idx) + (use_upstream_velocity && i > last_intersection_stop_line_candidate_nearest_ind) ? minimum_upstream_velocity /* to avoid null division */ : minimum_ego_velocity; const double passing_velocity = From f0ea398bd5fe71e51eb80116f0a29c035e2843a4 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Wed, 18 Oct 2023 10:27:43 +0900 Subject: [PATCH 012/202] fix(intersection): fix infinite loop in tsort (#5332) Signed-off-by: Mamoru Sobue --- .../src/util.cpp | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/planning/behavior_velocity_intersection_module/src/util.cpp b/planning/behavior_velocity_intersection_module/src/util.cpp index bd31f758f6d0d..403509a926022 100644 --- a/planning/behavior_velocity_intersection_module/src/util.cpp +++ b/planning/behavior_velocity_intersection_module/src/util.cpp @@ -605,6 +605,8 @@ mergeLaneletsByTopologicalSort( id2lanelet[id] = lanelet; ind++; } + // NOTE: this function aims to traverse the detection lanelet backward from ego side to farthest + // side, so if lane B follows lane A on the routing_graph, adj[B][A] = true for (const auto & lanelet : lanelets) { const auto & followings = routing_graph_ptr->following(lanelet); const int dst = lanelet.id(); @@ -628,18 +630,25 @@ mergeLaneletsByTopologicalSort( if (!has_no_previous(src)) { continue; } + // So `src` has no previous lanelets branches[(ind2id[src])] = std::vector{}; auto & branch = branches[(ind2id[src])]; lanelet::Id node_iter = ind2id[src]; + std::set visited_ids; while (true) { const auto & destinations = adjacency[(id2ind[node_iter])]; - // NOTE: assuming detection lanelets have only one previous lanelet + // NOTE: assuming detection lanelets have only one "previous"(on the routing_graph) lanelet const auto next = std::find(destinations.begin(), destinations.end(), true); if (next == destinations.end()) { branch.push_back(node_iter); break; } + if (visited_ids.find(node_iter) != visited_ids.end()) { + // loop detected + break; + } branch.push_back(node_iter); + visited_ids.insert(node_iter); node_iter = ind2id[std::distance(destinations.begin(), next)]; } } From 22a5ced2c7a4d4b9421b508cf90e4d9018a073c9 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Wed, 18 Oct 2023 10:48:05 +0900 Subject: [PATCH 013/202] feat(behavior_path_planner): add postProcess() in scene module interface (#5336) * add postProcess Signed-off-by: kyoichi-sugahara * modify comment Signed-off-by: kyoichi-sugahara --------- Signed-off-by: kyoichi-sugahara --- .../include/behavior_path_planner/planner_manager.hpp | 2 ++ .../scene_module/scene_module_interface.hpp | 6 ++++++ 2 files changed, 8 insertions(+) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp index 72c32039da627..4b9b0bff4be63 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp @@ -272,6 +272,8 @@ class PlannerManager const auto result = module_ptr->run(); module_ptr->unlockRTCCommand(); + module_ptr->postProcess(); + module_ptr->updateCurrentState(); module_ptr->publishRTCStatus(); diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp index 077f7a3a763d5..68faa3806f614 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp @@ -131,6 +131,12 @@ class SceneModuleInterface */ virtual void updateData() {} + /** + * @brief After executing run(), update the module-specific status and/or data used for internal + * processing that are not defined in ModuleStatus. + */ + virtual void postProcess() {} + /** * @brief Execute module. Once this function is executed, * it will continue to run as long as it is in the RUNNING state. From a39b20d95200527726284101a0030dad08aa5a59 Mon Sep 17 00:00:00 2001 From: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> Date: Wed, 18 Oct 2023 17:00:15 +0900 Subject: [PATCH 014/202] fix(detected_object_validation): consider shoulder lanelet in object lanelet filter (#5324) * fix(detected_object_validation): consider shoulder lanelet in object lanelet filter Signed-off-by: Shumpei Wakabayashi * style(pre-commit): autofix --------- Signed-off-by: Shumpei Wakabayashi Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../detected_object_filter/object_lanelet_filter.hpp | 1 + .../src/object_lanelet_filter.cpp | 10 ++++++++-- 2 files changed, 9 insertions(+), 2 deletions(-) diff --git a/perception/detected_object_validation/include/detected_object_filter/object_lanelet_filter.hpp b/perception/detected_object_validation/include/detected_object_filter/object_lanelet_filter.hpp index 600da31df5868..ae6162542a1c3 100644 --- a/perception/detected_object_validation/include/detected_object_filter/object_lanelet_filter.hpp +++ b/perception/detected_object_validation/include/detected_object_filter/object_lanelet_filter.hpp @@ -51,6 +51,7 @@ class ObjectLaneletFilterNode : public rclcpp::Node lanelet::LaneletMapPtr lanelet_map_ptr_; lanelet::ConstLanelets road_lanelets_; + lanelet::ConstLanelets shoulder_lanelets_; std::string lanelet_frame_id_; tf2_ros::Buffer tf_buffer_; diff --git a/perception/detected_object_validation/src/object_lanelet_filter.cpp b/perception/detected_object_validation/src/object_lanelet_filter.cpp index 3b78ae449e2da..f9b208cca02bc 100644 --- a/perception/detected_object_validation/src/object_lanelet_filter.cpp +++ b/perception/detected_object_validation/src/object_lanelet_filter.cpp @@ -62,6 +62,7 @@ void ObjectLaneletFilterNode::mapCallback( lanelet::utils::conversion::fromBinMsg(*map_msg, lanelet_map_ptr_); const lanelet::ConstLanelets all_lanelets = lanelet::utils::query::laneletLayer(lanelet_map_ptr_); road_lanelets_ = lanelet::utils::query::roadLanelets(all_lanelets); + shoulder_lanelets_ = lanelet::utils::query::shoulderLanelets(all_lanelets); } void ObjectLaneletFilterNode::objectCallback( @@ -87,7 +88,10 @@ void ObjectLaneletFilterNode::objectCallback( // calculate convex hull const auto convex_hull = getConvexHull(transformed_objects); // get intersected lanelets - lanelet::ConstLanelets intersected_lanelets = getIntersectedLanelets(convex_hull, road_lanelets_); + lanelet::ConstLanelets intersected_road_lanelets = + getIntersectedLanelets(convex_hull, road_lanelets_); + lanelet::ConstLanelets intersected_shoulder_lanelets = + getIntersectedLanelets(convex_hull, shoulder_lanelets_); int index = 0; for (const auto & object : transformed_objects.objects) { @@ -101,7 +105,9 @@ void ObjectLaneletFilterNode::objectCallback( polygon.outer().emplace_back(point_transformed.x, point_transformed.y); } polygon.outer().push_back(polygon.outer().front()); - if (isPolygonOverlapLanelets(polygon, intersected_lanelets)) { + if (isPolygonOverlapLanelets(polygon, intersected_road_lanelets)) { + output_object_msg.objects.emplace_back(input_msg->objects.at(index)); + } else if (isPolygonOverlapLanelets(polygon, intersected_shoulder_lanelets)) { output_object_msg.objects.emplace_back(input_msg->objects.at(index)); } } else { From 264accb7086239e6c128478bf0f548138db59068 Mon Sep 17 00:00:00 2001 From: melike tanrikulu <41450930+meliketanrikulu@users.noreply.github.com> Date: Wed, 18 Oct 2023 11:04:28 +0300 Subject: [PATCH 015/202] fix(gnss_poser): fix_transform_direction_problem (#5033) * fix(gnss_poser)fix_transform_direction_problem Signed-off-by: meliketanrikulu * style(pre-commit): autofix * fix(gnss_poser)update comment line Signed-off-by: meliketanrikulu --------- Signed-off-by: meliketanrikulu Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- sensing/gnss_poser/src/gnss_poser_core.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/sensing/gnss_poser/src/gnss_poser_core.cpp b/sensing/gnss_poser/src/gnss_poser_core.cpp index 599a017bffed7..3a18dca815f12 100644 --- a/sensing/gnss_poser/src/gnss_poser_core.cpp +++ b/sensing/gnss_poser/src/gnss_poser_core.cpp @@ -139,11 +139,11 @@ void GNSSPoser::callbackNavSatFix( tf2::Transform tf_map2gnss_antenna{}; tf2::fromMsg(gnss_antenna_pose, tf_map2gnss_antenna); - // get TF from base_link to gnss_antenna + // get TF from gnss_antenna to base_link auto tf_gnss_antenna2base_link_msg_ptr = std::make_shared(); getStaticTransform( - gnss_frame_, base_frame_, tf_gnss_antenna2base_link_msg_ptr, nav_sat_fix_msg_ptr->header.stamp); + base_frame_, gnss_frame_, tf_gnss_antenna2base_link_msg_ptr, nav_sat_fix_msg_ptr->header.stamp); tf2::Transform tf_gnss_antenna2base_link{}; tf2::fromMsg(tf_gnss_antenna2base_link_msg_ptr->transform, tf_gnss_antenna2base_link); From 5d175014c4972fead53a39ffb46d20fb8034f5e0 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Wed, 18 Oct 2023 17:22:45 +0900 Subject: [PATCH 016/202] feat(system_diagnostic_graph): change config file format (#5340) Signed-off-by: Takagi, Isamu --- system/system_diagnostic_graph/CMakeLists.txt | 8 +- system/system_diagnostic_graph/README.md | 38 ++- .../config/default.param.yaml | 2 + .../doc/overview.drawio.svg | 217 ++++++------- .../example/example.launch.xml | 4 +- .../example/example1.yaml | 41 --- .../example/example2.yaml | 32 -- .../example/example_0.yaml | 32 ++ .../example/example_1.yaml | 23 ++ .../example/example_2.yaml | 8 + .../example/example_diags.py | 64 ++++ .../example/publisher.py | 83 ----- .../src/core/config.cpp | 249 +++++++++++---- .../src/core/config.hpp | 90 ++++-- .../src/core/debug.cpp | 28 +- .../system_diagnostic_graph/src/core/expr.cpp | 284 ------------------ .../src/core/exprs.cpp | 216 +++++++++++++ .../src/core/{expr.hpp => exprs.hpp} | 46 ++- .../src/core/graph.cpp | 168 ++++++++--- .../src/core/graph.hpp | 27 +- .../src/core/modes.cpp | 75 +++++ .../src/core/{update.hpp => modes.hpp} | 45 ++- .../system_diagnostic_graph/src/core/node.cpp | 94 ------ .../system_diagnostic_graph/src/core/node.hpp | 84 ------ .../src/core/nodes.cpp | 157 ++++++++++ .../src/core/nodes.hpp | 114 +++++++ .../src/core/types.hpp | 7 +- .../src/core/update.cpp | 116 ------- system/system_diagnostic_graph/src/main.cpp | 35 ++- system/system_diagnostic_graph/src/main.hpp | 10 +- system/system_diagnostic_graph/src/tool.hpp | 1 - .../system_diagnostic_monitor/CMakeLists.txt | 7 - system/system_diagnostic_monitor/README.md | 1 - .../config/autoware.yaml | 74 ----- .../config/control.yaml | 10 - .../config/localization.yaml | 5 - .../system_diagnostic_monitor/config/map.yaml | 7 - .../config/perception.yaml | 7 - .../config/planning.yaml | 15 - .../config/system.yaml | 7 - .../config/vehicle.yaml | 10 - .../system_diagnostic_monitor.launch.xml | 6 - system/system_diagnostic_monitor/package.xml | 23 -- .../script/component_state_diagnostics.py | 79 ----- 44 files changed, 1299 insertions(+), 1350 deletions(-) delete mode 100644 system/system_diagnostic_graph/example/example1.yaml delete mode 100644 system/system_diagnostic_graph/example/example2.yaml create mode 100644 system/system_diagnostic_graph/example/example_0.yaml create mode 100644 system/system_diagnostic_graph/example/example_1.yaml create mode 100644 system/system_diagnostic_graph/example/example_2.yaml create mode 100755 system/system_diagnostic_graph/example/example_diags.py delete mode 100755 system/system_diagnostic_graph/example/publisher.py delete mode 100644 system/system_diagnostic_graph/src/core/expr.cpp create mode 100644 system/system_diagnostic_graph/src/core/exprs.cpp rename system/system_diagnostic_graph/src/core/{expr.hpp => exprs.hpp} (68%) create mode 100644 system/system_diagnostic_graph/src/core/modes.cpp rename system/system_diagnostic_graph/src/core/{update.hpp => modes.hpp} (53%) delete mode 100644 system/system_diagnostic_graph/src/core/node.cpp delete mode 100644 system/system_diagnostic_graph/src/core/node.hpp create mode 100644 system/system_diagnostic_graph/src/core/nodes.cpp create mode 100644 system/system_diagnostic_graph/src/core/nodes.hpp delete mode 100644 system/system_diagnostic_graph/src/core/update.cpp delete mode 100644 system/system_diagnostic_monitor/CMakeLists.txt delete mode 100644 system/system_diagnostic_monitor/README.md delete mode 100644 system/system_diagnostic_monitor/config/autoware.yaml delete mode 100644 system/system_diagnostic_monitor/config/control.yaml delete mode 100644 system/system_diagnostic_monitor/config/localization.yaml delete mode 100644 system/system_diagnostic_monitor/config/map.yaml delete mode 100644 system/system_diagnostic_monitor/config/perception.yaml delete mode 100644 system/system_diagnostic_monitor/config/planning.yaml delete mode 100644 system/system_diagnostic_monitor/config/system.yaml delete mode 100644 system/system_diagnostic_monitor/config/vehicle.yaml delete mode 100644 system/system_diagnostic_monitor/launch/system_diagnostic_monitor.launch.xml delete mode 100644 system/system_diagnostic_monitor/package.xml delete mode 100755 system/system_diagnostic_monitor/script/component_state_diagnostics.py diff --git a/system/system_diagnostic_graph/CMakeLists.txt b/system/system_diagnostic_graph/CMakeLists.txt index 54aebe6f37f73..81d8ba39b3d1b 100644 --- a/system/system_diagnostic_graph/CMakeLists.txt +++ b/system/system_diagnostic_graph/CMakeLists.txt @@ -5,13 +5,13 @@ find_package(autoware_cmake REQUIRED) autoware_package() ament_auto_add_executable(aggregator - src/main.cpp src/core/config.cpp src/core/debug.cpp src/core/graph.cpp - src/core/node.cpp - src/core/expr.cpp - src/core/update.cpp + src/core/nodes.cpp + src/core/exprs.cpp + src/core/modes.cpp + src/main.cpp ) ament_auto_add_executable(converter diff --git a/system/system_diagnostic_graph/README.md b/system/system_diagnostic_graph/README.md index c2c99938348e2..df22121a778fb 100644 --- a/system/system_diagnostic_graph/README.md +++ b/system/system_diagnostic_graph/README.md @@ -2,28 +2,42 @@ ## Overview -The system diagnostic graph node subscribes to diagnostic status and publishes aggregated diagnostic status. +The system diagnostic graph node subscribes to diagnostic array and publishes aggregated diagnostic graph. As shown in the diagram below, this node introduces extra diagnostic status for intermediate functional unit. Diagnostic status dependencies will be directed acyclic graph (DAG). ![overview](./doc/overview.drawio.svg) +## Operation mode availability + +For MRM, this node publishes the status of the top-level functional units in the dedicated message. +Therefore, the diagnostic graph must contain functional units with the following names. +This feature breaks the generality of the graph and may be changed to a plugin or another node in the future. + +- /autoware/operation/stop +- /autoware/operation/autonomous +- /autoware/operation/local +- /autoware/operation/remote +- /autoware/operation/emergency-stop +- /autoware/operation/comfortable-stop +- /autoware/operation/pull-over + ## Interface -| Interface Type | Interface Name | Data Type | Description | -| -------------- | --------------------------- | --------------------------------------- | ------------------ | -| subscription | `/diagnostics` | `diagnostic_msgs/msg/DiagnosticArray` | Input diagnostics. | -| publisher | `/diagnostics_graph/status` | `diagnostic_msgs/msg/DiagnosticArray` | Graph status. | -| publisher | `/diagnostics_graph/struct` | `tier4_system_msgs/msg/DiagnosticGraph` | Graph structure. | +| Interface Type | Interface Name | Data Type | Description | +| -------------- | ------------------------------------- | ------------------------------------------------- | ------------------ | +| subscription | `/diagnostics` | `diagnostic_msgs/msg/DiagnosticArray` | Diagnostics input. | +| publisher | `/diagnostics_graph` | `tier4_system_msgs/msg/DiagnosticGraph` | Diagnostics graph. | +| publisher | `/system/operation_mode/availability` | `tier4_system_msgs/msg/OperationModeAvailability` | mode availability. | ## Parameters -| Parameter Name | Data Type | Description | -| ------------------ | --------- | ------------------------------------------ | -| `graph_file` | `string` | Path of the config file. | -| `rate` | `double` | Rate of aggregation and topic publication. | -| `status_qos_depth` | `uint` | QoS depth of status topic. | -| `source_qos_depth` | `uint` | QoS depth of source topic. | +| Parameter Name | Data Type | Description | +| ----------------- | --------- | ------------------------------------------ | +| `graph_file` | `string` | Path of the config file. | +| `rate` | `double` | Rate of aggregation and topic publication. | +| `input_qos_depth` | `uint` | QoS depth of input array topic. | +| `graph_qos_depth` | `uint` | QoS depth of output graph topic. | ## Graph file format diff --git a/system/system_diagnostic_graph/config/default.param.yaml b/system/system_diagnostic_graph/config/default.param.yaml index f02247374b14e..9fd572c7926fa 100644 --- a/system/system_diagnostic_graph/config/default.param.yaml +++ b/system/system_diagnostic_graph/config/default.param.yaml @@ -1,5 +1,7 @@ /**: ros__parameters: + mode_availability: true + mode: psim rate: 1.0 input_qos_depth: 1000 graph_qos_depth: 1 diff --git a/system/system_diagnostic_graph/doc/overview.drawio.svg b/system/system_diagnostic_graph/doc/overview.drawio.svg index aa6be5a48b08e..e971c052dedc8 100644 --- a/system/system_diagnostic_graph/doc/overview.drawio.svg +++ b/system/system_diagnostic_graph/doc/overview.drawio.svg @@ -4,13 +4,13 @@ xmlns:xlink="http://www.w3.org/1999/xlink" version="1.1" width="921px" - height="561px" - viewBox="-0.5 -0.5 921 561" - content="<mxfile><diagram id="pC5EcGJeU-t8W7RoQB87" name="Page-1">3VtNc6M4EP01vpsPYfvoOJ7Z2sruTiVbtccpBRTQDtAuIcfx/vqVQBiQcGKXGdDkZGgakF4/tfpJeOZtsrevDO+SPyAi6cydR28z737mug5yFuJHWo6VBS1RZYgZjZRTY3ii/xFlnCvrnkak6DhygJTTXdcYQp6TkHdsmDE4dN1eIO2+dYdjYhieQpya1n9oxJPKunQXjf03QuOkfrMTrKorGa6dVU+KBEdwaJm87czbMABeHWVvG5JK8Gpcqvu+nLl6ahgjOb/kBtev7njF6V51TjhHFMc5FJyGxfdYhvB7wTHfF6rN/FgDwWCfR0Q+az7z7g4J5eRph0N59SDuE7aEZ6k4c8QhTmmci+OUvIi23b0SJl6A07Uyc5D+hbid5vFD6XOPhCXCRVK+Qj7D7J/qsnwaeWuZVH+/EsgIZ0fhoq76Cvpj9/TQBHJVRydpBREFyogVeeLTkxt8xYGC+Azc6AO4PwXCSw3hHoiXfg/EjjsExIGBIYnE6FWnwHgCMeQ43TbWuy7Kjc8DSMhKXP4lnB9VKsJ7Dl3kz6JWwJ6Fqh11fuCYxUS5eYoRso3vYstIijl97WagPqDKW9eM4WPLYQc050Xryd+koQmZp48KT8sb1/mLg6oFTchOXbksigtjoPwtQuHOH+j9+vG2UTIAww2KL02KO31ZxB+C4UtrGa5Y0GW4ZwXDkaPn/fcZHgTv+t/O8NUvFUW0tCKK/uq6KH7gf3MUa6haeeoLg7IFdmQqX0/UY2YqzzH6bw3HvZ5MtbCC4wHqhqyebC6dizX/2znu/lpRXNkRxcV1UfzA//YoemczFTwLeReKsAlFTrgQzBTyyRNXMO/i4bljJi7fXsojaxOXkYiCKxNXMDDlTbX9DQpJcyLEdoat4LkuJcblub1i2esRy2hwKXExUKYeXYt+5ZCBXBabZxAR66jkzsekksWqdGUVlVYGlTaQvYjO4+dyDi7kOt3UXNKn31G5VD/DQi759X6DFVyqW9Pi0jYjLM7Doy1EOpFkEiLZK118ewWoo88jEwtQ35Quj7Dn00+4OrdHXVzx7dUofo9GmTBJmjLgdzjK7bYftlRui2DKJGmvCPB7RIA/+I7ZxUCZIqAhkmUMGjcVLQ1g1n/eG5iIrvBuxwvO4AfZQApMWHLIJbVeaJpqpnpjOxQAEdaztZ3RKCp52Yd0NxYDgG1MeMgEu2+De4j9bX+SfaPeQJ1FcoSa5sMixHE0sKu8ou5q8L51kcvxryuONP+bi6Oaeu11XZrKUeLOn2XH9uWKV4jLH5xHkjsiaZGsJBHuKaM+zThFmoh1PHOcnj4qG3qgIns3v5BrjtPp6rO6NS0GP5XK1Y7aTN9BHbU2Q6b02TIGrIzDTvBjcnh0DdRTd5xqk8HRsVcCob5tGju+hNG/bPEW130Jo/nfPoOZ+kztTAY4k4TNn4tyesARZpPzXV8YHbXQRoEB1V+Pn3f+Pse8MepstLA3tyx7cosdS4d6xTX10iEylWnPVw87RiJqx2cPerXxM7eDZxKL+p8GFbjN/zW87f8=</diagram></mxfile>" + height="521px" + viewBox="-0.5 -0.5 921 521" + content="<mxfile><diagram id="pC5EcGJeU-t8W7RoQB87" name="Page-1">3VpNb6MwEP01ufMdckyTtntod1ftSnusXHDBrWEi43ywv37tYELAtE0UCqiXyDzGxn7zPB6PMrEXye6WoVV8DyGmE8sIdxN7ObEs3zXErwTyAvBMtwAiRsICMivgkfzDClT9ojUJcVYz5ACUk1UdDCBNccBrGGIMtnWzF6D1r65QhDXgMUBUR/+SkMdqWda0wn9gEsXll01vVrxJUGmsVpLFKITtEWRfT+wFA+BFK9ktMJXclbwU/W7eeXuYGMMpP6WD5RQ9Noiu1eKEcUhQlELGSZA9RdKDarI8LxlgsE5DLAcxJvbVNiYcP65QIN9uRQeBxTyh4skUTURJlIo2xS9iUlcbzMTIiM4VzEHaZ6I7SaO7vc3SFUiIsnj/CTmGvjC1Vjka3h1BaqG3GBLMWS5M1FtHcZ7XH7eVB2elW+Ij77kliJRqosPIFbGiobht59mdtfGc5RnHiWjACjPECaRPidgrAkAbRCh6JpTw/FuQ79fJ93XyfaeFfLML8i33E5F/R4Ydo1eKPY1DHIqYqR6B8RgiSBG9rtCrOsuVzR1Iyva8vGLOc3UAoDWHOvPvspbBmgVqHmVU5ohFWJnZShFyjh9yyzAV+3JTj/ttRO27zhlD+ZHBCkjKs6ORf0ugcplr1H1m+41ofZ69aBQzqFx2WMppXpxqG+WPcIVl3JHl/OGyXdJFAG9G8JYQbraFcKcLhfujVbhttCjcHoXCvWlDsd7HCp86H9pfrPCSqiOF3zDYz2AcGveMATVum9r6R6Nxu0Xj01FovKnZ0hWnRvGG/eUatzWNw3PGUSDcJe5cmIsrkUg1h5d6I2NpSwq/TurOeKXujlbqmnSNM6VudCx1PbNfQSZljkVin6BR6LyZtvSrcz2lk7JMIYH1hfeeL6DmQEMf1DimRg3DCXA8OC3Nu1yvtHjWxZHx3IjntBzupXe6i3gn60I/P0tdGAEkCUrD0Smk1zTR0aMuhQDRwVk5rHiQcDLeEojTUgJxOi+BnEyUfiS9Qi4LcW8j2mFNLfW7w3yNovnPpcaJWAqvLzzjDN7wAigwgaSQSpG9EEobUFmzDARBmLVULRMShnuFtjFd90UHZGt5oqmT3Va77KJ06cyG2LetjnqXyR6uAp/m7tMG10WAUZ0qui+9UphnXinMjq8UrqVtvUyW8IeOR83CUK9nmzve27LbdlseR/HTbxwhQxc/XT1vU8VPDyVSselztg/vKERscMFPvQEPYNfTqPr18H3PX015dn/nr6dTff9wPzr5fWW8nch9WP7lo9jY1f9m7Ov/</diagram></mxfile>" > - + @@ -20,243 +20,231 @@ >
- /diagnostics_graph_status + /diagnostics_graph
- /diagnostics_graph_status + /diagnostics_graph
- +
- /diagnostics + /system/operation_mode/availability
- /diagnostics + /system/operation_mode/availability
- - - +
-
+
- Top LiDAR + /diagnostics
- Top LiDAR + /diagnostics - - - - - + + +
- Front LiDAR + Top LiDAR
- Front LiDAR + Top LiDAR
- - - - - + + +
- Front obstacle detection + Front LiDAR
- Front obstacle detec... + Front LiDAR
- - - + + +
- Pose estimation + obstacle detection
- Pose estimation + obstacle detection
- - - + + +
- Autonomous mode + pose estimation
- Autonomous mode + pose estimation
- - - +
- Comfortable stop + autonomous
- Comfortable stop + autonomous
- - - +
- Emergncy stop + remote
- Emergncy stop + remote
- - - + + +
- Route + remote command
- Route + remote command
- - - +
- Joystick mode + local
- Joystick mode + local
- - - + + +
- Joystick + joystick command
- Joystick + joystick command
- +
@@ -265,73 +253,38 @@
- AND + AND - - - + + +
- Filter by use case and system state -
-
-
-
- Filter by use case and system state -
-
- - - - - - -
-
-
- Stop mode -
-
-
-
- Stop mode -
-
- - - - -
-
-
- Error report + stop
- Error report + stop
- - - + + +
@@ -340,16 +293,16 @@
- Front radar + Front radar - +
@@ -358,27 +311,25 @@
- OR + OR - - - +
- Front obstacle prediction + MRM
- Front obstacle predi... + MRM
diff --git a/system/system_diagnostic_graph/example/example.launch.xml b/system/system_diagnostic_graph/example/example.launch.xml index 461842f020ded..1456bfd5c6593 100644 --- a/system/system_diagnostic_graph/example/example.launch.xml +++ b/system/system_diagnostic_graph/example/example.launch.xml @@ -1,6 +1,6 @@ - + - + diff --git a/system/system_diagnostic_graph/example/example1.yaml b/system/system_diagnostic_graph/example/example1.yaml deleted file mode 100644 index 25053b5f7e12c..0000000000000 --- a/system/system_diagnostic_graph/example/example1.yaml +++ /dev/null @@ -1,41 +0,0 @@ -files: - - { package: system_diagnostic_graph, path: example/example2.yaml } - -nodes: - - name: /autoware/diagnostics - type: and - list: - - { type: unit, name: /autoware/operation/stop } - - { type: unit, name: /autoware/operation/autonomous } - - { type: unit, name: /autoware/operation/local } - - { type: unit, name: /autoware/operation/remote } - - { type: unit, name: /autoware/operation/emergency-stop } - - { type: unit, name: /autoware/operation/comfortable-stop } - - - name: /autoware/operation/stop - type: debug-ok - - - name: /autoware/operation/autonomous - type: and - list: - - { type: unit, name: /autoware/localization } - - { type: unit, name: /autoware/planning } - - { type: unit, name: /autoware/perception } - - - name: /autoware/operation/local - type: debug-ok - - - name: /autoware/operation/remote - type: and - list: - - { type: diag, hardware: test, name: /external/remote_command } - - - name: /autoware/operation/emergency-stop - type: debug-ok - - - name: /autoware/operation/comfortable-stop - type: and - list: - - { type: unit, name: /autoware/localization } - - { type: unit, name: /autoware/planning } - - { type: unit, name: /autoware/perception/front-obstacle-detection } diff --git a/system/system_diagnostic_graph/example/example2.yaml b/system/system_diagnostic_graph/example/example2.yaml deleted file mode 100644 index 2af09c0cb69a2..0000000000000 --- a/system/system_diagnostic_graph/example/example2.yaml +++ /dev/null @@ -1,32 +0,0 @@ -nodes: - - name: /autoware/localization - type: and - list: - - { type: diag, hardware: test, name: /sensing/lidars/top } - - - name: /autoware/planning - type: and - list: - - { type: unit, name: /autoware/planning/route } - - - name: /autoware/planning/route - type: and - list: - - { type: diag, hardware: test, name: /planning/route } - - - name: /autoware/perception - type: and - list: - - { type: unit, name: /autoware/perception/front-obstacle-detection } - - { type: unit, name: /autoware/perception/front-obstacle-prediction } - - - name: /autoware/perception/front-obstacle-detection - type: or - list: - - { type: diag, hardware: test, name: /sensing/lidars/front } - - { type: diag, hardware: test, name: /sensing/radars/front } - - - name: /autoware/perception/front-obstacle-prediction - type: and - list: - - { type: diag, hardware: test, name: /sensing/lidars/front } diff --git a/system/system_diagnostic_graph/example/example_0.yaml b/system/system_diagnostic_graph/example/example_0.yaml new file mode 100644 index 0000000000000..0ee6e59c8e121 --- /dev/null +++ b/system/system_diagnostic_graph/example/example_0.yaml @@ -0,0 +1,32 @@ +files: + - { package: system_diagnostic_graph, path: example/example_1.yaml } + - { package: system_diagnostic_graph, path: example/example_2.yaml } + +nodes: + - path: /autoware/modes/stop + type: debug-ok + + - path: /autoware/modes/autonomous + type: and + list: + - { type: link, path: /functions/pose_estimation } + - { type: link, path: /functions/obstacle_detection } + + - path: /autoware/modes/local + type: and + list: + - { type: link, path: /external/joystick_command } + + - path: /autoware/modes/remote + type: and + list: + - { type: link, path: /external/remote_command } + + - path: /autoware/modes/emergency-stop + type: debug-ok + + - path: /autoware/modes/comfortable-stop + type: debug-ok + + - path: /autoware/modes/pull-over + type: debug-ok diff --git a/system/system_diagnostic_graph/example/example_1.yaml b/system/system_diagnostic_graph/example/example_1.yaml new file mode 100644 index 0000000000000..5ba93ec3059e4 --- /dev/null +++ b/system/system_diagnostic_graph/example/example_1.yaml @@ -0,0 +1,23 @@ +nodes: + - path: /functions/pose_estimation + type: and + list: + - { type: link, path: /sensing/lidars/top } + + - path: /functions/obstacle_detection + type: or + list: + - { type: link, path: /sensing/lidars/front } + - { type: link, path: /sensing/radars/front } + + - path: /sensing/lidars/top + type: diag + name: "lidar_driver/top: status" + + - path: /sensing/lidars/front + type: diag + name: "lidar_driver/front: status" + + - path: /sensing/radars/front + type: diag + name: "radar_driver/front: status" diff --git a/system/system_diagnostic_graph/example/example_2.yaml b/system/system_diagnostic_graph/example/example_2.yaml new file mode 100644 index 0000000000000..f61f4accbfec8 --- /dev/null +++ b/system/system_diagnostic_graph/example/example_2.yaml @@ -0,0 +1,8 @@ +nodes: + - path: /external/joystick_command + type: diag + name: "external_command_checker: joystick_command" + + - path: /external/remote_command + type: diag + name: "external_command_checker: remote_command" diff --git a/system/system_diagnostic_graph/example/example_diags.py b/system/system_diagnostic_graph/example/example_diags.py new file mode 100755 index 0000000000000..52d6189a63f30 --- /dev/null +++ b/system/system_diagnostic_graph/example/example_diags.py @@ -0,0 +1,64 @@ +#!/usr/bin/env python3 + +# Copyright 2023 The Autoware Contributors +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from diagnostic_msgs.msg import DiagnosticArray +from diagnostic_msgs.msg import DiagnosticStatus +import rclpy +import rclpy.node +import rclpy.qos + + +class DummyDiagnostics(rclpy.node.Node): + def __init__(self, names): + super().__init__("dummy_diagnostics") + qos = rclpy.qos.qos_profile_system_default + self.diags = self.create_publisher(DiagnosticArray, "/diagnostics", qos) + self.timer = self.create_timer(0.5, self.on_timer) + self.count = 0 + self.array = [self.create_status(name) for name in names] + + def on_timer(self): + error_index = int(self.count / 10) + for index, status in enumerate(self.array, 1): + if index == error_index: + status.level = DiagnosticStatus.ERROR + status.message = "ERROR" + else: + status.level = DiagnosticStatus.OK + status.message = "OK" + + diagnostics = DiagnosticArray() + diagnostics.header.stamp = self.get_clock().now().to_msg() + diagnostics.status = self.array + self.count = (self.count + 1) % 60 + self.diags.publish(diagnostics) + + @staticmethod + def create_status(name: str): + return DiagnosticStatus(name=name, hardware_id="example") + + +if __name__ == "__main__": + diags = [ + "lidar_driver/top: status", + "lidar_driver/front: status", + "radar_driver/front: status", + "external_command_checker: joystick_command", + "external_command_checker: remote_command", + ] + rclpy.init() + rclpy.spin(DummyDiagnostics(diags)) + rclpy.shutdown() diff --git a/system/system_diagnostic_graph/example/publisher.py b/system/system_diagnostic_graph/example/publisher.py deleted file mode 100755 index 2e73237284508..0000000000000 --- a/system/system_diagnostic_graph/example/publisher.py +++ /dev/null @@ -1,83 +0,0 @@ -#!/usr/bin/env python3 - -# Copyright 2023 The Autoware Contributors -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -import argparse - -from diagnostic_msgs.msg import DiagnosticArray -from diagnostic_msgs.msg import DiagnosticStatus -import rclpy -import rclpy.node -import rclpy.qos - - -class DummyDiagnostics(rclpy.node.Node): - def __init__(self, array): - super().__init__("dummy_diagnostics") - qos = rclpy.qos.qos_profile_system_default - self.diags = self.create_publisher(DiagnosticArray, "/diagnostics", qos) - self.timer = self.create_timer(0.5, self.on_timer) - self.array = [self.create_status(*data) for data in array] - - def on_timer(self): - diagnostics = DiagnosticArray() - diagnostics.header.stamp = self.get_clock().now().to_msg() - diagnostics.status = self.array - self.diags.publish(diagnostics) - - @staticmethod - def create_status(name: str, level: int): - return DiagnosticStatus(level=level, name=name, message="OK", hardware_id="test") - - -if __name__ == "__main__": - data = { - "ok": [ - ("/sensing/lidars/top", DiagnosticStatus.OK), - ("/sensing/lidars/front", DiagnosticStatus.OK), - ("/sensing/radars/front", DiagnosticStatus.OK), - ("/planning/route", DiagnosticStatus.OK), - ("/external/remote_command", DiagnosticStatus.OK), - ], - "front-lidar": [ - ("/sensing/lidars/top", DiagnosticStatus.OK), - ("/sensing/lidars/front", DiagnosticStatus.ERROR), - ("/sensing/radars/front", DiagnosticStatus.OK), - ("/planning/route", DiagnosticStatus.OK), - ("/external/remote_command", DiagnosticStatus.OK), - ], - "front-radar": [ - ("/sensing/lidars/top", DiagnosticStatus.OK), - ("/sensing/lidars/front", DiagnosticStatus.OK), - ("/sensing/radars/front", DiagnosticStatus.ERROR), - ("/planning/route", DiagnosticStatus.OK), - ("/external/remote_command", DiagnosticStatus.OK), - ], - "front": [ - ("/sensing/lidars/top", DiagnosticStatus.OK), - ("/sensing/lidars/front", DiagnosticStatus.ERROR), - ("/sensing/radars/front", DiagnosticStatus.ERROR), - ("/planning/route", DiagnosticStatus.OK), - ("/external/remote_command", DiagnosticStatus.OK), - ], - } - - parser = argparse.ArgumentParser() - parser.add_argument("--data", default="ok") - args = parser.parse_args() - - rclpy.init() - rclpy.spin(DummyDiagnostics(data[args.data])) - rclpy.shutdown() diff --git a/system/system_diagnostic_graph/src/core/config.cpp b/system/system_diagnostic_graph/src/core/config.cpp index b33a7deb66fb6..305860af32840 100644 --- a/system/system_diagnostic_graph/src/core/config.cpp +++ b/system/system_diagnostic_graph/src/core/config.cpp @@ -17,106 +17,245 @@ #include #include -#include #include #include +#include + +// DEBUG +#include namespace system_diagnostic_graph { -ConfigError create_error(const FileConfig & config, const std::string & message) +ErrorMarker::ErrorMarker(const std::string & file) +{ + file_ = file; +} + +std::string ErrorMarker::str() const +{ + if (type_.empty()) { + return file_; + } + + std::string result = type_; + for (const auto & index : indices_) { + result += "-" + std::to_string(index); + } + return result + " in " + file_; +} + +ErrorMarker ErrorMarker::type(const std::string & type) const { - const std::string marker = config ? "File:" + config->path : "Parameter"; - return ConfigError(message + " (" + marker + ")"); + ErrorMarker mark = *this; + mark.type_ = type; + return mark; } -ConfigError create_error(const NodeConfig & config, const std::string & message) +ErrorMarker ErrorMarker::index(size_t index) const { - const std::string marker = "File:" + config->path + ", Node:" + config->name; - return ConfigError(message + " (" + marker + ")"); + ErrorMarker mark = *this; + mark.indices_.push_back(index); + return mark; } -NodeConfig parse_config_node(YAML::Node yaml, const FileConfig & scope) +ConfigObject::ConfigObject(const ErrorMarker & mark, YAML::Node yaml, const std::string & type) { if (!yaml.IsMap()) { - throw create_error(scope, "node object is not a dict"); + throw create_error(mark, type + " is not a dict type"); } - if (!yaml["name"]) { - throw create_error(scope, "node object has no 'name' field"); + for (const auto & kv : yaml) { + dict_[kv.first.as()] = kv.second; } + mark_ = mark; + type_ = type; +} - const auto config = std::make_shared(); - config->path = scope->path; - config->name = take(yaml, "name"); - config->yaml = yaml; - return config; +ErrorMarker ConfigObject::mark() const +{ + return mark_; } -FileConfig parse_config_path(YAML::Node yaml, const FileConfig & scope) +std::optional ConfigObject::take_yaml(const std::string & name) { - if (!yaml.IsMap()) { - throw create_error(scope, "file object is not a dict"); + if (!dict_.count(name)) { + return std::nullopt; } - if (!yaml["package"]) { - throw create_error(scope, "file object has no 'package' field"); + const auto yaml = dict_.at(name); + dict_.erase(name); + return yaml; +} + +std::string ConfigObject::take_text(const std::string & name) +{ + if (!dict_.count(name)) { + throw create_error(mark_, "object has no '" + name + "' field"); } - if (!yaml["path"]) { - throw create_error(scope, "file object has no 'path' field"); + + const auto yaml = dict_.at(name); + dict_.erase(name); + return yaml.as(); +} + +std::string ConfigObject::take_text(const std::string & name, const std::string & fail) +{ + if (!dict_.count(name)) { + return fail; } - const auto package_name = yaml["package"].as(); - const auto package_path = ament_index_cpp::get_package_share_directory(package_name); - return parse_config_path(package_path + "/" + yaml["path"].as(), scope); + const auto yaml = dict_.at(name); + dict_.erase(name); + return yaml.as(); } -FileConfig parse_config_path(const std::string & path, const FileConfig & scope) +std::vector ConfigObject::take_list(const std::string & name) { - if (!std::filesystem::exists(path)) { - throw create_error(scope, "config file '" + path + "' does not exist"); + if (!dict_.count(name)) { + return std::vector(); } - return parse_config_file(path); + + const auto yaml = dict_.at(name); + dict_.erase(name); + + if (!yaml.IsSequence()) { + throw ConfigError("the '" + name + "' field is not a list type"); + } + return std::vector(yaml.begin(), yaml.end()); +} + +bool ConfigFilter::check(const std::string & mode) const +{ + if (!excludes.empty() && excludes.count(mode) != 0) return false; + if (!includes.empty() && includes.count(mode) == 0) return false; + return true; } -FileConfig parse_config_file(const std::string & path) +ConfigError create_error(const ErrorMarker & mark, const std::string & message) { - const auto config = std::make_shared(); - config->path = path; + (void)mark; + return ConfigError(message); +} - const auto yaml = YAML::LoadFile(path); - if (!yaml.IsMap()) { - throw create_error(config, "config file is not a dict"); +ConfigFilter parse_mode_filter(const ErrorMarker & mark, std::optional yaml) +{ + std::unordered_set excludes; + std::unordered_set includes; + if (yaml) { + ConfigObject dict(mark, yaml.value(), "mode filter"); + + for (const auto & mode : dict.take_list("except")) { + excludes.emplace(mode.as()); + } + for (const auto & mode : dict.take_list("only")) { + includes.emplace(mode.as()); + } } + return ConfigFilter{excludes, includes}; +} + +FileConfig parse_file_config(const ErrorMarker & mark, YAML::Node yaml) +{ + ConfigObject dict(mark, yaml, "file object"); + const auto relative_path = dict.take_text("path"); + const auto package_name = dict.take_text("package"); + const auto package_path = ament_index_cpp::get_package_share_directory(package_name); + return FileConfig{mark, package_path + "/" + relative_path}; +} + +NodeConfig parse_node_config(const ErrorMarker & mark, YAML::Node yaml) +{ + ConfigObject dict(mark, yaml, "node object"); + const auto path = dict.take_text("path"); + const auto mode = parse_mode_filter(dict.mark(), dict.take_yaml("mode")); + return NodeConfig{path, mode, dict}; +} + +ExprConfig parse_expr_config(const ErrorMarker & mark, YAML::Node yaml) +{ + ConfigObject dict(mark, yaml, "expr object"); + return parse_expr_config(dict); +} + +ExprConfig parse_expr_config(ConfigObject & dict) +{ + const auto type = dict.take_text("type"); + const auto mode = parse_mode_filter(dict.mark(), dict.take_yaml("mode")); + return ExprConfig{type, mode, dict}; +} - const auto files = yaml["files"] ? yaml["files"] : YAML::Node(YAML::NodeType::Sequence); - if (!files.IsSequence()) { - throw create_error(config, "files section is not a list"); +void dump(const ConfigFile & config) +{ + std::cout << "=================================================================" << std::endl; + std::cout << config.mark.str() << std::endl; + for (const auto & file : config.files) { + std::cout << " - f: " << file.path << " (" << file.mark.str() << ")" << std::endl; + } + for (const auto & unit : config.units) { + std::cout << " - u: " << unit.path << " (" << unit.dict.mark().str() << ")" << std::endl; } - for (const auto file : files) { - config->files.push_back(parse_config_path(file, config)); + for (const auto & diag : config.diags) { + std::cout << " - d: " << diag.path << " (" << diag.dict.mark().str() << ")" << std::endl; } +} - const auto nodes = yaml["nodes"] ? yaml["nodes"] : YAML::Node(YAML::NodeType::Sequence); - if (!nodes.IsSequence()) { - throw create_error(config, "nodes section is not a list"); +template +auto apply(const ErrorMarker & mark, F & func, const std::vector & list) +{ + std::vector result; + for (size_t i = 0; i < list.size(); ++i) { + result.push_back(func(mark.index(i), list[i])); } - for (const auto node : nodes) { - config->nodes.push_back(parse_config_node(node, config)); + return result; +} + +ConfigFile load_config_file(const FileConfig & file) +{ + if (!std::filesystem::exists(file.path)) { + throw create_error(file.mark, "config file '" + file.path + "' does not exist"); } + const auto yaml = YAML::LoadFile(file.path); + const auto mark = ErrorMarker(file.path); + auto dict = ConfigObject(mark, yaml, "config file"); + + std::vector units; + std::vector diags; + for (const auto & node : dict.take_list("nodes")) { + const auto type = node["type"].as(); + if (type == "diag") { + diags.push_back(node); + } else { + units.push_back(node); + } + } + + ConfigFile config(mark); + config.files = apply(mark.type("file"), parse_file_config, dict.take_list("files")); + config.units = apply(mark.type("unit"), parse_node_config, units); + config.diags = apply(mark.type("diag"), parse_node_config, diags); return config; } -void walk_config_tree(const FileConfig & config, std::vector & nodes) +ConfigFile load_config_root(const std::string & path) { - nodes.insert(nodes.end(), config->nodes.begin(), config->nodes.end()); - for (const auto & file : config->files) walk_config_tree(file, nodes); -} + const auto mark = ErrorMarker("root file"); + std::vector configs; + configs.push_back(load_config_file(FileConfig{mark, path})); -std::vector load_config_file(const std::string & path) -{ - std::vector nodes; - walk_config_tree(parse_config_path(path, nullptr), nodes); - return nodes; + // Use an index because updating the vector invalidates the iterator. + for (size_t i = 0; i < configs.size(); ++i) { + for (const auto & file : configs[i].files) { + configs.push_back(load_config_file(file)); + } + } + + ConfigFile result(mark); + for (const auto & config : configs) { + result.files.insert(result.files.end(), config.files.begin(), config.files.end()); + result.units.insert(result.units.end(), config.units.begin(), config.units.end()); + result.diags.insert(result.diags.end(), config.diags.begin(), config.diags.end()); + } + return result; } } // namespace system_diagnostic_graph diff --git a/system/system_diagnostic_graph/src/core/config.hpp b/system/system_diagnostic_graph/src/core/config.hpp index 6393cb906b119..4d679ef575944 100644 --- a/system/system_diagnostic_graph/src/core/config.hpp +++ b/system/system_diagnostic_graph/src/core/config.hpp @@ -18,8 +18,11 @@ #include #include +#include #include #include +#include +#include #include namespace system_diagnostic_graph @@ -30,38 +33,79 @@ struct ConfigError : public std::runtime_error using runtime_error::runtime_error; }; -struct NodeConfig_ +class ErrorMarker +{ +public: + explicit ErrorMarker(const std::string & file = ""); + std::string str() const; + ErrorMarker type(const std::string & type) const; + ErrorMarker index(size_t index) const; + +private: + std::string file_; + std::string type_; + std::vector indices_; +}; + +class ConfigObject +{ +public: + ConfigObject(const ErrorMarker & mark, YAML::Node yaml, const std::string & type); + ErrorMarker mark() const; + std::optional take_yaml(const std::string & name); + std::string take_text(const std::string & name); + std::string take_text(const std::string & name, const std::string & fail); + std::vector take_list(const std::string & name); + +private: + ErrorMarker mark_; + std::string type_; + std::unordered_map dict_; +}; + +struct ConfigFilter +{ + bool check(const std::string & mode) const; + std::unordered_set excludes; + std::unordered_set includes; +}; + +struct ExprConfig +{ + std::string type; + ConfigFilter mode; + ConfigObject dict; +}; + +struct NodeConfig { std::string path; - std::string name; - YAML::Node yaml; + ConfigFilter mode; + ConfigObject dict; }; -struct FileConfig_ +struct FileConfig { + ErrorMarker mark; std::string path; - std::vector> files; - std::vector> nodes; }; -template -T take(YAML::Node yaml, const std::string & field) +struct ConfigFile { - const auto result = yaml[field].as(); - yaml.remove(field); - return result; -} - -using NodeConfig = std::shared_ptr; -using FileConfig = std::shared_ptr; -ConfigError create_error(const FileConfig & config, const std::string & message); -ConfigError create_error(const NodeConfig & config, const std::string & message); -std::vector load_config_file(const std::string & path); - -NodeConfig parse_config_node(YAML::Node yaml, const FileConfig & scope); -FileConfig parse_config_path(YAML::Node yaml, const FileConfig & scope); -FileConfig parse_config_path(const std::string & path, const FileConfig & scope); -FileConfig parse_config_file(const std::string & path); + explicit ConfigFile(const ErrorMarker & mark) : mark(mark) {} + ErrorMarker mark; + std::vector files; + std::vector units; + std::vector diags; +}; + +using ConfigDict = std::unordered_map; + +ConfigError create_error(const ErrorMarker & mark, const std::string & message); +ConfigFile load_config_root(const std::string & path); + +ExprConfig parse_expr_config(const ErrorMarker & mark, YAML::Node yaml); +ExprConfig parse_expr_config(ConfigObject & dict); } // namespace system_diagnostic_graph diff --git a/system/system_diagnostic_graph/src/core/debug.cpp b/system/system_diagnostic_graph/src/core/debug.cpp index 337be8c74aded..ed696573521a7 100644 --- a/system/system_diagnostic_graph/src/core/debug.cpp +++ b/system/system_diagnostic_graph/src/core/debug.cpp @@ -14,9 +14,9 @@ #include "debug.hpp" -#include "node.hpp" +#include "graph.hpp" +#include "nodes.hpp" #include "types.hpp" -#include "update.hpp" #include #include @@ -32,10 +32,10 @@ const std::unordered_map level_names = { {DiagnosticStatus::ERROR, "ERROR"}, {DiagnosticStatus::STALE, "STALE"}}; -void DiagGraph::debug() +void Graph::debug() { std::vector lines; - for (const auto & node : graph_.nodes()) { + for (const auto & node : nodes_) { lines.push_back(node->debug()); } @@ -59,17 +59,23 @@ void DiagGraph::debug() DiagDebugData UnitNode::debug() const { - const auto & level = node_.status.level; - const auto & name = node_.status.name; - return DiagDebugData{std::to_string(index()), "unit", name, "-----", level_names.at(level)}; + const auto level_name = level_names.at(level()); + const auto index_name = std::to_string(index()); + return {"unit", index_name, level_name, path_, "-----"}; } DiagDebugData DiagNode::debug() const { - const auto & level = node_.status.level; - const auto & name = node_.status.name; - const auto & hardware = node_.status.hardware_id; - return DiagDebugData{std::to_string(index()), "diag", name, hardware, level_names.at(level)}; + const auto level_name = level_names.at(level()); + const auto index_name = std::to_string(index()); + return {"diag", index_name, level_name, path_, name_}; +} + +DiagDebugData UnknownNode::debug() const +{ + const auto level_name = level_names.at(level()); + const auto index_name = std::to_string(index()); + return {"test", index_name, level_name, path_, "-----"}; } } // namespace system_diagnostic_graph diff --git a/system/system_diagnostic_graph/src/core/expr.cpp b/system/system_diagnostic_graph/src/core/expr.cpp deleted file mode 100644 index dc7ebcf8dd859..0000000000000 --- a/system/system_diagnostic_graph/src/core/expr.cpp +++ /dev/null @@ -1,284 +0,0 @@ -// Copyright 2023 The Autoware Contributors -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "expr.hpp" - -#include "config.hpp" -#include "graph.hpp" -#include "node.hpp" - -#include -#include -#include -#include - -// -#include - -namespace system_diagnostic_graph -{ - -using LinkStatus = std::vector>; - -void extend(LinkStatus & a, const LinkStatus & b) -{ - a.insert(a.end(), b.begin(), b.end()); -} - -void extend_false(LinkStatus & a, const LinkStatus & b) -{ - for (const auto & p : b) { - a.push_back(std::make_pair(p.first, false)); - } -} - -std::unique_ptr BaseExpr::create(Graph & graph, YAML::Node yaml) -{ - if (!yaml.IsMap()) { - throw ConfigError("expr object is not a dict"); - } - if (!yaml["type"]) { - throw ConfigError("expr object has no 'type' field"); - } - - const auto type = take(yaml, "type"); - - if (type == "unit") { - return std::make_unique(graph, yaml); - } - if (type == "diag") { - return std::make_unique(graph, yaml); - } - if (type == "and") { - return std::make_unique(graph, yaml); - } - if (type == "or") { - return std::make_unique(graph, yaml); - } - if (type == "if") { - return std::make_unique(graph, yaml); - } - if (type == "debug-ok") { - return std::make_unique(DiagnosticStatus::OK); - } - if (type == "debug-warn") { - return std::make_unique(DiagnosticStatus::WARN); - } - if (type == "debug-error") { - return std::make_unique(DiagnosticStatus::ERROR); - } - if (type == "debug-stale") { - return std::make_unique(DiagnosticStatus::STALE); - } - throw ConfigError("unknown expr type: " + type); -} - -ConstExpr::ConstExpr(const DiagnosticLevel level) -{ - level_ = level; -} - -ExprStatus ConstExpr::eval() const -{ - ExprStatus status; - status.level = level_; - return status; -} - -std::vector ConstExpr::get_dependency() const -{ - return {}; -} - -UnitExpr::UnitExpr(Graph & graph, YAML::Node yaml) -{ - if (!yaml["name"]) { - throw ConfigError("unit object has no 'name' field"); - } - const auto name = take(yaml, "name"); - node_ = graph.find_unit(name); - if (!node_) { - throw ConfigError("unit node '" + name + "' does not exist"); - } -} - -ExprStatus UnitExpr::eval() const -{ - ExprStatus status; - status.level = node_->level(); - status.links.push_back(std::make_pair(node_, true)); - return status; -} - -std::vector UnitExpr::get_dependency() const -{ - return {node_}; -} - -DiagExpr::DiagExpr(Graph & graph, YAML::Node yaml) -{ - if (!yaml["name"]) { - throw ConfigError("diag object has no 'name' field"); - } - const auto name = yaml["name"].as(); - const auto hardware = yaml["hardware"].as(""); - node_ = graph.find_diag(name, hardware); - if (!node_) { - node_ = graph.make_diag(name, hardware); - } -} - -ExprStatus DiagExpr::eval() const -{ - ExprStatus status; - status.level = node_->level(); - status.links.push_back(std::make_pair(node_, true)); - return status; -} - -std::vector DiagExpr::get_dependency() const -{ - return {node_}; -} - -AndExpr::AndExpr(Graph & graph, YAML::Node yaml) -{ - if (!yaml["list"]) { - throw ConfigError("expr object has no 'list' field"); - } - if (!yaml["list"].IsSequence()) { - throw ConfigError("list field is not a list"); - } - - for (const auto & node : yaml["list"]) { - list_.push_back(BaseExpr::create(graph, node)); - } -} - -ExprStatus AndExpr::eval() const -{ - std::vector results; - for (const auto & expr : list_) { - results.push_back(expr->eval()); - } - std::vector levels; - for (const auto & result : results) { - levels.push_back(result.level); - } - ExprStatus status; - for (const auto & result : results) { - extend(status.links, result.links); - } - const auto level = *std::max_element(levels.begin(), levels.end()); - status.level = std::min(level, DiagnosticStatus::ERROR); - return status; -} - -std::vector AndExpr::get_dependency() const -{ - std::vector depends; - for (const auto & expr : list_) { - const auto nodes = expr->get_dependency(); - depends.insert(depends.end(), nodes.begin(), nodes.end()); - } - return depends; -} - -OrExpr::OrExpr(Graph & graph, YAML::Node yaml) -{ - if (!yaml["list"]) { - throw ConfigError("expr object has no 'list' field"); - } - if (!yaml["list"].IsSequence()) { - throw ConfigError("list field is not a list"); - } - - for (const auto & node : yaml["list"]) { - list_.push_back(BaseExpr::create(graph, node)); - } -} - -ExprStatus OrExpr::eval() const -{ - std::vector results; - for (const auto & expr : list_) { - results.push_back(expr->eval()); - } - std::vector levels; - for (const auto & result : results) { - levels.push_back(result.level); - } - ExprStatus status; - for (const auto & result : results) { - extend(status.links, result.links); - } - const auto level = *std::min_element(levels.begin(), levels.end()); - status.level = std::min(level, DiagnosticStatus::ERROR); - return status; -} - -std::vector OrExpr::get_dependency() const -{ - std::vector depends; - for (const auto & expr : list_) { - const auto nodes = expr->get_dependency(); - depends.insert(depends.end(), nodes.begin(), nodes.end()); - } - return depends; -} - -IfExpr::IfExpr(Graph & graph, YAML::Node yaml) -{ - if (!yaml["cond"]) { - throw ConfigError("expr object has no 'cond' field"); - } - if (!yaml["then"]) { - throw ConfigError("expr object has no 'then' field"); - } - cond_ = BaseExpr::create(graph, yaml["cond"]); - then_ = BaseExpr::create(graph, yaml["then"]); -} - -ExprStatus IfExpr::eval() const -{ - const auto cond = cond_->eval(); - const auto then = then_->eval(); - ExprStatus status; - if (cond.level == DiagnosticStatus::OK) { - status.level = std::min(then.level, DiagnosticStatus::ERROR); - extend(status.links, cond.links); - extend(status.links, then.links); - } else { - status.level = std::min(cond.level, DiagnosticStatus::ERROR); - extend(status.links, cond.links); - extend_false(status.links, then.links); - } - return status; -} - -std::vector IfExpr::get_dependency() const -{ - std::vector depends; - { - const auto nodes = cond_->get_dependency(); - depends.insert(depends.end(), nodes.begin(), nodes.end()); - } - { - const auto nodes = then_->get_dependency(); - depends.insert(depends.end(), nodes.begin(), nodes.end()); - } - return depends; -} - -} // namespace system_diagnostic_graph diff --git a/system/system_diagnostic_graph/src/core/exprs.cpp b/system/system_diagnostic_graph/src/core/exprs.cpp new file mode 100644 index 0000000000000..22281f939cad2 --- /dev/null +++ b/system/system_diagnostic_graph/src/core/exprs.cpp @@ -0,0 +1,216 @@ +// Copyright 2023 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "exprs.hpp" + +#include "nodes.hpp" + +#include +#include +#include +#include +#include + +// DEBUG +#include + +namespace system_diagnostic_graph +{ + +using LinkStatus = std::vector>; + +void extend(LinkStatus & a, const LinkStatus & b) +{ + a.insert(a.end(), b.begin(), b.end()); +} + +void extend_false(LinkStatus & a, const LinkStatus & b) +{ + for (const auto & p : b) { + a.push_back(std::make_pair(p.first, false)); + } +} + +auto create_expr_list(ExprInit & exprs, ConfigObject & config) +{ + std::vector> result; + const auto list = config.take_list("list"); + for (size_t i = 0; i < list.size(); ++i) { + auto dict = parse_expr_config(config.mark().index(i), list[i]); + auto expr = exprs.create(dict); + if (expr) { + result.push_back(std::move(expr)); + } + } + return result; +} + +ConstExpr::ConstExpr(const DiagnosticLevel level) +{ + level_ = level; +} + +ExprStatus ConstExpr::eval() const +{ + ExprStatus status; + status.level = level_; + return status; +} + +std::vector ConstExpr::get_dependency() const +{ + return {}; +} + +LinkExpr::LinkExpr(ExprInit & exprs, ConfigObject & config) +{ + // TODO(Takagi, Isamu): remove + (void)config; + (void)exprs; +} + +void LinkExpr::init(ConfigObject & config, std::unordered_map nodes) +{ + const auto path = config.take_text("path"); + if (!nodes.count(path)) { + throw ConfigError("node path '" + path + "' does not exist"); + } + node_ = nodes.at(path); +} + +ExprStatus LinkExpr::eval() const +{ + ExprStatus status; + status.level = node_->level(); + status.links.push_back(std::make_pair(node_, true)); + return status; +} + +std::vector LinkExpr::get_dependency() const +{ + return {node_}; +} + +AndExpr::AndExpr(ExprInit & exprs, ConfigObject & config, bool short_circuit) +{ + list_ = create_expr_list(exprs, config); + short_circuit_ = short_circuit; +} + +ExprStatus AndExpr::eval() const +{ + if (list_.empty()) { + ExprStatus status; + status.level = DiagnosticStatus::OK; + return status; + } + + ExprStatus status; + status.level = DiagnosticStatus::OK; + for (const auto & expr : list_) { + const auto result = expr->eval(); + status.level = std::max(status.level, result.level); + extend(status.links, result.links); + if (short_circuit_ && status.level != DiagnosticStatus::OK) { + break; + } + } + status.level = std::min(status.level, DiagnosticStatus::ERROR); + return status; +} + +std::vector AndExpr::get_dependency() const +{ + std::vector depends; + for (const auto & expr : list_) { + const auto nodes = expr->get_dependency(); + depends.insert(depends.end(), nodes.begin(), nodes.end()); + } + return depends; +} + +OrExpr::OrExpr(ExprInit & exprs, ConfigObject & config) +{ + list_ = create_expr_list(exprs, config); +} + +ExprStatus OrExpr::eval() const +{ + if (list_.empty()) { + ExprStatus status; + status.level = DiagnosticStatus::OK; + return status; + } + + ExprStatus status; + status.level = DiagnosticStatus::ERROR; + for (const auto & expr : list_) { + const auto result = expr->eval(); + status.level = std::min(status.level, result.level); + extend(status.links, result.links); + } + status.level = std::min(status.level, DiagnosticStatus::ERROR); + return status; +} + +std::vector OrExpr::get_dependency() const +{ + std::vector depends; + for (const auto & expr : list_) { + const auto nodes = expr->get_dependency(); + depends.insert(depends.end(), nodes.begin(), nodes.end()); + } + return depends; +} + +ExprInit::ExprInit(const std::string & mode) +{ + mode_ = mode; +} + +std::unique_ptr ExprInit::create(ExprConfig config) +{ + if (!config.mode.check(mode_)) { + return nullptr; + } + if (config.type == "link") { + auto expr = std::make_unique(*this, config.dict); + links_.push_back(std::make_pair(expr.get(), config.dict)); + return expr; + } + if (config.type == "and") { + return std::make_unique(*this, config.dict, false); + } + if (config.type == "short-circuit-and") { + return std::make_unique(*this, config.dict, true); + } + if (config.type == "or") { + return std::make_unique(*this, config.dict); + } + if (config.type == "debug-ok") { + return std::make_unique(DiagnosticStatus::OK); + } + if (config.type == "debug-warn") { + return std::make_unique(DiagnosticStatus::WARN); + } + if (config.type == "debug-error") { + return std::make_unique(DiagnosticStatus::ERROR); + } + if (config.type == "debug-stale") { + return std::make_unique(DiagnosticStatus::STALE); + } + throw ConfigError("unknown expr type: " + config.type + " " + config.dict.mark().str()); +} + +} // namespace system_diagnostic_graph diff --git a/system/system_diagnostic_graph/src/core/expr.hpp b/system/system_diagnostic_graph/src/core/exprs.hpp similarity index 68% rename from system/system_diagnostic_graph/src/core/expr.hpp rename to system/system_diagnostic_graph/src/core/exprs.hpp index 541841582180a..f582e019d5691 100644 --- a/system/system_diagnostic_graph/src/core/expr.hpp +++ b/system/system_diagnostic_graph/src/core/exprs.hpp @@ -12,15 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef CORE__EXPR_HPP_ -#define CORE__EXPR_HPP_ +#ifndef CORE__EXPRS_HPP_ +#define CORE__EXPRS_HPP_ +#include "config.hpp" #include "types.hpp" -#include - #include #include +#include #include #include @@ -36,7 +36,6 @@ struct ExprStatus class BaseExpr { public: - static std::unique_ptr create(Graph & graph, YAML::Node yaml); virtual ~BaseExpr() = default; virtual ExprStatus eval() const = 0; virtual std::vector get_dependency() const = 0; @@ -53,43 +52,34 @@ class ConstExpr : public BaseExpr DiagnosticLevel level_; }; -class UnitExpr : public BaseExpr +class LinkExpr : public BaseExpr { public: - UnitExpr(Graph & graph, YAML::Node yaml); + LinkExpr(ExprInit & exprs, ConfigObject & config); + void init(ConfigObject & config, std::unordered_map nodes); ExprStatus eval() const override; std::vector get_dependency() const override; private: - UnitNode * node_; -}; - -class DiagExpr : public BaseExpr -{ -public: - DiagExpr(Graph & graph, YAML::Node yaml); - ExprStatus eval() const override; - std::vector get_dependency() const override; - -private: - DiagNode * node_; + BaseNode * node_; }; class AndExpr : public BaseExpr { public: - AndExpr(Graph & graph, YAML::Node yaml); + AndExpr(ExprInit & exprs, ConfigObject & config, bool short_circuit); ExprStatus eval() const override; std::vector get_dependency() const override; private: + bool short_circuit_; std::vector> list_; }; class OrExpr : public BaseExpr { public: - OrExpr(Graph & graph, YAML::Node yaml); + OrExpr(ExprInit & exprs, ConfigObject & config); ExprStatus eval() const override; std::vector get_dependency() const override; @@ -97,18 +87,18 @@ class OrExpr : public BaseExpr std::vector> list_; }; -class IfExpr : public BaseExpr +class ExprInit { public: - IfExpr(Graph & graph, YAML::Node yaml); - ExprStatus eval() const override; - std::vector get_dependency() const override; + explicit ExprInit(const std::string & mode); + std::unique_ptr create(ExprConfig config); + auto get() const { return links_; } private: - std::unique_ptr cond_; - std::unique_ptr then_; + std::string mode_; + std::vector> links_; }; } // namespace system_diagnostic_graph -#endif // CORE__EXPR_HPP_ +#endif // CORE__EXPRS_HPP_ diff --git a/system/system_diagnostic_graph/src/core/graph.cpp b/system/system_diagnostic_graph/src/core/graph.cpp index ba0e3cfd2e016..b4fd1d15827f3 100644 --- a/system/system_diagnostic_graph/src/core/graph.cpp +++ b/system/system_diagnostic_graph/src/core/graph.cpp @@ -14,58 +14,32 @@ #include "graph.hpp" -#include "node.hpp" +#include "config.hpp" +#include "exprs.hpp" +#include "nodes.hpp" #include -#include #include +#include +#include #include +#include -// +// DEBUG #include namespace system_diagnostic_graph { -UnitNode * Graph::make_unit(const std::string & name) +void topological_sort(std::vector> & input) { - const auto key = name; - auto unit = std::make_unique(key); - units_[key] = unit.get(); - nodes_.emplace_back(std::move(unit)); - return units_[key]; -} - -UnitNode * Graph::find_unit(const std::string & name) -{ - const auto key = name; - return units_.count(key) ? units_.at(key) : nullptr; -} - -DiagNode * Graph::make_diag(const std::string & name, const std::string & hardware) -{ - const auto key = std::make_pair(name, hardware); - auto diag = std::make_unique(name, hardware); - diags_[key] = diag.get(); - nodes_.emplace_back(std::move(diag)); - return diags_[key]; -} - -DiagNode * Graph::find_diag(const std::string & name, const std::string & hardware) -{ - const auto key = std::make_pair(name, hardware); - return diags_.count(key) ? diags_.at(key) : nullptr; -} - -void Graph::topological_sort() -{ - std::map degrees; + std::unordered_map degrees; std::deque nodes; std::deque result; std::deque buffer; // Create a list of raw pointer nodes. - for (const auto & node : nodes_) { + for (const auto & node : input) { nodes.push_back(node.get()); } @@ -104,15 +78,127 @@ void Graph::topological_sort() result = std::deque(result.rbegin(), result.rend()); // Replace node vector. - std::map indices; + std::unordered_map indices; for (size_t i = 0; i < result.size(); ++i) { indices[result[i]] = i; } - std::vector> temp(nodes_.size()); - for (auto & node : nodes_) { - temp[indices[node.get()]] = std::move(node); + std::vector> sorted(input.size()); + for (auto & node : input) { + sorted[indices[node.get()]] = std::move(node); + } + input = std::move(sorted); +} + +Graph::Graph() +{ + // for unique_ptr +} + +Graph::~Graph() +{ + // for unique_ptr +} + +void Graph::init(const std::string & file, const std::string & mode) +{ + ConfigFile root = load_config_root(file); + + std::vector> nodes; + std::unordered_map diags; + std::unordered_map paths; + ExprInit exprs(mode); + + for (auto & config : root.units) { + if (config.mode.check(mode)) { + auto node = std::make_unique(config.path); + nodes.push_back(std::move(node)); + } + } + for (auto & config : root.diags) { + if (config.mode.check(mode)) { + auto node = std::make_unique(config.path, config.dict); + diags[node->name()] = node.get(); + nodes.push_back(std::move(node)); + } + } + + // TODO(Takagi, Isamu): unknown diag names + { + auto node = std::make_unique("/unknown"); + unknown_ = node.get(); + nodes.push_back(std::move(node)); + } + + for (const auto & node : nodes) { + paths[node->path()] = node.get(); + } + + for (auto & config : root.units) { + if (paths.count(config.path)) { + paths.at(config.path)->create(config.dict, exprs); + } + } + for (auto & config : root.diags) { + if (paths.count(config.path)) { + paths.at(config.path)->create(config.dict, exprs); + } + } + + for (auto & [link, config] : exprs.get()) { + link->init(config, paths); + } + + // Sort unit nodes in topological order for update dependencies. + topological_sort(nodes); + + // Set the link index for the ros message. + for (size_t i = 0; i < nodes.size(); ++i) { + nodes[i]->set_index(i); + } + + nodes_ = std::move(nodes); + diags_ = diags; +} + +void Graph::callback(const DiagnosticArray & array, const rclcpp::Time & stamp) +{ + for (const auto & status : array.status) { + const auto iter = diags_.find(status.name); + if (iter != diags_.end()) { + iter->second->callback(status, stamp); + } else { + unknown_->callback(status, stamp); + } + } +} + +void Graph::update(const rclcpp::Time & stamp) +{ + for (const auto & node : nodes_) { + node->update(stamp); + } + stamp_ = stamp; +} + +DiagnosticGraph Graph::message() const +{ + DiagnosticGraph result; + result.stamp = stamp_; + result.nodes.reserve(nodes_.size()); + for (const auto & node : nodes_) { + result.nodes.push_back(node->report()); + } + return result; +} + +std::vector Graph::nodes() const +{ + std::vector result; + result.reserve(nodes_.size()); + for (const auto & node : nodes_) { + result.push_back(node.get()); } - nodes_ = std::move(temp); + return result; } } // namespace system_diagnostic_graph diff --git a/system/system_diagnostic_graph/src/core/graph.hpp b/system/system_diagnostic_graph/src/core/graph.hpp index a3f46760388f7..e0060c9111592 100644 --- a/system/system_diagnostic_graph/src/core/graph.hpp +++ b/system/system_diagnostic_graph/src/core/graph.hpp @@ -17,29 +17,36 @@ #include "types.hpp" -#include +#include + #include #include +#include #include #include namespace system_diagnostic_graph { -class Graph +class Graph final { public: - UnitNode * make_unit(const std::string & name); - UnitNode * find_unit(const std::string & name); - DiagNode * make_diag(const std::string & name, const std::string & hardware); - DiagNode * find_diag(const std::string & name, const std::string & hardware); - void topological_sort(); - const std::vector> & nodes() { return nodes_; } + Graph(); + ~Graph(); + + void init(const std::string & file, const std::string & mode); + void callback(const DiagnosticArray & array, const rclcpp::Time & stamp); + void update(const rclcpp::Time & stamp); + DiagnosticGraph message() const; + std::vector nodes() const; + + void debug(); private: std::vector> nodes_; - std::map units_; - std::map, DiagNode *> diags_; + std::unordered_map diags_; + UnknownNode * unknown_; + rclcpp::Time stamp_; }; } // namespace system_diagnostic_graph diff --git a/system/system_diagnostic_graph/src/core/modes.cpp b/system/system_diagnostic_graph/src/core/modes.cpp new file mode 100644 index 0000000000000..0ca18f84b0407 --- /dev/null +++ b/system/system_diagnostic_graph/src/core/modes.cpp @@ -0,0 +1,75 @@ +// Copyright 2023 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "modes.hpp" + +#include "config.hpp" +#include "nodes.hpp" + +#include +#include +#include + +namespace system_diagnostic_graph +{ + +OperationModes::OperationModes(rclcpp::Node & node, const std::vector & graph) +{ + pub_ = node.create_publisher("/system/operation_mode/availability", rclcpp::QoS(1)); + + using PathNodes = std::unordered_map; + PathNodes paths; + for (const auto & node : graph) { + paths[node->path()] = node; + } + + const auto find_node = [](const PathNodes & paths, const std::string & name) { + const auto iter = paths.find(name); + if (iter != paths.end()) { + return iter->second; + } + throw ConfigError("summary node '" + name + "' does node exist"); + }; + + // clang-format off + stop_mode_ = find_node(paths, "/autoware/modes/stop"); + autonomous_mode_ = find_node(paths, "/autoware/modes/autonomous"); + local_mode_ = find_node(paths, "/autoware/modes/local"); + remote_mode_ = find_node(paths, "/autoware/modes/remote"); + emergency_stop_mrm_ = find_node(paths, "/autoware/modes/emergency-stop"); + comfortable_stop_mrm_ = find_node(paths, "/autoware/modes/comfortable-stop"); + pull_over_mrm_ = find_node(paths, "/autoware/modes/pull-over"); + // clang-format on +} + +void OperationModes::update(const rclcpp::Time & stamp) const +{ + const auto is_ok = [](const BaseNode * node) { return node->level() == DiagnosticStatus::OK; }; + + // clang-format off + Availability message; + message.stamp = stamp; + message.stop = is_ok(stop_mode_); + message.autonomous = is_ok(autonomous_mode_); + message.local = is_ok(local_mode_); + message.remote = is_ok(remote_mode_); + message.emergency_stop = is_ok(emergency_stop_mrm_); + message.comfortable_stop = is_ok(comfortable_stop_mrm_); + message.pull_over = is_ok(pull_over_mrm_); + // clang-format on + + pub_->publish(message); +} + +} // namespace system_diagnostic_graph diff --git a/system/system_diagnostic_graph/src/core/update.hpp b/system/system_diagnostic_graph/src/core/modes.hpp similarity index 53% rename from system/system_diagnostic_graph/src/core/update.hpp rename to system/system_diagnostic_graph/src/core/modes.hpp index 3cba96ad8203a..ead1ec10dce93 100644 --- a/system/system_diagnostic_graph/src/core/update.hpp +++ b/system/system_diagnostic_graph/src/core/modes.hpp @@ -12,47 +12,40 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef CORE__UPDATE_HPP_ -#define CORE__UPDATE_HPP_ +#ifndef CORE__MODES_HPP_ +#define CORE__MODES_HPP_ -#include "graph.hpp" -#include "node.hpp" #include "types.hpp" #include -#include +#include + #include namespace system_diagnostic_graph { -struct Summary -{ - UnitNode * stop_mode; - UnitNode * autonomous_mode; - UnitNode * local_mode; - UnitNode * remote_mode; - UnitNode * emergency_stop_mrm; - UnitNode * comfortable_stop_mrm; - UnitNode * pull_over_mrm; -}; - -class DiagGraph +class OperationModes { public: - void create(const std::string & file); - void callback(const DiagnosticArray & array); - DiagnosticGraph report(const rclcpp::Time & stamp); - OperationModeAvailability summary(const rclcpp::Time & stamp); - - void debug(); + explicit OperationModes(rclcpp::Node & node, const std::vector & graph); + void update(const rclcpp::Time & stamp) const; private: - Graph graph_; - Summary summary_; + using Availability = tier4_system_msgs::msg::OperationModeAvailability; + rclcpp::TimerBase::SharedPtr timer_; + rclcpp::Publisher::SharedPtr pub_; + + BaseNode * stop_mode_; + BaseNode * autonomous_mode_; + BaseNode * local_mode_; + BaseNode * remote_mode_; + BaseNode * emergency_stop_mrm_; + BaseNode * comfortable_stop_mrm_; + BaseNode * pull_over_mrm_; }; } // namespace system_diagnostic_graph -#endif // CORE__UPDATE_HPP_ +#endif // CORE__MODES_HPP_ diff --git a/system/system_diagnostic_graph/src/core/node.cpp b/system/system_diagnostic_graph/src/core/node.cpp deleted file mode 100644 index 1439188d93e18..0000000000000 --- a/system/system_diagnostic_graph/src/core/node.cpp +++ /dev/null @@ -1,94 +0,0 @@ -// Copyright 2023 The Autoware Contributors -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "node.hpp" - -#include "expr.hpp" - -#include - -#include -#include - -namespace system_diagnostic_graph -{ - -UnitNode::UnitNode(const std::string & name) -{ - node_.status.level = DiagnosticStatus::STALE; - node_.status.name = name; - node_.status.hardware_id = ""; -} - -UnitNode::~UnitNode() -{ - // for unique_ptr -} - -DiagnosticNode UnitNode::report() const -{ - return node_; -} - -void UnitNode::update() -{ - const auto result = expr_->eval(); - node_.status.level = result.level; - node_.links.clear(); - for (const auto & [node, used] : result.links) { - DiagnosticLink link; - link.index = node->index(); - link.used = used; - node_.links.push_back(link); - } -} - -void UnitNode::create(Graph & graph, const NodeConfig & config) -{ - try { - expr_ = BaseExpr::create(graph, config->yaml); - } catch (const ConfigError & error) { - throw create_error(config, error.what()); - } -} - -std::vector UnitNode::links() const -{ - return expr_->get_dependency(); -} - -DiagNode::DiagNode(const std::string & name, const std::string & hardware) -{ - node_.status.level = DiagnosticStatus::STALE; - node_.status.name = name; - node_.status.hardware_id = hardware; -} - -DiagnosticNode DiagNode::report() const -{ - return node_; -} - -void DiagNode::update() -{ - // TODO(Takagi, Isamu): timeout, error hold - // constexpr double timeout = 1.0; // TODO(Takagi, Isamu): parameterize -} - -void DiagNode::callback(const DiagnosticStatus & status) -{ - node_.status = status; -} - -} // namespace system_diagnostic_graph diff --git a/system/system_diagnostic_graph/src/core/node.hpp b/system/system_diagnostic_graph/src/core/node.hpp deleted file mode 100644 index 359153fc2824a..0000000000000 --- a/system/system_diagnostic_graph/src/core/node.hpp +++ /dev/null @@ -1,84 +0,0 @@ -// Copyright 2023 The Autoware Contributors -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef CORE__NODE_HPP_ -#define CORE__NODE_HPP_ - -#include "config.hpp" -#include "debug.hpp" -#include "types.hpp" - -#include -#include -#include -#include - -namespace system_diagnostic_graph -{ - -class BaseNode -{ -public: - virtual ~BaseNode() = default; - virtual void update() = 0; - virtual DiagnosticNode report() const = 0; - virtual DiagDebugData debug() const = 0; - virtual std::vector links() const = 0; - - DiagnosticLevel level() const { return node_.status.level; } - std::string name() const { return node_.status.name; } - - size_t index() const { return index_; } - void set_index(const size_t index) { index_ = index; } - -protected: - size_t index_ = 0; - DiagnosticNode node_; -}; - -class UnitNode : public BaseNode -{ -public: - explicit UnitNode(const std::string & name); - ~UnitNode() override; - - DiagnosticNode report() const override; - DiagDebugData debug() const override; - void update() override; - void create(Graph & graph, const NodeConfig & config); - - std::vector links() const override; - -private: - std::unique_ptr expr_; -}; - -class DiagNode : public BaseNode -{ -public: - explicit DiagNode(const std::string & name, const std::string & hardware); - - DiagnosticNode report() const override; - DiagDebugData debug() const override; - void update() override; - void callback(const DiagnosticStatus & status); - - std::vector links() const override { return {}; } - -private: -}; - -} // namespace system_diagnostic_graph - -#endif // CORE__NODE_HPP_ diff --git a/system/system_diagnostic_graph/src/core/nodes.cpp b/system/system_diagnostic_graph/src/core/nodes.cpp new file mode 100644 index 0000000000000..bbc4bb4d42561 --- /dev/null +++ b/system/system_diagnostic_graph/src/core/nodes.cpp @@ -0,0 +1,157 @@ +// Copyright 2023 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "nodes.hpp" + +#include "exprs.hpp" + +#include + +#include +#include + +namespace system_diagnostic_graph +{ + +BaseNode::BaseNode(const std::string & path) : path_(path) +{ + index_ = 0; +} + +UnitNode::UnitNode(const std::string & path) : BaseNode(path) +{ + level_ = DiagnosticStatus::STALE; +} + +UnitNode::~UnitNode() +{ + // for unique_ptr +} + +void UnitNode::create(ConfigObject & config, ExprInit & exprs) +{ + expr_ = exprs.create(parse_expr_config(config)); +} + +void UnitNode::update(const rclcpp::Time &) +{ + const auto result = expr_->eval(); + level_ = result.level; + links_.clear(); + for (const auto & [node, used] : result.links) { + DiagnosticLink link; + link.index = node->index(); + link.used = used; + links_.push_back(link); + } +} + +DiagnosticNode UnitNode::report() const +{ + DiagnosticNode message; + message.status.level = level_; + message.status.name = path_; + message.links = links_; + return message; +} + +DiagnosticLevel UnitNode::level() const +{ + return level_; +} + +std::vector UnitNode::links() const +{ + return expr_->get_dependency(); +} + +DiagNode::DiagNode(const std::string & path, ConfigObject & config) : BaseNode(path) +{ + timeout_ = 3.0; // TODO(Takagi, Isamu): parameterize + name_ = config.take_text("name"); + + status_.level = DiagnosticStatus::STALE; +} + +void DiagNode::create(ConfigObject &, ExprInit &) +{ +} + +void DiagNode::update(const rclcpp::Time & stamp) +{ + if (time_) { + const auto elapsed = (stamp - time_.value()).seconds(); + if (timeout_ < elapsed) { + status_ = DiagnosticStatus(); + status_.level = DiagnosticStatus::STALE; + time_ = std::nullopt; + } + } +} + +DiagnosticNode DiagNode::report() const +{ + DiagnosticNode message; + message.status = status_; + message.status.name = path_; + return message; +} + +DiagnosticLevel DiagNode::level() const +{ + return status_.level; +} + +void DiagNode::callback(const DiagnosticStatus & status, const rclcpp::Time & stamp) +{ + status_ = status; + time_ = stamp; +} + +UnknownNode::UnknownNode(const std::string & path) : BaseNode(path) +{ +} + +void UnknownNode::create(ConfigObject &, ExprInit &) +{ +} + +void UnknownNode::update(const rclcpp::Time & stamp) +{ + (void)stamp; +} + +DiagnosticNode UnknownNode::report() const +{ + DiagnosticNode message; + message.status.name = path_; + for (const auto & diag : diagnostics_) { + diagnostic_msgs::msg::KeyValue kv; + kv.key = diag.first; + message.status.values.push_back(kv); + } + return message; +} + +DiagnosticLevel UnknownNode::level() const +{ + return DiagnosticStatus::WARN; +} + +void UnknownNode::callback(const DiagnosticStatus & status, const rclcpp::Time & stamp) +{ + diagnostics_[status.name] = stamp; +} + +} // namespace system_diagnostic_graph diff --git a/system/system_diagnostic_graph/src/core/nodes.hpp b/system/system_diagnostic_graph/src/core/nodes.hpp new file mode 100644 index 0000000000000..1a849cf58b268 --- /dev/null +++ b/system/system_diagnostic_graph/src/core/nodes.hpp @@ -0,0 +1,114 @@ +// Copyright 2023 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef CORE__NODES_HPP_ +#define CORE__NODES_HPP_ + +#include "config.hpp" +#include "debug.hpp" +#include "types.hpp" + +#include + +#include +#include +#include +#include +#include +#include + +namespace system_diagnostic_graph +{ + +class BaseNode +{ +public: + explicit BaseNode(const std::string & path); + virtual ~BaseNode() = default; + virtual void create(ConfigObject & config, ExprInit & exprs) = 0; + virtual void update(const rclcpp::Time & stamp) = 0; + virtual DiagnosticNode report() const = 0; + virtual DiagnosticLevel level() const = 0; + virtual DiagDebugData debug() const = 0; + virtual std::vector links() const = 0; + + std::string path() const { return path_; } + + size_t index() const { return index_; } + void set_index(const size_t index) { index_ = index; } + +protected: + const std::string path_; + size_t index_; +}; + +class UnitNode : public BaseNode +{ +public: + explicit UnitNode(const std::string & path); + ~UnitNode() override; + void create(ConfigObject & config, ExprInit & exprs) override; + void update(const rclcpp::Time & stamp) override; + DiagnosticNode report() const override; + DiagnosticLevel level() const override; + DiagDebugData debug() const override; + std::vector links() const override; + +private: + std::unique_ptr expr_; + std::vector links_; + DiagnosticLevel level_; +}; + +class DiagNode : public BaseNode +{ +public: + DiagNode(const std::string & path, ConfigObject & config); + void create(ConfigObject & config, ExprInit & exprs) override; + void update(const rclcpp::Time & stamp) override; + DiagnosticNode report() const override; + DiagnosticLevel level() const override; + DiagDebugData debug() const override; + std::vector links() const override { return {}; } + std::string name() const { return name_; } + + void callback(const DiagnosticStatus & status, const rclcpp::Time & stamp); + +private: + double timeout_; + std::optional time_; + std::string name_; + DiagnosticStatus status_; +}; + +class UnknownNode : public BaseNode +{ +public: + explicit UnknownNode(const std::string & path); + void create(ConfigObject & config, ExprInit & exprs) override; + void update(const rclcpp::Time & stamp) override; + DiagnosticNode report() const override; + DiagnosticLevel level() const override; + DiagDebugData debug() const override; + std::vector links() const override { return {}; } + + void callback(const DiagnosticStatus & status, const rclcpp::Time & stamp); + +private: + std::map diagnostics_; +}; + +} // namespace system_diagnostic_graph + +#endif // CORE__NODES_HPP_ diff --git a/system/system_diagnostic_graph/src/core/types.hpp b/system/system_diagnostic_graph/src/core/types.hpp index 75167958e49bc..2adfbb3f9d4ef 100644 --- a/system/system_diagnostic_graph/src/core/types.hpp +++ b/system/system_diagnostic_graph/src/core/types.hpp @@ -20,7 +20,6 @@ #include #include #include -#include namespace system_diagnostic_graph { @@ -30,15 +29,15 @@ using diagnostic_msgs::msg::DiagnosticStatus; using tier4_system_msgs::msg::DiagnosticGraph; using tier4_system_msgs::msg::DiagnosticLink; using tier4_system_msgs::msg::DiagnosticNode; -using tier4_system_msgs::msg::OperationModeAvailability; - using DiagnosticLevel = DiagnosticStatus::_level_type; -class Graph; class BaseNode; class UnitNode; class DiagNode; +class UnknownNode; + class BaseExpr; +class ExprInit; } // namespace system_diagnostic_graph diff --git a/system/system_diagnostic_graph/src/core/update.cpp b/system/system_diagnostic_graph/src/core/update.cpp deleted file mode 100644 index bb42dcba12192..0000000000000 --- a/system/system_diagnostic_graph/src/core/update.cpp +++ /dev/null @@ -1,116 +0,0 @@ -// Copyright 2023 The Autoware Contributors -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "update.hpp" - -#include "config.hpp" - -#include -#include -#include -#include -#include -#include - -namespace system_diagnostic_graph -{ - -UnitNode * find_node(Graph & graph, const std::string & name) -{ - const auto node = graph.find_unit(name); - if (!node) { - throw ConfigError("summary node '" + name + "' does node exist"); - } - return node; -}; - -void DiagGraph::create(const std::string & file) -{ - const auto configs = load_config_file(file); - - // Create unit nodes first because it is necessary for the link. - std::vector> units; - for (const auto & config : configs) { - UnitNode * unit = graph_.make_unit(config->name); - units.push_back(std::make_pair(config, unit)); - } - - // Reflect the config after creating all the unit nodes, - for (auto & [config, unit] : units) { - unit->create(graph_, config); - } - - // Sort unit nodes in topological order for update dependencies. - graph_.topological_sort(); - - // Set the link index for the ros message. - const auto & nodes = graph_.nodes(); - for (size_t i = 0; i < nodes.size(); ++i) { - nodes[i]->set_index(i); - } - - // Get reserved unit node for summary. - summary_.stop_mode = find_node(graph_, "/autoware/operation/stop"); - summary_.autonomous_mode = find_node(graph_, "/autoware/operation/autonomous"); - summary_.local_mode = find_node(graph_, "/autoware/operation/local"); - summary_.remote_mode = find_node(graph_, "/autoware/operation/remote"); - summary_.emergency_stop_mrm = find_node(graph_, "/autoware/operation/emergency-stop"); - summary_.comfortable_stop_mrm = find_node(graph_, "/autoware/operation/comfortable-stop"); - summary_.pull_over_mrm = find_node(graph_, "/autoware/operation/pull-over"); -} - -DiagnosticGraph DiagGraph::report(const rclcpp::Time & stamp) -{ - DiagnosticGraph message; - message.stamp = stamp; - message.nodes.reserve(graph_.nodes().size()); - - for (const auto & node : graph_.nodes()) { - node->update(); - } - for (const auto & node : graph_.nodes()) { - message.nodes.push_back(node->report()); - } - return message; -} - -OperationModeAvailability DiagGraph::summary(const rclcpp::Time & stamp) -{ - const auto is_ok = [](const UnitNode * node) { return node->level() == DiagnosticStatus::OK; }; - - OperationModeAvailability message; - message.stamp = stamp; - message.stop = is_ok(summary_.stop_mode); - message.autonomous = is_ok(summary_.autonomous_mode); - message.local = is_ok(summary_.local_mode); - message.remote = is_ok(summary_.remote_mode); - message.emergency_stop = is_ok(summary_.emergency_stop_mrm); - message.comfortable_stop = is_ok(summary_.comfortable_stop_mrm); - message.pull_over = is_ok(summary_.pull_over_mrm); - return message; -} - -void DiagGraph::callback(const DiagnosticArray & array) -{ - for (const auto & status : array.status) { - auto diag = graph_.find_diag(status.name, status.hardware_id); - if (diag) { - diag->callback(status); - } else { - // TODO(Takagi, Isamu): handle unknown diagnostics - } - } -} - -} // namespace system_diagnostic_graph diff --git a/system/system_diagnostic_graph/src/main.cpp b/system/system_diagnostic_graph/src/main.cpp index 38b9fa5bacb3b..722ddcf833577 100644 --- a/system/system_diagnostic_graph/src/main.cpp +++ b/system/system_diagnostic_graph/src/main.cpp @@ -22,6 +22,19 @@ namespace system_diagnostic_graph MainNode::MainNode() : Node("system_diagnostic_graph_aggregator") { + // Init diagnostics graph. + { + const auto file = declare_parameter("graph_file"); + const auto mode = declare_parameter("mode"); + graph_.init(file, mode); + graph_.debug(); + } + + // Init plugins + if (declare_parameter("mode_availability")) { + modes_ = std::make_unique(*this, graph_.nodes()); + } + // Init ros interface. { using std::placeholders::_1; @@ -31,32 +44,30 @@ MainNode::MainNode() : Node("system_diagnostic_graph_aggregator") const auto callback = std::bind(&MainNode::on_diag, this, _1); sub_input_ = create_subscription("/diagnostics", qos_input, callback); pub_graph_ = create_publisher("/diagnostics_graph", qos_graph); - pub_modes_ = create_publisher( - "/system/operation_mode/availability", rclcpp::QoS(1)); const auto rate = rclcpp::Rate(declare_parameter("rate")); timer_ = rclcpp::create_timer(this, get_clock(), rate.period(), [this]() { on_timer(); }); } +} - // Init diagnostics graph. - { - const auto file = declare_parameter("graph_file"); - graph_.create(file); - graph_.debug(); - } +MainNode::~MainNode() +{ + // for unique_ptr } void MainNode::on_timer() { - const auto data = graph_.report(now()); + const auto stamp = now(); + graph_.update(stamp); graph_.debug(); - pub_graph_->publish(data); - pub_modes_->publish(graph_.summary(now())); + pub_graph_->publish(graph_.message()); + + if (modes_) modes_->update(stamp); } void MainNode::on_diag(const DiagnosticArray::ConstSharedPtr msg) { - graph_.callback(*msg); + graph_.callback(*msg, now()); } } // namespace system_diagnostic_graph diff --git a/system/system_diagnostic_graph/src/main.hpp b/system/system_diagnostic_graph/src/main.hpp index 4cc659c978611..6deb0518cd9d0 100644 --- a/system/system_diagnostic_graph/src/main.hpp +++ b/system/system_diagnostic_graph/src/main.hpp @@ -15,11 +15,14 @@ #ifndef MAIN_HPP_ #define MAIN_HPP_ +#include "core/graph.hpp" +#include "core/modes.hpp" #include "core/types.hpp" -#include "core/update.hpp" #include +#include + namespace system_diagnostic_graph { @@ -27,13 +30,14 @@ class MainNode : public rclcpp::Node { public: MainNode(); + ~MainNode(); private: - DiagGraph graph_; + Graph graph_; + std::unique_ptr modes_; rclcpp::TimerBase::SharedPtr timer_; rclcpp::Subscription::SharedPtr sub_input_; rclcpp::Publisher::SharedPtr pub_graph_; - rclcpp::Publisher::SharedPtr pub_modes_; void on_timer(); void on_diag(const DiagnosticArray::ConstSharedPtr msg); }; diff --git a/system/system_diagnostic_graph/src/tool.hpp b/system/system_diagnostic_graph/src/tool.hpp index 11f6a2632386b..5ad19b8460c4b 100644 --- a/system/system_diagnostic_graph/src/tool.hpp +++ b/system/system_diagnostic_graph/src/tool.hpp @@ -15,7 +15,6 @@ #ifndef TOOL_HPP_ #define TOOL_HPP_ -#include "core/graph.hpp" #include "core/types.hpp" #include diff --git a/system/system_diagnostic_monitor/CMakeLists.txt b/system/system_diagnostic_monitor/CMakeLists.txt deleted file mode 100644 index 909210f99d55e..0000000000000 --- a/system/system_diagnostic_monitor/CMakeLists.txt +++ /dev/null @@ -1,7 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(system_diagnostic_monitor) - -find_package(autoware_cmake REQUIRED) -autoware_package() - -ament_auto_package(INSTALL_TO_SHARE config launch script) diff --git a/system/system_diagnostic_monitor/README.md b/system/system_diagnostic_monitor/README.md deleted file mode 100644 index 8dccca34db8c5..0000000000000 --- a/system/system_diagnostic_monitor/README.md +++ /dev/null @@ -1 +0,0 @@ -# System diagnostic monitor diff --git a/system/system_diagnostic_monitor/config/autoware.yaml b/system/system_diagnostic_monitor/config/autoware.yaml deleted file mode 100644 index 892a5da851ba7..0000000000000 --- a/system/system_diagnostic_monitor/config/autoware.yaml +++ /dev/null @@ -1,74 +0,0 @@ -files: - - { package: system_diagnostic_monitor, path: config/map.yaml } - - { package: system_diagnostic_monitor, path: config/localization.yaml } - - { package: system_diagnostic_monitor, path: config/planning.yaml } - - { package: system_diagnostic_monitor, path: config/perception.yaml } - - { package: system_diagnostic_monitor, path: config/control.yaml } - - { package: system_diagnostic_monitor, path: config/vehicle.yaml } - - { package: system_diagnostic_monitor, path: config/system.yaml } - -nodes: - - name: /autoware - type: and - list: - - { type: unit, name: /autoware/operation/stop } - - { type: unit, name: /autoware/operation/autonomous } - - { type: unit, name: /autoware/operation/local } - - { type: unit, name: /autoware/operation/remote } - - { type: unit, name: /autoware/operation/emergency-stop } - - { type: unit, name: /autoware/operation/comfortable-stop } - - { type: unit, name: /autoware/operation/pull-over } - - - name: /autoware/operation/stop - type: debug-ok - - - name: /autoware/operation/autonomous - type: and - list: - - { type: unit, name: /autoware/map } - - { type: unit, name: /autoware/localization } - - { type: unit, name: /autoware/planning } - - { type: unit, name: /autoware/perception } - - { type: unit, name: /autoware/control } - - { type: unit, name: /autoware/vehicle } - - { type: unit, name: /autoware/system } - - - name: /autoware/operation/local - type: and - list: - - { type: unit, name: /autoware/vehicle } - - { type: unit, name: /autoware/system } - - - name: /autoware/operation/remote - type: and - list: - - { type: unit, name: /autoware/vehicle } - - { type: unit, name: /autoware/system } - - - name: /autoware/operation/emergency-stop - type: and - list: - - { type: unit, name: /autoware/vehicle } - - { type: unit, name: /autoware/system } - - - name: /autoware/operation/comfortable-stop - type: and - list: - - { type: unit, name: /autoware/map } - - { type: unit, name: /autoware/localization } - - { type: unit, name: /autoware/planning } - - { type: unit, name: /autoware/perception } - - { type: unit, name: /autoware/control } - - { type: unit, name: /autoware/vehicle } - - { type: unit, name: /autoware/system } - - - name: /autoware/operation/pull-over - type: and - list: - - { type: unit, name: /autoware/map } - - { type: unit, name: /autoware/localization } - - { type: unit, name: /autoware/planning } - - { type: unit, name: /autoware/perception } - - { type: unit, name: /autoware/control } - - { type: unit, name: /autoware/vehicle } - - { type: unit, name: /autoware/system } diff --git a/system/system_diagnostic_monitor/config/control.yaml b/system/system_diagnostic_monitor/config/control.yaml deleted file mode 100644 index 8884a79847c71..0000000000000 --- a/system/system_diagnostic_monitor/config/control.yaml +++ /dev/null @@ -1,10 +0,0 @@ -nodes: - - name: /autoware/control - type: and - list: - - type: diag - name: "topic_state_monitor_trajectory_follower_control_cmd: control_topic_status" - hardware: topic_state_monitor - - type: diag - name: "topic_state_monitor_control_command_control_cmd: control_topic_status" - hardware: topic_state_monitor diff --git a/system/system_diagnostic_monitor/config/localization.yaml b/system/system_diagnostic_monitor/config/localization.yaml deleted file mode 100644 index 26d680b6c4f0f..0000000000000 --- a/system/system_diagnostic_monitor/config/localization.yaml +++ /dev/null @@ -1,5 +0,0 @@ -nodes: - - name: /autoware/localization - type: and - list: - - { type: diag, name: "component_state_diagnostics: localization_state" } diff --git a/system/system_diagnostic_monitor/config/map.yaml b/system/system_diagnostic_monitor/config/map.yaml deleted file mode 100644 index 7bee7419200bd..0000000000000 --- a/system/system_diagnostic_monitor/config/map.yaml +++ /dev/null @@ -1,7 +0,0 @@ -nodes: - - name: /autoware/map - type: and - list: - - type: diag - name: "topic_state_monitor_vector_map: map_topic_status" - hardware: topic_state_monitor diff --git a/system/system_diagnostic_monitor/config/perception.yaml b/system/system_diagnostic_monitor/config/perception.yaml deleted file mode 100644 index b6b4ec27d5596..0000000000000 --- a/system/system_diagnostic_monitor/config/perception.yaml +++ /dev/null @@ -1,7 +0,0 @@ -nodes: - - name: /autoware/perception - type: and - list: - - type: diag - name: "topic_state_monitor_object_recognition_objects: perception_topic_status" - hardware: topic_state_monitor diff --git a/system/system_diagnostic_monitor/config/planning.yaml b/system/system_diagnostic_monitor/config/planning.yaml deleted file mode 100644 index c29059193081b..0000000000000 --- a/system/system_diagnostic_monitor/config/planning.yaml +++ /dev/null @@ -1,15 +0,0 @@ -nodes: - - name: /autoware/planning - type: if - cond: - type: diag - name: "component_state_diagnostics: route_state" - then: - type: and - list: - - type: diag - name: "topic_state_monitor_mission_planning_route: planning_topic_status" - hardware: topic_state_monitor - - type: diag - name: "topic_state_monitor_scenario_planning_trajectory: planning_topic_status" - hardware: topic_state_monitor diff --git a/system/system_diagnostic_monitor/config/system.yaml b/system/system_diagnostic_monitor/config/system.yaml deleted file mode 100644 index 0377e68daaae6..0000000000000 --- a/system/system_diagnostic_monitor/config/system.yaml +++ /dev/null @@ -1,7 +0,0 @@ -nodes: - - name: /autoware/system - type: and - list: - - type: diag - name: "topic_state_monitor_system_emergency_control_cmd: system_topic_status" - hardware: topic_state_monitor diff --git a/system/system_diagnostic_monitor/config/vehicle.yaml b/system/system_diagnostic_monitor/config/vehicle.yaml deleted file mode 100644 index 4826c96e5f72f..0000000000000 --- a/system/system_diagnostic_monitor/config/vehicle.yaml +++ /dev/null @@ -1,10 +0,0 @@ -nodes: - - name: /autoware/vehicle - type: and - list: - - type: diag - name: "topic_state_monitor_vehicle_status_velocity_status: vehicle_topic_status" - hardware: topic_state_monitor - - type: diag - name: "topic_state_monitor_vehicle_status_steering_status: vehicle_topic_status" - hardware: topic_state_monitor diff --git a/system/system_diagnostic_monitor/launch/system_diagnostic_monitor.launch.xml b/system/system_diagnostic_monitor/launch/system_diagnostic_monitor.launch.xml deleted file mode 100644 index a13b1dc9b78bc..0000000000000 --- a/system/system_diagnostic_monitor/launch/system_diagnostic_monitor.launch.xml +++ /dev/null @@ -1,6 +0,0 @@ - - - - - - diff --git a/system/system_diagnostic_monitor/package.xml b/system/system_diagnostic_monitor/package.xml deleted file mode 100644 index d410e75000876..0000000000000 --- a/system/system_diagnostic_monitor/package.xml +++ /dev/null @@ -1,23 +0,0 @@ - - - - system_diagnostic_monitor - 0.1.0 - The system_diagnostic_monitor package - Takagi, Isamu - Apache License 2.0 - - ament_cmake_auto - autoware_cmake - - system_diagnostic_graph - - autoware_adapi_v1_msgs - - ament_lint_auto - autoware_lint_common - - - ament_cmake - - diff --git a/system/system_diagnostic_monitor/script/component_state_diagnostics.py b/system/system_diagnostic_monitor/script/component_state_diagnostics.py deleted file mode 100755 index 8e12ed6656674..0000000000000 --- a/system/system_diagnostic_monitor/script/component_state_diagnostics.py +++ /dev/null @@ -1,79 +0,0 @@ -#!/usr/bin/env python3 - -# Copyright 2023 The Autoware Contributors -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -from autoware_adapi_v1_msgs.msg import LocalizationInitializationState as LocalizationState -from autoware_adapi_v1_msgs.msg import RouteState -from diagnostic_msgs.msg import DiagnosticArray -from diagnostic_msgs.msg import DiagnosticStatus -import rclpy -import rclpy.node -import rclpy.qos - - -class ComponentStateDiagnostics(rclpy.node.Node): - def __init__(self): - super().__init__("component_state_diagnostics") - durable_qos = rclpy.qos.QoSProfile( - depth=1, - durability=rclpy.qos.DurabilityPolicy.TRANSIENT_LOCAL, - reliability=rclpy.qos.ReliabilityPolicy.RELIABLE, - ) - - self.timer = self.create_timer(0.5, self.on_timer) - self.pub = self.create_publisher(DiagnosticArray, "/diagnostics", 1) - self.sub1 = self.create_subscription( - LocalizationState, - "/api/localization/initialization_state", - self.on_localization, - durable_qos, - ) - self.sub2 = self.create_subscription( - RouteState, "/api/routing/state", self.on_routing, durable_qos - ) - - self.diags = DiagnosticArray() - self.diags.status.append( - DiagnosticStatus( - level=DiagnosticStatus.STALE, name="component_state_diagnostics: localization_state" - ) - ) - self.diags.status.append( - DiagnosticStatus( - level=DiagnosticStatus.STALE, name="component_state_diagnostics: route_state" - ) - ) - - def on_timer(self): - self.diags.header.stamp = self.get_clock().now().to_msg() - self.pub.publish(self.diags) - - def on_localization(self, msg): - self.diags.status[0].level = ( - DiagnosticStatus.OK - if msg.state == LocalizationState.INITIALIZED - else DiagnosticStatus.ERROR - ) - - def on_routing(self, msg): - self.diags.status[1].level = ( - DiagnosticStatus.OK if msg.state != RouteState.UNSET else DiagnosticStatus.ERROR - ) - - -if __name__ == "__main__": - rclpy.init() - rclpy.spin(ComponentStateDiagnostics()) - rclpy.shutdown() From 992584bb6b03c04bf189567be055f67c962b038f Mon Sep 17 00:00:00 2001 From: Shunsuke Miura <37187849+miursh@users.noreply.github.com> Date: Wed, 18 Oct 2023 17:32:25 +0900 Subject: [PATCH 017/202] chore(traffic_light_fine_detector): update onnx link in readme (#5339) chore(traffic_light_fine_detector): update onnx in readme Signed-off-by: Shunsuke Miura --- perception/traffic_light_fine_detector/README.md | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/perception/traffic_light_fine_detector/README.md b/perception/traffic_light_fine_detector/README.md index dcc89c76387c6..9e69c22fdc17b 100644 --- a/perception/traffic_light_fine_detector/README.md +++ b/perception/traffic_light_fine_detector/README.md @@ -16,7 +16,8 @@ The model was fine-tuned on around 17,000 TIER IV internal images of Japanese tr ### Trained Onnx model -- +You can download the ONNX file using these instructions. +Please visit [autoware-documentation](https://github.com/autowarefoundation/autoware-documentation/blob/main/docs/models/index.md) for more information. ## Inner-workings / Algorithms From 9a7fac5dd38294990a3a0be40f1837e349d38027 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 18 Oct 2023 18:12:18 +0900 Subject: [PATCH 018/202] fix(perception_reproducer): publish objects even if out of recorded timestamp (#5343) Signed-off-by: kosuke55 --- .../perception_replayer/perception_replayer_common.py | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer_common.py b/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer_common.py index 01079fdc3f8c1..f7453ad32ce58 100644 --- a/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer_common.py +++ b/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer_common.py @@ -153,6 +153,11 @@ def kill_online_perception_node(self): pass def binary_search(self, data, timestamp): + if data[-1][0] < timestamp: + return data[-1][1] + elif data[0][0] > timestamp: + return data[0][1] + low, high = 0, len(data) - 1 while low <= high: From a92b251516c0fdd2c8a7625fe725dfc25c046ba8 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 18 Oct 2023 18:39:10 +0900 Subject: [PATCH 019/202] perf(perception_reproducer): improve ego pose extraction (#5344) perf(perception_reproducer): imporove ego pose extraction Signed-off-by: kosuke55 --- .../perception_replayer/perception_replayer_common.py | 8 +------- 1 file changed, 1 insertion(+), 7 deletions(-) diff --git a/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer_common.py b/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer_common.py index f7453ad32ce58..7bf54c0278a27 100644 --- a/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer_common.py +++ b/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer_common.py @@ -180,10 +180,4 @@ def find_topics_by_timestamp(self, timestamp): return objects_data, traffic_signals_data def find_ego_odom_by_timestamp(self, timestamp): - ego_odom_data = None - for data in self.rosbag_ego_odom_data: - if timestamp < data[0]: - ego_odom_data = data[1] - break - - return ego_odom_data + return self.binary_search(self.rosbag_ego_odom_data, timestamp) From c6278ceace794c01cdd6bdefc460a90a77793167 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 18 Oct 2023 19:02:06 +0900 Subject: [PATCH 020/202] fix(lane_change): fix debug marker (#5346) Signed-off-by: kosuke55 --- .../path_safety_checker/safety_check.cpp | 26 ++++++++----------- 1 file changed, 11 insertions(+), 15 deletions(-) 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 e36115c62e148..08ebd01ba5d05 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 @@ -157,7 +157,7 @@ Polygon2d createExtendedPolygon( { debug.forward_lon_offset = forward_lon_offset; debug.backward_lon_offset = backward_lon_offset; - debug.lat_offset = (left_lat_offset + right_lat_offset) / 2; + debug.lat_offset = std::max(std::abs(left_lat_offset), std::abs(right_lat_offset)); } const auto p1 = @@ -324,17 +324,15 @@ std::vector getCollidedPolygons( const auto & ego_polygon = interpolated_data->poly; const auto & ego_velocity = interpolated_data->velocity; - { - debug.expected_ego_pose = ego_pose; - debug.expected_obj_pose = obj_pose; - debug.extended_ego_polygon = ego_polygon; - debug.extended_obj_polygon = obj_polygon; - } - // check overlap if (boost::geometry::overlaps(ego_polygon, obj_polygon)) { debug.unsafe_reason = "overlap_polygon"; collided_polygons.push_back(obj_polygon); + + debug.expected_ego_pose = ego_pose; + debug.expected_obj_pose = obj_pose; + debug.extended_ego_polygon = ego_polygon; + debug.extended_obj_polygon = obj_polygon; continue; } @@ -366,19 +364,17 @@ std::vector getCollidedPolygons( : createExtendedPolygon( obj_pose, target_object.shape, lon_offset, lat_margin, is_stopped_object, debug); - { + // check overlap with extended polygon + if (boost::geometry::overlaps(extended_ego_polygon, extended_obj_polygon)) { + debug.unsafe_reason = "overlap_extended_polygon"; + collided_polygons.push_back(obj_polygon); + debug.rss_longitudinal = rss_dist; debug.inter_vehicle_distance = min_lon_length; debug.extended_ego_polygon = extended_ego_polygon; debug.extended_obj_polygon = extended_obj_polygon; debug.is_front = is_object_front; } - - // check overlap with extended polygon - if (boost::geometry::overlaps(extended_ego_polygon, extended_obj_polygon)) { - debug.unsafe_reason = "overlap_extended_polygon"; - collided_polygons.push_back(obj_polygon); - } } return collided_polygons; From 8530b6bb4155b040f8ff845ec030aa836218b94e Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 18 Oct 2023 21:04:44 +0900 Subject: [PATCH 021/202] feat(pid_longitudinal_controller): transit to STOPPED even if the sign of the ego velocity goes opposite (#5255) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * feat(pid_longitudinal_controller): transit to STOPPED even if the sign of the ego velocity goes opposite Signed-off-by: Takayuki Murooka * pid_longitudinal_controller.cpp を更新 Co-authored-by: Takamasa Horibe * fix Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka Co-authored-by: Takamasa Horibe --- .../src/pid_longitudinal_controller.cpp | 23 ++++++++++++++++--- 1 file changed, 20 insertions(+), 3 deletions(-) diff --git a/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp b/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp index b80874a8a2e57..a134fd775155b 100644 --- a/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp +++ b/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp @@ -501,9 +501,26 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d m_enable_keep_stopped_until_steer_convergence && !lateral_sync_data_.is_steer_converged; const bool stopping_condition = stop_dist < p.stopping_state_stop_dist; - if ( - std::fabs(current_vel) > p.stopped_state_entry_vel || - std::fabs(current_acc) > p.stopped_state_entry_acc) { + + const bool is_stopped = std::abs(current_vel) < p.stopped_state_entry_vel && + std::abs(current_acc) < p.stopped_state_entry_acc; + // Case where the ego slips in the opposite direction of the gear due to e.g. a slope is also + // considered as a stop + const bool is_not_running = [&]() { + if (control_data.shift == Shift::Forward) { + if (is_stopped || current_vel < 0.0) { + // NOTE: Stopped or moving backward + return true; + } + } else { + if (is_stopped || 0.0 < current_vel) { + // NOTE: Stopped or moving forward + return true; + } + } + return false; + }(); + if (!is_not_running) { m_last_running_time = std::make_shared(clock_->now()); } const bool stopped_condition = From 89db33569a0b9a5e01c752b69dc3f4014db1be15 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 18 Oct 2023 21:38:00 +0900 Subject: [PATCH 022/202] feat(lane_change): disable cancel when ego is out of current lanes (#5348) --- .../src/scene_module/lane_change/interface.cpp | 2 +- .../src/scene_module/lane_change/normal.cpp | 6 ++++++ 2 files changed, 7 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp index 51875952d40fb..0a0cc3436bce7 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp @@ -147,7 +147,7 @@ ModuleStatus LaneChangeInterface::updateState() return ModuleStatus::RUNNING; } - if (module_type_->isEgoOnPreparePhase()) { + if (module_type_->isEgoOnPreparePhase() && module_type_->isAbleToReturnCurrentLane()) { RCLCPP_WARN_STREAM_THROTTLE( getLogger().get_child(module_type_->getModuleTypeStr()), *clock_, 5000, "Lane change path is unsafe. Cancel lane change."); 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 ce07cda882692..de4afc9260da0 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 @@ -510,6 +510,12 @@ bool NormalLaneChange::isAbleToReturnCurrentLane() const return false; } + if (!utils::isEgoWithinOriginalLane( + status_.current_lanes, getEgoPose(), planner_data_->parameters, + lane_change_parameters_->cancel.overhang_tolerance)) { + return false; + } + const auto nearest_idx = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( status_.lane_change_path.path.points, getEgoPose(), planner_data_->parameters.ego_nearest_dist_threshold, From 2ad1d816fa1bd31e0976fc9679c98ae2a9d56d4b Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Wed, 18 Oct 2023 23:23:25 +0900 Subject: [PATCH 023/202] perf(drivable area expansion): use faster lateral offset and nearest line calculations (#5349) Signed-off-by: Maxime CLEMENT --- .../drivable_area_expansion.hpp | 5 ++- .../drivable_area_expansion/map_utils.hpp | 6 ++-- .../utils/drivable_area_expansion/types.hpp | 4 +++ .../drivable_area_expansion.cpp | 35 +++++++++++-------- .../drivable_area_expansion/map_utils.cpp | 14 +++++--- 5 files changed, 39 insertions(+), 25 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/drivable_area_expansion.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/drivable_area_expansion.hpp index 19ea89a3ce3c7..3f6f107cdce51 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/drivable_area_expansion.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/drivable_area_expansion.hpp @@ -68,14 +68,13 @@ void apply_bound_change_rate_limit( /// @brief calculate the maximum distance by which a bound can be expanded /// @param [in] path_poses input path /// @param [in] bound bound points -/// @param [in] uncrossable_lines lines that limit the bound expansion +/// @param [in] uncrossable_segments segments that limit the bound expansion, indexed in a Rtree /// @param [in] uncrossable_polygons polygons that limit the bound expansion /// @param [in] params parameters with the buffer distance to keep with lines, /// and the static maximum expansion distance std::vector calculate_maximum_distance( const std::vector & path_poses, const std::vector bound, - const std::vector & uncrossable_lines, - const std::vector & uncrossable_polygons, + const SegmentRtree & uncrossable_lines, const std::vector & uncrossable_polygons, const DrivableAreaExpansionParameters & params); /// @brief expand a bound by the given lateral distances away from the path diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/map_utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/map_utils.hpp index 6f96b83237310..8c6bdb8a6943b 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/map_utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/map_utils.hpp @@ -25,12 +25,12 @@ namespace drivable_area_expansion { -/// @brief Extract uncrossable linestrings from the lanelet map that are in range of ego +/// @brief Extract uncrossable segments from the lanelet map that are in range of ego /// @param[in] lanelet_map lanelet map /// @param[in] ego_point point of the current ego position /// @param[in] params parameters with linestring types that cannot be crossed and maximum range -/// @return the uncrossable linestrings -MultiLineString2d extract_uncrossable_lines( +/// @return the uncrossable segments stored in a rtree +SegmentRtree extract_uncrossable_segments( const lanelet::LaneletMap & lanelet_map, const Point & ego_point, const DrivableAreaExpansionParameters & params); diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/types.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/types.hpp index 7db92c163f567..8da1521db6c28 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/types.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/types.hpp @@ -22,6 +22,8 @@ #include #include +#include + namespace drivable_area_expansion { using autoware_auto_perception_msgs::msg::PredictedObjects; @@ -39,6 +41,8 @@ using tier4_autoware_utils::Point2d; using tier4_autoware_utils::Polygon2d; using tier4_autoware_utils::Segment2d; +typedef boost::geometry::index::rtree> SegmentRtree; + struct PointDistance { Point2d point; diff --git a/planning/behavior_path_planner/src/utils/drivable_area_expansion/drivable_area_expansion.cpp b/planning/behavior_path_planner/src/utils/drivable_area_expansion/drivable_area_expansion.cpp index 25cf917d27135..3008f98331c92 100644 --- a/planning/behavior_path_planner/src/utils/drivable_area_expansion/drivable_area_expansion.cpp +++ b/planning/behavior_path_planner/src/utils/drivable_area_expansion/drivable_area_expansion.cpp @@ -36,12 +36,10 @@ namespace drivable_area_expansion namespace { - Point2d convert_point(const Point & p) { return Point2d{p.x, p.y}; } - } // namespace void reuse_previous_poses( @@ -61,11 +59,17 @@ void reuse_previous_poses( const auto deviation = motion_utils::calcLateralOffset(prev_poses, path.points.front().point.pose.position); if (first_idx && deviation < params.max_reuse_deviation) { + LineString2d path_ls; + for (const auto & p : path.points) path_ls.push_back(convert_point(p.point.pose.position)); for (auto idx = *first_idx; idx < prev_poses.size(); ++idx) { - if ( - motion_utils::calcLateralOffset(path.points, prev_poses[idx].position) > - params.max_reuse_deviation) - break; + double lateral_offset = std::numeric_limits::max(); + for (auto segment_idx = 0LU; segment_idx + 1 < path_ls.size(); ++segment_idx) { + const auto projection = point_to_line_projection( + convert_point(prev_poses[idx].position), path_ls[segment_idx], + path_ls[segment_idx + 1]); + lateral_offset = std::min(projection.distance, lateral_offset); + } + if (lateral_offset > params.max_reuse_deviation) break; cropped_poses.push_back(prev_poses[idx]); cropped_curvatures.push_back(prev_curvatures[idx]); } @@ -172,8 +176,7 @@ void apply_bound_change_rate_limit( std::vector calculate_maximum_distance( const std::vector & path_poses, const std::vector bound, - const std::vector & uncrossable_lines, - const std::vector & uncrossable_polygons, + const SegmentRtree & uncrossable_segments, const std::vector & uncrossable_polygons, const DrivableAreaExpansionParameters & params) { // TODO(Maxime): improve performances (dont use bg::distance ? use rtree ?) @@ -183,9 +186,13 @@ std::vector calculate_maximum_distance( for (const auto & p : bound) bound_ls.push_back(convert_point(p)); for (const auto & p : path_poses) path_ls.push_back(convert_point(p.position)); for (auto i = 0UL; i + 1 < bound_ls.size(); ++i) { - const LineString2d segment_ls = {bound_ls[i], bound_ls[i + 1]}; - for (const auto & uncrossable_line : uncrossable_lines) { - const auto bound_to_line_dist = boost::geometry::distance(segment_ls, uncrossable_line); + const Segment2d segment_ls = {bound_ls[i], bound_ls[i + 1]}; + std::vector query_result; + boost::geometry::index::query( + uncrossable_segments, boost::geometry::index::nearest(segment_ls, 1), + std::back_inserter(query_result)); + if (!query_result.empty()) { + const auto bound_to_line_dist = boost::geometry::distance(segment_ls, query_result.front()); const auto dist_limit = std::max(0.0, bound_to_line_dist - params.avoid_linestring_dist); maximum_distances[i] = std::min(maximum_distances[i], dist_limit); maximum_distances[i + 1] = std::min(maximum_distances[i + 1], dist_limit); @@ -267,7 +274,7 @@ void expand_drivable_area( // crop first/last non deviating path_poses const auto & params = planner_data->drivable_area_expansion_parameters; const auto & route_handler = *planner_data->route_handler; - const auto uncrossable_lines = extract_uncrossable_lines( + const auto uncrossable_segments = extract_uncrossable_segments( *route_handler.getLaneletMapPtr(), planner_data->self_odometry->pose.pose.position, params); const auto uncrossable_polygons = create_object_footprints(*planner_data->dynamic_object, params); const auto preprocessing_ms = stop_watch.toc("preprocessing"); @@ -295,9 +302,9 @@ void expand_drivable_area( stop_watch.tic("max_dist"); const auto max_left_expansions = calculate_maximum_distance( - path_poses, path.left_bound, uncrossable_lines, uncrossable_polygons, params); + path_poses, path.left_bound, uncrossable_segments, uncrossable_polygons, params); const auto max_right_expansions = calculate_maximum_distance( - path_poses, path.right_bound, uncrossable_lines, uncrossable_polygons, params); + path_poses, path.right_bound, uncrossable_segments, uncrossable_polygons, params); for (auto i = 0LU; i < left_expansions.size(); ++i) left_expansions[i] = std::min(left_expansions[i], max_left_expansions[i]); for (auto i = 0LU; i < right_expansions.size(); ++i) diff --git a/planning/behavior_path_planner/src/utils/drivable_area_expansion/map_utils.cpp b/planning/behavior_path_planner/src/utils/drivable_area_expansion/map_utils.cpp index deeb787cf39f6..6ed14138c62e4 100644 --- a/planning/behavior_path_planner/src/utils/drivable_area_expansion/map_utils.cpp +++ b/planning/behavior_path_planner/src/utils/drivable_area_expansion/map_utils.cpp @@ -24,22 +24,26 @@ namespace drivable_area_expansion { -MultiLineString2d extract_uncrossable_lines( +SegmentRtree extract_uncrossable_segments( const lanelet::LaneletMap & lanelet_map, const Point & ego_point, const DrivableAreaExpansionParameters & params) { - MultiLineString2d uncrossable_lines_in_range; + SegmentRtree uncrossable_segments_in_range; LineString2d line; const auto ego_p = Point2d{ego_point.x, ego_point.y}; for (const auto & ls : lanelet_map.lineStringLayer) { if (has_types(ls, params.avoid_linestring_types)) { line.clear(); for (const auto & p : ls) line.push_back(Point2d{p.x(), p.y()}); - if (boost::geometry::distance(line, ego_p) < params.max_path_arc_length) - uncrossable_lines_in_range.push_back(line); + for (auto segment_idx = 0LU; segment_idx + 1 < line.size(); ++segment_idx) { + Segment2d segment = {line[segment_idx], line[segment_idx + 1]}; + if (boost::geometry::distance(segment, ego_p) < params.max_path_arc_length) { + uncrossable_segments_in_range.insert(segment); + } + } } } - return uncrossable_lines_in_range; + return uncrossable_segments_in_range; } bool has_types(const lanelet::ConstLineString3d & ls, const std::vector & types) From b0196439a149318a10f4cb3a22d2ee7a541ff886 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 19 Oct 2023 10:18:31 +0900 Subject: [PATCH 024/202] fix(goal_planner): mutex lock for all getter and setter of status (#5202) * fix(goal_planner): mutex lock for all getter and setter of status Signed-off-by: kosuke55 * use transaction instead of recursive_mutex Signed-off-by: kosuke55 fix Signed-off-by: kosuke55 * fix increment Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 --- .../goal_planner/goal_planner_module.hpp | 175 +++++-- .../utils/goal_planner/util.hpp | 2 +- .../goal_planner/goal_planner_module.cpp | 476 ++++++++++-------- .../src/utils/goal_planner/util.cpp | 2 +- 4 files changed, 396 insertions(+), 259 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp index a82cff16756f8..632872471ce29 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp @@ -74,28 +74,143 @@ enum class PathType { FREESPACE, }; -struct PullOverStatus +class PullOverStatus; // Forward declaration for Transaction +// class that locks the PullOverStatus when multiple values are being updated from +// an external source. +class Transaction { - std::shared_ptr pull_over_path{}; - std::shared_ptr lane_parking_pull_over_path{}; - size_t current_path_idx{0}; - bool require_increment_{true}; // if false, keep current path idx. - std::shared_ptr prev_stop_path{nullptr}; - std::shared_ptr prev_stop_path_after_approval{nullptr}; - // stop path after approval, stop path is not updated until safety is confirmed - lanelet::ConstLanelets current_lanes{}; // TODO(someone): explain - lanelet::ConstLanelets pull_over_lanes{}; // TODO(someone): explain - std::vector lanes{}; // current + pull_over - bool has_decided_path{false}; // if true, the path has is decided and safe against static objects - bool is_safe_static_objects{false}; // current path is safe against *static* objects - bool is_safe_dynamic_objects{false}; // current path is safe against *dynamic* objects - bool prev_is_safe{false}; - bool prev_is_safe_dynamic_objects{false}; - bool has_decided_velocity{false}; - bool has_requested_approval{false}; - bool is_ready{false}; +public: + explicit Transaction(PullOverStatus & status); + ~Transaction(); + +private: + PullOverStatus & status_; }; +#define DEFINE_SETTER_GETTER(TYPE, NAME) \ +public: \ + void set_##NAME(const TYPE & value) \ + { \ + if (!is_in_transaction_) { \ + const std::lock_guard lock(mutex_); \ + NAME##_ = value; \ + } else { \ + NAME##_ = value; \ + } \ + } \ + \ + TYPE get_##NAME() const \ + { \ + if (!is_in_transaction_) { \ + const std::lock_guard lock(mutex_); \ + return NAME##_; \ + } \ + return NAME##_; \ + } + +class PullOverStatus +{ +public: + // Reset all data members to their initial states + void reset() + { + const std::lock_guard lock(mutex_); + pull_over_path_ = nullptr; + lane_parking_pull_over_path_ = nullptr; + current_path_idx_ = 0; + require_increment_ = true; + prev_stop_path_ = nullptr; + prev_stop_path_after_approval_ = nullptr; + current_lanes_.clear(); + pull_over_lanes_.clear(); + lanes_.clear(); + has_decided_path_ = false; + is_safe_static_objects_ = false; + is_safe_dynamic_objects_ = false; + prev_is_safe_ = false; + prev_is_safe_dynamic_objects_ = false; + has_decided_velocity_ = false; + has_requested_approval_ = false; + is_ready_ = false; + } + + // lock all data members + Transaction startTransaction() { return Transaction(*this); } + + DEFINE_SETTER_GETTER(std::shared_ptr, pull_over_path) + DEFINE_SETTER_GETTER(std::shared_ptr, lane_parking_pull_over_path) + DEFINE_SETTER_GETTER(size_t, current_path_idx) + DEFINE_SETTER_GETTER(bool, require_increment) + DEFINE_SETTER_GETTER(std::shared_ptr, prev_stop_path) + DEFINE_SETTER_GETTER(std::shared_ptr, prev_stop_path_after_approval) + DEFINE_SETTER_GETTER(lanelet::ConstLanelets, current_lanes) + DEFINE_SETTER_GETTER(lanelet::ConstLanelets, pull_over_lanes) + DEFINE_SETTER_GETTER(std::vector, lanes) + DEFINE_SETTER_GETTER(bool, has_decided_path) + DEFINE_SETTER_GETTER(bool, is_safe_static_objects) + DEFINE_SETTER_GETTER(bool, is_safe_dynamic_objects) + DEFINE_SETTER_GETTER(bool, prev_is_safe) + DEFINE_SETTER_GETTER(bool, prev_is_safe_dynamic_objects) + DEFINE_SETTER_GETTER(bool, has_decided_velocity) + DEFINE_SETTER_GETTER(bool, has_requested_approval) + DEFINE_SETTER_GETTER(bool, is_ready) + DEFINE_SETTER_GETTER(std::shared_ptr, last_approved_time) + DEFINE_SETTER_GETTER(std::shared_ptr, last_increment_time) + DEFINE_SETTER_GETTER(std::shared_ptr, last_path_update_time) + DEFINE_SETTER_GETTER(std::shared_ptr, last_approved_pose) + DEFINE_SETTER_GETTER(std::optional, modified_goal_pose) + DEFINE_SETTER_GETTER(Pose, refined_goal_pose) + DEFINE_SETTER_GETTER(GoalCandidates, goal_candidates) + DEFINE_SETTER_GETTER(std::vector, pull_over_path_candidates) + DEFINE_SETTER_GETTER(std::optional, closest_start_pose) + + void push_goal_candidate(const GoalCandidate & goal_candidate) + { + std::lock_guard lock(mutex_); + goal_candidates_.push_back(goal_candidate); + } + +private: + std::shared_ptr pull_over_path_{nullptr}; + std::shared_ptr lane_parking_pull_over_path_{nullptr}; + size_t current_path_idx_{0}; + bool require_increment_{true}; + std::shared_ptr prev_stop_path_{nullptr}; + std::shared_ptr prev_stop_path_after_approval_{nullptr}; + lanelet::ConstLanelets current_lanes_{}; + lanelet::ConstLanelets pull_over_lanes_{}; + std::vector lanes_{}; + bool has_decided_path_{false}; + bool is_safe_static_objects_{false}; + bool is_safe_dynamic_objects_{false}; + bool prev_is_safe_{false}; + bool prev_is_safe_dynamic_objects_{false}; + bool has_decided_velocity_{false}; + bool has_requested_approval_{false}; + bool is_ready_{false}; + + // save last time and pose + std::shared_ptr last_approved_time_; + std::shared_ptr last_increment_time_; + std::shared_ptr last_path_update_time_; + std::shared_ptr last_approved_pose_; + + // goal modification + std::optional modified_goal_pose_; + Pose refined_goal_pose_{}; + GoalCandidates goal_candidates_{}; + + // pull over path + std::vector pull_over_path_candidates_; + std::optional closest_start_pose_; + + friend class Transaction; + mutable std::mutex mutex_; + bool is_in_transaction_{false}; +}; + +#undef DEFINE_SETTER_GETTER + struct FreespacePlannerDebugData { bool is_planning{false}; @@ -155,8 +270,6 @@ class GoalPlannerModule : public SceneModuleInterface bool canTransitIdleToRunningState() override { return false; } - PullOverStatus status_; - mutable StartGoalPlannerData goal_planner_data_; std::shared_ptr parameters_; @@ -174,29 +287,19 @@ class GoalPlannerModule : public SceneModuleInterface // goal searcher std::shared_ptr goal_searcher_; - std::optional modified_goal_pose_; - Pose refined_goal_pose_{}; - GoalCandidates goal_candidates_{}; // collision detector // need to be shared_ptr to be used in planner and goal searcher std::shared_ptr occupancy_grid_map_; - // pull over path - std::vector pull_over_path_candidates_; - std::optional closest_start_pose_; - // check stopped and stuck state std::deque odometry_buffer_stopped_; std::deque odometry_buffer_stuck_; tier4_autoware_utils::LinearRing2d vehicle_footprint_; - // save last time and pose - std::unique_ptr last_approved_time_; - std::unique_ptr last_increment_time_; - std::unique_ptr last_path_update_time_; - std::unique_ptr last_approved_pose_; + std::mutex mutex_; + PullOverStatus status_; // approximate distance from the start point to the end point of pull_over. // this is used as an assumed value to decelerate, etc., before generating the actual path. @@ -210,7 +313,6 @@ class GoalPlannerModule : public SceneModuleInterface // pre-generate lane parking paths in a separate thread rclcpp::TimerBase::SharedPtr lane_parking_timer_; rclcpp::CallbackGroup::SharedPtr lane_parking_timer_cb_group_; - std::mutex mutex_; // generate freespace parking paths in a separate thread rclcpp::TimerBase::SharedPtr freespace_parking_timer_; @@ -245,7 +347,6 @@ class GoalPlannerModule : public SceneModuleInterface bool hasFinishedCurrentPath(); bool isOnModifiedGoal() const; double calcModuleRequestLength() const; - void resetStatus(); bool needPathUpdate(const double path_update_duration) const; bool isStuck(); bool hasDecidedPath() const; @@ -268,8 +369,8 @@ class GoalPlannerModule : public SceneModuleInterface BehaviorModuleOutput planWithGoalModification(); BehaviorModuleOutput planWaitingApprovalWithGoalModification(); void selectSafePullOverPath(); - void sortPullOverPathCandidatesByGoalPriority( - std::vector & pull_over_path_candidates, + std::vector sortPullOverPathCandidatesByGoalPriority( + const std::vector & pull_over_path_candidates, const GoalCandidates & goal_candidates) const; // deal with pull over partial paths diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/util.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/util.hpp index 1dc6cc411a31f..062a84bcd5aef 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/util.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/util.hpp @@ -63,7 +63,7 @@ MarkerArray createPosesMarkerArray( MarkerArray createTextsMarkerArray( const std::vector & poses, std::string && ns, const std_msgs::msg::ColorRGBA & color); MarkerArray createGoalCandidatesMarkerArray( - GoalCandidates & goal_candidates, const std_msgs::msg::ColorRGBA & color); + const GoalCandidates & goal_candidates, const std_msgs::msg::ColorRGBA & color); MarkerArray createNumObjectsToAvoidTextsMarkerArray( const GoalCandidates & goal_candidates, std::string && ns, const std_msgs::msg::ColorRGBA & color); diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index c6e68f8e81af7..dc1ac1466397d 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -51,6 +51,18 @@ using tier4_autoware_utils::inverseTransformPose; namespace behavior_path_planner { +Transaction::Transaction(PullOverStatus & status) : status_(status) +{ + status_.mutex_.lock(); + status_.is_in_transaction_ = true; +} + +Transaction::~Transaction() +{ + status_.mutex_.unlock(); + status_.is_in_transaction_ = false; +} + GoalPlannerModule::GoalPlannerModule( const std::string & name, rclcpp::Node & node, const std::shared_ptr & parameters, @@ -113,16 +125,7 @@ GoalPlannerModule::GoalPlannerModule( freespace_parking_timer_cb_group_); } - resetStatus(); -} - -void GoalPlannerModule::resetStatus() -{ - PullOverStatus initial_status{}; - status_ = initial_status; - pull_over_path_candidates_.clear(); - closest_start_pose_.reset(); - goal_candidates_.clear(); + status_.reset(); } // This function is needed for waiting for planner_data_ @@ -139,17 +142,15 @@ void GoalPlannerModule::updateOccupancyGrid() void GoalPlannerModule::onTimer() { // already generated pull over candidate paths - if (!pull_over_path_candidates_.empty()) { + if (!status_.get_pull_over_path_candidates().empty()) { return; } // goals are not yet available. - if (goal_candidates_.empty()) { + if (status_.get_goal_candidates().empty()) { return; } - mutex_.lock(); - const auto goal_candidates = goal_candidates_; - mutex_.unlock(); + const auto goal_candidates = status_.get_goal_candidates(); // generate valid pull over path candidates and calculate closest start pose const auto current_lanes = utils::getExtendedCurrentLanes( @@ -177,7 +178,6 @@ void GoalPlannerModule::onTimer() } } }; - // plan candidate paths and set them to the member variable if (parameters_->path_priority == "efficient_path") { for (const auto & planner : pull_over_planners_) { @@ -199,10 +199,9 @@ void GoalPlannerModule::onTimer() } // set member variables - mutex_.lock(); - pull_over_path_candidates_ = path_candidates; - closest_start_pose_ = closest_start_pose; - mutex_.unlock(); + const auto transaction = status_.startTransaction(); + status_.set_pull_over_path_candidates(path_candidates); + status_.set_closest_start_pose(closest_start_pose); } void GoalPlannerModule::onFreespaceParkingTimer() @@ -457,19 +456,23 @@ ModuleStatus GoalPlannerModule::updateState() bool GoalPlannerModule::planFreespacePath() { - mutex_.lock(); goal_searcher_->setPlannerData(planner_data_); - goal_searcher_->update(goal_candidates_); - const auto goal_candidates = goal_candidates_; - debug_data_.freespace_planner.num_goal_candidates = goal_candidates.size(); - debug_data_.freespace_planner.is_planning = true; - mutex_.unlock(); + auto goal_candidates = status_.get_goal_candidates(); + goal_searcher_->update(goal_candidates); + status_.set_goal_candidates(goal_candidates); + + { + const std::lock_guard lock(mutex_); + debug_data_.freespace_planner.num_goal_candidates = goal_candidates.size(); + debug_data_.freespace_planner.is_planning = true; + } for (size_t i = 0; i < goal_candidates.size(); i++) { const auto goal_candidate = goal_candidates.at(i); - mutex_.lock(); - debug_data_.freespace_planner.current_goal_idx = i; - mutex_.unlock(); + { + const std::lock_guard lock(mutex_); + debug_data_.freespace_planner.current_goal_idx = i; + } if (!goal_candidate.is_safe) { continue; @@ -480,17 +483,22 @@ bool GoalPlannerModule::planFreespacePath() if (!freespace_path) { continue; } - mutex_.lock(); - status_.pull_over_path = std::make_shared(*freespace_path); - status_.current_path_idx = 0; - status_.is_safe_static_objects = true; - modified_goal_pose_ = goal_candidate; - last_path_update_time_ = std::make_unique(clock_->now()); - debug_data_.freespace_planner.is_planning = false; - mutex_.unlock(); + + { + const auto transaction = status_.startTransaction(); + status_.set_pull_over_path(std::make_shared(*freespace_path)); + status_.set_current_path_idx(0); + status_.set_is_safe_static_objects(true); + status_.set_modified_goal_pose(goal_candidate); + status_.set_last_path_update_time(std::make_shared(clock_->now())); + const std::lock_guard lock(mutex_); + debug_data_.freespace_planner.is_planning = false; + } + return true; } + const std::lock_guard lock(mutex_); debug_data_.freespace_planner.is_planning = false; return false; } @@ -502,11 +510,11 @@ void GoalPlannerModule::returnToLaneParking() return; } - if (!status_.lane_parking_pull_over_path) { + if (!status_.get_lane_parking_pull_over_path()) { return; } - const PathWithLaneId path = status_.lane_parking_pull_over_path->getFullPath(); + const PathWithLaneId path = status_.get_lane_parking_pull_over_path()->getFullPath(); if (checkCollision(path)) { return; } @@ -519,13 +527,14 @@ void GoalPlannerModule::returnToLaneParking() return; } - mutex_.lock(); - status_.is_safe_static_objects = true; - status_.has_decided_path = false; - status_.pull_over_path = status_.lane_parking_pull_over_path; - status_.current_path_idx = 0; - last_path_update_time_ = std::make_unique(clock_->now()); - mutex_.unlock(); + { + const auto transaction = status_.startTransaction(); + status_.set_is_safe_static_objects(true); + status_.set_has_decided_path(false); + status_.set_pull_over_path(status_.get_lane_parking_pull_over_path()); + status_.set_current_path_idx(0); + status_.set_last_path_update_time(std::make_shared(clock_->now())); + } RCLCPP_INFO(getLogger(), "return to lane parking"); } @@ -537,22 +546,22 @@ void GoalPlannerModule::generateGoalCandidates() // with old architecture, module instance is not cleared when new route is received // so need to reset status here. // todo: move this check out of this function after old architecture is removed - if (!goal_candidates_.empty()) { + if (!status_.get_goal_candidates().empty()) { return; } // calculate goal candidates const Pose goal_pose = route_handler->getOriginalGoalPose(); - refined_goal_pose_ = calcRefinedGoal(goal_pose); + status_.set_refined_goal_pose(calcRefinedGoal(goal_pose)); if (goal_planner_utils::isAllowedGoalModification(route_handler)) { goal_searcher_->setPlannerData(planner_data_); - goal_searcher_->setReferenceGoal(refined_goal_pose_); - goal_candidates_ = goal_searcher_->search(); + goal_searcher_->setReferenceGoal(status_.get_refined_goal_pose()); + status_.set_goal_candidates(goal_searcher_->search()); } else { GoalCandidate goal_candidate{}; goal_candidate.goal_pose = goal_pose; goal_candidate.distance_from_original_goal = 0.0; - goal_candidates_.push_back(goal_candidate); + status_.push_goal_candidate(goal_candidate); } } @@ -573,10 +582,12 @@ BehaviorModuleOutput GoalPlannerModule::plan() } } -void GoalPlannerModule::sortPullOverPathCandidatesByGoalPriority( - std::vector & pull_over_path_candidates, +std::vector GoalPlannerModule::sortPullOverPathCandidatesByGoalPriority( + const std::vector & pull_over_path_candidates, const GoalCandidates & goal_candidates) const { + auto sorted_pull_over_path_candidates = pull_over_path_candidates; + // Create a map of goal_id to its index in goal_candidates std::map goal_id_to_index; for (size_t i = 0; i < goal_candidates.size(); ++i) { @@ -585,7 +596,7 @@ void GoalPlannerModule::sortPullOverPathCandidatesByGoalPriority( // Sort pull_over_path_candidates based on the order in goal_candidates std::stable_sort( - pull_over_path_candidates.begin(), pull_over_path_candidates.end(), + sorted_pull_over_path_candidates.begin(), sorted_pull_over_path_candidates.end(), [&goal_id_to_index](const auto & a, const auto & b) { return goal_id_to_index[a.goal_id] < goal_id_to_index[b.goal_id]; }); @@ -593,7 +604,7 @@ void GoalPlannerModule::sortPullOverPathCandidatesByGoalPriority( // Sort pull_over_path_candidates based on the order in efficient_path_order if (parameters_->path_priority == "efficient_path") { std::stable_sort( - pull_over_path_candidates.begin(), pull_over_path_candidates.end(), + sorted_pull_over_path_candidates.begin(), sorted_pull_over_path_candidates.end(), [this](const auto & a, const auto & b) { const auto & order = parameters_->efficient_path_order; const auto a_pos = std::find(order.begin(), order.end(), magic_enum::enum_name(a.type)); @@ -601,20 +612,27 @@ void GoalPlannerModule::sortPullOverPathCandidatesByGoalPriority( return a_pos < b_pos; }); } + + return sorted_pull_over_path_candidates; } void GoalPlannerModule::selectSafePullOverPath() { // select safe lane pull over path from candidates - mutex_.lock(); - goal_searcher_->setPlannerData(planner_data_); - goal_searcher_->update(goal_candidates_); - sortPullOverPathCandidatesByGoalPriority(pull_over_path_candidates_, goal_candidates_); - const auto pull_over_path_candidates = pull_over_path_candidates_; - const auto goal_candidates = goal_candidates_; - mutex_.unlock(); + std::vector pull_over_path_candidates{}; + GoalCandidates goal_candidates{}; + { + const auto transaction = status_.startTransaction(); + goal_searcher_->setPlannerData(planner_data_); + goal_candidates = status_.get_goal_candidates(); + goal_searcher_->update(goal_candidates); + status_.set_goal_candidates(goal_candidates); + status_.set_pull_over_path_candidates(sortPullOverPathCandidatesByGoalPriority( + status_.get_pull_over_path_candidates(), status_.get_goal_candidates())); + pull_over_path_candidates = status_.get_pull_over_path_candidates(); + status_.set_is_safe_static_objects(false); + } - status_.is_safe_static_objects = false; for (const auto & pull_over_path : pull_over_path_candidates) { // check if goal is safe const auto goal_candidate_it = std::find_if( @@ -633,71 +651,69 @@ void GoalPlannerModule::selectSafePullOverPath() continue; } - status_.is_safe_static_objects = true; - mutex_.lock(); - status_.pull_over_path = std::make_shared(pull_over_path); - status_.current_path_idx = 0; - status_.lane_parking_pull_over_path = status_.pull_over_path; - modified_goal_pose_ = *goal_candidate_it; - last_path_update_time_ = std::make_unique(clock_->now()); - mutex_.unlock(); + // found safe pull over path + { + const auto transaction = status_.startTransaction(); + status_.set_is_safe_static_objects(true); + status_.set_pull_over_path(std::make_shared(pull_over_path)); + status_.set_current_path_idx(0); + status_.set_lane_parking_pull_over_path(status_.get_pull_over_path()); + status_.set_modified_goal_pose(*goal_candidate_it); + status_.set_last_path_update_time(std::make_shared(clock_->now())); + } break; } + if (!status_.get_is_safe_static_objects()) { + return; + } + // decelerate before the search area start - if (status_.is_safe_static_objects) { - const auto search_start_offset_pose = calcLongitudinalOffsetPose( - status_.pull_over_path->getFullPath().points, refined_goal_pose_.position, - -parameters_->backward_goal_search_length - planner_data_->parameters.base_link2front - - approximate_pull_over_distance_); - auto & first_path = status_.pull_over_path->partial_paths.front(); - - if (search_start_offset_pose) { - decelerateBeforeSearchStart(*search_start_offset_pose, first_path); - } else { - // if already passed the search start offset pose, set pull_over_velocity to first_path. - const auto min_decel_distance = calcFeasibleDecelDistance( - planner_data_, parameters_->maximum_deceleration, parameters_->maximum_jerk, - parameters_->pull_over_velocity); - for (auto & p : first_path.points) { - const double distance_from_ego = calcSignedArcLengthFromEgo(first_path, p.point.pose); - if (min_decel_distance && distance_from_ego < *min_decel_distance) { - continue; - } - p.point.longitudinal_velocity_mps = std::min( - p.point.longitudinal_velocity_mps, static_cast(parameters_->pull_over_velocity)); + const auto search_start_offset_pose = calcLongitudinalOffsetPose( + status_.get_pull_over_path()->getFullPath().points, status_.get_refined_goal_pose().position, + -parameters_->backward_goal_search_length - planner_data_->parameters.base_link2front - + approximate_pull_over_distance_); + auto & first_path = status_.get_pull_over_path()->partial_paths.front(); + if (search_start_offset_pose) { + decelerateBeforeSearchStart(*search_start_offset_pose, first_path); + } else { + // if already passed the search start offset pose, set pull_over_velocity to first_path. + const auto min_decel_distance = calcFeasibleDecelDistance( + planner_data_, parameters_->maximum_deceleration, parameters_->maximum_jerk, + parameters_->pull_over_velocity); + for (auto & p : first_path.points) { + const double distance_from_ego = calcSignedArcLengthFromEgo(first_path, p.point.pose); + if (min_decel_distance && distance_from_ego < *min_decel_distance) { + continue; } + p.point.longitudinal_velocity_mps = std::min( + p.point.longitudinal_velocity_mps, static_cast(parameters_->pull_over_velocity)); } } - - // generate drivable area for each partial path - for (auto & path : status_.pull_over_path->partial_paths) { - const size_t ego_idx = planner_data_->findEgoIndex(path.points); - utils::clipPathLength(path, ego_idx, planner_data_->parameters); - } } void GoalPlannerModule::setLanes() { - status_.current_lanes = utils::getExtendedCurrentLanes( + const auto transaction = status_.startTransaction(); + status_.set_current_lanes(utils::getExtendedCurrentLanes( planner_data_, parameters_->backward_goal_search_length, parameters_->forward_goal_search_length, - /*forward_only_in_route*/ false); - status_.pull_over_lanes = goal_planner_utils::getPullOverLanes( + /*forward_only_in_route*/ false)); + status_.set_pull_over_lanes(goal_planner_utils::getPullOverLanes( *(planner_data_->route_handler), left_side_parking_, parameters_->backward_goal_search_length, - parameters_->forward_goal_search_length); - status_.lanes = - utils::generateDrivableLanesWithShoulderLanes(status_.current_lanes, status_.pull_over_lanes); + parameters_->forward_goal_search_length)); + status_.set_lanes(utils::generateDrivableLanesWithShoulderLanes( + status_.get_current_lanes(), status_.get_pull_over_lanes())); } void GoalPlannerModule::setOutput(BehaviorModuleOutput & output) { - if (!status_.is_safe_static_objects) { + if (!status_.get_is_safe_static_objects()) { // situation : not safe against static objects use stop_path setStopPath(output); } else if ( parameters_->safety_check_params.enable_safety_check && !isSafePath() && - status_.has_decided_path && isActivated()) { + status_.get_has_decided_path() && isActivated()) { // situation : not safe against dynamic objects after approval // insert stop point in current path if ego is able to stop with acceleration and jerk // constraints @@ -722,36 +738,37 @@ void GoalPlannerModule::setOutput(BehaviorModuleOutput & output) setModifiedGoal(output); // set hazard and turn signal - if (status_.has_decided_path) { + if (status_.get_has_decided_path()) { setTurnSignalInfo(output); } // for the next loop setOutput(). // this is used to determine whether to generate a new stop path or keep the current stop path. - status_.prev_is_safe = status_.is_safe_static_objects; - status_.prev_is_safe_dynamic_objects = - parameters_->safety_check_params.enable_safety_check ? isSafePath() : true; + const auto transaction = status_.startTransaction(); + status_.set_prev_is_safe(status_.get_is_safe_static_objects()); + status_.set_prev_is_safe_dynamic_objects( + parameters_->safety_check_params.enable_safety_check ? isSafePath() : true); } void GoalPlannerModule::setStopPath(BehaviorModuleOutput & output) { - if (status_.prev_is_safe || status_.prev_stop_path == nullptr) { + if (status_.get_prev_is_safe() || !status_.get_prev_stop_path()) { // safe -> not_safe or no prev_stop_path: generate new stop_path output.path = std::make_shared(generateStopPath()); - status_.prev_stop_path = output.path; + const auto transaction = status_.startTransaction(); + status_.set_prev_stop_path(output.path); // set stop path as pull over path - mutex_.lock(); - PullOverPath pull_over_path{}; - status_.pull_over_path = std::make_shared(pull_over_path); - status_.current_path_idx = 0; - status_.pull_over_path->partial_paths.push_back(*output.path); - last_path_update_time_ = std::make_unique(clock_->now()); - mutex_.unlock(); + auto stop_pull_over_path = std::make_shared(); + stop_pull_over_path->partial_paths.push_back(*output.path); + status_.set_pull_over_path(stop_pull_over_path); + status_.set_current_path_idx(0); + status_.set_last_path_update_time(std::make_shared(clock_->now())); + RCLCPP_WARN_THROTTLE( getLogger(), *clock_, 5000, "Not found safe pull_over path, generate stop path"); } else { // not_safe -> not_safe: use previous stop path - output.path = status_.prev_stop_path; + output.path = status_.get_prev_stop_path(); RCLCPP_WARN_THROTTLE( getLogger(), *clock_, 5000, "Not found safe pull_over path, use previous stop path"); } @@ -761,7 +778,7 @@ void GoalPlannerModule::setStopPath(BehaviorModuleOutput & output) void GoalPlannerModule::setStopPathFromCurrentPath(BehaviorModuleOutput & output) { // safe or not safe(no feasible stop_path found) -> not_safe: try to find new feasible stop_path - if (status_.prev_is_safe_dynamic_objects || status_.prev_stop_path_after_approval == nullptr) { + if (status_.get_prev_is_safe_dynamic_objects() || !status_.get_prev_stop_path_after_approval()) { auto current_path = getCurrentPath(); const auto stop_path = behavior_path_planner::utils::start_goal_planner_common::generateFeasibleStopPath( @@ -769,7 +786,7 @@ void GoalPlannerModule::setStopPathFromCurrentPath(BehaviorModuleOutput & output parameters_->maximum_jerk_for_stop); if (stop_path) { output.path = std::make_shared(*stop_path); - status_.prev_stop_path_after_approval = output.path; + status_.set_prev_stop_path_after_approval(output.path); RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 5000, "Collision detected, generate stop path"); } else { output.path = std::make_shared(getCurrentPath()); @@ -777,11 +794,10 @@ void GoalPlannerModule::setStopPathFromCurrentPath(BehaviorModuleOutput & output getLogger(), *clock_, 5000, "Collision detected, no feasible stop path found, cannot stop."); } - std::lock_guard lock(mutex_); - last_path_update_time_ = std::make_unique(clock_->now()); + status_.set_last_path_update_time(std::make_shared(clock_->now())); } else { // not_safe safe(no feasible stop path found) -> not_safe: use previous stop path - output.path = status_.prev_stop_path_after_approval; + output.path = status_.get_prev_stop_path_after_approval(); RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 5000, "Collision detected, use previous stop path"); } output.reference_path = getPreviousModuleOutput().reference_path; @@ -789,13 +805,13 @@ void GoalPlannerModule::setStopPathFromCurrentPath(BehaviorModuleOutput & output void GoalPlannerModule::setDrivableAreaInfo(BehaviorModuleOutput & output) const { - if (status_.pull_over_path->type == PullOverPlannerType::FREESPACE) { + if (status_.get_pull_over_path()->type == PullOverPlannerType::FREESPACE) { const double drivable_area_margin = planner_data_->parameters.vehicle_width; output.drivable_area_info.drivable_margin = planner_data_->parameters.vehicle_width / 2.0 + drivable_area_margin; } else { const auto target_drivable_lanes = utils::getNonOverlappingExpandedLanes( - *output.path, status_.lanes, planner_data_->drivable_area_expansion_parameters); + *output.path, status_.get_lanes(), planner_data_->drivable_area_expansion_parameters); DrivableAreaInfo current_drivable_area_info; current_drivable_area_info.drivable_lanes = target_drivable_lanes; @@ -807,10 +823,10 @@ void GoalPlannerModule::setDrivableAreaInfo(BehaviorModuleOutput & output) const void GoalPlannerModule::setModifiedGoal(BehaviorModuleOutput & output) const { const auto & route_handler = planner_data_->route_handler; - if (status_.is_safe_static_objects) { + if (status_.get_is_safe_static_objects()) { PoseWithUuidStamped modified_goal{}; modified_goal.uuid = route_handler->getRouteUuid(); - modified_goal.pose = modified_goal_pose_->goal_pose; + modified_goal.pose = status_.get_modified_goal_pose()->goal_pose; modified_goal.header = route_handler->getRouteHeader(); output.modified_goal = modified_goal; } else { @@ -850,12 +866,12 @@ void GoalPlannerModule::updateSteeringFactor( bool GoalPlannerModule::hasDecidedPath() const { // once decided, keep the decision - if (status_.has_decided_path) { + if (status_.get_has_decided_path()) { return true; } // if path is not safe, not decided - if (!status_.is_safe_static_objects) { + if (!status_.get_is_safe_static_objects()) { return false; } @@ -867,10 +883,10 @@ bool GoalPlannerModule::hasDecidedPath() const return false; } const size_t start_pose_segment_idx = motion_utils::findNearestSegmentIndex( - getCurrentPath().points, status_.pull_over_path->start_pose.position); + getCurrentPath().points, status_.get_pull_over_path()->start_pose.position); const double dist_to_parking_start_pose = calcSignedArcLength( getCurrentPath().points, current_pose.position, *ego_segment_idx, - status_.pull_over_path->start_pose.position, start_pose_segment_idx); + status_.get_pull_over_path()->start_pose.position, start_pose_segment_idx); return dist_to_parking_start_pose < parameters_->decide_path_distance; } @@ -879,15 +895,15 @@ void GoalPlannerModule::decideVelocity() const double current_vel = planner_data_->self_odometry->twist.twist.linear.x; // decide velocity to guarantee turn signal lighting time - if (!status_.has_decided_velocity) { - auto & first_path = status_.pull_over_path->partial_paths.front(); + if (!status_.get_has_decided_velocity()) { + auto & first_path = status_.get_pull_over_path()->partial_paths.front(); const auto vel = static_cast(std::max(current_vel, parameters_->pull_over_minimum_velocity)); for (auto & p : first_path.points) { p.point.longitudinal_velocity_mps = std::min(p.point.longitudinal_velocity_mps, vel); } } - status_.has_decided_velocity = true; + status_.set_has_decided_velocity(true); } BehaviorModuleOutput GoalPlannerModule::planWithGoalModification() @@ -901,21 +917,26 @@ BehaviorModuleOutput GoalPlannerModule::planWithGoalModification() setLanes(); // Check if it needs to decide path - status_.has_decided_path = hasDecidedPath(); + status_.set_has_decided_path(hasDecidedPath()); // Use decided path - if (status_.has_decided_path) { + if (status_.get_has_decided_path()) { if (isActivated() && isWaitingApproval()) { - last_approved_time_ = std::make_unique(clock_->now()); - last_approved_pose_ = std::make_unique(planner_data_->self_odometry->pose.pose); + { + const auto transaction = status_.startTransaction(); + status_.set_last_approved_time(std::make_shared(clock_->now())); + status_.set_last_approved_pose( + std::make_shared(planner_data_->self_odometry->pose.pose)); + } clearWaitingApproval(); decideVelocity(); } transitionToNextPathIfFinishingCurrentPath(); - } else if (!pull_over_path_candidates_.empty() && needPathUpdate(path_update_duration)) { + } else if ( + !status_.get_pull_over_path_candidates().empty() && needPathUpdate(path_update_duration)) { // if the final path is not decided and enough time has passed since last path update, // select safe path from lane parking pull over path candidates - // and set it to status_.pull_over_path + // and set it to status_.get_pull_over_path() selectSafePullOverPath(); } // else: stop path is generated and set by setOutput() @@ -923,21 +944,21 @@ BehaviorModuleOutput GoalPlannerModule::planWithGoalModification() // set output and status BehaviorModuleOutput output{}; setOutput(output); - path_candidate_ = std::make_shared(status_.pull_over_path->getFullPath()); + path_candidate_ = std::make_shared(status_.get_pull_over_path()->getFullPath()); path_reference_ = getPreviousModuleOutput().reference_path; // return to lane parking if it is possible - if (status_.pull_over_path->type == PullOverPlannerType::FREESPACE) { + if (status_.get_pull_over_path()->type == PullOverPlannerType::FREESPACE) { returnToLaneParking(); } const auto distance_to_path_change = calcDistanceToPathChange(); - if (status_.has_decided_path) { + if (status_.get_has_decided_path()) { updateRTCStatus(distance_to_path_change.first, distance_to_path_change.second); } // TODO(tkhmy) add handle status TRYING updateSteeringFactor( - {status_.pull_over_path->start_pose, modified_goal_pose_->goal_pose}, + {status_.get_pull_over_path()->start_pose, status_.get_modified_goal_pose()->goal_pose}, {distance_to_path_change.first, distance_to_path_change.second}, SteeringFactor::TURNING); // For debug @@ -947,7 +968,7 @@ BehaviorModuleOutput GoalPlannerModule::planWithGoalModification() printParkingPositionError(); } - setStopReason(StopReason::GOAL_PLANNER, status_.pull_over_path->getFullPath()); + setStopReason(StopReason::GOAL_PLANNER, status_.get_pull_over_path()->getFullPath()); return output; } @@ -976,20 +997,21 @@ BehaviorModuleOutput GoalPlannerModule::planWaitingApprovalWithGoalModification( out.modified_goal = plan().modified_goal; // update status_ out.path = std::make_shared(generateStopPath()); out.reference_path = getPreviousModuleOutput().reference_path; - path_candidate_ = status_.is_safe_static_objects - ? std::make_shared(status_.pull_over_path->getFullPath()) - : out.path; + path_candidate_ = + status_.get_is_safe_static_objects() + ? std::make_shared(status_.get_pull_over_path()->getFullPath()) + : out.path; path_reference_ = getPreviousModuleOutput().reference_path; const auto distance_to_path_change = calcDistanceToPathChange(); // generate drivable area info for new architecture - if (status_.pull_over_path->type == PullOverPlannerType::FREESPACE) { + if (status_.get_pull_over_path()->type == PullOverPlannerType::FREESPACE) { const double drivable_area_margin = planner_data_->parameters.vehicle_width; out.drivable_area_info.drivable_margin = planner_data_->parameters.vehicle_width / 2.0 + drivable_area_margin; } else { const auto target_drivable_lanes = utils::getNonOverlappingExpandedLanes( - *out.path, status_.lanes, planner_data_->drivable_area_expansion_parameters); + *out.path, status_.get_lanes(), planner_data_->drivable_area_expansion_parameters); DrivableAreaInfo current_drivable_area_info; current_drivable_area_info.drivable_lanes = target_drivable_lanes; @@ -997,21 +1019,21 @@ BehaviorModuleOutput GoalPlannerModule::planWaitingApprovalWithGoalModification( current_drivable_area_info, getPreviousModuleOutput().drivable_area_info); } - if (status_.has_decided_path) { + if (status_.get_has_decided_path()) { updateRTCStatus(distance_to_path_change.first, distance_to_path_change.second); } updateSteeringFactor( - {status_.pull_over_path->start_pose, modified_goal_pose_->goal_pose}, + {status_.get_pull_over_path()->start_pose, status_.get_modified_goal_pose()->goal_pose}, {distance_to_path_change.first, distance_to_path_change.second}, SteeringFactor::APPROACHING); - setStopReason(StopReason::GOAL_PLANNER, status_.pull_over_path->getFullPath()); + setStopReason(StopReason::GOAL_PLANNER, status_.get_pull_over_path()->getFullPath()); return out; } std::pair GoalPlannerModule::calcDistanceToPathChange() const { - const auto & full_path = status_.pull_over_path->getFullPath(); + const auto & full_path = status_.get_pull_over_path()->getFullPath(); const auto ego_segment_idx = motion_utils::findNearestSegmentIndex( full_path.points, planner_data_->self_odometry->pose.pose, std::numeric_limits::max(), @@ -1021,15 +1043,15 @@ std::pair GoalPlannerModule::calcDistanceToPathChange() const } const size_t start_pose_segment_idx = motion_utils::findNearestSegmentIndex( - full_path.points, status_.pull_over_path->start_pose.position); + full_path.points, status_.get_pull_over_path()->start_pose.position); const double dist_to_parking_start_pose = calcSignedArcLength( full_path.points, planner_data_->self_odometry->pose.pose.position, *ego_segment_idx, - status_.pull_over_path->start_pose.position, start_pose_segment_idx); + status_.get_pull_over_path()->start_pose.position, start_pose_segment_idx); const size_t goal_pose_segment_idx = motion_utils::findNearestSegmentIndex( - full_path.points, modified_goal_pose_->goal_pose.position); + full_path.points, status_.get_modified_goal_pose()->goal_pose.position); const double dist_to_parking_finish_pose = calcSignedArcLength( full_path.points, planner_data_->self_odometry->pose.pose.position, *ego_segment_idx, - modified_goal_pose_->goal_pose.position, goal_pose_segment_idx); + status_.get_modified_goal_pose()->goal_pose.position, goal_pose_segment_idx); return {dist_to_parking_start_pose, dist_to_parking_finish_pose}; } @@ -1047,17 +1069,17 @@ PathWithLaneId GoalPlannerModule::generateStopPath() const double current_vel = planner_data_->self_odometry->twist.twist.linear.x; const double pull_over_velocity = parameters_->pull_over_velocity; - if (status_.current_lanes.empty()) { + if (status_.get_current_lanes().empty()) { return PathWithLaneId{}; } // generate reference path const auto s_current = - lanelet::utils::getArcCoordinates(status_.current_lanes, current_pose).length; + lanelet::utils::getArcCoordinates(status_.get_current_lanes(), current_pose).length; const double s_start = std::max(0.0, s_current - common_parameters.backward_path_length); const double s_end = s_current + common_parameters.forward_path_length; auto reference_path = - route_handler->getCenterLinePath(status_.current_lanes, s_start, s_end, true); + route_handler->getCenterLinePath(status_.get_current_lanes(), s_start, s_end, true); // if not approved stop road lane. // stop point priority is @@ -1068,17 +1090,20 @@ PathWithLaneId GoalPlannerModule::generateStopPath() // difference between the outer and inner sides) // 4. feasible stop const auto search_start_offset_pose = calcLongitudinalOffsetPose( - reference_path.points, refined_goal_pose_.position, + reference_path.points, status_.get_refined_goal_pose().position, -parameters_->backward_goal_search_length - common_parameters.base_link2front - approximate_pull_over_distance_); - if (!status_.is_safe_static_objects && !closest_start_pose_ && !search_start_offset_pose) { + if ( + !status_.get_is_safe_static_objects() && !status_.get_closest_start_pose() && + !search_start_offset_pose) { return generateFeasibleStopPath(); } const Pose stop_pose = - status_.is_safe_static_objects - ? status_.pull_over_path->start_pose - : (closest_start_pose_ ? closest_start_pose_.value() : *search_start_offset_pose); + status_.get_is_safe_static_objects() + ? status_.get_pull_over_path()->start_pose + : (status_.get_closest_start_pose() ? status_.get_closest_start_pose().value() + : *search_start_offset_pose); // if stop pose is closer than min_stop_distance, stop as soon as possible const double ego_to_stop_distance = calcSignedArcLengthFromEgo(reference_path, stop_pose); @@ -1124,10 +1149,11 @@ PathWithLaneId GoalPlannerModule::generateFeasibleStopPath() // generate stop reference path const auto s_current = - lanelet::utils::getArcCoordinates(status_.current_lanes, current_pose).length; + lanelet::utils::getArcCoordinates(status_.get_current_lanes(), current_pose).length; const double s_start = std::max(0.0, s_current - common_parameters.backward_path_length); const double s_end = s_current + common_parameters.forward_path_length; - auto stop_path = route_handler->getCenterLinePath(status_.current_lanes, s_start, s_end, true); + auto stop_path = + route_handler->getCenterLinePath(status_.get_current_lanes(), s_start, s_end, true); // calc minimum stop distance under maximum deceleration const auto min_stop_distance = calcFeasibleDecelDistance( @@ -1148,15 +1174,16 @@ PathWithLaneId GoalPlannerModule::generateFeasibleStopPath() void GoalPlannerModule::transitionToNextPathIfFinishingCurrentPath() { - if (isActivated() && last_approved_time_ != nullptr) { + if (isActivated() && status_.get_last_approved_time()) { // if using arc_path and finishing current_path, get next path // enough time for turn signal - const bool has_passed_enough_time = (clock_->now() - *last_approved_time_).seconds() > - planner_data_->parameters.turn_signal_search_time; + const bool has_passed_enough_time = + (clock_->now() - *status_.get_last_approved_time()).seconds() > + planner_data_->parameters.turn_signal_search_time; - if (hasFinishedCurrentPath() && has_passed_enough_time && status_.require_increment_) { + if (hasFinishedCurrentPath() && has_passed_enough_time && status_.get_require_increment()) { if (incrementPathIndex()) { - last_increment_time_ = std::make_unique(clock_->now()); + status_.set_last_increment_time(std::make_shared(clock_->now())); } } } @@ -1164,23 +1191,23 @@ void GoalPlannerModule::transitionToNextPathIfFinishingCurrentPath() bool GoalPlannerModule::incrementPathIndex() { - if (status_.current_path_idx == status_.pull_over_path->partial_paths.size() - 1) { + if (status_.get_current_path_idx() == status_.get_pull_over_path()->partial_paths.size() - 1) { return false; } - status_.current_path_idx = status_.current_path_idx + 1; + status_.set_current_path_idx(status_.get_current_path_idx() + 1); return true; } PathWithLaneId GoalPlannerModule::getCurrentPath() const { - if (status_.pull_over_path == nullptr) { + if (status_.get_pull_over_path() == nullptr) { return PathWithLaneId{}; } - if (status_.pull_over_path->partial_paths.size() <= status_.current_path_idx) { + if (status_.get_pull_over_path()->partial_paths.size() <= status_.get_current_path_idx()) { return PathWithLaneId{}; } - return status_.pull_over_path->partial_paths.at(status_.current_path_idx); + return status_.get_pull_over_path()->partial_paths.at(status_.get_current_path_idx()); } bool GoalPlannerModule::isStopped( @@ -1209,6 +1236,7 @@ bool GoalPlannerModule::isStopped( bool GoalPlannerModule::isStopped() { + const std::lock_guard lock(mutex_); return isStopped(odometry_buffer_stopped_, parameters_->th_stopped_time); } @@ -1218,18 +1246,19 @@ bool GoalPlannerModule::isStuck() return false; } + const std::lock_guard lock(mutex_); constexpr double stuck_time = 5.0; if (!isStopped(odometry_buffer_stuck_, stuck_time)) { return false; } // not found safe path - if (!status_.is_safe_static_objects) { + if (!status_.get_is_safe_static_objects()) { return true; } // any path has never been found - if (!status_.pull_over_path) { + if (!status_.get_pull_over_path()) { return false; } @@ -1248,12 +1277,12 @@ bool GoalPlannerModule::hasFinishedCurrentPath() bool GoalPlannerModule::isOnModifiedGoal() const { - if (!modified_goal_pose_) { + if (!status_.get_modified_goal_pose()) { return false; } const Pose current_pose = planner_data_->self_odometry->pose.pose; - return calcDistance2d(current_pose, modified_goal_pose_->goal_pose) < + return calcDistance2d(current_pose, status_.get_modified_goal_pose()->goal_pose) < parameters_->th_arrived_distance; } @@ -1262,9 +1291,9 @@ TurnSignalInfo GoalPlannerModule::calcTurnSignalInfo() const TurnSignalInfo turn_signal{}; // output const auto & current_pose = planner_data_->self_odometry->pose.pose; - const auto & start_pose = status_.pull_over_path->start_pose; - const auto & end_pose = status_.pull_over_path->end_pose; - const auto full_path = status_.pull_over_path->getFullPath(); + const auto & start_pose = status_.get_pull_over_path()->start_pose; + const auto & end_pose = status_.get_pull_over_path()->end_pose; + const auto full_path = status_.get_pull_over_path()->getFullPath(); // calc TurnIndicatorsCommand { @@ -1287,7 +1316,9 @@ TurnSignalInfo GoalPlannerModule::calcTurnSignalInfo() const // ego decelerates so that current pose is the point `turn_light_on_threshold_time` seconds // before starting pull_over turn_signal.desired_start_point = - last_approved_pose_ && status_.has_decided_path ? *last_approved_pose_ : current_pose; + status_.get_last_approved_pose() && status_.get_has_decided_path() + ? *status_.get_last_approved_pose() + : current_pose; turn_signal.desired_end_point = end_pose; turn_signal.required_start_point = start_pose; turn_signal.required_end_point = end_pose; @@ -1344,7 +1375,7 @@ bool GoalPlannerModule::hasEnoughDistance(const PullOverPath & pull_over_path) c // so need enough distance to restart. // distance to restart should be less than decide_path_distance. // otherwise, the goal would change immediately after departure. - const bool is_separated_path = status_.pull_over_path->partial_paths.size() > 1; + const bool is_separated_path = status_.get_pull_over_path()->partial_paths.size() > 1; const double distance_to_start = calcSignedArcLength( pull_over_path.getFullPath().points, current_pose.position, pull_over_path.start_pose.position); const double distance_to_restart = parameters_->decide_path_distance / 2; @@ -1375,10 +1406,10 @@ void GoalPlannerModule::keepStoppedWithCurrentPath(PathWithLaneId & path) { constexpr double keep_stop_time = 2.0; constexpr double keep_current_idx_buffer_time = 2.0; - if (last_increment_time_) { - const auto time_diff = (clock_->now() - *last_increment_time_).seconds(); + if (status_.get_last_increment_time()) { + const auto time_diff = (clock_->now() - *status_.get_last_increment_time()).seconds(); if (time_diff < keep_stop_time) { - status_.require_increment_ = false; + status_.set_require_increment(false); for (auto & p : path.points) { p.point.longitudinal_velocity_mps = 0.0; } @@ -1386,7 +1417,7 @@ void GoalPlannerModule::keepStoppedWithCurrentPath(PathWithLaneId & path) // require increment only when the time passed is enough // to prevent increment before driving // when the end of the current path is close to the current pose - status_.require_increment_ = true; + status_.set_require_increment(true); } } } @@ -1552,7 +1583,7 @@ bool GoalPlannerModule::isCrossingPossible( bool GoalPlannerModule::isCrossingPossible(const PullOverPath & pull_over_path) const { - const lanelet::ConstLanelets lanes = utils::transformToLanelets(status_.lanes); + const lanelet::ConstLanelets lanes = utils::transformToLanelets(status_.get_lanes()); const Pose & start_pose = pull_over_path.start_pose; const Pose & end_pose = pull_over_path.end_pose; @@ -1587,11 +1618,12 @@ bool GoalPlannerModule::isSafePath() const const size_t ego_seg_idx = planner_data_->findEgoSegmentIndex(pull_over_path.points); const std::pair terminal_velocity_and_accel = utils::start_goal_planner_common::getPairsTerminalVelocityAndAccel( - status_.pull_over_path->pairs_terminal_velocity_and_accel, status_.current_path_idx); + status_.get_pull_over_path()->pairs_terminal_velocity_and_accel, + status_.get_current_path_idx()); RCLCPP_DEBUG( getLogger(), "pairs_terminal_velocity_and_accel for goal_planner: %f, %f", terminal_velocity_and_accel.first, terminal_velocity_and_accel.second); - RCLCPP_DEBUG(getLogger(), "current_path_idx %ld", status_.current_path_idx); + RCLCPP_DEBUG(getLogger(), "current_path_idx %ld", status_.get_current_path_idx()); utils::start_goal_planner_common::updatePathProperty( ego_predicted_path_params_, terminal_velocity_and_accel); // TODO(Sugahara): shoule judge is_object_front properly @@ -1612,7 +1644,7 @@ bool GoalPlannerModule::isSafePath() const pull_over_lanes, route_handler, filtered_objects, objects_filtering_params_); const double hysteresis_factor = - status_.prev_is_safe_dynamic_objects ? 1.0 : parameters_->hysteresis_factor_expand_rate; + status_.get_prev_is_safe_dynamic_objects() ? 1.0 : parameters_->hysteresis_factor_expand_rate; utils::start_goal_planner_common::updateSafetyCheckTargetObjectsData( goal_planner_data_, filtered_objects, target_objects_on_lane, ego_predicted_path); @@ -1674,29 +1706,31 @@ void GoalPlannerModule::setDebugData() }; if (goal_planner_utils::isAllowedGoalModification(planner_data_->route_handler)) { // Visualize pull over areas - const auto color = status_.has_decided_path ? createMarkerColor(1.0, 1.0, 0.0, 0.999) // yellow - : createMarkerColor(0.0, 1.0, 0.0, 0.999); // green - const double z = refined_goal_pose_.position.z; + const auto color = status_.get_has_decided_path() + ? createMarkerColor(1.0, 1.0, 0.0, 0.999) // yellow + : createMarkerColor(0.0, 1.0, 0.0, 0.999); // green + const double z = status_.get_refined_goal_pose().position.z; add(goal_planner_utils::createPullOverAreaMarkerArray( goal_searcher_->getAreaPolygons(), header, color, z)); // Visualize goal candidates - add(goal_planner_utils::createGoalCandidatesMarkerArray(goal_candidates_, color)); + const auto goal_candidates = status_.get_goal_candidates(); + add(goal_planner_utils::createGoalCandidatesMarkerArray(goal_candidates, color)); } // Visualize path and related pose - if (status_.is_safe_static_objects) { + if (status_.get_is_safe_static_objects()) { add(createPoseMarkerArray( - status_.pull_over_path->start_pose, "pull_over_start_pose", 0, 0.3, 0.3, 0.9)); + status_.get_pull_over_path()->start_pose, "pull_over_start_pose", 0, 0.3, 0.3, 0.9)); add(createPoseMarkerArray( - status_.pull_over_path->end_pose, "pull_over_end_pose", 0, 0.3, 0.3, 0.9)); - add( - createPathMarkerArray(status_.pull_over_path->getFullPath(), "full_path", 0, 0.0, 0.5, 0.9)); + status_.get_pull_over_path()->end_pose, "pull_over_end_pose", 0, 0.3, 0.3, 0.9)); + add(createPathMarkerArray( + status_.get_pull_over_path()->getFullPath(), "full_path", 0, 0.0, 0.5, 0.9)); add(createPathMarkerArray(getCurrentPath(), "current_path", 0, 0.9, 0.5, 0.0)); // visualize each partial path - for (size_t i = 0; i < status_.pull_over_path->partial_paths.size(); ++i) { - const auto & partial_path = status_.pull_over_path->partial_paths.at(i); + for (size_t i = 0; i < status_.get_pull_over_path()->partial_paths.size(); ++i) { + const auto & partial_path = status_.get_pull_over_path()->partial_paths.at(i); add( createPathMarkerArray(partial_path, "partial_path_" + std::to_string(i), 0, 0.9, 0.5, 0.9)); } @@ -1742,16 +1776,17 @@ void GoalPlannerModule::setDebugData() // Visualize planner type text { visualization_msgs::msg::MarkerArray planner_type_marker_array{}; - const auto color = status_.is_safe_static_objects ? createMarkerColor(1.0, 1.0, 1.0, 0.99) - : createMarkerColor(1.0, 0.0, 0.0, 0.99); + const auto color = status_.get_is_safe_static_objects() + ? createMarkerColor(1.0, 1.0, 1.0, 0.99) + : createMarkerColor(1.0, 0.0, 0.0, 0.99); auto marker = createDefaultMarker( header.frame_id, header.stamp, "planner_type", 0, visualization_msgs::msg::Marker::TEXT_VIEW_FACING, createMarkerScale(0.0, 0.0, 1.0), color); - marker.pose = modified_goal_pose_ ? modified_goal_pose_->goal_pose - : planner_data_->self_odometry->pose.pose; - marker.text = magic_enum::enum_name(status_.pull_over_path->type); - marker.text += " " + std::to_string(status_.current_path_idx) + "/" + - std::to_string(status_.pull_over_path->partial_paths.size() - 1); + marker.pose = status_.get_modified_goal_pose() ? status_.get_modified_goal_pose()->goal_pose + : planner_data_->self_odometry->pose.pose; + marker.text = magic_enum::enum_name(status_.get_pull_over_path()->type); + marker.text += " " + std::to_string(status_.get_current_path_idx()) + "/" + + std::to_string(status_.get_pull_over_path()->partial_paths.size() - 1); if (isStuck()) { marker.text += " stuck"; } else if (isStopped()) { @@ -1769,7 +1804,7 @@ void GoalPlannerModule::setDebugData() } // Visualize debug poses - const auto & debug_poses = status_.pull_over_path->debug_poses; + const auto & debug_poses = status_.get_pull_over_path()->debug_poses; for (size_t i = 0; i < debug_poses.size(); ++i) { add(createPoseMarkerArray( debug_poses.at(i), "debug_pose_" + std::to_string(i), 0, 0.3, 0.3, 0.3)); @@ -1781,7 +1816,8 @@ void GoalPlannerModule::printParkingPositionError() const const auto current_pose = planner_data_->self_odometry->pose.pose; const double real_shoulder_to_map_shoulder = 0.0; - const Pose goal_to_ego = inverseTransformPose(current_pose, modified_goal_pose_->goal_pose); + const Pose goal_to_ego = + inverseTransformPose(current_pose, status_.get_modified_goal_pose()->goal_pose); const double dx = goal_to_ego.position.x; const double dy = goal_to_ego.position.y; const double distance_from_real_shoulder = @@ -1790,7 +1826,7 @@ void GoalPlannerModule::printParkingPositionError() const getLogger(), "current pose to goal, dx:%f dy:%f dyaw:%f from_real_shoulder:%f", dx, dy, tier4_autoware_utils::rad2deg( tf2::getYaw(current_pose.orientation) - - tf2::getYaw(modified_goal_pose_->goal_pose.orientation)), + tf2::getYaw(status_.get_modified_goal_pose()->goal_pose.orientation)), distance_from_real_shoulder); } @@ -1816,10 +1852,10 @@ bool GoalPlannerModule::needPathUpdate(const double path_update_duration) const bool GoalPlannerModule::hasEnoughTimePassedSincePathUpdate(const double duration) const { - if (!last_path_update_time_) { + if (!status_.get_last_path_update_time()) { return true; } - return (clock_->now() - *last_path_update_time_).seconds() > duration; + return (clock_->now() - *status_.get_last_path_update_time()).seconds() > duration; } } // namespace behavior_path_planner diff --git a/planning/behavior_path_planner/src/utils/goal_planner/util.cpp b/planning/behavior_path_planner/src/utils/goal_planner/util.cpp index ff26c7a3654c3..e7fa5e42dc092 100644 --- a/planning/behavior_path_planner/src/utils/goal_planner/util.cpp +++ b/planning/behavior_path_planner/src/utils/goal_planner/util.cpp @@ -171,7 +171,7 @@ MarkerArray createNumObjectsToAvoidTextsMarkerArray( } MarkerArray createGoalCandidatesMarkerArray( - GoalCandidates & goal_candidates, const std_msgs::msg::ColorRGBA & color) + const GoalCandidates & goal_candidates, const std_msgs::msg::ColorRGBA & color) { GoalCandidates safe_goal_candidates{}; std::copy_if( From eaf9f684dc092ee1681221b7e724081ff1f0833f Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Thu, 19 Oct 2023 12:58:42 +0900 Subject: [PATCH 025/202] test(ndt_scan_matcher): add test_ndt_scan_matcher_launch.py (#5347) * Added test_ndt_scan_matcher_launch.py Signed-off-by: Shintaro Sakoda * Added assert and raising exception Signed-off-by: Shintaro Sakoda --------- Signed-off-by: Shintaro Sakoda --- localization/ndt_scan_matcher/CMakeLists.txt | 5 + localization/ndt_scan_matcher/package.xml | 1 + .../src/map_update_module.cpp | 15 +-- .../test/test_ndt_scan_matcher_launch.py | 101 ++++++++++++++++++ 4 files changed, 115 insertions(+), 7 deletions(-) create mode 100644 localization/ndt_scan_matcher/test/test_ndt_scan_matcher_launch.py diff --git a/localization/ndt_scan_matcher/CMakeLists.txt b/localization/ndt_scan_matcher/CMakeLists.txt index 6f51b5210d853..955234f95ff18 100644 --- a/localization/ndt_scan_matcher/CMakeLists.txt +++ b/localization/ndt_scan_matcher/CMakeLists.txt @@ -41,6 +41,11 @@ link_directories(${PCL_LIBRARY_DIRS}) target_link_libraries(ndt_scan_matcher ${PCL_LIBRARIES}) if(BUILD_TESTING) + add_ros_test( + test/test_ndt_scan_matcher_launch.py + TIMEOUT "30" + ) + find_package(ament_cmake_gtest REQUIRED) ament_add_gtest(test_tpe test/test_tpe.cpp diff --git a/localization/ndt_scan_matcher/package.xml b/localization/ndt_scan_matcher/package.xml index 92c690a708492..986179b9e02e2 100644 --- a/localization/ndt_scan_matcher/package.xml +++ b/localization/ndt_scan_matcher/package.xml @@ -38,6 +38,7 @@ ament_cmake_cppcheck ament_lint_auto + ros_testing ament_cmake diff --git a/localization/ndt_scan_matcher/src/map_update_module.cpp b/localization/ndt_scan_matcher/src/map_update_module.cpp index 9c94467dc94c0..7512ae2e77a21 100644 --- a/localization/ndt_scan_matcher/src/map_update_module.cpp +++ b/localization/ndt_scan_matcher/src/map_update_module.cpp @@ -55,12 +55,6 @@ MapUpdateModule::MapUpdateModule( pcd_loader_client_ = node->create_client("pcd_loader_service"); - while (!pcd_loader_client_->wait_for_service(std::chrono::seconds(1)) && rclcpp::ok()) { - RCLCPP_INFO( - logger_, - "Waiting for pcd loader service. Check if the enable_differential_load in " - "pointcloud_map_loader is set `true`."); - } double map_update_dt = 1.0; auto period_ns = std::chrono::duration_cast( @@ -117,7 +111,14 @@ void MapUpdateModule::update_map(const geometry_msgs::msg::Point & position) request->area.radius = static_cast(dynamic_map_loading_map_radius_); request->cached_ids = ndt_ptr_->getCurrentMapIDs(); - // // send a request to map_loader + while (!pcd_loader_client_->wait_for_service(std::chrono::seconds(1)) && rclcpp::ok()) { + RCLCPP_INFO( + logger_, + "Waiting for pcd loader service. Check if the enable_differential_load in " + "pointcloud_map_loader is set `true`."); + } + + // send a request to map_loader auto result{pcd_loader_client_->async_send_request( request, [](rclcpp::Client::SharedFuture) {})}; diff --git a/localization/ndt_scan_matcher/test/test_ndt_scan_matcher_launch.py b/localization/ndt_scan_matcher/test/test_ndt_scan_matcher_launch.py new file mode 100644 index 0000000000000..2dc4958c4704f --- /dev/null +++ b/localization/ndt_scan_matcher/test/test_ndt_scan_matcher_launch.py @@ -0,0 +1,101 @@ +#!/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 os +import unittest + +from ament_index_python import get_package_share_directory +import launch +from launch.actions import IncludeLaunchDescription +from launch.launch_description_sources import AnyLaunchDescriptionSource +from launch.logging import get_logger +import launch_testing +import pytest +import rclpy +from std_srvs.srv import SetBool + +logger = get_logger(__name__) + + +@pytest.mark.launch_test +def generate_test_description(): + test_ndt_scan_matcher_launch_file = os.path.join( + get_package_share_directory("ndt_scan_matcher"), + "launch", + "ndt_scan_matcher.launch.xml", + ) + ndt_scan_matcher = IncludeLaunchDescription( + AnyLaunchDescriptionSource(test_ndt_scan_matcher_launch_file), + ) + + return launch.LaunchDescription( + [ + ndt_scan_matcher, + # Start tests right away - no need to wait for anything + launch_testing.actions.ReadyToTest(), + ] + ) + + +class TestNDTScanMatcher(unittest.TestCase): + @classmethod + def setUpClass(cls): + # Initialize the ROS context for the test node + rclpy.init() + + @classmethod + def tearDownClass(cls): + # Shutdown the ROS context + rclpy.shutdown() + + def setUp(self): + # Create a ROS node for tests + self.test_node = rclpy.create_node("test_node") + + def tearDown(self): + self.test_node.destroy_node() + + @staticmethod + def print_message(stat): + logger.debug("===========================") + logger.debug(stat) + + def test_launch(self): + # Trigger ndt_scan_matcher to activate the node + cli_trigger = self.test_node.create_client(SetBool, "/trigger_node") + while not cli_trigger.wait_for_service(timeout_sec=1.0): + continue + + request = SetBool.Request() + request.data = True + future = cli_trigger.call_async(request) + rclpy.spin_until_future_complete(self.test_node, future) + + if future.result() is not None: + self.test_node.get_logger().info("Result of bool service: %s" % future.result().message) + self.assertTrue(future.result().success, "ndt_scan_matcher is not activated") + else: + self.test_node.get_logger().error( + "Exception while calling service: %r" % future.exception() + ) + raise self.failureException("service trigger failed") + + +@launch_testing.post_shutdown_test() +class TestProcessOutput(unittest.TestCase): + def test_exit_code(self, proc_info): + # Check that process exits with code 0: no error + launch_testing.asserts.assertExitCodes(proc_info) From e67badaf95f53e049b2360f8c3c24025935942f7 Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Thu, 19 Oct 2023 13:41:20 +0900 Subject: [PATCH 026/202] refactor(ndt_scan_matcher): rename `align_using_monte_carlo` , etc. (#5351) * Renamed align_using_monte_carlo to align_pose Signed-off-by: Shintaro SAKODA * Removed the waste arg ndt_ptr Signed-off-by: Shintaro SAKODA * Fixed log messages Signed-off-by: Shintaro SAKODA * style(pre-commit): autofix --------- Signed-off-by: Shintaro SAKODA Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../ndt_scan_matcher_core.hpp | 3 +- .../src/ndt_scan_matcher_core.cpp | 32 ++++++++----------- 2 files changed, 14 insertions(+), 21 deletions(-) diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp index a07eb9cd5c8d0..153418e5a8f75 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp @@ -92,8 +92,7 @@ class NDTScanMatcher : public rclcpp::Node void callback_regularization_pose( geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr pose_conv_msg_ptr); - geometry_msgs::msg::PoseWithCovarianceStamped align_using_monte_carlo( - const std::shared_ptr & ndt_ptr, + geometry_msgs::msg::PoseWithCovarianceStamped align_pose( const geometry_msgs::msg::PoseWithCovarianceStamped & initial_pose_with_cov); void transform_sensor_measurement( diff --git a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp index 25033c8c83c01..b7f32d2de53ff 100644 --- a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp +++ b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp @@ -764,38 +764,33 @@ void NDTScanMatcher::service_ndt_align( map_update_module_->update_map(initial_pose_msg_in_map_frame.pose.pose.position); } + // mutex Map + std::lock_guard lock(ndt_ptr_mtx_); + if (ndt_ptr_->getInputTarget() == nullptr) { res->success = false; - RCLCPP_WARN(get_logger(), "No InputTarget"); + RCLCPP_WARN( + get_logger(), "No InputTarget. Please check the map file and the map_loader service"); return; } if (ndt_ptr_->getInputSource() == nullptr) { res->success = false; - RCLCPP_WARN(get_logger(), "No InputSource"); + RCLCPP_WARN(get_logger(), "No InputSource. Please check the input lidar topic"); return; } - // mutex Map - std::lock_guard lock(ndt_ptr_mtx_); - (*state_ptr_)["state"] = "Aligning"; - res->pose_with_covariance = align_using_monte_carlo(ndt_ptr_, initial_pose_msg_in_map_frame); + res->pose_with_covariance = align_pose(initial_pose_msg_in_map_frame); (*state_ptr_)["state"] = "Sleeping"; res->success = true; res->pose_with_covariance.pose.covariance = req->pose_with_covariance.pose.covariance; } -geometry_msgs::msg::PoseWithCovarianceStamped NDTScanMatcher::align_using_monte_carlo( - const std::shared_ptr & ndt_ptr, +geometry_msgs::msg::PoseWithCovarianceStamped NDTScanMatcher::align_pose( const geometry_msgs::msg::PoseWithCovarianceStamped & initial_pose_with_cov) { - if (ndt_ptr->getInputTarget() == nullptr || ndt_ptr->getInputSource() == nullptr) { - RCLCPP_WARN(get_logger(), "No Map or Sensor PointCloud"); - return geometry_msgs::msg::PoseWithCovarianceStamped(); - } - - output_pose_with_cov_to_log(get_logger(), "align_using_monte_carlo_input", initial_pose_with_cov); + output_pose_with_cov_to_log(get_logger(), "align_pose_input", initial_pose_with_cov); const auto base_rpy = get_rpy(initial_pose_with_cov); const Eigen::Map covariance = { @@ -856,8 +851,8 @@ geometry_msgs::msg::PoseWithCovarianceStamped NDTScanMatcher::align_using_monte_ initial_pose.orientation = tf2::toMsg(tf_quaternion); const Eigen::Matrix4f initial_pose_matrix = pose_to_matrix4f(initial_pose); - ndt_ptr->align(*output_cloud, initial_pose_matrix); - const pclomp::NdtResult ndt_result = ndt_ptr->getResult(); + ndt_ptr_->align(*output_cloud, initial_pose_matrix); + const pclomp::NdtResult ndt_result = ndt_ptr_->getResult(); Particle particle( initial_pose, matrix4f_to_pose(ndt_result.pose), ndt_result.transform_probability, @@ -891,7 +886,7 @@ geometry_msgs::msg::PoseWithCovarianceStamped NDTScanMatcher::align_using_monte_ auto sensor_points_in_map_ptr = std::make_shared>(); tier4_autoware_utils::transformPointCloud( - *ndt_ptr->getInputSource(), *sensor_points_in_map_ptr, ndt_result.pose); + *ndt_ptr_->getInputSource(), *sensor_points_in_map_ptr, ndt_result.pose); publish_point_cloud(initial_pose_with_cov.header.stamp, map_frame_, sensor_points_in_map_ptr); } @@ -904,8 +899,7 @@ geometry_msgs::msg::PoseWithCovarianceStamped NDTScanMatcher::align_using_monte_ result_pose_with_cov_msg.header.frame_id = map_frame_; result_pose_with_cov_msg.pose.pose = best_particle_ptr->result_pose; - output_pose_with_cov_to_log( - get_logger(), "align_using_monte_carlo_output", result_pose_with_cov_msg); + output_pose_with_cov_to_log(get_logger(), "align_pose_output", result_pose_with_cov_msg); RCLCPP_INFO_STREAM(get_logger(), "best_score," << best_particle_ptr->score); return result_pose_with_cov_msg; From 64d80800c500d574bc14c1b65028f2fbfeeebc53 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Thu, 19 Oct 2023 14:43:32 +0900 Subject: [PATCH 027/202] refactor(behavior_path_planner): remove unused headers (#5341) * refactor(behavior_path_planner): remove unused headers Signed-off-by: Muhammad Zulfaqar Azmi * style(pre-commit): autofix * additional headers Signed-off-by: Muhammad Zulfaqar * additional headers removed Signed-off-by: Muhammad Zulfaqar --------- Signed-off-by: Muhammad Zulfaqar Azmi Signed-off-by: Muhammad Zulfaqar Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../behavior_path_planner/behavior_path_planner_node.hpp | 7 ------- .../include/behavior_path_planner/parameters.hpp | 1 - .../include/behavior_path_planner/planner_manager.hpp | 3 --- .../dynamic_avoidance/dynamic_avoidance_module.hpp | 5 +++++ .../scene_module/goal_planner/goal_planner_module.hpp | 2 ++ .../scene_module/scene_module_interface.hpp | 1 + .../behavior_path_planner/steering_factor_interface.hpp | 8 +++----- .../utils/avoidance/avoidance_module_data.hpp | 2 +- .../behavior_path_planner/utils/avoidance/utils.hpp | 3 --- .../utils/drivable_area_expansion/footprints.hpp | 6 ------ .../utils/drivable_area_expansion/parameters.hpp | 2 -- .../utils/drivable_area_expansion/path_projection.hpp | 1 - .../geometric_parallel_parking.hpp | 2 -- .../utils/goal_planner/default_fixed_goal_planner.hpp | 1 - .../utils/goal_planner/fixed_goal_planner_base.hpp | 2 -- .../utils/goal_planner/goal_searcher.hpp | 3 --- .../utils/goal_planner/goal_searcher_base.hpp | 2 -- .../utils/goal_planner/pull_over_planner_base.hpp | 1 - .../utils/lane_change/lane_change_module_data.hpp | 8 -------- .../behavior_path_planner/utils/lane_change/utils.hpp | 5 ----- .../utils/lane_following/module_data.hpp | 3 --- .../utils/path_safety_checker/objects_filtering.hpp | 1 - .../utils/path_safety_checker/safety_check.hpp | 4 ---- .../utils/path_shifter/path_shifter.hpp | 3 --- .../behavior_path_planner/utils/side_shift/util.hpp | 3 --- .../start_goal_planner_common/common_module_data.hpp | 1 - .../utils/start_planner/freespace_pull_out.hpp | 1 - .../utils/start_planner/pull_out_planner_base.hpp | 6 ++---- .../behavior_path_planner/utils/start_planner/util.hpp | 2 -- .../include/behavior_path_planner/utils/utils.hpp | 8 -------- .../src/behavior_path_planner_node.cpp | 8 ++++++-- .../src/marker_utils/avoidance/debug.cpp | 3 --- .../src/marker_utils/lane_change/debug.cpp | 2 -- .../behavior_path_planner/src/marker_utils/utils.cpp | 1 - planning/behavior_path_planner/src/planner_manager.cpp | 1 - .../src/scene_module/avoidance/avoidance_module.cpp | 5 ----- .../dynamic_avoidance/dynamic_avoidance_module.cpp | 3 +-- .../scene_module/goal_planner/goal_planner_module.cpp | 3 +-- .../lane_change/avoidance_by_lane_change.cpp | 1 - .../src/scene_module/lane_change/external_request.cpp | 9 --------- .../src/scene_module/lane_change/interface.cpp | 2 -- .../src/scene_module/lane_change/manager.cpp | 1 - .../src/scene_module/lane_change/normal.cpp | 2 +- .../src/scene_module/side_shift/side_shift_module.cpp | 1 - .../scene_module/start_planner/start_planner_module.cpp | 2 -- .../behavior_path_planner/src/utils/avoidance/utils.cpp | 1 - .../geometric_parallel_parking.cpp | 3 --- .../utils/goal_planner/default_fixed_goal_planner.cpp | 1 - .../src/utils/goal_planner/geometric_pull_over.cpp | 2 -- .../src/utils/goal_planner/goal_searcher.cpp | 2 -- .../src/utils/goal_planner/shift_pull_over.cpp | 2 -- .../src/utils/goal_planner/util.cpp | 4 ---- .../src/utils/lane_change/utils.cpp | 4 ++-- .../src/utils/path_safety_checker/objects_filtering.cpp | 1 + .../src/utils/path_safety_checker/safety_check.cpp | 6 +++--- .../src/utils/path_shifter/path_shifter.cpp | 2 -- planning/behavior_path_planner/src/utils/path_utils.cpp | 2 -- planning/behavior_path_planner/src/utils/utils.cpp | 5 ++--- planning/behavior_path_planner/test/input.hpp | 7 ++++++- 59 files changed, 37 insertions(+), 146 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp b/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp index e8ad6c7e2f987..420a5a8aa6ee5 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp @@ -17,13 +17,7 @@ #include "behavior_path_planner/data_manager.hpp" #include "behavior_path_planner/planner_manager.hpp" -#include "behavior_path_planner/scene_module/avoidance/manager.hpp" -#include "behavior_path_planner/scene_module/dynamic_avoidance/manager.hpp" -#include "behavior_path_planner/scene_module/goal_planner/manager.hpp" -#include "behavior_path_planner/scene_module/lane_change/manager.hpp" #include "behavior_path_planner/scene_module/scene_module_interface.hpp" -#include "behavior_path_planner/scene_module/side_shift/manager.hpp" -#include "behavior_path_planner/scene_module/start_planner/manager.hpp" #include "behavior_path_planner/steering_factor_interface.hpp" #include "tier4_autoware_utils/ros/logger_level_configure.hpp" @@ -66,7 +60,6 @@ using autoware_auto_vehicle_msgs::msg::HazardLightsCommand; using autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand; using autoware_planning_msgs::msg::LaneletRoute; using autoware_planning_msgs::msg::PoseWithUuidStamped; -using geometry_msgs::msg::TwistStamped; using nav_msgs::msg::OccupancyGrid; using nav_msgs::msg::Odometry; using rcl_interfaces::msg::SetParametersResult; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp b/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp index e3a3784c5e928..40df1f5157c71 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp @@ -18,7 +18,6 @@ #include #include -#include #include #include diff --git a/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp index 4b9b0bff4be63..c0437aa69764a 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp @@ -18,20 +18,17 @@ #include "behavior_path_planner/scene_module/scene_module_interface.hpp" #include "behavior_path_planner/scene_module/scene_module_manager_interface.hpp" #include "behavior_path_planner/scene_module/scene_module_visitor.hpp" -#include "behavior_path_planner/utils/lane_following/module_data.hpp" #include "tier4_autoware_utils/ros/debug_publisher.hpp" #include "tier4_autoware_utils/system/stop_watch.hpp" #include -#include "tier4_debug_msgs/msg/float64_stamped.hpp" #include #include #include #include -#include #include #include #include diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp index ab8e3cfd70dff..6c522c79a8774 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp @@ -18,8 +18,10 @@ #include "behavior_path_planner/scene_module/scene_module_interface.hpp" #include +#include #include +#include #include #include #include @@ -35,6 +37,9 @@ namespace behavior_path_planner { +using autoware_auto_perception_msgs::msg::PredictedPath; +using tier4_autoware_utils::Polygon2d; + struct MinMaxValue { double min_value{0.0}; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp index 632872471ce29..251b72ea6eadb 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp @@ -32,6 +32,7 @@ #include #include #include +#include #include #include @@ -65,6 +66,7 @@ using behavior_path_planner::utils::path_safety_checker::ObjectsFilteringParams; using behavior_path_planner::utils::path_safety_checker::PoseWithVelocityStamped; using behavior_path_planner::utils::path_safety_checker::SafetyCheckParams; using behavior_path_planner::utils::path_safety_checker::TargetObjectsOnLane; +using tier4_autoware_utils::Polygon2d; enum class PathType { NONE = 0, diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp index 68faa3806f614..7f24683e5680c 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp @@ -16,6 +16,7 @@ #define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__SCENE_MODULE_INTERFACE_HPP_ #include "behavior_path_planner/data_manager.hpp" +#include "behavior_path_planner/marker_utils/utils.hpp" #include "behavior_path_planner/scene_module/scene_module_visitor.hpp" #include "behavior_path_planner/utils/utils.hpp" diff --git a/planning/behavior_path_planner/include/behavior_path_planner/steering_factor_interface.hpp b/planning/behavior_path_planner/include/behavior_path_planner/steering_factor_interface.hpp index 8afe0576ec1aa..3a334cf67edbf 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/steering_factor_interface.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/steering_factor_interface.hpp @@ -15,15 +15,13 @@ #ifndef BEHAVIOR_PATH_PLANNER__STEERING_FACTOR_INTERFACE_HPP_ #define BEHAVIOR_PATH_PLANNER__STEERING_FACTOR_INTERFACE_HPP_ -#include "rclcpp/rclcpp.hpp" +#include -#include "autoware_adapi_v1_msgs/msg/steering_factor_array.hpp" -#include "geometry_msgs/msg/pose.hpp" -#include "unique_identifier_msgs/msg/uuid.hpp" +#include +#include #include #include -#include namespace steering_factor_interface { 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 d04b35a3b185b..74464be0fa5ea 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 @@ -15,7 +15,7 @@ #ifndef BEHAVIOR_PATH_PLANNER__UTILS__AVOIDANCE__AVOIDANCE_MODULE_DATA_HPP_ #define BEHAVIOR_PATH_PLANNER__UTILS__AVOIDANCE__AVOIDANCE_MODULE_DATA_HPP_ -#include "behavior_path_planner/marker_utils/utils.hpp" +#include "behavior_path_planner/data_manager.hpp" #include "behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include "behavior_path_planner/utils/path_shifter/path_shifter.hpp" diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp index 8cb09cd47b444..0237fb458ea0b 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp @@ -18,11 +18,8 @@ #include "behavior_path_planner/data_manager.hpp" #include "behavior_path_planner/utils/avoidance/avoidance_module_data.hpp" #include "behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp" -#include "behavior_path_planner/utils/path_safety_checker/safety_check.hpp" -#include #include -#include #include #include diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/footprints.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/footprints.hpp index 418a9a5a68572..9591ac0582e04 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/footprints.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/footprints.hpp @@ -20,7 +20,6 @@ #include -#include "autoware_auto_planning_msgs/msg/detail/path_point__struct.hpp" #include #include #include @@ -31,11 +30,6 @@ #include #include -#include -#include -#include -#include - namespace drivable_area_expansion { /// @brief translate a polygon by some (x,y) vector diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/parameters.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/parameters.hpp index e7275960b0888..2f9604223a248 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/parameters.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/parameters.hpp @@ -15,8 +15,6 @@ #ifndef BEHAVIOR_PATH_PLANNER__UTILS__DRIVABLE_AREA_EXPANSION__PARAMETERS_HPP_ #define BEHAVIOR_PATH_PLANNER__UTILS__DRIVABLE_AREA_EXPANSION__PARAMETERS_HPP_ -#include "behavior_path_planner/utils/drivable_area_expansion/types.hpp" - #include #include diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/path_projection.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/path_projection.hpp index 93afaad825582..3f5327acbca68 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/path_projection.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/path_projection.hpp @@ -21,7 +21,6 @@ #include -#include #include namespace drivable_area_expansion diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/geometric_parallel_parking/geometric_parallel_parking.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/geometric_parallel_parking/geometric_parallel_parking.hpp index c2d36fdd6e0d7..f4ab10db61b9c 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/geometric_parallel_parking/geometric_parallel_parking.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/geometric_parallel_parking/geometric_parallel_parking.hpp @@ -30,9 +30,7 @@ #include -#include #include -#include #include #include diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/default_fixed_goal_planner.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/default_fixed_goal_planner.hpp index 40c339e507683..9cede67fff6e5 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/default_fixed_goal_planner.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/default_fixed_goal_planner.hpp @@ -20,7 +20,6 @@ #include #include -#include namespace behavior_path_planner { diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/fixed_goal_planner_base.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/fixed_goal_planner_base.hpp index 3bc0e960fe468..f587051442dcd 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/fixed_goal_planner_base.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/fixed_goal_planner_base.hpp @@ -16,13 +16,11 @@ #define BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__FIXED_GOAL_PLANNER_BASE_HPP_ #include "behavior_path_planner/data_manager.hpp" -#include "behavior_path_planner/parameters.hpp" #include #include #include -#include using autoware_auto_planning_msgs::msg::PathWithLaneId; using geometry_msgs::msg::Pose; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_searcher.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_searcher.hpp index 9d957ae9767c9..2ed58b9678e70 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_searcher.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_searcher.hpp @@ -18,14 +18,11 @@ #include "behavior_path_planner/utils/goal_planner/goal_searcher_base.hpp" #include "behavior_path_planner/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp" -#include "autoware_auto_planning_msgs/msg/path_point_with_lane_id.hpp" - #include #include namespace behavior_path_planner { -using autoware_auto_planning_msgs::msg::PathPointWithLaneId; using tier4_autoware_utils::LinearRing2d; using BasicPolygons2d = std::vector; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_searcher_base.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_searcher_base.hpp index 7364ea91339e4..ab319111f6da6 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_searcher_base.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_searcher_base.hpp @@ -16,12 +16,10 @@ #define BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__GOAL_SEARCHER_BASE_HPP_ #include "behavior_path_planner/data_manager.hpp" -#include "behavior_path_planner/parameters.hpp" #include "behavior_path_planner/utils/goal_planner/goal_planner_parameters.hpp" #include -#include #include #include diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp index 20788e53309ec..54bba6aee2fc2 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp @@ -16,7 +16,6 @@ #define BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__PULL_OVER_PLANNER_BASE_HPP_ #include "behavior_path_planner/data_manager.hpp" -#include "behavior_path_planner/parameters.hpp" #include "behavior_path_planner/utils/create_vehicle_footprint.hpp" #include "behavior_path_planner/utils/goal_planner/goal_planner_parameters.hpp" diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp index 8b9ef52394cdd..c664ae3e15aef 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp @@ -16,17 +16,9 @@ #include "behavior_path_planner/utils/avoidance/avoidance_module_data.hpp" #include "behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp" -#include "behavior_path_planner/utils/path_safety_checker/safety_check.hpp" -#include "lanelet2_core/geometry/Lanelet.h" - -#include "autoware_auto_planning_msgs/msg/path_point_with_lane_id.hpp" #include -#include -#include -#include -#include #include namespace behavior_path_planner diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp index cd8f293b2e610..ac712fa2f0fa5 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp @@ -15,12 +15,10 @@ #ifndef BEHAVIOR_PATH_PLANNER__UTILS__LANE_CHANGE__UTILS_HPP_ #define BEHAVIOR_PATH_PLANNER__UTILS__LANE_CHANGE__UTILS_HPP_ -#include "behavior_path_planner/marker_utils/lane_change/debug.hpp" #include "behavior_path_planner/parameters.hpp" #include "behavior_path_planner/utils/lane_change/lane_change_module_data.hpp" #include "behavior_path_planner/utils/lane_change/lane_change_path.hpp" #include "behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp" -#include "behavior_path_planner/utils/path_safety_checker/safety_check.hpp" #include "behavior_path_planner/utils/utils.hpp" #include @@ -32,10 +30,7 @@ #include -#include #include -#include -#include #include namespace behavior_path_planner::utils::lane_change diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_following/module_data.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_following/module_data.hpp index 93e4542568745..98d52b79e2edf 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_following/module_data.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_following/module_data.hpp @@ -15,9 +15,6 @@ #ifndef BEHAVIOR_PATH_PLANNER__UTILS__LANE_FOLLOWING__MODULE_DATA_HPP_ #define BEHAVIOR_PATH_PLANNER__UTILS__LANE_FOLLOWING__MODULE_DATA_HPP_ -#include -#include - namespace behavior_path_planner { 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 15b15bac40b51..67588ed0a67b6 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 @@ -27,7 +27,6 @@ #include #include -#include #include #include 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 64f5c9e5fc3e0..8409116236169 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 @@ -16,7 +16,6 @@ #define BEHAVIOR_PATH_PLANNER__UTILS__PATH_SAFETY_CHECKER__SAFETY_CHECK_HPP_ #include "behavior_path_planner/data_manager.hpp" -#include "behavior_path_planner/marker_utils/utils.hpp" #include "behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include @@ -35,7 +34,6 @@ #include #endif -#include #include namespace behavior_path_planner::utils::path_safety_checker @@ -52,8 +50,6 @@ using tier4_autoware_utils::Point2d; using tier4_autoware_utils::Polygon2d; using vehicle_info_util::VehicleInfo; -namespace bg = boost::geometry; - bool isTargetObjectOncoming( const geometry_msgs::msg::Pose & vehicle_pose, const geometry_msgs::msg::Pose & object_pose); diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_shifter/path_shifter.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_shifter/path_shifter.hpp index 4b1115a049ab0..91ed95b14b905 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_shifter/path_shifter.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_shifter/path_shifter.hpp @@ -15,8 +15,6 @@ #ifndef BEHAVIOR_PATH_PLANNER__UTILS__PATH_SHIFTER__PATH_SHIFTER_HPP_ #define BEHAVIOR_PATH_PLANNER__UTILS__PATH_SHIFTER__PATH_SHIFTER_HPP_ -#include "behavior_path_planner/parameters.hpp" - #include #include @@ -24,7 +22,6 @@ #include -#include #include #include #include diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/side_shift/util.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/side_shift/util.hpp index 65d79a2a4977b..6cdfd84d79075 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/side_shift/util.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/side_shift/util.hpp @@ -20,9 +20,6 @@ #include #include -#include -#include - namespace behavior_path_planner { using autoware_auto_planning_msgs::msg::PathWithLaneId; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_goal_planner_common/common_module_data.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/start_goal_planner_common/common_module_data.hpp index 55b8bdf777692..7a973a3bd699f 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_goal_planner_common/common_module_data.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/start_goal_planner_common/common_module_data.hpp @@ -15,7 +15,6 @@ #ifndef BEHAVIOR_PATH_PLANNER__UTILS__START_GOAL_PLANNER_COMMON__COMMON_MODULE_DATA_HPP_ #define BEHAVIOR_PATH_PLANNER__UTILS__START_GOAL_PLANNER_COMMON__COMMON_MODULE_DATA_HPP_ -#include "behavior_path_planner/marker_utils/utils.hpp" #include "behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/freespace_pull_out.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/freespace_pull_out.hpp index 2b2de183b2dac..d78df16f89a80 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/freespace_pull_out.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/freespace_pull_out.hpp @@ -24,7 +24,6 @@ #include #include -#include namespace behavior_path_planner { diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/pull_out_planner_base.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/pull_out_planner_base.hpp index cb662efd767bf..4c9271d57127d 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/pull_out_planner_base.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/pull_out_planner_base.hpp @@ -16,7 +16,6 @@ #define BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__PULL_OUT_PLANNER_BASE_HPP_ #include "behavior_path_planner/data_manager.hpp" -#include "behavior_path_planner/parameters.hpp" #include "behavior_path_planner/utils/create_vehicle_footprint.hpp" #include "behavior_path_planner/utils/start_planner/pull_out_path.hpp" #include "behavior_path_planner/utils/start_planner/start_planner_parameters.hpp" @@ -27,14 +26,13 @@ #include #include -#include +namespace behavior_path_planner +{ using autoware_auto_planning_msgs::msg::PathWithLaneId; using geometry_msgs::msg::Pose; using tier4_autoware_utils::LinearRing2d; -namespace behavior_path_planner -{ enum class PlannerType { NONE = 0, SHIFT = 1, diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/util.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/util.hpp index f2dba684de991..e7f51b2e86d5b 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/util.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/util.hpp @@ -18,7 +18,6 @@ #include "behavior_path_planner/data_manager.hpp" #include "behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include "behavior_path_planner/utils/path_safety_checker/safety_check.hpp" -#include "behavior_path_planner/utils/start_planner/pull_out_path.hpp" #include @@ -32,7 +31,6 @@ #include #include -#include namespace behavior_path_planner::start_planner_utils { diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp index 3e03a09d3adf8..f418c9c7300f7 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp @@ -16,14 +16,8 @@ #define BEHAVIOR_PATH_PLANNER__UTILS__UTILS_HPP_ #include "behavior_path_planner/data_manager.hpp" -#include "behavior_path_planner/marker_utils/utils.hpp" -#include "behavior_path_planner/utils/lane_change/lane_change_module_data.hpp" -#include "behavior_path_planner/utils/lane_following/module_data.hpp" #include "behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp" -#include "behavior_path_planner/utils/path_safety_checker/safety_check.hpp" -#include "behavior_path_planner/utils/start_planner/pull_out_path.hpp" #include "motion_utils/trajectory/trajectory.hpp" -#include "object_recognition_utils/predicted_path_utils.hpp" #include #include @@ -51,8 +45,6 @@ #include #include #include -#include -#include #include namespace behavior_path_planner::utils diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index 3fb9060835698..52adfc72ce761 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -15,8 +15,13 @@ #include "behavior_path_planner/behavior_path_planner_node.hpp" #include "behavior_path_planner/marker_utils/utils.hpp" +#include "behavior_path_planner/scene_module/avoidance/manager.hpp" +#include "behavior_path_planner/scene_module/dynamic_avoidance/manager.hpp" +#include "behavior_path_planner/scene_module/goal_planner/manager.hpp" #include "behavior_path_planner/scene_module/lane_change/interface.hpp" -#include "behavior_path_planner/utils/drivable_area_expansion/map_utils.hpp" +#include "behavior_path_planner/scene_module/lane_change/manager.hpp" +#include "behavior_path_planner/scene_module/side_shift/manager.hpp" +#include "behavior_path_planner/scene_module/start_planner/manager.hpp" #include "behavior_path_planner/utils/path_utils.hpp" #include @@ -26,7 +31,6 @@ #include #include -#include #include namespace diff --git a/planning/behavior_path_planner/src/marker_utils/avoidance/debug.cpp b/planning/behavior_path_planner/src/marker_utils/avoidance/debug.cpp index 14a7d5be6a58a..ce9cedc816a19 100644 --- a/planning/behavior_path_planner/src/marker_utils/avoidance/debug.cpp +++ b/planning/behavior_path_planner/src/marker_utils/avoidance/debug.cpp @@ -14,9 +14,7 @@ #include "behavior_path_planner/marker_utils/avoidance/debug.hpp" -#include "behavior_path_planner/utils/path_utils.hpp" #include "behavior_path_planner/utils/utils.hpp" -#include "motion_utils/trajectory/path_with_lane_id.hpp" #include @@ -29,7 +27,6 @@ namespace marker_utils::avoidance_marker { -using behavior_path_planner::AvoidLine; using tier4_autoware_utils::appendMarkerArray; using tier4_autoware_utils::calcDistance2d; using tier4_autoware_utils::calcOffsetPose; diff --git a/planning/behavior_path_planner/src/marker_utils/lane_change/debug.cpp b/planning/behavior_path_planner/src/marker_utils/lane_change/debug.cpp index a1b77b1802999..a7604124ebe43 100644 --- a/planning/behavior_path_planner/src/marker_utils/lane_change/debug.cpp +++ b/planning/behavior_path_planner/src/marker_utils/lane_change/debug.cpp @@ -25,8 +25,6 @@ #include #include -#include -#include #include #include diff --git a/planning/behavior_path_planner/src/marker_utils/utils.cpp b/planning/behavior_path_planner/src/marker_utils/utils.cpp index 03ac135ec4bc1..031926f2d9d1d 100644 --- a/planning/behavior_path_planner/src/marker_utils/utils.cpp +++ b/planning/behavior_path_planner/src/marker_utils/utils.cpp @@ -17,7 +17,6 @@ #include "behavior_path_planner/marker_utils/colors.hpp" #include "behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include "behavior_path_planner/utils/path_utils.hpp" -#include "behavior_path_planner/utils/utils.hpp" #include #include diff --git a/planning/behavior_path_planner/src/planner_manager.cpp b/planning/behavior_path_planner/src/planner_manager.cpp index d0e55ffa574fd..4c3d7cff0c24c 100644 --- a/planning/behavior_path_planner/src/planner_manager.cpp +++ b/planning/behavior_path_planner/src/planner_manager.cpp @@ -14,7 +14,6 @@ #include "behavior_path_planner/planner_manager.hpp" -#include "behavior_path_planner/utils/path_utils.hpp" #include "behavior_path_planner/utils/utils.hpp" #include "tier4_autoware_utils/ros/debug_publisher.hpp" #include "tier4_autoware_utils/system/stop_watch.hpp" 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 b4b0a871eec62..84064a1c38bcb 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 @@ -52,17 +52,12 @@ namespace behavior_path_planner { -using behavior_path_planner::utils::path_safety_checker::CollisionCheckDebug; using motion_utils::calcLongitudinalOffsetPose; using motion_utils::calcSignedArcLength; using motion_utils::findNearestIndex; -using motion_utils::findNearestSegmentIndex; using tier4_autoware_utils::appendMarkerArray; using tier4_autoware_utils::calcDistance2d; -using tier4_autoware_utils::calcInterpolatedPose; using tier4_autoware_utils::calcLateralDeviation; -using tier4_autoware_utils::calcLongitudinalDeviation; -using tier4_autoware_utils::calcYawDeviation; using tier4_autoware_utils::getPoint; using tier4_autoware_utils::getPose; using tier4_autoware_utils::toHexString; diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp index 24c074bcb629b..d8434593d2214 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp @@ -14,8 +14,8 @@ #include "behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp" -#include "behavior_path_planner/utils/path_utils.hpp" #include "behavior_path_planner/utils/utils.hpp" +#include "object_recognition_utils/predicted_path_utils.hpp" #include "signal_processing/lowpass_filter_1d.hpp" #include @@ -30,7 +30,6 @@ #include #include #include -#include #include #include namespace behavior_path_planner diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index dc1ac1466397d..6253097b1692d 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -17,11 +17,11 @@ #include "behavior_path_planner/utils/create_vehicle_footprint.hpp" #include "behavior_path_planner/utils/goal_planner/util.hpp" #include "behavior_path_planner/utils/path_safety_checker/objects_filtering.hpp" +#include "behavior_path_planner/utils/path_safety_checker/safety_check.hpp" #include "behavior_path_planner/utils/path_shifter/path_shifter.hpp" #include "behavior_path_planner/utils/path_utils.hpp" #include "behavior_path_planner/utils/start_goal_planner_common/utils.hpp" #include "behavior_path_planner/utils/utils.hpp" -#include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp" #include "tier4_autoware_utils/math/unit_conversion.hpp" #include @@ -38,7 +38,6 @@ #include using behavior_path_planner::utils::start_goal_planner_common::calcFeasibleDecelDistance; -using motion_utils::calcDecelDistWithJerkAndAccConstraints; using motion_utils::calcLongitudinalOffsetPose; using motion_utils::calcSignedArcLength; using motion_utils::findFirstNearestSegmentIndexWithSoftConstraints; diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/avoidance_by_lane_change.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/avoidance_by_lane_change.cpp index 1f305e3988828..daba02e1cee89 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/avoidance_by_lane_change.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/avoidance_by_lane_change.cpp @@ -17,7 +17,6 @@ #include "behavior_path_planner/utils/avoidance/utils.hpp" #include "behavior_path_planner/utils/path_safety_checker/objects_filtering.hpp" #include "behavior_path_planner/utils/path_utils.hpp" -#include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp" #include #include diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/external_request.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/external_request.cpp index a74a51b7e2cdb..3a304a9b5bb53 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/external_request.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/external_request.cpp @@ -14,18 +14,9 @@ #include "behavior_path_planner/scene_module/lane_change/external_request.hpp" -#include "behavior_path_planner/scene_module/scene_module_visitor.hpp" -#include "behavior_path_planner/utils/lane_change/utils.hpp" -#include "behavior_path_planner/utils/path_utils.hpp" - #include -#include -#include #include -#include -#include -#include namespace behavior_path_planner { diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp index 0a0cc3436bce7..22c8ac022ad1a 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp @@ -19,12 +19,10 @@ #include "behavior_path_planner/scene_module/scene_module_interface.hpp" #include "behavior_path_planner/scene_module/scene_module_visitor.hpp" #include "behavior_path_planner/utils/lane_change/utils.hpp" -#include "behavior_path_planner/utils/path_utils.hpp" #include #include -#include #include #include #include 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 c6995ada1bfa6..78e05c940a814 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 @@ -21,7 +21,6 @@ #include #include -#include #include namespace behavior_path_planner 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 de4afc9260da0..de120592e7505 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 @@ -15,9 +15,9 @@ #include "behavior_path_planner/scene_module/lane_change/normal.hpp" #include "behavior_path_planner/marker_utils/utils.hpp" -#include "behavior_path_planner/scene_module/scene_module_visitor.hpp" #include "behavior_path_planner/utils/lane_change/utils.hpp" #include "behavior_path_planner/utils/path_safety_checker/objects_filtering.hpp" +#include "behavior_path_planner/utils/path_safety_checker/safety_check.hpp" #include "behavior_path_planner/utils/path_utils.hpp" #include "behavior_path_planner/utils/utils.hpp" diff --git a/planning/behavior_path_planner/src/scene_module/side_shift/side_shift_module.cpp b/planning/behavior_path_planner/src/scene_module/side_shift/side_shift_module.cpp index 4e9680cee4d59..2232c6d750d55 100644 --- a/planning/behavior_path_planner/src/scene_module/side_shift/side_shift_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/side_shift/side_shift_module.cpp @@ -32,7 +32,6 @@ using motion_utils::calcSignedArcLength; using motion_utils::findNearestIndex; using motion_utils::findNearestSegmentIndex; using tier4_autoware_utils::calcDistance2d; -using tier4_autoware_utils::calcOffsetPose; using tier4_autoware_utils::getPoint; SideShiftModule::SideShiftModule( diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp index c828a747856d8..ed14292747e68 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp @@ -20,7 +20,6 @@ #include "behavior_path_planner/utils/start_goal_planner_common/utils.hpp" #include "behavior_path_planner/utils/start_planner/util.hpp" #include "motion_utils/trajectory/trajectory.hpp" -#include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp" #include #include @@ -39,7 +38,6 @@ using motion_utils::calcLongitudinalOffsetPose; using tier4_autoware_utils::calcOffsetPose; -using tier4_autoware_utils::inverseTransformPoint; namespace behavior_path_planner { diff --git a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp index 8fb30a28f1272..a9f40dad86ae4 100644 --- a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp +++ b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp @@ -18,7 +18,6 @@ #include "behavior_path_planner/utils/avoidance/utils.hpp" #include "behavior_path_planner/utils/path_safety_checker/objects_filtering.hpp" #include "behavior_path_planner/utils/path_utils.hpp" -#include "motion_utils/trajectory/path_with_lane_id.hpp" #include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp" #include diff --git a/planning/behavior_path_planner/src/utils/geometric_parallel_parking/geometric_parallel_parking.cpp b/planning/behavior_path_planner/src/utils/geometric_parallel_parking/geometric_parallel_parking.cpp index 3d315e7213f96..d5bf67f754ab7 100644 --- a/planning/behavior_path_planner/src/utils/geometric_parallel_parking/geometric_parallel_parking.cpp +++ b/planning/behavior_path_planner/src/utils/geometric_parallel_parking/geometric_parallel_parking.cpp @@ -17,7 +17,6 @@ #include "behavior_path_planner/utils/path_utils.hpp" #include "behavior_path_planner/utils/start_planner/util.hpp" #include "behavior_path_planner/utils/utils.hpp" -#include "motion_utils/trajectory/path_with_lane_id.hpp" #include "tier4_autoware_utils/geometry/geometry.hpp" #include "tier4_autoware_utils/math/unit_conversion.hpp" @@ -37,8 +36,6 @@ #include -#include -#include #include #include diff --git a/planning/behavior_path_planner/src/utils/goal_planner/default_fixed_goal_planner.cpp b/planning/behavior_path_planner/src/utils/goal_planner/default_fixed_goal_planner.cpp index 7efdbdf1552d5..4c9832c374c63 100644 --- a/planning/behavior_path_planner/src/utils/goal_planner/default_fixed_goal_planner.cpp +++ b/planning/behavior_path_planner/src/utils/goal_planner/default_fixed_goal_planner.cpp @@ -21,7 +21,6 @@ #include #include -#include namespace behavior_path_planner { diff --git a/planning/behavior_path_planner/src/utils/goal_planner/geometric_pull_over.cpp b/planning/behavior_path_planner/src/utils/goal_planner/geometric_pull_over.cpp index a80f7892b0bef..017ecb218bea3 100644 --- a/planning/behavior_path_planner/src/utils/goal_planner/geometric_pull_over.cpp +++ b/planning/behavior_path_planner/src/utils/goal_planner/geometric_pull_over.cpp @@ -15,8 +15,6 @@ #include "behavior_path_planner/utils/goal_planner/geometric_pull_over.hpp" #include "behavior_path_planner/utils/goal_planner/util.hpp" -#include "behavior_path_planner/utils/path_utils.hpp" -#include "motion_utils/trajectory/path_with_lane_id.hpp" #include #include diff --git a/planning/behavior_path_planner/src/utils/goal_planner/goal_searcher.cpp b/planning/behavior_path_planner/src/utils/goal_planner/goal_searcher.cpp index 12044980ebd81..1e6dc1776359b 100644 --- a/planning/behavior_path_planner/src/utils/goal_planner/goal_searcher.cpp +++ b/planning/behavior_path_planner/src/utils/goal_planner/goal_searcher.cpp @@ -20,7 +20,6 @@ #include "lanelet2_extension/regulatory_elements/no_parking_area.hpp" #include "lanelet2_extension/regulatory_elements/no_stopping_area.hpp" #include "lanelet2_extension/utility/utilities.hpp" -#include "motion_utils/trajectory/path_with_lane_id.hpp" #include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp" #include @@ -37,7 +36,6 @@ using lane_departure_checker::LaneDepartureChecker; using lanelet::autoware::NoParkingArea; using lanelet::autoware::NoStoppingArea; using tier4_autoware_utils::calcOffsetPose; -using tier4_autoware_utils::inverseTransformPose; // Sort with smaller longitudinal distances taking precedence over smaller lateral distances. struct SortByLongitudinalDistance diff --git a/planning/behavior_path_planner/src/utils/goal_planner/shift_pull_over.cpp b/planning/behavior_path_planner/src/utils/goal_planner/shift_pull_over.cpp index e1bdaf977dad8..60cc2d19c5f35 100644 --- a/planning/behavior_path_planner/src/utils/goal_planner/shift_pull_over.cpp +++ b/planning/behavior_path_planner/src/utils/goal_planner/shift_pull_over.cpp @@ -16,8 +16,6 @@ #include "behavior_path_planner/utils/goal_planner/util.hpp" #include "behavior_path_planner/utils/path_utils.hpp" -#include "behavior_path_planner/utils/start_goal_planner_common/utils.hpp" -#include "motion_utils/trajectory/path_with_lane_id.hpp" #include #include diff --git a/planning/behavior_path_planner/src/utils/goal_planner/util.cpp b/planning/behavior_path_planner/src/utils/goal_planner/util.cpp index e7fa5e42dc092..1cd985d566f73 100644 --- a/planning/behavior_path_planner/src/utils/goal_planner/util.cpp +++ b/planning/behavior_path_planner/src/utils/goal_planner/util.cpp @@ -14,9 +14,6 @@ #include "behavior_path_planner/utils/goal_planner/util.hpp" -#include "behavior_path_planner/utils/path_shifter/path_shifter.hpp" -#include "behavior_path_planner/utils/path_utils.hpp" - #include #include #include @@ -29,7 +26,6 @@ #include #include -#include #include #include #include diff --git a/planning/behavior_path_planner/src/utils/lane_change/utils.cpp b/planning/behavior_path_planner/src/utils/lane_change/utils.cpp index 6d25cb8751a8e..d5867c40824d2 100644 --- a/planning/behavior_path_planner/src/utils/lane_change/utils.cpp +++ b/planning/behavior_path_planner/src/utils/lane_change/utils.cpp @@ -14,13 +14,14 @@ #include "behavior_path_planner/utils/lane_change/utils.hpp" +#include "behavior_path_planner/marker_utils/utils.hpp" #include "behavior_path_planner/parameters.hpp" #include "behavior_path_planner/utils/lane_change/lane_change_module_data.hpp" #include "behavior_path_planner/utils/lane_change/lane_change_path.hpp" -#include "behavior_path_planner/utils/path_safety_checker/safety_check.hpp" #include "behavior_path_planner/utils/path_shifter/path_shifter.hpp" #include "behavior_path_planner/utils/path_utils.hpp" #include "behavior_path_planner/utils/utils.hpp" +#include "object_recognition_utils/predicted_path_utils.hpp" #include #include @@ -39,7 +40,6 @@ #include #include -#include #include #include 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 dfc9f76b25e33..a7c604985de3a 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 @@ -15,6 +15,7 @@ #include "behavior_path_planner/utils/path_safety_checker/objects_filtering.hpp" #include "behavior_path_planner/utils/utils.hpp" +#include "object_recognition_utils/predicted_path_utils.hpp" #include #include 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 08ebd01ba5d05..8ebc144a34584 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 @@ -14,11 +14,8 @@ #include "behavior_path_planner/utils/path_safety_checker/safety_check.hpp" -#include "behavior_path_planner/marker_utils/utils.hpp" #include "interpolation/linear_interpolation.hpp" -#include "motion_utils/trajectory/path_with_lane_id.hpp" #include "motion_utils/trajectory/trajectory.hpp" -#include "object_recognition_utils/predicted_path_utils.hpp" #include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp" #include @@ -27,6 +24,9 @@ namespace behavior_path_planner::utils::path_safety_checker { + +namespace bg = boost::geometry; + void appendPointToPolygon(Polygon2d & polygon, const geometry_msgs::msg::Point & geom_point) { Point2d point; 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 21d4ff666e28a..df2d82b1072d4 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 @@ -15,13 +15,11 @@ #include "behavior_path_planner/utils/path_shifter/path_shifter.hpp" #include "behavior_path_planner/utils/path_utils.hpp" -#include "behavior_path_planner/utils/utils.hpp" #include #include #include -#include #include #include #include diff --git a/planning/behavior_path_planner/src/utils/path_utils.cpp b/planning/behavior_path_planner/src/utils/path_utils.cpp index 1ac63f4a4be87..3ac3c09ba0d97 100644 --- a/planning/behavior_path_planner/src/utils/path_utils.cpp +++ b/planning/behavior_path_planner/src/utils/path_utils.cpp @@ -15,7 +15,6 @@ #include "behavior_path_planner/utils/path_utils.hpp" #include "behavior_path_planner/utils/utils.hpp" -#include "motion_utils/trajectory/path_with_lane_id.hpp" #include #include @@ -23,7 +22,6 @@ #include #include -// #include #include #include diff --git a/planning/behavior_path_planner/src/utils/utils.cpp b/planning/behavior_path_planner/src/utils/utils.cpp index cb0486b6cd01b..6927327e24ef4 100644 --- a/planning/behavior_path_planner/src/utils/utils.cpp +++ b/planning/behavior_path_planner/src/utils/utils.cpp @@ -15,7 +15,9 @@ #include "behavior_path_planner/utils/utils.hpp" #include "behavior_path_planner/utils/drivable_area_expansion/drivable_area_expansion.hpp" +#include "behavior_path_planner/utils/path_shifter/path_shifter.hpp" #include "motion_utils/trajectory/path_with_lane_id.hpp" +#include "object_recognition_utils/predicted_path_utils.hpp" #include #include @@ -24,9 +26,6 @@ #include #include -#include "autoware_auto_perception_msgs/msg/predicted_object.hpp" -#include "autoware_auto_perception_msgs/msg/predicted_path.hpp" - #include #include diff --git a/planning/behavior_path_planner/test/input.hpp b/planning/behavior_path_planner/test/input.hpp index de167bc8b4bcb..ededb32f78be0 100644 --- a/planning/behavior_path_planner/test/input.hpp +++ b/planning/behavior_path_planner/test/input.hpp @@ -16,9 +16,11 @@ #define INPUT_HPP_ #endif // INPUT_HPP_ -#include "behavior_path_planner/utils/utils.hpp" #include "autoware_auto_planning_msgs/msg/path_point.hpp" +#include "autoware_auto_planning_msgs/msg/path_point_with_lane_id.hpp" +#include "autoware_auto_planning_msgs/msg/path_with_lane_id.hpp" +#include "geometry_msgs/msg/pose.hpp" #include "geometry_msgs/msg/twist.hpp" #include @@ -26,6 +28,9 @@ namespace behavior_path_planner { using autoware_auto_planning_msgs::msg::PathPoint; +using autoware_auto_planning_msgs::msg::PathPointWithLaneId; +using autoware_auto_planning_msgs::msg::PathWithLaneId; +using geometry_msgs::msg::Pose; using geometry_msgs::msg::Twist; PathWithLaneId generateStraightSamplePathWithLaneId( float initial_pose_value, float pose_increment, size_t point_sample); From 45b05031b3ed3fa83033b2e7c3763115b121d589 Mon Sep 17 00:00:00 2001 From: Vincent Richard Date: Thu, 19 Oct 2023 15:03:22 +0900 Subject: [PATCH 028/202] perf(pointcloud_preprocessor): move print out of hot loop (#5283) * perf(pointcloud_preprocessor): move print out of hot loop Signed-off-by: Vincent Richard * style(pre-commit): autofix --------- Signed-off-by: Vincent Richard Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../src/crop_box_filter/crop_box_filter_nodelet.cpp | 13 +++++++++++-- 1 file changed, 11 insertions(+), 2 deletions(-) diff --git a/sensing/pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_nodelet.cpp index 0cae2c90c2f16..20d1f5c8b3d6d 100644 --- a/sensing/pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_nodelet.cpp @@ -119,7 +119,8 @@ void CropBoxFilterComponent::faster_filter( stop_watch_ptr_->toc("processing_time", true); if (indices) { - RCLCPP_WARN(get_logger(), "Indices are not supported and will be ignored"); + RCLCPP_WARN_THROTTLE( + get_logger(), *get_clock(), 1000, "Indices are not supported and will be ignored"); } int x_offset = input->fields[pcl::getFieldIndex(*input, "x")].offset; @@ -129,6 +130,8 @@ void CropBoxFilterComponent::faster_filter( output.data.resize(input->data.size()); size_t output_size = 0; + int skipped_count = 0; + for (size_t global_offset = 0; global_offset + input->point_step <= input->data.size(); global_offset += input->point_step) { Eigen::Vector4f point; @@ -138,7 +141,7 @@ void CropBoxFilterComponent::faster_filter( point[3] = 1; if (!std::isfinite(point[0]) || !std::isfinite(point[1]) || !std::isfinite(point[2])) { - RCLCPP_WARN(this->get_logger(), "Ignoring point containing NaN values"); + skipped_count++; continue; } @@ -162,6 +165,12 @@ void CropBoxFilterComponent::faster_filter( } } + if (skipped_count > 0) { + RCLCPP_WARN_THROTTLE( + get_logger(), *get_clock(), 1000, "%d points contained NaN values and have been ignored", + skipped_count); + } + output.data.resize(output_size); // Note that tf_input_orig_frame_ is the input frame, while tf_input_frame_ is the frame of the From 48568b737e07d580c66e2819aa6c15bd94a10a42 Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Thu, 19 Oct 2023 16:05:03 +0900 Subject: [PATCH 029/202] fix(ndt_scan_matcher): fix `validate_num_iteration` (#5354) Fixed validate_num_iteration Signed-off-by: Shintaro SAKODA --- .../ndt_scan_matcher/src/ndt_scan_matcher_core.cpp | 14 +------------- 1 file changed, 1 insertion(+), 13 deletions(-) diff --git a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp index b7f32d2de53ff..8e583fd3a666b 100644 --- a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp +++ b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp @@ -448,20 +448,8 @@ void NDTScanMatcher::callback_sensor_points( } // perform several validations - /***************************************************************************** - The reason the add 2 to the ndt_ptr_->getMaximumIterations() is that there are bugs in - implementation of ndt. - 1. gradient descent method ends when the iteration is greater than max_iteration if it does not - converge (be careful it's 'greater than' instead of 'greater equal than'.) - https://github.com/tier4/autoware.iv/blob/2323e5baa0b680d43a9219f5fb3b7a11dd9edc82/localization/pose_estimator/ndt_scan_matcher/ndt_omp/include/ndt_omp/ndt_omp_impl.hpp#L212 - 2. iterate iteration count when end of gradient descent function. - https://github.com/tier4/autoware.iv/blob/2323e5baa0b680d43a9219f5fb3b7a11dd9edc82/localization/pose_estimator/ndt_scan_matcher/ndt_omp/include/ndt_omp/ndt_omp_impl.hpp#L217 - - These bugs are now resolved in original pcl implementation. - https://github.com/PointCloudLibrary/pcl/blob/424c1c6a0ca97d94ca63e5daff4b183a4db8aae4/registration/include/pcl/registration/impl/ndt.hpp#L73-L180 - *****************************************************************************/ bool is_ok_iteration_num = - validate_num_iteration(ndt_result.iteration_num, ndt_ptr_->getMaximumIterations() + 2); + validate_num_iteration(ndt_result.iteration_num, ndt_ptr_->getMaximumIterations()); bool is_local_optimal_solution_oscillation = false; if (!is_ok_iteration_num) { is_local_optimal_solution_oscillation = validate_local_optimal_solution_oscillation( From 0d0a22c175a333a487f434c01da2ebb15621db24 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 19 Oct 2023 16:17:36 +0900 Subject: [PATCH 030/202] feat(planner_manager): limit iteration number by parameter (#5352) Signed-off-by: satoshi-ota --- .../config/behavior_path_planner.param.yaml | 1 + .../behavior_path_planner/parameters.hpp | 1 + .../behavior_path_planner/planner_manager.hpp | 4 +++- .../src/behavior_path_planner_node.cpp | 3 ++- .../src/planner_manager.cpp | 17 ++++++++++++++--- 5 files changed, 21 insertions(+), 5 deletions(-) diff --git a/planning/behavior_path_planner/config/behavior_path_planner.param.yaml b/planning/behavior_path_planner/config/behavior_path_planner.param.yaml index 95c60612bfdb7..d333cbfd778cb 100644 --- a/planning/behavior_path_planner/config/behavior_path_planner.param.yaml +++ b/planning/behavior_path_planner/config/behavior_path_planner.param.yaml @@ -1,6 +1,7 @@ /**: ros__parameters: verbose: false + max_iteration_num: 100 planning_hz: 10.0 backward_path_length: 5.0 forward_path_length: 300.0 diff --git a/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp b/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp index 40df1f5157c71..a4e6fc18ab050 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp @@ -76,6 +76,7 @@ struct LateralAccelerationMap struct BehaviorPathPlannerParameters { bool verbose; + size_t max_iteration_num{100}; ModuleConfigParameters config_avoidance; ModuleConfigParameters config_avoidance_by_lc; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp index c0437aa69764a..1d1ad56342f4d 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp @@ -94,7 +94,7 @@ struct SceneModuleStatus class PlannerManager { public: - PlannerManager(rclcpp::Node & node, const bool verbose); + PlannerManager(rclcpp::Node & node, const size_t max_iteration_num, const bool verbose); /** * @brief run all candidate and approved modules. @@ -443,6 +443,8 @@ class PlannerManager mutable std::shared_ptr debug_msg_ptr_; + size_t max_iteration_num_{100}; + bool verbose_{false}; }; } // namespace behavior_path_planner diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index 52adfc72ce761..0777822650dfb 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -136,7 +136,7 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod const std::lock_guard lock(mutex_manager_); // for planner_manager_ const auto & p = planner_data_->parameters; - planner_manager_ = std::make_shared(*this, p.verbose); + planner_manager_ = std::make_shared(*this, p.max_iteration_num, p.verbose); const auto register_and_create_publisher = [&](const auto & manager, const bool create_publishers) { @@ -276,6 +276,7 @@ BehaviorPathPlannerParameters BehaviorPathPlannerNode::getCommonParam() BehaviorPathPlannerParameters p{}; p.verbose = declare_parameter("verbose"); + p.max_iteration_num = declare_parameter("max_iteration_num"); const auto get_scene_module_manager_param = [&](std::string && ns) { ModuleConfigParameters config; diff --git a/planning/behavior_path_planner/src/planner_manager.cpp b/planning/behavior_path_planner/src/planner_manager.cpp index 4c3d7cff0c24c..442049654d64e 100644 --- a/planning/behavior_path_planner/src/planner_manager.cpp +++ b/planning/behavior_path_planner/src/planner_manager.cpp @@ -28,9 +28,11 @@ namespace behavior_path_planner { -PlannerManager::PlannerManager(rclcpp::Node & node, const bool verbose) +PlannerManager::PlannerManager( + rclcpp::Node & node, const size_t max_iteration_num, const bool verbose) : logger_(node.get_logger().get_child("planner_manager")), clock_(*node.get_clock()), + max_iteration_num_{max_iteration_num}, verbose_{verbose} { processing_time_.emplace("total_time", 0.0); @@ -81,7 +83,7 @@ BehaviorModuleOutput PlannerManager::run(const std::shared_ptr & da return output; } - while (rclcpp::ok()) { + for (size_t itr_num = 0;; ++itr_num) { /** * STEP1: get approved modules' output */ @@ -127,8 +129,17 @@ BehaviorModuleOutput PlannerManager::run(const std::shared_ptr & da addApprovedModule(highest_priority_module); clearCandidateModules(); debug_info_.emplace_back(highest_priority_module, Action::ADD, "To Approval"); + + if (itr_num >= max_iteration_num_) { + RCLCPP_WARN_THROTTLE( + logger_, clock_, 1000, "Reach iteration limit (max: %ld). Output current result.", + max_iteration_num_); + processing_time_.at("total_time") = stop_watch_.toc("total_time", true); + return candidate_modules_output; + } } - return BehaviorModuleOutput{}; + + return BehaviorModuleOutput{}; // something wrong. }(); std::for_each( From c75d581016c559e7bd8a6bf3e63b173c13e30d63 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Thu, 19 Oct 2023 17:18:14 +0900 Subject: [PATCH 031/202] feat(tier4_perception_launch): add parameter to control detection_by_tracker on/off (#5313) * add parameter to control detection_by_tracker on/off Signed-off-by: yoshiri * style(pre-commit): autofix * Update launch/tier4_perception_launch/launch/perception.launch.xml Co-authored-by: Shunsuke Miura <37187849+miursh@users.noreply.github.com> --------- Signed-off-by: yoshiri Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Shunsuke Miura <37187849+miursh@users.noreply.github.com> --- ...ra_lidar_fusion_based_detection.launch.xml | 19 ++++++++++++----- ...ar_radar_fusion_based_detection.launch.xml | 21 +++++++++++++------ .../lidar_based_detection.launch.xml | 19 ++++++++++++----- .../launch/perception.launch.xml | 3 +++ 4 files changed, 46 insertions(+), 16 deletions(-) diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml index 67e123ea5b018..59fe3f13f1231 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml @@ -192,7 +192,7 @@ - + @@ -329,19 +329,24 @@ + + + + - + - + + @@ -356,16 +361,20 @@ + + - + + + - + diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml index 07640495a5e19..11deaad5d06cc 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml @@ -217,7 +217,7 @@ - + @@ -367,21 +367,26 @@ + + + + - + - + + - + @@ -394,16 +399,20 @@ + + - + + + - + diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml index c844db39f4e9d..822c251ddad33 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml @@ -58,7 +58,7 @@ - + @@ -128,18 +128,23 @@ + + + + - + - + + @@ -154,16 +159,20 @@ + + - + + + - + diff --git a/launch/tier4_perception_launch/launch/perception.launch.xml b/launch/tier4_perception_launch/launch/perception.launch.xml index 63ea0cc7f0f3d..347606d91759f 100644 --- a/launch/tier4_perception_launch/launch/perception.launch.xml +++ b/launch/tier4_perception_launch/launch/perception.launch.xml @@ -96,6 +96,9 @@ + + + Date: Thu, 19 Oct 2023 23:12:44 +0900 Subject: [PATCH 032/202] feat(map_based_prediction): remove crossing fence path (#5356) * remove crossing fence path Signed-off-by: kyoichi-sugahara --------- Signed-off-by: kyoichi-sugahara --- .../map_based_prediction_node.hpp | 8 +++ .../src/map_based_prediction_node.cpp | 49 +++++++++++++++++++ 2 files changed, 57 insertions(+) diff --git a/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp b/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp index 3d01ab96e9b62..c4c7ff4a8e942 100644 --- a/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp +++ b/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp @@ -165,6 +165,14 @@ class MapBasedPredictionNode : public rclcpp::Node void mapCallback(const HADMapBin::ConstSharedPtr msg); void objectsCallback(const TrackedObjects::ConstSharedPtr in_objects); + bool doesPathCrossAnyFence(const PredictedPath & predicted_path); + bool doesPathCrossFence( + const PredictedPath & predicted_path, const lanelet::ConstLineString3d & fence_line); + lanelet::BasicLineString2d convertToFenceLine(const lanelet::ConstLineString3d & fence); + bool isIntersecting( + const geometry_msgs::msg::Point & point1, const geometry_msgs::msg::Point & point2, + const lanelet::ConstPoint3d & point3, const lanelet::ConstPoint3d & point4); + PredictedObjectKinematics convertToPredictedKinematics( const TrackedObjectKinematics & tracked_object); 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 745bccf6dbabe..6604a9dc1539a 100644 --- a/perception/map_based_prediction/src/map_based_prediction_node.cpp +++ b/perception/map_based_prediction/src/map_based_prediction_node.cpp @@ -976,6 +976,46 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt pub_calculation_time_->publish(calculation_time_msg); } +bool MapBasedPredictionNode::doesPathCrossAnyFence(const PredictedPath & predicted_path) +{ + const lanelet::ConstLineStrings3d & all_fences = + lanelet::utils::query::getAllFences(lanelet_map_ptr_); + for (const auto & fence_line : all_fences) { + if (doesPathCrossFence(predicted_path, fence_line)) { + return true; + } + } + return false; +} + +bool MapBasedPredictionNode::doesPathCrossFence( + const PredictedPath & predicted_path, const lanelet::ConstLineString3d & fence_line) +{ + // check whether the predicted path cross with fence + for (size_t i = 0; i < predicted_path.path.size(); ++i) { + for (size_t j = 0; j < fence_line.size() - 1; ++j) { + if (isIntersecting( + predicted_path.path[i].position, predicted_path.path[i + 1].position, fence_line[j], + fence_line[j + 1])) { + return true; + } + } + } + return false; +} + +bool MapBasedPredictionNode::isIntersecting( + const geometry_msgs::msg::Point & point1, const geometry_msgs::msg::Point & point2, + const lanelet::ConstPoint3d & point3, const lanelet::ConstPoint3d & point4) +{ + const auto p1 = tier4_autoware_utils::createPoint(point1.x, point1.y, 0.0); + const auto p2 = tier4_autoware_utils::createPoint(point2.x, point2.y, 0.0); + const auto p3 = tier4_autoware_utils::createPoint(point3.x(), point3.y(), 0.0); + const auto p4 = tier4_autoware_utils::createPoint(point4.x(), point4.y(), 0.0); + const auto intersection = tier4_autoware_utils::intersect(p1, p2, p3, p4); + return intersection.has_value(); +} + PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser( const TrackedObject & object) { @@ -995,6 +1035,7 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser( } } + // If the object is in the crosswalk, generate path to the crosswalk edge if (crossing_crosswalk) { const auto edge_points = getCrosswalkEdgePoints(crossing_crosswalk.get()); @@ -1018,6 +1059,8 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser( predicted_object.kinematics.predicted_paths.push_back(predicted_path); } + // If the object is not crossing the crosswalk, in the road lanelets, try to find the closest + // crosswalk and generate path to the crosswalk edge } else if (withinRoadLanelet(object, lanelet_map_ptr_)) { lanelet::ConstLanelet closest_crosswalk{}; const auto & obj_pose = object.kinematics.pose_with_covariance.pose; @@ -1048,6 +1091,8 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser( } } + // If the object is not crossing the crosswalk, not in the road lanelets, try to find the edge + // points for all crosswalks and generate path to the crosswalk edge } else { for (const auto & crosswalk : crosswalks_) { const auto edge_points = getCrosswalkEdgePoints(crosswalk); @@ -1080,6 +1125,10 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser( if (predicted_path.path.empty()) { continue; } + // If the predicted path to the crosswalk is crossing the fence, don't use it + if (doesPathCrossAnyFence(predicted_path)) { + continue; + } predicted_object.kinematics.predicted_paths.push_back(predicted_path); } From 55e0deabf8f9f4fab0aa4c8b50f6db2d7a706610 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 20 Oct 2023 09:33:57 +0900 Subject: [PATCH 033/202] fix(route_handler): fix getting next lane logic to prevent from unexpected path cut (#5355) Signed-off-by: satoshi-ota --- planning/route_handler/src/route_handler.cpp | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/planning/route_handler/src/route_handler.cpp b/planning/route_handler/src/route_handler.cpp index ba9c46f157f2b..cf309a294d81f 100644 --- a/planning/route_handler/src/route_handler.cpp +++ b/planning/route_handler/src/route_handler.cpp @@ -855,12 +855,11 @@ bool RouteHandler::getNextLaneletWithinRoute( return false; } - lanelet::ConstLanelet start_lanelet; - const bool flag_check = getClosestLaneletWithinRoute(route_ptr_->start_pose, &start_lanelet); + const auto start_lane_id = route_ptr_->segments.front().preferred_primitive.id; const auto following_lanelets = routing_graph_ptr_->following(lanelet); for (const auto & llt : following_lanelets) { - if (!(flag_check && start_lanelet.id() == llt.id()) && exists(route_lanelets_, llt)) { + if (start_lane_id != llt.id() && exists(route_lanelets_, llt)) { *next_lanelet = llt; return true; } From d36be5529cc66b27be0edb314b7647b210663b37 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Fri, 20 Oct 2023 11:14:21 +0900 Subject: [PATCH 034/202] feat(map_based_prediction): enable to control lateral path convergence speed by setting control time horizon (#5285) * enable to control lateral path convergence speed by setting control time horizon Signed-off-by: yoshiri * update readme Signed-off-by: yoshiri * add comment in generate path function Signed-off-by: yoshiri --------- Signed-off-by: yoshiri --- perception/map_based_prediction/README.md | 16 ++++++++++++++ .../config/map_based_prediction.param.yaml | 1 + .../map_based_prediction_node.hpp | 1 + .../map_based_prediction/path_generator.hpp | 5 +++-- .../src/map_based_prediction_node.cpp | 5 ++++- .../src/path_generator.cpp | 22 +++++++++++++------ 6 files changed, 40 insertions(+), 10 deletions(-) diff --git a/perception/map_based_prediction/README.md b/perception/map_based_prediction/README.md index 7631b47772862..6d3d7f5e035a9 100644 --- a/perception/map_based_prediction/README.md +++ b/perception/map_based_prediction/README.md @@ -109,6 +109,21 @@ For the additional information, here we show how we calculate lateral velocity. Currently, we use the upper method with a low-pass filter to calculate lateral velocity. +### Path generation + +Path generation is generated on the frenet frame. The path is generated by the following steps: + +1. Get the frenet frame of the reference path. +2. Generate the frenet frame of the current position of the object and the finite position of the object. +3. Optimize the path in each longitudinal and lateral coordinate of the frenet frame. (Use the quintic polynomial to fit start and end conditions.) +4. Convert the path to the global coordinate. + +See paper [2] for more details. + +#### Tuning lateral path shape + +`lateral_control_time_horizon` parameter supports the tuning of the lateral path shape. This parameter is used to calculate the time to reach the reference path. The smaller the value, the more the path will be generated to reach the reference path quickly. (Mostly the center of the lane.) + ### Path prediction for crosswalk users This module treats **Pedestrians** and **Bicycles** as objects using the crosswalk, and outputs prediction path based on map and estimated object's velocity, assuming the object has intention to cross the crosswalk, if the objects satisfies at least one of the following conditions: @@ -155,6 +170,7 @@ If the target object is inside the road or crosswalk, this module outputs one or | ---------------------------------------------------------------- | ----- | ------ | ------------------------------------------------------------------------------------------------------------------------------------- | | `enable_delay_compensation` | [-] | bool | flag to enable the time delay compensation for the position of the object | | `prediction_time_horizon` | [s] | double | predict time duration for predicted path | +| `lateral_control_time_horizon` | [s] | double | time duration for predicted path will reach the reference path (mostly center of the lane) | | `prediction_sampling_delta_time` | [s] | double | sampling time for points in predicted path | | `min_velocity_for_map_based_prediction` | [m/s] | double | apply map-based prediction to the objects with higher velocity than this value | | `min_crosswalk_user_velocity` | [m/s] | double | minimum velocity used when crosswalk user's velocity is calculated | 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 31fae9c811092..260ae45da2e05 100644 --- a/perception/map_based_prediction/config/map_based_prediction.param.yaml +++ b/perception/map_based_prediction/config/map_based_prediction.param.yaml @@ -2,6 +2,7 @@ ros__parameters: enable_delay_compensation: true prediction_time_horizon: 10.0 #[s] + lateral_control_time_horizon: 5.0 #[s] prediction_sampling_delta_time: 0.5 #[s] min_velocity_for_map_based_prediction: 1.39 #[m/s] min_crosswalk_user_velocity: 1.39 #[m/s] diff --git a/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp b/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp index c4c7ff4a8e942..01f39057aef36 100644 --- a/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp +++ b/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp @@ -135,6 +135,7 @@ class MapBasedPredictionNode : public rclcpp::Node // Parameters bool enable_delay_compensation_; double prediction_time_horizon_; + double lateral_control_time_horizon_; double prediction_time_horizon_rate_for_validate_lane_length_; double prediction_sampling_time_interval_; double min_velocity_for_map_based_prediction_; diff --git a/perception/map_based_prediction/include/map_based_prediction/path_generator.hpp b/perception/map_based_prediction/include/map_based_prediction/path_generator.hpp index 7bb1542557d2c..4da4f62be2ede 100644 --- a/perception/map_based_prediction/include/map_based_prediction/path_generator.hpp +++ b/perception/map_based_prediction/include/map_based_prediction/path_generator.hpp @@ -81,8 +81,8 @@ class PathGenerator { public: PathGenerator( - const double time_horizon, const double sampling_time_interval, - const double min_crosswalk_user_velocity); + const double time_horizon, const double lateral_time_horizon, + const double sampling_time_interval, const double min_crosswalk_user_velocity); PredictedPath generatePathForNonVehicleObject(const TrackedObject & object); @@ -102,6 +102,7 @@ class PathGenerator private: // Parameters double time_horizon_; + double lateral_time_horizon_; double sampling_time_interval_; double min_crosswalk_user_velocity_; 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 6604a9dc1539a..08fc06330b1d8 100644 --- a/perception/map_based_prediction/src/map_based_prediction_node.cpp +++ b/perception/map_based_prediction/src/map_based_prediction_node.cpp @@ -694,6 +694,8 @@ MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_ { enable_delay_compensation_ = declare_parameter("enable_delay_compensation"); prediction_time_horizon_ = declare_parameter("prediction_time_horizon"); + lateral_control_time_horizon_ = + declare_parameter("lateral_control_time_horizon"); // [s] for lateral control point prediction_sampling_time_interval_ = declare_parameter("prediction_sampling_delta_time"); min_velocity_for_map_based_prediction_ = declare_parameter("min_velocity_for_map_based_prediction"); @@ -740,7 +742,8 @@ MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_ 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_); + prediction_time_horizon_, lateral_control_time_horizon_, prediction_sampling_time_interval_, + min_crosswalk_user_velocity_); sub_objects_ = this->create_subscription( "~/input/objects", 1, diff --git a/perception/map_based_prediction/src/path_generator.cpp b/perception/map_based_prediction/src/path_generator.cpp index 547132410badf..5cb7e186b7cc4 100644 --- a/perception/map_based_prediction/src/path_generator.cpp +++ b/perception/map_based_prediction/src/path_generator.cpp @@ -23,9 +23,10 @@ namespace map_based_prediction { PathGenerator::PathGenerator( - const double time_horizon, const double sampling_time_interval, + const double time_horizon, const double lateral_time_horizon, const double sampling_time_interval, const double min_crosswalk_user_velocity) : time_horizon_(time_horizon), + lateral_time_horizon_(lateral_time_horizon), sampling_time_interval_(sampling_time_interval), min_crosswalk_user_velocity_(min_crosswalk_user_velocity) { @@ -213,18 +214,25 @@ FrenetPath PathGenerator::generateFrenetPath( { FrenetPath path; const double duration = time_horizon_; + const double lateral_duration = lateral_time_horizon_; // Compute Lateral and Longitudinal Coefficients to generate the trajectory - const Eigen::Vector3d lat_coeff = calcLatCoefficients(current_point, target_point, duration); + const Eigen::Vector3d lat_coeff = + calcLatCoefficients(current_point, target_point, lateral_duration); const Eigen::Vector2d lon_coeff = calcLonCoefficients(current_point, target_point, duration); path.reserve(static_cast(duration / sampling_time_interval_)); for (double t = 0.0; t <= duration; t += sampling_time_interval_) { - const double d_next = current_point.d + current_point.d_vel * t + 0 * 2 * std::pow(t, 2) + - lat_coeff(0) * std::pow(t, 3) + lat_coeff(1) * std::pow(t, 4) + - lat_coeff(2) * std::pow(t, 5); - const double s_next = current_point.s + current_point.s_vel * t + 2 * 0 * std::pow(t, 2) + - lon_coeff(0) * std::pow(t, 3) + lon_coeff(1) * std::pow(t, 4); + const double current_acc = + 0.0; // Currently we assume the object is traveling at a constant speed + const double d_next_ = current_point.d + current_point.d_vel * t + + current_acc * 2.0 * std::pow(t, 2) + lat_coeff(0) * std::pow(t, 3) + + lat_coeff(1) * std::pow(t, 4) + lat_coeff(2) * std::pow(t, 5); + // t > lateral_duration: 0.0, else d_next_ + const double d_next = t > lateral_duration ? 0.0 : d_next_; + const double s_next = current_point.s + current_point.s_vel * t + + 2.0 * current_acc * std::pow(t, 2) + lon_coeff(0) * std::pow(t, 3) + + lon_coeff(1) * std::pow(t, 4); if (s_next > max_length) { break; } From 915d47dbb1bc01f27b33a9e4577fb14e83a609e6 Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Fri, 20 Oct 2023 16:42:06 +0900 Subject: [PATCH 035/202] fix(obstacle_stop_planner, dynamic avoidance): fix coordinate transformation bug (#5248) fix a known bug https://github.com/autowarefoundation/autoware.universe/pull/5180 Signed-off-by: Yuki Takagi --- .../dynamic_avoidance_module.cpp | 21 ++++++++----------- .../src/adaptive_cruise_control.cpp | 19 +++++++++++------ 2 files changed, 22 insertions(+), 18 deletions(-) diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp index d8434593d2214..2c5e78a267d5a 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp @@ -32,6 +32,7 @@ #include #include #include + namespace behavior_path_planner { namespace @@ -105,21 +106,17 @@ std::pair projectObstacleVelocityToTrajectory( const std::vector & path_points, const PredictedObject & object) { const auto & obj_pose = object.kinematics.initial_pose_with_covariance.pose; - const double obj_vel_norm = std::hypot( - object.kinematics.initial_twist_with_covariance.twist.linear.x, - object.kinematics.initial_twist_with_covariance.twist.linear.y); - - const size_t obj_idx = motion_utils::findNearestIndex(path_points, obj_pose.position); - const double obj_yaw = tf2::getYaw(obj_pose.orientation); - const double obj_vel_yaw = - obj_yaw + std::atan2( - object.kinematics.initial_twist_with_covariance.twist.linear.y, - object.kinematics.initial_twist_with_covariance.twist.linear.x); + const size_t obj_idx = motion_utils::findNearestIndex(path_points, obj_pose.position); const double path_yaw = tf2::getYaw(path_points.at(obj_idx).point.pose.orientation); - const double diff_yaw = tier4_autoware_utils::normalizeRadian(obj_vel_yaw - path_yaw); - return std::make_pair(obj_vel_norm * std::cos(diff_yaw), obj_vel_norm * std::sin(diff_yaw)); + const Eigen::Rotation2Dd R_ego_to_obstacle(obj_yaw - path_yaw); + const Eigen::Vector2d obstacle_velocity( + object.kinematics.initial_twist_with_covariance.twist.linear.x, + object.kinematics.initial_twist_with_covariance.twist.linear.y); + const Eigen::Vector2d projected_velocity = R_ego_to_obstacle * obstacle_velocity; + + return std::make_pair(projected_velocity[0], projected_velocity[1]); } double calcObstacleMaxLength(const autoware_auto_perception_msgs::msg::Shape & shape) diff --git a/planning/obstacle_stop_planner/src/adaptive_cruise_control.cpp b/planning/obstacle_stop_planner/src/adaptive_cruise_control.cpp index b33342b9dea4f..c0f57489078d6 100644 --- a/planning/obstacle_stop_planner/src/adaptive_cruise_control.cpp +++ b/planning/obstacle_stop_planner/src/adaptive_cruise_control.cpp @@ -427,9 +427,12 @@ bool AdaptiveCruiseController::estimatePointVelocityFromObject( obj_vel_norm = std::hypot( obj.kinematics.initial_twist_with_covariance.twist.linear.x, obj.kinematics.initial_twist_with_covariance.twist.linear.y); - obj_vel_yaw = std::atan2( - obj.kinematics.initial_twist_with_covariance.twist.linear.y, - obj.kinematics.initial_twist_with_covariance.twist.linear.x); + + const double obj_yaw = + tf2::getYaw(obj.kinematics.initial_pose_with_covariance.pose.orientation); + obj_vel_yaw = obj_yaw + std::atan2( + obj.kinematics.initial_twist_with_covariance.twist.linear.y, + obj.kinematics.initial_twist_with_covariance.twist.linear.x); get_obj = true; break; } @@ -451,9 +454,13 @@ void AdaptiveCruiseController::calculateProjectedVelocityFromObject( double obj_vel_norm = std::hypot( object.kinematics.initial_twist_with_covariance.twist.linear.x, object.kinematics.initial_twist_with_covariance.twist.linear.y); - double obj_vel_yaw = std::atan2( - object.kinematics.initial_twist_with_covariance.twist.linear.y, - object.kinematics.initial_twist_with_covariance.twist.linear.x); + + const double obj_yaw = + tf2::getYaw(object.kinematics.initial_pose_with_covariance.pose.orientation); + const double obj_vel_yaw = + obj_yaw + std::atan2( + object.kinematics.initial_twist_with_covariance.twist.linear.y, + object.kinematics.initial_twist_with_covariance.twist.linear.x); *velocity = obj_vel_norm * std::cos(tier4_autoware_utils::normalizeRadian(obj_vel_yaw - traj_yaw)); From e519c4b5f5e2900d1a62fc0182ade9b2df125fab Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Fri, 20 Oct 2023 16:51:31 +0900 Subject: [PATCH 036/202] chore(behavior_velocity_crosswalk_module): add maintainer (#5363) * add maintainer Signed-off-by: kyoichi-sugahara * style(pre-commit): autofix --------- Signed-off-by: kyoichi-sugahara Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- planning/behavior_velocity_crosswalk_module/package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/planning/behavior_velocity_crosswalk_module/package.xml b/planning/behavior_velocity_crosswalk_module/package.xml index 66f326ed799af..3830aa9edddff 100644 --- a/planning/behavior_velocity_crosswalk_module/package.xml +++ b/planning/behavior_velocity_crosswalk_module/package.xml @@ -9,6 +9,7 @@ Tomoya Kimura Shumpei Wakabayashi Takayuki Murooka + Kyoichi Sugahara Apache License 2.0 From 33bc810a591fefa9b52339d03ac54ff92472bc28 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Fri, 20 Oct 2023 19:04:52 +0900 Subject: [PATCH 037/202] feat(intersection): timeout static occlusion with traffic light (#5353) Signed-off-by: Mamoru Sobue --- .../config/intersection.param.yaml | 1 + .../src/debug.cpp | 14 +- .../src/manager.cpp | 2 + .../src/scene_intersection.cpp | 152 +++++++++++++----- .../src/scene_intersection.hpp | 23 ++- .../src/util.cpp | 2 +- .../src/util_type.hpp | 4 +- 7 files changed, 146 insertions(+), 52 deletions(-) diff --git a/planning/behavior_velocity_intersection_module/config/intersection.param.yaml b/planning/behavior_velocity_intersection_module/config/intersection.param.yaml index 1a5143678ddce..be8e822b31d5c 100644 --- a/planning/behavior_velocity_intersection_module/config/intersection.param.yaml +++ b/planning/behavior_velocity_intersection_module/config/intersection.param.yaml @@ -76,6 +76,7 @@ maximum_peeking_distance: 6.0 # [m] attention_lane_crop_curvature_threshold: 0.25 attention_lane_curvature_calculation_ds: 0.5 + static_occlusion_with_traffic_light_timeout: 3.5 enable_rtc: intersection: false # If set to true, the scene modules require approval from the rtc (request to cooperate) function. If set to false, the modules can be executed without requiring rtc approval diff --git a/planning/behavior_velocity_intersection_module/src/debug.cpp b/planning/behavior_velocity_intersection_module/src/debug.cpp index 3d5874c3c89e8..f472c4bf51e31 100644 --- a/planning/behavior_velocity_intersection_module/src/debug.cpp +++ b/planning/behavior_velocity_intersection_module/src/debug.cpp @@ -188,14 +188,6 @@ visualization_msgs::msg::MarkerArray IntersectionModule::createDebugMarkerArray( &debug_marker_array); } - if (debug_data_.intersection_area) { - appendMarkerArray( - debug::createPolygonMarkerArray( - debug_data_.intersection_area.value(), "intersection_area", lane_id_, now, 0.3, 0.0, 0.0, - 0.0, 1.0, 0.0), - &debug_marker_array); - } - if (debug_data_.stuck_vehicle_detect_area) { appendMarkerArray( debug::createPolygonMarkerArray( @@ -309,6 +301,12 @@ motion_utils::VirtualWalls IntersectionModule::createVirtualWalls() if (debug_data_.occlusion_stop_wall_pose) { wall.style = motion_utils::VirtualWallType::stop; wall.text = "intersection_occlusion"; + if (debug_data_.static_occlusion_with_traffic_light_timeout) { + std::stringstream timeout; + timeout << std::setprecision(2) + << debug_data_.static_occlusion_with_traffic_light_timeout.value(); + wall.text += "(" + timeout.str() + ")"; + } wall.ns = "intersection_occlusion" + std::to_string(module_id_) + "_"; wall.pose = debug_data_.occlusion_stop_wall_pose.value(); virtual_walls.push_back(wall); diff --git a/planning/behavior_velocity_intersection_module/src/manager.cpp b/planning/behavior_velocity_intersection_module/src/manager.cpp index 22fa57f20e79f..0b4131b55ed90 100644 --- a/planning/behavior_velocity_intersection_module/src/manager.cpp +++ b/planning/behavior_velocity_intersection_module/src/manager.cpp @@ -172,6 +172,8 @@ IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node) getOrDeclareParameter(node, ns + ".occlusion.attention_lane_crop_curvature_threshold"); ip.occlusion.attention_lane_curvature_calculation_ds = getOrDeclareParameter(node, ns + ".occlusion.attention_lane_curvature_calculation_ds"); + ip.occlusion.static_occlusion_with_traffic_light_timeout = getOrDeclareParameter( + node, ns + ".occlusion.static_occlusion_with_traffic_light_timeout"); } void IntersectionModuleManager::launchNewModules( diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp index b37b70f290ff6..1bbff9ecaf048 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -129,6 +129,11 @@ IntersectionModule::IntersectionModule( planner_param_.occlusion.before_creep_stop_time); temporal_stop_before_attention_state_machine_.setState(StateMachine::State::STOP); } + { + static_occlusion_timeout_state_machine_.setMarginTime( + planner_param_.occlusion.static_occlusion_with_traffic_light_timeout); + static_occlusion_timeout_state_machine_.setState(StateMachine::State::STOP); + } decision_state_pub_ = node_.create_publisher("~/debug/intersection/decision_state", 1); @@ -589,6 +594,8 @@ void reactRTCApprovalByDecisionResult( planning_utils::setVelocityFromIndex(occlusion_peeking_stop_line, 0.0, path); debug_data->occlusion_stop_wall_pose = planning_utils::getAheadPose(occlusion_peeking_stop_line, baselink2front, *path); + debug_data->static_occlusion_with_traffic_light_timeout = + decision_result.static_occlusion_timeout; { tier4_planning_msgs::msg::StopFactor stop_factor; stop_factor.stop_pose = path->points.at(occlusion_peeking_stop_line).point.pose; @@ -648,6 +655,8 @@ void reactRTCApprovalByDecisionResult( planning_utils::setVelocityFromIndex(stop_line_idx, 0.0, path); debug_data->occlusion_stop_wall_pose = planning_utils::getAheadPose(stop_line_idx, baselink2front, *path); + debug_data->static_occlusion_with_traffic_light_timeout = + decision_result.static_occlusion_timeout; { tier4_planning_msgs::msg::StopFactor stop_factor; stop_factor.stop_pose = path->points.at(stop_line_idx).point.pose; @@ -1017,6 +1026,19 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( } return state_machine.getState() == StateMachine::State::GO; }; + auto stoppedAtPosition = [&](const size_t pos, const double duration) { + const double dist_stopline = fromEgoDist(pos); + const bool approached_dist_stopline = + (std::fabs(dist_stopline) < planner_param_.common.stop_overshoot_margin); + const bool over_stopline = (dist_stopline < -planner_param_.common.stop_overshoot_margin); + const bool is_stopped = planner_data_->isVehicleStopped(duration); + if (over_stopline) { + return true; + } else if (is_stopped && approached_dist_stopline) { + return true; + } + return false; + }; // stuck vehicle detection is viable even if attention area is empty // so this needs to be checked before attention area validation @@ -1111,13 +1133,7 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( debug_data_.adjacent_area = intersection_lanelets.adjacent_area(); // get intersection area - const auto intersection_area = planner_param_.common.use_intersection_area - ? util::getIntersectionArea(assigned_lanelet, lanelet_map_ptr) - : std::nullopt; - if (intersection_area) { - const auto intersection_area_2d = intersection_area.value(); - debug_data_.intersection_area = toGeomPoly(intersection_area_2d); - } + const auto intersection_area = util::getIntersectionArea(assigned_lanelet, lanelet_map_ptr); auto target_objects = generateTargetObjects(intersection_lanelets, intersection_area); @@ -1143,8 +1159,9 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( } if (initial_green_light_observed_time_) { const auto now = clock_->now(); - const bool exist_close_vehicles = - std::any_of(target_objects.all.begin(), target_objects.all.end(), [&](const auto & object) { + const bool exist_close_vehicles = std::any_of( + target_objects.all_attention_objects.begin(), target_objects.all_attention_objects.end(), + [&](const auto & object) { return object.dist_to_stop_line.has_value() && object.dist_to_stop_line.value() < planner_param_.collision_detection.yield_on_green_traffic_light @@ -1194,27 +1211,30 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( const double occlusion_dist_thr = std::fabs( std::pow(planner_param_.occlusion.max_vehicle_velocity_for_rss, 2) / (2 * planner_param_.occlusion.min_vehicle_brake_for_rss)); - const auto blocking_attention_objects = target_objects.parked_attention_objects; - for (const auto & blocking_attention_object : blocking_attention_objects) { - debug_data_.blocking_attention_objects.objects.push_back(blocking_attention_object.object); - } - // debug_data_.blocking_attention_objects.objects = blocking_attention_objects; - const bool is_occlusion_cleared = + auto occlusion_status = (enable_occlusion_detection_ && !occlusion_attention_lanelets.empty() && !is_prioritized) - ? isOcclusionCleared( + ? getOcclusionStatus( *planner_data_->occupancy_grid, occlusion_attention_area, adjacent_lanelets, first_attention_area, interpolated_path_info, occlusion_attention_divisions, - blocking_attention_objects, occlusion_dist_thr) - : true; + target_objects, current_pose, occlusion_dist_thr) + : OcclusionType::NOT_OCCLUDED; occlusion_stop_state_machine_.setStateWithMarginTime( - is_occlusion_cleared ? StateMachine::State::GO : StateMachine::STOP, + occlusion_status == OcclusionType::NOT_OCCLUDED ? StateMachine::State::GO : StateMachine::STOP, logger_.get_child("occlusion_stop"), *clock_); const bool is_occlusion_cleared_with_margin = (occlusion_stop_state_machine_.getState() == StateMachine::State::GO); - // distinguish if ego detected occlusion or RTC detects occlusion const bool ext_occlusion_requested = (is_occlusion_cleared_with_margin && !occlusion_activated_); + if (ext_occlusion_requested) { + occlusion_status = OcclusionType::RTC_OCCLUDED; + } const bool is_occlusion_state = (!is_occlusion_cleared_with_margin || ext_occlusion_requested); + if (is_occlusion_state && occlusion_status == OcclusionType::NOT_OCCLUDED) { + occlusion_status = prev_occlusion_status_; + } else { + prev_occlusion_status_ = occlusion_status; + } + // Safe if (!is_occlusion_state && !has_collision_with_margin) { return IntersectionModule::Safe{closest_idx, collision_stop_line_idx, occlusion_stop_line_idx}; @@ -1225,11 +1245,13 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( closest_idx, collision_stop_line_idx, occlusion_stop_line_idx}; } // Occluded + // occlusion_status is assured to be not NOT_OCCLUDED const bool stopped_at_default_line = stoppedForDuration( default_stop_line_idx, planner_param_.occlusion.before_creep_stop_time, before_creep_state_machine_); if (stopped_at_default_line) { - // in this case ego will temporarily stop before entering attention area + // if specified the parameter occlusion.temporal_stop_before_attention_area OR + // has_no_traffic_light_, ego will temporarily stop before entering attention area const bool temporal_stop_before_attention_required = (planner_param_.occlusion.temporal_stop_before_attention_area || !has_traffic_light_) ? !stoppedForDuration( @@ -1246,20 +1268,51 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( temporal_stop_before_attention_required, closest_idx, first_attention_stop_line_idx, occlusion_stop_line_idx}; } + // following remaining block is "has_traffic_light_" + // if ego is stuck by static occlusion in the presence of traffic light, start timeout count + const bool is_static_occlusion = occlusion_status == OcclusionType::STATICALLY_OCCLUDED; + const bool is_stuck_by_static_occlusion = + stoppedAtPosition(occlusion_stop_line_idx, planner_param_.occlusion.before_creep_stop_time) && + is_static_occlusion; + if (has_collision_with_margin) { + // if collision is detected, timeout is reset + static_occlusion_timeout_state_machine_.setState(StateMachine::State::STOP); + } else if (is_stuck_by_static_occlusion) { + static_occlusion_timeout_state_machine_.setStateWithMarginTime( + StateMachine::State::GO, logger_.get_child("static_occlusion"), *clock_); + } + const bool release_static_occlusion_stuck = + (static_occlusion_timeout_state_machine_.getState() == StateMachine::State::GO); + if (!has_collision_with_margin && release_static_occlusion_stuck) { + return IntersectionModule::Safe{ + closest_idx, collision_stop_line_idx, occlusion_stop_line_idx}; + } + // occlusion_status is either STATICALLY_OCCLUDED or DYNAMICALLY_OCCLUDED + const double max_timeout = + planner_param_.occlusion.static_occlusion_with_traffic_light_timeout + + planner_param_.occlusion.stop_release_margin_time; + const std::optional static_occlusion_timeout = + is_stuck_by_static_occlusion + ? std::make_optional( + max_timeout - static_occlusion_timeout_state_machine_.getDuration() - + occlusion_stop_state_machine_.getDuration()) + : (is_static_occlusion ? std::make_optional(max_timeout) : std::nullopt); if (has_collision_with_margin) { return IntersectionModule::OccludedCollisionStop{is_occlusion_cleared_with_margin, temporal_stop_before_attention_required, closest_idx, collision_stop_line_idx, first_attention_stop_line_idx, - occlusion_stop_line_idx}; + occlusion_stop_line_idx, + static_occlusion_timeout}; } else { return IntersectionModule::PeekingTowardOcclusion{is_occlusion_cleared_with_margin, temporal_stop_before_attention_required, closest_idx, collision_stop_line_idx, first_attention_stop_line_idx, - occlusion_stop_line_idx}; + occlusion_stop_line_idx, + static_occlusion_timeout}; } } else { const auto occlusion_stop_line = @@ -1359,6 +1412,7 @@ util::TargetObjects IntersectionModule::generateTargetObjects( auto & container = is_parked_vehicle ? target_objects.parked_attention_objects : target_objects.attention_objects; if (intersection_area) { + const auto & obj_pos = object.kinematics.initial_pose_with_covariance.pose.position; const auto obj_poly = tier4_autoware_utils::toPolygon2d(object); const auto intersection_area_2d = intersection_area.value(); const auto belong_attention_lanelet_id = util::checkAngleForTargetLanelets( @@ -1366,18 +1420,18 @@ util::TargetObjects IntersectionModule::generateTargetObjects( planner_param_.common.consider_wrong_direction_vehicle, planner_param_.common.attention_area_margin, is_parked_vehicle); if (belong_attention_lanelet_id) { - const auto id = belong_adjacent_lanelet_id.value(); + const auto id = belong_attention_lanelet_id.value(); util::TargetObject target_object; target_object.object = object; target_object.attention_lanelet = attention_lanelets.at(id); target_object.stop_line = attention_lanelet_stoplines.at(id); container.push_back(target_object); - } else if (bg::within(obj_poly, intersection_area_2d)) { + } else if (bg::within(Point2d{obj_pos.x, obj_pos.y}, intersection_area_2d)) { util::TargetObject target_object; target_object.object = object; target_object.attention_lanelet = std::nullopt; target_object.stop_line = std::nullopt; - container.push_back(target_object); + target_objects.intersection_area_objects.push_back(target_object); } } else if (const auto belong_attention_lanelet_id = util::checkAngleForTargetLanelets( object_direction, attention_lanelets, @@ -1395,12 +1449,12 @@ util::TargetObjects IntersectionModule::generateTargetObjects( } } for (const auto & object : target_objects.attention_objects) { - target_objects.all.push_back(object); + target_objects.all_attention_objects.push_back(object); } for (const auto & object : target_objects.parked_attention_objects) { - target_objects.all.push_back(object); + target_objects.all_attention_objects.push_back(object); } - for (auto & object : target_objects.all) { + for (auto & object : target_objects.all_attention_objects) { object.calc_dist_to_stop_line(); } return target_objects; @@ -1467,7 +1521,7 @@ bool IntersectionModule::checkCollision( // check collision between predicted_path and ego_area bool collision_detected = false; - for (const auto & target_object : target_objects->all) { + for (const auto & target_object : target_objects->all_attention_objects) { const auto & object = target_object.object; // If the vehicle is expected to stop before their stopline, ignore if ( @@ -1566,14 +1620,14 @@ bool IntersectionModule::checkCollision( return collision_detected; } -bool IntersectionModule::isOcclusionCleared( +IntersectionModule::OcclusionType IntersectionModule::getOcclusionStatus( const nav_msgs::msg::OccupancyGrid & occ_grid, const std::vector & attention_areas, const lanelet::ConstLanelets & adjacent_lanelets, const lanelet::CompoundPolygon3d & first_attention_area, const util::InterpolatedPathInfo & interpolated_path_info, const std::vector & lane_divisions, - const std::vector & blocking_attention_objects, + const util::TargetObjects & target_objects, const geometry_msgs::msg::Pose & current_pose, const double occlusion_dist_thr) { const auto & path_ip = interpolated_path_info.path; @@ -1582,7 +1636,7 @@ bool IntersectionModule::isOcclusionCleared( const auto first_attention_area_idx = util::getFirstPointInsidePolygon(path_ip, lane_interval_ip, first_attention_area); if (!first_attention_area_idx) { - return false; + return OcclusionType::NOT_OCCLUDED; } const auto first_inside_attention_idx_ip_opt = @@ -1697,6 +1751,10 @@ bool IntersectionModule::isOcclusionCleared( // re-use attention_mask attention_mask = cv::Mat(width, height, CV_8UC1, cv::Scalar(0)); // (3.1) draw all cells on attention_mask behind blocking vehicles as not occluded + const auto & blocking_attention_objects = target_objects.parked_attention_objects; + for (const auto & blocking_attention_object : blocking_attention_objects) { + debug_data_.blocking_attention_objects.objects.push_back(blocking_attention_object.object); + } std::vector> blocking_polygons; for (const auto & blocking_attention_object : blocking_attention_objects) { const Polygon2d obj_poly = tier4_autoware_utils::toPolygon2d(blocking_attention_object.object); @@ -1808,8 +1866,9 @@ bool IntersectionModule::isOcclusionCleared( }; struct NearestOcclusionPoint { - int64 division_index; - double dist; + int64 division_index{0}; + int64 point_index{0}; + double dist{0.0}; geometry_msgs::msg::Point point; geometry_msgs::msg::Point projection; } nearest_occlusion_point; @@ -1848,7 +1907,6 @@ bool IntersectionModule::isOcclusionCleared( acc_dist += dist; acc_dist_it = point_it; const auto [valid, idx_x, idx_y] = coord2index(point_it->x(), point_it->y()); - // TODO(Mamoru Sobue): add handling for blocking vehicles if (!valid) continue; const auto pixel = occlusion_mask.at(height - 1 - idx_y, idx_x); if (pixel == BLOCKED) { @@ -1858,7 +1916,7 @@ bool IntersectionModule::isOcclusionCleared( if (acc_dist < min_dist) { min_dist = acc_dist; nearest_occlusion_point = { - std::distance(division.begin(), point_it), acc_dist, + division_index, std::distance(division.begin(), point_it), acc_dist, tier4_autoware_utils::createPoint(point_it->x(), point_it->y(), origin.z), tier4_autoware_utils::createPoint(projection_it->x(), projection_it->y(), origin.z)}; } @@ -1867,11 +1925,27 @@ bool IntersectionModule::isOcclusionCleared( } if (min_dist == std::numeric_limits::infinity() || min_dist > occlusion_dist_thr) { - return true; + return OcclusionType::NOT_OCCLUDED; } + debug_data_.nearest_occlusion_projection = std::make_pair(nearest_occlusion_point.point, nearest_occlusion_point.projection); - return false; + LineString2d ego_occlusion_line; + ego_occlusion_line.emplace_back(current_pose.position.x, current_pose.position.y); + ego_occlusion_line.emplace_back(nearest_occlusion_point.point.x, nearest_occlusion_point.point.y); + for (const auto & attention_object : target_objects.all_attention_objects) { + const auto obj_poly = tier4_autoware_utils::toPolygon2d(attention_object.object); + if (bg::intersects(obj_poly, ego_occlusion_line)) { + return OcclusionType::DYNAMICALLY_OCCLUDED; + } + } + for (const auto & attention_object : target_objects.intersection_area_objects) { + const auto obj_poly = tier4_autoware_utils::toPolygon2d(attention_object.object); + if (bg::intersects(obj_poly, ego_occlusion_line)) { + return OcclusionType::DYNAMICALLY_OCCLUDED; + } + } + return OcclusionType::STATICALLY_OCCLUDED; } /* diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp index beb13ef7bef7a..c604f01c7a86b 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp @@ -141,9 +141,17 @@ class IntersectionModule : public SceneModuleInterface } absence_traffic_light; double attention_lane_crop_curvature_threshold; double attention_lane_curvature_calculation_ds; + double static_occlusion_with_traffic_light_timeout; } occlusion; }; + enum OcclusionType { + NOT_OCCLUDED, + STATICALLY_OCCLUDED, + DYNAMICALLY_OCCLUDED, + RTC_OCCLUDED, // actual occlusion does not exist, only disapproved by RTC + }; + struct Indecisive { std::string error; @@ -172,6 +180,7 @@ class IntersectionModule : public SceneModuleInterface size_t first_stop_line_idx{0}; size_t occlusion_stop_line_idx{0}; }; + // A state peeking to occlusion limit line in the presence of traffic light struct PeekingTowardOcclusion { // NOTE: if intersection_occlusion is disapproved externally through RTC, @@ -182,7 +191,12 @@ class IntersectionModule : public SceneModuleInterface size_t collision_stop_line_idx{0}; size_t first_attention_stop_line_idx{0}; size_t occlusion_stop_line_idx{0}; + // if null, it is dynamic occlusion and shows up intersection_occlusion(dyn) + // if valid, it contains the remaining time to release the static occlusion stuck and shows up + // intersection_occlusion(x.y) + std::optional static_occlusion_timeout{std::nullopt}; }; + // A state detecting both collision and occlusion in the presence of traffic light struct OccludedCollisionStop { bool is_actually_occlusion_cleared{false}; @@ -191,6 +205,9 @@ class IntersectionModule : public SceneModuleInterface size_t collision_stop_line_idx{0}; size_t first_attention_stop_line_idx{0}; size_t occlusion_stop_line_idx{0}; + // if null, it is dynamic occlusion and shows up intersection_occlusion(dyn) + // if valid, it contains the remaining time to release the static occlusion stuck + std::optional static_occlusion_timeout{std::nullopt}; }; struct OccludedAbsenceTrafficLight { @@ -262,6 +279,7 @@ class IntersectionModule : public SceneModuleInterface bool is_go_out_{false}; bool is_permanent_go_{false}; DecisionResult prev_decision_result_{Indecisive{""}}; + OcclusionType prev_occlusion_status_; // Parameter PlannerParam planner_param_; @@ -276,6 +294,7 @@ class IntersectionModule : public SceneModuleInterface StateMachine before_creep_state_machine_; //! for two phase stop StateMachine occlusion_stop_state_machine_; StateMachine temporal_stop_before_attention_state_machine_; + StateMachine static_occlusion_timeout_state_machine_; // for pseudo-collision detection when ego just entered intersection on green light and upcoming // vehicles are very slow @@ -317,14 +336,14 @@ class IntersectionModule : public SceneModuleInterface const size_t closest_idx, const size_t last_intersection_stop_line_candidate_idx, const double time_delay, const util::TrafficPrioritizedLevel & traffic_prioritized_level); - bool isOcclusionCleared( + OcclusionType getOcclusionStatus( const nav_msgs::msg::OccupancyGrid & occ_grid, const std::vector & attention_areas, const lanelet::ConstLanelets & adjacent_lanelets, const lanelet::CompoundPolygon3d & first_attention_area, const util::InterpolatedPathInfo & interpolated_path_info, const std::vector & lane_divisions, - const std::vector & blocking_attention_objects, + const util::TargetObjects & target_objects, const geometry_msgs::msg::Pose & current_pose, const double occlusion_dist_thr); /* diff --git a/planning/behavior_velocity_intersection_module/src/util.cpp b/planning/behavior_velocity_intersection_module/src/util.cpp index 403509a926022..d3b2ca3baceb4 100644 --- a/planning/behavior_velocity_intersection_module/src/util.cpp +++ b/planning/behavior_velocity_intersection_module/src/util.cpp @@ -1279,7 +1279,7 @@ void cutPredictPathWithDuration( util::TargetObjects * target_objects, const rclcpp::Clock::SharedPtr clock, const double time_thr) { const rclcpp::Time current_time = clock->now(); - for (auto & target_object : target_objects->all) { // each objects + for (auto & target_object : target_objects->all_attention_objects) { // each objects for (auto & predicted_path : target_object.object.kinematics.predicted_paths) { // each predicted paths const auto origin_path = predicted_path; diff --git a/planning/behavior_velocity_intersection_module/src/util_type.hpp b/planning/behavior_velocity_intersection_module/src/util_type.hpp index 3f09b54f88be4..fdcf05a97a7a9 100644 --- a/planning/behavior_velocity_intersection_module/src/util_type.hpp +++ b/planning/behavior_velocity_intersection_module/src/util_type.hpp @@ -42,7 +42,6 @@ struct DebugData std::optional pass_judge_wall_pose{std::nullopt}; std::optional> attention_area{std::nullopt}; std::optional> occlusion_attention_area{std::nullopt}; - std::optional intersection_area{std::nullopt}; std::optional ego_lane{std::nullopt}; std::optional> adjacent_area{std::nullopt}; std::optional stuck_vehicle_detect_area{std::nullopt}; @@ -57,6 +56,7 @@ struct DebugData nearest_occlusion_projection{std::nullopt}; autoware_auto_perception_msgs::msg::PredictedObjects blocking_attention_objects; std::optional absence_traffic_light_creep_wall{std::nullopt}; + std::optional static_occlusion_with_traffic_light_timeout{std::nullopt}; }; struct InterpolatedPathInfo @@ -191,7 +191,7 @@ struct TargetObjects std::vector attention_objects; std::vector parked_attention_objects; std::vector intersection_area_objects; - std::vector all; // TODO(Mamoru Sobue): avoid copy + std::vector all_attention_objects; // TODO(Mamoru Sobue): avoid copy }; enum class TrafficPrioritizedLevel { From 89ae3bbcb0ca6dd11c3178c667ae404cc1575da7 Mon Sep 17 00:00:00 2001 From: Mehmet Dogru <48479081+mehmetdogru@users.noreply.github.com> Date: Fri, 20 Oct 2023 15:36:31 +0300 Subject: [PATCH 038/202] fix(route_handler): filter out start lanelets wrt start checkpoint orientation (#5358) Signed-off-by: Mehmet Dogru --- planning/route_handler/src/route_handler.cpp | 19 +++++++++++++++++-- 1 file changed, 17 insertions(+), 2 deletions(-) diff --git a/planning/route_handler/src/route_handler.cpp b/planning/route_handler/src/route_handler.cpp index cf309a294d81f..d74a8712a6e3f 100644 --- a/planning/route_handler/src/route_handler.cpp +++ b/planning/route_handler/src/route_handler.cpp @@ -14,6 +14,7 @@ #include "route_handler/route_handler.hpp" +#include #include #include #include @@ -2127,10 +2128,24 @@ bool RouteHandler::planPathLaneletsBetweenCheckpoints( double shortest_path_length2d = std::numeric_limits::max(); for (const auto & st_llt : start_lanelets) { + // check if the angle difference between start_checkpoint and start lanelet center line + // orientation is in yaw_threshold range + double yaw_threshold = M_PI / 2.0; + bool is_proper_angle = false; + { + double lanelet_angle = lanelet::utils::getLaneletAngle(st_llt, start_checkpoint.position); + double pose_yaw = tf2::getYaw(start_checkpoint.orientation); + double angle_diff = std::abs(autoware_utils::normalize_radian(lanelet_angle - pose_yaw)); + + if (angle_diff <= std::abs(yaw_threshold)) { + is_proper_angle = true; + } + } + optional_route = routing_graph_ptr_->getRoute(st_llt, goal_lanelet, 0); - if (!optional_route) { + if (!optional_route || !is_proper_angle) { RCLCPP_ERROR_STREAM( - logger_, "Failed to find a proper path!" + logger_, "Failed to find a proper route!" << std::endl << " - start checkpoint: " << toString(start_checkpoint) << std::endl << " - goal checkpoint: " << toString(goal_checkpoint) << std::endl From 98c24b824c68605c28513de47a36aaf5a4a89817 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Sat, 21 Oct 2023 11:00:34 +0900 Subject: [PATCH 039/202] perf(motion_utils): faster removeOverlapPoints (#5360) Signed-off-by: Takayuki Murooka --- .../include/motion_utils/trajectory/trajectory.hpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/common/motion_utils/include/motion_utils/trajectory/trajectory.hpp b/common/motion_utils/include/motion_utils/trajectory/trajectory.hpp index dcdefe61e4000..5d773c5be32d9 100644 --- a/common/motion_utils/include/motion_utils/trajectory/trajectory.hpp +++ b/common/motion_utils/include/motion_utils/trajectory/trajectory.hpp @@ -177,8 +177,7 @@ T removeOverlapPoints(const T & points, const size_t start_idx = 0) for (size_t i = start_idx + 1; i < points.size(); ++i) { const auto prev_p = tier4_autoware_utils::getPoint(dst.back()); const auto curr_p = tier4_autoware_utils::getPoint(points.at(i)); - const double dist = tier4_autoware_utils::calcDistance2d(prev_p, curr_p); - if (dist < eps) { + if (std::abs(prev_p.x - curr_p.x) < eps && std::abs(prev_p.y - curr_p.y) < eps) { continue; } dst.push_back(points.at(i)); From 1502e66edba93f8e39cf9e1e190c947d32b17702 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Mon, 23 Oct 2023 14:12:54 +0900 Subject: [PATCH 040/202] feat(intersection): use own max acc/jerk param (#5370) Signed-off-by: Mamoru Sobue --- .../config/intersection.param.yaml | 3 +++ .../behavior_velocity_intersection_module/src/manager.cpp | 4 ++++ .../src/scene_intersection.cpp | 3 ++- .../src/scene_intersection.hpp | 3 +++ .../behavior_velocity_intersection_module/src/util.cpp | 8 +++----- .../behavior_velocity_intersection_module/src/util.hpp | 3 ++- 6 files changed, 17 insertions(+), 7 deletions(-) diff --git a/planning/behavior_velocity_intersection_module/config/intersection.param.yaml b/planning/behavior_velocity_intersection_module/config/intersection.param.yaml index be8e822b31d5c..fde55dc7a6c55 100644 --- a/planning/behavior_velocity_intersection_module/config/intersection.param.yaml +++ b/planning/behavior_velocity_intersection_module/config/intersection.param.yaml @@ -12,6 +12,9 @@ use_intersection_area: false path_interpolation_ds: 0.1 # [m] consider_wrong_direction_vehicle: false + max_accel: -2.8 + max_jerk: -5.0 + delay_response_time: 0.5 stuck_vehicle: turn_direction: left: true diff --git a/planning/behavior_velocity_intersection_module/src/manager.cpp b/planning/behavior_velocity_intersection_module/src/manager.cpp index 0b4131b55ed90..a65e06eedcdf0 100644 --- a/planning/behavior_velocity_intersection_module/src/manager.cpp +++ b/planning/behavior_velocity_intersection_module/src/manager.cpp @@ -62,6 +62,10 @@ IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node) getOrDeclareParameter(node, ns + ".common.path_interpolation_ds"); ip.common.consider_wrong_direction_vehicle = getOrDeclareParameter(node, ns + ".common.consider_wrong_direction_vehicle"); + ip.common.max_accel = getOrDeclareParameter(node, ns + ".common.max_accel"); + ip.common.max_jerk = getOrDeclareParameter(node, ns + ".common.max_jerk"); + ip.common.delay_response_time = + getOrDeclareParameter(node, ns + ".common.delay_response_time"); ip.stuck_vehicle.turn_direction.left = getOrDeclareParameter(node, ns + ".stuck_vehicle.turn_direction.left"); diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp index 1bbff9ecaf048..4def152567b32 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -987,7 +987,8 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( const auto intersection_stop_lines_opt = util::generateIntersectionStopLines( first_conflicting_area, dummy_first_attention_area, planner_data_, interpolated_path_info, planner_param_.stuck_vehicle.use_stuck_stopline, planner_param_.common.stop_line_margin, - peeking_offset, path); + planner_param_.common.max_accel, planner_param_.common.max_jerk, + planner_param_.common.delay_response_time, peeking_offset, path); if (!intersection_stop_lines_opt) { return IntersectionModule::Indecisive{"failed to generate intersection_stop_lines"}; } diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp index c604f01c7a86b..764f5bd7fe058 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp @@ -58,6 +58,9 @@ class IntersectionModule : public SceneModuleInterface bool use_intersection_area; bool consider_wrong_direction_vehicle; double path_interpolation_ds; + double max_accel; + double max_jerk; + double delay_response_time; } common; struct StuckVehicle { diff --git a/planning/behavior_velocity_intersection_module/src/util.cpp b/planning/behavior_velocity_intersection_module/src/util.cpp index d3b2ca3baceb4..27310f2129937 100644 --- a/planning/behavior_velocity_intersection_module/src/util.cpp +++ b/planning/behavior_velocity_intersection_module/src/util.cpp @@ -269,7 +269,8 @@ std::optional generateIntersectionStopLines( const lanelet::CompoundPolygon3d & first_detection_area, const std::shared_ptr & planner_data, const InterpolatedPathInfo & interpolated_path_info, const bool use_stuck_stopline, - const double stop_line_margin, const double peeking_offset, + const double stop_line_margin, const double peeking_offset, const double max_accel, + const double max_jerk, const double delay_response_time, autoware_auto_planning_msgs::msg::PathWithLaneId * original_path) { const auto & path_ip = interpolated_path_info.path; @@ -350,11 +351,8 @@ std::optional generateIntersectionStopLines( // (4) pass judge line position on interpolated path const double velocity = planner_data->current_velocity->twist.linear.x; const double acceleration = planner_data->current_acceleration->accel.accel.linear.x; - const double max_stop_acceleration = planner_data->max_stop_acceleration_threshold; - const double max_stop_jerk = planner_data->max_stop_jerk_threshold; - const double delay_response_time = planner_data->delay_response_time; const double braking_dist = planning_utils::calcJudgeLineDistWithJerkLimit( - velocity, acceleration, max_stop_acceleration, max_stop_jerk, delay_response_time); + velocity, acceleration, max_accel, max_jerk, delay_response_time); int pass_judge_ip_int = static_cast(first_footprint_inside_detection_ip) - std::ceil(braking_dist / ds); const auto pass_judge_line_ip = static_cast( diff --git a/planning/behavior_velocity_intersection_module/src/util.hpp b/planning/behavior_velocity_intersection_module/src/util.hpp index ef658a25fce55..125d3bdfb570a 100644 --- a/planning/behavior_velocity_intersection_module/src/util.hpp +++ b/planning/behavior_velocity_intersection_module/src/util.hpp @@ -70,7 +70,8 @@ std::optional generateIntersectionStopLines( const lanelet::CompoundPolygon3d & first_detection_area, const std::shared_ptr & planner_data, const InterpolatedPathInfo & interpolated_path_info, const bool use_stuck_stopline, - const double stop_line_margin, const double peeking_offset, + const double stop_line_margin, const double peeking_offset, const double max_accel, + const double max_jerk, const double delay_response_time, autoware_auto_planning_msgs::msg::PathWithLaneId * original_path); std::optional getFirstPointInsidePolygon( From 6832af073897f841f8901dd8c2038ffee7318d72 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Mon, 23 Oct 2023 15:07:59 +0900 Subject: [PATCH 041/202] fix(start_planner): fix invalid lane id access (#5372) Signed-off-by: kosuke55 --- .../src/scene_module/start_planner/start_planner_module.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp index ed14292747e68..6b56c88eb942a 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp @@ -624,6 +624,9 @@ lanelet::ConstLanelets StartPlannerModule::getPathRoadLanes(const PathWithLaneId std::vector lane_ids; for (const auto & p : path.points) { for (const auto & id : p.lane_ids) { + if (id == lanelet::InvalId) { + continue; + } if (route_handler->isShoulderLanelet(lanelet_layer.get(id))) { continue; } From eca2d255e16aa3cd1b96a9ec7c09fa8e1b626af1 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Mon, 23 Oct 2023 16:45:19 +0900 Subject: [PATCH 042/202] fix(behavior_path_planner): fix iteration num initial value (#5369) fix(behavior_path_planner): fix iter num initial value Signed-off-by: kminoda --- planning/behavior_path_planner/src/planner_manager.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/src/planner_manager.cpp b/planning/behavior_path_planner/src/planner_manager.cpp index 442049654d64e..79e6055d26a81 100644 --- a/planning/behavior_path_planner/src/planner_manager.cpp +++ b/planning/behavior_path_planner/src/planner_manager.cpp @@ -83,7 +83,7 @@ BehaviorModuleOutput PlannerManager::run(const std::shared_ptr & da return output; } - for (size_t itr_num = 0;; ++itr_num) { + for (size_t itr_num = 1;; ++itr_num) { /** * STEP1: get approved modules' output */ From 911a2727bcb17760ffc5978ba3570a87e2c36089 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Mon, 23 Oct 2023 17:19:30 +0900 Subject: [PATCH 043/202] feat(processing_time_checker): add a script to display processing time (#5375) * feat(processing_time_checker): add script to visualize processing time Signed-off-by: Takamasa Horibe * add maintainer Signed-off-by: Takamasa Horibe * update readme Signed-off-by: Takamasa Horibe * add empty case Signed-off-by: Takamasa Horibe * fix format Signed-off-by: Takamasa Horibe --------- Signed-off-by: Takamasa Horibe --- planning/planning_debug_tools/CMakeLists.txt | 1 + planning/planning_debug_tools/README.md | 23 ++++ .../image/processing_time_checker.png | Bin 0 -> 162295 bytes planning/planning_debug_tools/package.xml | 1 + .../scripts/processing_time_checker.py | 104 ++++++++++++++++++ 5 files changed, 129 insertions(+) create mode 100644 planning/planning_debug_tools/image/processing_time_checker.png create mode 100755 planning/planning_debug_tools/scripts/processing_time_checker.py diff --git a/planning/planning_debug_tools/CMakeLists.txt b/planning/planning_debug_tools/CMakeLists.txt index bf7e36c4c0c0a..58f73ca3836c2 100644 --- a/planning/planning_debug_tools/CMakeLists.txt +++ b/planning/planning_debug_tools/CMakeLists.txt @@ -48,6 +48,7 @@ ament_auto_package( ) install(PROGRAMS + scripts/processing_time_checker.py scripts/trajectory_visualizer.py scripts/closest_velocity_checker.py scripts/perception_replayer/perception_reproducer.py diff --git a/planning/planning_debug_tools/README.md b/planning/planning_debug_tools/README.md index fe9615614de81..aa46c0e2fc7ef 100644 --- a/planning/planning_debug_tools/README.md +++ b/planning/planning_debug_tools/README.md @@ -4,6 +4,8 @@ This package contains several planning-related debug tools. - **Trajectory analyzer**: visualizes the information (speed, curvature, yaw, etc) along the trajectory - **Closest velocity checker**: prints the velocity information indicated by each modules +- **Perception reproducer**: generates detected objects from rosbag data in planning simulator environment +- **processing time checker**: displays processing_time of modules on the terminal ## Trajectory analyzer @@ -241,3 +243,24 @@ ros2 run planning_debug_tools perception_replayer.py -b ``` Instead of publishing predicted objects, you can publish detected/tracked objects by designating `-d` or `-t`, respectively. + +## Processing time checker + +The purpose of the Processing Time Subscriber is to monitor and visualize the processing times of various ROS 2 topics in a system. By providing a real-time terminal-based visualization, users can easily confirm the processing time performance as in the picture below. + +![processing_time_checker](image/processing_time_checker.png) + +You can run the program by the following command. + +```bash +ros2 run planning_debug_tools processing_time_checker.py -f -m +``` + +This program subscribes to ROS 2 topics that have a suffix of `processing_time_ms`. + +The program allows users to customize two parameters via command-line arguments: + +- --max_display_time (or -m): This sets the maximum display time in milliseconds. The default value is 150ms. +- --display_frequency (or -f): This sets the frequency at which the terminal UI updates. The default value is 5Hz. + +By adjusting these parameters, users can tailor the display to their specific monitoring needs. diff --git a/planning/planning_debug_tools/image/processing_time_checker.png b/planning/planning_debug_tools/image/processing_time_checker.png new file mode 100644 index 0000000000000000000000000000000000000000..fb064372796ae1729d600f82e9fb0ee6cf4c1138 GIT binary patch literal 162295 zcmbTdWmH>R*EWn4D8*VRZY@QMyIWhdEmGVyNO5;a+EU!5xRl}=Jh;1-;w~Ws2<{N% zJ3d%E-x6-fGJ=1m;Jv`MXr+N?fC3xRHjQ+ahqxIqStFAXh zub<>-w{dI|i*Cxu>@>Hs2z*en4aR8JeEKc#)3YyM9?I|Ye?@s7&4avwDzGp!nV=C} z`(?-xSxlu>j?P(b43(5{yRoW65^yog$G92Fl|v3$~rXSbox`CBw5bxNb<*2 zVzP(#1#D}y<4QkHQgD&@x6c`q7Y{e+_ixWquzmU;)5TUozY@P7yoo$>mq%r51o;HS zaI(|$vsjYb8t+?MC{T>fXO36^Dy33w&xJJ_UErHUGqinm4C%v?VxzpgMZa3S%-V|= z?wDvJ(>q!sNnMb+lNAWiS~^6|r4=l&zcdxe6I5mUr-+2NugP1<6lBd=$;zkL?fDt? z5;aqGex)2f3lG(k`Ma`mgwRAUy>`Z%BrS<4Aq>txL$an0Eq{XgYEJCP;qJG%B^&7o zhn3zlPM%vy_5)abnkVq?Kx658TT7FXjD=s~TgzSj=ht>DmI#`Zo>=b0F+1G##b(~N zKrqdE#$jufx$>jiI`8T&H)@E{;%658=-OyFXMNbcqDFV#QOq1McVdF1p-fC%O&X|( zgK9qveD(Hu&7Zfqc7PEqfaiX1K*a=0zO*%n#?wzp&%U~ zlIFfk6uzzVqRt>7BAL|>IxTiML|a|&^1!@jVKj5L)@RUzlh?vt19L$#jX0`R`pp@Z ztY+TpumPPhy_WUe!bYLXD<)xZ!t>QcCbFwdNmsuO4SS*I6u+hp4}()L>W)CgQ|!@*+Z0RcwMgT)?YX3IF)^*^k>2ANZtZOwadZ@YBr zOfPl1;j!7YfWidj7Khv6Mi!1?;T-9}6#eUm9_J;2{#p8`1^R>B>ejPC2wA)wYp=n` z0NTSNJ>>)4xbu35nwP@f|Im58RFYaS|uxXEF=&1FLCv3-B=vDW)!^+0U^x+K7{@B*H=Uu>Kx_x_* zfcbrdf;pDswN4bl&U1<9-*{@aKk%Qo4*+KW6cXXmHAxsZ$`rdx!rOL_eP-J#mTsrzT^2;Jp1~X z`@StBup&b?vAI7OcV%r%jMAgr(2>0{3@Bro}Z z1M#d<^|HIdFUaPbth}ZaXa_t%V5a8r!;52GFPchlcEP;XPcpCBTB+$999mFw+*zmL zdeMjz+4uhP(xK)xgFH?e+4+J8gmzwY=@Ws_)CANNk_JiP+zR(!$G#mh*UR0C!F+=R zcurKx-8rAxmwBDMDJ;Wxl;gswd5DFM15<@vHlbqYppdR117+mu`OjSEJ%+qWlcTUE z$PZzyrk^3&P?P@(ZR)xQWomcHI{Y4h4vPTXWN6yuk$NbpIv3lwkpLHW_hE~x39F!m zsa(BjF$dDWqv#XVXO-CbY3d6V^TD*yh+dD>TI_= zS&{X_=EegI_uD>7+Fj^^9CG|8L5`2_N|xThz` zGW+h`pieq0oFzfLZ_a@RS~e}VRkZcBl#ZcI7-*KHkY44!JkA$}?7{J@pNSGRr+X zzYBU#y=Uy{ZK+!04wL8#4M9VE6q)|a4j6f z6OV1o;~{yKtEqBihjSz&O>iCit)#|-nrQQ|KSUuvb3}JZyl?putUiUBJ!tpMebRKFOfZD8P&;+(k#b?81=DKbf?Xg%*rz zpTJ4bdZ*pOD8~hl;A`peRtw<`63^IUc~qjSIhnOTS_hX-hsJH2v+uP{K(vX3KF@>q z`un*t(O?Bcai!|N3SZ?44c4Bf%4gA-1jYsyR`dSuVPWA+a|@qmP6o0EQ`lIQdjut`aXz$` zI{CeI`(F|+aAsha|q*OKoo>zu@7;vD{t z5nm+IP)|8XWfX2Oqq|c1C+N_pUGm;4{cPrNZmclH6S6lc#wH6VV*7|k(nityw77u3 z^Q3Ux`DtBIxyIk)?D{fGTjVV5Au!#Z$_Q`j?u26>T=W*4Mg1~St1cw>O}IItV{2$$ zJ5>#l*7F^BTDR*T~hIDzoqeb8Vn+^<)|U7|OlP-*8FN6>8_xe9L}h_+Jkelr)79({3E+ z(6GgH!KJd`A+K@*)GkWXHo>)wFZ5P%O!Q zfC~6%qpLS57Udg7=74$BVjlzhkA>bOZIL@mp|A{Ze+cbGa z*Q@hE$cSWtWj{8v`A6Cwsac~3+6##A%xfNkrYhP2jcgS-VsnC;j!={LI9u7v&V{b< zmdsi}G$M76OrD7L)hd95V$0SL5_7_0sVXWby1=Iix)ND-;!rl6nAjE31Jeqgqz;wt zhg&N3j<6XxMK}8xK@+@YX*P;SVc>A+oJ9*-0{fqEw>mOW_+gO(ngFrj1Gt50m+Ea= z4pDz#%{}m9NJi`QJ*vYfMdeZ|e_h=F(wm=r*I=nhn*aFoVz|Ucl)0(|>Ox8I;b-O6~JC%NfD$C3|*L6g+zM7EfD4|1!u|I~_1Cq1 zuV&bMIKOtc_2OO$D&@neGF>iA8+OJjKUObyJ2#56l@z)8s)G%glKFJQFRAvyMJi!M z+!Z-f;NVRD`1QHp5~asYcIKmSWI)HN%{F9^S_@siSj|08x;mHeTaAwA39KA${0ZNt zN%J+eTcg8|Ew_HcyX+aYPqH&IU5YSvnFZI)W%{U_<|wi*)et)A%k$AMeYB*gVptG;yJDh?*!ts;HT7QOM! z1SC}@-ft1Az+E{&Mhb2-!_Z>e_`y9v7A!$q<88)zPoHxNUMv^$+H}H_(0@-!xx12R?Y`0 z9okm-I^U-(-))Vp#b@8f;#`p=B#YU~?@+OHmSk``F;=C+L zOFa1SQ38>o@-C)hbX3Q6_$3|2p&pL$;tx$INrmo0hbHs^sP|LF1GG;SIx=Nb#tH`$ zP|3*m5=~K6MWQHayl3bm?FMH{;LP>N{5yKQHm#6^L_?)kiPA!~{@A)T0wB#fY8-sO zqxqIodC$Xe>BnESY?iAX=zN>LbQ-Et2gi328{Q)WhVQ7=_Jpn^`JyW`C3}$?K~B)a**$fM_soQ2 zM{fdenF6;uWsjgK{y~`cI;=jJ%+d&Ap}#(0F;YYZxf*w-gxn8G+nf0T9S*5^5I?GF zeNk|~e8a3>96FIRq}%IBwQ`Y{U;R^kE6+3ChF|6e2KnOu;?E9#+T#$846B*CIcU?y z#YZJ-TQM%h6R@taKP=|nvwPKJfRaRq2=*LY>Pn@%aOCW(oqqs!HTza`kt>i}r_IF9H8Sy@&0_4FYh`&Y<80lX zyfnS@k<8=}`J{OL?NE#J#Xv}QXP?g(nd*9S7T4yCnDg{E#<%CbcOcpdbFD|W?JdnL=1}BLFdOtD?h67DAk9m7k}%iU5_Pq{0+6(N0Z;XncZHJqL{A~&j>*`c2?s>*xVM>Z#5`>R*$#?sSarnqIj^Y zrGAALICHH#^}uAOca`xivgF;kk2E2Tt*&<@hnjhjCY^{Mr5>b#S4x;OH&pF&Eo51` zvBu$e{i}w0D?fbk-VON`gmsM;(kTk(Kc4?QJ}IM+nLC?gyS_k|K)SQ{YhJSD${Ul; z3+Ag-*ojia>$MlrhqY?*QfSWgHssEKQ4G9SqHa#rYC5vsr>Xmjf_o)U>P6G~F%7Kg zYe2^_`Mu-i20(nL?ltJS>TZwcZgn4|@dQvJp=LJ^xa?6&+RY?p$SQAG1DaC>;+{4} zx&D%$Ye+6dxB#h4iqd4k$2R4M>5XJ}Ta0LJ%Q%9o;B$Jo!CcJ#ZPGhauBkokVWU<~ z24d|NWASjW@Qg$cvjKzg8KN2Gj=-B0Dr03D&@-G@(k|ZkyYeSrAYPv9Q9HP13l&0o z(NRh7U?!t)G}*KVQWouh7GZQ#D*RRs^OtI3-}A0{Dq9Ebt651I7F!H1VphUIpk{ae zDzZeNL(i*YAb5FR`g=`-BN8ZI9O2I2cS3Zb)d_B^6hXZ;MDO!lz zc$d*T@fK9UFqXBQOzLzQ93#C?-CmcBycf9l%!7?4zDNsY{XtN#AYgUJPF(~_zw;G- zxv2$dkh<5|J6UwFuV+8JdB6*sG+^Du{ytQcYyJs{(oIg`s8DSPrA_%K;$Bm9vs=EN zH?k(h3^VODo2BlMJmbTxUj;h zud*8GB`E@l7q5US%-5$QjYGT!WD<{1rsd}qq%P`v6n`k$2~Et`)Pf%Iy4!&EiA$)PA<%^! z3qRz;$a_!T3OjPHYV5&YU{|boK>G5xQNkq!R|b}@2QvbeEUh;!v3RU^ChejQ$DN@^ z)q6lRb7yJROoj#WA4L;6?_9;gT5kg;ecCX86i%1ouookpyIC?}+G`A%-;PziH}6A* z=zSOs)&iD%4)^wYZ(*s4sOv77dcY+4Ak4`BZXmcOD8ua0HKM?GpLyMkxZGG_q?c5E z%K=@x4fBzq{oECKIAv2bGqn;d-adaE5hIb-y5rKbBpLz>$awV|xz|5dU}NuOu{nLq z=K4%eSc{$~=JajwRfqlA#;w04<+I0qNbvX5dl_I!ojAc=#?@|KO5T`f_&G^n&+1aJ z!gH%%j%VTQ7HPJ5EVEWOb9!cvMn#2ruFOM|9B1RMOMDYlJMwa4?5RxwgMb+*kb`)p zyNsFy6d?42TIlqh(bL9Z;8gfwcWXeR{DTN;CL_Rk( zltl2?#&g_T4Zy#QT&9b)m#{>0xIm5Ho>a@fe|DH(8{MXl#U0W^qg$F1`-WvqI#IMb zoZoNQdMaNdO9w$=M$(3~{`EtV_?Kpxi5d{&Oi3dpO*`O(A2AaPMQ*9e3xDK>4XOxC zZ|_9%mxOtIT&Nc(#wo5?uib8EJBFz^r{hi8sS_F$%i28xI zURQ<6fS7t1ON?Q%QrY;WJj;|k+@&Ag(o7IWtTU;I=B;Wk2S=Y#_ys?6CdRfno$!DH zOs#%x47F>7Z1|XS{W_X3{$BA^NjD?}2Han;Fqgai{rA_}+p|64`O?3p{d!rYj4Xj) z?$fj_Cr92?f!D)vDMWEGA8vIgiV)FFUV7zR@9urgKcrZ3c%X1+=5gjFd#ZpHKdWZ$ zV}oX%vB-N-vKt=h++%M@897Wl%SQIe;eZ2An5KVevcE=&z)TE(71+kYMJtS(ai*MK zZ+iNBTY{VI9PMC#qEVk@OZU#H#t(~ikvv5sWn;K)%S|O|Czz^dvM??QGLq#Ug(Cz$ z6tIX)k}|DjtZ31+90Q@S&BrTEj@)dyEYJWOJ@6Z=NN4BKZFMW~T%0^cBso7zx+ms_ zRwa=03O<%M=!tj2`RH+OyysadAPH>!%8qR%1Y`LSz&~{D^#Ya7N@DX}q-0$ZjMY6l zp5$#nLPX(;vbmnA^V^8}-|9fQNOc}rl-g9GREjX{ZRX@;YCe!Ne{0k`O3V2J0Rpeh z;Yk4X(IPmT(&8@TJX#HuQ4Y@V0Qadz$LCC0bS!6{W3T8j?eVjz&PyG*BQ|9Ktg4JWmyen4k2Hji=CbOp)6`#4A8$%K z9M9dM`;WA-9K+3QsrA#HIB)U{qQPmB$d3!@QF&JEG?ZMCaU+ln1B>?z`hd;a+7R{i zXgfNmSaJKnOb5~p5tE#6xvK$Eo4PMT{ZkWpks(@1d^Sd98u?YXP$%EXb=?Mn#`JNu zH67%s(8g`k=bI_QyPJ<0GkzS+SZ-?zPsBqa1ajzY0lOaiNAsMNZ|NQ}Rf@4+8A_dR z!$O_~hTfQV#|<=2eWcz+u`y z{s5G=+EK&x+&zi^&o&p^ z4Aqr9^#NBKIQ+J$s4}RlzE`A z_-N8j^RNip-NFr_rFgJxPv1_7eZSHZt;?H7nN(YQ1Cdc89`QcJ;85@kxX-zvx823R zE%xv2HS7B3PumE$##&6#YKy0}8=F%pD))jg~>nQF6bO{u=% z-}`9W`1|?4w^RTsl#+SiB)hF!W2Hr{8UJibmBo_T7Xt%DO%JWVPwIC+rgL38bu47k zG@@G<;ckmpYh5F7!3$k($7+DgQ&AiI4ne;ccz?F|LFmTedfC=(?6x%|y=1m1=lT3e z#?jBUN39pMf4}+fZOjKJTpf%e0b?Ff$UUbDy|1u@S3KTX*}i9O%k4`jApcq(D7e5T zDWX6pgMf(g7jQi`~LBBap0--I%yS zs3jP^+7N$MOxzh`Qmxd|tbf&N-|7)1)ZJv*wk>6>nV3t+{WA(b&{8KL$%l*0c09L%TLWZf@ixkFXLP5(FDju)~WskG=i-9?PY_;D|W zHZF$EqRMB(^!@mnS9NYhzw_X~GG>y*qwEO+<*~}fQ82Uo-V5-*9_x>JeSIDNRa6aP ziWgR6j60t3 zQuF_5#FrZ%yXEV6-B>5e$#ABkFNxaBIPGhM_x*>yOry+({gdYXt)b9Sr$Kf9`-+q# zo;~lhEu`_TzQpOh9v-Ip5Zk{MhMuo!JF@Dy^v&iHvoZEAwsU}mZT=7Sw=e*1ow)Y# zeuuU5qB*Ypjm`IU!4JR3{d;>WPK9zWmf~asZN(`&;eE&16~&$nEdthmn}DiWB;JF2 zXlblSG1k+(cdmnFlGI{18?Gt8oWHyJ@4mdekPu0^J!&zk4ZF5K9t!!QUTHhomqlG{ zk_HO40+)X^_OIc95~naNZk=?!h;E@*ZKY;44;D7XigYIH|J}~JQOg;NttU+@P$6cM zDJaHV_GHNwQ?i z?h30=zF&C5ht!W0X`;ceZ&Fr7hhTg=e$0ud4&I)FF(4+G$<_}i3GdM3YvQ8IQ->eZ z*mQKNWK4m1=vZTgDqUksv0Q{QH@AsDo6Wt%L4To0pNSJsV>tyxu9(}n)D1_Uovck4 zopD<4S5HHCIR<-^q0!!r6`Pb2E7Z$hq1%4pY+QONZR_@Yu9F%&DC*%rb$uFE3(a8P zAO+3XmrrZqCRXm%J;H)86Q%lNF8$v8K3_L0kdCrak9EHdUb|5ri%`Ac50;@mCFyPXQ}iGOn{^1tU8`h!S8=z zXdky}T@wQZSObaGgqrf$kHo~or?KVU3x&JXVK*MTyoOJPM?212#He;Hdy#=}xzcJe znm!y5LPJ8JU-k9@7tys7#krDS`_{WuichWdFBZi0Cpa{re>1V}jhRnQtlIqrW^SUD zb0|6iW$h!SJu5wAkWSX*s9~3}iA`q~w=<3v2nLpzL$qSrVB_>cJGz!+$22IPcJDSI z_<4~mdr?o9YBNygTF$n)o3is4;$y^dR(#MbbxP2xu!NjyL8QzD)%Y(~-w{f~ukZyG z8k&}0--2XT`F7g*qYU37Q{=L#c;0)Cq{lk44TtS?n6ySNdZjQ>^$0I~U3TKUZlVCr zv(b4Ssx&VT>(9@RE(Fm){f*pVm+<8$Zc3I1$o+$Lc6R)1?Zw9$`FM*C%@K`DKHtWc z7Zej&yjsag$I7uFz5<^s98O;JTIDHFi!6B)MEPFg1Av}!Ooq)dRmyBxUl!WjH^i>U z_J^aOB}j*ra9z1`x4$`8yde<4X1riJ8Q!5$8LFvR4k*^!++MQaHZIY7kZN?SnU8NL zI?Z5pCY?YEtD1a8cxV&XRw!MCj^Pm~?#vdl+}tHqTpZV8&yE!}VI3wKm^-CH0dIOq zP__Oo$mG9LBBLHxWexvBO0Ykrq?!wmiQj1Aq7Nd zeYsa%*gveyYNRZL;Ba+kG3aTnh!fsNkJlh?qlrigbKJ(z=Ddg2XAK#tWe#1Dh2s}q zJ5Ouvmb=foq>KnIw_VLQt4Kdg=WQ&|sAWt+qSm(YQlu$PH4X{!jUVG48ui zh54s1&!%9kZmdaowJIYi81U?OGw_5mIi+6SePs+_PlPDKs2R8?xE>e6b)%Bu7N6yyUqVg_XMbnb* z<-K&sPYtE6TdQZa(#uC1yX8BxGi?8Yy?@xh?nYJJ?q=Zf0`5^HS5xE^AE5vkonsgR z+K3sA%)J#^GQD?Q+`AJIUCh=p4!5hY1@Aj5RTtavAUD(t7N={5#4)h4&9)}HzoHU7 z@P=Ze^_0Tsws!v~fz%O&R9n1V8~L=+$ZR@=8av0AlN+SG{v8gHY}2UGTXGd3OYQFK z%=ZmHw=YtY zy=YwAid(Le!qs+*Nhy=iU}oC4E3fESd&CFAGVOc3$>A$xwM{3^SEp8r>F*M{h(QO( zbp%Obpv3cQ6`DYLf~c8`SF82g8p(667o!>{5{(!d*#v~GzM>Me^k&N&kJqhT6HUZU zUjZx@y(wwgM`mz>=CmY6{LlrDd%ClA9+TgffTq{P0-JsKBdq0I90#2@nvwW%dA38L z$DVB0b{wnicX+wZ;pWR%4A)0j^S;7N5-vdE1j^@>ohuhl-IreO)cJ^TZZ7-~8*;$) zhY~4yX@88ojDp4z>_bbo?ej}rdVp=hDB5Sh8+s418zw87USak59V->Nk9#N?N96^* ze9K;|tCxd_rk9RD;nU6I9;oXjl6lYDzQQN`g^1(Lx?V7)3#Brsp)-9j%UhB1i|~aH zVZaEdGF&7IN>w>6kmXsrXP(xaLDaNfls~u}mP zH9vlhce+$@b$xhp-PKPxk?+JF2oHVE-s0*7=MxX;a5eKr3Z1TD-_N@) zF25Ohpne>vzLD93>V}p=es(kydQ;R{cX(mzksuy2F49|hwi|S5I;Y82zW4V1F2UV< z$T0;M^mOtA+VLXe&9IikaDHcji*V_ge#^2pnoRXy!0fDW+_mxf=Xd8%^xSh-!0PFn!|gvF{P@V{`4n>g-h7G@da;&i zW;&lXC?mDMl5+Ec{AO6GB>(2fkqt%d&~s#G86P?9<9o6}LU@jKkQml!JGTn#+ci%M z$-BhMuB%u6w7f*t3Ae#>8>x?OQC^g~d~$v?*0C-|`wf1mN<(8oL(_hE7+Y*8(9`wv zs{e zFO0KpOV*#PzG+f5!-iCa_0ZG$!jHXtt<$518LgoQ`Z_DuM|7^o;!jQG@tUMl+R)alCA)q5IKL(nl{b5z3(Y&uM7!pHG6>VAKe9v4^v?GC-CIP;1Nn>DsVOFNaf{zF$6VUa3L-5@mqN;7uc!8wMi>(HAw_(C~l+&S#E-Hn% z5x@_+X^B@izWj2^wZZLexD>WV8)gClP;Ua~cmncDMQEWE1F znWA|F+}`7{XL_BV`Va-gx$w1hDK5>!O0ES7VDa+hHEM|u3W^Jov-drSEv6}IQK%W; z1Zq+h_eu=;WZLzjy$2Hfw0#vOc6M{%Jh^uhcX>?UI844PMm1zdhtQ^0p>I$DFEi3#p>jo8NZx3*3n8UyjA+U{n)HdNOW}3C_mRPSapM)8UP76f(*#SbPogElXfSD1 z71JFoQ^Qj(LdOTrY%Z~xl;G@rpYzy?^p4o_lGZGJ+wF|6EeZ6WKWwDm@EH)9Dhtqzuz>v6Qpy zpl?g=u&g~0^1EN_6;eDr*-Iifx$$<4VQc9ZBZbO}v^(s3UN1~UMdR>lSQC27d*{7g zNCUKg!0|X;?fc`7qO&uC7)}?`r-g#7Q=5fUU6|BI6=z|BoK0dN;&V5Hy~}SaCTPev zLd#OzSW^70O)W|fWg?#xO>fUSaI7LYIiXEVW=M^T)5t`dA8R5D@VXZ)P~9bzKe?tP zI{4^nNils?z;)_>_$dcB1!S|_|if-3iIic zr~*rxpp|9Ql#F()jgnuv8<<|mG)?< zJ~PljDeGv&YshG=g7CR0Sa4=EcvdY>4s4!tJmh4yk|>q*_HwA zmWQHn!*qM|$;ZF+qIMKtE3Nli8 zh`IjMxQ}793-HM^rzXy}8so5SrViAA)9QM6Co>NXosuoOe#^?uStexZi z=<3Tb^ots!wQ%1Ycl@l}Wa_EFP)bMQsW(B@Y&y%; zO=~8Nrboj}0?{@C65(J|2j#L$44;{*c|wCm#)^?luhu}^Nne67Dz>?67UK+Wuk^=1 zsBkWAPCpoch}#B*f_z&aH7qf|8;bFbJnk6xnw%HNANKK|_i1QFRynv7jH+Oiu(Gxd zRy^*HdVbbbwK=zBvSlfGp!_DuQt^sWpe!JPo#OFZvHH7>!jF$;&izwotFa>`3x&Cf z1RCLJAa?6XH~Cv1N+0xS0VF$3gXx=E$yWzs2Sq-0Mg44s^>=!jFtS0{SSTcpN+ph$ zc1J3^tG-Eqe>GZ|;@2gOPSh2i@!)7`Cm31tyGD4wAyFJ;VZyrp@*{)x&--2Tro1>t zyd7LqyE`d9pG!r4td^943J$bxvqe1_g4}YFt29RFI(Mz4Xq#9okQG^a5bT zwk;PD`032B(OXzy2gUu?t(aF=j8moWvUg|wwi>pXH0>onF)v4l#xQ7mnh=y*bqfr2 zFACo^J-D4QNMIS!wHR7>wRFSgEbcqVmN&Z98U4Jop6x&wM-W-yY$`}``CLNFwjDtB z_V~4y^L2YSn^A>-PPIHswXFgMh-IG8-zX-nA)FaX@^f#mec{l|4tNd3)+7AoIH2L! zdjOAkux5FDnv<~r+)7^{Ic69KEw(LH%dc%~GFqJxuq|yLcIJGb4g1pL^?#v7)z%4$ zzWtF#k>jvk9#%Xb(4dqI>Nh%Bs~x-@#Iqpey#ThFM@^K@UT_Dz(G2xV(V$59w~ zEp#>dXmD_7Hg?)0H)xuhf0DxG&HUm{RFUlQ(#_WFN7iw<>+KQn3*gejcCx^WrqzHE z_JPiWQK@}ll9|d#MI=D@@(Aa$7n0Q6@@^trzqfh|Ar6z>tQCH#u<<9JJ>~lo&&+)u zr5Wv*ZDMIQmr*);1hRfSKlTi=Z3+5_KlfwkPk@`o&KjtA+^R`1d#Z&h z7U9x&HrRO@nV%FMA?ZBoWaudZCMh2_{CY*DQBFsN6LbAPd0B$}H+^mHB%`zPtzjc8 zUuQ6eMvDPfW^9wzy-!w)l@z|Vlj=q2;+@Adcwo)D(+shov4311pXP=a!(3ap=*pV- zV!#`_*}74zo4Piw*Gm>O*_$hvu`33MH&Iy!@6U& z%38WwOI_>8rPU}pH!Y5BU%_}g4~o)(QfRN&A&cu@$2nr?j^Umj!c~Cc=h@lCHM1g+ z6kC(~6N7IaC^puSoR_%?Us%PJ`2f7FTS)D5v!%SD#Y3yU*k)EGqp_C_gZ_F=1^A8bfmJ~g**h|QSBhYt0j@94L5HV<0dY1c$^ z^Qj2Mz^um3DH^mml^-zE+v$x~p35Eg6NI$;LApSaDNOE}@AqG)3wcN@n`YxNW6x_N z7aOn724!P+P&Hc)Uyj;01|K8OHbR%2q%mUOYPZHShXFfW>W%uMWKf~DaXPnifTpJN zcbK?M8L6yo85$t2%f0hUcN1<2Aq^T5NrEan<^Cw;VCQdU2~l3*q(mIBYl%dc8)Dc& zE@OqyqUwg-%Mq-73|JAR3FNNhT=E23cYMYR>%63g)sLGvE9|1yvKtO0?4{RlY#B;F zh@GkTMKxLwj-kEnBg=dNS`ymf#y$1w#Q7uhU%ijX{S`Mj7t6eHA?O=5yih0!=ju904;

Gt;~0 z_CC4w@Dn9r(Iri#uy*{VMxPkFZJJa9Aj`LuW&i>H;zZFt{6%xYRK$*a{KzJni9lIGNwe=>lm7^u$82qu_ z2+Rh1RrWC7gwvj8JW97^1+T__{c}b_7bgw83{GNs!~NznlE!%6lJiJ){hR*JeMVXQ z!?>nH2MaNwlsooAcLB%C0>Ad%1@7-+J_2O`*bafG#V-ZT9k#V;tfy`*a{TK%?bMDN z;pS6;2a-j9<^F^~h4j$Ls&9oU#;Yv$@F^6s-sax9v_-wek+K9=o5C0h_!5a5ot9Ev zT;B5XC^{G{ae|JW|H!iW0*#chsiX9K6uW==MS?}%eZly!{neS6_X|KChU8NYTU^)y zGl9zo8X6y0g($*wJ?Hx_LoPSLd#FIrFK#YQzU3%70}wT_*GAL*wsjEPB)nyst85zQ zI%D+h=zE1#U-f;-SQW^GSwEEEa3f0eL_aZI?K6=>YbK@0zVX_rGB+SjR_?F5aOjA` z{bqCoaJryE+lC8Yn@xy>(vd3?1Hhd$G^ZJ+x0BKgvN1zMrm35-wkjCq3!V}@d401d zUXWV(dAAYY*wkixyQ76~sqxb^soCkpPqKIY_hp>>$um&BB#;R$J{iUtK6kt)g$SEq zO~KdmIaRwL&SQ%kpE}@rGcLARM_r-lWGUHwJwA1Qe`AiuYN%;n!{Q%@Q$qV4!so%0 z6!#VWp~%v9N~-s5x>SI20nb*9FE@sz!=4C>yoJEbq*j)%MlPNuj;4iE4KLts zElKaVfoN|VXB*bFmYShNB=pv}QXSL5s8HH0Ek7d()Ggba72qD|#bL0$rnWH2@lS*k zZR7R~+m#SWlvUkWeXip`XRH>*aXFv;@e{2_@PG{;vN0jrCjl^DD_?fq`$9iG)vPp0 z6fk~l9{IthlZLp~;vs#7&2Xl#@ET4Y+g!2JZ$A0{IIbzL8;km=Z{{qS|NSOc^0wWT zl*93cbX{H?eJ9cSyjc`})wReCiQoq^gj!(63KhmoBzs|FZ8^ULEZF{AJRh|Ov(*4M zHr9XaAuRZ*hLza#w;sDc5BvUioEQ-0A2crx3B-Bw#^lp0*%+Jh;7LMUoXR?xvMqsE zZp8o2-aizY(k<5sC?)4Fu|L1((Tj&q8BE*JwEZASf8`~A^}fc&UF!7+5~kQv>-s~I zjmK;-!-hjipD>rE=~h$wV!*4T#+Zkt$5$3!<8DtsST^CvH`#w*UjiEM)Qh|pWhQt} z8gV?PmIeoZ7zTsl0IP0aB9W`(^-Al@gCSX4ZLeLepE^}T=)XAd120@d3}JXKEFckQ=@jLCc1_ z<}*jRj#a?dza2M_JCPdxUy_Bl+gW4^!W5@F-Q;#fR7=jG&-DKwg%JOt&f@uK^<+?@yScE{P?eq zN&c&hI~k2Q-Xp^gu_1Q&Qnw?Wo~J>p)#3|8(SIWiHA3~JGcAAb1-R>bK9MG5T_X{J zli3&)HrH*f|Cev)NMH7E4p_6d7irp_LGmNq!gP4w>EM0RyLd#UdzsRoC7Y;LSml9g z#3r=jlb!&n^&n@x1+h*`jNwm@S!uR`v897GdJGlde*N1&>P1jPDy=2RGRUYs| zm8VEj0X?sR=#{+3qfMI5xc6WJTcgJ0X4p4WkY-P zrQkabP1*n++Vj=WPu!m$pgpHwmyl;1ZX9B#dV4{gaB;1Mz`pcJdIcc`cp`40Jz4KRS|N77Y05^2)~9odcdEIy!1A zoRiUqs`f%;gYuT!mto7SwT|8^N}qx~JKmJe8&aby#OZ-wT&~3VjtXl~B2~#C5A0WYxNr!TJ;7O{;Cw%nzi4 z`hr%9SKRihOe36kSVjryGoiBCqBQVArZ*u*4Z*@e&utg{7H;+c>&jQ3sQc|tK#a7$ zhsJQVkaZ?!yP7#3T8OXUyw1X~+3-~QNXnu@K_bAxk|S8*N{sV#~2DVQ{G z&2ogHyF`8XaP%JN>UHvVk76d$V)*)?5*F*s7t4;*Y6egj*(*8yj&ZtiOF;YGQeMiJ zU9(cT_i?=~_Hs!G{L7xuR8DVw6^Js0A1|jR@!Js5*pB`Md9g>%jFynfj4TdCUp4Wa z9BD7>?jymw)O?HG9|y4=FR5_a7J_Z|>Z8V17p)d2u*5n2C%!_Z*{;7%`fwVpc3M%R z>E5`Xr1HefBZJ1+%4uZkXU*tsEoVtb1q#zg0AIJ z96cZ=H_p<^GOJQ{@kCWNe&d2@%>Aset#aa?RAt)XBvdl4HF;mlQ&A8G@oP$ca4IP} zvXa?vmFVl67agBCM=R`&Y9uftg)<@f3(MHvg5gJ)gq$qOTwrten7$*B{_WE zXi2mMOSZG#6Z=vaMoU-yjgxeQ3NX4hs#AYE(Y^b0zT+2^#_(p@i~@-;W0J1AX${kE zX04%bWeLUW-2SN|NqkC4T+^u9`phq^%f!oVvw&7PwDS>Q$eI7#_mamyW!|Vm+;&Md z5cPZ9X{V?datXC0^wd^8`J20jR6Y93?yN>TU31xdNl@=48=kWt~_~uK{gQHHHSQ8ZNc+qS$%SLMrPi;NAJh zp01{WW=EO%iH*~!Jqz{uGw$fooa7f1XzKJ zVD)REY;U%jQ4SRLPxj*$JXYl)%?`~yzo?UYz(Pes(u1p=o7RiN3os|8vaLDi!3%^j zqIbyXf^}9znwFW)bCzg9;s;(MNq3_Yo_gjLo^4uG*y_Zga~`W!U4+ur28@mU|6}hh zgWKxbbj`36W6W$PF~+2r*@|OkX12`CY&nT3M#ap`%uF%L%#1O!95Y*^ykCFQZ+iMW zea=jushXE)e1Nnte<_|rzmET%QUom@E5()?4N0*LT*Ipo=$Hy%BDA%G&ww7bf*FYiEh_zk(w zJSy?X)$T+u#3vSaO!c;+bYHZo`P}Qqf^tstHEEBu{sz6=_w!%-R?^k)t+Pz;`b{xN zyBBc8j|c(WWGpcm4h&wqT-PG0BxnjD0>)EgsAjWKV*rdCM=d?oqaoEIp+P@^J2vdw zw9ULZa=Q=A7)rix5^Jg*IF1Y{*qg19S#?`6wYqqw?@#H6lL0@*^SN8|NTaZRQJ<~i zyPG(@<=q14PaU~GJFEA#k4iIEgrSBe9Fbww~mL;AM6SyJMu#1)KnI;C>_Y??XLef7DQL+W-F>D-P@wg2Jb+i9l7p@t_u z^N@zXUut9&>lvJL(b@Ff0S305mbNVehS+#@pNGY4nYp4dXzKsyH6s9i@6x}3s?R<>7n|I z+}94S-XhgebFG^4Nb`X^T}&al;48=GlW+L@sSn>e+jh@(=E-~*Q&FeT=jlH`TJbs= z5`4xX{+1Q$;eKCaY1ZG$+D~8 zr=RLZPX@iCGO%weAFgGL3c*A+GHW}z*^##Epq3prGrGej4$%++PkY0GIf9EL0qM7P zY}0Y!14rBQsSkI_@fo#YjB(Xb4f_2wRbMY38s;&=ZtS4>`oj#K5zqCgXUQigPq*WC_(;ZtykWY_o>sp#TDT+OYIg3mXQhzduQ4M=vcWAcH3-B$VaCs2! zp>*=MvWDiD0$I?DO`j%??_@ioZT5Q~+H8PkBW2iN?fXsP#`81NQ%HiveSo0zj&9p( z=F-w%;YEXtFc7y#{jo++Uf-+U+?Vv+5_uAmb^=4$9UdHogLD?Ou8YJ;I1AOu&GHDr zHhw2HdZ{>S9<9KJUcNlbtXO%TsdSp5^!kCi zSDx>&l8~*HDatO}A^&ok`8&>s*9-XG!-X;uRP;TCR!`HfS30oi$<}$u(O5Dyt{3Un zB)6L*4poZZq+-*gTdLC!W)lE){}BDvL=_HTtZ;u8E>c$p-HRU#E)_g3ER|=eI3J%Y zjbm}$>pW*151K!_-7K@CFZzWOc$xEI?LuBtgCjy?6)>Cdm524$Seu<=83)_NOt0Jk zbU=$@s!6wDzi)5XRHAR{<*Q#p6j|d7`Ls>sN@kw(le{CaZ^Ai9?3*(Nj{|{vgQ=Y4 zCi5rzL36E9EyT5zo=4^|Iwd}ne`PeF8KYczn?L9Znu)qq~&ic}NrK&q&EsdzD~zQfMF zskD!yCS@HW^gceYCdZ$!l5W8^n<^?YZ;Y-NBTTvm+?mc(JPj7|KVy`YAW_`6SJwg6 zRsBPbbgrR9Ns{ycfO1b+zwS)TP#K&5GY;bTBhig?h3g!T6n)`PgUK3??z~OyIhVR! zBddk>2q;`~1T1rXo#c4sd?YE}ZhP0P=e=p9lIrB0@368VozsJZFue5wTtQilM?)$O zA12D<%dT|QH^B{+g&y}xSx(S23d_$j(13uxY!$f`#o>xYOO%vBUt)FV@=6-3Hvm1a zJwaU;@bejFkuE@Tcjy!~OH_$A|Kh#S92O^w>6+-r&L(q$896UMPt(@Vu3MOS7PM+eoZGcR4kPm8c`o%*)oWdnq`Hn~5g@aL9`PA9+4qIhRR! zthDkJTZxeaJ&_r8%f^04+L!&E#(+}Z+x(RdmAYl|^=N)!Vfta=@;OM^ok4v8;Zqa- zk=fY5YcQ;hizLk#Z#GP!OzzE(O~Br4@JH4L9!2hjoyH_=w*CXCRYz#dyPQ1T(*4oI za{uQTVim2fp!>wy5>M;0gm}QdP^gj88YQER^U2cbOq8 zEb_ZtPOLqP^act4&+7(&AESVD6T9yhtv$ z#B)hh&nfm62`%&*`N$u)t|G38y39uzB0u&b*m&A{)=JidQdMk4ak;`Si;+)4km=eV zQ9zT2H4p4*$w^T}-8|#C5Utw$9*b%QMtuBI?Nmv}9;CV5(Eyx1AKR{Owa06*wH#5q zMUT;VRrA%_sv#NCjlW*E?>dm`*bYfRMLz27@ez&Vj{b6Je9~SgfRj92Qb4cy_iXjG z4-4Ls>YZKgq+~IXex*;wK2c(>p4Y{$`YP@aV#d=Lh+Q_5s(ViyRqMX<<*#g>(Vh42N=+F5XR^($st`TlABpdXA$# zI(A1Sua`Bs?>mK)B1tK6B(}pIHX5Gnc;DV8Nvg@p-2mdJaV<7=PFj^t@d3D^tqk)H zM2(J+(g;imr#SMmo|XB4dPf?7!_D!ZXS!Ly_EH8I-U!wq-NBXKt6D4-ZuYx>!t%%U=4X7 ztV><+vH#WDLVCc=`pK_FW(M?-hJOfY^L>=wcL|fmaN8ohXYuG9erMcYSN}>&GurRKLC5*5N9qMUG#x)S##GZsZ+dqw|9eugO z@omB8gZ;(=+Fhz@h!Rx@7Ps@0Mkkv<`~vNZOKEfFJA29X>1CaQHZUhQkJ*FHu1AgN zcpbC$4d-K<)VSO^_(OBy!VXU(nzZc0Y;XL9!!HY=1s6M$1@jTD7WKb}urAzoLl)e! zUQG)_`p+^?vGIXyGfr%5x3xUc#haNrH^;R(mUU6!F*%)b>Enlglt*?c;k8$!B(`b7WsSDs6 ztU9VTTyHcR&emXNH!~~iw9YHffo%lF2)S=9Z@bO=uqXNOOT5W`cAi`rm8ObeI{#G3J>QPXb4{k2=mcNXFU5HOOveTo8qHNKNrHD&ezPyeNvnE3 zsZ*@Mo}71d%L_55pL2Ng+|u`gZ9IR`w;p*R^P3W|czbpU!vW4lJNv-gG|c6x)@WK& zFwGEZ>6sg~zZ5D<0sX+n7Bn>BQ?soWc1iqVGNb)I0C`u75}hB2J_Q959@#6d&b9bj+l^6UE|vxODi79Ao&0$lsoS=xHndc(8S(;B00$p;NV zlkR7qFP@p>!&8UKy*O!+oLx@_RQ}R1E{NT|1opFWiL{%i`OAlxd3<(><7B0*`ruIFP*N_f8U!KTOCtAaQY(35r zQGw+=?bLPids~tYvE^e03aENUQCatq%sU54&Nf271TR%2icHeHxOYB)T?IN6b4 zCC++lbs${2{V2qT&e410qU$WCLFD9yIaF1B#PtgvsxaF=CABiH*$P4T~AfkXi)jP&V_5r zXGafFDl)&UA4WHVHdU8$=hW<`YC>#FCm%W82A5s{qzc3W7d$ZCOpq|4+I+#~)7ym= z5Ie1MPJCH%(Ds6(dILq%VBo4q7o%Qp<7nUx{J`mjwm8+p?el{<`(SM?tfb|5nR_Vo z!&SpJ;kF(m^Nz$pag8h4?b>oZR6)372IZ>tJ_|MV29*;(+hHy6`N6VFq;`y6T~5Vq zitDla+T#ELo*1p>6A5mY;RlMAvvmmap8RRg#-`Y|LKMN`BE$pdyCcV!EWN?4Bs9Ws z#~BG7&ZN4DBmE7(hec*@+Q+R#&&^G_D_od8>(btdjch}%ZGW}T*)MWiP+me%yB1=_ zG&?Y-$?pg^cfkR5{vjUIr(73(NnXk4k6gpjI#!52nH+$pn}0nAig0_*Dn1VC?1vf@ zoGAO;6W|nW*jvGp?syM%VW?@n(YM65uziEkN*W%U)Dd)qUv4S&Rnv+Ss-(ViSH{pGGa? zQum=P+Gp}@$MW$q)H11=KxFHTO5&_xsrPNlBTK!Wj%vydqv`Q#4fv{!dQ7THGr(Z& zum-BI~voqK)()9oQ)6Tp(qUrP{&?fVpNzU`OS zad+C=cXDup+L3$d_+M(N$uASyjy97BL+0FT4}{h6w{xz4PGqyUyuer+)(0|7TPcFj ztF|`F)SCcu-o#${7=$8Aa%Ad%bbXZCvm+^Cwl=n$aJg0&yk4#Y`*On*7I~AHLJ5x zqxoc|et=v&KJmlO3f$0Yo+LG~W?**4a#~RH*N0Rcp4353GE*2eR46cbPhL5tYn6%; zy^L=>w?_CTR!W>?I6RAJU!3Ezv zPc;>GFR%hCP~-a#5{OU&;33{I=vJ&l(7~VGG+M9kr-4^a>)eD;Nmlmk1=cDzs~_C4 za_(`AL5jS8rvh&a19Q$$RiT>2RM=Y1q|o3J9?MYu32r0Du<3c*H#YvDAG@Jnd%9S!U zP2a6*^TUuW{C-AA81=6>_%Fv$X{!=ai|d?E4&~GYGrAoUIQADl)F+nANu07&;Fip9GeQMFV-VpPb8aH+|();l# zZ9u}$J(=x=(!BP*w4iS>ff;ek&qs?r^+ZwYlSCizthje6Md1BwrfqLovg)yN(2KfA z`gPJ;hJV#=IdIUvGv8$}85+qSGjxxpXGT|9@YX$uxz>kES}Dmoqjr5VkL092f^%kA+4;TxwWSxaARh2?`FusIBWghT8*j>11l|}-PPAlq@dtA zg=pV}7?(16ya+UDYd_eq(@Y(V4l3!k;!XyFKTl1lRXpg&PKNwZwpirU*bo%QNh>n4 zYpBeetvPESuI%4*OO&JY@Nnqlxf|$*;c33yZhmPs@%52yNpjjgPAX7H(LyjRR#KVM z+*M(Tvd51mKg3=ge}F+)MdoODON+%k4$(?GN%R|nJIM`Id0H_ zkv~HP(Zh`_870*+m(N}>(|r@A^+#3p_XkCIN`t9YNSZ!%LX)LUMaZ$y(DIl>U1u3c z{eNPpKYj}FZ=xD~dRo1vQOL8S*%#N1tsP=+yds^~ccA)KnAF5VVkGd$bQbL)`f_au zh&B}G;wr7*v2zh$RG(HPx;)?w;!(B+u8l~nmD@ykl=8ry3y$fZ0yvcQ^Y9iM1x3)bKS;K+JJ zl2J4;^GrDxeZO+PaJ!Nc9iYO2 z&R+vwG_e^%yF}Y;tc7jIDOj(*w+^2ET)s*{Xy-k#_9eri`h_1lscajWOkpiKr<-J3 zMu(E4*joACo+3$OciyWEZ_m-%j3~=iqGD6Ip_ILJr$e=b*Yl2=#l% z)B1`ZD&)G&L3uG6-{>k48-Wjpbe5?KuO8!f%QTM!bI4h?jMO!#7c2Lprb}B;1$k>% zz3yX0z@N`hOpe1QkRf!~Y8RYkVw@x@1Ght?#R zui~H7uQuQl7J`|k#5;NGsbub-(pnMw`LE+l_1e>`1v;x)Pn~X3qDwXLq4QUPEg})u z&TXyf>Mo18MAm;?qAE#ar_K6N_3O>BzULJ=jF{WFx&h?Qenbq_BWr?BWK~q51 z5n>cNSSNqk;3u~itV3e(FflRBS^jHe% zNc|R0ciPWSGNiSY&g!O9iu}A3_HGeXTxY#E1rnk){zx_EDVu_bC=MAU4eBf`0wEq+ zcO#gxFFhSVvf%Kv@UQf69AY2EV-LOtUR54+sj?9*9dpU?V@lqQ ziwtt38mzau7oFT)7n4-5|G{um+KKpro*El z2yCReSExmXqU`XLXX*ZtE3oR3_&;X>T6l5yvurEgR}fLB;{9L1s`GOU_dnES z0ohz*P$`)-Qay;$CJm{>1FRL|`>5+QHx{AfmM@=K#dUva5Tm7ifFzRZka6KEja#$ErLD7!#4!j<)?7fxhw2ZGRo%=8dWB%_#)xz*2g5 ze!=|M#{0g_jnqDu(!jRYFJnHq@SU^ikKGv^*wM2eSVG$ZwJe`BAW{IuYku;6)}0=@68 zB5UQ%JWi7knr;JsW|M|Q&sMJl!J$JyIXQ>z`_4zBeK)J5soqDARJ(t7mn54CGZr65 zuZ=EoFmeKLdH_?+b_sg99DXA{AzD73aoa#XBinV4mW0YJi6`3vL!R`*bB=TQUTSj? zNf@nm2+=3Q8etXKd31P=(~#|tdvuFSRa|SOr1b(NWN){KPYE)lfu~(kt4>zCA?Jh4 znVBc%oaw|e$l+CoX;m7>MWFGt$1{6{P(-?l=NyjrvCf<|fo-;HxlR|f8!o-BMxtVp zx%tb$sRm{OJK>_4ak6eOzH=@=2WiM?F=a!*xyCr`IG(8iyWga=EE%E%1F592r&$_y1R+ z>Fs|XG)0d6e*#VS+5W!>O*6Ql8^QXG=O`I(3~|LA1V>IsIoP+Oel3|6^BU*umVgLO zJ5a7R_(n{5E60}1P!<}5igoIf9G^c_lRILpmhp-92-#M?mr(mXogiPal3%{0BEIs@ zUOjNFyn~>s=cKcG*XocflEzebAcAulq*Ls@7sJSV9yz0`raU4Vqah-*8NN5Wp_>%z zdSA=}ZeT_{-~e3F&8B|vq=VR|=HzRvB6O9enW8Iox9%)U!9@N7ig@+mQYJw5VBlt(Gos+eyq-NMD=AX4H4Ji| zIgwsaeKb$NcyrJl#AphdZM*&8|6@#DkB6x(&C>Jc)X^|to}*TKTz2d0`?Nvi<%t~& zAlqIiY1UWnssj-`uLOM`d8LswEi0i{PDSWLSDYulgS3Y4Aa;C94<9KwDkrJWd6=CX z^t>qWkLN?fvZMJT1e7a-@FwFT))TSrS6RIp+AHY#$DT2y08Pffr#>sufVv|Bf)xtw z8+)k9I~U#rqxAohf_i*YmR>8TvsZUK_mwQB8@w4$Th1_PFX8l&hdJ6M+cmmOBeOS1fH29awI^ z@3nRw)_lVrLX5QE9ytWbF#f3XWPS3a#q7ZK%g&_N4vt^jD;6BtA1U`{4|Tt~f}!=p zV!okfsseSvTw?H|y!&=?8g?5Da=|?Q6$gf#mu0z(FD>++EPWN}Z0&Gy-cS?dqmlhM zQ?42>VXvw8hlYh!)PvQGryk3=7WY_W85tIZqc@u9%}vd9YSO@m77H+D>cnX*CXV9T zI!cN=lt`B2I=(FknH$duoA|fsn?pmLz*qZD$J05Mk0XlqDko+Wp9N=qn*}RSwjpLfmOueWjet|!akbXw#*)Tj zP8R27v{|N(WMa#ZGRRAB}4m5S{1xwVdW_O#DW%WJDY2&o$1 zhE*FWp0H^?zs`s#n6@QQ{x`(X{XR&@f*-xe^1wy)pL?PLNXdM2)4%^pWp2N*@;WB> z`wtV}6CGnQp^#NV70lo8pE&OeLLoO zQDN0DJ^j2cXMcxz@wy$=?M7z02j|n+tLfI7_@4>u?k1bGXYWRl9eT@5Gxe2t+>PZr zdhaSXBa+aT(e`-Zovwex`pjU4M`qn=E(^f$X=(kcIrtO_xd*<_1KP)9BlYcpT8F6; z&T%ed49u}$Iag~QF4a&KLyMlz8Y8T=n+C0Ew*YkLcKUM{(BwY$OS|h3p4xY#(xu_b z!yJvUE#G67Tjrz>pd9ht_c{AK)znr7?VSq6M@xakNXvu2W;z>AcU%XP8X`dnJUbjt zAL|-uD_$frCLETvjoj3;$k7$gW#c`j_CGCj(u&Ud>cP~ui5g$~#$H{N%AtWRYfp?y zRfTJB*tn)C>uYWALY2Sw_U)*p9l=W42glRzvB?V`ARuG4o|7{U#s`#_`TvbD68BQc z07l@=s7Z)bRN9~gq^)jJxa6f>)Ov3N0;tJ^=M{?On?3Dj+2^q0pkZA^g)rkoJHl#T zXI3IR^a1?RKi`;b=){tHXc8q%(v(+lCNc(A8+|;bD6hcC&WXz58k;Y7 zu78`0^BciuCB#{d2!n_AAZuTF^PiGk5w7%v9T%y644)a|t1;vA4}^f855|$q{K3PR(4TO3v!}ZIz7-{psRD1$Q@`zC_p4O6ghM;v3yvU5`2wo$&pf7wu1;s zlTTWR$PMx3?F7Y6EkAmPDVAZVDml?bP_~d~%&>jpbr?QJg3~#h4Q*_MpC>O?q)u4} zusT1qEV6s?9x=#$0=gz&DPw!TSo}EJC?l))R09WJ3V{$a4qL<#t0_?7{$gPkaxev$zAFFa>lbNa+FR0z7rVkqthmv&dt%#v~z|~tAp0WtEWG;8GQUFryh_X znFfBkQD(aJ%&jJP;L5SLJSv^k zYfB;_WrLSGwP;f8E)Y~Qz4y4@-dqMt;(v5)wk|jz&%}v{OO)1a!CO4B;L0Fuy55MZ z9&qRwy*v4LcxbKp_ud%-9)9Y}6d>Yox}{WQN}2Qs8b9iDItd*duL1BUX1}huhB(kb z5}MEr2X*Y&D!%1D?RgD$ruH<2y=yrWlHd=Vpc((*k73yL-3fjBYRqrlY6*<2rSR^! zLe*ngAb7#hXA837#nx8z@}#gQ2;V~>h}m=uMmCs2F+Q87n?{|BZ8hhC730r+#>zX} zOrI=9meAu}d-RRRI#;6Zi=XD3n!#GcTtkQ~HrdZalt3;#$8eG&e6%LNu~Eg|IaDZp zBnqSwEJ)d+>lSaiV&2{3JeDj`WoR)vsvEcR;uLrzV&gjc%9ZA=3!Asenn$~}=^mAvRmGGpHWgudh*nBHw#1iLZVtH*FL zEE}B9Ky2iT_X?WSt1P(WRxVx1CR8goKO#@RI5f{zXh5>Ztrfw{1FMfzG?8ySn9G;n zgIrSVFG`(8ER;$#2xcy%X=a)TQ$)iJ%*?Qo^57ODWkg4usQE&^w`jQIb>bu*V3I;; z{Gl{oP{U(wpglud5=MlvjW9}?8;7;5d@$O2|H03<4WP+cf+R zz?tR}7~kEKf4cMd@YOi2xoy_(=+r0)tDk_Cu0g{tBGuV{>W-)+sLU^w-;yHIogC|6 z6g|iF0^}TlMUey*0#Z4(tA##e=KKQ3eir9>j(c!*tcm2JeZ>Ni)Bn2 zZ3d}%1gwZ&_5>BXUprnj)g)FlUFRsY&B!=ezaHt~FJP(A{<~Na1n{$Wjq2^bEc@+V zaboz^)qJaAk@vV|pV9Q158(E!k&M)4U*u;3sW6G-F>QxtT2YTchjsh1HkWs3itUKO zX7~Y16a71z>rd1E0>W_9Jl3C|=#Eza`Xk{=8}pH~XFXPXK!Jev5&jV_xChSW_V*|( z=xW!19l@z0U;`QSFKeSV3hx>j!%WcM29np40?6f|es z;k!bweofJe^9}^ngv>SF<8XTj_ze2^Vho3`4=YeK_!zxeuH_rY3NL^7IYKLU$=b}Q zJz13st&m&ZST9DZx4gr7n10Oyx~$sr2VA``#KK^uLZ>GW%;{IUKL^PdM?xzaY)_7= zJsViP-YLOsKR0{`JiDSe;MPb8TrD-6YV}WTPH`p{bv*y3J?%p%7(Nko@ttGpl-qOX zrRfU{{c+FE0@H!Fo9dKBsanGU_uc18r}v^U`=dL54S!(;rjq@h%CMn?d-|X~hI4*L zT0s{ZkXh}zM7;QkN|2Ewl+N*$Tpwvx4|TrVpbB9dPJdRk9?$zCpn=V3=N;8u8Q*z2 zz6Y3N_gL&3SB&jS7or(65BUVEpMo*1K~o+@{3T%A7=elOThbVWes9YR+1XPOua63h z!)d-_!KWqd>Ln=ptcBQAqcbVPVG`LZ`e8fytO4-HVV+jW59W-4N8o7Qqocu9Zn56B zjcuN7pBs!SZGg{JvyN{Rp#?K(C)vbufvL3+bVjzI0QHsrymPAj#{z!aZ@|wvVb2j(+<7G{5;LLkIpMdPiuSAS7`8MOQ%tndO zS90?B>*WXncgHPJ9Nd`6)MN2`1%DKfe!rgK)70U~X)>nnY2F^XA1{zp?`eg@4L9)7wH_DN{gHapSf2h-SjoOl@hxW z<)2m8`qx6P^~=bjpzxe|^eF*3c)`@KJO0W9oxDcbZKN{3vSXX6+RO)5}A8 zBZhp7dA+sB;!M!lc(0tPsKkRwYVDVz@%pIJKGb?^deLr0zSMFb3?`hyOC8TOLwiXq z5czn9(-{>tCY$|@(~jNExtU_keSN#q4H|B0A}>~;idx*-D5HSP%fkiVTC^1HUsL-0 zo)$1=q#Vn({!l&9O*JZ=iWw~9sZVev>`+?(_Lmlz;Yst{U7NGi)d&Q>S_6Uid>&Qg z&o6p_&XK{5E@kNWY^)T`lpyp~`Hl=vb5GLHCU!KY1VvCb=JRw-<|+8iClntDD*fJn zk6p4gJO~6Zm#TgKj{w-X0?=AGM^hb}I9q6*&I?xLtEh21u?!lI(guLuT}=!48HrTV zvFJ5?^ysm{lM8N#;`~4xY3Uu6OpZQgYxdO|p9FsHs1;P_l2r&JsdI2vcb!t@*OOf< zuO3(*W!=xC{(X-oa-HM0&xq;xSX~i}yVRyTgI8J&&0w6E^YwY1Z&%*TvWB|}OgWJL zJwP(bGN^HQ=VJWHjond^&s#PRssUZT!RvSAPZBxboHmyj5ntY<(X+c2cAWO)1}{vW z_A@*b53-TpbCQvo8(bF8s5i3Sk3(7!Aawcs(K_@pQ-&feG`_{^%IsC!UF_lVK-l7< zTuV{Fht1Bwox~gVGT8@mQ>%+gj$PiwvCBp2xZ$B+RB@9lmsOi>QnPj+2Cm{5=OX9M zdy?XH6S|*Pk*yC#U(UJAs~#V{`eWCR(SM&>Zs90x#K`|eWrE%5j;$riZveIfp?UC*op zKlVKYt;m)CI_rxqj^FwVBxRzrJ_I51uZ*E){CZ0V+l#iw z5C+2jKcCB|Qpfm-F!hWYw;0s}y@j@^QN&FmrEiQ?9DaiKcWTG|?O#GW-R08c@vk0^ z@IZ`F*6g>fc=U65pl{l>ezwzHj)JZvmgDP-b8Toti7yma1|+wF%v_l6LZ^5Y59oi; zT4g;)Gnx;EXN9cCxcDc*hm@*Z6x<{XaKfMK+jOyCEk%); z42Lk8satZPTiwoK9YGN&-9%mW)rexiBYi5D;T8AoqN*L6Gayx9Nk>bbVk+H|FM%E0 zf4)Wcx9RZ;7X2v+?|t;#q&=5hGmb1YwpD$Ego2JP&E;w1SoTk@g$M2=+_qd|ywl$} zj}sqv{K*c7HFeaBq}khPONONg^Sj`ze(7owfzZ~s_j`dln-t|F7mRr)3 zUH)|{s8D_7dAi;IecNN_zY{#rBpU-|SCNwSf50Rc|rcXW=5$KNdL&c`5+=X)D6HdwHwVl;Jj#bk`gL z(;>3Hx#O*tplZYc<}|g*VFqwmC(aWwkoRu=9k}#xcVr}p&|+cML4r2{CD)6E-VKmh zbU&Jp;Tnp(HCTzS@yqz@y`T)gk4*&{)#%)Cf64z2W25nm<`bMf4NC{?&Lh;V$?cKT zxnNhsN=-#l+CUElyojEG-U^v=l5Kq~fokr&*Omz(@PN-o311W5LMj zjYnEoxT~{^1571Eg@6AMCg!#D-b~1Me|t)tF9p`N9{!sSc70$6=Z}|z9E`ya2}iAt z#gR2fl(8;HtR7Z+4|SGLcfZ)25$Bt9M&4}N&Ufl07Zi&gCt%A!Vqnr}6pKVV_(-r?^<_&Owwp2(|$PDx$+(H8>`#fsb z&V7>Qo1+h1Ggx#pv)zS@@ciVsPg;n{dclyx0t8~VRXFl_{Il<%W8kO&Qlzr)WG{ny+EfA)ej z8^G4*KXSkNac@IsM2hl10(%EhD$b+TA&%PY<-6fQ#Wy)oS}CQ=ngI<;gnHyjGqjq04gmz^p*=$x~i%vo$5S(W?$68A> zL2(W2)I`@d0Ql_dDj8zqs{_3S_y1Qqv zfK@IUORc~;?=id8i@Iu*IGRLHUe508(e`)1j@-u~whstP{%6Nrkv%*>A#8f5Q!g-bo! z#r=OHdq;neJy;>d)&MUa!Yh-{`!}+O2lJ?|t+OjfCFaZ5F5(~MU(ewvJQIBOtb_U` zUC0yG%e!47$2$(10)iSl}deZhpusfe6l3!42P!1yqb@v-^_rUwqpI9 z&nO>402)=t$`7bKWDk_vJ2Axa1(bowQap)ifOED3GV)^TBW1o<9^{|O%s;zaC9h*V zsO*g<4)-1Ib2WIA7HOdwZ>@O}usRW!m56@?x`x&pVRK$IrKZ;q4|p9I>K-V_s^4PH z4@YgtRKz4opyUVC(zd0ZhIc!3%tMMA1N4LYeJE+Sa-9zFLeI-UU229jcHR2E-ROzbikf@ZKX$3_V;30xsgO%Pz>93kyoEC24>EYA&AY2>3i zK^d2jn>sdMj(#-pP&x9p?5E?a7)L8A(L+SgA|NY5pC9;TU2p~z)$!y>MGV)}2Rd?&4C^W;@T1WR|4x=B4=&_DX7W|wV-KQxPsAN&T zb+X3oOv2-AvFwl8c_`W6Gmf67kC#m9RTl_W@i`EVgpY z3{O03SbF5iYMsY75bd&{!F5Cv9;+tT7;f`aiBOM&g)Nm|YpfA1dCp`0-ozE}?>$2W z8uj28<&i);m6>`z_OK;>n%g<85E&h%wFzsf?PVtv*>{E$dYkA7=V5Eu80e?C7g^X% z81>zr)5YMDMB%;6NB*b@sL}`jm7a3J0+RkSig=LKoC~s+E}y+v$yvQOH^~J7n)euBHQvzW36rl) zsBb2p^ijn+YX_z}#eYb!WFn>H*&<0$mD_Vg&T6HKt1^EM5g+F7Xrzib^SS}2x|MJf zPm9`9cL(>?fx)CU{QivYNWfx}!SzeNKF~wa+}VNzOL6M6S}XCb@N*Jr`Q`*8CoQhR z?QGJ!Y7g2f>XD7s#h8O|)-kWq6jT)6f!I0TlvWM;zaXOaKOtftuSS&xEoA9dj%-r3 z(%lD3b;X5kG=DJ+VLN;WLD&u{Zc5)vCqCz1ST^2Hs7#H4=~@@Eqp#1C6&Sg*=XU-Y zLq(U-pEy`KIUU%%4|wcsX7}4`jTaPuM$cuv*nk39v^wXvIWoIN(#iu z^FUQKAPToRqj;jw!p;j8H!Zq*h`~&1xQj*(2Is+z)T*YOc|u1=6YQ$=({B7)`XC)D z#62+C3}rPwhhHc)wLg8!E=!KYaV4y@p*^xz7#+sfop0}5&+#VmTO@1jR(HjD(bF^d zHcoCDTh&|Sjvm=;-dl|urJz#^vD=)=)WOr_p=!O1gdd@Ny?t+XjaW1|eki96gOFZ( z!3bWxpEGL>dqvC_*%~%naXxd`S}`bCoWn&tLUiu2ENr^M#c?1T`(^R(ihWz?pJSI^ zh~E980q?!7s9Mtu(`mXlJoQ=XoUCxQuNLOCM>Q#L%)?tB!QnI@DO?q>Xdt^{>mv((ddejPyb4h?~2;g>8X2 zNFX7kUh21EzXn4Z=%4`q6WYx<+3~&0>o+@K7%H3?B6}=6()!V2(cqn|@ixFgBu$Do z8B|o>5n8EiaIS29(cpmP4lO(qpJ&)_JNgY4ef2&5if~zu{8$OVn zRgIYiT7H~2|A{L)?nlJZ@fl%0X3b^js$RN%IKmisKbX;!%W9}7hR(<*?NTx0JPbc0 zLusaAHt1M!GkTW|ZwM^gW-x}%MLsnkJ&eQNx9?5zczd|R>hV%0>B_J*y1gOZ_m1n5 zep-~rK6TfM&$DLp;?~n(zTw*;jb&~3AIM}uN)QKMLJ!kKPHCx}S zL3no&N)*s1^1^ca_%5&_$5uT4Yr|oR4=ac9TgdQ&c`wBiOIAjsmvRi`a)`5Quk=Cf zGXG}#GhoIFbcR%$qeZml5d0s^y=72bU$?KDgaAn(kl;@6;O-WJI|O%k3pB1F1Pd12 zJ-E9=aBtjQ8+V6>v&jG5wUc+>TW9ZkPu0EOfC8#(^<1mx9MAYY18D63gu7PC7BeH} z@D7O0Er`Zj$*c5MnS|74=u3@D#CS5RF{l{y4tt%tWuY!fMUH@+H^Z}qnoj8XW z8eB-7Z=YQ85bQaHqBCoofEvd`|D;I)JGR%`hQ2V${jNCK+TbP0qrKV0-5rWjD}^NY zBc1Q?Mes-&MqqK2A(Kp4mYmb+@NY&!Cwl7}E+2j(37-Ry#|^-N+`n<4xsJA2a|3c! zb#4J^m*z@eD5EV||JvTe;zs7=5R(B|GkaEBzqdr3377s$-qQsFuY_%%LQ9te-s+xT ze|Ni2Y@IAmqA-_ZfG58@x+oT8+g`WdeS*<$+L~_RZl>@eTFvziyD6ZSddhMzo2Ump z$nb7~)i9=dDc@3d7FZG}MO~5jIWScvC z5EME&=#A`9CcO}HMvETFQRrF4h-6_9uT_k(DXcYcIqOQ7K8}H&TXd^Er(al||GvxI z;BLH&DJUU5$M$opI|ixW*q&iMq9v_i|N31Sv@oUVy8}GaPwl^!h$3~7l3YMBCT?zi zW_tJoJHGvEmSG28ug?}M<**N%+iVHz&nM-MeM=$Yx&_(KoukxYR9HMMk843$A^rpSyb2^v8c)RezU zHGeLi7b~O+E6A>`mPI&duXQJ^eCaWe>}m1N)k~#TKBy3V%MFnl+_HTj_0v40Upr$Z zoSkR%ewjI|SG?*vi`3%pCR$T6>)H_wWb_q+rzdu_P8(xyP<|vA+Q(Yp2HNkI zO|!`rm5%KQaUO9!TR_}frma0tb8TSKaO+t?tzeoctM2wAMAYwA^x=PDdD&rgwz z;Giis#H+V}atzK#0Gsv!hoa;m`pnrjty#3e*wXa&?Wv}b4H!Wq)8=nT1QMy%tx6hU zsPkD%ax2AkB(|y!Rg_4{tN2o;ht`$FI$h$a2)i>{pd7CE$+t?IS4N7SN}rN>W8de& z-4Hq{Y}^mW1Cbfg=oN{E>Q5_#ui z5}!H#c+G7z-&;g|fMD{$1iR(lwzUo(PpOuGxwT1@apxd$d%TR1&oKNB!pG)S8+;DW zL}$}K9hPKHjNps!YcFJlzw7cXEin3t(fyQ2_U(LTV+N8kdzTJ3`BX$_W8*{)qssaVlecUI}X0AW`pV2z41%veokcMV4r@V zzi29rMC6S6EAX2Ohw*yIT}30LN?srl{GG;uS{dOGSz+h+kl$;G8oSj z-%1@Wje^kNp>ODVC()EHcQRc<<4J;-+l>tN$FO2O7Aus1mQ;%BJr@0#0Z6jVqX88p zfbUpuLY&#wFq+{lqdve_O{WG<2sqt2Cb2aY!>cd!Oj}h|+E_@^_DXC!n&TerfuQt` z1Of>?eH~*M{RzlqeB-@4)*PWnFg-HHfp6euq|Qp+agLh%)H7n$qm*s08& zvOEQV(?|Qs4)BwCN+jxF#{P+UXeVfXlGKapfhZ`3`T3LNU_$M+K=um*rQbE(N-E3^ zq%<^taJ5;TOZw-#PlE{l*GA^TSF0+u=V4PWJNrJ@R(m5s*cJptM?T%oYl)!iI(M>E z$=oCZh4cIF;pV9{5B3vxZ8A^1$#hf?#q@m5RH}{gQHSqOr%ZFTkd-T?q*Gv`#M7lu z(fTaw&EF&Q-TT9tAiemru_{x_gCz6TW=gV!hQ@9ZeHjW zO<#*A&DI5ty4rtYFVb}xNz4cUzh1kERUgd=3~VZc)fnB8ADZgAp2m{Fr{-O6;L=wb zy7M{Y4^5k52Arm+T7|r1760xu&HC&&*@g@6TK2T);sIj-s>@$mHQ(^sSp8yGSj_yn z&VEgUZ;=b?Xcp?A!c^&2kytrRt34KH%!mz-;4gm2@!->QHL|l{4oCXi0IfhX!!_9g zA^_~UVa(Xd9!W>BdI46R^ubOC_p^_rn3eBl!%}`7K?up$?qjFl*eIxr$liv?9&&$; zrTn1{N};W7RsPyneYBDfpRy7zUwRoCrs_cYdgoGi9OSb-J?lT=MwdH5Wc=~aD>%?& z=w$3`4aXa=w~;n)LK4+DHO?wILvElZ43Ik9QsF|Q{RfZU_)|_*9F|syeQVnD#urTw z*aU>p{TH2*s^<{lXY~uMweTsr>XUdFcX8i}D|P-uXu6dG2u;`e!@xgcjM`Um12DYk z9=aZdrh@+PsVjtl(3Ix>%VDTRB^FamcnN>d(q5f=oyxJT8;U<1Q2N<@j1#=dydFC* z%ZYcDcT)&e334him@(KxcV7m z3v;1TdT=J`>Of&KrF?X2awORE#;lP!b#-hXb2#}indftNcT5M~xEixQTlmKR@XqYA zX`t)579|^EfncX+W}Bl5(W5h%_O~wBHHy%9(70cz9f)05;iWvlS%hsO8(!4zs`5`P`9NkI6H;Y%A^GDheoNvWSFRbP~IzR!CQ<#%ebasR1ZSkuA`trmkS4! z8~$G&%>Jm@$JnApUF*KH)rzx{x=873uW66Y{lNd`QAM_JM{~L?+6U9bb|K`o>Sf5yzp*?yqo?0r8`38I ztTNTLXx*(xN?17TTvRbHvf6U7c(FalN0c4xHhoj4iUjqH(|pHu^4$H1$%o>?ctHVI zTm{N9pYSU@nU@?Ufr zn4ROaA8Zc}-2&CcKt-{~fZkU9jR2W4x`>Bah>iZTm3If7Yq-%8c?OJp%UrFwR5#N_ zlX+Rb$sPqUaiW=r>*(s5s?54~o&&wBpOLNZ3}3nZ2d5#n!Jr%8!)EHZr@NPt05R;% zEo-`70-yhc;~KF^;_9%OLt2MS*#ZeYePS)wtBUPz``;2s`{Jd~!v`|I6MCdIj|n{* z|KO`JLpaTM$kg#KbHq91FBl?U?fzcM@&_DFmY*!g>`p#zTx|@vBxl}Hv7uUWRz5E0 z4ZH@q=v%^Q=x_G&*}S}oDrJcKEq~~)TvOPyeU~GR|L6rktmmWkT8h4L2@;qxW%Jz? zh_>iT;DUc2`!O*ei12mAw|m(R@4m%Jf zlV0P0Jz^I~XhY(tAQ*hWAh_QYC_bHhNBccmwwQRbn4Wp!vdxh#7O7%!d9aSWd=;sD zKk}j6+@NhE-lTv;8MMmbiO1#7+AZ}d{+#UZ4Wnn zNIko>(P0hhp8tu=0Uq_%|%B}8_WTGO}I2r;3_Za*IAGG=oVh>FwzaMk} z0?w3kjp-@~3noIU*iSR&~(2opoP)`|Q~49OeTjf{Rxu6ahmj$0x6(^_t1C zx$q`WN<-1F&gwlat@z%2>}QwiibiIA$ixP^UGiO0Q5hT$nT4KmWDyUkLBl3`pCq>FT<|r&Sa8i48tSi+522w7znMVU@ zs7^F*33a><<*S#L&0mMe6v1WvpYrZSjatxVKT@)dJ7x7Hg`|E|+Skaxy;00cm1W<- zkzR3?+ejz_w4zAMpXwLbovpaoSft2{Tu(BRtdvYN#%Z~>;U_D0K1j#H9G$h!!O&^< z6sMK+k{qnL45(QV^N#dQ2vRq+exJ%Txd%g-H_O?6vL=g$7`Pp|yn*EjAEi z+BckD`rWS;Tn9^+w0JzLyd)$0h2F$mvPlCry)KEAQGEVx2UFg%c(ThwBdrqLI=x?m zh#r(lZ$+C8M&_f1a(4fbiKacuM1`uG&d7K5CFk=>wcl|fGf?iSWX)yZp^t;EX-$58 z77lDjp$hN6_(vuxFXx0*uz-zT+1a^}cn!S^Im5&1y6hgD=gGx}OwtqAuhS?TEM}{> zjxWghdXj|kP@86d#Y8t~&;1X}EE&)&;GF5>gx$l3lpM?mkxi9*vAjtxrgnzL3XKewJ!zJfN& zPno{gM5dyP)S**JfyuQ_&wxeiFPtl#>BEXv!FQ2gtp1!q`^~MVmzW##>$9D7+cL$% zZA!|Y3Sqzev`wp}KA}7v1ioDS5h3BXnr4(UY0$rVSEdRk3?kdSeBQ{P*l)F>QnvDt zAu$k>589sB*}EI^GIMF?0aAF~u`RK2TJt@stS)N`$aXR&bvwbzf4<=z=-JZ)MY`;Q z1-uR3g~FH3{S9uAKQSEspBN7HPYib-X$O*Q<8noL=!`9#ai;Qe#6$Lq0G;){&Q**M z1e4(p4#m3SIEEoBM>f$-eaMtD zX<90`h-P^p?yZ*W@N9??-zP@;i}w_T&=*z^@ssRniNT++ih>$ZIzukq`kZ?E-AY=5 z48j}y2dE$gE=Po}n<>WCf)hlZ!1hta)nV9k1I0p&;v8U`Q7RM-4G@PY4r9!Cm0stJ zoniBRN$KX@Mn`K8Tk4Ks%#2Q~%Hx$(C_calW+jhtws?I8NEiP__$j3USNGa*JXU`% z5hkI#yA}^&Y$7C7&sMcZKsy(&g-R<0!$~`;v)5+wlC$Klheq0uETnD+)GxctaVaVWz8U4%4 zot~hRY6q96(bcsPX3y>GLhh#$fzJ}xd#Suu_1+-Jxb4<>+3OTig`Ha|O2#_}!27A4 zoL6Iw84q|rlegWgMA~W?4biAwuWvWzUH1^uGUtA+Zv_b@C|{VkVc``35A_8&uqE%l zCo}usM`%bQZqJZez3@fdSH9(cI1h^Ve)5VcsOiE-X9j2}cEE zGt5pDc^B+gXHqhRvaM*Ixb1LRcJIf+bVJLG<|r*)jyv$HM%OOF&-iZ;yvU3*udB#< zDsbSnw`MxJlY|>A-jVoamC{!cv}UhaF500)-_G8|?_17dgU9nKYNsyn-DDGA9x#28 zLm-V+owUVw9o1_yEUvTvu@wh0ROiiGq71%?(FA9s^H|eezSxZs8a>^)im!CkG(;{28$^ z5r@<+%FMyyEnVT&KSUq#7qM;X(M!eZK_5|EtmOJ}i?cWpc^Bs(a< zxK}?*cgT}1;Wb@qq3|}TMt!@#to*Htz^Yp&%PRmgRz|d9ZNj&3-ZQ;p=OjSun9)M; zF!K<#V%v!_zVww zB6A4wMP&?hQTcg#h)(xjhPqdODVfSa-)oRLnT2gkaD{KDINJ!F@p*YP(j(5@aFgnIrUlF+ogcJw0&`4Jc>fr}Vicn1E*>-WwWs(Iv-Y8BZ!KTE5eZ zUbv*9%3plQp0DXIa{1U170zLQ$zf04RZe`plxXqd>h?)?BTi^cbjLApaY3gqtEL(9 z2ZZOz9(Pd!o!y$zYq1|)qD~|!%+7D!-`Mjz`2m8o9On!Zop-DU3~zJFPciELe-&gB94=CKn1Ea73+gg#&ivl_S2GVazVkZT0_Jo02^sNj9mNHz{@aH2^U~CM8 z0thj7VIvHX$~Nohudkgbz|6@ZN+s3vo?i4)+?Zuh!@=sfKe0qWy`%*;S_F{B(~qpt zPHC#z3WFulVQrfBpLMAZA?NhIZgF0K{#6x(P#}CQ0f;nH^7_hV#3Ws zTK8RVxP4ziJFi(4qgE_yA!HRSDDR|tGicbV8A2xbFnAa(W6mrsGPDvent*cN*K%dr z&dC`%!#t7Gzjo?ey2PnG;G8^o{9i4c>$*S^YVcqw0!A|k;5n@o7BibQ!($;&!@1BVB!9nL^n(wpashq$9xg=J2YlnR zZB4b+11SE*a=2@90pHgF%jV&U{H{qnqY0gY6@A(I6luH}=CAQD*1-IwGXdplo=XA^ zL*0VEuCloyB~D>JI$=eAd@WDzglDNm`X?C8|3q}A4m^wHG0d>TwH7vh=M6z{fL}8{ zk5mZSHA>M;&Qw%N{EuHVPF6?X)B?nbupVCOPH>8mQ&*{KokiD`Zr(u8rOpn|I^N0V zz&={@D7d+q=;A00F>xuKnz0#&DXf;+;0?%af`M%7_`w?4aUPPQEbh5Xhh zD(|s?x#NiwRdNK6h_1eT;A2#Kh#)3QKMEeG2#|_rAA@Fo(im5=juJ<+N<6AddbJMuGq=zcZ()QhFN@gY#jwNU)rN;Oo!kX( zybUuoi^jHMdc|5T!s6jh4Qq!tF&*v-eb-E`gGyJMLsR5wVqP>I~B73H== zT%k+4!Ix*XLVY7JmTHZ`sU-W=kcF>{Ua4)v-YO$K6tPipVxCZ4Y+NKmG#Uf)+ROJM z3m(kLTx?zbG!YN;-J8gcU2rD$~WWhDY^!`ct*sK1N@*Rb(P>cT`pnUn2|GK0Wli!W`diT_- zzw`PdVl}I(7!*pF8w5{uF(JsinYMahu@}KWRPKW4C6FwIGh6YIkGI;>J7^!i`TD=J zoNt;xzwt4Ybqm@L{0^baCO=EDrBESz=-W|gem8;l@iGt<3mQQ|i3-d&`D8zQw{>&H zJU_L|VsXDjy(fK^)vgtZeR?BRIHsd#(D=Gk@BCz0ADE7)l^_f2!nSp4uBemzR8B;D`U)mT~F3-{fD5?g|x|xJdOSP>}_Em9cuko zyTV~?*n1Dl44l4R<9Ayu(6?QPrh;o-p3bx7Vq7S_n_(@$hFUQxepditr}JkG#aO1W zhdYfjT~a8~$tf^!kUUh%AckMf){iIAWNlu3HA|9xgx>n>L)A@7iY;#-w3qYO=n5p zc=5|x&X{%3#1C;VC5foyLB4YB*$)Yc_&Q|?!z5S6d01+dC$YYTOst8n4*%e=SA%}& z1a@H!oK5#^zAH6OKf{N}A~I2d;fO#ZDIo70Dq?nlUNcnl-(cww(99#C4pOwVf!1Uz zu8LuWTe8b33?jc2<|#HzZ=-Up{#ab)ZWM(4X^9 zEp;`qllN3Y!}Xic6M!m?+bE77NI<`y(W3ZoJpQCs0Z$prAf}-1HV9H%B!2HR;ZLIu ze)Ghh$iQs5OhzHcT#xF97@GJV!8E(OT+27_4_mvc>8}x z3TeG{Qsa6>EVNrs-~(i=Byzl##2TuNJtfONHtp8t={)J?cL`U*MIH98ow85xI+le) zv}gy|P+59py%}tOkTRaIy*1WU%XkEawA5Zmm6Bx2PQ2Fn33QY!0f*F}(P@ z2db;$*G6kWCtPt1&bqmiMS9!Q;{ORt-1hlD#}eyQ|DUr&x3b(1kxQWmTWlRqd%sE=T#Tg;l~!Hu;QLXg2oqnY9FLu`9dCi72CjxMmbiX-vCNAy2Oh**{JsmOZq`h#)vd)|%Y@jKo z{d7rpf8>rxvl^kdlfX+${(1%g&K@9s|2!fk?E$g zB(Ccs&c~Z-*#Js|f$yGlF@i0Gs{E41YD!c56`GSy}*YNuX&mRZtNZR#t6f$(#^#t%s8~=hmDUFE#obV0R z2$?yr^fwB?+z17AlXtSwQv7akPnzQFE7508ju8ZHa2EAlr^}ybvV7G{AMh1+io%re zD3L(QhfwMcv#MVo7miP1LcbRYmh(crhTq6zyJ)!=hlpWG$AHxfGqjsW$vTT4AQ)cxW{2Gd1NUn!l&4 z{`5Y8?JP-~+Su2bVI2&AopIOInNZ{0SQzFQu5D+9?`_Cm@I7(eQHv;NQGb+zDsLMp zMri_4Q2Zhua0NB7_O^)hwL@Hc`U9QOW&b6!g|L%;^}g=V4ej16C?N=zov^BF|Am#| z+E%$1X)H)^6mK$RaGAOyx4-EZ`-`G)26MH*xCQ3Dsb>pQ9PA}zmK&)s@mSKxs3 z`+7&}u=@v_gq%J7je~q?*^SZ1>4qgf;&J|!*?HJZkJAlFBkbifU49VaZ2z9Xsao`V zyiFgetyoC6o&$bE|L^g#ZAy=2-Ck`VJqXN_*>lnAy_1j^)2%=lGE>4*=9kbY(2RfG zA4HXZV8IgIOt+A`i+(zre6 z6IsGW-sM%_y;nE8Jga;u-ANPVqo}})!paliL4n(`q}|}3eapB0;9>tQgLC&Z^z@Wk z@?|`CO1Da=&=3qQMWiJ%DkrW&o$14utbwI#_b$yzzsl^>+>u~s3nZQkCjRcItzRJn z3Uk8cbYEg^c%#E!{oU-FqxPNe3mx9Hx?RlVv-%YN3X4t{0-DOEb2uFGeR5(6Thgzz zUK@Rceu+3^Hj4_uR*nIO{8#M$t4t%$8W>KpUOwk=&kUtSW{J$CjjjkT=5`^e?{FO; zA5iU8sGr-eMJl3Tt60BpD%^D-VMnZuPp9`~UhQ$BNoa`Jvd6c_}FDc+Z&~T>eUWduZkNmh1S-( zF}I|)gr~r?U)|TnC&II?&EE(M#U|9y+T4%Oke6D8G4nFw=CQVR6PHKCci}S zCtKWF)`BY!6QnR0s6&a#eT*WvMgOkn2mF)l;-Y__qBC8(ty|7v%CC|#hG7?_BQg<2 zyupO2AfwH(a2ZpwdS1JX^V+u=3@iblJoW>N+Qf^>3r}(3qcFnz7_}O`ifBfr!6VOs z*6Li#gBS8JcI7=_-?T5TrkXU-Caw~%w#P|I(=iihBcp^KrJ?EUKYvE7jDN9uomwDz zbhMj!G43dpTV<;1sEPi69Z7n-EFf*A3n91-;zpvR@bdhb?f@@cAHDK3>sW zmDwP>TP_)Eo$eiF!T7o>f-b~`E(>ZDU?w36-AqRaw3xzlzl({GA|BH%3U$)+TlFca zi-KjA@y7G~blScWNTWenQt8E7elby8#tEUr_c}`a23P~=F4nP<3tUQvo*B?D^Yw<2 zN*Q5l?AQ-OHKWh7<0l9RqVDle-;J5wAQFBUT1z>5^?jxL(4aqVuzzrNJSB@##R;Jc z2UW7M3hw4L%ucELZ*^l7xvlEyV~S;C{YMZoUo%}wSpVQ}bLjfJ->nC9vVnJB?MD?H z+!NTzepR;Yfy5ry3hny4mi!9OzDz}9bfsN4`VtW$*^qh>(1)xN<~uIoEZTf51Bu%M zVBaLS<2KP}xzH5X4G(#+EW2%3aaqyTh{a@}auQm|d^^0scB5mndQ`J}&71{CLQJ2c z(4DT(&E^~-m3PRT)p0aM8KU9lkiA&1Ww?`e?Ua2wf%9^y>xX>dR_LXqg)>RyW*Cv~ zX^YG4lAAcSlddHJW+ZCe)<~3w_6rIYE6l@(gw?AcLNiA4u0MlM=H*l@68}L6A8tUbxT>$Vl#z zX8@7$1~y% zme2~MOmG~193to2q?y%%!DgiK^~gJa!G>>g8WWi-HISY<1I|tcCRuU?xmhihT~@{~ z)4{x``d}Amgg=!|fln^AnIH)t7|JP{JrQ}6+?H$8yJ4x`N)iDIE43CUtj z`&G#&iI?f06s79;Ysl(JF18|5!=GO9%AUjlE>Wms1Y!Y&H!UvEz|9Mfie~fZ5)Iwq zG=m3RqJ4$E%yslmWDRRlEQIzH?QP(4qYIfFn~#!@&IJS&Rp@ypE?R->iOggnPM^W$ zeI$HUwB=&zw}~43*DO>{B*ksjJ!|90y8+D>uOf{Fz|~GOF4=`9Sq&LUl)@5ZU&4!w7~$--Tpc zIBs)V$&+#P(EIFmGg1JP)xUe#5JmH_?%@oM9ORxk_-WSEp|# zp58owUX95n%)EisGoTnvhSEUuITbAkfk4KGI7H&u*rb~Yq0p{6|&@X z)j6pel}$}n>2B53v8OYWPtMRf#*k%1#?VH~&$*@h+%zOsdZ`podpyn%Z|S?Ecm4wv z6dWfr&ziMUl}it~dMz-I%y;k+Q-@=@jgiTJiIPxk&~$rg_oZ0n^o&g zCGlrAbAG2?9rQDaW1t?UC5>l(=&1U$+|Z41#*$aO6Eiup@g3s5JmF~Afx+Nd>haj3 z#5`IwN1;33Y;?}eZg-mM2Jr}R3gV``WFU4YW+uPZ2M>}0Jg`Alc{95{Q*}`1qwIXw z?0IIbt18BBbHKZbfn>)>wuuT(w<87T*2c~qX;zo-h2v`QcoQ{Xl?USt{pzk z!oL>t!tb7r@9SPR#YD@8FmZt0SX~*VyG5rBJV-IF-=52aX&XDwxHJ76oe%`{#=hE+ z@1sxtIdOO@Fbti?zGo*$UJXp~@E)&i7fR{_>vUv6Dt)PX=t*`&eH8!^#Btp>6j7Ia zpRy^_P+&d7{a(-Vz8b4kx_V{_2l#LEi7nh8_-bu|ChK}P$TsAKn-Nt(#`BD0^D zcNZs{%)=S8|3LycKpda5@`z!kQ+tZ@Va$!@D5c}uORu%?z#sPzg65QpD0~x1q;C$T zI@#}LwNZn!ERIfKe-)Vwr0_Hx+l1lY&!z}+tT!Gzm6t5+7?c8i*IzHy|tC6vwz z^gr=EM3B?XP;~}knSe=xKL{b7owH((%yLlSf5R-%(LQZ9kuKcB7ai#|ja#@(n?|6< zJv69bl6&2g?oWZ&u8|ESmwqt7g66m%j4k^<5+v7*{SYObG*<62U&Og11JSzHc&S)&7K(2g5)m zpV!}nz)WJC`e8NmHDsN`ct|moE^KJ6)f1x1xaPptExG^ao%k)60OK}ZJqWH${}MDp zQ^d8U-r8bRGVuQrRBF$OY1DpI2WG*W2l0UK54HHrp)|~!14jA#WHEOMq!oxTaX7>K z$2swQJ$*5dMS~zj%fD!td#|aj=^KlCe%F;DGWgnO3F3lN4!508>A5ZrLl1j( z0yxZa?=i@ zheYq1XOmV2WL7pWp%pAR;izL@X^pg%8)UU({nI8du0!vh32ClGh$I}69Z-$A}%aXsqq(pzg8}Z*GT@n`P zXc?H`MRl36bp z1mXTpIs8?BS&MrzdX+;pX|Os+oKof$T9IR>CTk^1 z$x9+3T0?V@uv-eobyqL!?vm@_&Cr)pSQAJf^rfEvA3usKnt`vF9Zx;@oeMKw+y+#Wg?Yul}!A6lcj-1`d;)YTM8!aol1v#0K84l9`JH#M z5%2~qE=e-Kwc8D;>h9OtcUUNcqfInux=#4PdiNa- z9?1~dT#+XJq&BP4P?k8}EH%FWff|3YAwXSa6DPF~#%yvw56y>j6xPq8`-2&(@H;B6 zrz$Q9;R7U#>YD6^=JSvoDCzfbpprM%P-Ho@vXu=(n?A}~229H`_ zty68o>(Fr&WVRDB`vJqQutV_zI2&&K zdHi*55+YMgyZWWf(!f9cf!W&{hNa1Lm^y1w5l#WY^~^$iGZbBj8$>@ABYtu$#lX6p zZ|TGTt%N1HGWDUoML+Qerc;t+@vNoMZs}xxx+`5!$BL0rXS&8@7&RbGwI0u|iord{ zrJ85@ElrK-)U#TTsZ)5pqo_TdS8%JOhBBm5I_un+8)Af!Vg5f#{CO_aoyTdMLA+}Y zerBa;bp296PC!a-ZD;<-dATc6O{d;H({W0gtu)3+{$E0V!CdYfsDEAsV2GF;LrRry zX}&Utg+=S3>&i13Cg1Z6(L}@xug`HwZT#k*_6hed4B#r$Z4LN&tkg*H0}W5RbxQSY zsK5i~X|U(|qjQnlBN=>r7}S_D-EXe1fw6X|-DFL=8e;_dLQBdl)@Wk9veet%nbXI| zIfaWUQT%hkZA?HS*VyCKi3^=)l+J04n}^GWqOS8*W-09x5KM91t@a}>Ga|7$3o;{3 zMP z(W6^bZ5TlP+v66H<6OWKd$o}-L@`F8fPd3!S&vu0->T`rgC0sp~py>70 zCp=dmN@z5H+&dO*Zt(Ez*0!HtAMXj*wN6u;LCJo1zA9K`L(NR#^|<4cERM5k8Lesr z-_uz0hR<`&Qps_Zt7O)9*GdFl(6pvdC>-eF#{Y%e?OSaPP}gD%?oNU-BT`5$MwQFk zQ)_Xah7zXA4Rf*tU9dOe)jDA zoy89}$-`q9&L7k(QjMQ56A}PvS5NGJQ(?yUN6xmAVR@K2WcgMEJ6e5+F0@`~a;>BP zzP$41)cUrR$G-T-hteok`0?1Yk<-ZOiXD8%RB+a}H(Vi!t--Kwe;V8c~rM;kzIb}uk;qlt`(Av|q`xH89sN}&^9bXNn+k9(R`H^H+;_yn!D?c zQ>lzI(lN=P#*h7|^+f$@LzCa(%?&Wb?kw5fF33_f!7n{4r3`sGH;P%{%yn7ZlfSoX z5#8qW`eg{xS~m0bM9vHC%5Sm;K^E>RA?IYas@)uxzfR->m7)hsiO$^CUv6rrijH%8 znK&f)vcZVhf>OXrElarI?VkDz4n`Vm4&8Br@=QJ?Y;r48yl-slQ>7v&K- zE79}$b*<$3dQW9eFBjWl`?+RCmSxr=eLNgH+8yD62D0P5=0)`W?$c()8zrBEz^H>3 zo}4;oh$beQzBbuVc8u26$O=m$W)bnV-}O9yS=_m7lSEg*^?ZXaG2_Ssd8_%rdE;!e z;*R7M9!SGgXUsdBXgJ4 zC>;RU3a5g~PW@5PP6>u+7p06hOix?;NY$_8$QLKS*G>^`L`sJ$$%m2}Y(vRUyAVm; zp>W{*m~?%u50rWG8i9*i?e!|JHVUg6V~%So$u@ktUA&~J*p?yFiZsdEdTq&q*N#h< z55I;*f(g(?R!<wY#kW@Th)WiO)kW3sV zRHTo{bKdsXVzbP1&$-E%Pbi4bL&3drbZGJgQA%eP~_E>&b`rD}t z?T*G*fhHse@LGqGc{){C_OgZwfZ~(|b2n)>;^RQU=1h#_&58jYqF9=AZxcIwx}vJ%7K{d`AE&p5(Zjp~rk2?pFtc&m}lpBhFepUF7SJ zD)IKETGsP(3u)6he%h}?Z)267HMPBD6ew2dee%I)KI7L9rJ0(=GYhy5((fNFXUVp=}``hJ>DR-85630`IdSP911uI|BpJ$yn zZ3q}SRjMPUvX&Fno~_qQ6EThs5(>$6Q*YoZ`-vR;=`lThH5`m6@op$1U$P6M=*@gg z>1LmfZ*yZlY1XK-mZMPrW*TJ}yG)oCj=rqo(K>Ug2Idqt4j1ts)@8A?NEQ)3-;X11 z80$TxX~wwtAxHBHV1j!&EjzTO2cvsov!PN^u94p zl*Hb3#&99kW(pNXPdb3!kd(~Yy$*g)7%5Shk0%KM3&oWOeDBYHKsP#jhGhLcYiq^= zYubvox8*}ePr8udq49o7JuUV`nu9radznvsT(?7ZGWLnZoQ+{Bd4(zoF%MP<&to=~ zsc`D|j2hMmj`fUgJ&)uD3o4V$lfsPj*-&{1xk>S?Z{Kx6^_0WJoJ#da7&dm`p_uPi zk5R-LXmV*T&qoC{Pm#YAk|;CRSIZ8lGHk%d7exOjIr1kt=eE(m+yv54HJWqM{K{7)Ue&!mGvRFOBZ4P zFXqlVDz2{0@^KO*B)AjYEx0GR7w!_=AxPm+Ap{7ng}VlKx8UwhA%VgRcPL~k@7G`V zo9>>O?pZTy&7ZYkmE3#Ix#v8;XYbv5=8#t>+!b%%)}EOoQeECE=i@`2X}5wf|3n&I zw*xRwY&XU~g-+N0B?fGmc$ou#UrlXqypf{G^_rxElcLP{_B5t`qi>7Rpfc`C;2*ed zaUFr{T#|@K9}>fYrX}c$pPPW6Qu{*-fqM17GE?+sQyx#^Ao>Uj#C2TERId?>4YK5X z1Cxur+mDbnLCDq4-kTR;2R-pLL%Q5~g60T#-+EK1(W;*hPIt?AeJ8=Yp*|*uINl+o zfd9Oo(^5q0p4rI=DIo9bmQc1sN6nIyuz{-J02_XZ)MWYwOI-S`GVMB)!de!aIcHX_ z#VG^CBEjc?A1GlE(g@MelM-m!vc1k2DzoW$BC@H^K&6FRbZGCrfzGrh{A)*=bh(m{LKL0UOLOG6aWU6TE8l@F@ z|Jm!-sE;K{hCVk;FNF5pvgf}hLfkf!2d}P5HRkkfa&@`i66~I}lS8yd(#9(|P$>Gu zYWhoF)Do+_`zW8mQL?=Tiu}XHx{Inm3+AzrP-`|p^fV+~gF)SVx*+A)>S1-WqQ=1W z#nRZgN!LYj?1U4a_GgtO3m$Lp@}!ek)%RzHV*1NO`$zbf2s6%sv83MqA7Lq> z3w@0WP_6Pcg}ktpc7`JMu~8x#y1}l>_N)j<-A# zqXQ?XJI7UEO1yv622LGjh$;Dg`SVyZTo89mbY0hhDX!;}1ZQhxbO?#c7C{Q7)P zEPJNAfNwU$)f~zyt0zSsZ%-VOTD-LvCR?+E*3tobtn)Ktwa}HI5xsYJfgCG3(tjrV zQMDU^WJ)s=oqJI=@-;ZO(y`ffI5}cq*q<4_118!`smFC98d3zz4%mYWCVxp;@shdt+4 z+MhK#?qCjU{`w-j<0=+)5u0(Z=Jy6IMPw&m)!GUN4RjEBcwp(c${QUl`Y)QoQ|36> znc(4+6Hm0JCmLBqK_0`+$%CWBl=s{C$R+n2O<9D)jHW3AKreB}`L|r9p@w6aPHubP zmt6MWDFh+G1(xid`1g@tnXG9HN{9!uUGJkLMP?8dl6+~Q|Lg_mjak>Zdj*^O+L4;f zlaR@iVB)M-&#*O=>Q!YYfO4q+v&GbUKE{OHXsASP+a-8E#Km2Z6%q3n&r>}2=`Q}S zm_My1&4+F`k_H&MKt_ovIzXCqc z0T$LA^njl_(IQ*Omj$Wd6DGFLhzl=3H2e^n!Pw09zxqfhUwi+h8H`I4vr?jcY9_yh zd;0NYc-V3)y(_My|F=VD8nIW-J|57n@K>qckCe9N{s_p0xKLnr_$Tix9J7^}(apK4 z?aZZDvp!0@d6&^7P;^!lu!LFARp=qWz0RxQuRPS$Uxl1) zJS51nD{}Q(7QIK1EuQTyD7@nThp zcq)XSgN6<8Cdm85T6|$(mi~I&xa(cVME3V^S9UBzTMsVIsvj$4*pBVn`c^6r z*W;wC>On3lL#F=gl*DGE{R^nhO(ANY$aiP2xona;OfiG!uB18qIZ3J`rV8{s3j6}4 zNd;5f%ffm`)uqh5Pz`P!IFm2bVga3(gg|D|?0<=+yzwCNz%&+TyFDC*y}H|%I&gQ# z&{m?RY1Qp7weA0H(3!??EdycOU3`{?SSGhv{BLP%SW<_859|9!yo-E0+yY(^!XDC( zd8Gq`6zD2wEXS<1kz5@toLib8@!W(lZd|{7#)!c_(;1%RV9j&tG{U`Mk0txp9c}$*Z-rfrTuKL&dqIyS+q60oNaO;99j`! z7J1om=;j$>{ANZ4Ke!QL5h=2EG(iFMh(g#&`**F1PvAkz**52;;y*M+UL1(6X&oT3 zd?kQnylGR8TSd{V6*Jzr;=U@FNexZpQo%i47v2BvxdUjfx*jUq63FYA3T=&G-tb*D z*YtiUvXKQ(y!~UU2{T{0R0e}}fW>aQc!YD2;Zv<2N34#}dBBGi`_nGpo4v@Dk~h zUk^`woJj-&!gFbOy=$K_aeNh;q?u$A4ghth7$AuaC{D2ib;=@!)6sK`K#?hRs5S1y zvcI+RA=<|hG-R^ftQ3_8&lp!e;qJSTc-Gkq0fx5GSTN|Z-0;rBHs&IC&%j0gL%U1j z9R1%fa~6r3f?bJj1^84L*h@KcD$L0-%=Q?E_-uf;^uwbTNz{y;{=@GItVh<*S+MgI zwJ!+=zOB|x3UqxfVGRteC%rzZc)*C!VG|=a)uh>!%4>NLfbu8nQPR>tvvV2sq97Ub zCv@>fM1?c(lW($4(cQV4`K=N+IHQQ8uz_)CXHUY`i`kcu?y{N|SpkOnXRsw)cPqcJ zv9tpBUEnj_-((9h&v`X5>|0VZ+pgw*(mtZhHB9HhlP6xoAlYN-H_b;@$}5 zUuy8U)tgc&fsmdoHiS_q;>F+ZCBh5S9#_r|n5Xd|KfA|J&(}g8qw~ih;g2t* zBsbEw{n;m1JzrdfWB3@U`1kjp(gOFFsBM<=$?H#BC-v>_5Rx{;$s-4!(6=-uYo`fF9?77uTIoe zVwIPIW<%=%Qf(orF)uJaY!$e&-UNSY82xvi;(5EEF`zC$_uR2YT_wMt@!F2psSHik zCjv((TC!DVm>;tLaCh2}dDQ`Z_<3LDwpp~n*ji-mr||NJJU*8hZc$1RVonu$5Zzc^ zyA3Z!6&(@`s-?ErBbxL4%ckhGRT{(6`;H!$FblA`iCW97&mE(}Rx0fv$6w13VRT+K z`%*+Rdd9(`WzT9U9W6k7+(oNv<&OvFH6RM!ij5aV!`Fj9F4Sb1BL?+C-Lu0XYyv%4 zCs20pvZEHE#XzX!O9ONK)-NC%?Yhu@;89*GH3#Dg2QN`yeXPLJt4&)|DDL z&>fu}A=V9y=TBmK-l4p~y+tz;E?t_mS?yTlaxb}&t}B$wHGa`U=G+&t8j^sqfx6Ss zbp3f*>4|)%?p-epe$nm7P0rh~TEP+#5jq%AxIZ+OyU)j3BOq+Hn|=#LnuxE7^|g1E z7eTZVaFrjp;C8Lhmf67#3GXso;w1-h6t!RhJ#zLt8t! z=dmg-H_Etikc%Ga^N@Z`Hf(nGr|s=6vTEvLA^)&F@K&^Jm9FkI-O7XbkqXj_*N0N8 zBhy`;>~>ZRlrS-}grv!;t|Q64nw%K;{>rtA5#d0L!spUV7ahoZn`&ld-dVA=qvoWw zF`B`AGJG{$A=Uh_ICKP7^Q!#o_EUs(_Vm#}6a?#Y7W`v+KI@{97*AZ@g!jw^a`yKJse!l)2~d-YhD%QaiO+6sC$@sk2b~&k@YUdJ+3l)f9?*dG`|CrR$-5d zYqQ>wct?989@TDeEZSUBu~4aNN8O7ay{|)8(LR=BN?0Lho>BIz-DvyM}Z(bYG zl1rS5cs&esj5vS>f=MfcZi+o_rHBX+RZn%HU%cvS&m~x|xG!0c^OmcT`6ShEEr-nd zTt=!MR}eTupXht%5h|ezcjO~6gm;K_EwLP*g>tAbwua(?R*F@e4qq`|9qE%(eC3HJ z8BIeM{zH_Wop!h4rTuLii?X)@YH(O#r=e~NKl!VGpY0`ZPMEf1T@q6#D=TA}iMa8=@7H)7&gkI4GE;EWn^wMEE)V>w;iZJ_qipz#JYlpSlpP z+!To2rv2|(SEzw}b$g^Mw0lsjxQ zU0VC_#zGdoVD6KVDmE;O)w2Y?n4nPssr!_z`4lS^ne46mKKLaG*-xyVU)=!S7q~@A z^SB?+QXVML<$dQamsdk58pdqisicv}9*%rOOp6TlfP|ow)0b6tJl))b_Z_}dMso6< zmP^Y61#740Q#M_9j6OF6HsgeIN3#HFVV&Sycfzj|L@^jI-#L!N2=L{G{=jCqUW+#p zfv*hNo{}2tj~m5#rv{Ze>mmamTdc-A-A#SmHYi)0be-sDsx-7D2#E9O5sJ)K9(gtn z^QF1Iqa^gyXdd38;ou8R9$D8&CwCji5DH@|J=Wu#iSIHbh9aJJzb!J~XZw#GM$sgA zdXp#}-lk4l;w+%zbq{+NQn9~Nmo>`bRdz(vK-~%5`IKcGEunMs8ur2R43T{Kq-9PL zHl-_avUONR)-6*+nE(Dfh~_1uSIT8J@>t6c6iA|<7yQ6(BsO5odzV6ZQiF>%Ymco;~q*oYB@FywX{SK52(G zw^3sg9y!_2$0?Mtu8w4SH6407w&2kr+Jt0@xOA^GFp7|?TB~Pf-+QRy1r4SfPn+kD z`_`x1oTbb(1sIp<6z^WcgTfJLzWk%J8+X*YBP)<(D8o*iNV6t_oOsN;N?{P%3OyYq zE&|;-W5~t}vzy*1BEsx2c@6c?2yw&4V~?jAuzXHv zx4ZOL=YslHjKeltk4!&6KAW}ri(@gCSx!`x?x`3`#DC)KH+UFK zhVi-X7Y)diGg}1IxQ?>r&A4D0t6h84lwzG^FI+A-N(+01`aOPy1wf^Sj=jy|9SR-a zwD#4$CJk z7hV!xX1w<$3vZXFo;5xX$&1Uw+RbN*r*>F-cD94#n<$rC`S;_(OEP-R6iG+U{aXO> z9;Oa(q-?Q}SDo+lC}nBU`sLGwjWukT{}za^6gmD`YwLJ9ZeR$K7h zS4wobe_%3+aL8239-)u*As;!VmFf7WIRy`qhrP~hw^*Oy3k%+bu!+0m$E;|%NaoX{ zP1Q4ZD!=wVBJFk((%F}2}Dne!0vMOzan-4LcC4t&A$S;?`n*K{>qSF~(a? zM;5ZOmL8IdkebO@OS7Ym%zQrL1Ose$v$%%zD0VFRO=ep|Pm5B)`A(EvG5yAfFX;s+ zHM-UPuvRXiU$a4grzAuT)>Pw-8%YgfHGPX6ul7*Xz5SeM5leQwYL>Meq8$zL{T?M6 z)VDmmAPCe+EBpwXatSa-VrPqh$?>zV&(^N=3CWvPNQk+y61e|Xnwe^r{Z%2fqIBpJ zkLbMNbDjOybuD{Denhth1$?SuTLvqvE3@%`VPp5x`V|F4K~%4724%@XH1D54O8syI zRJ!HK0lpbv-xU)7YfKc>?s|~eD8A?h=v}C#1Id`N`P`AXj=OzBQqiAYBRqJKx}Q^# zjIupm>N!f*ILKLQ1s#J9i9UJ{dt}@`TWLKbvyC76HC_`lKKPM=DW_{xY$uK=7}(7* z5^6J8YZQ$9F2geB)ByQUH&fcmIZ{p7HWyr`M74OK&~lrLczE5dw8R=5qr;Hqz(48< zTsD~{EXx$%B*}teNhaG~P#J?sos+fMy>_5-_Mq=9D?War(*72P-if!jaw1EuO1FHfel0xR!(KTILI~kC@ zm>63-$6{YI{^9VghoPP>tL!&3Pbvo<$8 zzG^61_CUG*U*$7Zgpt#JnBB7JyDgrx_dU&nhBd!;ar6Y0e^q$b^L|%&t(KU7EVPyz zPPUsksDRGLmcy+0nd^+t&I`#SY$aj(<&_5bNB5 z`Ax^>=R{|sQ=FV^S_F>PgMO4L2h0d4NZ78MOi9cD2}ZwSyS}%*eXXyR>g%(~BdtXp zfZCRHgr;M4%h!L>^(?xiGidJsFf-GoT{7@$N>s0&dFuokM5z-vS!JLj=WtQR*S#3N ze5Ye1=#nzk=+&0mwd${mIOY!^V&O{W6b`NVJ_V`3t)wphrzC3gze%DN{&yrwDjU+2 zjCWeNUmv1oZ`6q>E{GQF|2S{?SMHSG=Bailv6S7AscaCil3(9Mb3!dInueryrTu#Z zl%2j(-4(gzv;1~J-2J^sp6K2Nv(3cd$y=o~nSodJS+2OZ{aH6#S&yo5L=)~hI7I4N z+F|xx(J)8E%sZjW=Yer_`|Q`>&r6GK9&Dzsm}^+;&|9L~4c@12FFv0DNu9QUOa9oF zTnU7DFBb-wIm$Vf)DjitsSSBgGicaPw{KJm#0iP+th|reF6q@(AYs46@1C;!Oj(nn z-kJY?r&8d8d0ssH)X%FWvKn(ffjZ2nBZ25O_KV4AsLe{$*AfA6&NGIm_DMtEza8?p zG(KahXIQ;I=Q$Q(Av@outAoRwuQNlo zy7Ce&=UpkIaQX`4X1wulCapJ@bbSuq9ZQZXTAb(4V=q~l(Lq&9p$yT3;pGmdsD5b) zoyKKiI!mbcp*Z&bWGheVSQ8Tyi%xA z0^}|wN)T20VC^BFGBDSNTFZPhzT8UCyuzA+iuTVuEx5xE664x4O63p{d{%3|wgmKO zdpiaG2g+I-dG%m4=*iwM3ftZvPAbn`_eBu_El)c$?L?)4Wft+Ivfo`Q_vCQBRw`iWJW#m1ciPGSJ&*inLH?FP)s`jmKm8>`ptU@_q+> zZmSvq=16mg#BnB}HpU6b$ILa;$WmAQ;g5Qh)Gd?)tM(|8ewrL^R#`Ss2;ph7DuU*} z*d947SeJ}=>-SPNf}C%8Sn*rUE4}>|R~7ub-rfeLu85Op5oC5u-q_t;*z#^+%KAg``ryGO zn@4-Lu0~RKP?>rqJTL~Upm`~7_&`IS>ZrX5-*e?j=_Lyp`+evg)slPPlqkN{8-1Z-3Fp9^ZzAKqNV?@0;R(LFM$%h53$91HA8o(rcQ1sd+TD@FmjBOW&wq8t~g zrnN^27N8QAyv0qnyF#*Heobh(;x(8FIfTZ|xA30L7|Ns=aQRQ3pTucu*O-p9l@^^S zz#;~<&aQBf=?MZMCv2DwuxtS?riA8L%JBW$@4{tEBja*K@s?O_khrIfj*}_v2`)@D zyX(11MSoP=3F2l7+;#GEHB(8%tw%6*Qg_ryG~;1h3$X$7pjX?2OQa7`B!qD%Lv0u= zM3JmDCQ~cRpFA#f1e%@W$qc;b5-e?dkLM)W`#e`&n_Ifse!&V*#g`D_-eeALJ5hWs zQV7`)f-R9-hC0mQo!aEcX6Q+IUOG5NxF}7{F@Jk=KJwn{@nD=qG10>d;fC$8P#I|A ze?&@N7FH4~lJO@$kJyV_AJl4d@2$dh{{RcVj9U*{z_90f`Htu6@>LJT8G4ZmBmc&d z+R~6N25z?nJWz>c0gg8|ue2?mdFKK0bbL@Bf_d9~0%J3O7+?g(lN6||qENo}|54I2 z%be4~&83WsfJq2>rjP9a?|B=yd;Y1)Vw>A5C)?4g6ZnuUsK!Xe=|=eG*=1No<=qab zT#x!-!1m)mdjV>Z|6V%%K{fasFwObFRnDN~%F1@>zQ`MUHaJ)J{B-B>%Z$tKk2wUd ziN{~P@bO>G?ZA?O`G_X6-nt|OYL;VfM!vnIAQieWFmhy||2R;tFcc-{`QYB;%GD&L zsL&%RtJO$e_pxe2g}IwYwd8W+Rs80+aM=n4Z$t!Knl#Z&TMu4f7~3dX>D$^618YzF z>RH10PkLA6fPDnj0sN*qtx}^KzbbJxT|6-M0h@X^m^zPb{8I#5(}5wapP;_C2EA;5 zEO0+?f3u~Fts(5e3iZ@kD^S70KuHFoXQ~upp+Ye8#vQxkDX4?5hJxdR({ZE1{Jit~ zN*O{9jjUGbmXI4n@|)MkzhIX+nQoLD4saY%)I;#CKW^$95nY)PfL+PS>}iaab=sUZ z8z#;GFqJDe^E^%I?-%xu4Wh#iJMV)sZ=l*NGs40q&pGjr0snW>C-TyMo~Dj(v(gIu zF!>RY*%mx}tn!kKnKSPKHHAIdK_l>}=y0?8UE`uaOrlDoaVgZLQK31eDevM3#HFh& zrYrMJn2PO4zC?}dfA}`$d2c+168h1id~o?`;xiuc0b2aVHJ%OLQurZ0b61hKQw>Q^ z_<>=;-@3|5!E#CMd%>hhoL5~+!|V%sb16i%n_{J8Gj;#s;r@D2(JNE>`9*p+y8)B= zv7R2G^P^TS)42q_V#iX2werGUhwY*bD5sNTX{$A(2JoWQ8^IG=mGdp+ces4WJCUjj z8*}RFs`JFciAT%tnP9cVELSoJ_@eO-_>#w?>cD2CR)G3c2ZOg-I5k;sQRj()?cn*x z9qnqaEtTvAPo@Sw=FWx6h_1p_tnfke5xS1c5qTjZ;k60Fe+5l6X3`Xvlwmnh9MKXJ zQUw3Wi-y<<+VPJ1lhu4J9@lrN3xiKS2eAL0MA2_pzZ<*;rKNWiCUQ9I)d3uV#lH$Q zD91m{5?5(+_KM9BBwBbv-|(&X9*N5ZIR>09E_v}B()#8pmfk~SLeFm^cl{(jKrX70 zU*#4%@!*83EWd-7=;3qeBbXcurNj1K2hZ8?iKP?*#2rpqLO1vkTL}bcLIhLJ)~_jw zclH))<0mzS8!n@0V8Y=~DK~VRl`n>CbxE0XU3Q129q?!4ys6Z~Hm~c~Q`Y#s4j0#( zjw${aQ@R5~)rlvb2gw$OmlIo87Um<*QS{W0V0-~^gSL1ft%ue5>j#RZ7n=W4Yfnar zFRsW14O_dGtRZBC(q)8+&WCs}&cfae9TLsILYiwe!d~gAUtaNVhJ+gg!V=C0?00J5 zrfE0us6r@mUbvj@F|vvW4@ig+*CqdMDmYsU{r?ib?Q(vg#az z+vl3kTo!xoU^))jBKDuuD(ROro-+p5Y&s5dY7YE)<;9X9^xwaIgi1l73qk@%IY$rG9cE)Zf*x+H#2B@nx)$cP=I$|*0(zH<>& zoOI`^H=C+%{oEN%E*z}$*wuPFsS(ZWQ@qzjn|H!Qu&`CTuEUC`9O1nGOo`ud9d?vE zWq|FWPsipQQFCHhu|K-m1AkW-_v!KqI#6Ss2~u!uG3 zN~fRyZSRQdin*R@o_AiY2mzB9CCcn=90SoHfBb)$gMHjmGRA+R9m9;;1j6B78Vj2- z^ohmAj!bU$i@?207WKz2VEl$o)S1I?movJt{}QF#fq9EVQlqU~=Rwer#aiX%Qr?is zNmtSK1RIthj0ZmJGX$FHQpwN`phr~v$pq_H(;QIuX2V=;J6^uJ=v9v%90#);)p1&G z({Jq2b}}5KbjM2HZI9{FTy6{bXkNdCWses2Ms#J8Im~_9c$#LcruONXAIJ$E(|%XJ zD8tF5JH5vyzy{Ih_@?M1H}kJ)^TxO5M-*NjZQ`QTCfbhdH&nkOAnlx?L|QTTJ7XkCDQ}nBga|a1tg#4jHb9h`2`vW>f(9ieA4FO z->VM+xNox}2qTh3(}iW4Rum$@g=OB>8T8G*EY1lCLeiA zWg5>3vMm31N!UB}M{VtkZTDmy%Rb*`XHqIInO>X;2b>2YS6FeDx5gfz#O`)mdXa6~wgSeBrJ+r`s$WGJeSEmxmbMOf#FD&p@cmCBM2kLsWth+0R zvxFl*@(ev8_$9&v#qxTUc6jkpXXz$XA#4q>In(ret z;Z?4JeutzwKXI%ZjQ7_61Z_pyF1GX#HcU1k$>fW?iu3C>%!{U#$+jLpE0LHyt`TYy zs*NjuS*xjD%`f^_>;|ob!@p?kHy6Gy*+@lA>%az{gimYpA}YuEK_y8AMn(*uo;VYu z0T}9%c6hv4ZJn~NM}6`$KQl$vdY8Q;Hy0dyzz~hfrD~xDnD1HxFm3{Ki+MAI*tP$! zLAKSx|8vMTfE~k`6jq=-Af&N39`MIVwTOr}hal=Jt>b4uK_K>(E%i^`@@!uhIhEL-n5K;#d36#tg3IOZn zjX>7&HGk10V>Lc&a57v~7U3Eh*CpnZvrbToH-SI-vG*B+%KrnxmWke#DU*f<(*TDL zo^l2$6KVfva2%0yG)T{0u2ND%jfiP<$6~|OFs#{QHEtdw?dWa+P#L9 zupQXcu1Kze;BUd1D=umv|y8z$M^!hWg`zoHiwmk4kLcnR9)r^JvlZUkKdot-ErNj_JQJt&I!$ce+*}mT3qm0qbT|Y$%!F8OD+_cfn=DT3lt>D2idrnW?@YQZ|A5^Sa@w;;n z8|5s`prNLxTj#$9?zFRKP{VEdf827?wWsT6hL!X^nhl~@E)Q~w{Y)1PO=`lAOn`35mFh&Ay0uiH}*s@v<-F^`kJlFaW*hg)no-wUV8X<+G zr4r^0>lk}7P@$X{sd6Y)^oDTmQC`K`j>4GS6=Pj zQiC#Ek8ZUJ__Tm~Ht}G=6Ab>OHx{}JLfu6N`fHw-qBRz=j9xyMfxl-!{1=zS)OoWq zFF)J*@+6R#aC)|2x~ZcjZQ$-#H(y(miQMhnf4F{cFlY{(?v z8;rY9-rj;ehRhGSt=}+UO0C}4f+Kn*2ql7niP0ai3V7ZBWPZ5NT!LYVVbjeGxI5^c z#LWkuyF$c~uwbkp6)GKQt2l@<{bjTxgVYQK4$7n8jN6Vqjhw7z- zQ$aXn1XS}>i0X{V^D8x8B6E)sy7wU*eBWMVN9n*g=nL(8vF1}1e9Y&GQwup1p^d1r zyl3r!d+rVh$1U_<+u^BuOVz1Mo|CjLQ{b6K{-_cg%Hjq2xDa1{r#cen*ETYJYjsy! zMq9Xy2@~2Aa(-2uL|*b6D#?vM(41za__W{8*RViuca1i7h=PVqP7n8~w&8_DY=ktTWg;`XQhEf1zE2PW^YZYdQC8ie#fQvyWa7Yov8> z201u8g1)aE9r|?sG%UF~XfuC#FdO(fSNL>E=zLn;dL3#z|HCPlU1MK$!%G_i8`|9$ z)X5ZO<36g92iELpgjxChwHgoD{d6guBAro;Iv8kZJroSvMXbb2PN{`cp1<8amNT4t zd!0Fd<{682noOV~wEC9_fQaaQi*fygX+Tszcm4OH|99C?&>LSLMO{T@C{G*?U!>(} z6XwIF(HfTe6&sMa{kxC)g>W5sk~z&E$(gXzUcVv61%BWC(BkxMA$)2E$X`1(+{|gs zp7D09knpM5@Wu!g;7w#*LWEBt*RuV(=9hmF!sTp=i~4IYewdCr4<0B?sJC*w-Mr#% zoE#`&=9)k6v9^e62;AoBCNoYxNKh^6n@U=hB{lbei+WvO5E9AIi=n^<*SE|ub}z#C zY8}Vq4ldTo!#YCk>mY2&tj4*zma1dk_}Vdb6^;swgh=SCNl~+G_t(;kj_XcwELyT& zX|EfH?>XDJxOrzjRHd5ro`TGbjcR7hnBEl;d3t;Dm1@uWqmT^D1BdZh^_14ileDW% z%_YFUpZ1?)Qz1r|0fCLQ%T;0NBd-m|w(Y#!JBEP93r=Q}j%!6_VjD1EAur3S9>ga* z#gV~+x;G>k(PWQ5W8Ic1aua8T5Ye@a4>wu$8mEQrYAEqAgRP?n>V9-*HgR|y0QMGn zLsphKV!6_7v!I-U<@*nj>8C8muxC$UQzP>HYP{()jj75tEykUBe*J6oY(1C4zO{t3Vl8bL$#VlJ)N{?JF@I09mW}2>|tNg?df%G z>9{Bkc1_&jxY1tN+Be-l=pabjvVNxLf`Z=4=l`q3{v^IloPo*Ai7dNT<>S_3qVe7h z9Lc%ajLuKed22HLHKGgYm*y8b#4%DaNqtJON}1U*Zoo8~NEk@WQDPK1Vu>h6)|D*= ztFxWgY%<*d&BxG~`j%Uhq4dy@Jay+oNc0I*I)@)A>)+IJTHpCX}a7k=jva19OIvFZa#5t&=r_$cYbef=3Q82Kk(DYMJ;jvt&~Fu z=89n)Y0nuBOct()n=ARA-VHfKSIVK{`*5xj)=pj3glq)8La<28`K9#YlAs!chJmBT z&w3*py_nLquk+2@Y7^G>3|<8{5Vyb)GPgaR0-#o}*4mK>y~Et24Mbp`x=sEiCvkaK zgSOogA<1smx_Pa4Oiy_b1-^4fdi$#6_03=xfqKhH1s~ANve)!C=1h_*JSRs4=EWMe zT>K7zYKZJIyz9*j6!26FuroqD@l;EtM^wIdPACt&B>zzmQefsmhSYZDTlK)5Vt5Cb zEN<(GsxzYd0n_t~s59+c5P#17*XjbhRkc2hl++JbP!!`Ak%wEi=5aPZ6zG85eAr8k zr;lzNoeVOnS?m`I^0_Pks&)5c$y)gmOP-B}ss>wXElo|cr@tZQirN&LPm0!M@vrfU z3y@CAsf{z-vFaa4vp)ar-z9cTR5X9D`2^4cs5YMIjyIv)n<#msCm zrzsR^{-`j^30msV{#8XoRwmw&3u3yt0TpSP^7lu1{h?A<;l}y0V_%yv4h$kfu6L<& zNCf>|;1+g?k;APi)YTlRpCA`8KdQ+D1%pePsM%Z(L=Gyw6>O3ct{W*0G4?ZI=BrC6 z^>sE(p3!n*p$*_yO9~a<OaU1h5H!|~iwF>3|>1!*B7<;kiuWj1317x{>>+{sx zV)T`cJ`o95R2SO~SzTuVM- zqmp;3atp&Ej4oH{2MXBuGRwQ*hxP3b)<$9HQ3MM;(DGnC2x@znWqLr-!|e!Erk+ks%RYv6vvV-b0j5GF&_lgJJ&F9$jyg7 zJsK~*;fwh-Lj0<9PV!jm{d?rmi0Ad*)W!A04~p87-&W1-M8Bs8@K$r~H{mG8fdW(# zx5kbs94Ay8Zbs*Uwev2` zie_pia3Hffm#$@|JDep&mg?G;Aq85S67*}qQkzeLv%cbd9)Pjw zTO}K^)Rooa71sp0wgP~Is1I_lk0v4pt+!w48fZ-qS@sG1B1yyg`9#(3Y?Olcpm<-h z5t=QI%Qm%ZbYlNu%P?kpw)ioyj|T4i1W7o3cosIX-&-0}X~t!ryEGD6!R-J)^L>V7 zwVt20IX4TuLLxLaSF5UYYitpwxI;<6&W62kq8XpJ;w}wH`xM@VTMixujQKa`rV~wm z1;)eFyv#}9QAXpXgN`e=Hak_`0Et;NY-JrvbnkcQsde+Iczpe8xqr>JpiJ+W6pL2) zmetn>ABM{|PAn#xMB^2fcPE$M)@+OO=c_5B@9i)ANw=!%DoIiFvU@6(wq!ngqh&Y> zsaZr!xXnuIpR+lM(m2kJwHCc-)41N$bo?I!bcHj1Ec)X>6Wun-f`+qKc7vu-Q z+?fPWn9b7F-6wqbV{^i;u5f?G4nIsAN`>-QffN`w7#j<_77MY5t5vfwDhFGU?2vPp zHo}grF?zZlmKE0|5J2Jv)NoY&C>K#!i8g9X1b!A(C#E845Q8-0l~5 z-kQ~qo)FaKnIjU{*^3|h#4#$r-ZwuFF*rF@;7*fnfHP*;@!tUU{OKG?bixOlmLzC- zUuo41+fDDG)P40=JhFyiHuic8fR>7=I8 z$S9*UzZS1G4FkiCsr7ppDQT}q@1fq@VAd*h5zrOb*=emumED{wTR?^?_u`JLMo#Tq zYn%XM_n`ZB<*?n9nt4N^i@th2HJukzJh0}=dRWNyY)|*dMaMNXD1{%C@|58+{@Maf zjnj^i;jBP8yg>IUZ3;lIRub5Zn_~RXaXEiTsfN~8TVNzu&AsSeN-%Cvh&X9O^?-;m z)J{JmI-SD3y{uxXi>C(D4M*`8Qfnoxwm%3vZK|Z-9G!`9%L2{sGbx>32SP8=>Rroe zTjD&u$x_DH=inf~Y1f0AtLWeN9$6RTG2Ex;UxfrNud?O7d-?->cwr_{zE9Tf?`Ty9 zu7gZxMbcVpz8WBe2l2f<$05poDa|y+^`zE|@6DDfhx)Be9Dhw-@*Y`sC*$2S{+x;| zjS%k1$g5yX#+Ejn{e(evja@opWo%GU^EtZcPSPXjQ~YhQR4*Xx>~JQzhybCb7HuxB zR+1oII3xT3yM?Ck#s}goMl)vzj0>?RJxJh=2F2qck46g=d*=ZBSt13nrU6AOp+_^m z7HH)4$E&N~Zg1Yg(E9@knu<2VR0@P~8Fp0c6$uUg+|nPJK2Nzn5EZgK6;Ls2{^>U} zt9fKy>GdQrN-k{seoBrSy}bOmJ7O+@7El(d-0WyQE;kcRh*h$t&GAZI)HUS_aR}1m zTXEz(k0_(rEtjLD?ZlFsv}>1W> zJA`ec_+cViYbYuGVA||Db|E3K@J{IP^M1;eA|ZTgR?5~v{$%Ww`9eGY=VFC$%nFGZ zCX6@yzVSP{5TL6k@SnW^i(0qiIPZ+Lq|u1-l|jtP6Z!h9R$kLxPAc*?e~K!V)I9j$ zW^E&T?4p(q0;1Hl1j9+g4cVTWoZeK{mu50vXgU7e$de%yR_T?6zIM-tP12ip>np8~ z%d)bKyJaR%$(F4v-e8~5P&V_n18b0dN}X00>7tcSS{CS6Ehi2;CMkQrA?`#mUr^>7 z5xgSmndzjtKP7-7-$P<>NC?y&E6cqL)LX97yNl|+?wh|J^+k4O7(Ov|{G+z>$NKhz zPbH{~13playR9DFR^}TZF@8G}j3e-e2Keurk2f9i)EvPyKX&=3;!JDG7Odb6X6Y;1 zj$B1Uw%8(5nt3>92|Q^ZXP-$kO+K;oglqP^KK#-U47cQ7*FPW}udsr@#ii*NC9}#K zNCAWq9R40S`3YaQdCVBO#it4m;;teatMMJs?@BG+U5@=RtOQ2B>DRw!5ND{{<+DgK zONJHtUS?dyQa7vOv~<9tooY55lCg|iguAW9t?m|gB}_}+XwGkD|@e1 zHjxjP4$Wts0%nV|BSq-H7%)4NiW}E-lhzHTb5F-KpinL+>(U1McN#SgATRuB+}4SF zi*rk1x0l{!cFI=L_S}}|L3lg~LQ8}iw!(Ht;6?r-XkOm+N0#U}$?HsP=AlAgH6%0+guo5*P~vNsK4t|MVY$zr)JuNZbj_!2 zDpB>G576+@Q~(n*;sBHKnC2-q$0$% zid)aju5{l{K0c<-zUgqisop$EMO+5%e_V!Q0oBzzUA2(Rf~7~)Ek0;XBoJ9I?Q`*Y zZp5XS%5&KLQA?uHUHuDIf4R~0{kvBC#MXsV>ANq#%+C9H%z<}*s$46@;SY1Z64U`LAD6c)%PkCe=_Dsf?y}mrToCJ`_|*# zU^m<(x4t5suf*=tA_TNGVQYVUi-Z*7)OYy);CfBm&RYEfAYPpBv%Un!IgRg5m1y`R zD7p@_|KwqbgJ~u>R6zG>Fc2!~Dk_P|~{%US_KUm^}}sX)sD(w}L!!4(kXDUbZOP zPW4n_@Hn%TznC%YYB(htNs=F^uwmuQQc2T^crGACbGL==wjsriycXfGtiz%+k2j+^ zjkR?mMS{b?g6{oZXxT*7;7T!lMpH4^Jxm3u z=Da>-O#9m;IjcW$h(@LHLpMiBX~1;c1apTju!Q=;Qr_mYTi$vxa6E>2W3f`>D(kFE zor7TM{v|+w;Nxxd|KRQ|!>VfAb$=BV6#*BnfN_m+-}m*q&hwN{tR$IKR3bWLcG zJSbla+jjgq<0V6Cx#c?fEHG?eQq8BcZls=uyA!ryRNmk0f(imAY01(^gtLjRC67OL zH-B%Rs9Ap{XiZ5*vfZ&CPu5-B5ijz`Ls}H6JM6ELy1b?)J4IE$oiW>N$)L3iVuI?6 zUh;854@4uY6L%8{q`ii#QET;&SHc>g46@0bKNpikj$2H;bT6JX?@G0$LW!$}bi%y7 z9|>r1kPi)hnCKSy$fVsj30~nToz*oTA)9km;+9SJ|1`Mxp|c#fn(-zKr1`@VtVL~+ z9k9?-wdTF?;#z!0d+LxREdi@L;7z!K3t;F<#@M_e7>K?nwnO=Fvu-PgoRGq730^#- z;A9wKXYkDAY-Yr`hx=-AEG>`Jk-Dq$; zWfdEt24@hDE=gs_4Ccq{B?COpRoa z!ETNH;S-W~vFjG0#v$*$y4M?RiU9W@5=&<@dA}xY1;BeMLbn$kfd8g!f9!ofkRD=iopoQXzZbl`hk4yvdM(g!GcTg`CMP=f zRonW#S5Hw_OxDpFE!WG?OaZ}??Le@XY7xrseLY3cZ98AV&Cf70a z6-OoP^-)ZRB^zKxCr4tPf=qc^lw9vrki`jn5Oq#`8OHAm&@e5tN! z$&zuGz>B&*yb&}~DEc-|$#!=pR(!Te+cd>HM)p3b|5#`@Iyo$)QYtwdH$S&i?j$mf z`N0E}pp6^9nr42>dQ@eL%F3e>LJ?I=ct%ahw388Cm|+0EVd2Mgm9?~)Z-P)Nh4BMA zh58^zpzW_}vt>Bf(qNM9f2ndTMs?ZGpu<53r=`IFq+1XCXUH)QT9 zU)sz`ULAKCI50Jm2*j_7ct>enK(S@cH>|Qnw(%G4O>op<##h>df_Our5 z2+ZaF8^hKOWFM?qa!_Lm9GL>gqN6&^d@1tug^Cr&D9oCvbtLP;EV3=zhQX(-M0JSO zlH+6{loDRb5|2jE@y$7%?1H3Htx46B2Va0KZ7)2-xbTOTqQToX8 zDV?37lB#~~UMeQ>=-hx2+jh0UhEwW94BeIZkKhqbw<{74#82Vvqz{`ME3VgVMT*Kg zq3?MGP6;E?gS6AVT6_GqhRTrJbO|LkIKLLpMCD?O^nH}^_+iVHx}HCMP|n4IqjdWz zsk+RDx284{e}Odsk4Yz#!wl8@?u;UTU~Ofx0Pic+Ui5Gt*w7qg2e)qT1@dxY$t z?|boOlei^G@~|b`8nD7fY-vuPWCZ98gp;{t-Pa~C3Gs-!MPM~wk(vY>TcUd@FU!1* z7rY^iM1@uu+-Wrl%E28T}vOAg}82ZTokMpNf`k1gaSO# z$ku(Id#Omuc5_JjOPa!G>tkm6e6;#QBbGleK(%bO31qH!F^XmM9QH;-ZVF=C*L~7< zvOUcP$d+aY)$Ch8L???g>#xf^sz_g}WKiFy^XS0^w-f%OcBgQzfO6h9)eYDBU+o1I2m_ zRb)gOTZB6JB8{1Yha-M>#jeLl2$G?#gT0o;FVa9vdq29ZJNS+)B|7ez{ZK_F4Ad(Gw8b$XN&N+XmxnEX|G} zo@iR`KzSKYwk=A5mCzm+FIi~q6OX;hX{Gp7Gg}2 z1ufyY%jW3v>i|L|d#Bb@4L3hd5bn$L#sb}J`>}1d<6Bazjv<*(*-yWhhl&iB6UtT! zB=HmOl}V;b<6V5Rev~b=HjdZ)U5i~)Pj{G7!^Ao;%<4nmwfs>B?{yJ1GREP~4Qce# z)3*+1Nm-Hg_IM&4O+FrPYAoKGY4XTJv6hQDn$lXF18tYR2al(ZKNkP|svUe0(A-aS zj#%HAZ>AOaNK5Xj7R!IC+s#zRMpe7R)j4VyR&d)%66){m6I;)+#&#%SS5w+S&_jI%A`dGbDTDO zdQXsJH4SFwS)|xD9wEI%tg~E3?OE)ie*<7M<<_!(Z@m?}oZQ>13 z2;;jJx?W6m;)`oCcxW%mP53TDqdWb3VyCgN91{VSvEdF1tH3t&OK39+X6WZWx zgx4ZB9`AS|XKSO%+V=G0(8z)62-Zpd z%kDP2I*zzry^kI;v~@*x^p-P2BQdRU37CVW)Y-=6*7J;ZI!$rJd#c|Lsj3>FTntJz z<@)a9aeT*S=^BH_lTBax{APycUM9vu2nvlQ2F6YBW*&sUgu?Vby%f;kQkJl!iC-m6 z>lF#$q|-*ib8UmZP>2Ub|>pBQM}7Z>fx`%Evf)UPgOf7YiES!7e?vxm9pwkVgRSGT+OciRjMV z%p8Rka%ThmmzZ1S?2SSuDG zb*o>5=daGR8fB^f-k18I96|zXTd8gJHmg3bM_EjnU=O-1Nm>c4=FpKosF?4cw39q` z%F@S7=hbi=>e(;+ke7FwdPbkEvAc0ycW>nF!Kopk8raAg_c_10z<}XF|LSfm?Nn## zIBU;r_@;eg=Tthdm4UDXChkPq{)?cf-bx`UaD8Vt_=kAC-e1bhBgCL<@4^&_| zHJSfJ3eCmrZc}XDT&f7 zZHOMImhWlkjADm5Cl}lGrW?Om!wu(jBhmR-xZlZY>V3ofkYyQhkw~acYV=Kp^PCC@MkO8;XkL9X3 zGTdT2rJ|iSY`szBvRWzVvFBF8;B~N+X&H8r;}QHm%%H}&Y4Y{qV-uT}Bf~z3>Ed*H zJ5$q_Gixdfy8f}}?d{M zUNYbjE>^^?XiikndN3<(EcSM_B)ht+zqy*uZqHAsEji%uFS&%wMN-jo+a)}f)_uo& z5nZt)k*l)yn12XJZK?aU`T7mL=hhg*OQo>AY&I6IeEaiGwL4xZeUKoM{BapQu!eo` z2)1+#`0oW^KQ>^*E$tlc<6P%MeZ3mCpBnrcltu0J#vwR#@LaXWJgKdtG}+; z-GDwQ;=4&n=K)cX&Gpiq1nX+Z^4&8j3;tCOKm&E9Ei|LflqiM&brUIY5 z>1Q`i#@@R}hjEukRZSlXLf$#=sEM)^SA}$D{GipTtYeEy9iy(f8Y^%&qY5ipvLcGF zbXRk(K3aDSeWAKRIV&b*iEsek43K41<*Qa|{1$ENl{j;mcCX3^AtkVF(HG%&R1qy$ zsk6)SFAVR}XwF`Frw-NDsp4!y=EbVfG(O?LwDO`(`$?tl1Y|qlYYSeO37YnxgS=IX z`xK#6dNpg4=Ifx*Jcg7Rhmms?;Xh{o73g9-nPw3@4JL?7NJl8ubi4z@LctA@)0XUc zXZJ_T3vg?=;_H`<^nOH4AAhW0l*tUPua+yzh*+;gJT%=Mw0dt4 zQDJ-Xy!c6QJ4y9W_C2!|PeWSsz-lIkiFiRXvd}ZxL9(ME)2jMw+YO?^T{*D0!6=K@ zq6=Z{6OL0Q&8b&BF~}q-ot_ic(~cuDDK>FJkz_})h8v}S}17%%z+t_8m|CzVB2!;DG|=B!Si;ndNG_?@9t#0rXA4) zYLPPWMQ<%Hpy3#S+R@Zi)0=`2T5Y`s0@mR1uOqn1W*%6j({s4Ja^^7vz*#^5T3Ln* zY6HfgfxVF_!MLEK?XJ}rDi&}qFt$`#nos&AriLYMEyKeM&e3%)TD_69hp7BfCn#1vBmN_9rfr__!f(LP?8=G>oYt?K%w&N}`$z_}Wc3cXbm-5SC_zRHM#A@i>Mrvh7H7r>72AY4W6Z*H0`K?R*K%-!wN0Cc8z3 zWh}A{vho(7J#n4>LPetItv?+Z&L;Noxh})6YqaPst}_~|F8QS?bd;&;Ep8s#W-D34 z+1Z0vhntU|%BA&$-?@^*Q=zvK&K@^Q?*cWnW$sWn`7PeuCUIn-U4BWI`}J$1^3qKk zc01*$IMKHbshY)OMNnF$3x5CgKKy2ElJKh#K7e-dJ)OtAJ$f{E^uP+H3JF`viK1cJ17!_ za1j)Ix<*^q-tXympR>@LDgtLQ^ziJ%sgMkfG`v3Q;m>i516MPgvL&kn7FO}|QEf9! zSzV0h8318An9)Y(mpkWpRp&$eH^*( zZ#rD@K&T*AqRq$DIJdQ)my|wK9>{;Or+^Q{UV;UUtTsRH<6m*5)h?01q+KPli|tEg(ceXl_q(Xg((zs8_rer7w3cd>_w{1;?Xj+u*M?$u z0s(PVbTsD%UE?<#b6-tQz3;x{Xjbw$@ z-E=IQ=IO0F{Mf}FtinF37%bIQqD4|Sd*C=b?5)ov6Lm6W*Wl(Z^Y@bexR)Cc6d3Ed z2$-q-EYf_4VFL4fGMUv~T-{yzM9tJmupI$`X(yJQ;_;Rwc1Yg~C?dZ47qZmcZY+jL zrM6*Iz60N`aDbDsIltw{hmo$Fi6>kq-#*L&-$v)PsTV|r}H@ORZr)$R;E)DfeCVi23@BaPRBT32qnIf>nWKFF-q?+ zyD#ZR7!LcE1SDhGUDSBjENG202lo>!uZ7>UZV%-xKG4`8+32g|ulg0|fX5MrNF2W5 zg1HdA3eG&F?{1qBzf!(<)GeZLTXog{%$n%i#9Lni5@NZoQj+q!Pf*VS+i=iHr>ShQ zkeMYm4%K4M_>5F%hE1-|=%QyAm1UZ7PZ*BN&=o$4mn>q4ih7JWPt3vFj4~QoZR%oK z+#)9U&zvRxu2L5o6{1;1NOjFl=v`s#1?Ogfd3Bsh{6LMC?Cr`@CU4uFXHU#!h2r$1_eZj6=&v%Ea1LmLW znP$y{d|G@|&&E0h&o~q{wW9e?8$uf=XqcUM2Uly5huhsEvYQ!~{m`9%thsd48mJ2c zsFS1ojv6{0kfet3H`Q3lnTLQbx*6gaoA?Bd-ti9ff8RJT9Su4>>SrdlxTJYXvF-&gs=9ifX z>{ae1#+!wdUoed)LX&ki`!{!H80a_dueBcFmxpqgG_*#n<3~M@gyZM=I`rsHXmSFc{W@ z&|qjuM!G++WVjTQK!FAa+g_hF2EtNAY(;| z7D}od7K`>N-5MA2M1a|DrVPU-i!Hxj$@3q*==^Pz)~r*@2g z?BkbgDSvW`KyBiR#yMNC${=$gma!_0S?a}dMm0&TK}W4uuKX^ZK6ZXpLz=F3x2%HG zCf5fms_rW&k*^=YB3E)r)>&4XoOC>YX(!@Nd>O~u7$HZOrcDiM!Y8Ro)U@ySM5-$a zzh3DrXgZ7)6a~v)w}@=IJ7Qc1Xa1+xK1GD-DPGG=&49!OgUm zH#mRX7vi-bG!wTYa!|C`5>C={hiffWZFsd7*pqLPt~%*|L_PNj!{H|Xq@FlYie&$s z1^C}hK)XiIX`rQ)wQY^I8k+XSv>r^}TIYoaQ1x#`ETa||1~SCU@M`taiZA9G-RD1n z|8iK$&jc2M=hit+{?!@ z&upn3bZwymv4KuxJqL1hJIq<9Y6@Hi^HfeZXOngzz2EFNcyc+CV+^K0n|;jZ_gnm( zM|qkq^edLEpZc3nr>k|Ng`t6(0Z1vOm&{eIxPkw)`@$t!!E;H(Q^Vl$6HqGA|0oqT z;-W*hl8G|ht5r3Gj|PVvk;{!>Zs3}|V-bW$g@S{{+e|+>pdewQ7CoCvyQj{u^iXsw z7-GT>yM3MJ!tQ%Pk>9mb(2M6>g0em2afnHr`le-C*V|yU0h%Ic zAHlX|c&=yVh=Shei~~7CS!=+^Zz2)VlF;ALw11Y)6&;0srhncW^<`qYm-LU48i$v* zs|MJs5*b0U<@FtJ%2@J8H6Akmon_t;*mSJI@m$R{lQ=DXnmK}2{f2Lv4pF?OV*~lj z1xzvW~k*E0qWL=Nf_ z8RNOAa!P<6hB0@Q1)6=6piwB4<{P37&T7#GssOS6j+po=>mKjyAbHYgYYY;?z> zlJ`kIMq2HeF3|gDJiSvp8R4n=<#<lw|icJrw208KTmSnQ(G(omEoKO-@#wG!24-WznxV06sVAOdvH-CZv0 zgKEhosOU%o`|odKKv6WJE4?5qTx=0{53O-j)!PzfoZnbQ1rzw7Au5R0av>2yED|3x z&^rL&m6C@yj4NqOI;+)2)#za)|8r22rUjon?qRN=BNv>O@GlwhZ^RY3&KtCfmD)M7BLt%_+h*d2L1#hGIPtFtgydA7)I zupnme=@>QOLKDkPXQ7n3v1V5|rW3%K{O@s4WK?dh!lpO?$Qd>B_bF3%g(*6>WAO;rB#zhRAuqWI- z(%tW2IIrp1W9n|BUC+c>$^HSR4IlR1M6AjXH?a6Iq7J9TsnZ^_M1izKbP)MLU3NC(=A{9MrLcJ&Czb6l15O z*FYCGI${a#5y;;0;LH;%T&wI6Ncs&N8?+wA&VYxElvb)8EF1%M^Oz`?@`4gr$>YZd zn?*(#(2stOk$x2S9MB78*`S0@DsC|?f!3LMb!S7agokq7?PWAsdkXP%^v!x=Cu`nO z9ZT!?B!VCTPB|iUscq5*1ze|iI&MSh9P(a2?~r)s>mA-ogo>NCC_@D2_xHu80!B|g z*6wjfav0;-#HY^2-!xrr;noFQGjrs?l_Ez@rt%vaPnrAEY`lfi@Njt5HMz=}obgq) zC%-{^L8T;r?ou7SI>1mf3Ka{6oEV_t$$JMAfU7+w7WRvQ^OlQZ^lMTS|XU1FSb3*MZb4TWOt!D z9pz_B+gAq-&NMpr$K`@7+Li?7XoYb5pE2Trp@XUp)g<`Z@V&NHZs;iwwnx-w_fJYx z-v}T`&u!@fjePMre8RK|Ln78plJeM|T4~kv#)B6Fg}n#}OFf`S6n5YWn?H^@us=!xy#___~9? z_}aLSnvE|lT;Hku`dRYvrgd>W!rlGkWM6lj_}#SR?|xb%4vDfINN*y3;?(VG9=kQl zwY1_QnQilZpB!DPm=oj16gUp-23Un=9Vd+CQ$etaNi!eFSh@{YdZM}G98ih_8I-%D zz6oa@*AP!ABo%&Sek~sux!vy^wIhLIn{AacHAs?tKGQi_{!|Om!3{$^({GE!GjnXq zz=f%DrJU9i{9Z=l*8BODO)Ez@e5ABNJd8q$qEnU((42`-xhY9IvF}heA^( zx2M;fL^+>l#cdFCNj!*7XTeFoEA5qc05fLx_to`&Pchc7Jgx%>DVLTmaL$}xZ9C0AC z9&z`&>hwDNWqk8zgBN>!km!Tuz_cY`mMJPeDaczpJO<_{B|FHFm!C?>Bc2ViL1G`F zYYYz=xn>b{c-t_*Q!PqCD^O6#9eBBWzxb}YnI+1!w`6^29kQ!d6J^OK_ru(KDxYKT z{YMPCARKG5Twi3Lbp(+q#;5cQJo^imz!mfx=2QzA5!8WL`@^-4d{$2dymhD7RS0QH zJ7>kCZT%zN22VSCzNOwvm?E_Lm3Mv1T`b!yMx$Rj*q-A0gD_~YR|j-~48{LEUY@1LY8sfDtgO=;?MX^2 zO=WPvtFjN-cY1L5_3_x(xnh2tvl^d^fXamOo{yb)DDkLH2ZmKY#n@j~*zq2#I_*|z zCld=D)AYMF_Y&QfkbgEHcWn{Cz5Il{ESMrJ^Tb;{yCVG!#b}qUUOxpD%JxL5>Tr6~ zA693tK+DK6T1n%!V&GI2_TllS%(nK)ii6MB!~5&zb>yym3M?V=+z?(9tP&*6xI!9F zz<;Cw`})#rzj>M@Jsf)^RX0BsKXVP{L!o_?6&75;R)Ld^Y^R0bJ^~t;L8M53oWwigrlS;&6uLoJh$$Y_dOiSC?IRYaUH5r`5X8ZA zc;6gz#uMYoezKC&5S6Bd{3MZ!dEcv@35L=%2=e%EM<=;zhYoqfHNCQ8^XqPHB=tD^cq|2CG!aa|mh?P8b+EUn z^p_b@2Pfd#J7H(kgQo*eX}|{I;$$Iu2T2be`9GZ$A*+$m*(ogi@+tDW^mdkdrKA9o z3F@;t@&}5eUCJqMA)54DF-9J5yU!H zYOPW#CHAT{bi)vf*0X5Js26d`&oP9s76Oih+CVv}96hy)Kv@$07rI%F{NfFd?aPwQ zIc#r5>XUPs!k~*C|IYqK*eB~f&I-pNU)azZYj}<|n!@pcX$s-wWi&Zu>zb;z)X+$D zHOtDRFE&JWm6%&L4~t$C=eXx07Y*aAzpDP;b^o9&fTz-H*`^3BY3G)k)j{jxzcSF^ ze_@~(v1vmZ?AhbCf#zG|A?!mhs2bzkn${+Bx#kI|FrZ7NFGyOG>gPJYMcFWy`%rp{ zGoJ#%Jq@oUlU9=V-8iWtbM^7v2%KL^7D5~j zZG`XK82d~}f(8mX!M(EIntHC~*y9DQliP`I}{~ri^u+* zeDnMd-HCP^+Hv1PFA>d`T&X{kDq=}gUal6pr!RG9fGjRnxD&CxKWONFKukF9N-KH* ziJ7|Gq4virUK$(;rWkq0KLfBVBDsd`ernGR-?0031Rk%Bot?s!jypTQ&(Z=BC>!_uE#CJT`tE4!uxiJ6{7 z9F~Kz0wZ08voX>^VV^&Ld_$0TuScM(Q%dl(edyOeIFa7j#&1ppQcYbe>ai`fA8Wo`~6c@f57d|lua3lNLnMhjJrBvqI#jE6o={W zIUf2|i@)Z@Oe05+jWM zeUG{Z$uC`A@TfePyryw}V~)2UffDW}P?|4&>*6(?_70=79Xzg>dWGWk3g~vyYT5(oVFo})O|6^) zJeIulgiyWuJI8Buo6*tHEqB3yivyf8&)(;D#gaFOD~oLbR$s3{{@%?DUd&ZPAlTCX zHrP;za{%`Vxd+tefKMiGaV)=b)-#$FY*U{qBb7?v#hGg+OHUdh>vLzPSBH8EF{Fn-ALNjD^q3i|6Z!*Wl}c=K;~& zJ9X`zH&027D>+q?QXKY*W&pKv!a#VOrh zv2M+`jFlTj6XNvu7{`@cIqP{e=yDYi0%N0rFA5oc1POi*8kpUcdzrcl9J>Fl$|dF4 z7jNx3TD+TMuNUz{;-dS?4{%;xx_>z0oEWvxcq4hwb=?|yGOals8DFCC8}w7uHa-2s zlTKSDZrZRzUV4>Kmx)nlzPaeK?B#vhKtHl<5X>88JlhUF%l}?!tI!}DyIrI($sl!( z<|Jpo5YD@9mxAv)xCyXODbjS%@~)h&%U(mVL@t8Y)V^sX6jvRtWdmmNSH&c^wQ+yv zd1czZ%bUv{JZoQ^aGrE-Dqvh$&;|~edafS--W~B!ky`S7jB*J zs?!(+UQbNhs`K3TdtdzYe&mem9fOB{73IGCpt+ep`9Ob6EIjkt)>&)JQv5!+ky&)W zp!aBdkL8aBE;Jr{fx2%=!0fsY1eYwv-&DDtq@b+c-t@tulN}72Y68{JVE_j7aE?ls zt!D8a!SBo*>(%!+$qI$`F8V4tq$C__(WZKSE^ghptUBKQb-+%s4A8_D@OHPoAxAeS z*%~!_2hDv9(8E+2NYL>v6_?$wqr~Ey(f;QOIM-?=Pgaz-Ba<6aPwWQO7u>n&rHn3mHoDD4*5LS7!|$1uhYL4pvse3-$T%XilS8GS0FXkO;cuY;f=`?e z-$F2LuIkY*bNWwY5|19CYv>xZly+AXG5Hj}o=;EeUVVto*>v%m!0=CJsb}cNNW0*2 zGm|7seQ?Q6b$79-u3zAD_E|FstOTb&Xj~@1`d~8mgh5s5{=zK_t@ooZt4s^~-b6Cr z)q-sHTcP4VfKr=QEf*)9P%7m z#^ezNwpGA5$)~JVAG7!uktcSAk^TNAv5Ks2_e^8rzcQ#?K=E1GuP<67Ysa9~4MK82 zC2BNj1-F%E&Mvkx4nf#^(U08P0;qe_zaOqYo@A(REejtAu+Nu}>OMCE`{zqGqsT`S zVl=%6Xc~E77H5VJaP^fUbp3TXQunqct8n^jEu?4?DRXDNnXq{vG4~{f7XaNvky6{9>cPOylTL zNs`rl)Oy(uu+e>l3ZUbEm6gW=&49Nby@XLpNF@UKX|r%vCl};C(42fd>ABtFw+PT| zWG%NO@e2hu&|h-MbMiX5SAcXi`M(1?tuX)o>z8a1-H;^DC6)drJ1`ndrQw_T(m5e! z$$ZfcMYFE{#!{P$-Yq|IgW&r*VU0})f1MXzx<%FP`4PDBC;LLqLrum7X=8fBTE{v=J8ErYoTA ztCIfhtKZgWqwP3i<*9BVko@Sl3vdK&*&Y$B@hGqq%S#iPj|clzrfQ9&G#-xh?!F^X z6GOmmI{aMfc*+***r=N`15A6c;5^;fVeoS>fQ0{c>m!dVZwCd1L8H=rdgJWy^f-@RjqFp0 z$q^aR7784Ej<;AhTcsotc4 zd$2sXiTZk74dFk-E=S~gSKE*XF3|-e#;FGjAw0TRP4PlMPFhd;*a_}%qk}HWEhoVA z(@84Fw@eVh*JM=8Ml$lP1g1G8Gc7Q5?310Z^f(96vCExa+f}fyw$}Hl(lw18CnSUp zU8dn~@e6%J$WLt?C*%Cbc;vU28ZAj0M72Ewx5^O=XXSL;F zF8%3aw)e}C%II48|1rR6;$*f&Fia8mWqg?30z>nxHMlfjb}Fwyg}r`!tO-Y8#;C&B zivBWSaSZ?e0O_pz^q(Z1J%s-kNN30Np3XmK0sfz-o@M`&)N`xpKS4e9m2X*=YccJ{ zvj|CWCQoQrS_{lA#`%>$w>SEYG=?pk*Y%-xBxQ^lA(`bJm($I$!DjM!OEG#3KMnl5 z=o1f>Teavn`t)MRdot=cgCetStPf8H#wnx&kLV(3*@pEG-@??YS)8Y%?6wUFtO)I~ zEN;GEqTIig4oaAM)EXx!b0zPiilf zmtW(O{(9?p{w97Rh3?Lih-fD9l5BiAihryU{qVMx+D*WjZ?a~tGYO-@?N9%Om1z|# zhNH2cdS@zpv#JponnV+}G{WxX#DY?aVTR&<@vlTc>C5D zQ$a!aNrRF_M$jYd2EOZgS0VJX7!i6KTI|!GzU;zp-@f|rJnHRJiMOb4Mo_x<2M!|V zFCP@QjRWLo;Jo-7x&-)tTc}NUismPpuKq<(Tq?7tct&&O}@)9tfUa`$X zm0r2-xc~K8ku)zav&zbt0#eq{nWTOH7A39zh5H!q#O(>2;sCaR=|Z5-mksg<_^(-3 zOw$t7KCF%y7T-a?|MKFpokfyo1%G}R+AJ-u%F7r4dr&nbUFS6N{`5fQaN3>b3(izI zJF2iW?~2QV-*Kly_J~n_)`fwz+=Jt@=ivy0Jmw{+@w1e3`t&_IhfA9HGYVU^HtyoK zV})Q)Y@dnnsiy}iTWLS(aU+*{qD7|c{p-20dPP62qqCXqXvX;NXa`;0xkn1TL&;*g^Z|ckaHFk@-+^hn)r&HaWMQ!*arrGw z78ZRpI7oR7BtEAU(RBps85T@gyA(TPjnqgGUcDzQTAeQQ0&UguM@q&l58)5i*l(0W z;oQWY2s^aq3$BR{zC4-f6V|eaZdNam(KYHk-dk%h@QEc6F+1mo12g^~;XiVCuS*{O zn-y~r{@<*ag>NGj;JL5BW^38ZX{x3;V&Uajr6|g{c6%AP2DI15gal@uzJTTXsBsZd zeGf>HBUt*MpF8Jl4OPxyq$COYVi7^?W@XLj1X-$+Lv z$sgUwcuxr2Q3iPpZ%x({2x~l=e$kRyO+-K?q|x4r4%jU}jyA4eh_iyGIwP0bg4Z8U zjY!Bk#^~?0XUZ)^ShiyhtcA4ntKa8tUnu--KSk>Q$+)mq3e2aGix~k-RZXT>IvD+O z)B{uyKG}@FGg2dLO%C*=e8`4_5BH_R(m4IkPPn48-MHqGq~_MgDy%Vj>3ub`|0f58#Tvc|Q^2QACu9#(dYG5%L}2wV0mW_TrGq|{0_9r@8t_a<`St5>%V zy|v4tPAiQ2SqvqshDgKeAz0<5LM{0ODd4Pj3jM7!>`F1zw+?%-iphCbdXWy8kN%H$ zHLsxHW4|x&GgF{(s%(fjW;svxbo6GKRH-lqmD1s*o15_G*d%39=h{FYur;!stJ z@m1>>aQ1xpOuyHe=dX~e)MSCaNCJvo4{mr)2$q^JIZYp6abMb`K} z+tcPPehJCXq8tSUSH8S&Rt~3py(I#rW2C^M|VC^b@ikc+MN3Fh&Y7mhxV{ zGhj3G7R3{YOhCP+zBmEB+=PX+>yq9ClKLC(>yPgzF*GaZJDLf#S+i^n~}Pji1Q)*jRQaMl2Z-@GsX}eUG0;GzgXi%BYX>c-(b~1JxG-~@HbtKigWcWdS z1QBYqBwKMKco)pMleIL|%~Shz9C?S2#K-$V_-zJrX_tui7qX>WQF=9lcNK zL1LE3_>M#!Bsz_u)z|lJ_l-C~y~B}FwkAwDZ_)8NESI+@GX6MKDj397@D0Tt%|Dotf;>iB1#fIyrL2r(S zKU^^{1r$E6zs-o4f11=ipH?KXvSx;dV*$5l4Z}(v8Rb7WG?BdtHe^GTdkuXqfi2;8 zHZiAZE;kuk^e zRK(fzbhmMLiX~iVf!m)`*D|9GG+$1lHo#PebIINElh@H^R1P$dKW>$uvba!gFxm2@ z5O7L96A~j*?U0@L!naUG#RO%E$ucjj|a2K>zF zlWu-gldt|&CNC4!S83%WIL-Lb@E^v{wYHVYlH2rZ-mK^K{%EK3ryfJs94vH&cJPTTWOE{) zqI%_dj&j3giDr4+rpd!_(_-On*WPW1409&$AA+}G&}4ZYm8K(-VhE7Y z`W%n)DSGpdA;)CxCdOeW`m~QbHt%4U(dBDuP(TT4mdRMeXgqslK&}xqnr)4nrv?Y} zv()6OHpi)X^T{d7E_|i3bs>%AF7`WSp;eKt8Qm#DsOf7r>yPjO4#=B0URQ#NnJZSG ze?9kp8bG{OZyiym2I+xsSG|+gWZas3vomZ!uD+A`J1^55y7-CIvo`=(5rxnMR;R(N z4j918CYP0xCjV7XM@P)7_wPq(^S*6ewihpSPTvy@40+|7PRNt(?|H6{J9Gy8!vUG* z9}dWSH_B!Q-$mr&=y+@f` z*R0$46WYI*p2iRn=gF{zoWfpP-w^yx57CKvX;=NK6?5qheuDW@*tDwaqgYt2n(5r(XTVaI$I&+wI3%6JWNxFE%ZUY=*>ZHA?uCsN1s9XZ2l^!YJFa2h!|{ z&AdIA-ttOkwyrfq=T+E#iFeCie7)WLCKso~tCQ^mGi^5)qvTRa4K*tcAU*VdUu~AN zKL3B@on=s5UAv~EK!893!7T&}?rtF@xCCij0v+7lA%OtFT|+~FppCmju*MsAx5nKY znVt9hzL_^?s%B2jnKM&U^N$}u)mnS)wby#?=f1BYE<`&>*MTK=RU-*B!Udc7aMsD8 z>%x-#$W-8m*~ZnSOFwgC;9#+lfReU1)cz>3_8g5?KA?u0q%c6y@S28y$IY2e6OT6w z5##v^cjV&vtPn$p_~n<1RX*+Nv{q}`SCsQTpGoL!y{>7!1$DpTPx^nj)AD?ttoLqs zhzo$c+V}P+?ZD07%8oqoo_5Fi?F)^Ss@fri_a!;h&fIb%qx&m%93DQ$@5+t+i}C8P zC9LDl5%+v;~S zIMXGfQ8+R3y2yjK8z6e3pMZ5KO&V`qa@Gq7qH3q1kOE!dc-a0eZh0l>+VLfs#fUZ6 zMDDyFUxbsv%4qdAzdf>1E)An&X2H-T80wORRD+lo*4tlxWf%tq8mhlWcT^){rD z?Lr5TPapOSF8=lL!U;U32;4i~0X1*20JH&FBe@LafC1{W*hkUmzMG;}=*`LCE^gkO zLZ1iUtEuC&==m$YFxycP@!napk$vhIm^GJ2H<$WN2QZ>{`JLar^&0`}V$V-X6nI*y zo#<`DLUImykG&_6E1~H{GImGkrDF{S842qBK13<40E@V!5Lm+mNRFM~YdCC+Gj90< zaD1YdH(TGfP66V9*^65@yvKxDx0Vf!HU|>@If?MF{2t=Co)uD^@@fuyCnrL35?yCL zuwaMN<{t%TRXwWm@{ZiTb7VbF<0@yzuTw~p@WCp%Mz$Z%e63$mo(uP3D{K=#;H;+X zQfwogO?K8jdfhE7u64!l$na%xXK!HDp0ZO@x8s0QjO76Q@bD zbFWL~#iYvA^|E2I5LZx?Vn3qlrKsim%heo;l@G)I#bKNQVeRmQL-}eX5kKNd5&gho zdv)(*#hs3Qwg*iX&8EhYWl(?+ip2@5c_cKPihZEOybNRPm}N0W86OOW+YZBJOPX+@0O42Ay?sab!} z?AcsQjC}*32PgvZj#Q9q;131LT~RLj%lb(!cD)y7LVS(%>(QQNI9TP#Pfp~-04G)w z{pQ4Z+$yn)hL@n^cI5SuE_p@7XrA6Xtv&-~2`rQGh0bLYINgmD7c@<)JK!d3P38PX zBCL0CBb!^gDByC?+>Hol{zj>kf(3^1X9?c;3W8UicD%yTAlSC#S zONLKwH1CxpPFp7r0M?+dF3m3^W1S9{sRyi4`7E%&9wf&R@iI7KCuB*nJVCtMk(`uYFg+a6>9=(u-auCfgzcvbyiHIJkT6(0igs>W*Z4 zkGRo8?3~{j+pTQML9S5AAt?OKdrKjYd#9q*++Gy`t9&LruUCWI&E?f@-vC90$2WxJ z_NQX+q|0L1M{fV&wc&UTEr0eE(TS95)NQzIBCn4_*0uVt89vKVe-abS)(VFwQFPnY zoqylL-|93}gr{4{CYU=ZsEyfr>WjF5Mo2}WHTD)}THmd6oJx;7!o#j?;dF{aUURQf z@8G2v6jF&=9LxGPY&6GK&-6A%|dmNW6kdT_czby<5_*38EzsDf_2))F%ouF(H?39 zzzq(|iF-Sne$AWnYH(W7GB0jQ&fp-A^j&RMi1=+(KbcFU(c!auTo9>=To8-WNN@ge zvCk#Lhlvh6DKs5WS1*CFXSlw!;Aioxr}eUGM;59KcU}_`KHNp8miW0Z{aU^6%Nw9 zPdv1Jb;~7O8<zN6x{wAw$^Ytu6M*R@HVQd;K%(cV1%CHe!H2}JX>FLoTs0y8TF`rlm_$%~>~9z=5KUxU`@<)ip=L%VKC_htEz5{gG#YavlXobX&F61+ z`T2{#e(X?CP@oY0ctUZ{pD#j`l57TNRtma&EbrwwC-GKiK8 zaGS!m1Eo`v$sfD^-~WMK6i1w*>ew6LKNyYm;J+Lig5c^6<(Ak(8$AE;TL1A*5%xZM z)4{u0>k3T;-&f!DEhY=8Ry!pYq5OJam+g$1$PQswN2%Sq^471oC$PX3mxo(#P_*P+ z7g`@uPv=xT<=npin_T-;#pz$<+Keh7E!P{S8u0#N%tgUdib?>e5=JFF?%}TZ`+&b` znK0Zb7qcmWT&{~9->V}s3OBAEhg5A@tJ!iprL>fPk7qmH>g*vJervOMD9`9-16{e> zzji`vIv`B9Yc>Bq_UMK=c6UP<4JRuS(Abzx{&BIf)^G7h^tlQ^=nV9L2+krB9J>01HVR_=*N0Nd)-p07;A zV=dht>FsE))(ohnmCO?;S*50b4e{LEoDFPA5p=0cpsla|omeh(j4~~R!vAc|!402W zGXTD{K(fy9Bm1{r+DqXPUdxF(SPHpj|3svMwtJ=5A3Kq@RQ2VTGRxne9i@3(*0pRu zyB{cLcnfI#C9cyuBv@0?;x5eBo}z6n0`mK2P1Pg`=uM>H^BqT;l4h3Z>peNC#uZ0& z7BLc;CC(M-=-EG2UgL*@p)ogV#h4^Tz=U7`=xj#=(ktW3Q5s+tT(&Bfjv&An$)<`d zs4dw-!!9>t4-6{Al-HGD-|k?XI`0z0DcdTJ^(tqc2nfl8sEyi&_o^GtFD-9xn=7^j zmDa6z9In)QUFxO2*JU3uUZ$EA9cV3j@3Xc-rU@XktH)!%b)Vb9$R2J^>QEs!$axxS zeJOmp9gYzTEUu+w&1VyAyJMom4ik(*$HqGT8l$Ge#{!)Tyur6#txpaGC5^Aes#tV? zVGn7}uSxpfa0%*rJ{dU$h%8=@N!8XGuCASe5%Wzc zO5NUt#K>#i`O~)mdYN$k%QYDz|8oDakcS8n-O;bn6!P~03jxKnkR6KoRaV&aM_ImK zwRO{0PQ4|+@^kE+-!GS>K>1F(kMd*zurKzQnctc?utL&)gMGOtT7VS-ftf#K6i>74 ztz677&%x6vfPuD&H3SP4alkBG?H6X>-0&p^wXoKzG==%=k61mm+zc6s`)%C6!N|j3 zF0Ej@BA+=n?pj;>Sn<3szZF|G8?*Z|?JP$LA#&ZO?wsR^Ea@aRVYKNS4WPuHmx&0a z&^$iM`IOYQA!@}Cqjx~(FfDq?Uyk2NPm{Ofx@IN7qS>{Iic)$97wm5Q7Wil0?N&qw zzjoy{UGlLg5K8S(1}zd?uQE^JB~Y7~>$BPw_;w%Sz<;o35Zqfu)@5`q+OtX`FjD9A z^7ib(@Jhzz=8fW14J(GtxclH+RQ8)w55mDFqWk!aZrzeWx1S#C7sxNB?9EOT1lAa7 zNNQE1rw291rQnwCxZa76zsnX>tNkDa36By8L0ExqP4F`e3+K5g9J&0VutXhv#s8+hn`i#2@ z5=|Z&axd2LH=KE@zoPI+fg8$1w7$C#W<8!I>t<^7VjsF~(#%=c@#-M|jWCzS%2| z?#}t1_Q418D^DH+XzI#k7AysMo&#^KcD;y}ZxCAH#8Hi(wfJmB^dVox23*kNoNp@v z3Io8GbE8p*vij?F`g-8oZFY_O*C>aJ(~?iz&h2i`)`%n*4By?Yyw_J>DSeH;;^v=N zoxdtclZrPyinz=GWP(NFcbmylcKUc@t6CcLaFmnA9$1m>?k0U0yd$EA|2-uSsa zOFj<#{-5}a>^XvbjRr?&`w_U{H(ie*407M**o%w zv&e_(@T3Fj@IRs%QWt5Ry(EFNICxw^zl{t+$4 z!%W0oEAPG}`^M(?8Uas&ZH4ZwKLayDP4Y^Fpbnbj!#4N09P7i4?G+4}A=|;=GHAeh z3Z`~a5>^}P^LV@t1S*3N`UElVID(_Ke7tOxV(5j2*04kC3)-7qGvB+4Z>-q)tQMIF z+7gcrj~xMs{Bto!QU_F*zVEV1tudZN7EU|c!6J?)*!dy|Hi zPU@U_7x=$=0qT{Bg^?yA4Xoi3+0RgzT{|xap*V3~&)-C#rmhbKmF)YSYmg;8?MGod ztQ|VpdeM?B>}GECE$JIk1gDh-@dE2DDryWmJNMHpCqYIte0>s#iE}!Xew%qj;rSp z(BcN9fi}HONVC_}2R7i)HUTDzI1NyDDE_+z7y-xeH0i4akC?b_{OJ>lU-FHNG@LKh zLNYSHG1dk5qPVoaSV{S4gq{f>JbNKoxNduY!(T)zXZ;mU^KGP4PC-STHBJmZ%TK#o zPm$0*@$(Fp9TUTgr5oK8daR6@pMpep*Oq1b9zp$ib;_26Y5~DF0Wf!UN92pv_1F{*Nb|RJyr((Id$Jb(*49* zM!}IuI)6Xf`m>d0r9xv!X@2K1;H_gd?6dMvH~4UuIXOYZfe#{rGqyJ<1KGful=3$a z)_mhG?r(+#`8!a#J{HPIG+3_ODZ_8}PHhWyh z+sOmn*;}F@WD2Hb>QYxZ5p+i#PrH(~e3^7x;BhUFb(1kt?856?@u&=s0c0h}qu^cf z&7WdxV;zka?%c>cXAXTPNgSrlP1h1HVVt(4OIZByF*OR7doU#Oa0rMkLHF*ERe)FtGf5nap;;b*)`0+UXA zB;qVeIlgK@;$-GLHMqI%U(KC=TAhtk&0o1Q^VQYIJv>podY*aEaHNN>>L;1eU6FX~ zJ-fsECmQ^aUergW^z_=yVU3^rVjh2Fcm-?oK%27)T=%OrdrL^4Ce&Z1h)afTe(hT` zE|UCAodjBj+5d(^`r4i2>I>zgcRnrp1eVl|mQ`=%G;x?6 z(N?T2-tTNH9&Dl@@?YBpX}C9b6evAJ)2%PsadIK={ZPvCBk^Y!^Sj;r>wAPBUYiuI zjfFPSgsM>VBidMFN**@v$hHn2f~=b?&_s9clr|}q>48&QyTM!>HlQf5ZOdACaZ^ct zwYBWl*E}3EbA0Js3?Yy4sO39L?#NH|_?(;j%J?an6!JVG%JiX1ju_^SR?9CuB>mw1 zIo|D2{Q98cX6GWA%5&=Y0Uwj)SjuY~1WMW4h7Dc?vSq|BD%tM#yO#-`0%0N#eJ77} z!?l_XJ`lN2*wo~?uu3hwveVGi?F3lMah>-VZU8TXCZO^E2F%j((kERn3R!A&E6USy zmkw7D2nQxw*-fsWA&z(!BI7f_=-cljO5TR=1;J);tbp2Gy+f8^C}`-nN--bGIahgp ztma$jYixVBQkC+QB!nRpfoG_f_Y^plgqg%~ojNty!aiF(Tf6<>rcda|yh95|Ic+qD z72!b9%{*DWUkuRayH%OQ*kAA(5_hQZu|$rF+r6_(6qKmSbOQ6OoAmLk8|fdqF`TYt z7D!$$#bNWgWOXhTdlxqU4!u3A*niY5N?k)LXquk>Nac;E1p9q2ZCui2#gG<bZckg)Yd~uD!QvhxwU?b}t<2xM4=?Vcs+h7`*W9TU5lu$nixIz1dVj$? z+-15N7_iM>?XE_=`Ivau@8M8akuxz~Ts1g&Lqf8-d?#2&+5Llx6A`|{M&{a%w;76q z`Wa&5jBIDBBu>{On%+_5#fX**RYn}-0cUYryT?-^_hB`kTy=T9dg=>bsL5 z!?8qH=PaHTm~Gv$cM!^?(~fDPT(SW|C(dikSa(zelHy0A;Z@RfeE$M!q=J)A~En>je+H8qym=BGI$A=tn=4Mre!l zx2XTPrH@8t?O;_nL_@<-lGjs4(*@Pc-lOU|$ay*`c#qi@Eaq><*%)YV*w29~q!#2= z3zk(r)az9#(qxZg>T{*h?_wSH*W1{>rles0iH)n5C{r?ny)|hSTPU#&B4$}(Y)IdJFXkCs%HNyBW@ymG>>^8nTxyxdFk9c0Reu`lJlsN;vS3@ zT5NQzU$p$rFtcjq$8+0mW})lpcMqx?Iz(^r zK&KSnfG3~b`H1Vw@~UrLUD+S;S%-pPF&70r=I`xV0^M;k$9hhP=46LfC^&liu}jHK z9lNat21oVYa!n6FvSO?|H4EBxeL#%o=(BA}D_6~pm+X4_^KX|U0^3UW^E1#yn)0rmSJs>*gy#@6QCbxBWou-89 zz>~wlN#!Rjv=MUyP)3y@I4K=vTl?aYI!>K+dG7@2ba+RMDVf4MULTGsQs{Vo${Xg< z_hW08g5IHkFzSBtwC%;V>tnk0s*^21yR?Bx=XVPpP-C(F1bTQrh)8spZ#ui{j*-h2 zY^%$;!^Cx8+_Wk#&~ZA>KE)JTg8vxI^gQopCxFUbYCzOJnf21#Xc-E-hf-Sz|HXhU z{I3ky-9H$xoz!bDmP=|9aUP(VYITgV2&W~E&F~?8+K8t2x%vUePh(?5L-Ow|+$u|r z`qyjOe{B$uG?`s8`>yWcCulaZC7YkO*{!V3MB~nl9JQT!Q(5I#XxHP8R`T;y@!&FM zTL+#?3cBH(jZ+Cq6RmqkmLC?jL4qKl0gtN*N7QKQ&{n~YTDhm(>0CLLaQ9+bnH?^1 z4!1r7rM}5x@eGr&O?$56lLa*KTP;rXx%cHU2dU64mgzwb>HIK&K-}Zk&5+?5>kl@` z1q<(+fIwUucm0g0t1+d4JCEf2h~E0$nw(0)z7qmE-0KmNhTBe&vboS|%rJ_(aK|l7 z`k81i8*ZaNiiQM_LsqOlB?ErrtS$?C zfNA6yU^)m!!{n;lJ<_4v*SCYe`ySuw$5TFp#34QXlMSOK#be{k-8~7gS_FtV-7*CzV%S!;`goVu`$d zIdQkCw1=Nrf_cJ2rd2q@<5}M`m~Yx^?<1i;A(mmj=}U4TS-W(Wab%qjmR+j8;@fgC(QBP}(qc*izMei$iEE?U5 zX+H3z)U_wkf@6JJltb!b@-n7^XML#djDqryBRdb;dOfeOPV9xY4J5+0(C7K4SaVQ2UJwyS`;tw&UDfs8fg=%{FbPJXxpwu>>yZ z52ci(&LE2TauX!|(djF1?Wi`$@xa*q3RGxk7fBK{Oj zACizX;j|N~p#pDn8j`bwc*VJM5^fgpOytvlH3Zke%Xy79Xw`tc<$p^3kB6@J_br~> zt~{MZ_PAE~Ix2XUheAYY;&V!KN_STvvlmCU7uNKsP$cm>%GmE95MKoQ=blSdN>Q0z zT{^FR!3GimKW*6E7uepZBx?^9;}V-vPB5u7CdEt*_=C0@F{{*F? zZSU2LR)M!T;w9%HQiA2jsJrCLmqP+mP<`Xyl{EQu$Jz>-cr}B*3ph7o_t(`i&U*iX z4*ebIfXAEIX{nRQk8M}y?P~W`;h&aK0@gzCan+TZY*{LA?di485Gh9GmQkM5&ZL$cc z_7M%~t)rnLicE%Q2b=|-2i)E=(ZheD>;##@pA_P$Svw66X#W5#qmmOnKB{g{)&J9U zP-6VbEAwyEom;IPB%-YolTye9?S_d>B66JrCeB^fk{y`ig5FJ4QDXAQevtpHXiv{L z;w1cxSzq7|moonf zV<@KAk;z%LM9(AYa7t!Wn)x~Z-YSL=@QW^&tpCLP{WFxGUR(+HDZ4kZVd@{Yel*Ih zfbmkdL_NDPwWm)T9r2+k8^osWm%hJm$t^4~+W+Ra|MmdHOY}RN#{aI%En+n-Vm|a$Ug3hUaDs!x1=dE9t40Zlx1DHjZ*ek&;p_`$#98&Ha z%%2B%<&C!5trIP3AS^3;%X`vu7FA@2NNT&+@7h!$Kr-&GE}-e>GH1W6TVRhfcdW(G#VdLh#cFhXa-+YS1;fAXm+QIzJZ283zju>YihB#-So0@7%2 zrI;C$)?ednOg880wEk?j!Fkhg(0J_sRtTw+>Tlb|;fZxO&z5kXTbSK~Qs;Kkp%23U zIed3Dg0eU9t?9(Md3M7sX7y9d_ zDaz{APTj8xc$l%GW0ZZs$&M~l+9@@B;rzkEt>N+2XY;^+X`k{rADEn~7PjIH+Cchi zo|Hjt!7QQT3ruNspHy`(6d*i0O(QnB2mMu4b{Y;(8L>d4UIqDa>3O}cjT>FD)vF34 zHY3+O|D}7Xmamw*+P%JM*#A97gzH(O5QY-6uOjIJ?L4BqWSf=s@bIkspNglpN%_IC zQA7Emm!6ji4;4#cr%bk{yYFIOvf;|Kn1L<{`ZJFmY3AH?fy0>bmax>6M|@^% zzxKo5J3-nz`hAPi`PB`a3TC%7!a%Ir{dio6bE8etAToNWR?XOG>isss$YwB&WP@A0 z8JuqAod~cYW#(>y47TGH&aiEc62Mj^G%1TZy1P|%Mw1`MRQT(GLfrs}^yG*}D5p<8#eSs-4aWe!dFY#c zE!uSKdsSb)a*y+E8_F`6VS=K2!qw-qSEBvpygxoe-ZjL`hPd+mQR~RK)gV>TIEFp@y0ET?Z2RlY)HxYftq z4R`jhn;Xot&+pcjb;Ww;J@m7~CsO{fDa<6i zW6L)MC_21>6RG<$tKf)ZO}R~_M6_mvQEEL^QdTwV?`YfY(b;X|b*AQsZwL1VvPcci zk0LZGZ&lp{I_gSJ>SILj_U~&w+FYgSEV~h8Le`gRnctgIAuFpra3>-L?xnB=(^97_ zqI@?kI{;jRZ3#cyt>!zfolA{a0~uG>(5 zlo-OUOIOsmfij$9wO3Vx$`z(Dw&m=rKk=G$>3USH_74mrU$1NW#zD&9xTzhJuyI>7hjjY+_ zx@Z}oXp1`a%LOj^q4fqYA3ww+C$b28vh6^$q-mjf6k&?a#JtIGfF5&u#`Vibt33gA zEa7Cx0e7--S=bpekp1nYKzOa6;Cg@7>m})?&`NB1VxBOQOTGb|6#9T)lT6% zwpvcTkKkxs`mod+PKtQ~Nh%dIKYXDT&qej1o+h*(u!oAr8}BC1e|Z#y_XZe0OuU#i zb$3Gl*q7_NiFRkW624((i_Y97pjCNsxN_tMg$ z?5hZ6k9i(Z3)0;m{Pv9qpxL+Myh>mJpBDQ+I?F*lmrL1oW&oV>P8YY7IQN-EPeoieQYZkWA))ue^wGnq3ki|#H6y$%Bz{uEN!ANqm!iw5&?C$x5VRaR;m^~jCP4o=rp_DN*Hv}tc`zBpJG|S#jnLok&>-sa2O4<5DO3iw z<|dc%B5>Tb2_hI#DBO9tQJ&y%(a~JWGSA-Mo0{7WCc&vme8?V z@CLtH*rv}Y!0x%~bx6JvM5u{n>4Un;^NdXDszv)d-58}v&+cJ|Gk)6TERJ%&c{s~! zLOP^$M>B8U=O$^T&u~iP8O|T7r(T(3_UvSD0$=45R(_6ETauQ;<=8I$Mslc6Fv8@jeD9E#|0G1Ad43LU7^h1O&9riNlJ9cp6~1?F=69+@p_#FG zp`1KORc1^zn1tQmq1MpWVcaKA!26GU4$4tYM@Pgg=xN1pmbTrkoTN+9a=w}SC0y9L zlJj9P29*gCmDGvdJmq+|6<)VgesugKh4aQcSxl11b*Ib)8)<>!|?G)B;@Qi4dgvU_sxS6y9EGwXK; zJ=u8W(Wus9ax~A(GFHUG^q);kOX4nrh?1X}lcVt?`G~y|S2V+6^@l@v(HEzmP9BP* zeY^eK%rYtEK4s~jSVpb2@vL)hJa}>jB_DjJt z)~hg;zza8|m?To*c^6HZLMHt4%PP-=%yAn+)qwd^66>uwjNkrYHMIo0-00u7HemC$ z*TIK_apJu3g1hBqXhr$3Nz{&1Vx;8@xOU&eDUG#Bt7>m*8~S;FW^E+4x(`tmL}q#{ zA6C61QPw`&)5#+QgDLx@oAs380+t z1Htl@ZX&dNa&bt|&9=5vv}ydkLEP{&OJ%G(3As#HblBr)_t)XCu^eDs&K1^}u%P;#6D2UHS|E?fXrvKkj5Tlj;a}>nl zC7DE#`QMc%HC3Rn53n;`QZ#EDO&AF~= zv~UkAY&!fE)l7I}q_2?aXod7(a?Z^@I5J%4I}*x zgjfDDZM}{Q9`mpZE*|tkb$o9!?Wo^Y#Ug+;86N8#c(Fdm%NH9Nfj=DhgjJ4aau?NU zhi6c3?@aYQaaP>n%$?Kl?WS(CAACLv>$iV6!7?74SJLM(BU zAHvfFgc13Bzf>M{2yHv>I1`jFV(w?o?qKXsmpvnR&GIAn(ObXoKa^a>cD9p}RtLXE z;)f0HTz*PLsd)2Niz}dy$sUhRiKLROm}tsbF6@cvgO2XUPEJNNe=A}8Y)zjwS?hH{O__nZcF}0EsqAh{}Ib$<^QtfaoavrH@Q=ul%di^ zeMuV>nrBN8XkaZ*v5(cxaqZDYXO7oV~&sdY~y(}U2>BGt_ z!_=@nU}->wzR2jJEu=r6HF-3lZ?=4(PIAFrPHxd1-=2qSs|jS$$NYNi1CMo!T~IL7 z;mzfhAK!nakIJ0O+sHa3b+h#vaVIQ423wnR4h5Ue9PUfy3`CYOPo1kp|B>=)r&JOv zs^bK70;pe1m$nD5=<71xnN3;r4YIoOS!@b_^=2Lknm*Ewi-GkuO0t=8w9`zPa(m*e zuyz~3%LTjhFItq~beHdFvk$3i+*I)cj~<$J+f`YM`p?C`d)p9qpI2e=>O%h7xekrF z1S9>n^5PX&vM_EqsrzUYC?5l4q&S<`y zO(9TTF-0oT7a}=MauA~)H77cllHsY83tNiiy>-KV%5Sx*j`6x_>0 zQ^djzov{VU z`HwC^7A*hn+Us@R)8)Lxe0u)dx9D9{xQsU1u18jYMTQ$qA8 z@BOyvkAARwxM?78GM_yCQGZQ1cK4brLB=u{rl_0h00JT^_Kpf#H$-{>SL53YELoRMrj+hn zTSC&vmU0`iyyoucvyt{4p^o;M0DCupZW*V}R7q2^d+eukm*Y`;_cJN1bkM1X>&oHt z+5%nbLiij&w{!;RmSp6hKJ$&oqXiOxrbG|rd&j>+>PI9 zOYB?%nN0h9@RcqoUshh>{gco|IIXypT-|2S46ipCoC-MJtm;)syxJ!=n+LAmqMb(`4kX zkTc}pBiF&_y-+2Tb}>lr28^XC!ycifqu?Yf|D?}A3+9SqL1XxV#xVJY75%kuqet4S zT(n#QmSBJAN3l2VPiVdp->0Ja^7Rprbwn=+L>;L{_fLI_v0UCiCRdM^a~`-J*iT8C zyR=)snJmSmV2=$FZ?t1KihSng8z#w{sk3Kt-c*8PBJ8J<*7PeQRyvfNH;isu>}a#C zAPuSSEvOn!5*Hn~25)=23-m%y(yMnbj+)pUD7D^TQt*5+!=1D1QJ`X9euRW4AS9|Q zb+~QP^`|=mNJU8m87taODQ0=L{wn)?O&u()& z%)4^SY-O)FZ%BW;j^8bg+9keiRYen^W)GwUsTN7A8k$Z~3&*C-Ye!6E-nbqV8kla{ zr6Aq-f6Y)~RIzuIIe^$6&hKC}v#goAQHbegc9t~`#C9M zc?1Zzj$jL9nq)^4+WAIeB(2NmpAgTqnv+kn&Bxix`B&O$mB{OL@O{?X{T}eEtLg=Q z?|sz(MN9Z$2VED_kpqOW*{k*KL{KQj9h##2=hbGcgPRn*ogijCG>hGuQ9an8Ihvw3 zPc*GUybYII%40vr=<%lR9qjO^%#tu1ZCJQ0BZ}N!5T)yrdbqkx#2+P{+{Oz0rd$8` zqX+UM==jD!0~lv9Ld!LZzHyPYcH=^~Qb=bki!-LlJC%oIy?pVQb7DS{jcairLgbTN zt6^#?g=GTl`S_>gyN{{b+~KPe6o~S|`0ph~9UoLvRt=s<2UbR$m~ltdW}*GgiN)*> zWcQe|y1pFM8NW3G4~>d?F-`c|Z5#g|>wfiauqyac8Y0K7W+; z^~lZim%vLLai!XSX2hcXl@U8jGL%tEk}UbMTAm{4JYI2ZZLKu;Ygp|xGy`&1ssF2zdA)w-rWlDxBU8`{;17dSd?i~jlvdb4xqdY-~ziNiQS zPiA_95lwVl^sI?EZRmFBpH9?^*{NIdVxQUvX>zAs%EshZXkz^XjLFKcD;UCL4o(vw zPSWn7bl9PF7Ds(ue{48Jgm7J89k%mBX})m!;3^VvG0C{BlxD5kXtjLqSoF28NbMQ$wo z5}yzGW2~>^#HjY~*a%7=YzWk?MP!>jW~|l<))~4lpZRfYLRqh&18v<(ueGhZhJjb= zcoW9?UA^2g@DiR=eAfD08h508ao^FO3F+d1v2mrIqcO@4v_q1Fe zO(CHmY=3&cDuUJH)IaltK3PyqJYcw5TO1S5&7dFBA|}2uS1Hz^2SW+xu*tO@Ed@}A zcHH#XAXUjChK|9?`(GOCa6S~f_r4@`Vp2!RvKTr_QQYO8@68)7E`@TbKXpAP><7!@ zANc^qmhR%TgRKm@O_E$5lCiIzw>gb;%1gEgGXE5p8lDiX?nxJvG|OaZ7e?Hq#ww)@ zw~@`wgv3i*7cH(RAJruIqI?WXHQTx$0ntpG?4K;wjCT^U{ERPRYqZSOG4P7bA8(g$ zB^y2L<%!i=G;g^(`)(GG(=$CNw}!GQjnrVLAyxMy;1#)h;AbiHqbGf7dEsk7s@^Bm zi;t^JwV<+vqmGjG{31Sm*`tyYi{nA|6_vQ1F@o@s9PWgbJ`x5}hu^WdI{iQ_F6ghk z*b3sV*a@4}!5GOPse-20g6kSZn3ZNJ_-dChP+V=k+g#rb>w@^lN#Z8&B|dd~-9z(L zg(JL};eA1Gk%@7k0yLQ5ek|lTe8QNLAr096M7l@QCC>VN;y@la^cRohGp*}qh|UJz z)HzuPyFj4SDIz`LS&Wy$6$j2n`9ogiV*AQ7^nd%TpA8>P^e*ILlfZF2JY`Yl7_YR;B0dyWO5I&RB-1*hJxs(D(ub z%{JdlxnxmD$jCg{q+;4l_V1f*yJ+C^KBGc`c#tM{|204}gNBC()CPdcRcp33OzUbp zD@Vt)pZ0IeSM!^Bs5$h+dqie)EyJ_E{7R@wa=txin01WyzDrae;CjWoOsWnwuU-o? z2m{I6u>`Fee2G39r2NNpV~yr;$3N@`rrZ9n>3-S^Om`}jn<)T`Kb}#nkT}PGv}|QK zx#CBVwh*dX(OS!)eJqB6yU0Y@ZCL~{kI4h>^8UA~q2oVz!8sKxJzMG*#)_rBAaN>p z`TD@BLv4-obzW+L%Mq(qSBb`Txz?{f<-B4}B0Nzm%7LMgX_}?WIGW`Bn>^l3V7-wV z&pSh`tox=H^QU}@qR*w;^I0`LNqsv-S{nD|=p1^GJ590G#R6R99AR|XkL}%h)tp(T zq;|3xb!75?I*2=CddzFdh0r(<-DoIcHIvE(KTHky`<4BzDg{{2fYEe4dAuRb^j@72 zw|e8EiTiwTVZ6YkGC8?1+LrWrJU!{<&Lhps;!Ux@JVo|8ec9`4AzPj-fL$NEtMA!H z5r|W26o%5DLx(Gx`0m{J)RuESl9)_kV}kM0+v}0KQ*TqY(7=HR^MS>Nye@(?8tz|; z2r1U67941h32o&`Runb9J$OyV6p_(8fA(Avj!j!H1%7e%cyYD&^jx^5%Rtw3eh^QX zD(IrC{Hy07{WjJMedf$q!UtM&@h7P~U+#PP9vl~mTe~wzN7Y}rkNfba##hHZPuqJ) z&P)!tXD)~SnM+}<&tpLT%v#=r@6Io2bSU8wiY=Q~J zhF)EGr`J(J6|&@Nnw~#)bUIM+g-U|0z3zUI zzGG+S!Aj%+wQ_rcT4v&2=XTBh_k^1AsLT6jehCGJZ1)7{n;ZHa_Q@$Hpu7=2ykvLW ztfe0}iF$7#n?f$n6?LkUc1_kK1=rL=`o2rd%bENu6*{oB4@IR*rzP`%e_@w z_rqpaNZAWqRp4tB$que6E#+i&X%g0*k#x!D_f*JgctyDklQ639E#7{R;VO<7?Mn=ircxEVX?%o9hW`e3Ea10cp2_ zYR26;5$2Tn)f`r?b6I>^93;Z!du%&XL-G;!D&D&^L6xjkVRiZL6c@9m{_!t;iH{Gq z90}XN5w2xcous#X9#&7>jY7$UcNM*FUwutwo$X+jKQCSKEtvna_v-VIXIqO-i@9dz z*pbth>-~+(khY!IKo69I+q+c_1R!ZP%PEC4cPh_D; zE7rId>S^|D_u;ID%S#Y*0N-=IOCs8nptWlMeFrXvhko_g-tzX}`nznNo$e)erX*Om zz9{?h^zJr3M7@mdil>!%TKUmuj4v_zi&IfkJ9>2~l|Dv`W2Y>gB4?y3!-$fD3BKQ6 z%MFY-$F-?55~pwOoM;wU>ZO$Ho@CbZYKDG7#xHGlf$U#r= z?5c6Mxr19g4M)26M>(Fp@f;q<{gtSIABH_H1f z!V}QXQUZ_gYy*?<>6p@P732F~sn4sa{@CYMRTG$X!t&75a2{PWC062NjJviowo&rh zIaVwj1|b1B+07(UOcHL4W+Xq{@%Pnc;g$NF5g8u4h6S3SP_S=xq>fgBpi*$``9N{l zH;{3~#nHWt!RrhNGjOR!h2;6N-i+_Xo8%(;NU77r&AQ84XQfWt0(L{Stm#=;wgudu zGs2E``D&lb?$l$L&|pq`E{ruNjqX)+7xEptVe=mj2bcaA1)@(SMWy$Q<8jTsX*&;tgtL@x>()O{KO**V zXUDsD5p9M|#RY_<-si-E zkd71vRpK@klerFSn2e|GbW9VjME`@Aj*lBDP=i&l~w8^Iks zVEg2-EaDzQA&FO1xU(Ivy~}O$BfQ`?mUp~q#S?m6*7jY{hcc!n_nf}q#|IS%vewho zsASqtf$d?FF>vAm@-u1Dy)#(2bzkrL0$by1yiIN4WgkUsvT z60=pUZ*CxDZHZ?WcM6kg!>Zi`~&KEFLl#^0DH!q$V*b?z1sE;&^6T}XjTzi7g_es)iC)`h}$JmVh^6Vp-24JO935CvSMV{0_DwrI-sFh#Y?04{N zS_GZOdUB7qW3=-zxMwqRtj$G))5ixdl99+f{*o#My`-XE^8+Hu&=s#5w(0^moUg`T z^VZzB%E>3nryjCDQio5{meviSF ztXh1N0Qv=VX3iho=T%n>9wIBeOWVpxQTM2AUNjINwQijG9yT@1TG6EQ1L3@X@p|&+ zbmxAxIwp3fSX7R$e|8dF)hYBXf=ry{{(H~jZ!5xqL;FnoiT0n^)EAX#7I*W?OiONfWf4;QN!9j7vo3MLpRG-yTOwA6 zZfsnaEpen3s75yfBpR$Xs0GnZV=`dieR657`tuRTV4aFKU>{rWG4odLy9{Jp%!raD zFNF}+4Q+SOe3rJtd1az~*ml<;774sa41&|9D;KlF+WY4^(tOpd^Ti+EdkgOLls!+e zb(?%Ai=|gKIDV%*NzcVt^s6;W${NiKVF(?|p<9=wbjnS{f0&{73o-VcC|!q&pmF`Y zE`$~dm}f5&{YYowW(FV-*n97BCA~KOw9V|ILx#Ph2sNLK?uIQdUXN<7N^Yby46fWT zZvxVY0{JMVd2z$?0AV^i8P&idVGqfhvh&}iVK8m4qxSNIu4hYP z-=*X@s}vP;u{4D_NwV-q&7HQXvEJMmj&LkFUD~kK=~;28n3y?8yz8iWo&Rj~3x7Ss z#zUlVEX+VWSb9&J$0LBw6!gZM8DaKubaT`I0Nq?Q*rFu=DXr6b(2|)n@ul&F8L{iE zi@)DzMd{3)t)C?Xr{}acf%=K%w%gSaRq0&T2q9Pv3wDRN+IA(#8smHL7{)(#p7md0 zZd{OaN%hP7I88`&e z#2p-ZReTS-GHm%cs0!QI6jnWlZp(0nOAe>b$OWaC^giW9(^r@8n-L#RO;cao=yNpT zWCx9VV7Rt1Ed&qE2vw>D8_2TmxY%snABUG(viRXiotR$y)M;(wMR+*Z_^^Sxv~(@z z$!W!KHXhbwDvOacnec07w8w@|sa%EUyX0=@#Ad3;6-pG3m-%8ZiAW-}DvO&V-)k0O z>)tEAFoeHF_WV>69;*2AtV*pM+$MXMl5BvY=9+l196WBQYYmJg|jM~TN@&|sNEz`o|-OEOJ?h?)q-$Pcz{o8G>n??uQkvQe|kQMCkb<<9^A_!1ZZ&oQ`l7%nF zN5VI{cy`CyDMovg?pH;hnqAtMY#ijAEx<@gJY9ow6+v{Ied4p@GWwPGIgA3NsU1va zODi>GPF%-iGKeEJWJDE{K~Ozz8eUtDj-!w-e2D##X#(^ z?@E;;);&KF5&>@jg-{~0?vzHK~F3#0yE_=gQg zv}MGwwTQ_S=$#^EvN)Y*D&5&r6L(65^(wRLE7P0h*MzdAQqQ}2>QA^Mr+LF$^*S0; z0G-{gH|t6K`nORciZxxC-a>Iw7}oet%0b1PMdytxdU@1fKn zj!N~44j&TPV{u^xwJpaAar)V@kRtke2sog)=>Ed&2-KTF*_gk}*ueuiSuJ{`#}b;h zrp!_SK$H=^)GN}}E_&*r4ok$|T3mifF(#+-SNK=r@K(Vo@iAJ6F|brW#b#HMSd|;OEaFIpszP44T%&60%UYwIBbi@Z zN8kF}F+%hqxr;Emo}OH+Fe1w{mZ_Z0L~r&+&-g??X?7Q(9|+-@a@|9RONL284rFuC zWrgFLSzl>^lO7U-H|!?Qmbtq^;NGX~TtC(_NF zRg!#rz+pwihwtREBrJaY3N}Z=B)a*>12%;DM|y_^T_VYP;f`9BCXzNs+3DmrNQcg8 z{}{iMnS(fbE7LLMR&1QsTOKEK4zR)Tsmr>>1h7LytQm?To~p%p$hN5uTVvrGyco3FK98da{6IWCT<6 zg~&wVM=|0l($LzuFS0Nf(p4MDK|MPz?{480$=1-U%{$xK(oe2U=3gm#?2oUp2 zvkSy@B(#s-RT<$48d75fx^Ef|z9&6@K@e#z*0cmV_A;Otbw?-=^zs#@iNO`H#+RG% z-I@&45W4QTcP=F4!lghT$_VsdP=cOSDV0Ze7J*jQa{TV_1g)M;QZ{eKrimH$yuQj{ z0-;)1Hd(9)chrWWrij@uFYj61Q~K4uLtprGs|+H)ntRQ7butv|5-1Oh6Wx$J>^7Dx%* zk!J_3Cv$H!nIm(pZfeOuzCKI!uNt13*Y)^0S0>QfggeB;BV3>sZ@Fc|d=p45*SsFqz>`>Adb$`3* zSwC$*nN^A#5&~yU!snIn;MX!r)&@*cH|pY;EGV-HQ%kr|M)J@?hZVi^Z9(L=CbO(D ztmx&ImvJ4n-Qg>RZrr<3{dNBEZ4tpOeVQ2GwtAYBf5F1lsXj<-Q#p_tNYctRYe_*{ z_Z4+;#NY8>})_P*5MeEEEgTpKz7J_AX>H+>PY%Isrbbf)fZmX?shJ# z9%q;AhLTd`lvYf1>38X4xvfExD0DqEKgadj`hGqsP~_~VFq!rQGszTBnDE3dBnB2g zv~M{c(MJ@9d+nQjwWdkgGT6Q=068J0E}-b|FZ!CBHFwQ3(A~I>cm4oEe}oxRaM-5K z)Itkrf%f5PT!e)k7B$sl3M!^M@z z|MVx7%>7MmpE^Pw!8o=1%@Og}E{+ZgCEGyvm4Z?Ht$oV-a(5MY0zqQ{+X@5z=5}@* zTnlkXhZ7tODxOdc9;AF=q)pjMw0!~ZDpIjvMr6`LBVHh{=FKcdj_$G>o|| z*XF;El@(+Ieq3q}FxiVvB4O2QdK;E|bKo@X`!_^AQzQM1YHTKaJ%EAdnM0K)(0V~4 z;*hhgvxz5E%^{2BnWidovh!U5Kzqfzks)y|ACz3gzoX<4?xMiKj?OERYI!R|fdi?HTM7!m)Lz@LV=lBWGyWh%2HbXCbxDhw}6piU*= zI4vhshbYS^xk{-=?!_^~7Z6US^>r=nID%a0#b(k-iAH_*{m!JC$NH;=x7sbT`khQt ziI9&av~5rI(s5_LPGjwCkfVpvrUypglcex)?DQcb*ok~Q+8omLTBr630n3j4%(^(5 zc_SjKtL{K$JNCxi1t4EFTlGEXH!J-sLR9;|Mu<8BKI&JLznCgnu}2ao8jAb0r&;^g zo4&TcEzmL2f_ILR>AchU-p=(b=NnQ6L+S{RJ+qiAc(qgfE4%(lh_6G^6FF>n1s>k9 zksQm0Ql3YWLhxG6C$_QsJWoFudALew|M9IV(;C4B%QRt+nK;mNC{wZtqwUCJy6#L! z8N$6yN0JE*{DL>4Z2dF6HWEvz%Z|gyy3|((A`x&A_5GPQ>j+drfAItNG2`|Kv1R85w!^INjt5JaC%kGB++MLnQflWOW?7tg$!v~$i(ytu zjraU1-4z0Z*)n)ouY2mG6JB{gprRmy+00>%jIth)Y2%c4$0C1+yndC;``_XlXz4I9 zE5SI`ny~B?H2}j+reMWjT`YRlA9y$E-|;TzGIrr-UWpE$VLDU%C<42P5|z5e^S;Wy z;(YFe&*zmNCERv@o)t-6?IR=ZPvQ@K2cu%4@i@b8W#s|eSs}EbX?$#vK*FK8Ox5s7 zVT%L1I5p$#nx3W?99HGeElg7U3vtUn+4RYp1LLMEPG!!zRM|aG+*1oOUXdG4C(sL` zeKI0hTXD&c;n{{~NGYa?W5MN8LAsO2S%7=&nKmeDuq@0mg*jcJf+vP~ef3bL@^EM^ zL`w(5RIRnwhm&esD2irNkwT_@p5@TZl7%6D*!aRofal(xnWpZ>{>$G#q0g5rKbk7B z93dfPZX6|pAh@5ch={ygbA$AHzbRG!;Odkwno@?LV@LcA)NRd5lIr*?^_bGT%L+A0TnVFX5xoaj9N(sBqOIlH*muMTAwGthe?+pg`i`aFzq#vhETGtL$r z6v;2ukCRb-{Hu=6GZt6mW65Il$|NOorraCv6{mg~ISLwk96iu26L9jpo^@l=>wWie zOIpM%SKnf9&vcKJUxn`Q#tA6N2yjYnw&f~@()K-mq-|^yWd9Z3bh_@QQB*N1oWS`8 zo(~X2N6Ys}c#qF@-Z$Ber)2VOeMoO7ha`JkWy31iAn=Zg*ZR>FMZ?_s&8O zD67Ond`Qn_sM-dkHnTO{PlScjh-&207FI{Xu+ZPmO@)`>$W{6D`l#2O33ob&co`hJ zlQ2DA;9d$iDUx;1T|yH|kt0APddAxU%fFed21HEbp`4xRHy={hL}5593gK5ahjg-E z;>JttwOTzSf8N9Yqyrc0z;O@iN(#`z847B!9C5Oo2@= zU^L&smbSyV5q!W20dLs^%WGIyB19N}ERq9^R4D?Bx}eG&z|sg85##^{ub9P0&%k*S zLNdfmS-Jc&AEXmd`uZ{nW6BP8%ZQM%o)BHHym2d?Hb`r=?@Pga#<^>^jVr8)K{PZ( z+k?exStPgZ<^>(v7PU^vqHK1rX5%yA{q^xl*wzk{@Gi7VXKBKbgn+UCUp#UTL1wT> zHz!rd5BOoZF8M%}p|?a-6_BUzH2aR{e}~c*`~5#gX;1$TD6P*zs#qIeKFdyC3bVhJ zes@R5_C_3iSbMl_Xg%iBHQ}`_99QSBoGl5Arbl{su1;`|*GK_i>;(_~JqMc3UL)r1 zvoX)|oq7dsw@gp5dPFc^PM$JmDt3K<14! zoU=rZNE>t-L2J45F*G-I|1*UFmAF2$bVoN6M)cMA;bUWx8s3F3Io2-rYCyx3c~Uht z5fSbrHw+?cv|qNviu%T<1r8@BU;RtBKlAS5p)C~1CVht8U=c8Gjh$X8geCLg%+}6( z*70F22edQm2=<-m9d6pkQDB zuxfCF3wa0IDHR60Qz!3P9kBTp(6)=*(zwrVTdcSNj1bnmz8K_P8X&hjd!Xzx--Im` z&rs%@67qtxBNY#O81?jy+3c^X(uIQhZFO^a^zM!lf&K8ltC|74p|O3dK@mW^DZK68 zUJ7u0xA|^N%VV?XlOz!nKKs;{2+0pEx&p0V)`VMc>zV=V{2pODMG1FNcMl%)v{{vP z+3;0`VanI`dsWelI>p(KGWZX+7LS>T_{P_oI|mDyl#y41jHC&YJ8yATNx>07SF=8O zVG-ES9^qZ8%hXjKoMNqWLnmSRCXF7#!18dGLs_xQT7V0J5byFt*u|R7Yr3p+O^CV3 zfeCLx2U^Z?<&MT_B^yCHG;z~s-|=V;Uyk7ixxb&P7m)x}LqA5WHo@&iJb{$7bk-{# zkM-?%iToJ!m18^df^AGZr8qWcN5$*IE%iQW>&E$naG^q7p+AqZ`(a@G>DFqvPs+&s z_u6>9Wl3+W66+#!21^w+BPsW#W4ZHkrq@haCZZjl0h@?&KT%VW!u>!i`eS~&R;g`q zU#I1|9SpgfI4B>7f+k06TO1I|_-4eBLm8;8g8%2(w)4M_Z5Q)#dDr(2o(=@QLKoiW43)4l;&wcnB=VVv${QHL?CfRFDy z&hFM3B)Ou_;mtO3^b$tF!mVQA=>)I~^25mmcsN>31KJ_A`*H3Q20*-lX?>0^zQld- zt*|g_(nJg5NISR4S4P}t?h|CxX*qQ0G3C#jjjqhC=S;ls$E!cgc0zEq+JXHnZ8tQo z7{M!?!vr`HH7>IXkQ?5ePN!ArOa~Xa`iJCFPMbNJfcg;v)!Su+-)%o^wYcBng*LYdySZ-BRP$coNzWBX&*{c|PdiqyhP5X;q;|Vj~bSR2A#~b$us%&6oa2PhXF^>E1YRY zH2yx(y``0;R6i99Oi~9OBYyDT&^Dc)O5a&hq!}(L25?f?o%O5|I`GK!$)g)aWRUw| zgdMED5K`k-0t)UB#d)R4s_ZeX+y2RUz5L6b$c~s{KN;^3k99rDgx;))@)m5?*dA;I zCN!{J3Y5RY&Uk&~dCLAVy6b7|j#HS-9kZP~&byh`-tyfa^NaGJmr7QgM<(q<9uSmV zaYCcnghzv;nZzG)rgTP!Uqx+?2^~=^LNM$&^(_C8G`ulp+1J;|tJ@tcYev(|`k*>Q zDXM14V0@`s;LJ5yX7?em9_DmJwiGhd{_D)wZb{(%&-}hJ@&qWd2|~uzMT$Fm!cWai@OVA+NR7>k|%hky?mBhlPI@? z3H$z5#PRvQxow`GFB6U6_Fm|@tp(N>2P4AHKqDkooT0Y<0TH_}T-+~8o7mBqkRAN! zK#FQ}`h;J^XDskKAFO)uVr=RS=(zG`P)|WjZhJ0YB)7v8W7&7+4HSp{Xf`ze^__Z6 zhoO|1ig`vdBjmb@I~4(LQu|tQkk5u(`vcskttb)^{~w|Q^&&_Bd{>twcl)xvoh6(S zSN`w0kfGiAAAtIg!N8XnexAq->2Ly>zatHifluPBo4thhJp?=cwgFMyPZVf!zp#M zcCYdK$!u2THoG$*K0~sKH-mkcmx!TM_fO3l*-^3={Q{eOR&Ty4(okDBb8{=~G3gcbA z>&|NK4$dqs%gwk8%&L!_XB3p-)qfVm&VDi)<_h4~RrOH-#v&(oE~HD&i_HS)pTQdp z{{*~fx&Il!tNb4TuT9BM#(&cS{AXbA}JWYD2}pLlTLW7SCW>zE=xTJ9E*g6fq&su$^JiRy`gVFZ$jX0xx_ zF?a65&jzM?TiTJ6Y2b2)Z{Y7PUTR;ykc(CYX+AiyFO?IFVw{Ba7%hHSd8FPD8q%a76cS09fU6RPyh4(H^0&ZP_ZQk(mtB4WF6+vAsF? zZrI;jG75lPG?`57wI5SyL}IFPY>baT(d_Wt9wcU4b&7c5j>a?3o18*d-g~0W`ws-% z;SEQ?R6*Pr15KNz@W$J4RnR{P|67*_(GHU9`_zZ%82 zbj5H5!F|k8hp1AAkC6KX$w#>i+xkb(d_Syu!csY8HcoJJIcooFArWO+j$t@DGsqhy zp#5sy6u*^a{1}%QXk0s=kE;nk>~1PHQPO1o4Ajv0x*3q-K|`=>PN>xqL-)yRZ}}3z zdbill{(w}Gj@OgWlYSAPy;a5f+g*O!TCVCWBK_acZ=CaQ@C&ThW=NCSTpqk^9prR3 z#2gR4e2u@Dkcq)Je>-VCTHg`gx%}{j+v~d{(c<}-rr-|Xolk0p34=bA5gnlw`nzGJ zL*U}kMpD}a-tB@_QSTxQ=bQ!z6LF*s*L%q> z*t0?y?yMvv~^|^spL_1Pmgr-sdSsKih@P9yqv32KKm`ZzjtkFBl2)c$P*j%YS zQ18f4*oj=xT@ZV#jZ~Q>IA=osIy?T)aqwHU{}v8bBn>u#f1fy?3yy5|o>wd+ zhABLaY_6Gs)hFd}GiA=XT1doH=t)3MDT*x3tc4+mIsM{+b`tO})zrcSami*HrtG1h z#OP#q(v3cn4`K6<<7s@7@OxPO;=Penxn>q!xQqXRTO7b1gkjhBr6WbF(gyY^dK2{p zNzyMeFBHOimcb=mt>1Ny6Rbjix9a6<t1Ba-6HlQUI03JpL8 zN5{yu$cM9P`;xyurGq35*nOUq?cg+8#8(W1&|0r>&XKh*qXnDGMN;_O*SzewNDE4r zLi&rON?6bx0y~h^a^$LZ%6d!Zb?&3$n^H9%UJ^Vb$p$&p?0Rsd2W2GG_*}o7kYTa% z@*;I2ArXDtF=d;nL2F7f&+ScHcb%$>46ljQ{?MT{3Mwm@@ad~rO2z^;>BZOB?6^&+ zcrVBPYHwKWybP8=N#^xkOl1q^bDF;=YdbxPWHl^o(zm_Jdf|4lqh`@f2Z!>#|n$HPDVxAAaaympv$ZAl+iUF9*W_9++~fRI6$(im&ez`3ae>@ zFNBf~q~0cr(WVe(unHYuRB<6#V5g9EZVIQ%V5`s8-UqYo&eD&lxlnmm$4&b4;}sw9 zByI3C_=ut234x|%ZgehLeby(EB=m&jQcxipr_dxzn=iQdwmae^tds^U@R1_M z*-b=Cj1eDZP#M1X`9UOPUUf(&u-cHCR`$H|)j;=x_-$=+|B|BLR#u^G0JuA`?T{1Z zX~AguSY2hdpCK4;*$E%OEx;eR>$FfX97R4uH$LR^^@p&>qeFlCZl`}uHDk9xW8$Aq ztmM)&m?uftZdFLkB2LRl16{NyXb2n;)r(6w{>g{Xj8>A%pe1#huo8IeasD<={XVam zznVRR!2re%V_RdEE=o(iXg}iPY@x`<$M5VQUQixgl9{f|9=FMhPc&Jc#F~|8K|S)y zjDNj;W$tJ2`R51rYq46h;{fp6e!!&oM%y+9XQ0}mNVsKbG8Y_o+mXN9Db9?C2nU7q zQ(P5@(j&V@nLB{bD)%_zZGvOse4e7TJ9;@YDj|X^H}mA?Nd5mz3!{xvU{kAzzSbKX z-YyfRh5KEW%>i%Rghn6hk&jMx1MZ+BeyQ=oKP+)uPY)(STkcjuD+=B!X?|ca@X$D0 zy7r^oeyL!nPAdC747Se^@Pa$8`V%8d37E~tTrrMwC~K;ZU-{^oqQKHLN)&LYBu?fa zH4g_ht3qDoN^4UlPn1@Pr9~#OM&XwgU?^I&=FPcEU-b`s?%!|i{kt7n1=Z2n9*F3F zYKC~z21c(rNq|-uZ6jU_PI92#&$g6omXRghmoO@ zSN1MW=2l0UbAV+XKE6#SYe?;PLsb~;pacK^f8V^}$L2yS&2KiF_r)qYh%z~IgUD{Z zW!kZX(I^VE@ z43sk@~FEIF(0pf9{YPCsqmI{3LAss5DL#mO4!N!B06#>%`R zdqNXWQQ?<@h%ypw0?jb}6)*+AXK2a!iJ9Pos|my+{)qVzdNHlb-353tTaKZAI`j_A zKUOSh^DBWWfJ4Knw~2e8J3C}2E2j@=B0JJ__Wje+8~wYR-^5cgBfANM{VTOs3rDT9 zA$1B^b}f_i;&>s`u)^rMcoLT~_x@ZIe`#ZKY#?nhnOdCT?!vcUx;n25)!Mc(BY5NK zd?)J6+(rwo@K3gtHD>1|o3ffVW}7g+%PbMqGw)_x5r6jY9)Tc1vbyUuf@t;Oi(HO# zB-cY!ZaA4ME!{gf3EibY6axzU2}N09-?K+H5_FBK5@`Jw*#T{wf^RFYYE73YR~?&Kb;P-gGs*hS5{~pSJa`L#&gcQ#w@%QPaDrVmr+*#>8rX{_ur`6D-AUFm1>Z0_eMO2 zFX3oZ7YA{k9fChfnvM08h)rEHux~gn^2;6226npUAiZj(i$tcn+rkC}BLyUEKCZE7 z@!|`{Hg`bm=p${Qm>D z|Ca}D2dn)#Z0Vm%dRbUT#PP~vjTRL1m^if(Xfj*vr7XdA_=aI?xI9ms+*tt+O0GUv zC?_!6dHx1vR~XBL`Bee`$|*s*kG0hJGoo2tX}#+==1hW}A zjf|a3&GGp?dF>ar?|#Z(zA%x;G<66men}cmm9WO=Kbaj`_FEbjxK7>S-x*$taWJ>* zRR*_lptXC4`gr4ufC|ECB2`1Z6%ycrMi!HgEAsA4z6*Dhra*SEx_N@6pfYt$(X}hF zm-UA>J~smyUa_xVpDqWW|LQm;=Yv(n+IZ9HjG6v&&2nd~yKdUZ&V@4T!wkV;oK@GC z3D6JhL%mdpcmtmc&Ng>#mPZ0hj1GtQel)I^(;3`(c-C%k**gaDDoO{cMA}2jbY9<) zs{+b1FL+I!6%4Om{rp_te$Ln)dGG)IN>|GAQ)oQrXm9F!*w@Rv!^?5R%cWJQwu9q57aKt0oo;uwoY+LjNOQnq-3d&#D%tW+K}AtZ{9CV zN=@fi$@*(K!>=4;N4oHGV;pV%}ww_YY*XSBJ{E*qh6@YLFdaY3tQ|ciwd6r-F8DP=w zbcL=sWNcRrynzk?O9hf&mx(0a->csuxK&x(L}(HjQo7Dy3^%g)XT-zOd|yKoHE-XJ z4M<8tC&BERk*-1hAiYoq&*ucNGc1W6q^er;NHxQ~4^Q}CrC-v^$ufSp$k{FxNRI^l z(n{pKrU7p;eBFyI+LfHm8^itvcH!ZY#`A-1O19r}2M_ZT#K*Ury*8DyzAv0&)4g!J z(SWgz_pL+*WHgpoWR#d>Uzu+E;L2>l=1<#AW~b$~1u<5S_C_{a8x6(y_?~GI|UYPMRcU;tabh zd6kC=WEXY(x3Gh|Dc=Or8gtTD(CQ>Wc!CuPHFKZ_uxItx>A#FZE7tl;Y-&iGzcwW@ zP=y+~dF6_!80qBRKJL zPxV~3Qg_on!Ey2++2QXC8z8V?fk(m&Kv}}MRA)X?kkH1?Z>@&wrhzKmIwd!(Q-?$_ z&NUvFw8$e9hn_;A=fz+)h0BWCGm}2FO1e+1i+s286u4cJI!&X(tM*U zKakd)Q~Nxx(OCw)%r-Sm+f`AhO}t@e8g@4A#yGLRaY_6B;IUEG8(lQUGNoIPIQgj2 zl`ZGw=)l|{q}?6bbhoyt^6~pToaz^S-PWYL9J$@|<>hH{wx#wFR6{fG?z2(e`41_o z2skrU@yBp0z=fPT>`-lnWn4!k#A;{nuGf5)suwjZgexw7AJ)`A6MEj@8=0aQZ?b9i zD?YF{;Fv=($8mx-m4tj)Kc#skNz-6I(A~e=N);MfE4vKyVOQ z>M(Va3?Y%i`kMy9urxl*iXb^xw{;W6AvHQeTA|MnfygH;???1*_!x&%Gn1e@$G< zShtx{3!OZw>`^M>1$Q_17<5nn4o$7xmqKog7|-zx*0^G&>k#lo`+QV0es|UGT;66~ zRcuP~p1<`QPdCE2n<$E1uRap~a3--Ep>|USKhaoqjXcFYXG@{_*iP~zU9n!s^M?2z{Ji9Mx%6_=cCErWr zy~uM3^prge@0-R4$a>A!RVlLcS?m_T*8m+vTKu7HLbj4)3}rxwa{^;B6F}fOg0Dda z8lUsL;}&!*g<>l*YnH%^EH3Dk+z?)*tl zHZ3Apa?S%ZiIrSebI(_btNI4Z-6cuVz^ZW&Orx!)LST^ zU86Pd#|N?zj}y}E^{XD~;volyKhMK>p=g;2R&$!wm382kWzD*`7*q#3BVGZvPC%3o z4TKf2R}IA>8$7K{aauNLlw;NY^aUOAU0bsWQRpk3m%hytGg>+C+n%_fhqI$MoR655 z#0io4Pw|J33YLxamtL~a7Pm*xG*am-k5=*Vf7%n18F5nYUw`!MOP@7i@wuE%oofnh zOR2B%u=xPZ)5bYf-qd#cp_2%8AC^O5w6hm7s7>YMZNm&pj(!rp5no} z7cbwMNs_VCmcd+N#~rw9X`)+kDkyS+_!|)-YyDX-@=r`g(whMS)0qGZz9Eu8MV3h9 z>>Rvm%M`8&(9h(Gx4W}Q;q-N_2J%ERmhi#dre4Nik$omKtltI7yxUxj2`29wA6R-j z7$pw-++XQ@e}1WfZqw^1fVFJ+j#FnlG%X&Q8898g$iMbTgTTrI-Jd9}d_e zNxRR*v~OLU%oml?)S1Pp8R+_E>G^udG7!}Cbu^yw4ZHn{>*EjcWhG;g zC=8L7583UjK)g7vsq;k0wG8b^nMFytk+JWDl+g3BCn*uAs4)_3R;}_pYF_pJW@wJp zXx4^DoqddmYsdZt1Y0|p+yi^PJ>}|MT~3tMqv}moo&Y)Z>)9#_EARte%2U)xXMsld zKC5Gm)>o0G{+?A8gQ?T~f@VWhOo;rN^@Wo)8GpZB2nQuAFErInbg8CAV^v_8NoJ^O z?Rrnv)ygc3xW;az`DhL7Yi^@=%REKVJ4aFCBLd%{KMt(VX|u0Bm3BAg6-0y6Tve3h zf$<~@ZZU%fl)wrjPJ=$ls);mdpp#knV&Az&locVrpQX4i=thmwesTOnz1|fSSnW6l zpooOl@laPGBp;#h=|KqyjEa|vD#1ThQ4%rBOJ)EHl89ft5KwG}ohLo_e8L&A!G z2cs)!x}cRTW63Uj@BwjNr4e*xjtkttVv`PljvI&h#)Ku!9;!+?KN?BKQy;&JdzTJ_H9T*WY&URg8Ig0}G zgvc-Wv;;HGUUfOIv3Y~q`*&U=)SJIXd{8##FLM&gv-bf8$RNh#<@>VGKhAAzN{rvV z9dme3R32pTK#M_UjY3LI`{c-xoTe97@Pt9IDTQd}jTp#1anTUgx6q%8%y)^ePJHP- z{^Vqnnc9ZBuXXZTCIlE8TS5wyoMz+Z`&c#HjG8hsy3f(=5bEo&F0A!RAp;3QP5n$L z1KVs%?LfrcomZpwS3?7VL146Sl>3kFNMd5O0(`S>tmh88o4cn)rSed2g)P3(9b$qGccs>=^t z!CsE&4Uww@DJ3!EpmcK1k)EIHvuh0oq08c;*uc*irbM!~axN3~eNz@{vYEsS*o|A9^fNLNWFnE(80rxszGM1bsjPgwm$ zB4;X^c>P)LBfX;*OR8P^(_Hc1n1binI15t>Rn^Py( zfzgS8c=0+t+)KgHr|@T;6bpFQD~1lpzNKE&r6EYq^QCBbMu6mOYc9Hi0c*(0(b~?o z92v2&*1z$_>;?t5H^@?&5bBHpoFu5K3&jW$diikc+?~c={2-uo`x+KB+h}gsM`kBQAb>9vAS;SD+1bMdA_)3Q9 z{rYF5g|wWeqZ!95)7oFFjv;_Wxt!{(fOO2knabedbb$;H!0Ov1vp%0+Uw$zBRNYnw zI_=74>|NVIp(2EQcJbOJd}Vi+nRR(VvBML<5iBC(>0X49UGpHVD;jBA60;s?rQv z2~+D4u2$wPHwGi>>8(5F>8HBDnN`^sfD^DmO3U5_upwW)k%pPG*rgy)aJ*6Aw3+0y z%1=zK*`2PA@!jZnZHAb}O79K$9M$Bn1Km9GjL*X^0zBy+yYIGc(`{p=^56i5~H37vhFV;eSqMY+T+hsFAGV+a? zZ(eJNhE1=zb${b!=e8;Qx%9zq?#6DnahP#iMI0Vuu0!kaE{>O8peG(vN;n-|4U{-& z2O+H<0qpJ)55I-Uog9Y*B#7tf;a!-M25oz^)`xK@*~LA&!@d^Ycv_gL`7i`xwo>&S+b zfO)EKvda$CgMw0$`)-a)uhO~w)BVSLG6qC!-hQmmqGaKJA2-H80bM%&Fk_*84Oil9vlrHhLu_S6W? zT2x(Y%xm9D%<**1bA!dX?M%>8*rC`HS6BMKu=ZAAZLQtj_o^YKKq)O0FU4Bi9a5a) z?(QxLE}_Mp;_mM5)?&dexNC5C2=Hb-`&-Xi-S2*`Zy&t#XdWb2=Dah;E#o)F_z&*B zvqAxXBS_cyd3uKNey*!@+GauU%DYlOON~P zmHnMI=1Kh2k9V!<7a{yx`Mnwo$1$8Go`fo&Wbdc{lx^jQ@Oy-L89T z|Bf>EN(FbW2C>}|p}rXvNJNX3F)*^R@5rrtjhnh=6n^+sZ^kUFpqD)N#rg$AbWIij zx*kSuv^LSjX!r8ppRXKEFbo+b=q{U@tPHi=zSd>v@OaFclp!W zJvb9(VB=of=O_%JlYLru+#@X@lww#=z85Z17;(2Xk%oRH?1$4D<6in>aQamvZe$^ykeu zvaZ{!l{RHrsAcCHo$L05T@G@ohtS(;Kw{DZe*^<6%SNUDP~wz6p{%Dpu6j9tM}Ve; zEjMSeki7GofY^V@yGj!TZNy2CV~7|sJ0|wBkSzZ^il8$%u*b#K)!y~I`M8}Q<+Tr* zVc780%B~vx2Uc_I!oXtuC7YZT^*`B3o zb#!))RNZFQ&%}MGCHv=YIt#3pVf0LesMW}HDi|~JU^4%ahrfkpEwAa}{kf?isef1>#ws3<)OzEyWR|9}9NvGoXT3UeV^P_u2giqRf zre8>+wY%SDdtN_A#~*p@uRMTQnBkRG_cvbE+BpBM-Ln|Zr}>OpBgB>{;37%K7|U{2 zP*uCWx|`-3vZt7q^Z>N|H8C9;Y7x`TYr9D~8zL~3bqn1LkVQQFHf$vAHYsqhDmaF_ z1RD|5@w$Dv?lZ_nC?|D_E2(xWZ{mYf{I&7@x?JsIyohc}2pfG5yR`**JtvjD+9Umi zR{l?f<{q&Ji15H_i}PmBwB>GzA4ol{oXbFC=6|nr8X+We_rmV;w5$&hr+A2Igag8i zmMJl^F*>fQ?q>2aRmQZhV~V*>YdDqnXVVMISr90z zY*etHR_S-Prn{@#4>7QMo^oaW^COx(wzEgGQx_!LztnH+Gk3f&P($A*PGW+?+*y8^ zyhm8^141-PAwV!NuY?O$08=yh?MyC+GNxrFV9l*EZzjO-xJ<2CqoVZ;QPmsY{W}x? zr>S(jr_^q*P*Y}jd`f*VCn3#K`Ok;`=O+bG^a&Mn9g8(;rL~I7?Q21SuLW5p^JIJn zllmGgTZ~cLUuQj-={PhSb3>`Fx)$DVwJQNrVIo(kS9V7+I$??<)D}>jFd_gV0Ns__ zzad@ToCh+j&@_zC`R?+Xb<;-l%F@w(1n;+nij{yetm>keJ4xsEq&8Ky((>$AUEv-% z&SO>R?6fQOV>pZ>iVCbg1euq7xLeuGWc8azNqc5`+<`fu=3;w=q^%~G%xyJ{Uz}DP z#aU8fLC8LNYoFMNHod@uK&x6ux}vorisp))uD95{4j%+cEs6P(B)n9|lnmRrx@EH` z^c91IN-6kyWc98m4;Uw>xd;n|$}E9|wS`krE0ybb?4#}SyXu9y6M1y_Twwaz#)4o< z4lrA+7J{8ge>1-3eP}i3Cv{9UvuM*gxjq|AClZ{N!M!0tiDkMO-znNlxE%&b5p00W zwSMF8fs{i^=44aB=~}9bnaa+`EO!jj0m=TOTs+>bSTFitjI%hO&8FnLtbSL$UcEBd zTrSqdCnn+^8=eoi6acH?@3+(zcfyJ*cN-BWgWw{FKC~p=-$+T5HI^yoB+XGX@Y@nZqsJ9@?!cVouwatzKSRd6nv`dV(0C* z$k5t@%QK?<@LtOD>oE~#^>+Kfjo#VICHRWIsJ2f1qRe7b#A>CjYUO@*pOWkrK5;5C z^X&KkrFxI)Hx4z1m{bq_=7C>%V$t&0&*|kfMCSi+VDG6mtbphLgx61-bDIi z`IJw{MbmB$7cA^wj%CK1^vIYuwA0x*$#Ak+7D`RxWnR;`iAC(inlQt_zk1&}YB<-r za5L5UcJPKL(^M;cD~TsU?{N7jBSgn&E1R8zJKQT!jN~P3zg%;s(u(Y}>99Rzbs7vR z(zoxn?%71I*>wOyu72!htV-^m__N{pzgMR&3W!3Tlk&6xRN{f=aiM8V^mUSDx=FIz zE6N;Ac4U5DLH!%cnyh7?2>ZKUo9EAKIu_%^cE?caO0T1aBJpOlTs((t8CjMaBYq5* zo>ZyzedQJCDvI@J<&Qga+i8UHc35*bQDmet&@Gf2r3M>J2g|DCCP^?^K+M2oiH}3+ zJF2(h%~_?7YbO-?ZB`nWVl|f_1r^AUj(PYl~gJG_mw#@go@>wdimxJoPX2tIv)Zc>BV=Xg8CWC2V)O_k7|88tw+R z@Fv@g;?wO1+Vlt!SvP=|K1ExSjG2OmG7Z46xC|pD)%ywA*q*nh>lu;u1@sk-qQfhDTYJEn<2b>d5Pf(;6Z1*-bmPudy$dW=h{AD|Jt1HU z;C~b#dwj`ZIxwF#e6P)9NuYjMD(YjY16nIBq@96%U!>9P{+p)a}g45#YG=mH>H5YbY!^)P%z(}4%y zr_;i1NJc*?(~A7JKm6$#`h=3*BBh(u2QwO%p0h=&tsaWgNr^km9*jiH9XChcU)Eo< z$#TEi7Sro-i@WFZ<_!UOQc4^5&yTE~O;dP)M*ScJrjRPrO~^if^w%d#4n)p~42A?* zfqg{}Y-2jE>DXu6aqW>2x}hJ$&a$UtcBEWZ<*Q6vJ7CX~$C=ze4-SZ%0 zpEA{+lVwE5#=uXXj=6OS(Rw^+SgjJw97mLkbE^jCO1rnbk;LU#5jZX}bp-;kGD+x6 z4^BKhkd``X8fBTNY)K`(q(oGk=>6*cU~M00)bIarPNI4`3HfRSo2{rh7m?)D1g?wa zrk!MsbdH?H2eDs*&q0LxhIS&A{29jl910s! zmZdegL|69(!|98$>1x{D-qxR&0~4N9YP`l89`m-`;UGtWW+sgLaS**{EMf6mwd9II zb^}8#6r;U3+#LBkVJ~Qcn(gT^rF%{9LAH^+2K1PN$zO!8w}ds{-Da>Qk-!-A+>cOs z>#kphx7@N5WJ$)I&H%?hA=SF5>>LGi^?&X|McR1ob6Y4uR21st-<{d-vilVD#D3Yc z-`|Diz$U39MkM5T(9>U5ND`+C4;x_7D3e(svo~AOk~zNoZmuTuV4oDMQ<+@tw{)HY z~5_&}%a%OQae`aS{lL$xlJ}UCp(Za^g7>(iaWCJ=JEOH2pSXO?rEwZqX?v0LM-kzXpX{1iNj8NrM zmn>@nu@VIBI*5 zvg#ujmc4H@9>u`3EHY}swW)wgP{7)|6I2F<1u2Ug>QJH005h;qB4a6${1I5ndCD>kGl-%e-uIIU5Kc<^rpC>=J`gs(I zs@BxjS9x3!k1 zT9#{;?9L*iU^3_pR|q)hUa}&8*TY(aM zhT==T7M5~0pJ^1}`rvujiX4V?i*94xVZASb9GYH(Kzk{BMjRz2#dbL}G*y@(#yZ5@ z-P`1t@C%*klvaR*>yp7}%2eK)k(UrwmBZ3Vfkup!D`SplXD!hnk*!ZK64I{j&i}{_ zLt62^!L|Z0U4`@CtvM?H!QXaRW9^t$Q1f(qJ)j+0R6G2S^x;Jz{~_VK zq5w7T#(fD{X7F-nxg|z)jCs}~Iy9kDk5p$CO|7lKEV6u2cBpDyjsBg+*DXAjabs%Vi6D$W3uMtZP_%f3YTY(H*;w zp*6GQ#W{IHYS?yc^Vi~4%IZcj25(-?wbo-#el@idWE`oWhnlICl+=)VRY0wI$Q+|H zW?l$IY{h*au9Gy4%$k`Ib#%{jY_pqKsqX7S(X~E!&*y=$07l$ie=2xptq28(j z{Sv((>O;MpeEX+~8Q`T(XP()QexhDCFP$Aeg=8uXu6u8r`8y;Fa6v1ywhZ{DNo_Z# z3~k1se`Cnbo|s^ZecYGU^7A)pwb%07KVi2i&n7;a7Ilfn$%8aRS6nfoSC-ljrl8d_{kRtzJJ8eYgg->( zJHK_gG2@OFRJ6*l!&=T>b6FSp=90$!Di*H)YbQb03~+93L*)4)ZN8H_VoVgKtjX`n zwK7&El8emqdtEVlpWx2apEbp^)9)}w&!ZgwWg%d-_5699rey~@YsIVA#JLS`e&zY( z6?*B}ywtmnGEJD7}}(8%$26wE6)Yx|<*Dxa~k# z;?OO_StJyDQbW&L>VWmMr#s?%<8Z87ndK5AYrT?!ROLI?=t8)#f0qRp^1Wa#odq9B zHW04Yndj4|0R1)bNceLyB}lNDfGuByE-luuO#oEBi3mRb5j`DRw1FOLh|hdgRA5+ET+q{I<*@u0oqN5uma)pB_m-@T$$n#Ano!oZOGhW= z3;gr;bUndgj{JcwHdOXltffcV=MHMHZUb~2ZMlO!GKX#0%Kp$U+-B2N{Z;m^g%zai zSI=tFwEReTg;>PzDF9fhWj=A@f={);#w0DO6mc6il2qJ|Op%Z7619Fc{xIdMvgeLI zIYdFyw(<7AEhO=;ByT`AG>d4Z4Otf*^%^^erAB~_KN61Jku`2h@3-T0kfo2eE{bJJaLnzL5vP`A*ow?Ff)ArX)EA-^v{n@j| z=}V%>AQL!pDEZ7&bLDVHt$@SxL@-HwI-si(+qAE?3EHHKsi7Gx-bd@X;5sJHP9LE+ znx)QrVe%oFLpUqvXoGJXu!&l!Az;Lw$002?G$BQwl<{qfg!JM8uI?iJzP& zGWu2i>a)^5*8Gadv}6hEcig?$ui&NjoZVhns{p@BdW-=sFr?J`(QMkk2N;3K&p%B; zYz<-evsU4}0f$g*K-j4plUs{ief)NAE-(jvdlB(f<|p^%J~*&WW&6(p@Yi%xTrY^2U4}(j*NFQedl^ylQ<+l zYPkEV4E9GlBEN!vZKdga0hF_$!aEac>%{cdB-)KTjF;dGt^P8J;dwT+;V4b2Z8=)# zXF_7=c1&+web%Qef02^Oh9p%sjaN?Fm_XJ-Zm zD&=}Y$Ilk7C!YGJ%aUE*ZSJFnQH{h6#;L}SuSI?i1>fT3xi-sd{gAY=col$M1YjS2 z-`#cZ%(Z;w@nh^PZR56sRp!1TWsyfFI{$R9&cUhu1}80I2{MDcW$)wuq!2P32Ny4Q zx$FE&WI>#;pgHC|PAFP$>qp?Xk=JE^ewORe`nmdi&T*Wbb~7wgGlB75)JB~VhlC-l z!$@YDT?l~7gWNJ;czDxgLy+Y7+w;lW{SoxIea@7(}b5CrO%;^(g zQrD#wBPqI%b(vB&B#0_jsR8r_n@|z3OT(%(&t|TTIUAiAnhI+R$>`62wV*s))n8o0 zUCFQ7nXu>>VilJesH`-#T<=-Uyi`fKGBHlpB><&{MATt_*{vYo-isVUZo%>G)j?Nx zUYj~Cg$R*~%biK9IbHk_|LzEZKUZQW72<@#F)TT@NAOSr`a5QEPS?Fm=R+iKbYnCwkr0)c z#EXrtQ+iVR11Nlp4W++Ls%ztUFKTzx9=M!l@uwsZx~2?PlLPGxjZd^rtt)NFRy=l| zf%uT@mW%RtYV}bW;JQ*5n1|B86Egd_|BH~V@%%=}w8^dt~sJkcCrOgh3p6CrwbrCLJk;>JQx-#!vSH$HgYxGuNhkVrmny3?#1T=1 z{61vAJqI7tj@*sB;iVITpK+9Kh_~jUyZ#+L|L=DN&#+@kG$#j~O>*IArQ_|&^DBtn zwn-d{RDvc$Mhk39lT+ttq_6T^#}49lq|z6#L5A@n6X6?!l8V-I+PBTG1p_7h`jT~= zrMG(Y>U-$FVy_8|#x&zCmd6hMj;khu3io|Xq@NMBj=z~YCDOP+d(`#BD)GTR;tuL= zr!~BEOhdpMxaesYL-CD^d!H9c3vW!GUC2++3L>nikB4@2u#~~EW2qQ0q;5C~Qbs^z z<*?2?4FElh^JYMZI{<^cz;Vb&L~-YcI>};?qxgDEW84t_ z++TOGY=gmaSAw)>x2UiVu?U2xb8ig7HVka9f@5xh)^m&74~JQj)(<6FePNBbv%CT* zV-9NmBkRk_FzhwGV-+sZAlSgW2*3z@mek>Z+zYNaydjy7$PnG-8DX;i5it?+&){sJ zMzs=L6v{SAeKe*~{0R>_fNa;s{I!MPRy-QO{Q(omT(e zc0zLY&Lw5G)Q7Sx^B#CN0YD&U=d26vp5vqlbnggv z9`Ta)pPBznvLtn2A=-FO07}rF2OrB4oW;|r{TD)2uvC#Aw8!rsu;lvf!TfQvyYZ2% zPv!R66^7RR&sUV;2V#&Z%F{RDSPz?99(N$Z7j9qG?*n8^P8X-4<+gw5Y(zSF0OlWT zDUvZv2p&@?=kYppJkg5Xsr{Q-_ef@4vAKS^k$}#=jZzdJl!2uP*GyUyl!Ws6^XxAT2Wap+b?yekrbN z5sjE0@_ILVwfoS!$;X0RM@He@%<6G#( zd`uhR=MmB`rq|;0#8=cE<8&Xn6NXJy+Fib-s77pUcABiP>PLtMA8)`H-;3>5`w35NB4vjWx%PenA>MjX0h@)mXI| zAiFSoKCj}@2kU*MH470qBN!ZXJ|xQlS+>xs0N=>IuC$=gEsxl2(Qzx|im;mx(?&Jh zl0|ckIS?RMPTNeWq2YuH=>wk?v{aA_l>B0ZpWt-w4V$914nJ~ zec0t$l035KaH;V%nKx}~&!!HB3c)O0Iz&%3LTp~Sn;~&5&-nbI%MpAA>jfJ%FExpaRFHREzD0m6S2yNy=1GAxxYRK7C;8r&4a_mYJjV%_LVJHc0jdZ%5* z+Y6#pXI)??+DGq;)vbwjv9-}3oK_XLPqr$H`dNPb@@h&)<+#dCopv1$PyJ=(e;#bi z{z0YHCJCa+aQ@-^gz9=%ZdN$~rRB&mt(_(^;!sP%*Buf1S3El5y;Nb^nGVC@5SYl;IQ4J zqKoy=jpv3yZv!y<|471aEV+o*-x>@SjpKY9N92rV5N?(XQa2jwmYvnf1(V1PB#Lgj zlELUCVi(}IJi*h4R`4P>Yqm>cKPOddw1E4?iP#{L)?w-P_HLFV!j6|Kzk@JHD)-i> zZYR|upzb!|E7=5`*(eOFR zzU*zD*V%pC`rBvuvSoSm$6Jl?V2p&zv<`ono~cO>`3FgPLYm!QY~>D_Ab0FYraHGi zN4LWxkM@r#zebii9KScuzGi6tUC7%mEEitN&PYP>D^o9lGm_|+e-;ICt7zE@Zcd!;@cJJ zX?th;Y44l2UHsh~@>5YDZLV)NHv~7=-6%j-fSYvUurDq#h5HnZl}yEFqHNQLo_tKg z?#_*Y6~B?#C67|UO)Zx(_rq#lcD#>(n}k|1mP|*K=yVdvh8hk$D=8eaZ zcMKhG2QiY8C`tmJa;tysV_M`kxz~=Ainhz-K)gYW!KX2uO zlw&*0mb5OqKAJ555ZQ(tRdJ6A-W7}4OFmKu;Jq$>fwf9V*ANF5@@6Co{;b_K{##XF zDLdPZbGGUhi8P*A6yOS{j|_JDvjtVy*Gr~GITQ1LEYnjD{j*F@F2pqU zp)4UgB`QVli;Nv9AQ>(2?og4vOVivL`ZkYN!`JkX#REUdr;NGhb60|b<|jlp>Z^YF zm&Pi6bkx?FH~rb9ctQ^WgN5EGuYmQEfz*;5PrQUXDyfCh|4qa2eg08>r~O%XaOaU$e=MK7 z39(5fDH~|iz&_o`e#L!(YFieZcfYO-w&8&!3e$i|eYU4gpN})=CM$CIWq!ZGotmP}!x;lerwORhU+368Gx+U*@|2q1rc}K8%(e+B zNyl|drJ}ueay(3c!|{XV7F9|`HL(nUpmWtz?9btGooq|@P?y9Td=E}HvC&8~W!7oI9GyJskwz{>EX_R4^5DiiOBz4QZ36gHL^XQDii z>?3zp2dRzcdmiUcI#}t)ryWB%amz!TO5i{kM+_=-4(nn#+M}`1K{Y1ZUhTFGlEOrK zUAipyFvFYgSTKVlCoZ_H(&4Ompp+)6)XU%BdiPOH7VG3D-m zdiJ2(=ddah)TOVzR zfBcDUz^i<#M>>ldv~jy37aF^;Asn?{w2;JJ)J`)ILBkL`h-ux~7-OfRokpqBWfbbfU0v zztY?QuDfqb3#KTl&VwI-1NJ--ro~yG(mL-H8ZTgof;7!u;4K=36xb8*W`#%#P(Wkd z%Jy;`&F*Sc{LGF<-NSOr`8@Qk!Wk>~U5#MpLl#x6p^}m(k)oY!Q&Xy;vy1n5SW?nn z#gER%n^3;;A%lnAVy;RMt~-ad>D7|(sif_&#S=bM8&fj3O`CCx27SxJv5*fVaV`uV z>6kbw@b51avjC-RoTgiA2a~eab6Mgj76LqZ>shbf(g$a-s zV`Hy&*tZN*s7K#n)9+13^obcFcqa2!KBCxbaLrJOSUYMT)a3e2ul#L>ypvK z+EgKxy`z_3AzJBYaT+zv5|91Nw11k7Jy&&6Q#dYqQJ$-$=SCR*uyVRJB12JtYHx*d zir8u&_z8H`0YyIrz1+QM&4poi9Dv+``>lS$lh@N6_{0xHCsz{dqfMz@YHq8hXIXo_ z$=mg-n3t5gy>o7d{3?7k3Ft)L+W^;>_4l5nyeIg8^a5rS{KP%0n~lwHVgoo%kKsE1 zJl*=*b$Od?t#6KxR62%5`IS1w&{kDEMlISl#nlzMqeLiZ5$Qn%ig%=(5}v+q+rZ0n z;vT#rd5G?;Y&2_omT=zh;6eD16<+$DH9DJR(k^tM*+$8gs2Y_;B{=pFiKk4+a)CW= zB-m(ug;a~@)UBtTIdVQ645{k2EbK0vpbf;HVhRcnlukaUrj${)X z!BSMiHX1#ZMLa*)y4feKXRI!dWSYj2Q*~5Z&z)l*a>apy@50yfr*71t)Y6|)!tJTc zOU7}i4Rc>+17i%}1sgbXh^7ljrpTY-8vpg*q9cRIReKP#0gGyam;l!GP0bgw_9dJK zH;lF*fddUg@Pnsd8pFL<^$QlL%WD3Bn&VNj)ks@PUkIh1PW2Dt;y0C*iMpz`o5Pqm zppkt$jJCFjQ}Zmk2oRMar!%uZ_FdEo+=D5b^3voCkVTz7)2n5Q*nq!yO9`8NBuV_O zr+CA*TG74aPKU~;*%IY?5V9&%(pGeCKCZu%%E!h^^7e8uMX9me%0g`9$-~?9P>RAe zbkW7&T5++n(=J6HM7JR(=S(qO=QnNe;0w()NhcZL8D*(l`J%T3h2Pt>=`oGk96zK) zdN8%_?{#iMp8xAQH;DEBs?JTm;-7VHTl4=@Z5wh#gc2-=?j_iCUN-1eGGmlL{sP{< zvo}e5L}m57I<}?a&!#Q1G(yc&$8Ld+Tm)+u$I@}Bb*M2a2)}RTuYZV4kxTWtE_8HP z=LXIq&>EEiH6$XNsSG|&)RiEpSr8h#Nm%3V6Ok_i46!uK_2DmwVnGkSK}xNkfp*gOWGwWwNGj)O0`Otpnchew4PAu)-z)R~B=3lPvXIk1~ z_22uH?jxjL4LKfaqwXSo<$065G`#%V890eoau#`HlO#^Hpup9tc`7|q6L)7)5o3=w3BOVk@!%r@m)OY(OoW70-|0T4UKc zvx!5>WN6(d%7=h3!sauu$#6hN>Je6)QGSVZsWegQfFHk^WH1HkNIsc5( zqS2-Cz*Ga;wDR?Y4cF(RrX6p4kf^F1f7#}qWHa`} z0^k3+$6;29)6MX4vOPYTu(z?#P3I0JiA^zA8syk$$yEaF9*Kte7!&?^Xm!rz4Zm|| z7ZZ#y@PxCQETs>@dO_R#d?(O`3QouhlT6_vk=(AXe|I&a?aW9bI+spC!5*)G-u5*lK$3Y(!mcn!YQ&rgw8c9A^gA?Bs;pfJ8x)c9I zUUrA?Au^3DHp8?w{f~);roWE*D;Jzv6MY|-mpmb2@>^bnUPCt2KYT~sKV)Ql^v(!; zL5m_D`4J`mo5Eq&OJG4p;8xJZIhbk}m8!tByTi4BN+IT>$Oohx6s*svo zDIU#cTcr0yT3EQT@ol7H1V%O$NC?eqxJRV&=7vM9ZbzyTd$AD_A!n!QJjy#FtKN2I zkK8VgtFVSLF%zDYq_%%^y9&#B%#L89?2TV2aTv$OsHCbZvO$fP9L$%zE`loE%BJ_R z%?1(PxS?u#aZ32d*7HQo+;)UKUjRgYSIh^c>f)fv=ch0v`Z0WtR}An6u(u;Q;PLxC z3=ynIvhPqC%sl>j%CDKaM&0~%t^WmYx(AvNxb=MV+1EhzX^C)*B z+$JE(gr-hx{9wKk=Okzc#wPX#SN!2uN069!r1d>$vaM5XU{e7;elJ?cz>iTDZ7a$=ud5kzP6&kT#e&S=U}s5CuV< zjbmTibnPUHm=hG1=nX?01l7t8Y%820_L2fuTk$>(wr$2E2a1i3g1DD0l@TQdpRI_H z&VF`a)l@a7nK_ckqO*Qge;|x#t!iEgcpppWZo^8G=JD>%vz}=q@n!+fEXtMH|31B~ zKc8gtUhl&ueQgdEp$t*xmI*WHSfE~NWv)`A3SNb_L?%}bciH23rTP?!D?3p(tJ5w znJ5<|g;4O(dMifg=F1`Z_A96IkGXYzfxWIUs4X`d44)PcjtQnV?5K~*^KeRvNEuqk ztTQ?S$yU1z6>2ozc&A>`6R;~+6nCq? zn9UyBFZYOb!&m5Os18yZ(l4bG76t==Tqn!Z>V%iip(Z27RqJ?h9_bmeNl&c8wwXW} zipU!kt9@Qo0^dtN{`*o8;5Tm7OVGpbPG<{&v@0C@0<>)!Qf|fC$<{J(ZBNuxXS~g) zS}}!g7iF?PkPz7f_QtdfkQ8-FR0go@E}Fh4G+`hUpg$oQHeAyDJegFA zpG$u!RD963t+)8fr7*;Lmo5prKmS4T0(=BgavXE1&%g;c9+GDhbG4QaGJ?PSD;I!Z zt7$I56su5u@U0U=!iaZtrw(2Lp#L;gL({(U2!YCO;mP}BKfx%9L&mtN11J6q>$oZy8m_TP{G_gx_^fuD;0 zi_>i7GefmAADs}t$|Su{HOj&kESfZKGD$x(XuMgIgOu3Feq7dv8ZHFN%#1ke2oJ{x z?>n3maQ}Z=$D3RE*-SSy#G=5ilMWk28BL(_7k;Y%nBP?8$Qd+aAiVpn)_=NEc z$CAzN0rGCc;(ggqRSwf?>jQt5t7Z|YHtwH5|Ikqa*X!n7+NBlv)lmCoCZ(1r$~IG4 zew$9$J`azQrJjJuZUsA!?uAy$t-gHsoxXG_NyO|tusiixBkkbX$!2L?!Ds7T$0yP# zM^K*%f8!%^i+-2-th~z`jY+T2TL(hk7;rpCH!Ms_ZQC$bS#iFVyZ?}mtq!C3Tduu) z6Y3&~QMXt-A;n%@czRPvW?-+_ZJUb(4Ue(OY89S=w|>e)!EvCJhAf>ryC z7TryTf;Uln&R?pu{^Ng$rEU<_F}qNKGG>k%%bM~QCqCLP6_q8pey_;&atPTg&yv<4 zpC_xPHSLv}?RQrsUM*}+U)|FM(zTac;9b|7i9j>-k^=nJ6s_k=)rh8awh*Nu3IN&? zBS1;wg<@*UBo14?bZeU*#gH3oG($MCJ?&lhLsNQ!^bLhslvf59}lhz4cvoVgT`L zcO+Xb!TdOmHuFMg>Z1y61D^0+r$?xrPoYT2Y#}{ZyNy0(2Dt9udsVG?fg0Mr_Lbh$ zHTr)gfhXeWyfRDb(u*HGeQj3R^g1?7oLWh4vBbDu_rNR80z5=;P z?Qwr8r;jfBG~g{?x9-m=|FrwLs5aNn@@ZOV&Nx;qovs+#x_xVW^y-wxE zU+j7ZryW4AU03<5&H(vO;-x%)$aB=?t5+jkb1{q0 zko4Ww15Ad(jR=X27Elg`d{rsOtEGjWdICAIoxk-)ENxZ48%tr+o=*aj)L&YQRp*gT zoDGm(^y;v;-_z^bNPNJxG)FjK;>k^VLzkmuGiXm|Gt*U*Q=q7BDvh|74^zCf^`c^O=Nx_C?p03($(tcCqc7cze=hUL6`T=n=cKp+fls7bJV8 zk}Tx%zG;m7ju8O&e3JgS-Bf^RHhbO}2=IWDbFev=t+1Gl1-yFtll)*0*JUF&z3*bm zrCtNDIhL}L%JpjvZgs@$yK}TC?Xve}m^i{<-u=;Jw#e`%UHOoISde6(62aVZJ#*jb zBxScKJ4qTs2t3x%}>nngmAXa2b1=9NxxEuEw@uB*6y$vdq9$R9chdnGml zb5}%Ig)E_ZO+yI-F%Rr@fGbu0g%}HK;*vM)8tBBr(3P&NT*BLtwhs_P!du{QdurvTtrOmC? z6e0b=7OIm*L`p|Nnth2oj7{*+{Tp$&q|ysedEx__ZYz<%5yWQ9H#Z4Kc>tTLy$%RT9k4HW+S#!(6|**Ba;`b@{umpHA2U;SmV zxiLwGdgFoAYG6!qS>RQ_qN~sikKL$Ga^e{V3y{gJ0Sv_mz8n)J+3cE}! zR)fcj55LdUVgwQjr8lM5d>yHvoYMasmUv2bwA4!CrHRsN3RrE@(+Z8X#_ILE;vM!O z(}VDYsJ8)L;9nYbML*klgVP&7KcZGFwC^kHmT=-JdpzVFKl?5@s1*EZNMqCPV|9i; z{t{!@tgKEDnE?gO;{z&0)^r_O!1dj}Yy}C9ntsm7B9>wZ)s$3wu%!IOXQMyJ7r{tj z$d2|9|INHm3uo>rqaXvUDYBLE@rpm4mS0A~|5^Gi>HEt36kKr01j~1awkvz$_b|OX zO|+Y}K!Id|Y`ljxY}N#}cv&Z-xZ5&?dCB{VsQU{1J&1&EZ4@3^;34LS{;6Z3l?EJN za^1rWd?URuUaQ8;a6Vbmi*jkI-AAG7r$6u6`_2XGZ8Kd*%45KF$NY1!MBUoLay$)f zF2!i5TmZ3Hu3tq4^ZeJI8wC8auIUaYZpE=x|&Wv^Kl!Vm8 zg{Ke5f*xQ?%r55XmIv>D@_9&E!1iQ!r)5LU@))KW3LTt9xZ0qC2 z^FJy#u`lD^G}`*=e9330Lzd*nLkI^9)+ z*wZd4uq#r4%KH+B02MqSqdlk+e63}+0=qrVoN^MpDXzP(-NADZt`F4ANI3ihKTkZ>E@m_oO4HCsf=nOhuHgY= z$oJbGPzP>D>(I(8;fJq|kf3M#3rzu_pASCYwHh3r#$Uc#Yo2*)X-xkV^8M$nvA5A{bBJVg;_FrLgzE}Sg zWNV7F1P%Dv>wLYp&qlr>roTTdYv6mSznze`?`cd)Qtnh5Tm?W%r!QwQ{vs==S~A!k ztKH~mR!R3Ec}99Ka3)DnVl!5EL^Qe>&%+We{Qiz<>7Ew{`FJ2)&10_h=MSFS&dhen1Rx>Gi@cL%nQV3)$umT&org;KW5jV6$&tS# zgPxJr-rz>@m)$#bgW)%cw8N~#N|E@U=ow)FqX|eQTn~tCyPgY+gq_D3#AelV&ohsP z(-W$5(|@RgI}htryEQHcvufp`-P%7%g?SmaZirkv^_WGG5x{H^^H0_3=H`ashcZ{n zGB)G$FKg*Ri!mbmkb#`6;^irkw!VgMMJ4UOMtb@VL(7gZKL(yUcPu@~Tu;GU8IQ4! zU)sDzfN9!4F$^l{1w<5;u9#^wFA)J@MyW-vgY(bQ|B&9l2hg{xp=SXKhONut?^);%x}w zy|rf+)KmKDE{8NCi(2*?NL`H<%U4Ejd?^O$n+}FVqUJo_rlsm7O{d6&BTR5N1(n|V zsUb4{``UsP?ecGOPHFGvHcG@InZognn&yFo)~G*8Q1dFlwrF$n7Yr;`@x5W?jo>;z zfXzB$KXx{X|16ojd1`qE_zI04U_xk_G~QQ@5V!BKv0h^_1W{5 zZ*tbiSkkzzB~k4`OR0vK`|kvyBNm}w%I(v#b_9BX1C3C_nbPRE;uBjOi`ib-80ln< zaG2}_s!_TIeRHA!-}$X7UQbo0#lG`B{d=bv2{&j~{Vdl$xD{1&TwDwGFa1~{o(#hT zPxbd7$pcbRDt1Cx)w!9^_^zC2*xX<7K|C7h+YI0@U*8mcpa@-6a!&WOP`%8JDf#R- zG!5>|st;6Y{2t=sKbPkeaTv?EIb}o4-uPyl^lDJRl(DBm#j>l|%v5=Vdy4c^ORKkc zAMnF25mSl+;|xRQ&v_ET1bk^VRd|kx+ah0^RV{uI?!)v<@+h*^{pEayLgu2P!m{S! z+tFcqm+YOVmcb8UE><4$4x!{$yUGt4?X=V<_dlFC=eJH4vwhlCalumbcB~v$Q?7TA zH8*v4vATU(P-16Q&ah4N?P0sT#!PN^#iPiCZW@OPGw{9u^aAPnKE{DxFQ>*TncX_x z4NM5=WlDYe5r+^PX2B_Ltsp)(68K}nxU@1v7n#^Q)P!hdp%uJ8bsK#gfGUAo|Mpmf zl|2KViDEJ7(*b3v=RXtR=;A}ZJ>9Opx~RQ#2PFOYeF4Y5s%arb<36!Lg;SbKSQWVB z1&vYd7&Bic&Dp;<>H91?GEaWD=-c4kXBV%WZc)R8H>GUYheTLnc>&3qETJY#ov1Bq zmNG^e#U*(DwFAX7MbU2yG8rfLw%O=`!ZLKbdMf*QRY&dSMAyA+mUD2_;58O%hB1^8 zZ;Ut`UVfgR2%lw{)5~xy%|MO8wm%{cbCT(6UNh*uzwK7_4&pYHs_&Qj>`#e${9N)p z^G{S5wH($friI_j13p>;1{AUjzpKH++#Oo`xsf$(%ucDk2Nfo$;?IoQFIa!|L>-A{ zSGTOr{a6Pe)+I2Nf6?v%&pEiZASwvnkzd_g&UY_~sVFKz^d`XWi4KEcj0vW~Rb8b> zwm?T1;Y?3gUsX{FH0R)usI5H=IRJwvwFFQ3v;*nshUh9x#fp5y0OYPg;X5X9raAY< z1%qj=I^PhfFr1usrn&S&@m*_P31_DOdRo&dTPG8{Q-YLKhEjM$`z=wJeU$utapX57 z=&zJGObL7skX>~Z3bU|_MK92VQ|*OK&zky)QZCo1L~4#vc|NX1m`^{zvHaw1K4#Hj zDxb=6XiD_v8}@+jEuwFy??1>#M`*VS99ikkWL;?6qE!-9mso%wSTQ?W5C|C(c%=qg z(Yv04WQYABWEHl|v*Tao=Mo~^_!5@=Sc4MySCTl{?;}58ThLm>nwl9d4yG)o^lA<& z??}oMzCeqN1F1578;-Il8Au?)-cla;^aOWccAX-acD@dL5KOASBe;6o+886yE48|j zr9w7W7Q{M(4ZH+6v6&r+>!_22yKJ!y1@aVZIiaR8PJms52WQ`+2X<{rIMa*bO_1jf z<|e&*S|&Din&fu=h@JnYs>lt~!Y#S7ux&nyMK~eict+oV(GFMWv?VJ4q{Zw9rPb+J z-M}Vd{@@M+dj?Ald>tXsXe_!-O2(}RrAjV?KOj*<8igAQ{k>c{Rh~?N-+(Od1Y?*9q0P`*-%W(tK^64*{zdOwA@oPMGi7PAkkRQ z9W~UeV0VP7Acm!ha8pPKE2C+y-Cp_ksH@rLZXvV-*rZJ<#0Nzc5sKYH^IfpywP|_E z1G_QiZlp`@c%MSrQ%r3w6$?9$lnjK@(UC7y8lp{{?Mc_G0Hk=E9&AZZ1Y<41?LL)J zX|UF6X(U3|HZdrl3NV$9EEdpL<&DtI$DLuLN6WG;eF^moX5E$@l(6Zqp2>a+nV#;v zUj4lKYPuP5UEpOob-pke{CU9|bM*>HH1vtAO+)?^QvOgQ_=7Q*2hmpe%Y~4kUK!e%PFvBmut*zS%`(#vim+Q{;XBb_%oHUOaXgC`-o!R(*5|Ph z@~7qnZ}{?`)Vc8Sl3j;E<$?NK8?S!oJ{1>;*J!2S^R{vGvLugc?O$=_Dkj&z@lRK; zPSK-)w$?DW#0j~eISDlANhBrH%~{gSqT>Z;I_L&?+EegG1`q7fZT);XYaXxra@9ad^4MN_{fyA(;NSqfa$38P=t%YzPT1c;KgL{`NY#$tb5LtJBQJs6vR zb@;-R9}zMH$zHCF?Sxf2vv{Qj-EKjheMh^QUY`IIHl} z&@OH!XRd;~VU!5Jbt3GSx^5d539RcdGSm)~H_sS$2;=@%)Kp9&E@KX4%@!5!pn0r?WQ9(M7NYOstib>NEz15-;bQTLi)(pz^zm#lR4a~ zm$C7l3HY0S_%j$%J$^e}cwux=i%4I9J!)~38=iwOh#X1JzW3;u{^(<}9nkyDgjM+md`w~EbmqXrnR_+5v z>aeOFbH(7hrfC1yueI`CcO?QYZJV&`AMiH>etE$gOJ%z?q<`|!(qwU9s_F%gC>*Va zC;27J^nXvoRzS;j)Uk02u?H&IIVY(i(dH%i{70vF6}Q%3u^6qKXo^q$2r;U>sF1Ve z*997x@V?9Q>vCY~-oD7j!S=H7#NOa=e|VF~`!m*JSfRBD?u+VPAwcWpH`f}2=`3f8;mDsd>gKc_uE7vzu%n(D~ahU)Xr z4s3%Kvr_tGzt6jaCr0Qv%yzgaOdjN*JCzvpqq~=;-zTgY!)2Vu#azwa+U}6?h>`t{ za9;AHoUFHt4rLP+DX*&SqtefccTL3Z)6Sl%7(YB-5mzmsXcBwNp?+$EvYAOxlU1H0 zND1VJp*6 zlX1BRF%tmU6^g~ot^)znUwAv@`Gw3dALroPE>ATwgUzoh#IBFF6d4q5iXNP{)JTA~p7&vh z{eWNNIOh$(=R4%di3p#P?EjmCeR1y1hT0SKa;tNkQ(k{qO#Yg@Ms0k2?#n!NH9Nwj zW0$MCx1JXQc|Hg1U!M2ORu|Y68}G>d1u6cOGR)4uI=3UGhs+3*(h>2rJiSS%+|#(% zxaU!ouP;P8A-3J>h0*Z&l=9WgPI{71vfty`go5;d5q9P%FEN6A zx6#-SE$$roNQMs_RbvQjlv4Lf4Ih7m?ICId2~nJ%f!@ugZOiJY=q34M^m=DNcTF>a zZ0Vi{(eS<_3F^gyqynAiet6wkr}4Y26>X~bYXS{B&ch%syf;noz#^U^uv z7Gp0QiYYZgXJY8vzzBJ53uUXJBt?v^%tS!m}ZMrgU*Hg-R8kHLRO<0Lcw3E z46};dn%oJJ$i(x~a~@jsElaMSET&%Aj@zp4N-O^tzQKV&qFgTYZlZNjXB4-<}nXp;+tbwb-{6CbX&A z_vw~%i~dpXKgw{L3=-l%Y9XF9ds3U8agT_ofE$qPMcmJ)_V|$J-}vjr_F6%?l32G9 z%J41NCWLed!%bxkv2Nj4q6ugIg4rIHZdJ8^(JzI)q%hejItY(KbJ*7MyDMl^vVUQ` z`Ce{8quc}>yYyMnQ_g*((r0OjrBfA-E%8@#RCK!Jdi-z2H$sK3=adMntZ%Q@bgvZg zS*TG?hz68(Sq)&xgj z%P^fGRwBgFW9#4h6;j8$igd3+ufX}l22In`ScT)jYA7h{byE^1W?MkZifWIeN&t8K zscXS}$&3J&UiUTQ7_B^(RmQ}g}f8&+eXs_Mws_5Bl^JA3!E<{{kA z8;qp{s)Dht>IW(#yJ$r^D*L!YycQMg=P!j6>M9yH&f-7uoLr1(W9@l8mqQ+iw0{=0 zkGR4jLECh`aVlz=2Cya?yqn`9o8-jWk$n?NxkNTUA9UBn4HAD0Td^LkRgKe25 zS7p@+0Hm%kbD7Jv%y%w$_-m5%hmr!5BsTis356E52&wMM!o!oawH0y7MGFUzs)Kr| zM!~v(I&6tyTFtx$(R}Hg(3@(WHI3h&zaKrlt2`urIDSMXb!~ac8?nN)W>tiuMl@*y z7rGcKJZRIKJbSxT|545*UXGqQ#kZI{d!THlitW&?!F|s#YL~gn{hCi)WLaYPyz$sD z>e$ZW`R=B}jHG|qrdTkN?+7i&%%?q0%Jsc@oBZ>}^+}r&kz}jX&L4!?(VVCJzA7u+&C!*zzmm)*5O!$V8wD*5REyey{tK~6|7T() z#J_6!83t@-#NV9CdhRX4pA;zgYDHrIcq+)GKcN65R~-(xsz}!ud9-!08sYkpH4*9= z%gRg3r&e7Q(f*)5k~kF}D5F(bCRn+rLXlAEXD7yCs1HDbiECX42okgB3xX2S^nh6r zM0RmsDxoVqyR>TOisY&dI5POoH}*R2xkf44vPeioK&f}HKTs!9xW*|su6vY(j^n2; zcNN>zIb7ZMl&(}11#eBhnYwphbL1-AiTz}ag$r9q#$Z%x$5HYqqu!lm371l|ORf)u zgr#}%+!u*W>gp1e!e!IgRts?;Kl$?Sijc%-kWF^s%7}avYu&uQHAK;V1+7IJDs_|4 zC@+3KtF7HgMgLY$yq)n#LwD*O=6Y``3 zeIA0tOs%oAA)Fbl7Axr*ltuJ&nh6O!V93dZ7N$#uHecLTDp9*1D7(&)Dn7v028s^Lo zbWoQz%)0KZb=vQM61>@;QmDG09i$fL_x}b^KXB@G0y2AoLiD`GW3+5lh$`j+w3@t` zHylBvCDhs^&CSPBi!#-Ep~D4+6;*VjqSsHlnJ_?_?7mjMfJ8gN2ehg7FE_S zaQo}OdK~K-tiCpWk+v-Ro$&`-ME{vcKXMD1g_rqrT{3nPP7|&cU3VX}(zT~;2ay% zVQb=gBPre=|Mu0TVO?$47KAd-2@9+nfQX-eTSOdrcC!-0N2OYFw4Z8yZOQ8`g34Y&rVQZtE%W%AjFn0QbTe6Xn3@&*dlWP&{YbNa$_;Ei{dVw zr_b6KmL*N-3ZmDcx%GFea=TQdq83@u3q$u9!#2ND-p}=@+65MGZ=P*Tr_)x*<)DfN ze*g+y&S%oIDC*UB>^+m{3xmhJ(_Q?$A~3giX@3RisS@5I`F zHX9T3HQ?q^0AzB_Z%(fTKM(gO|MwA z1iWS3&ab4)KdKwe1>V&4siiOEW%H_EM zLmQ;VoiAA29n>xMzUDhmT%2(^JZzjvJxB5u3N@#c!nURD{_z!4p;R;#)` zMd_;$I}y+EjXsT0bq(ss?zHdZe&}c3)|VQ#G;(VdLNpfux75(Kr=8>=S~tQ1YX^X* zo3lBQ_c!0_tq5K_z)0|psDqsd-4Qo%+D~GbjUp*ISwFL-42Vvqv}Y@^4r9v5(KjT< z^q99z`DeDYVxF1846IE8kqa4S*8lF(tuIN)?pN1>N%hToP%lqmFK-AEjHe6(;TWdB z+)XTcOd`!jOeWh)SLDX&^Y+?gc7e$azx12ki`P7oIj`=yYn~Z3*Uw35!h}edA0~s? zK6h`SH1&9 zZl^dLx3;vxf-KZ)Y9=0rl$!J)qp1oXS}6u4(Wm;jnCa!rk#cVMbDmkeM}~iZ8gK6Z z8`N~cdpQtz#&$|j=au>^4yS+lTj^kr1n!*Y`-AM+i7$ICnL>d*M%c)f@b)UHCM_(Y6{KWb(rHf%* z(2-@xYQPW{%cG>QW<9hJWHsEljC6b6OkOs7!Fp?T=$Q`D9=>rt7W_gT9m2Vw+oiy@k#YdD*tR#HM>N3JopcQy_tAu0K ztuzU}1+_t8+Y9~xPNngqE^7eiWuIHf5CnEG*6dY8FF;P6LE4f^EKxMWo4{w=R8&2q zL~Pov!JIz(pM*t{WlTROb@@GcO>8wtSTwmINasfIXza1z1eQr#&RFo5ZopJ=^Qp4x z``NE^rwKC*r);8o2%^&WfktaW?w2`0#_Evb5jo~nC1-GKV_L@wto{VaKO-r?v_rxn zqnmW^mX_@!^;I{){0~$EGR(yBPKrBaiZAn3sV`jWCN0!I;B2XKfDgWZ1^X(pyXyN+y;z6JHX3!|* zNJtubVMz!`(ceqI_dFE&*~@sYaL*9nBj+K=EPUw!NxoZhtZr!0NlV{S|7}f>7=9yl zk&PkAIWT(92^+Vb6Kv;(6OB9>{N!ga^tHu3lyTpkDy+hrbG6?k{(fYz@kZ+LsTn&Q z8|0+DX-M7}t7MlVt+1VxmW_kFOs?U6erCB8D? ztTNQ#iJRoEpH2}cZmWw8M_<~g4P11yxb3C+wytoc^~8X>!+6eUM5m^bs3U$}(sD-s z1|V_>021ueWMw54i@*^VyKKcN^AdxDwiNaJ|umHL>j$>4XF>a1$t%^=qe6irsHwQg~qKS}deiR#@|Xyy79Ax+&%_mo{>` z|5+8l%U^-`r(fFog$XY&*ihn|3W8R|9F@e|e}aY)e?HqwfY&$w3sjtuJ%etfN7M}+ZvrDjg_%3-10zSs{0H|AH!$9KDPhNbN7KcZU=7r zSe>Blo$n`^tO)Cd6bQytV_Gpg%#9a#Yz)zOe{pDhubPzfcPybJ)GSNCCy7^~&&&St z6^Gj}>EP!Ui%DlJ2}`CSbh{0gV{1#kbMnUI-e!|QZ^cH2x(5cp$8HNK?YlSC4w86+ z(c43Yh5dpV6Dvg>LPIg``4UjBt7bIyZij7fl=3cM^KIn$nDrPH@}?t?|#Ctzzj@R8#>amZyu63xG()N(w$Kq$M|YQ)o) zq9z8zDYF>ZVcNSO|CwZ^vdM+m*D_9ZdTG{El{qkDB1uZ<=#BY!{%p@-2ARbvsle4F zZilsc?pslT@WjqGV<&uvg(sW*o?LYq)Yu;VHdM4DG1QEvM;yA*?Y8_L^KVih2N{K` zDd?c*zs#G`%!Ss^Z~W23gCqqHLx6kR@7Gz?hi#(f0AcI~z2#aYWK!=ApUT*!Uo4Jj z&mOGT#<`C6C)5wxoH(HGAH*btml8-fCgItmTg)4+nHwbMOqW!AD9pOt3nb6ubT@_$Q+U9NIOcFy1Yt9 z(gj7FFUecK=@jN|YKkUs&)}8Y=G|%EhrsVmkb+OD)cf$SPQklNh5sKc!I48K_N@#Q zXmmbz;_;E-rk@V)W(==n;Md`2ZhS5|s98ldmQ~0-;mr;!LBZmCmCCzo%H`T9!gr zm2I{lFW-8>Fu-M#)|kzsv%bomY7d4=`HkijURb2cibM1W^g0^#9zGH8Ubqk+g_74? zzi}zl@HlYEyU4QJ2s5*#P42*S+D8grlhrw6>#5b6-!X36jsgg15-PGrf$S6z0_HlD zk>!-Yq8)~XJ9OxR5Ua#4>U5F_SEd9gk5?xY3|e^Q6HsY%cp~`43*9nhlyn9xW+C9} z36QwYXD?nl&yyE~`AHqhaDfj; zKA#~Ny!Ds3;`H@RZ;vZJZ1D6u1P&QI3U}uNk6xS=TSFM*mk8} zgP4nh39j*I?Eo8JuTDGq3Lbn>XpLFm$G0}=JUD|gfb6fU)hc$W_S*z!v>tEkFOyaC6 zKe(SSJ`|xca;mji_UC|oS1spo#A}KNx!#d*==HkXx)+u-hWp<$!~-1Chfpo%p|!nL z4`x1MxU2P@w8UMoFkZ)|lCI~V+F~zOLV&HW^6C#uaaZt%r)t)DcEaP$-g#LX8k!m&8vyAN_FT?iMy7oW{Fjq4AfB`{X` z_V==}0gLGV*jOznEv?p&akDtu?*PokbcSQPyO!KZjhq)v5Py9>LIVfXQUNuP17v>7 zy(zw6Fi{RN``7yFe0Ve)^xAX7ENx6P7_C%^CTVQ2`;VPxcX=;~RW##bxY8_&ut&4#d!9Z)nAKSB-!s(~(eruFr8vg+v$d5A zQ`Bm~vV6Ra6s#(T^WXFyQNW5*%LDV#?lR&wRV#1sQ_Nyyu9n!KcvDUVll8KbHrI)JY~P8X3a44uLUbT=0SLw zez%F0z`SOSzqLFgcQWX69tkiIMGRR>hQWMQ?T=FKM1?7=7Z1$1G4HF$1)K@2>en$S|<@#QB4p)slN3Uhqnd(~DaTU$#^d?=G)DBrC+QLB|Rndpc?s=f7>0 z{_Y=MV|ZZ6{G`}y3CoNdd*s5t*hKXo)J~--yOSE34HLDnMis=(X6;vv*jWE}Mo9(7 YJqg1R=HZ7aAR&^JnEbnfH+nw*2fdP;*8l(j literal 0 HcmV?d00001 diff --git a/planning/planning_debug_tools/package.xml b/planning/planning_debug_tools/package.xml index deadcd54fffdd..14db1277cc02a 100644 --- a/planning/planning_debug_tools/package.xml +++ b/planning/planning_debug_tools/package.xml @@ -6,6 +6,7 @@ The planning_debug_tools package Takamasa Horibe Taiki Tanaka + Takayuki Murooka Apache License 2.0 Takamasa Horibe diff --git a/planning/planning_debug_tools/scripts/processing_time_checker.py b/planning/planning_debug_tools/scripts/processing_time_checker.py new file mode 100755 index 0000000000000..3b80ce4e5588f --- /dev/null +++ b/planning/planning_debug_tools/scripts/processing_time_checker.py @@ -0,0 +1,104 @@ +#!/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 +import os +import sys + +import rclpy +from rclpy.node import Node +from tier4_debug_msgs.msg import Float64Stamped + + +class ProcessingTimeSubscriber(Node): + def __init__(self, max_display_time=150, display_frequency=5.0): + super().__init__("processing_time_subscriber") + self.data_map = {} # {topic_name: data_value} + self.max_display_time = max_display_time + self.get_topic_list() + + # Timer to print data at given frequency + self.create_timer(1.0 / display_frequency, self.print_data) + + def get_topic_list(self): + # Get list of existing topics in the system + topic_list = self.get_topic_names_and_types() + + # Subscribe to topics with 'processing_time_ms' suffix + for topic, types in topic_list: + if topic.endswith("processing_time_ms"): + self.create_subscription( + Float64Stamped, topic, lambda msg, topic=topic: self.callback(msg, topic), 1 + ) + self.get_logger().info(f"Subscribed to {topic} | Type: {types}") + + def callback(self, msg, topic): + self.data_map[topic] = msg.data + + def print_data(self): + # Clear terminal + os.system("cls" if os.name == "nt" else "clear") + + if not self.data_map: + print("No topics available.") + return + + # Get the maximum topic name length for alignment + max_topic_length = max(map(len, self.data_map.keys())) + + # Generate the header based on the max_display_time + header_str = "topics".ljust(max_topic_length) + ":" + for i in range(0, self.max_display_time + 1, 20): + header_str += f" {i}ms".ljust(20) + + # Print the header + print(header_str) + print("-" * len(header_str)) + + # Print each topic's data + for topic, data in self.data_map.items(): + # Round the data to the third decimal place for display + data_rounded = round(data, 3) + # Calculate the number of bars to be displayed (clamped to max_display_time) + num_bars = int(min(data, self.max_display_time - 1)) + 1 + print(f"{topic.ljust(max_topic_length)}: {'|' * num_bars} ({data_rounded}ms)") + + +def main(args=None): + # Get the command line arguments before argparse processes them + cmd_args = sys.argv[1:] + + parser = argparse.ArgumentParser(description="Processing Time Subscriber Parameters") + parser.add_argument( + "-m", "--max_display_time", type=int, default=150, help="Maximum display time in ms" + ) + parser.add_argument( + "-f", "--display_frequency", type=float, default=5.0, help="Display frequency in Hz" + ) + args = parser.parse_args() + + rclpy.init(args=cmd_args) # Use the original command line arguments here + subscriber = ProcessingTimeSubscriber( + max_display_time=args.max_display_time, display_frequency=args.display_frequency + ) + rclpy.spin(subscriber) + subscriber.destroy_node() + rclpy.shutdown() + + +if __name__ == "__main__": + main() From fdbe64a470eca3c016b69501ed7a76bcd574a53e Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Mon, 23 Oct 2023 17:28:47 +0900 Subject: [PATCH 044/202] refactor(start_planner): guard for invalid lane id (#5376) Signed-off-by: kosuke55 --- .../src/scene_module/start_planner/start_planner_module.cpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp index 6b56c88eb942a..62f3dbfe191ac 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp @@ -639,9 +639,7 @@ lanelet::ConstLanelets StartPlannerModule::getPathRoadLanes(const PathWithLaneId lanelet::ConstLanelets path_lanes; path_lanes.reserve(lane_ids.size()); for (const auto & id : lane_ids) { - if (id != lanelet::InvalId) { - path_lanes.push_back(lanelet_layer.get(id)); - } + path_lanes.push_back(lanelet_layer.get(id)); } return path_lanes; From 69813cbc879b7cac763ffd7415a346ec2a88441d Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Mon, 23 Oct 2023 20:27:52 +0900 Subject: [PATCH 045/202] feat(duplicated_node_checker): add duplicated node names to msg (#5382) * add duplicated node names to msg Signed-off-by: kyoichi-sugahara * align with launcher repository Signed-off-by: kyoichi-sugahara --------- Signed-off-by: kyoichi-sugahara --- .../config/duplicated_node_checker.param.yaml | 1 + .../duplicated_node_checker_core.hpp | 1 + .../src/duplicated_node_checker_core.cpp | 9 ++++++++- .../system_error_monitor.planning_simulation.param.yaml | 1 + 4 files changed, 11 insertions(+), 1 deletion(-) diff --git a/system/duplicated_node_checker/config/duplicated_node_checker.param.yaml b/system/duplicated_node_checker/config/duplicated_node_checker.param.yaml index 5b8c019de5a20..54b4f691b6eb1 100644 --- a/system/duplicated_node_checker/config/duplicated_node_checker.param.yaml +++ b/system/duplicated_node_checker/config/duplicated_node_checker.param.yaml @@ -1,3 +1,4 @@ /**: ros__parameters: update_rate: 10.0 + add_duplicated_node_names_to_msg: false # if true, duplicated node names are added to msg diff --git a/system/duplicated_node_checker/include/duplicated_node_checker/duplicated_node_checker_core.hpp b/system/duplicated_node_checker/include/duplicated_node_checker/duplicated_node_checker_core.hpp index ec086058e9041..9d806754f3c20 100644 --- a/system/duplicated_node_checker/include/duplicated_node_checker/duplicated_node_checker_core.hpp +++ b/system/duplicated_node_checker/include/duplicated_node_checker/duplicated_node_checker_core.hpp @@ -48,6 +48,7 @@ class DuplicatedNodeChecker : public rclcpp::Node diagnostic_updater::Updater updater_{this}; rclcpp::TimerBase::SharedPtr timer_; + bool add_duplicated_node_names_to_msg_; }; } // namespace duplicated_node_checker diff --git a/system/duplicated_node_checker/src/duplicated_node_checker_core.cpp b/system/duplicated_node_checker/src/duplicated_node_checker_core.cpp index c9aa483724532..46c02d9d6e133 100644 --- a/system/duplicated_node_checker/src/duplicated_node_checker_core.cpp +++ b/system/duplicated_node_checker/src/duplicated_node_checker_core.cpp @@ -28,6 +28,7 @@ DuplicatedNodeChecker::DuplicatedNodeChecker(const rclcpp::NodeOptions & node_op : Node("duplicated_node_checker", node_options) { double update_rate = declare_parameter("update_rate"); + add_duplicated_node_names_to_msg_ = declare_parameter("add_duplicated_node_names_to_msg"); updater_.setHardwareID("duplicated_node_checker"); updater_.add("duplicated_node_checker", this, &DuplicatedNodeChecker::produceDiagnostics); @@ -63,8 +64,14 @@ void DuplicatedNodeChecker::produceDiagnostics(diagnostic_updater::DiagnosticSta std::string msg; int level; if (identical_names.size() > 0) { - msg = "Error"; level = DiagnosticStatus::ERROR; + msg = "Error: Duplicated nodes detected"; + if (add_duplicated_node_names_to_msg_) { + std::set unique_identical_names(identical_names.begin(), identical_names.end()); + for (const auto & name : unique_identical_names) { + msg += " " + name; + } + } for (auto name : identical_names) { stat.add("Duplicated Node Name", name); } diff --git a/system/system_error_monitor/config/system_error_monitor.planning_simulation.param.yaml b/system/system_error_monitor/config/system_error_monitor.planning_simulation.param.yaml index c396e2e9f5ed8..9784259490ec2 100644 --- a/system/system_error_monitor/config/system_error_monitor.planning_simulation.param.yaml +++ b/system/system_error_monitor/config/system_error_monitor.planning_simulation.param.yaml @@ -40,6 +40,7 @@ /autoware/system/service_log_checker: { sf_at: "warn", lf_at: "none", spf_at: "none" } /autoware/system/duplicated_node_checker: default # /autoware/system/resource_monitoring: { sf_at: "warn", lf_at: "error", spf_at: "none" } + # /autoware/system/duplicated_node_checker: default /autoware/vehicle/node_alive_monitoring: default From 20c0d15a60f908d9028bcadf1d25cafa920b4885 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 24 Oct 2023 00:52:53 +0900 Subject: [PATCH 046/202] fix(goal_planner): fixed goal memory leak (#5381) Signed-off-by: kosuke55 --- .../scene_module/goal_planner/goal_planner_module.hpp | 6 ------ .../src/scene_module/goal_planner/goal_planner_module.cpp | 4 +++- 2 files changed, 3 insertions(+), 7 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp index 251b72ea6eadb..a072c77526ef5 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp @@ -166,12 +166,6 @@ class PullOverStatus DEFINE_SETTER_GETTER(std::vector, pull_over_path_candidates) DEFINE_SETTER_GETTER(std::optional, closest_start_pose) - void push_goal_candidate(const GoalCandidate & goal_candidate) - { - std::lock_guard lock(mutex_); - goal_candidates_.push_back(goal_candidate); - } - private: std::shared_ptr pull_over_path_{nullptr}; std::shared_ptr lane_parking_pull_over_path_{nullptr}; diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index 6253097b1692d..6c431ce5806c3 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -560,7 +560,9 @@ void GoalPlannerModule::generateGoalCandidates() GoalCandidate goal_candidate{}; goal_candidate.goal_pose = goal_pose; goal_candidate.distance_from_original_goal = 0.0; - status_.push_goal_candidate(goal_candidate); + GoalCandidates goal_candidates{}; + goal_candidates.push_back(goal_candidate); + status_.set_goal_candidates(goal_candidates); } } From 3d2a7f6038627ca52a4f0c2af6f5a8d56bc6962b Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 24 Oct 2023 00:54:47 +0900 Subject: [PATCH 047/202] refactor(goal_planner): rebuild state transition (#5371) * refactor(goal_planner): rebuild state transition Signed-off-by: kosuke55 * fix occ Signed-off-by: kosuke55 * fix canTransitIdleToRunningState Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 --- .../goal_planner/goal_planner_module.hpp | 19 +++--- .../goal_planner/goal_planner_module.cpp | 59 ++++++++----------- 2 files changed, 32 insertions(+), 46 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp index a072c77526ef5..34ffb61dcd8d5 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp @@ -240,31 +240,28 @@ class GoalPlannerModule : public SceneModuleInterface } } - // TODO(someone): remove this, and use base class function - [[deprecated]] BehaviorModuleOutput run() override; - bool isExecutionRequested() const override; - bool isExecutionReady() const override; - // TODO(someone): remove this, and use base class function - [[deprecated]] ModuleStatus updateState() override; + CandidateOutput planCandidate() const override; BehaviorModuleOutput plan() override; BehaviorModuleOutput planWaitingApproval() override; - void processOnEntry() override; + bool isExecutionRequested() const override; + bool isExecutionReady() const override; void processOnExit() override; + void updateData() override; void setParameters(const std::shared_ptr & parameters); void acceptVisitor( [[maybe_unused]] const std::shared_ptr & visitor) const override { } - // not used, but need to override - CandidateOutput planCandidate() const override { return CandidateOutput{}; }; - private: + // The start_planner activates when it receives a new route, + // so there is no need to terminate the goal planner. + // If terminating it, it may switch to lane following and could generate an inappropriate path. bool canTransitSuccessState() override { return false; } bool canTransitFailureState() override { return false; } - bool canTransitIdleToRunningState() override { return false; } + bool canTransitIdleToRunningState() override { return true; } mutable StartGoalPlannerData goal_planner_data_; diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index 6c431ce5806c3..e71b1ac7936be 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -124,6 +124,13 @@ GoalPlannerModule::GoalPlannerModule( freespace_parking_timer_cb_group_); } + // Initialize safety checker + if (parameters_->safety_check_params.enable_safety_check) { + initializeSafetyCheckParameters(); + utils::start_goal_planner_common::initializeCollisionCheckDebugMap( + goal_planner_data_.collision_check); + } + status_.reset(); } @@ -228,16 +235,18 @@ void GoalPlannerModule::onFreespaceParkingTimer() } } -BehaviorModuleOutput GoalPlannerModule::run() +void GoalPlannerModule::updateData() { - current_state_ = ModuleStatus::RUNNING; - updateOccupancyGrid(); - - if (!isActivated()) { - return planWaitingApproval(); + // Initialize Occupancy Grid Map + // This operation requires waiting for `planner_data_`, hence it is executed here instead of in + // the constructor. Ideally, this operation should only need to be performed once. + if ( + parameters_->use_occupancy_grid_for_goal_search || + parameters_->use_occupancy_grid_for_path_collision_check) { + initializeOccupancyGridMap(); } - return plan(); + updateOccupancyGrid(); } void GoalPlannerModule::initializeOccupancyGridMap() @@ -264,22 +273,6 @@ void GoalPlannerModule::initializeSafetyCheckParameters() objects_filtering_params_, parameters_); } -void GoalPlannerModule::processOnEntry() -{ - // Initialize occupancy grid map - if ( - parameters_->use_occupancy_grid_for_goal_search || - parameters_->use_occupancy_grid_for_path_collision_check) { - initializeOccupancyGridMap(); - } - // Initialize safety checker - if (parameters_->safety_check_params.enable_safety_check) { - initializeSafetyCheckParameters(); - utils::start_goal_planner_common::initializeCollisionCheckDebugMap( - goal_planner_data_.collision_check); - } -} - void GoalPlannerModule::processOnExit() { resetPathCandidate(); @@ -446,13 +439,6 @@ Pose GoalPlannerModule::calcRefinedGoal(const Pose & goal_pose) const return refined_goal_pose; } -ModuleStatus GoalPlannerModule::updateState() -{ - // start_planner module will be run when setting new goal, so not need finishing pull_over module. - // Finishing it causes wrong lane_following path generation. - return current_state_; -} - bool GoalPlannerModule::planFreespacePath() { goal_searcher_->setPlannerData(planner_data_); @@ -907,6 +893,12 @@ void GoalPlannerModule::decideVelocity() status_.set_has_decided_velocity(true); } +CandidateOutput GoalPlannerModule::planCandidate() const +{ + return CandidateOutput( + status_.get_pull_over_path() ? status_.get_pull_over_path()->getFullPath() : PathWithLaneId()); +} + BehaviorModuleOutput GoalPlannerModule::planWithGoalModification() { constexpr double path_update_duration = 1.0; @@ -945,7 +937,7 @@ BehaviorModuleOutput GoalPlannerModule::planWithGoalModification() // set output and status BehaviorModuleOutput output{}; setOutput(output); - path_candidate_ = std::make_shared(status_.get_pull_over_path()->getFullPath()); + path_candidate_ = std::make_shared(planCandidate().path_candidate); path_reference_ = getPreviousModuleOutput().reference_path; // return to lane parking if it is possible @@ -998,10 +990,7 @@ BehaviorModuleOutput GoalPlannerModule::planWaitingApprovalWithGoalModification( out.modified_goal = plan().modified_goal; // update status_ out.path = std::make_shared(generateStopPath()); out.reference_path = getPreviousModuleOutput().reference_path; - path_candidate_ = - status_.get_is_safe_static_objects() - ? std::make_shared(status_.get_pull_over_path()->getFullPath()) - : out.path; + path_candidate_ = std::make_shared(planCandidate().path_candidate); path_reference_ = getPreviousModuleOutput().reference_path; const auto distance_to_path_change = calcDistanceToPathChange(); From 0938f5b69b4046216e05553a2cf1b8a966afd65f Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 24 Oct 2023 02:17:03 +0900 Subject: [PATCH 048/202] fix(goal_planner): use recursive mutex instead of transaction (#5379) Revert "use transaction instead of recursive_mutex" This reverts commit 654fa8cd0dbf036cf693abbd137acae9936c327c. --- .../goal_planner/goal_planner_module.hpp | 57 ++++++------------- .../goal_planner/goal_planner_module.cpp | 49 +++++++--------- 2 files changed, 36 insertions(+), 70 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp index 34ffb61dcd8d5..21372ed6e2c2f 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp @@ -76,47 +76,29 @@ enum class PathType { FREESPACE, }; -class PullOverStatus; // Forward declaration for Transaction -// class that locks the PullOverStatus when multiple values are being updated from -// an external source. -class Transaction -{ -public: - explicit Transaction(PullOverStatus & status); - ~Transaction(); - -private: - PullOverStatus & status_; -}; - -#define DEFINE_SETTER_GETTER(TYPE, NAME) \ -public: \ - void set_##NAME(const TYPE & value) \ - { \ - if (!is_in_transaction_) { \ - const std::lock_guard lock(mutex_); \ - NAME##_ = value; \ - } else { \ - NAME##_ = value; \ - } \ - } \ - \ - TYPE get_##NAME() const \ - { \ - if (!is_in_transaction_) { \ - const std::lock_guard lock(mutex_); \ - return NAME##_; \ - } \ - return NAME##_; \ +#define DEFINE_SETTER_GETTER(TYPE, NAME) \ +public: \ + void set_##NAME(const TYPE & value) \ + { \ + const std::lock_guard lock(mutex_); \ + NAME##_ = value; \ + } \ + \ + TYPE get_##NAME() const \ + { \ + const std::lock_guard lock(mutex_); \ + return NAME##_; \ } class PullOverStatus { public: + explicit PullOverStatus(std::recursive_mutex & mutex) : mutex_(mutex) {} + // Reset all data members to their initial states void reset() { - const std::lock_guard lock(mutex_); + std::lock_guard lock(mutex_); pull_over_path_ = nullptr; lane_parking_pull_over_path_ = nullptr; current_path_idx_ = 0; @@ -136,9 +118,6 @@ class PullOverStatus is_ready_ = false; } - // lock all data members - Transaction startTransaction() { return Transaction(*this); } - DEFINE_SETTER_GETTER(std::shared_ptr, pull_over_path) DEFINE_SETTER_GETTER(std::shared_ptr, lane_parking_pull_over_path) DEFINE_SETTER_GETTER(size_t, current_path_idx) @@ -200,9 +179,7 @@ class PullOverStatus std::vector pull_over_path_candidates_; std::optional closest_start_pose_; - friend class Transaction; - mutable std::mutex mutex_; - bool is_in_transaction_{false}; + std::recursive_mutex & mutex_; }; #undef DEFINE_SETTER_GETTER @@ -291,7 +268,7 @@ class GoalPlannerModule : public SceneModuleInterface tier4_autoware_utils::LinearRing2d vehicle_footprint_; - std::mutex mutex_; + std::recursive_mutex mutex_; PullOverStatus status_; // approximate distance from the start point to the end point of pull_over. diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index e71b1ac7936be..95ac47494d016 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -50,25 +50,14 @@ using tier4_autoware_utils::inverseTransformPose; namespace behavior_path_planner { -Transaction::Transaction(PullOverStatus & status) : status_(status) -{ - status_.mutex_.lock(); - status_.is_in_transaction_ = true; -} - -Transaction::~Transaction() -{ - status_.mutex_.unlock(); - status_.is_in_transaction_ = false; -} - GoalPlannerModule::GoalPlannerModule( const std::string & name, rclcpp::Node & node, const std::shared_ptr & parameters, const std::unordered_map > & rtc_interface_ptr_map) : SceneModuleInterface{name, node, rtc_interface_ptr_map}, parameters_{parameters}, - vehicle_info_{vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo()} + vehicle_info_{vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo()}, + status_{mutex_} { LaneDepartureChecker lane_departure_checker{}; lane_departure_checker.setVehicleInfo(vehicle_info_); @@ -205,9 +194,11 @@ void GoalPlannerModule::onTimer() } // set member variables - const auto transaction = status_.startTransaction(); - status_.set_pull_over_path_candidates(path_candidates); - status_.set_closest_start_pose(closest_start_pose); + { + const std::lock_guard lock(mutex_); + status_.set_pull_over_path_candidates(path_candidates); + status_.set_closest_start_pose(closest_start_pose); + } } void GoalPlannerModule::onFreespaceParkingTimer() @@ -447,7 +438,7 @@ bool GoalPlannerModule::planFreespacePath() status_.set_goal_candidates(goal_candidates); { - const std::lock_guard lock(mutex_); + const std::lock_guard lock(mutex_); debug_data_.freespace_planner.num_goal_candidates = goal_candidates.size(); debug_data_.freespace_planner.is_planning = true; } @@ -455,7 +446,7 @@ bool GoalPlannerModule::planFreespacePath() for (size_t i = 0; i < goal_candidates.size(); i++) { const auto goal_candidate = goal_candidates.at(i); { - const std::lock_guard lock(mutex_); + const std::lock_guard lock(mutex_); debug_data_.freespace_planner.current_goal_idx = i; } @@ -470,20 +461,19 @@ bool GoalPlannerModule::planFreespacePath() } { - const auto transaction = status_.startTransaction(); + const std::lock_guard lock(mutex_); status_.set_pull_over_path(std::make_shared(*freespace_path)); status_.set_current_path_idx(0); status_.set_is_safe_static_objects(true); status_.set_modified_goal_pose(goal_candidate); status_.set_last_path_update_time(std::make_shared(clock_->now())); - const std::lock_guard lock(mutex_); debug_data_.freespace_planner.is_planning = false; } return true; } - const std::lock_guard lock(mutex_); + const std::lock_guard lock(mutex_); debug_data_.freespace_planner.is_planning = false; return false; } @@ -513,7 +503,7 @@ void GoalPlannerModule::returnToLaneParking() } { - const auto transaction = status_.startTransaction(); + const std::lock_guard lock(mutex_); status_.set_is_safe_static_objects(true); status_.set_has_decided_path(false); status_.set_pull_over_path(status_.get_lane_parking_pull_over_path()); @@ -609,7 +599,7 @@ void GoalPlannerModule::selectSafePullOverPath() std::vector pull_over_path_candidates{}; GoalCandidates goal_candidates{}; { - const auto transaction = status_.startTransaction(); + const std::lock_guard lock(mutex_); goal_searcher_->setPlannerData(planner_data_); goal_candidates = status_.get_goal_candidates(); goal_searcher_->update(goal_candidates); @@ -640,7 +630,7 @@ void GoalPlannerModule::selectSafePullOverPath() // found safe pull over path { - const auto transaction = status_.startTransaction(); + const std::lock_guard lock(mutex_); status_.set_is_safe_static_objects(true); status_.set_pull_over_path(std::make_shared(pull_over_path)); status_.set_current_path_idx(0); @@ -681,7 +671,7 @@ void GoalPlannerModule::selectSafePullOverPath() void GoalPlannerModule::setLanes() { - const auto transaction = status_.startTransaction(); + const std::lock_guard lock(mutex_); status_.set_current_lanes(utils::getExtendedCurrentLanes( planner_data_, parameters_->backward_goal_search_length, parameters_->forward_goal_search_length, @@ -731,7 +721,7 @@ void GoalPlannerModule::setOutput(BehaviorModuleOutput & output) // for the next loop setOutput(). // this is used to determine whether to generate a new stop path or keep the current stop path. - const auto transaction = status_.startTransaction(); + const std::lock_guard lock(mutex_); status_.set_prev_is_safe(status_.get_is_safe_static_objects()); status_.set_prev_is_safe_dynamic_objects( parameters_->safety_check_params.enable_safety_check ? isSafePath() : true); @@ -742,7 +732,7 @@ void GoalPlannerModule::setStopPath(BehaviorModuleOutput & output) if (status_.get_prev_is_safe() || !status_.get_prev_stop_path()) { // safe -> not_safe or no prev_stop_path: generate new stop_path output.path = std::make_shared(generateStopPath()); - const auto transaction = status_.startTransaction(); + const std::lock_guard lock(mutex_); status_.set_prev_stop_path(output.path); // set stop path as pull over path auto stop_pull_over_path = std::make_shared(); @@ -916,7 +906,7 @@ BehaviorModuleOutput GoalPlannerModule::planWithGoalModification() if (status_.get_has_decided_path()) { if (isActivated() && isWaitingApproval()) { { - const auto transaction = status_.startTransaction(); + const std::lock_guard lock(mutex_); status_.set_last_approved_time(std::make_shared(clock_->now())); status_.set_last_approved_pose( std::make_shared(planner_data_->self_odometry->pose.pose)); @@ -1226,7 +1216,7 @@ bool GoalPlannerModule::isStopped( bool GoalPlannerModule::isStopped() { - const std::lock_guard lock(mutex_); + const std::lock_guard lock(mutex_); return isStopped(odometry_buffer_stopped_, parameters_->th_stopped_time); } @@ -1236,7 +1226,6 @@ bool GoalPlannerModule::isStuck() return false; } - const std::lock_guard lock(mutex_); constexpr double stuck_time = 5.0; if (!isStopped(odometry_buffer_stuck_, stuck_time)) { return false; From 8a66cbae0ac31735bc7ccf915818dd5a631349ec Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 24 Oct 2023 09:29:32 +0900 Subject: [PATCH 049/202] fix(crosswalk): fix duplicated crosswalk launch (#5383) Signed-off-by: Takayuki Murooka --- .../src/manager.cpp | 21 ++++++++++++------- .../src/scene_crosswalk.cpp | 8 +++---- .../src/scene_crosswalk.hpp | 4 ++-- 3 files changed, 19 insertions(+), 14 deletions(-) diff --git a/planning/behavior_velocity_crosswalk_module/src/manager.cpp b/planning/behavior_velocity_crosswalk_module/src/manager.cpp index 94e87d0174193..dd8dc95a8ad3c 100644 --- a/planning/behavior_velocity_crosswalk_module/src/manager.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/manager.cpp @@ -128,8 +128,9 @@ void CrosswalkModuleManager::launchNewModules(const PathWithLaneId & path) { const auto rh = planner_data_->route_handler_; - const auto launch = [this, &path](const auto id, const auto & use_regulatory_element) { - if (isModuleRegistered(id)) { + const auto launch = [this, &path]( + const auto lane_id, const std::optional & reg_elem_id) { + if (isModuleRegistered(lane_id)) { return; } @@ -137,24 +138,28 @@ void CrosswalkModuleManager::launchNewModules(const PathWithLaneId & path) const auto logger = logger_.get_child("crosswalk_module"); const auto lanelet_map_ptr = planner_data_->route_handler_->getLaneletMapPtr(); + // NOTE: module_id is always a lane id so that isModuleRegistered works correctly in the case + // where both regulatory element and non-regulatory element crosswalks exist. registerModule(std::make_shared( - node_, id, lanelet_map_ptr, p, use_regulatory_element, logger, clock_)); - generateUUID(id); - updateRTCStatus(getUUID(id), true, std::numeric_limits::lowest(), path.header.stamp); + node_, lane_id, reg_elem_id, lanelet_map_ptr, p, logger, clock_)); + generateUUID(lane_id); + updateRTCStatus( + getUUID(lane_id), true, std::numeric_limits::lowest(), path.header.stamp); }; const auto crosswalk_leg_elem_map = planning_utils::getRegElemMapOnPath( path, rh->getLaneletMapPtr(), planner_data_->current_odometry->pose); for (const auto & crosswalk : crosswalk_leg_elem_map) { - launch(crosswalk.first->id(), true); + // NOTE: The former id is a lane id, and the latter one is a regulatory element's id. + launch(crosswalk.first->crosswalkLanelet().id(), crosswalk.first->id()); } const auto crosswalk_lanelets = getCrosswalksOnPath( planner_data_->current_odometry->pose, path, rh->getLaneletMapPtr(), rh->getOverallGraphPtr()); for (const auto & crosswalk : crosswalk_lanelets) { - launch(crosswalk.id(), false); + launch(crosswalk.id(), std::nullopt); } } @@ -172,7 +177,7 @@ CrosswalkModuleManager::getModuleExpiredFunction(const PathWithLaneId & path) path, rh->getLaneletMapPtr(), planner_data_->current_odometry->pose); for (const auto & crosswalk : crosswalk_leg_elem_map) { - crosswalk_id_set.insert(crosswalk.first->id()); + crosswalk_id_set.insert(crosswalk.first->crosswalkLanelet().id()); } return [crosswalk_id_set](const std::shared_ptr & scene_module) { diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index fe96985743b94..56f5072a2ade9 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -176,20 +176,20 @@ tier4_debug_msgs::msg::StringStamped createStringStampedMessage( } // namespace CrosswalkModule::CrosswalkModule( - rclcpp::Node & node, const int64_t module_id, const lanelet::LaneletMapPtr & lanelet_map_ptr, - const PlannerParam & planner_param, const bool use_regulatory_element, + rclcpp::Node & node, const int64_t module_id, const std::optional & reg_elem_id, + const lanelet::LaneletMapPtr & lanelet_map_ptr, const PlannerParam & planner_param, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock) : SceneModuleInterface(module_id, logger, clock), module_id_(module_id), planner_param_(planner_param), - use_regulatory_element_(use_regulatory_element) + use_regulatory_element_(reg_elem_id) { velocity_factor_.init(VelocityFactor::CROSSWALK); passed_safety_slow_point_ = false; if (use_regulatory_element_) { const auto reg_elem_ptr = std::dynamic_pointer_cast( - lanelet_map_ptr->regulatoryElementLayer.get(module_id)); + lanelet_map_ptr->regulatoryElementLayer.get(*reg_elem_id)); stop_lines_ = reg_elem_ptr->stopLines(); crosswalk_ = reg_elem_ptr->crosswalkLanelet(); } else { diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp index 063ea4f83cd45..0768101179857 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp @@ -299,8 +299,8 @@ class CrosswalkModule : public SceneModuleInterface }; CrosswalkModule( - rclcpp::Node & node, const int64_t module_id, const lanelet::LaneletMapPtr & lanelet_map_ptr, - const PlannerParam & planner_param, const bool use_regulatory_element, + rclcpp::Node & node, const int64_t module_id, const std::optional & reg_elem_id, + const lanelet::LaneletMapPtr & lanelet_map_ptr, const PlannerParam & planner_param, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock); bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override; From 7c3bde1a6bdcda425999b5f02f06ffe5712fc709 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Tue, 24 Oct 2023 09:33:04 +0900 Subject: [PATCH 050/202] docs(mpc_lateral_controller): update parameter description (#5309) * update parameter Signed-off-by: kyoichi-sugahara * fix description Signed-off-by: kyoichi-sugahara --------- Signed-off-by: kyoichi-sugahara --- control/mpc_lateral_controller/README.md | 169 +++++++++++++---------- 1 file changed, 96 insertions(+), 73 deletions(-) diff --git a/control/mpc_lateral_controller/README.md b/control/mpc_lateral_controller/README.md index 7579e3da265c4..50e9d44a0a7a4 100644 --- a/control/mpc_lateral_controller/README.md +++ b/control/mpc_lateral_controller/README.md @@ -67,7 +67,7 @@ Set the following from the [controller_node](../trajectory_follower_node/README. - `autoware_auto_planning_msgs/Trajectory` : reference trajectory to follow. - `nav_msgs/Odometry`: current odometry -- `autoware_auto_vehicle_msgs/SteeringReport` current steering +- `autoware_auto_vehicle_msgs/SteeringReport`: current steering ### Outputs @@ -89,83 +89,108 @@ can be calculated by providing the current steer, velocity, and pose to function The default parameters defined in `param/lateral_controller_defaults.param.yaml` are adjusted to the AutonomouStuff Lexus RX 450h for under 40 km/h driving. -| Name | Type | Description | Default value | -| :------------------------------------------- | :----- | :--------------------------------------------------------------------------------------------------------------------------------------------------- | :------------ | -| show_debug_info | bool | display debug info | false | -| traj_resample_dist | double | distance of waypoints in resampling [m] | 0.1 | -| enable_path_smoothing | bool | path smoothing flag. This should be true when uses path resampling to reduce resampling noise. | true | -| path_filter_moving_ave_num | int | number of data points moving average filter for path smoothing | 35 | -| path_smoothing_times | int | number of times of applying path smoothing filter | 1 | -| curvature_smoothing_num_ref_steer | double | index distance of points used in curvature calculation for reference steering command: p(i-num), p(i), p(i+num). larger num makes less noisy values. | 35 | -| curvature_smoothing_num_traj | double | index distance of points used in curvature calculation for trajectory: p(i-num), p(i), p(i+num). larger num makes less noisy values. | 1 | -| extend_trajectory_for_end_yaw_control | bool | trajectory extending flag for end yaw control. | true | -| steering_lpf_cutoff_hz | double | cutoff frequency of lowpass filter for steering output command [hz] | 3.0 | -| admissible_position_error | double | stop vehicle when following position error is larger than this value [m]. | 5.0 | -| admissible_yaw_error_rad | double | stop vehicle when following yaw angle error is larger than this value [rad]. | 1.57 | -| stop_state_entry_ego_speed \*1 | double | threshold value of the ego vehicle speed used to the stop state entry condition | 0.0 | -| stop_state_entry_target_speed \*1 | double | threshold value of the target speed used to the stop state entry condition | 0.0 | -| converged_steer_rad | double | threshold value of the steer convergence | 0.1 | -| keep_steer_control_until_converged | bool | keep steer control until steer is converged | true | -| new_traj_duration_time | double | threshold value of the time to be considered as new trajectory | 1.0 | -| new_traj_end_dist | double | threshold value of the distance between trajectory ends to be considered as new trajectory | 0.3 | -| mpc_converged_threshold_rps | double | threshold value to be sure output of the optimization is converged, it is used in stopped state | 0.3 | - -(\*1) To prevent unnecessary steering movement, the steering command is fixed to the previous value in the stop state. - -#### MPC algorithm - -| Name | Type | Description | Default value | -| :-------------------------------------------------- | :----- | :------------------------------------------------------------------------------------------------------------------------------------------------- | :---------------- | -| qp_solver_type | string | QP solver option. described below in detail. | unconstraint_fast | -| mpc_vehicle_model_type | string | vehicle model option. described below in detail. | kinematics | -| mpc_prediction_horizon | int | total prediction step for MPC | 70 | -| mpc_prediction_sampling_time | double | prediction period for one step [s] | 0.1 | -| mpc_weight_lat_error | double | weight for lateral error | 0.1 | -| mpc_weight_heading_error | double | weight for heading error | 0.0 | -| mpc_weight_heading_error_squared_vel_coeff | double | weight for heading error \* velocity | 5.0 | -| mpc_weight_steering_input | double | weight for steering error (steer command - reference steer) | 1.0 | -| mpc_weight_steering_input_squared_vel_coeff | double | weight for steering error (steer command - reference steer) \* velocity | 0.25 | -| mpc_weight_lat_jerk | double | weight for lateral jerk (steer(i) - steer(i-1)) \* velocity | 0.0 | -| mpc_weight_terminal_lat_error | double | terminal cost weight for lateral error | 1.0 | -| mpc_weight_steer_rate | double | weight for steering rate [rad/s] | 0.0 | -| mpc_weight_steer_acc | double | weight for derivatives of the steering rate [rad/ss] | 0.0 | -| mpc_weight_terminal_heading_error | double | terminal cost weight for heading error | 0.1 | -| mpc_low_curvature_thresh_curvature | double | trajectory curvature threshold to change the weight. If the curvature is lower than this value, the `low_curvature_weight_**` values will be used. | 0.0 | -| mpc_low_curvature_weight_lat_error | double | [used in a low curvature trajectory] weight for lateral error | 0.0 | -| mpc_low_curvature_weight_heading_error | double | [used in a low curvature trajectory] weight for heading error | 0.0 | -| mpc_low_curvature_weight_heading_error_squared_vel | double | [used in a low curvature trajectory] weight for heading error \* velocity | 0.0 | -| mpc_low_curvature_weight_steering_input | double | [used in a low curvature trajectory] weight for steering error (steer command - reference steer) | 0.0 | -| mpc_low_curvature_weight_steering_input_squared_vel | double | [used in a low curvature trajectory] weight for steering error (steer command - reference steer) \* velocity | 0.0 | -| mpc_low_curvature_weight_lat_jerk | double | [used in a low curvature trajectory] weight for lateral jerk (steer(i) - steer(i-1)) \* velocity | 0.0 | -| mpc_low_curvature_weight_steer_rate | double | [used in a low curvature trajectory] weight for steering rate [rad/s] | 0.0 | -| mpc_low_curvature_weight_steer_acc | double | [used in a low curvature trajectory] weight for derivatives of the steering rate [rad/ss] | 0.0 | -| mpc_zero_ff_steer_deg | double | threshold of feedforward angle [deg]. feedforward angle smaller than this value is set to zero. | 2.0 | - -#### Steering offset remover - -Defined in the `steering_offset` namespace. This logic is designed as simple as possible, with minimum design parameters. - -| Name | Type | Description | Default value | -| :---------------------------------- | :----- | :----------------------------------------------------------------------------------------------- | :------------ | -| enable_auto_steering_offset_removal | bool | Estimate the steering offset and apply compensation | true | -| update_vel_threshold | double | If the velocity is smaller than this value, the data is not used for the offset estimation. | 5.56 | -| update_steer_threshold | double | If the steering angle is larger than this value, the data is not used for the offset estimation. | 0.035 | -| average_num | double | The average of this number of data is used as a steering offset. | 1000 | -| steering_offset_limit | double | The angle limit to be applied to the offset compensation. | 0.02 | - -#### Vehicle model +#### System + +| Name | Type | Description | Default value | +| :------------------------ | :------ | :-------------------------------------------------------------------------- | :------------ | +| traj_resample_dist | double | distance of waypoints in resampling [m] | 0.1 | +| use_steer_prediction | boolean | flag for using steer prediction (do not use steer measurement) | false | +| admissible_position_error | double | stop vehicle when following position error is larger than this value [m] | 5.0 | +| admissible_yaw_error_rad | double | stop vehicle when following yaw angle error is larger than this value [rad] | 1.57 | + +#### Path Smoothing + +| Name | Type | Description | Default value | +| :-------------------------------- | :------ | :--------------------------------------------------------------------------------------------------------------------------------------------------- | :------------ | +| enable_path_smoothing | boolean | path smoothing flag. This should be true when uses path resampling to reduce resampling noise. | false | +| path_filter_moving_ave_num | int | number of data points moving average filter for path smoothing | 25 | +| curvature_smoothing_num_traj | int | index distance of points used in curvature calculation for trajectory: p(i-num), p(i), p(i+num). larger num makes less noisy values. | 15 | +| curvature_smoothing_num_ref_steer | int | index distance of points used in curvature calculation for reference steering command: p(i-num), p(i), p(i+num). larger num makes less noisy values. | 15 | + +#### Trajectory Extending + +| Name | Type | Description | Default value | +| :------------------------------------ | :------ | :-------------------------------------------- | :------------ | +| extend_trajectory_for_end_yaw_control | boolean | trajectory extending flag for end yaw control | true | + +#### MPC Optimization + +| Name | Type | Description | Default value | +| :-------------------------------------------------- | :----- | :----------------------------------------------------------------------------------------------------------- | :------------ | +| qp_solver_type | string | QP solver option. described below in detail. | "osqp" | +| mpc_prediction_horizon | int | total prediction step for MPC | 50 | +| mpc_prediction_dt | double | prediction period for one step [s] | 0.1 | +| mpc_weight_lat_error | double | weight for lateral error | 1.0 | +| mpc_weight_heading_error | double | weight for heading error | 0.0 | +| mpc_weight_heading_error_squared_vel | double | weight for heading error \* velocity | 0.3 | +| mpc_weight_steering_input | double | weight for steering error (steer command - reference steer) | 1.0 | +| mpc_weight_steering_input_squared_vel | double | weight for steering error (steer command - reference steer) \* velocity | 0.25 | +| mpc_weight_lat_jerk | double | weight for lateral jerk (steer(i) - steer(i-1)) \* velocity | 0.1 | +| mpc_weight_steer_rate | double | weight for steering rate [rad/s] | 0.0 | +| mpc_weight_steer_acc | double | weight for derivatives of the steering rate [rad/ss] | 0.000001 | +| mpc_low_curvature_weight_lat_error | double | [used in a low curvature trajectory] weight for lateral error | 0.1 | +| mpc_low_curvature_weight_heading_error | double | [used in a low curvature trajectory] weight for heading error | 0.0 | +| mpc_low_curvature_weight_heading_error_squared_vel | double | [used in a low curvature trajectory] weight for heading error \* velocity | 0.3 | +| mpc_low_curvature_weight_steering_input | double | [used in a low curvature trajectory] weight for steering error (steer command - reference steer) | 1.0 | +| mpc_low_curvature_weight_steering_input_squared_vel | double | [used in a low curvature trajectory] weight for steering error (steer command - reference steer) \* velocity | 0.25 | +| mpc_low_curvature_weight_lat_jerk | double | [used in a low curvature trajectory] weight for lateral jerk (steer(i) - steer(i-1)) \* velocity | 0.0 | +| mpc_low_curvature_weight_steer_rate | double | [used in a low curvature trajectory] weight for steering rate [rad/s] | 0.0 | +| mpc_low_curvature_weight_steer_acc | double | [used in a low curvature trajectory] weight for derivatives of the steering rate [rad/ss] | 0.000001 | +| mpc_low_curvature_thresh_curvature | double | threshold of curvature to use "low_curvature" parameter | 0.0 | +| mpc_weight_terminal_lat_error | double | terminal lateral error weight in matrix Q to improve mpc stability | 1.0 | +| mpc_weight_terminal_heading_error | double | terminal heading error weight in matrix Q to improve mpc stability | 0.1 | +| mpc_zero_ff_steer_deg | double | threshold that feed-forward angle becomes zero | 0.5 | +| mpc_acceleration_limit | double | limit on the vehicle's acceleration | 2.0 | +| mpc_velocity_time_constant | double | time constant used for velocity smoothing | 0.3 | +| mpc_min_prediction_length | double | minimum prediction length | 5.0 | + +#### Vehicle Model | Name | Type | Description | Default value | | :----------------------------------- | :------- | :--------------------------------------------------------------------------------- | :------------------- | +| vehicle_model_type | string | vehicle model type for mpc prediction | "kinematics" | | input_delay | double | steering input delay time for delay compensation | 0.24 | -| vehicle_model_steer_tau | double | steering dynamics time constant | 0.3 | -| steer_rate_lim_dps_list_by_curvature | [double] | steering angle rate limit list depending on curvature [deg/s] | [10.0, 20.0, 30.0] | +| vehicle_model_steer_tau | double | steering dynamics time constant (1d approximation) [s] | 0.3 | +| steer_rate_lim_dps_list_by_curvature | [double] | steering angle rate limit list depending on curvature [deg/s] | [40.0, 50.0, 60.0] | | curvature_list_for_steer_rate_lim | [double] | curvature list for steering angle rate limit interpolation in ascending order [/m] | [0.001, 0.002, 0.01] | -| steer_rate_lim_dps_list_by_velocity | [double] | steering angle rate limit list depending on velocity [deg/s] | [40.0, 30.0, 20.0] | +| steer_rate_lim_dps_list_by_velocity | [double] | steering angle rate limit list depending on velocity [deg/s] | [60.0, 50.0, 40.0] | | velocity_list_for_steer_rate_lim | [double] | velocity list for steering angle rate limit interpolation in ascending order [m/s] | [10.0, 15.0, 20.0] | | acceleration_limit | double | acceleration limit for trajectory velocity modification [m/ss] | 2.0 | | velocity_time_constant | double | velocity dynamics time constant for trajectory velocity modification [s] | 0.3 | +#### Lowpass Filter for Noise Reduction + +| Name | Type | Description | Default value | +| :------------------------ | :----- | :------------------------------------------------------------------ | :------------ | +| steering_lpf_cutoff_hz | double | cutoff frequency of lowpass filter for steering output command [hz] | 3.0 | +| error_deriv_lpf_cutoff_hz | double | cutoff frequency of lowpass filter for error derivative [Hz] | 5.0 | + +#### Stop State + +| Name | Type | Description | Default value | +| :------------------------------------------- | :------ | :---------------------------------------------------------------------------------------------- | :------------ | +| stop_state_entry_ego_speed \*1 | double | threshold value of the ego vehicle speed used to the stop state entry condition | 0.001 | +| stop_state_entry_target_speed \*1 | double | threshold value of the target speed used to the stop state entry condition | 0.001 | +| converged_steer_rad | double | threshold value of the steer convergence | 0.1 | +| keep_steer_control_until_converged | boolean | keep steer control until steer is converged | true | +| new_traj_duration_time | double | threshold value of the time to be considered as new trajectory | 1.0 | +| new_traj_end_dist | double | threshold value of the distance between trajectory ends to be considered as new trajectory | 0.3 | +| mpc_converged_threshold_rps | double | threshold value to be sure output of the optimization is converged, it is used in stopped state | 0.01 | + +(\*1) To prevent unnecessary steering movement, the steering command is fixed to the previous value in the stop state. + +#### Steer Offset + +Defined in the `steering_offset` namespace. This logic is designed as simple as possible, with minimum design parameters. + +| Name | Type | Description | Default value | +| :---------------------------------- | :------ | :----------------------------------------------------------------------------------------------- | :------------ | +| enable_auto_steering_offset_removal | boolean | Estimate the steering offset and apply compensation | true | +| update_vel_threshold | double | If the velocity is smaller than this value, the data is not used for the offset estimation | 5.56 | +| update_steer_threshold | double | If the steering angle is larger than this value, the data is not used for the offset estimation. | 0.035 | +| average_num | int | The average of this number of data is used as a steering offset. | 1000 | +| steering_offset_limit | double | The angle limit to be applied to the offset compensation. | 0.02 | + ##### For dynamics model (WIP) | Name | Type | Description | Default value | @@ -215,10 +240,8 @@ If you want to adjust the effect only in the high-speed range, you can use `weig - `weight_steering_input`: Reduce oscillation of tracking. - `weight_steering_input_squared_vel_coeff`: Reduce oscillation of tracking in high speed range. - `weight_lat_jerk`: Reduce lateral jerk. -- `weight_terminal_lat_error`: Preferable to set a higher value than normal lateral weight `weight_lat_error` for - stability. -- `weight_terminal_heading_error`: Preferable to set a higher value than normal heading weight `weight_heading_error` - for stability. +- `weight_terminal_lat_error`: Preferable to set a higher value than normal lateral weight `weight_lat_error` for stability. +- `weight_terminal_heading_error`: Preferable to set a higher value than normal heading weight `weight_heading_error` for stability. #### Other tips for tuning From 763a9b842affd2752edd2dd783ebddcb7f385644 Mon Sep 17 00:00:00 2001 From: Tomohito ANDO Date: Tue, 24 Oct 2023 11:52:24 +0900 Subject: [PATCH 051/202] feat(behavior_velocity_run_out): ignore momentary detection caused by false positive (#5359) * feat(behavior_velocity_run_out): ignore momentary detection caused by false positive Signed-off-by: Tomohito Ando * style(pre-commit): autofix --------- Signed-off-by: Tomohito Ando Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../README.md | 5 ++++ .../config/run_out.param.yaml | 5 ++++ .../src/manager.cpp | 7 ++++++ .../src/scene.cpp | 25 ++++++++++++++++++- .../src/scene.hpp | 6 +++-- .../src/utils.hpp | 7 ++++++ 6 files changed, 52 insertions(+), 3 deletions(-) diff --git a/planning/behavior_velocity_run_out_module/README.md b/planning/behavior_velocity_run_out_module/README.md index ee762653245c6..a36cfdf6485c6 100644 --- a/planning/behavior_velocity_run_out_module/README.md +++ b/planning/behavior_velocity_run_out_module/README.md @@ -217,6 +217,11 @@ You can choose whether to use this feature by parameter of `slow_down_limit.enab | `max_jerk` | double | [m/s^3] minimum jerk deceleration for safe brake. | | `max_acc` | double | [m/s^2] minimum accel deceleration for safe brake. | +| Parameter /ignore_momentary_detection | Type | Description | +| ------------------------------------- | ------ | ----------------------------------------------------------------- | +| `enable` | bool | [-] whether to ignore momentary detection | +| `time_threshold` | double | [sec] ignores detections that persist for less than this duration | + ### Future extensions / Unimplemented parts - Calculate obstacle's min velocity and max velocity from covariance diff --git a/planning/behavior_velocity_run_out_module/config/run_out.param.yaml b/planning/behavior_velocity_run_out_module/config/run_out.param.yaml index f9668549f2fb2..2641214ac5ad4 100644 --- a/planning/behavior_velocity_run_out_module/config/run_out.param.yaml +++ b/planning/behavior_velocity_run_out_module/config/run_out.param.yaml @@ -48,3 +48,8 @@ enable: true max_jerk: -0.7 # [m/s^3] minimum jerk deceleration for safe brake. max_acc : -2.0 # [m/s^2] minimum accel deceleration for safe brake. + + # prevent abrupt stops caused by false positives in perception + ignore_momentary_detection: + enable: true + time_threshold: 0.15 # [sec] ignores detections that persist for less than this duration diff --git a/planning/behavior_velocity_run_out_module/src/manager.cpp b/planning/behavior_velocity_run_out_module/src/manager.cpp index b262bf00cb57a..a5253f59b60f9 100644 --- a/planning/behavior_velocity_run_out_module/src/manager.cpp +++ b/planning/behavior_velocity_run_out_module/src/manager.cpp @@ -119,6 +119,13 @@ RunOutModuleManager::RunOutModuleManager(rclcpp::Node & node) p.max_acc = getOrDeclareParameter(node, ns_m + ".max_acc"); } + { + auto & p = planner_param_.ignore_momentary_detection; + const std::string ns_param = ns + ".ignore_momentary_detection"; + p.enable = getOrDeclareParameter(node, ns_param + ".enable"); + p.time_threshold = getOrDeclareParameter(node, ns_param + ".time_threshold"); + } + debug_ptr_ = std::make_shared(node); setDynamicObstacleCreator(node, debug_ptr_); } diff --git a/planning/behavior_velocity_run_out_module/src/scene.cpp b/planning/behavior_velocity_run_out_module/src/scene.cpp index b91d1d1fe1ae7..54902f52c47da 100644 --- a/planning/behavior_velocity_run_out_module/src/scene.cpp +++ b/planning/behavior_velocity_run_out_module/src/scene.cpp @@ -137,7 +137,7 @@ bool RunOutModule::modifyPathVelocity( } boost::optional RunOutModule::detectCollision( - const std::vector & dynamic_obstacles, const PathWithLaneId & path) const + const std::vector & dynamic_obstacles, const PathWithLaneId & path) { if (path.points.size() < 2) { RCLCPP_WARN_STREAM(logger_, "path doesn't have enough points."); @@ -181,6 +181,11 @@ boost::optional RunOutModule::detectCollision( continue; } + // ignore momentary obstacle detection to avoid sudden stopping by false positive + if (isMomentaryDetection()) { + return {}; + } + debug_ptr_->pushCollisionPoints(obstacle_selected->collision_points); debug_ptr_->pushNearestCollisionPoint(obstacle_selected->nearest_collision_point); @@ -188,6 +193,7 @@ boost::optional RunOutModule::detectCollision( } // no collision detected + first_detected_time_.reset(); return {}; } @@ -812,4 +818,21 @@ void RunOutModule::publishDebugValue( debug_ptr_->publishDebugValue(); } +bool RunOutModule::isMomentaryDetection() +{ + if (!planner_param_.ignore_momentary_detection.enable) { + return false; + } + + if (!first_detected_time_) { + first_detected_time_ = std::make_shared(clock_->now()); + return true; + } + + const auto now = clock_->now(); + const double elapsed_time_since_detection = (now - *first_detected_time_).seconds(); + RCLCPP_DEBUG_STREAM(logger_, "elapsed_time_since_detection: " << elapsed_time_since_detection); + + return elapsed_time_since_detection < planner_param_.ignore_momentary_detection.time_threshold; +} } // namespace behavior_velocity_planner diff --git a/planning/behavior_velocity_run_out_module/src/scene.hpp b/planning/behavior_velocity_run_out_module/src/scene.hpp index 20bd8ffc799ff..925d8ea8b234c 100644 --- a/planning/behavior_velocity_run_out_module/src/scene.hpp +++ b/planning/behavior_velocity_run_out_module/src/scene.hpp @@ -62,13 +62,13 @@ class RunOutModule : public SceneModuleInterface std::unique_ptr dynamic_obstacle_creator_; std::shared_ptr debug_ptr_; std::unique_ptr state_machine_; + std::shared_ptr first_detected_time_; // Function Polygons2d createDetectionAreaPolygon(const PathWithLaneId & smoothed_path) const; boost::optional detectCollision( - const std::vector & dynamic_obstacles, - const PathWithLaneId & path_points) const; + const std::vector & dynamic_obstacles, const PathWithLaneId & path_points); float calcCollisionPositionOfVehicleSide( const geometry_msgs::msg::Point & point, const geometry_msgs::msg::Pose & base_pose) const; @@ -141,6 +141,8 @@ class RunOutModule : public SceneModuleInterface const PathWithLaneId & path, const std::vector extracted_obstacles, const boost::optional & dynamic_obstacle, const geometry_msgs::msg::Pose & current_pose) const; + + bool isMomentaryDetection(); }; } // namespace behavior_velocity_planner diff --git a/planning/behavior_velocity_run_out_module/src/utils.hpp b/planning/behavior_velocity_run_out_module/src/utils.hpp index 8fc3d48de4858..b25a8fc94bff3 100644 --- a/planning/behavior_velocity_run_out_module/src/utils.hpp +++ b/planning/behavior_velocity_run_out_module/src/utils.hpp @@ -126,6 +126,12 @@ struct DynamicObstacleParam float points_interval; // [m] }; +struct IgnoreMomentaryDetection +{ + bool enable; + double time_threshold; +}; + struct PlannerParam { CommonParam common; @@ -138,6 +144,7 @@ struct PlannerParam DynamicObstacleParam dynamic_obstacle; SlowDownLimit slow_down_limit; Smoother smoother; + IgnoreMomentaryDetection ignore_momentary_detection; }; enum class DetectionMethod { From 0f9eb8af887b1f72611b60b03fed41013556e356 Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Tue, 24 Oct 2023 14:13:29 +0900 Subject: [PATCH 052/202] feat(imu_corrector): changed input topic of GyroBiasEstimator from ndt_pose to ekf_odom (#5374) Changed input topic of GyroBiasEstimator from pose to odom Signed-off-by: Shintaro Sakoda --- .../launch/gyro_bias_estimator.launch.xml | 4 ++-- sensing/imu_corrector/src/gyro_bias_estimator.cpp | 13 ++++++------- sensing/imu_corrector/src/gyro_bias_estimator.hpp | 6 ++++-- 3 files changed, 12 insertions(+), 11 deletions(-) diff --git a/sensing/imu_corrector/launch/gyro_bias_estimator.launch.xml b/sensing/imu_corrector/launch/gyro_bias_estimator.launch.xml index 0d7cba9faa3a6..e16ccef446aba 100644 --- a/sensing/imu_corrector/launch/gyro_bias_estimator.launch.xml +++ b/sensing/imu_corrector/launch/gyro_bias_estimator.launch.xml @@ -1,14 +1,14 @@ - + - + diff --git a/sensing/imu_corrector/src/gyro_bias_estimator.cpp b/sensing/imu_corrector/src/gyro_bias_estimator.cpp index 21bb51dc5f1f1..50e4a702ec949 100644 --- a/sensing/imu_corrector/src/gyro_bias_estimator.cpp +++ b/sensing/imu_corrector/src/gyro_bias_estimator.cpp @@ -43,9 +43,9 @@ GyroBiasEstimator::GyroBiasEstimator() imu_sub_ = create_subscription( "~/input/imu_raw", rclcpp::SensorDataQoS(), [this](const Imu::ConstSharedPtr msg) { callback_imu(msg); }); - pose_sub_ = create_subscription( - "~/input/pose", rclcpp::SensorDataQoS(), - [this](const PoseWithCovarianceStamped::ConstSharedPtr msg) { callback_pose(msg); }); + odom_sub_ = create_subscription( + "~/input/odom", rclcpp::SensorDataQoS(), + [this](const Odometry::ConstSharedPtr msg) { callback_odom(msg); }); gyro_bias_pub_ = create_publisher("~/output/gyro_bias", rclcpp::SensorDataQoS()); auto timer_callback = std::bind(&GyroBiasEstimator::timer_callback, this); @@ -88,12 +88,11 @@ void GyroBiasEstimator::callback_imu(const Imu::ConstSharedPtr imu_msg_ptr) } } -void GyroBiasEstimator::callback_pose(const PoseWithCovarianceStamped::ConstSharedPtr pose_msg_ptr) +void GyroBiasEstimator::callback_odom(const Odometry::ConstSharedPtr odom_msg_ptr) { - // push pose_msg to queue geometry_msgs::msg::PoseStamped pose; - pose.header = pose_msg_ptr->header; - pose.pose = pose_msg_ptr->pose.pose; + pose.header = odom_msg_ptr->header; + pose.pose = odom_msg_ptr->pose.pose; pose_buf_.push_back(pose); } diff --git a/sensing/imu_corrector/src/gyro_bias_estimator.hpp b/sensing/imu_corrector/src/gyro_bias_estimator.hpp index 7eb06bcdcb365..821cba0b213ff 100644 --- a/sensing/imu_corrector/src/gyro_bias_estimator.hpp +++ b/sensing/imu_corrector/src/gyro_bias_estimator.hpp @@ -22,6 +22,7 @@ #include #include +#include #include #include @@ -38,6 +39,7 @@ class GyroBiasEstimator : public rclcpp::Node using PoseWithCovarianceStamped = geometry_msgs::msg::PoseWithCovarianceStamped; using Vector3Stamped = geometry_msgs::msg::Vector3Stamped; using Vector3 = geometry_msgs::msg::Vector3; + using Odometry = nav_msgs::msg::Odometry; public: GyroBiasEstimator(); @@ -45,7 +47,7 @@ class GyroBiasEstimator : public rclcpp::Node private: void update_diagnostics(diagnostic_updater::DiagnosticStatusWrapper & stat); void callback_imu(const Imu::ConstSharedPtr imu_msg_ptr); - void callback_pose(const PoseWithCovarianceStamped::ConstSharedPtr pose_msg_ptr); + void callback_odom(const Odometry::ConstSharedPtr odom_msg_ptr); void timer_callback(); static geometry_msgs::msg::Vector3 transform_vector3( @@ -55,7 +57,7 @@ class GyroBiasEstimator : public rclcpp::Node const std::string output_frame_ = "base_link"; rclcpp::Subscription::SharedPtr imu_sub_; - rclcpp::Subscription::SharedPtr pose_sub_; + rclcpp::Subscription::SharedPtr odom_sub_; rclcpp::Publisher::SharedPtr gyro_bias_pub_; rclcpp::TimerBase::SharedPtr timer_; From 91481daab67f95623894a37cec231e7d42661b1d Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Tue, 24 Oct 2023 15:15:01 +0900 Subject: [PATCH 053/202] chore(processing_time_checker): update for windows size and rich display (#5389) Signed-off-by: Takamasa Horibe --- .../scripts/processing_time_checker.py | 71 ++++++++++++++++--- 1 file changed, 61 insertions(+), 10 deletions(-) diff --git a/planning/planning_debug_tools/scripts/processing_time_checker.py b/planning/planning_debug_tools/scripts/processing_time_checker.py index 3b80ce4e5588f..fa6bc57fb7ae5 100755 --- a/planning/planning_debug_tools/scripts/processing_time_checker.py +++ b/planning/planning_debug_tools/scripts/processing_time_checker.py @@ -16,6 +16,7 @@ import argparse +from collections import deque import os import sys @@ -25,11 +26,28 @@ class ProcessingTimeSubscriber(Node): - def __init__(self, max_display_time=150, display_frequency=5.0): + def __init__( + self, + max_display_time=150, + display_frequency=5.0, + window_size=1, + bar_scale=2, + display_character="|", + ): super().__init__("processing_time_subscriber") self.data_map = {} # {topic_name: data_value} + self.data_queue_map = {} # {topic_name: deque} + self.window_size = window_size self.max_display_time = max_display_time + self.bar_scale = bar_scale + self.display_character = display_character + + # Initialize a set to keep track of subscribed topics + self.subscribed_topics = set() + + # Call get_topic_list immediately and set a timer to call it regularly self.get_topic_list() + self.create_timer(1.0, self.get_topic_list) # update topic list every 1 second # Timer to print data at given frequency self.create_timer(1.0 / display_frequency, self.print_data) @@ -40,14 +58,22 @@ def get_topic_list(self): # Subscribe to topics with 'processing_time_ms' suffix for topic, types in topic_list: - if topic.endswith("processing_time_ms"): + if topic.endswith("processing_time_ms") and topic not in self.subscribed_topics: self.create_subscription( Float64Stamped, topic, lambda msg, topic=topic: self.callback(msg, topic), 1 ) self.get_logger().info(f"Subscribed to {topic} | Type: {types}") + self.subscribed_topics.add(topic) def callback(self, msg, topic): - self.data_map[topic] = msg.data + # Add the new data to the queue + if topic not in self.data_queue_map: + self.data_queue_map[topic] = deque(maxlen=self.window_size) + self.data_queue_map[topic].append(msg.data) + + # Calculate the average + avg_value = sum(self.data_queue_map[topic]) / len(self.data_queue_map[topic]) + self.data_map[topic] = avg_value def print_data(self): # Clear terminal @@ -61,9 +87,9 @@ def print_data(self): max_topic_length = max(map(len, self.data_map.keys())) # Generate the header based on the max_display_time - header_str = "topics".ljust(max_topic_length) + ":" - for i in range(0, self.max_display_time + 1, 20): - header_str += f" {i}ms".ljust(20) + header_str = f"topics (window size = {self.window_size})".ljust(max_topic_length) + ":" + for i in range(0, self.max_display_time + 1, 10): + header_str += f" {i}ms".ljust(self.bar_scale * 10) # Print the header print(header_str) @@ -74,8 +100,12 @@ def print_data(self): # Round the data to the third decimal place for display data_rounded = round(data, 3) # Calculate the number of bars to be displayed (clamped to max_display_time) - num_bars = int(min(data, self.max_display_time - 1)) + 1 - print(f"{topic.ljust(max_topic_length)}: {'|' * num_bars} ({data_rounded}ms)") + num_bars = ( + int(min(data * self.bar_scale, self.max_display_time * self.bar_scale - 1)) + 1 + ) # Convert bar_scale's reciprocal to milliseconds + print( + f"{topic.ljust(max_topic_length)}: {self.display_character * num_bars} [{data_rounded}ms]" + ) def main(args=None): @@ -84,16 +114,37 @@ def main(args=None): parser = argparse.ArgumentParser(description="Processing Time Subscriber Parameters") parser.add_argument( - "-m", "--max_display_time", type=int, default=150, help="Maximum display time in ms" + "-m", "--max_display_time", type=int, default=50, help="Maximum display time in ms" ) parser.add_argument( "-f", "--display_frequency", type=float, default=5.0, help="Display frequency in Hz" ) + parser.add_argument( + "-w", "--window_size", type=int, default=5, help="Number of samples to average" + ) + parser.add_argument( + "-bs", + "--bar_scale", + type=int, + default=2, + help="Number of bars per second. Default is 2 bars per second.", + ) + parser.add_argument( + "-dc", + "--display_character", + type=str, + default="|", + help="Character to use for the display. Default is '|'.", + ) args = parser.parse_args() rclpy.init(args=cmd_args) # Use the original command line arguments here subscriber = ProcessingTimeSubscriber( - max_display_time=args.max_display_time, display_frequency=args.display_frequency + max_display_time=args.max_display_time, + display_frequency=args.display_frequency, + window_size=args.window_size, + bar_scale=args.bar_scale, + display_character=args.display_character, ) rclpy.spin(subscriber) subscriber.destroy_node() From 189438e2729e5152d58b8ac7357c5c7202ec5b98 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Tue, 24 Oct 2023 15:16:56 +0900 Subject: [PATCH 054/202] refactor(topic_state_monitor): add state log message (#5378) * refactor(topic_state_monitor): add state log message Signed-off-by: Takamasa Horibe * add debug print Signed-off-by: Takamasa Horibe --------- Signed-off-by: Takamasa Horibe --- system/default_ad_api/src/operation_mode.cpp | 18 ++++++++++++++---- system/default_ad_api/src/operation_mode.hpp | 3 ++- .../src/topic_state_monitor_core.cpp | 11 +++++++++++ 3 files changed, 27 insertions(+), 5 deletions(-) diff --git a/system/default_ad_api/src/operation_mode.cpp b/system/default_ad_api/src/operation_mode.cpp index a61a1b75697ab..829585ed4b8b4 100644 --- a/system/default_ad_api/src/operation_mode.cpp +++ b/system/default_ad_api/src/operation_mode.cpp @@ -46,12 +46,11 @@ OperationModeNode::OperationModeNode(const rclcpp::NodeOptions & options) for (size_t i = 0; i < module_names.size(); ++i) { const auto name = "/system/component_state_monitor/component/autonomous/" + module_names[i]; const auto qos = rclcpp::QoS(1).transient_local(); - const auto callback = [this, i](const ModeChangeAvailable::ConstSharedPtr msg) { - module_states_[i] = msg->available; + const auto callback = [this, i, module_names](const ModeChangeAvailable::ConstSharedPtr msg) { + module_states_[module_names[i]] = msg->available; }; sub_module_states_.push_back(create_subscription(name, qos, callback)); } - module_states_.resize(module_names.size()); timer_ = rclcpp::create_timer( this, get_clock(), rclcpp::Rate(5.0).period(), std::bind(&OperationModeNode::on_timer, this)); @@ -137,11 +136,22 @@ void OperationModeNode::on_state(const OperationModeState::Message::ConstSharedP void OperationModeNode::on_timer() { bool autonomous_available = true; + std::string unhealthy_components = ""; for (const auto & state : module_states_) { - autonomous_available &= state; + if (!state.second) { + unhealthy_components += unhealthy_components.empty() ? state.first : ", " + state.first; + } + autonomous_available &= state.second; } mode_available_[OperationModeState::Message::AUTONOMOUS] = autonomous_available; + if (!unhealthy_components.empty()) { + RCLCPP_INFO_THROTTLE( + get_logger(), *get_clock(), 3000, + "%s component state is unhealthy. Autonomous is not available.", + unhealthy_components.c_str()); + } + update_state(); } diff --git a/system/default_ad_api/src/operation_mode.hpp b/system/default_ad_api/src/operation_mode.hpp index 5f5699f42cab7..1830b7041b566 100644 --- a/system/default_ad_api/src/operation_mode.hpp +++ b/system/default_ad_api/src/operation_mode.hpp @@ -20,6 +20,7 @@ #include #include +#include #include #include @@ -65,7 +66,7 @@ class OperationModeNode : public rclcpp::Node Cli cli_mode_; Cli cli_control_; - std::vector module_states_; + std::unordered_map module_states_; std::vector::SharedPtr> sub_module_states_; void on_change_to_stop( diff --git a/system/topic_state_monitor/src/topic_state_monitor_core.cpp b/system/topic_state_monitor/src/topic_state_monitor_core.cpp index 326193a58dc4e..68fa3764d8ecd 100644 --- a/system/topic_state_monitor/src/topic_state_monitor_core.cpp +++ b/system/topic_state_monitor/src/topic_state_monitor_core.cpp @@ -151,6 +151,13 @@ void TopicStateMonitorNode::checkTopicStatus(diagnostic_updater::DiagnosticStatu stat.addf("topic", "%s", node_param_.topic.c_str()); } + const auto print_warn = [&](const std::string & msg) { + RCLCPP_WARN_THROTTLE(get_logger(), *get_clock(), 3000, "%s", msg.c_str()); + }; + const auto print_debug = [&](const std::string & msg) { + RCLCPP_DEBUG_THROTTLE(get_logger(), *get_clock(), 3000, "%s", msg.c_str()); + }; + // Judge level int8_t level = DiagnosticStatus::OK; if (topic_status == TopicStatus::Ok) { @@ -159,15 +166,19 @@ void TopicStateMonitorNode::checkTopicStatus(diagnostic_updater::DiagnosticStatu } else if (topic_status == TopicStatus::NotReceived) { level = DiagnosticStatus::ERROR; stat.add("status", "NotReceived"); + print_debug(node_param_.topic + " has not received."); } else if (topic_status == TopicStatus::WarnRate) { level = DiagnosticStatus::WARN; stat.add("status", "WarnRate"); + print_warn(node_param_.topic + " topic rate has dropped to the warning level."); } else if (topic_status == TopicStatus::ErrorRate) { level = DiagnosticStatus::ERROR; stat.add("status", "ErrorRate"); + print_warn(node_param_.topic + " topic rate has dropped to the error level."); } else if (topic_status == TopicStatus::Timeout) { level = DiagnosticStatus::ERROR; stat.add("status", "Timeout"); + print_warn(node_param_.topic + " topic is timeout."); } // Add key-value From cc0b202353b8ef55cb5f54f9ade446bdd7d7a242 Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Tue, 24 Oct 2023 16:26:06 +0900 Subject: [PATCH 055/202] refactor(localization): add localization_util package (#5377) * Added localization_util Signed-off-by: Shintaro Sakoda * Fixed library Signed-off-by: Shintaro Sakoda * Separated a package tree_structured_parzen_estimator Signed-off-by: Shintaro Sakoda * style(pre-commit): autofix * Fixed library Signed-off-by: Shintaro Sakoda * Added maintainer Signed-off-by: Shintaro Sakoda --------- Signed-off-by: Shintaro Sakoda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- localization/localization_util/CMakeLists.txt | 15 +++++++ localization/localization_util/README.md | 5 +++ .../localization_util}/matrix_type.hpp | 6 +-- .../pose_array_interpolator.hpp | 8 ++-- .../tf2_listener_module.hpp | 6 +-- .../include/localization_util}/util_func.hpp | 6 +-- localization/localization_util/package.xml | 40 +++++++++++++++++++ .../src/pose_array_interpolator.cpp | 2 +- .../src/tf2_listener_module.cpp | 2 +- .../src/util_func.cpp | 4 +- localization/ndt_scan_matcher/CMakeLists.txt | 12 ------ .../ndt_scan_matcher/map_update_module.hpp | 4 +- .../ndt_scan_matcher_core.hpp | 2 +- localization/ndt_scan_matcher/package.xml | 2 + localization/ndt_scan_matcher/src/debug.cpp | 2 +- .../src/ndt_scan_matcher_core.cpp | 8 ++-- .../CMakeLists.txt | 23 +++++++++++ .../README.md | 5 +++ .../tree_structured_parzen_estimator.hpp | 6 +-- .../package.xml | 23 +++++++++++ .../src/tree_structured_parzen_estimator.cpp | 2 +- .../test/test_tpe.cpp | 2 +- 22 files changed, 143 insertions(+), 42 deletions(-) create mode 100644 localization/localization_util/CMakeLists.txt create mode 100644 localization/localization_util/README.md rename localization/{ndt_scan_matcher/include/ndt_scan_matcher => localization_util/include/localization_util}/matrix_type.hpp (84%) rename localization/{ndt_scan_matcher/include/ndt_scan_matcher => localization_util/include/localization_util}/pose_array_interpolator.hpp (90%) rename localization/{ndt_scan_matcher/include/ndt_scan_matcher => localization_util/include/localization_util}/tf2_listener_module.hpp (88%) rename localization/{ndt_scan_matcher/include/ndt_scan_matcher => localization_util/include/localization_util}/util_func.hpp (96%) create mode 100644 localization/localization_util/package.xml rename localization/{ndt_scan_matcher => localization_util}/src/pose_array_interpolator.cpp (98%) rename localization/{ndt_scan_matcher => localization_util}/src/tf2_listener_module.cpp (97%) rename localization/{ndt_scan_matcher => localization_util}/src/util_func.cpp (99%) create mode 100644 localization/tree_structured_parzen_estimator/CMakeLists.txt create mode 100644 localization/tree_structured_parzen_estimator/README.md rename localization/{ndt_scan_matcher/include/ndt_scan_matcher => tree_structured_parzen_estimator/include/tree_structured_parzen_estimator}/tree_structured_parzen_estimator.hpp (90%) create mode 100644 localization/tree_structured_parzen_estimator/package.xml rename localization/{ndt_scan_matcher => tree_structured_parzen_estimator}/src/tree_structured_parzen_estimator.cpp (98%) rename localization/{ndt_scan_matcher => tree_structured_parzen_estimator}/test/test_tpe.cpp (96%) diff --git a/localization/localization_util/CMakeLists.txt b/localization/localization_util/CMakeLists.txt new file mode 100644 index 0000000000000..9490ffb67723b --- /dev/null +++ b/localization/localization_util/CMakeLists.txt @@ -0,0 +1,15 @@ +cmake_minimum_required(VERSION 3.14) +project(localization_util) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +ament_auto_add_library(localization_util SHARED + src/util_func.cpp + src/pose_array_interpolator.cpp + src/tf2_listener_module.cpp +) + +ament_auto_package( + INSTALL_TO_SHARE +) diff --git a/localization/localization_util/README.md b/localization/localization_util/README.md new file mode 100644 index 0000000000000..a3e980464d0c6 --- /dev/null +++ b/localization/localization_util/README.md @@ -0,0 +1,5 @@ +# localization_util + +`localization_util`` is a localization utility package. + +This package does not have a node, it is just a library. diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/matrix_type.hpp b/localization/localization_util/include/localization_util/matrix_type.hpp similarity index 84% rename from localization/ndt_scan_matcher/include/ndt_scan_matcher/matrix_type.hpp rename to localization/localization_util/include/localization_util/matrix_type.hpp index 038ed4549eb2f..d9ec9b369127a 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/matrix_type.hpp +++ b/localization/localization_util/include/localization_util/matrix_type.hpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef NDT_SCAN_MATCHER__MATRIX_TYPE_HPP_ -#define NDT_SCAN_MATCHER__MATRIX_TYPE_HPP_ +#ifndef LOCALIZATION_UTIL__MATRIX_TYPE_HPP_ +#define LOCALIZATION_UTIL__MATRIX_TYPE_HPP_ #include using Matrix6d = Eigen::Matrix; using RowMatrixXd = Eigen::Matrix; -#endif // NDT_SCAN_MATCHER__MATRIX_TYPE_HPP_ +#endif // LOCALIZATION_UTIL__MATRIX_TYPE_HPP_ diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/pose_array_interpolator.hpp b/localization/localization_util/include/localization_util/pose_array_interpolator.hpp similarity index 90% rename from localization/ndt_scan_matcher/include/ndt_scan_matcher/pose_array_interpolator.hpp rename to localization/localization_util/include/localization_util/pose_array_interpolator.hpp index f1e7dfb3f544b..998d8465733f5 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/pose_array_interpolator.hpp +++ b/localization/localization_util/include/localization_util/pose_array_interpolator.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef NDT_SCAN_MATCHER__POSE_ARRAY_INTERPOLATOR_HPP_ -#define NDT_SCAN_MATCHER__POSE_ARRAY_INTERPOLATOR_HPP_ +#ifndef LOCALIZATION_UTIL__POSE_ARRAY_INTERPOLATOR_HPP_ +#define LOCALIZATION_UTIL__POSE_ARRAY_INTERPOLATOR_HPP_ -#include "ndt_scan_matcher/util_func.hpp" +#include "localization_util/util_func.hpp" #include @@ -59,4 +59,4 @@ class PoseArrayInterpolator const geometry_msgs::msg::Point & reference_point, const double distance_tolerance_m_) const; }; -#endif // NDT_SCAN_MATCHER__POSE_ARRAY_INTERPOLATOR_HPP_ +#endif // LOCALIZATION_UTIL__POSE_ARRAY_INTERPOLATOR_HPP_ diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/tf2_listener_module.hpp b/localization/localization_util/include/localization_util/tf2_listener_module.hpp similarity index 88% rename from localization/ndt_scan_matcher/include/ndt_scan_matcher/tf2_listener_module.hpp rename to localization/localization_util/include/localization_util/tf2_listener_module.hpp index 159acbd75ce3d..b332f9effe0e0 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/tf2_listener_module.hpp +++ b/localization/localization_util/include/localization_util/tf2_listener_module.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef NDT_SCAN_MATCHER__TF2_LISTENER_MODULE_HPP_ -#define NDT_SCAN_MATCHER__TF2_LISTENER_MODULE_HPP_ +#ifndef LOCALIZATION_UTIL__TF2_LISTENER_MODULE_HPP_ +#define LOCALIZATION_UTIL__TF2_LISTENER_MODULE_HPP_ #include @@ -40,4 +40,4 @@ class Tf2ListenerModule tf2_ros::TransformListener tf2_listener_; }; -#endif // NDT_SCAN_MATCHER__TF2_LISTENER_MODULE_HPP_ +#endif // LOCALIZATION_UTIL__TF2_LISTENER_MODULE_HPP_ diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/util_func.hpp b/localization/localization_util/include/localization_util/util_func.hpp similarity index 96% rename from localization/ndt_scan_matcher/include/ndt_scan_matcher/util_func.hpp rename to localization/localization_util/include/localization_util/util_func.hpp index 5c37cef36c422..bd9a2b9305e25 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/util_func.hpp +++ b/localization/localization_util/include/localization_util/util_func.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef NDT_SCAN_MATCHER__UTIL_FUNC_HPP_ -#define NDT_SCAN_MATCHER__UTIL_FUNC_HPP_ +#ifndef LOCALIZATION_UTIL__UTIL_FUNC_HPP_ +#define LOCALIZATION_UTIL__UTIL_FUNC_HPP_ #include #include @@ -91,4 +91,4 @@ void output_pose_with_cov_to_log( const rclcpp::Logger logger, const std::string & prefix, const geometry_msgs::msg::PoseWithCovarianceStamped & pose_with_cov); -#endif // NDT_SCAN_MATCHER__UTIL_FUNC_HPP_ +#endif // LOCALIZATION_UTIL__UTIL_FUNC_HPP_ diff --git a/localization/localization_util/package.xml b/localization/localization_util/package.xml new file mode 100644 index 0000000000000..20f9b160212b5 --- /dev/null +++ b/localization/localization_util/package.xml @@ -0,0 +1,40 @@ + + + + localization_util + 0.1.0 + The localization_util package + Yamato Ando + Masahiro Sakamoto + Shintaro Sakoda + Kento Yabuuchi + Apache License 2.0 + Yamato Ando + + ament_cmake_auto + autoware_cmake + + fmt + geometry_msgs + nav_msgs + rclcpp + sensor_msgs + std_msgs + std_srvs + tf2 + tf2_eigen + tf2_geometry_msgs + tf2_ros + tf2_sensor_msgs + tier4_autoware_utils + tier4_debug_msgs + tier4_localization_msgs + visualization_msgs + + ament_cmake_cppcheck + ament_lint_auto + + + ament_cmake + + diff --git a/localization/ndt_scan_matcher/src/pose_array_interpolator.cpp b/localization/localization_util/src/pose_array_interpolator.cpp similarity index 98% rename from localization/ndt_scan_matcher/src/pose_array_interpolator.cpp rename to localization/localization_util/src/pose_array_interpolator.cpp index f09b71523e804..ebc904fcf8d38 100644 --- a/localization/ndt_scan_matcher/src/pose_array_interpolator.cpp +++ b/localization/localization_util/src/pose_array_interpolator.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "ndt_scan_matcher/pose_array_interpolator.hpp" +#include "localization_util/pose_array_interpolator.hpp" PoseArrayInterpolator::PoseArrayInterpolator( rclcpp::Node * node, const rclcpp::Time & target_ros_time, diff --git a/localization/ndt_scan_matcher/src/tf2_listener_module.cpp b/localization/localization_util/src/tf2_listener_module.cpp similarity index 97% rename from localization/ndt_scan_matcher/src/tf2_listener_module.cpp rename to localization/localization_util/src/tf2_listener_module.cpp index 364952a631f06..8a19ceec9f30d 100644 --- a/localization/ndt_scan_matcher/src/tf2_listener_module.cpp +++ b/localization/localization_util/src/tf2_listener_module.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "ndt_scan_matcher/tf2_listener_module.hpp" +#include "localization_util/tf2_listener_module.hpp" #include diff --git a/localization/ndt_scan_matcher/src/util_func.cpp b/localization/localization_util/src/util_func.cpp similarity index 99% rename from localization/ndt_scan_matcher/src/util_func.cpp rename to localization/localization_util/src/util_func.cpp index 52cb7844ab241..865cc02cff293 100644 --- a/localization/ndt_scan_matcher/src/util_func.cpp +++ b/localization/localization_util/src/util_func.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "ndt_scan_matcher/util_func.hpp" +#include "localization_util/util_func.hpp" -#include "ndt_scan_matcher/matrix_type.hpp" +#include "localization_util/matrix_type.hpp" static std::random_device seed_gen; diff --git a/localization/ndt_scan_matcher/CMakeLists.txt b/localization/ndt_scan_matcher/CMakeLists.txt index 955234f95ff18..79491a85a0a66 100644 --- a/localization/ndt_scan_matcher/CMakeLists.txt +++ b/localization/ndt_scan_matcher/CMakeLists.txt @@ -29,12 +29,8 @@ ament_auto_add_executable(ndt_scan_matcher src/debug.cpp src/ndt_scan_matcher_node.cpp src/ndt_scan_matcher_core.cpp - src/util_func.cpp - src/pose_array_interpolator.cpp - src/tf2_listener_module.cpp src/map_module.cpp src/map_update_module.cpp - src/tree_structured_parzen_estimator.cpp ) link_directories(${PCL_LIBRARY_DIRS}) @@ -45,14 +41,6 @@ if(BUILD_TESTING) test/test_ndt_scan_matcher_launch.py TIMEOUT "30" ) - - find_package(ament_cmake_gtest REQUIRED) - ament_add_gtest(test_tpe - test/test_tpe.cpp - src/tree_structured_parzen_estimator.cpp - ) - target_include_directories(test_tpe PRIVATE include) - target_link_libraries(test_tpe) endif() ament_auto_package( diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp index 4f630bb8c5898..13721c03ca22e 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp @@ -15,10 +15,10 @@ #ifndef NDT_SCAN_MATCHER__MAP_UPDATE_MODULE_HPP_ #define NDT_SCAN_MATCHER__MAP_UPDATE_MODULE_HPP_ +#include "localization_util/tf2_listener_module.hpp" +#include "localization_util/util_func.hpp" #include "ndt_scan_matcher/debug.hpp" #include "ndt_scan_matcher/particle.hpp" -#include "ndt_scan_matcher/tf2_listener_module.hpp" -#include "ndt_scan_matcher/util_func.hpp" #include #include diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp index 153418e5a8f75..e5f46b5022b51 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp @@ -17,9 +17,9 @@ #define FMT_HEADER_ONLY +#include "localization_util/tf2_listener_module.hpp" #include "ndt_scan_matcher/map_module.hpp" #include "ndt_scan_matcher/map_update_module.hpp" -#include "ndt_scan_matcher/tf2_listener_module.hpp" #include diff --git a/localization/ndt_scan_matcher/package.xml b/localization/ndt_scan_matcher/package.xml index 986179b9e02e2..a9083c4ae0ae4 100644 --- a/localization/ndt_scan_matcher/package.xml +++ b/localization/ndt_scan_matcher/package.xml @@ -19,6 +19,7 @@ fmt geometry_msgs libpcl-all-dev + localization_util nav_msgs ndt_omp pcl_conversions @@ -34,6 +35,7 @@ tier4_autoware_utils tier4_debug_msgs tier4_localization_msgs + tree_structured_parzen_estimator visualization_msgs ament_cmake_cppcheck diff --git a/localization/ndt_scan_matcher/src/debug.cpp b/localization/ndt_scan_matcher/src/debug.cpp index 9c82e06d89b80..941f682de5803 100644 --- a/localization/ndt_scan_matcher/src/debug.cpp +++ b/localization/ndt_scan_matcher/src/debug.cpp @@ -14,7 +14,7 @@ #include "ndt_scan_matcher/debug.hpp" -#include "ndt_scan_matcher/util_func.hpp" +#include "localization_util/util_func.hpp" visualization_msgs::msg::MarkerArray make_debug_markers( const builtin_interfaces::msg::Time & stamp, const std::string & map_frame_, diff --git a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp index 8e583fd3a666b..b38e3f0826184 100644 --- a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp +++ b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp @@ -14,11 +14,11 @@ #include "ndt_scan_matcher/ndt_scan_matcher_core.hpp" -#include "ndt_scan_matcher/matrix_type.hpp" +#include "localization_util/matrix_type.hpp" +#include "localization_util/pose_array_interpolator.hpp" +#include "localization_util/util_func.hpp" #include "ndt_scan_matcher/particle.hpp" -#include "ndt_scan_matcher/pose_array_interpolator.hpp" -#include "ndt_scan_matcher/tree_structured_parzen_estimator.hpp" -#include "ndt_scan_matcher/util_func.hpp" +#include "tree_structured_parzen_estimator/tree_structured_parzen_estimator.hpp" #include #include diff --git a/localization/tree_structured_parzen_estimator/CMakeLists.txt b/localization/tree_structured_parzen_estimator/CMakeLists.txt new file mode 100644 index 0000000000000..7b687a12a003c --- /dev/null +++ b/localization/tree_structured_parzen_estimator/CMakeLists.txt @@ -0,0 +1,23 @@ +cmake_minimum_required(VERSION 3.14) +project(tree_structured_parzen_estimator) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +ament_auto_add_library(tree_structured_parzen_estimator SHARED + src/tree_structured_parzen_estimator.cpp +) + +if(BUILD_TESTING) + find_package(ament_cmake_gtest REQUIRED) + ament_add_gtest(test_tpe + test/test_tpe.cpp + src/tree_structured_parzen_estimator.cpp + ) + target_include_directories(test_tpe PRIVATE include) + target_link_libraries(test_tpe) +endif() + +ament_auto_package( + INSTALL_TO_SHARE +) diff --git a/localization/tree_structured_parzen_estimator/README.md b/localization/tree_structured_parzen_estimator/README.md new file mode 100644 index 0000000000000..2b21e65929485 --- /dev/null +++ b/localization/tree_structured_parzen_estimator/README.md @@ -0,0 +1,5 @@ +# tree_structured_parzen_estimator + +`tree_structured_parzen_estimator`` is a package for black-box optimization. + +This package does not have a node, it is just a library. diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/tree_structured_parzen_estimator.hpp b/localization/tree_structured_parzen_estimator/include/tree_structured_parzen_estimator/tree_structured_parzen_estimator.hpp similarity index 90% rename from localization/ndt_scan_matcher/include/ndt_scan_matcher/tree_structured_parzen_estimator.hpp rename to localization/tree_structured_parzen_estimator/include/tree_structured_parzen_estimator/tree_structured_parzen_estimator.hpp index 3c79ab75dba48..b7b522b4e6b76 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/tree_structured_parzen_estimator.hpp +++ b/localization/tree_structured_parzen_estimator/include/tree_structured_parzen_estimator/tree_structured_parzen_estimator.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef NDT_SCAN_MATCHER__TREE_STRUCTURED_PARZEN_ESTIMATOR_HPP_ -#define NDT_SCAN_MATCHER__TREE_STRUCTURED_PARZEN_ESTIMATOR_HPP_ +#ifndef TREE_STRUCTURED_PARZEN_ESTIMATOR__TREE_STRUCTURED_PARZEN_ESTIMATOR_HPP_ +#define TREE_STRUCTURED_PARZEN_ESTIMATOR__TREE_STRUCTURED_PARZEN_ESTIMATOR_HPP_ /* A implementation of tree-structured parzen estimator (TPE) @@ -77,4 +77,4 @@ class TreeStructuredParzenEstimator const Input base_stddev_; }; -#endif // NDT_SCAN_MATCHER__TREE_STRUCTURED_PARZEN_ESTIMATOR_HPP_ +#endif // TREE_STRUCTURED_PARZEN_ESTIMATOR__TREE_STRUCTURED_PARZEN_ESTIMATOR_HPP_ diff --git a/localization/tree_structured_parzen_estimator/package.xml b/localization/tree_structured_parzen_estimator/package.xml new file mode 100644 index 0000000000000..b699d5c69e610 --- /dev/null +++ b/localization/tree_structured_parzen_estimator/package.xml @@ -0,0 +1,23 @@ + + + + tree_structured_parzen_estimator + 0.1.0 + The tree_structured_parzen_estimator package + Yamato Ando + Masahiro Sakamoto + Shintaro Sakoda + Kento Yabuuchi + Apache License 2.0 + Shintaro Sakoda + + ament_cmake_auto + autoware_cmake + + ament_cmake_cppcheck + ament_lint_auto + + + ament_cmake + + diff --git a/localization/ndt_scan_matcher/src/tree_structured_parzen_estimator.cpp b/localization/tree_structured_parzen_estimator/src/tree_structured_parzen_estimator.cpp similarity index 98% rename from localization/ndt_scan_matcher/src/tree_structured_parzen_estimator.cpp rename to localization/tree_structured_parzen_estimator/src/tree_structured_parzen_estimator.cpp index b92c8a075252c..99c70a844f331 100644 --- a/localization/ndt_scan_matcher/src/tree_structured_parzen_estimator.cpp +++ b/localization/tree_structured_parzen_estimator/src/tree_structured_parzen_estimator.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "ndt_scan_matcher/tree_structured_parzen_estimator.hpp" +#include "tree_structured_parzen_estimator/tree_structured_parzen_estimator.hpp" #include #include diff --git a/localization/ndt_scan_matcher/test/test_tpe.cpp b/localization/tree_structured_parzen_estimator/test/test_tpe.cpp similarity index 96% rename from localization/ndt_scan_matcher/test/test_tpe.cpp rename to localization/tree_structured_parzen_estimator/test/test_tpe.cpp index fb7190f4a1c74..32eb66e70fb16 100644 --- a/localization/ndt_scan_matcher/test/test_tpe.cpp +++ b/localization/tree_structured_parzen_estimator/test/test_tpe.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "ndt_scan_matcher/tree_structured_parzen_estimator.hpp" +#include "tree_structured_parzen_estimator/tree_structured_parzen_estimator.hpp" #include From db2768626a2e60e859934e0155b42088ef592be5 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 24 Oct 2023 17:03:54 +0900 Subject: [PATCH 056/202] fix(intersection): wrong argument order (#5386) Signed-off-by: Takayuki Murooka --- planning/behavior_velocity_intersection_module/src/util.cpp | 4 ++-- planning/behavior_velocity_intersection_module/src/util.hpp | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/planning/behavior_velocity_intersection_module/src/util.cpp b/planning/behavior_velocity_intersection_module/src/util.cpp index 27310f2129937..42412bbccd424 100644 --- a/planning/behavior_velocity_intersection_module/src/util.cpp +++ b/planning/behavior_velocity_intersection_module/src/util.cpp @@ -269,8 +269,8 @@ std::optional generateIntersectionStopLines( const lanelet::CompoundPolygon3d & first_detection_area, const std::shared_ptr & planner_data, const InterpolatedPathInfo & interpolated_path_info, const bool use_stuck_stopline, - const double stop_line_margin, const double peeking_offset, const double max_accel, - const double max_jerk, const double delay_response_time, + const double stop_line_margin, const double max_accel, const double max_jerk, + const double delay_response_time, const double peeking_offset, autoware_auto_planning_msgs::msg::PathWithLaneId * original_path) { const auto & path_ip = interpolated_path_info.path; diff --git a/planning/behavior_velocity_intersection_module/src/util.hpp b/planning/behavior_velocity_intersection_module/src/util.hpp index 125d3bdfb570a..5faacd4325b06 100644 --- a/planning/behavior_velocity_intersection_module/src/util.hpp +++ b/planning/behavior_velocity_intersection_module/src/util.hpp @@ -70,8 +70,8 @@ std::optional generateIntersectionStopLines( const lanelet::CompoundPolygon3d & first_detection_area, const std::shared_ptr & planner_data, const InterpolatedPathInfo & interpolated_path_info, const bool use_stuck_stopline, - const double stop_line_margin, const double peeking_offset, const double max_accel, - const double max_jerk, const double delay_response_time, + const double stop_line_margin, const double max_accel, const double max_jerk, + const double delay_response_time, const double peeking_offset, autoware_auto_planning_msgs::msg::PathWithLaneId * original_path); std::optional getFirstPointInsidePolygon( From f400b912c1d0570a94b5fcf969f32fca2739b33a Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 24 Oct 2023 21:39:33 +0900 Subject: [PATCH 057/202] fix(utils): remove sharp angle bound (#5384) * fix(utils): remove sharp angle bound Signed-off-by: satoshi-ota * fix(utils): guard invalid access Signed-off-by: satoshi-ota * chore(utils): add comment Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../behavior_path_planner/src/utils/utils.cpp | 20 ++++++++++++++++--- 1 file changed, 17 insertions(+), 3 deletions(-) diff --git a/planning/behavior_path_planner/src/utils/utils.cpp b/planning/behavior_path_planner/src/utils/utils.cpp index 6927327e24ef4..9b10dfc32457f 100644 --- a/planning/behavior_path_planner/src/utils/utils.cpp +++ b/planning/behavior_path_planner/src/utils/utils.cpp @@ -2011,6 +2011,11 @@ void makeBoundLongitudinallyMonotonic( std::vector ret = bound; auto itr = std::next(ret.begin()); while (std::next(itr) != ret.end()) { + if (itr == ret.begin()) { + itr++; + continue; + } + const auto p1 = *std::prev(itr); const auto p2 = *itr; const auto p3 = *std::next(itr); @@ -2024,11 +2029,20 @@ void makeBoundLongitudinallyMonotonic( const auto dist_3to2 = tier4_autoware_utils::calcDistance3d(p3, p2); constexpr double epsilon = 1e-3; + + // Remove overlapped point. + if (dist_1to2 < epsilon || dist_3to2 < epsilon) { + itr = std::prev(ret.erase(itr)); + continue; + } + + // If the angle between the points is sharper than 45 degrees, remove the middle point. if (std::cos(M_PI_4) < product / dist_1to2 / dist_3to2 + epsilon) { - itr = ret.erase(itr); - } else { - itr++; + itr = std::prev(ret.erase(itr)); + continue; } + + itr++; } return ret; From fe650db2ce9dea71c9767cd3f0619c345eaf46bf Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Wed, 25 Oct 2023 10:38:52 +0900 Subject: [PATCH 058/202] feat(intersection): check path margin for overshoot vehicles on red light (#5394) --- .../config/intersection.param.yaml | 2 + .../src/debug.cpp | 6 +++ .../src/manager.cpp | 3 ++ .../src/scene_intersection.cpp | 51 ++++++++++++++++++- .../src/scene_intersection.hpp | 4 ++ .../src/util.cpp | 11 +++- .../src/util_type.hpp | 1 + 7 files changed, 74 insertions(+), 4 deletions(-) diff --git a/planning/behavior_velocity_intersection_module/config/intersection.param.yaml b/planning/behavior_velocity_intersection_module/config/intersection.param.yaml index fde55dc7a6c55..82a5f65622d0b 100644 --- a/planning/behavior_velocity_intersection_module/config/intersection.param.yaml +++ b/planning/behavior_velocity_intersection_module/config/intersection.param.yaml @@ -56,6 +56,8 @@ object_dist_to_stopline: 10.0 # [m] ignore_on_amber_traffic_light: object_expected_deceleration: 2.0 # [m/ss] + ignore_on_red_traffic_light: + object_margin_to_path: 2.0 occlusion: enable: false diff --git a/planning/behavior_velocity_intersection_module/src/debug.cpp b/planning/behavior_velocity_intersection_module/src/debug.cpp index f472c4bf51e31..8d9beb34d05ee 100644 --- a/planning/behavior_velocity_intersection_module/src/debug.cpp +++ b/planning/behavior_velocity_intersection_module/src/debug.cpp @@ -230,6 +230,12 @@ visualization_msgs::msg::MarkerArray IntersectionModule::createDebugMarkerArray( debug_data_.amber_ignore_targets, "amber_ignore_targets", module_id_, now, 0.0, 1.0, 0.0), &debug_marker_array, now); + appendMarkerArray( + debug::createObjectsMarkerArray( + debug_data_.red_overshoot_ignore_targets, "red_overshoot_ignore_targets", module_id_, now, + 0.0, 1.0, 0.0), + &debug_marker_array, now); + appendMarkerArray( debug::createObjectsMarkerArray( debug_data_.stuck_targets, "stuck_targets", module_id_, now, 0.99, 0.99, 0.2), diff --git a/planning/behavior_velocity_intersection_module/src/manager.cpp b/planning/behavior_velocity_intersection_module/src/manager.cpp index a65e06eedcdf0..3c0d7fa0b4f1c 100644 --- a/planning/behavior_velocity_intersection_module/src/manager.cpp +++ b/planning/behavior_velocity_intersection_module/src/manager.cpp @@ -139,6 +139,9 @@ IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node) ip.collision_detection.ignore_on_amber_traffic_light.object_expected_deceleration = getOrDeclareParameter( node, ns + ".collision_detection.ignore_on_amber_traffic_light.object_expected_deceleration"); + ip.collision_detection.ignore_on_red_traffic_light.object_margin_to_path = + getOrDeclareParameter( + node, ns + ".collision_detection.ignore_on_red_traffic_light.object_margin_to_path"); ip.occlusion.enable = getOrDeclareParameter(node, ns + ".occlusion.enable"); ip.occlusion.occlusion_attention_area_length = diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp index 4def152567b32..53a99a1ee6b4d 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -30,6 +30,7 @@ #include #include +#include #include #include #include @@ -1519,18 +1520,64 @@ bool IntersectionModule::checkCollision( .object_expected_deceleration)); return dist_to_stop_line > braking_distance; }; - + const auto isTolerableOvershoot = [&](const util::TargetObject & target_object) { + if ( + !target_object.attention_lanelet || !target_object.dist_to_stop_line || + !target_object.stop_line) { + return false; + } + const double dist_to_stop_line = target_object.dist_to_stop_line.value(); + const double v = target_object.object.kinematics.initial_twist_with_covariance.twist.linear.x; + const double braking_distance = + v * v / + (2.0 * std::fabs(planner_param_.collision_detection.ignore_on_amber_traffic_light + .object_expected_deceleration)); + if (dist_to_stop_line > braking_distance) { + return false; + } + const auto stopline_front = target_object.stop_line.value().front(); + const auto stopline_back = target_object.stop_line.value().back(); + tier4_autoware_utils::LineString2d object_line; + object_line.emplace_back( + (stopline_front.x() + stopline_back.x()) / 2.0, + (stopline_front.y() + stopline_back.y()) / 2.0); + const auto stopline_mid = object_line.front(); + const auto endpoint = target_object.attention_lanelet.value().centerline().back(); + object_line.emplace_back(endpoint.x(), endpoint.y()); + std::vector intersections; + bg::intersection(object_line, ego_lane.centerline2d().basicLineString(), intersections); + if (intersections.empty()) { + return false; + } + const auto collision_point = intersections.front(); + // distance from object expected stop position to collision point + const double stopline_to_object = -1.0 * dist_to_stop_line + braking_distance; + const double stopline_to_collision = + std::hypot(collision_point.x() - stopline_mid.x(), collision_point.y() - stopline_mid.y()); + const double object2collision = stopline_to_collision - stopline_to_object; + const double margin = + planner_param_.collision_detection.ignore_on_red_traffic_light.object_margin_to_path; + return (object2collision > margin) || (object2collision < 0); + }; // check collision between predicted_path and ego_area bool collision_detected = false; for (const auto & target_object : target_objects->all_attention_objects) { const auto & object = target_object.object; // If the vehicle is expected to stop before their stopline, ignore + const bool expected_to_stop_before_stopline = expectedToStopBeforeStopLine(target_object); if ( traffic_prioritized_level == util::TrafficPrioritizedLevel::PARTIALLY_PRIORITIZED && - expectedToStopBeforeStopLine(target_object)) { + expected_to_stop_before_stopline) { debug_data_.amber_ignore_targets.objects.push_back(object); continue; } + const bool is_tolerable_overshoot = isTolerableOvershoot(target_object); + if ( + traffic_prioritized_level == util::TrafficPrioritizedLevel::FULLY_PRIORITIZED && + !expected_to_stop_before_stopline && is_tolerable_overshoot) { + debug_data_.red_overshoot_ignore_targets.objects.push_back(object); + continue; + } for (const auto & predicted_path : object.kinematics.predicted_paths) { if ( predicted_path.confidence < diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp index 764f5bd7fe058..93fec171ec0d2 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp @@ -118,6 +118,10 @@ class IntersectionModule : public SceneModuleInterface { double object_expected_deceleration; } ignore_on_amber_traffic_light; + struct IgnoreOnRedTrafficLight + { + double object_margin_to_path; + } ignore_on_red_traffic_light; } collision_detection; struct Occlusion { diff --git a/planning/behavior_velocity_intersection_module/src/util.cpp b/planning/behavior_velocity_intersection_module/src/util.cpp index 42412bbccd424..25eaaf4d8cb9d 100644 --- a/planning/behavior_velocity_intersection_module/src/util.cpp +++ b/planning/behavior_velocity_intersection_module/src/util.cpp @@ -841,9 +841,16 @@ IntersectionLanelets getObjectiveLanelets( result.attention_stop_lines_.push_back(stop_line); } result.attention_non_preceding_ = std::move(detection_lanelets); - // TODO(Mamoru Sobue): find stop lines for attention_non_preceding_ if needed for (unsigned i = 0; i < result.attention_non_preceding_.size(); ++i) { - result.attention_non_preceding_stop_lines_.push_back(std::nullopt); + std::optional stop_line = std::nullopt; + const auto & ll = result.attention_non_preceding_.at(i); + const auto traffic_lights = ll.regulatoryElementsAs(); + for (const auto & traffic_light : traffic_lights) { + const auto stop_line_opt = traffic_light->stopLine(); + if (!stop_line_opt) continue; + stop_line = stop_line_opt.get(); + } + result.attention_non_preceding_stop_lines_.push_back(stop_line); } result.conflicting_ = std::move(conflicting_ex_ego_lanelets); result.adjacent_ = planning_utils::getConstLaneletsFromIds(lanelet_map_ptr, associative_ids); diff --git a/planning/behavior_velocity_intersection_module/src/util_type.hpp b/planning/behavior_velocity_intersection_module/src/util_type.hpp index fdcf05a97a7a9..73e60aea6471a 100644 --- a/planning/behavior_velocity_intersection_module/src/util_type.hpp +++ b/planning/behavior_velocity_intersection_module/src/util_type.hpp @@ -49,6 +49,7 @@ struct DebugData std::vector candidate_collision_object_polygons; autoware_auto_perception_msgs::msg::PredictedObjects conflicting_targets; autoware_auto_perception_msgs::msg::PredictedObjects amber_ignore_targets; + autoware_auto_perception_msgs::msg::PredictedObjects red_overshoot_ignore_targets; autoware_auto_perception_msgs::msg::PredictedObjects stuck_targets; autoware_auto_perception_msgs::msg::PredictedObjects yield_stuck_targets; std::vector occlusion_polygons; From cb0279964cb84db290fca6528a97c00d9eb188a7 Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Wed, 25 Oct 2023 11:28:24 +0900 Subject: [PATCH 059/202] fix(goal_planner): change debug polygons to contain the nominal margin (#5365) * fixed so that the visualize polygons contain the nominal margin, with some refactoring --------- Signed-off-by: Yuki Takagi Co-authored-by: Kyoichi Sugahara --- .../path_safety_checker/safety_check.hpp | 14 ++---- .../goal_planner/goal_planner_module.cpp | 45 ++++++++++++++----- .../path_safety_checker/safety_check.cpp | 44 +++--------------- 3 files changed, 42 insertions(+), 61 deletions(-) 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 8409116236169..b8bd1629d5f3f 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 @@ -107,10 +107,6 @@ bool checkCollision( const BehaviorPathPlannerParameters & common_parameters, const RSSparams & rss_parameters, const double hysteresis_factor, CollisionCheckDebug & debug); -std::vector generatePolygonsWithStoppingAndInertialMargin( - const PathWithLaneId & ego_path, const double base_to_front, const double base_to_rear, - const double width, const double maximum_deceleration, const double max_extra_stopping_margin); - /** * @brief Iterate the points in the ego and target's predicted path and * perform safety check for each of the iterated points. @@ -133,13 +129,9 @@ std::vector getCollidedPolygons( const BehaviorPathPlannerParameters & common_parameters, const RSSparams & rss_parameters, const double hysteresis_factor, CollisionCheckDebug & debug); -/** - * @brief Check collision between ego polygons with margin and objects. - * @return Has collision or not - */ -bool checkCollisionWithMargin( - const std::vector & ego_polygons, const PredictedObjects & dynamic_objects, - const double collision_check_margin); +bool checkPolygonsIntersects( + const std::vector & polys_1, const std::vector & polys_2); + } // namespace behavior_path_planner::utils::path_safety_checker #endif // BEHAVIOR_PATH_PLANNER__UTILS__PATH_SAFETY_CHECKER__SAFETY_CHECK_HPP_ diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index 95ac47494d016..46b358948863b 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -22,6 +22,7 @@ #include "behavior_path_planner/utils/path_utils.hpp" #include "behavior_path_planner/utils/start_goal_planner_common/utils.hpp" #include "behavior_path_planner/utils/utils.hpp" +#include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp" #include "tier4_autoware_utils/math/unit_conversion.hpp" #include @@ -1314,7 +1315,6 @@ bool GoalPlannerModule::checkCollision(const PathWithLaneId & path) const return true; } } - if (!parameters_->use_object_recognition) { return false; } @@ -1328,20 +1328,41 @@ bool GoalPlannerModule::checkCollision(const PathWithLaneId & path) const utils::path_safety_checker::isPolygonOverlapLanelet); const auto pull_over_lane_stop_objects = utils::path_safety_checker::filterObjectsByVelocity( pull_over_lane_objects, parameters_->th_moving_object_velocity); - const auto common_parameters = planner_data_->parameters; - const double base_link2front = common_parameters.base_link2front; - const double base_link2rear = common_parameters.base_link2rear; - const double vehicle_width = common_parameters.vehicle_width; - - const auto ego_polygons_expanded = - utils::path_safety_checker::generatePolygonsWithStoppingAndInertialMargin( - path, base_link2front, base_link2rear, vehicle_width, parameters_->maximum_deceleration, + std::vector obj_polygons; + for (const auto & object : pull_over_lane_stop_objects.objects) { + obj_polygons.push_back(tier4_autoware_utils::toPolygon2d(object)); + } + + std::vector ego_polygons_expanded; + const auto curvatures = motion_utils::calcCurvature(path.points); + for (size_t i = 0; i < path.points.size(); ++i) { + const auto p = path.points.at(i); + + const double extra_stopping_margin = std::min( + std::pow(p.point.longitudinal_velocity_mps, 2) * 0.5 / parameters_->maximum_deceleration, parameters_->object_recognition_collision_check_max_extra_stopping_margin); + + double extra_lateral_margin = (-1) * curvatures.at(i) * p.point.longitudinal_velocity_mps * + std::abs(p.point.longitudinal_velocity_mps); + extra_lateral_margin = + std::clamp(extra_lateral_margin, -extra_stopping_margin, extra_stopping_margin); + + const auto lateral_offset_pose = + tier4_autoware_utils::calcOffsetPose(p.point.pose, 0.0, extra_lateral_margin / 2.0, 0.0); + const auto ego_polygon = tier4_autoware_utils::toFootprint( + lateral_offset_pose, + planner_data_->parameters.base_link2front + + parameters_->object_recognition_collision_check_margin + extra_stopping_margin, + planner_data_->parameters.base_link2rear + + parameters_->object_recognition_collision_check_margin, + planner_data_->parameters.vehicle_width + + parameters_->object_recognition_collision_check_margin * 2.0 + + std::abs(extra_lateral_margin)); + ego_polygons_expanded.push_back(ego_polygon); + } debug_data_.ego_polygons_expanded = ego_polygons_expanded; - return utils::path_safety_checker::checkCollisionWithMargin( - ego_polygons_expanded, pull_over_lane_stop_objects, - parameters_->object_recognition_collision_check_margin); + return utils::path_safety_checker::checkPolygonsIntersects(ego_polygons_expanded, obj_polygons); } bool GoalPlannerModule::hasEnoughDistance(const PullOverPath & pull_over_path) const 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 8ebc144a34584..40aa184105edb 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 @@ -18,7 +18,7 @@ #include "motion_utils/trajectory/trajectory.hpp" #include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp" -#include +#include #include #include @@ -380,44 +380,12 @@ std::vector getCollidedPolygons( return collided_polygons; } -std::vector generatePolygonsWithStoppingAndInertialMargin( - const PathWithLaneId & ego_path, const double base_to_front, const double base_to_rear, - const double width, const double maximum_deceleration, const double max_extra_stopping_margin) +bool checkPolygonsIntersects( + const std::vector & polys_1, const std::vector & polys_2) { - std::vector polygons; - const auto curvatures = motion_utils::calcCurvature(ego_path.points); - - for (size_t i = 0; i < ego_path.points.size(); ++i) { - const auto p = ego_path.points.at(i); - - const double extra_stopping_margin = std::min( - std::pow(p.point.longitudinal_velocity_mps, 2) * 0.5 / maximum_deceleration, - max_extra_stopping_margin); - - double extra_lateral_margin = (-1) * curvatures[i] * p.point.longitudinal_velocity_mps * - std::abs(p.point.longitudinal_velocity_mps); - extra_lateral_margin = - std::clamp(extra_lateral_margin, -extra_stopping_margin, extra_stopping_margin); - - const auto lateral_offset_pose = - tier4_autoware_utils::calcOffsetPose(p.point.pose, 0.0, extra_lateral_margin / 2.0, 0.0); - const auto ego_polygon = tier4_autoware_utils::toFootprint( - lateral_offset_pose, base_to_front + extra_stopping_margin, base_to_rear, - width + std::abs(extra_lateral_margin)); - polygons.push_back(ego_polygon); - } - return polygons; -} - -bool checkCollisionWithMargin( - const std::vector & ego_polygons, const PredictedObjects & dynamic_objects, - const double collision_check_margin) -{ - for (const auto & ego_polygon : ego_polygons) { - for (const auto & object : dynamic_objects.objects) { - const auto obj_polygon = tier4_autoware_utils::toPolygon2d(object); - const double distance = boost::geometry::distance(obj_polygon, ego_polygon); - if (distance < collision_check_margin) { + for (const auto & poly_1 : polys_1) { + for (const auto & poly_2 : polys_2) { + if (boost::geometry::intersects(poly_1, poly_2)) { return true; } } From 92f78a476d47bf0811cbb69315fd403be574224f Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 25 Oct 2023 11:39:02 +0900 Subject: [PATCH 060/202] fix(goal_planner): revert "refactor(goal_planner): rebuild state transition (#5371)" (#5399) This reverts commit 3d2a7f6038627ca52a4f0c2af6f5a8d56bc6962b. --- .../goal_planner/goal_planner_module.hpp | 19 +++--- .../goal_planner/goal_planner_module.cpp | 59 +++++++++++-------- 2 files changed, 46 insertions(+), 32 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp index 21372ed6e2c2f..343302a022a69 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp @@ -217,28 +217,31 @@ class GoalPlannerModule : public SceneModuleInterface } } - CandidateOutput planCandidate() const override; - BehaviorModuleOutput plan() override; - BehaviorModuleOutput planWaitingApproval() override; + // TODO(someone): remove this, and use base class function + [[deprecated]] BehaviorModuleOutput run() override; bool isExecutionRequested() const override; bool isExecutionReady() const override; + // TODO(someone): remove this, and use base class function + [[deprecated]] ModuleStatus updateState() override; + BehaviorModuleOutput plan() override; + BehaviorModuleOutput planWaitingApproval() override; + void processOnEntry() override; void processOnExit() override; - void updateData() override; void setParameters(const std::shared_ptr & parameters); void acceptVisitor( [[maybe_unused]] const std::shared_ptr & visitor) const override { } + // not used, but need to override + CandidateOutput planCandidate() const override { return CandidateOutput{}; }; + private: - // The start_planner activates when it receives a new route, - // so there is no need to terminate the goal planner. - // If terminating it, it may switch to lane following and could generate an inappropriate path. bool canTransitSuccessState() override { return false; } bool canTransitFailureState() override { return false; } - bool canTransitIdleToRunningState() override { return true; } + bool canTransitIdleToRunningState() override { return false; } mutable StartGoalPlannerData goal_planner_data_; diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index 46b358948863b..87417bfe6a42d 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -114,13 +114,6 @@ GoalPlannerModule::GoalPlannerModule( freespace_parking_timer_cb_group_); } - // Initialize safety checker - if (parameters_->safety_check_params.enable_safety_check) { - initializeSafetyCheckParameters(); - utils::start_goal_planner_common::initializeCollisionCheckDebugMap( - goal_planner_data_.collision_check); - } - status_.reset(); } @@ -227,18 +220,16 @@ void GoalPlannerModule::onFreespaceParkingTimer() } } -void GoalPlannerModule::updateData() +BehaviorModuleOutput GoalPlannerModule::run() { - // Initialize Occupancy Grid Map - // This operation requires waiting for `planner_data_`, hence it is executed here instead of in - // the constructor. Ideally, this operation should only need to be performed once. - if ( - parameters_->use_occupancy_grid_for_goal_search || - parameters_->use_occupancy_grid_for_path_collision_check) { - initializeOccupancyGridMap(); + current_state_ = ModuleStatus::RUNNING; + updateOccupancyGrid(); + + if (!isActivated()) { + return planWaitingApproval(); } - updateOccupancyGrid(); + return plan(); } void GoalPlannerModule::initializeOccupancyGridMap() @@ -265,6 +256,22 @@ void GoalPlannerModule::initializeSafetyCheckParameters() objects_filtering_params_, parameters_); } +void GoalPlannerModule::processOnEntry() +{ + // Initialize occupancy grid map + if ( + parameters_->use_occupancy_grid_for_goal_search || + parameters_->use_occupancy_grid_for_path_collision_check) { + initializeOccupancyGridMap(); + } + // Initialize safety checker + if (parameters_->safety_check_params.enable_safety_check) { + initializeSafetyCheckParameters(); + utils::start_goal_planner_common::initializeCollisionCheckDebugMap( + goal_planner_data_.collision_check); + } +} + void GoalPlannerModule::processOnExit() { resetPathCandidate(); @@ -431,6 +438,13 @@ Pose GoalPlannerModule::calcRefinedGoal(const Pose & goal_pose) const return refined_goal_pose; } +ModuleStatus GoalPlannerModule::updateState() +{ + // start_planner module will be run when setting new goal, so not need finishing pull_over module. + // Finishing it causes wrong lane_following path generation. + return current_state_; +} + bool GoalPlannerModule::planFreespacePath() { goal_searcher_->setPlannerData(planner_data_); @@ -884,12 +898,6 @@ void GoalPlannerModule::decideVelocity() status_.set_has_decided_velocity(true); } -CandidateOutput GoalPlannerModule::planCandidate() const -{ - return CandidateOutput( - status_.get_pull_over_path() ? status_.get_pull_over_path()->getFullPath() : PathWithLaneId()); -} - BehaviorModuleOutput GoalPlannerModule::planWithGoalModification() { constexpr double path_update_duration = 1.0; @@ -928,7 +936,7 @@ BehaviorModuleOutput GoalPlannerModule::planWithGoalModification() // set output and status BehaviorModuleOutput output{}; setOutput(output); - path_candidate_ = std::make_shared(planCandidate().path_candidate); + path_candidate_ = std::make_shared(status_.get_pull_over_path()->getFullPath()); path_reference_ = getPreviousModuleOutput().reference_path; // return to lane parking if it is possible @@ -981,7 +989,10 @@ BehaviorModuleOutput GoalPlannerModule::planWaitingApprovalWithGoalModification( out.modified_goal = plan().modified_goal; // update status_ out.path = std::make_shared(generateStopPath()); out.reference_path = getPreviousModuleOutput().reference_path; - path_candidate_ = std::make_shared(planCandidate().path_candidate); + path_candidate_ = + status_.get_is_safe_static_objects() + ? std::make_shared(status_.get_pull_over_path()->getFullPath()) + : out.path; path_reference_ = getPreviousModuleOutput().reference_path; const auto distance_to_path_change = calcDistanceToPathChange(); From ce3db689c924f192350c23f3e35ed8f3acc52e5a Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 25 Oct 2023 11:39:12 +0900 Subject: [PATCH 061/202] fix(lane_change): fix terminal stop distance (#5392) * fix(lane_change): fix terminal stop distance Signed-off-by: kosuke55 * make current lanes include path front id Signed-off-by: kosuke55 * fixup! make current lanes include path front id --------- Signed-off-by: kosuke55 --- .../behavior_path_planner/src/utils/utils.cpp | 19 +++++++++++++++++-- 1 file changed, 17 insertions(+), 2 deletions(-) diff --git a/planning/behavior_path_planner/src/utils/utils.cpp b/planning/behavior_path_planner/src/utils/utils.cpp index 9b10dfc32457f..35dd7675ae3fc 100644 --- a/planning/behavior_path_planner/src/utils/utils.cpp +++ b/planning/behavior_path_planner/src/utils/utils.cpp @@ -3081,9 +3081,24 @@ lanelet::ConstLanelets getCurrentLanesFromPath( lanelet::ConstLanelet current_lane; lanelet::utils::query::getClosestLanelet(reference_lanes, current_pose, ¤t_lane); - - return route_handler->getLaneletSequence( + auto current_lanes = route_handler->getLaneletSequence( current_lane, current_pose, p.backward_path_length, p.forward_path_length); + + // Extend the 'current_lanes' with previous lanes until it contains 'front_lane_ids'. + const auto front_lane_ids = path.points.front().lane_ids; + auto have_front_lanes = [front_lane_ids](const auto & lanes) { + return std::any_of(lanes.begin(), lanes.end(), [&](const auto & lane) { + return std::find(front_lane_ids.begin(), front_lane_ids.end(), lane.id()) != + front_lane_ids.end(); + }); + }; + while (!have_front_lanes(current_lanes)) { + const auto extended_lanes = extendPrevLane(route_handler, current_lanes); + if (extended_lanes.size() == current_lanes.size()) break; + current_lanes = extended_lanes; + } + + return current_lanes; } lanelet::ConstLanelets extendNextLane( From aabbe102ed62f2dd5b8994f171b9bad675b5fc0b Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Wed, 25 Oct 2023 11:54:15 +0900 Subject: [PATCH 062/202] refactor(behavior_path_planner): change start planner's variable name (#5390) * change variable name Signed-off-by: kyoichi-sugahara * change variable name to driving_forward Signed-off-by: kyoichi-sugahara * fix typo Signed-off-by: kyoichi-sugahara --------- Signed-off-by: kyoichi-sugahara --- .../start_planner/start_planner_module.hpp | 7 +-- .../scene_module/start_planner/manager.cpp | 4 +- .../start_planner/start_planner_module.cpp | 60 +++++++++---------- 3 files changed, 35 insertions(+), 36 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp index 7ab404d99bb12..8124f8f993906 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp @@ -59,10 +59,9 @@ struct PullOutStatus PlannerType planner_type{PlannerType::NONE}; PathWithLaneId backward_path{}; lanelet::ConstLanelets pull_out_lanes{}; - bool is_safe_static_objects{false}; // current path is safe against static objects + bool found_pull_out_path{false}; // current path is safe against static objects bool is_safe_dynamic_objects{false}; // current path is safe against dynamic objects - bool back_finished{false}; // if backward driving is not required, this is also set to true - // todo: rename to clear variable name. + bool driving_forward{false}; // if ego is driving on backward path, this is set to false bool backward_driving_complete{ false}; // after backward driving is complete, this is set to true (warning: this is set to // false at next cycle after backward driving is complete) @@ -120,7 +119,7 @@ class StartPlannerModule : public SceneModuleInterface } // Condition to disable simultaneous execution - bool isBackFinished() const { return status_.back_finished; } + bool isDrivingForward() const { return status_.driving_forward; } bool isFreespacePlanning() const { return status_.planner_type == PlannerType::FREESPACE; } private: diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp index 30810bda252c3..46db10417d19e 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp @@ -320,7 +320,7 @@ bool StartPlannerModuleManager::isSimultaneousExecutableAsApprovedModule() const const auto start_planner_ptr = std::dynamic_pointer_cast(observer.lock()); // Currently simultaneous execution with other modules is not supported while backward driving - if (!start_planner_ptr->isBackFinished()) { + if (!start_planner_ptr->isDrivingForward()) { return false; } @@ -349,7 +349,7 @@ bool StartPlannerModuleManager::isSimultaneousExecutableAsCandidateModule() cons const auto start_planner_ptr = std::dynamic_pointer_cast(observer.lock()); // Currently simultaneous execution with other modules is not supported while backward driving - if (!start_planner_ptr->isBackFinished()) { + if (start_planner_ptr->isDrivingForward()) { return false; } diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp index 62f3dbfe191ac..8228542141c77 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp @@ -135,8 +135,8 @@ void StartPlannerModule::updateData() if (has_received_new_route) { status_ = PullOutStatus(); } - // check safety status after back finished - if (parameters_->safety_check_params.enable_safety_check && status_.back_finished) { + // check safety status when driving forward + if (parameters_->safety_check_params.enable_safety_check && status_.driving_forward) { status_.is_safe_dynamic_objects = isSafePath(); } else { status_.is_safe_dynamic_objects = true; @@ -184,15 +184,15 @@ bool StartPlannerModule::isExecutionRequested() const bool StartPlannerModule::isExecutionReady() const { - // when is_safe_static_objects is false,the path is not generated and approval shouldn't be + // when found_pull_out_path is false,the path is not generated and approval shouldn't be // allowed - if (!status_.is_safe_static_objects) { - RCLCPP_ERROR_THROTTLE(getLogger(), *clock_, 5000, "Path is not safe against static objects"); + if (!status_.found_pull_out_path) { + RCLCPP_ERROR_THROTTLE(getLogger(), *clock_, 5000, "Pull over path is not found"); return false; } if ( - parameters_->safety_check_params.enable_safety_check && status_.back_finished && + parameters_->safety_check_params.enable_safety_check && status_.driving_forward && isWaitingApproval()) { if (!isSafePath()) { RCLCPP_ERROR_THROTTLE(getLogger(), *clock_, 5000, "Path is not safe against dynamic objects"); @@ -250,7 +250,7 @@ BehaviorModuleOutput StartPlannerModule::plan() } BehaviorModuleOutput output; - if (!status_.is_safe_static_objects) { + if (!status_.found_pull_out_path) { RCLCPP_WARN_THROTTLE( getLogger(), *clock_, 5000, "Not found safe pull out path, publish stop path"); const auto output = generateStopOutput(); @@ -262,7 +262,7 @@ BehaviorModuleOutput StartPlannerModule::plan() PathWithLaneId path; // Check if backward motion is finished - if (status_.back_finished) { + if (status_.driving_forward) { // Increment path index if the current path is finished if (hasFinishedCurrentPath()) { RCLCPP_INFO(getLogger(), "Increment path index"); @@ -317,7 +317,7 @@ BehaviorModuleOutput StartPlannerModule::plan() return SteeringFactor::STRAIGHT; }); - if (status_.back_finished) { + if (status_.driving_forward) { const double start_distance = motion_utils::calcSignedArcLength( path.points, planner_data_->self_odometry->pose.pose.position, status_.pull_out_path.start_pose.position); @@ -369,7 +369,7 @@ PathWithLaneId StartPlannerModule::getFullPath() const pull_out_path.points.end(), partial_path.points.begin(), partial_path.points.end()); } - if (status_.back_finished) { + if (status_.driving_forward) { // not need backward path or finish it return pull_out_path; } @@ -396,7 +396,7 @@ BehaviorModuleOutput StartPlannerModule::planWaitingApproval() } BehaviorModuleOutput output; - if (!status_.is_safe_static_objects) { + if (!status_.found_pull_out_path) { RCLCPP_WARN_THROTTLE( getLogger(), *clock_, 5000, "Not found safe pull out path, publish stop path"); clearWaitingApproval(); @@ -414,7 +414,7 @@ BehaviorModuleOutput StartPlannerModule::planWaitingApproval() planner_data_, backward_path_length, std::numeric_limits::max(), /*forward_only_in_route*/ true); - auto stop_path = status_.back_finished ? getCurrentPath() : status_.backward_path; + auto stop_path = status_.driving_forward ? getCurrentPath() : status_.backward_path; const auto drivable_lanes = generateDrivableLanes(stop_path); const auto & dp = planner_data_->drivable_area_expansion_parameters; const auto expanded_lanes = utils::expandLanelets( @@ -441,7 +441,7 @@ BehaviorModuleOutput StartPlannerModule::planWaitingApproval() return SteeringFactor::STRAIGHT; }); - if (status_.back_finished) { + if (status_.driving_forward) { const double start_distance = motion_utils::calcSignedArcLength( stop_path.points, planner_data_->self_odometry->pose.pose.position, status_.pull_out_path.start_pose.position); @@ -502,7 +502,7 @@ void StartPlannerModule::planWithPriority( const auto & pull_out_start_pose = start_pose_candidates.at(i); // Set back_finished to true if the current start pose is same to refined_start_pose - status_.back_finished = + status_.driving_forward = tier4_autoware_utils::calcDistance2d(pull_out_start_pose, refined_start_pose) < 0.01; planner->setPlannerData(planner_data_); @@ -512,9 +512,9 @@ void StartPlannerModule::planWithPriority( return false; } // use current path if back is not needed - if (status_.back_finished) { + if (status_.driving_forward) { const std::lock_guard lock(mutex_); - status_.is_safe_static_objects = true; + status_.found_pull_out_path = true; status_.pull_out_path = *pull_out_path; status_.pull_out_start_pose = pull_out_start_pose; status_.planner_type = planner->getPlannerType(); @@ -535,7 +535,7 @@ void StartPlannerModule::planWithPriority( // Update status variables with the next path information { const std::lock_guard lock(mutex_); - status_.is_safe_static_objects = true; + status_.found_pull_out_path = true; status_.pull_out_path = *pull_out_path_next; status_.pull_out_start_pose = pull_out_start_pose_next; status_.planner_type = planner->getPlannerType(); @@ -587,7 +587,7 @@ void StartPlannerModule::planWithPriority( // not found safe path if (status_.planner_type != PlannerType::FREESPACE) { const std::lock_guard lock(mutex_); - status_.is_safe_static_objects = false; + status_.found_pull_out_path = false; status_.planner_type = PlannerType::NONE; } } @@ -730,7 +730,7 @@ void StartPlannerModule::updatePullOutStatus() void StartPlannerModule::updateStatusAfterBackwardDriving() { - status_.back_finished = true; + status_.driving_forward = true; status_.backward_driving_complete = true; // request start_planner approval waitApproval(); @@ -835,7 +835,7 @@ bool StartPlannerModule::isOverlappedWithLane( bool StartPlannerModule::hasFinishedPullOut() const { - if (!status_.back_finished || !status_.is_safe_static_objects) { + if (!status_.driving_forward || !status_.found_pull_out_path) { return false; } @@ -874,7 +874,7 @@ bool StartPlannerModule::isBackwardDrivingComplete() const const double ego_vel = utils::l2Norm(planner_data_->self_odometry->twist.twist.linear); const bool is_stopped = ego_vel < parameters_->th_stopped_velocity; - const bool back_finished = !status_.back_finished && is_near && is_stopped; + const bool back_finished = !status_.driving_forward && is_near && is_stopped; if (back_finished) { RCLCPP_INFO(getLogger(), "back finished"); } @@ -916,7 +916,7 @@ bool StartPlannerModule::isStuck() } // not found safe path - if (!status_.is_safe_static_objects) { + if (!status_.found_pull_out_path) { return true; } @@ -943,7 +943,7 @@ TurnSignalInfo StartPlannerModule::calcTurnSignalInfo() const const Pose & end_pose = status_.pull_out_path.end_pose; // turn on hazard light when backward driving - if (!status_.back_finished) { + if (!status_.driving_forward) { turn_signal.hazard_signal.command = HazardLightsCommand::ENABLE; const auto back_start_pose = planner_data_->route_handler->getOriginalStartPose(); turn_signal.desired_start_point = back_start_pose; @@ -1157,7 +1157,7 @@ BehaviorModuleOutput StartPlannerModule::generateStopOutput() { const std::lock_guard lock(mutex_); - status_.back_finished = true; + status_.driving_forward = true; status_.planner_type = PlannerType::STOP; status_.pull_out_path.partial_paths.clear(); status_.pull_out_path.partial_paths.push_back(stop_path); @@ -1209,8 +1209,8 @@ bool StartPlannerModule::planFreespacePath() status_.pull_out_path = *freespace_path; status_.pull_out_start_pose = current_pose; status_.planner_type = freespace_planner_->getPlannerType(); - status_.is_safe_static_objects = true; - status_.back_finished = true; + status_.found_pull_out_path = true; + status_.driving_forward = true; return true; } @@ -1231,7 +1231,7 @@ void StartPlannerModule::setDrivableAreaInfo(BehaviorModuleOutput & output) cons DrivableAreaInfo current_drivable_area_info; current_drivable_area_info.drivable_lanes = target_drivable_lanes; output.drivable_area_info = - status_.back_finished + status_.driving_forward ? utils::combineDrivableAreaInfo( current_drivable_area_info, getPreviousModuleOutput().drivable_area_info) : current_drivable_area_info; @@ -1291,13 +1291,13 @@ void StartPlannerModule::setDebugData() const const auto header = planner_data_->route_handler->getRouteHeader(); { visualization_msgs::msg::MarkerArray planner_type_marker_array{}; - const auto color = status_.is_safe_static_objects ? createMarkerColor(1.0, 1.0, 1.0, 0.99) - : createMarkerColor(1.0, 0.0, 0.0, 0.99); + const auto color = status_.found_pull_out_path ? createMarkerColor(1.0, 1.0, 1.0, 0.99) + : createMarkerColor(1.0, 0.0, 0.0, 0.99); auto marker = createDefaultMarker( header.frame_id, header.stamp, "planner_type", 0, visualization_msgs::msg::Marker::TEXT_VIEW_FACING, createMarkerScale(0.0, 0.0, 1.0), color); marker.pose = status_.pull_out_start_pose; - if (!status_.back_finished) { + if (!status_.driving_forward) { marker.text = "BACK -> "; } marker.text += magic_enum::enum_name(status_.planner_type); From ae5035f4d4b724a6dde175d4ac9c53ed0f740905 Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Wed, 25 Oct 2023 13:24:57 +0900 Subject: [PATCH 063/202] fix(motion_utils): fix build error (#5404) Signed-off-by: Fumiya Watanabe --- .../motion_utils/vehicle/vehicle_state_checker.hpp | 8 ++++---- common/motion_utils/src/vehicle/vehicle_state_checker.cpp | 4 ++-- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/common/motion_utils/include/motion_utils/vehicle/vehicle_state_checker.hpp b/common/motion_utils/include/motion_utils/vehicle/vehicle_state_checker.hpp index f5f423f881ba2..6a9bd01a5a9a0 100644 --- a/common/motion_utils/include/motion_utils/vehicle/vehicle_state_checker.hpp +++ b/common/motion_utils/include/motion_utils/vehicle/vehicle_state_checker.hpp @@ -55,11 +55,11 @@ class VehicleStopChecker : public VehicleStopCheckerBase protected: rclcpp::Subscription::SharedPtr sub_odom_; - Odometry::SharedPtr odometry_ptr_; + Odometry::ConstSharedPtr odometry_ptr_; private: static constexpr double velocity_buffer_time_sec = 10.0; - void onOdom(const Odometry::SharedPtr msg); + void onOdom(const Odometry::ConstSharedPtr msg); }; class VehicleArrivalChecker : public VehicleStopChecker @@ -74,9 +74,9 @@ class VehicleArrivalChecker : public VehicleStopChecker rclcpp::Subscription::SharedPtr sub_trajectory_; - Trajectory::SharedPtr trajectory_ptr_; + Trajectory::ConstSharedPtr trajectory_ptr_; - void onTrajectory(const Trajectory::SharedPtr msg); + void onTrajectory(const Trajectory::ConstSharedPtr msg); }; } // namespace motion_utils diff --git a/common/motion_utils/src/vehicle/vehicle_state_checker.cpp b/common/motion_utils/src/vehicle/vehicle_state_checker.cpp index 6ed9472d39e0f..194c49ae3bff8 100644 --- a/common/motion_utils/src/vehicle/vehicle_state_checker.cpp +++ b/common/motion_utils/src/vehicle/vehicle_state_checker.cpp @@ -88,7 +88,7 @@ VehicleStopChecker::VehicleStopChecker(rclcpp::Node * node) std::bind(&VehicleStopChecker::onOdom, this, _1)); } -void VehicleStopChecker::onOdom(const Odometry::SharedPtr msg) +void VehicleStopChecker::onOdom(const Odometry::ConstSharedPtr msg) { odometry_ptr_ = msg; @@ -128,7 +128,7 @@ bool VehicleArrivalChecker::isVehicleStoppedAtStopPoint(const double stop_durati th_arrived_distance_m; } -void VehicleArrivalChecker::onTrajectory(const Trajectory::SharedPtr msg) +void VehicleArrivalChecker::onTrajectory(const Trajectory::ConstSharedPtr msg) { trajectory_ptr_ = msg; } From 71848084513463e86729693d41b39c2bf9aa3288 Mon Sep 17 00:00:00 2001 From: Shohei Sakai Date: Wed, 25 Oct 2023 13:39:03 +0900 Subject: [PATCH 064/202] feat(map_loader): display curbstone as marker array (#4958) display curbstone as marker array Signed-off-by: Shohei Sakai Co-authored-by: kminoda <44218668+kminoda@users.noreply.github.com> --- .../lanelet2_map_visualization_node.cpp | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_visualization_node.cpp b/map/map_loader/src/lanelet2_map_loader/lanelet2_map_visualization_node.cpp index 53794fb93b7c6..c325f183fd783 100644 --- a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_visualization_node.cpp +++ b/map/map_loader/src/lanelet2_map_loader/lanelet2_map_visualization_node.cpp @@ -127,13 +127,14 @@ void Lanelet2MapVisualizationNode::onMapBin( lanelet::utils::query::getAllPolygonsByType(viz_lanelet_map, "hatched_road_markings"); std::vector no_parking_reg_elems = lanelet::utils::query::noParkingAreas(all_lanelets); + lanelet::ConstLineStrings3d curbstones = lanelet::utils::query::curbstones(viz_lanelet_map); std_msgs::msg::ColorRGBA cl_road, cl_shoulder, cl_cross, cl_partitions, cl_pedestrian_markings, cl_ll_borders, cl_shoulder_borders, cl_stoplines, cl_trafficlights, cl_detection_areas, cl_speed_bumps, cl_crosswalks, cl_parking_lots, cl_parking_spaces, cl_lanelet_id, cl_obstacle_polygons, cl_no_stopping_areas, cl_no_obstacle_segmentation_area, cl_no_obstacle_segmentation_area_for_run_out, cl_hatched_road_markings_area, - cl_hatched_road_markings_line, cl_no_parking_areas; + cl_hatched_road_markings_line, cl_no_parking_areas, cl_curbstones; setColor(&cl_road, 0.27, 0.27, 0.27, 0.999); setColor(&cl_shoulder, 0.15, 0.15, 0.15, 0.999); setColor(&cl_cross, 0.27, 0.3, 0.27, 0.5); @@ -156,6 +157,7 @@ void Lanelet2MapVisualizationNode::onMapBin( setColor(&cl_hatched_road_markings_area, 0.3, 0.3, 0.3, 0.5); setColor(&cl_hatched_road_markings_line, 0.5, 0.5, 0.5, 0.999); setColor(&cl_no_parking_areas, 0.42, 0.42, 0.42, 0.5); + setColor(&cl_curbstones, 0.1, 0.1, 0.2, 0.999); visualization_msgs::msg::MarkerArray map_marker_array; @@ -242,6 +244,10 @@ void Lanelet2MapVisualizationNode::onMapBin( &map_marker_array, lanelet::visualization::noParkingAreasAsMarkerArray(no_parking_reg_elems, cl_no_parking_areas)); + insertMarkerArray( + &map_marker_array, + lanelet::visualization::lineStringsAsMarkerArray(curbstones, "curbstone", cl_curbstones, 0.2)); + pub_marker_->publish(map_marker_array); } From 6e6053625dac33d3d4d12148da43c78519d13bed Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Wed, 25 Oct 2023 13:54:53 +0900 Subject: [PATCH 065/202] refactor(behavior_path_planner): refactor planWithPriority in start_planner (#5393) * minor refactor planWithPriority Signed-off-by: kyoichi-sugahara * apply changes based on comments Signed-off-by: kyoichi-sugahara --------- Signed-off-by: kyoichi-sugahara Co-authored-by: Kosuke Takeuchi --- .../start_planner/start_planner_module.hpp | 15 ++ .../start_planner/start_planner_module.cpp | 160 ++++++++++-------- 2 files changed, 100 insertions(+), 75 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp index 8124f8f993906..206ca5ea080c3 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp @@ -51,6 +51,7 @@ using behavior_path_planner::utils::path_safety_checker::SafetyCheckParams; using behavior_path_planner::utils::path_safety_checker::TargetObjectsOnLane; using geometry_msgs::msg::PoseArray; using lane_departure_checker::LaneDepartureChecker; +using PriorityOrder = std::vector>>; struct PullOutStatus { @@ -131,6 +132,20 @@ class StartPlannerModule : public SceneModuleInterface void initializeSafetyCheckParameters(); + PriorityOrder determinePriorityOrder( + const std::string & search_priority, const size_t candidates_size); + bool findPullOutPath( + const std::vector & start_pose_candidates, const size_t index, + const std::shared_ptr & planner, const Pose & refined_start_pose, + const Pose & goal_pose); + void updateStatusWithCurrentPath( + const behavior_path_planner::PullOutPath & path, const Pose & start_pose, + const behavior_path_planner::PlannerType & planner_type); + void updateStatusWithNextPath( + const behavior_path_planner::PullOutPath & path, const Pose & start_pose, + const behavior_path_planner::PlannerType & planner_type); + void updateStatusIfNoSafePathFound(); + std::shared_ptr parameters_; mutable std::shared_ptr ego_predicted_path_params_; mutable std::shared_ptr objects_filtering_params_; diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp index 8228542141c77..622cc9e3b87ae 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp @@ -492,99 +492,109 @@ void StartPlannerModule::planWithPriority( const std::vector & start_pose_candidates, const Pose & refined_start_pose, const Pose & goal_pose, const std::string search_priority) { - // check if start pose candidates are valid - if (start_pose_candidates.empty()) { - return; - } - - const auto is_safe_with_pose_planner = [&](const size_t i, const auto & planner) { - // Get the pull_out_start_pose for the current index - const auto & pull_out_start_pose = start_pose_candidates.at(i); - - // Set back_finished to true if the current start pose is same to refined_start_pose - status_.driving_forward = - tier4_autoware_utils::calcDistance2d(pull_out_start_pose, refined_start_pose) < 0.01; - - planner->setPlannerData(planner_data_); - const auto pull_out_path = planner->plan(pull_out_start_pose, goal_pose); - // not found safe path - if (!pull_out_path) { - return false; - } - // use current path if back is not needed - if (status_.driving_forward) { - const std::lock_guard lock(mutex_); - status_.found_pull_out_path = true; - status_.pull_out_path = *pull_out_path; - status_.pull_out_start_pose = pull_out_start_pose; - status_.planner_type = planner->getPlannerType(); - return true; - } + if (start_pose_candidates.empty()) return; - // If this is the last start pose candidate, return false - if (i == start_pose_candidates.size() - 1) return false; + const PriorityOrder order_priority = + determinePriorityOrder(search_priority, start_pose_candidates.size()); - // check next path if back is needed - const auto & pull_out_start_pose_next = start_pose_candidates.at(i + 1); - const auto pull_out_path_next = planner->plan(pull_out_start_pose_next, goal_pose); - // not found safe path - if (!pull_out_path_next) { - return false; - } + for (const auto & [index, planner] : order_priority) { + if (findPullOutPath(start_pose_candidates, index, planner, refined_start_pose, goal_pose)) + return; + } - // Update status variables with the next path information - { - const std::lock_guard lock(mutex_); - status_.found_pull_out_path = true; - status_.pull_out_path = *pull_out_path_next; - status_.pull_out_start_pose = pull_out_start_pose_next; - status_.planner_type = planner->getPlannerType(); - } - return true; - }; + updateStatusIfNoSafePathFound(); +} - using PriorityOrder = std::vector>>; - const auto make_loop_order_planner_first = [&]() { - PriorityOrder order_priority; +PriorityOrder StartPlannerModule::determinePriorityOrder( + const std::string & search_priority, const size_t candidates_size) +{ + PriorityOrder order_priority; + if (search_priority == "efficient_path") { for (const auto & planner : start_planners_) { - for (size_t i = 0; i < start_pose_candidates.size(); i++) { + for (size_t i = 0; i < candidates_size; i++) { order_priority.emplace_back(i, planner); } } - return order_priority; - }; - - const auto make_loop_order_pose_first = [&]() { - PriorityOrder order_priority; - for (size_t i = 0; i < start_pose_candidates.size(); i++) { + } else if (search_priority == "short_back_distance") { + for (size_t i = 0; i < candidates_size; i++) { for (const auto & planner : start_planners_) { order_priority.emplace_back(i, planner); } } - return order_priority; - }; - - // Choose loop order based on priority_on_efficient_path - PriorityOrder order_priority; - if (search_priority == "efficient_path") { - order_priority = make_loop_order_planner_first(); - } else if (search_priority == "short_back_distance") { - order_priority = make_loop_order_pose_first(); } else { - RCLCPP_ERROR( - getLogger(), - "search_priority should be efficient_path or short_back_distance, but %s is given.", - search_priority.c_str()); + RCLCPP_ERROR(getLogger(), "Invalid search_priority: %s", search_priority.c_str()); throw std::domain_error("[start_planner] invalid search_priority"); } + return order_priority; +} - for (const auto & p : order_priority) { - if (is_safe_with_pose_planner(p.first, p.second)) { - return; - } +bool StartPlannerModule::findPullOutPath( + const std::vector & start_pose_candidates, const size_t index, + const std::shared_ptr & planner, const Pose & refined_start_pose, + const Pose & goal_pose) +{ + // Ensure the index is within the bounds of the start_pose_candidates vector + if (index >= start_pose_candidates.size()) return false; + + const Pose & pull_out_start_pose = start_pose_candidates.at(index); + const bool is_driving_forward = + tier4_autoware_utils::calcDistance2d(pull_out_start_pose, refined_start_pose) < 0.01; + + planner->setPlannerData(planner_data_); + const auto pull_out_path = planner->plan(pull_out_start_pose, goal_pose); + + // If no path is found, return false + if (!pull_out_path) { + return false; } - // not found safe path + // If driving forward, update status with the current path and return true + if (is_driving_forward) { + updateStatusWithCurrentPath(*pull_out_path, pull_out_start_pose, planner->getPlannerType()); + return true; + } + + // If this is the last start pose candidate, return false + if (index == start_pose_candidates.size() - 1) return false; + + const Pose & next_pull_out_start_pose = start_pose_candidates.at(index + 1); + const auto next_pull_out_path = planner->plan(next_pull_out_start_pose, goal_pose); + + // If no next path is found, return false + if (!next_pull_out_path) return false; + + // Update status with the next path and return true + updateStatusWithNextPath( + *next_pull_out_path, next_pull_out_start_pose, planner->getPlannerType()); + return true; +} + +void StartPlannerModule::updateStatusWithCurrentPath( + const behavior_path_planner::PullOutPath & path, const Pose & start_pose, + const behavior_path_planner::PlannerType & planner_type) +{ + const std::lock_guard lock(mutex_); + status_.driving_forward = true; + status_.found_pull_out_path = true; + status_.pull_out_path = path; + status_.pull_out_start_pose = start_pose; + status_.planner_type = planner_type; +} + +void StartPlannerModule::updateStatusWithNextPath( + const behavior_path_planner::PullOutPath & path, const Pose & start_pose, + const behavior_path_planner::PlannerType & planner_type) +{ + const std::lock_guard lock(mutex_); + status_.driving_forward = false; + status_.found_pull_out_path = true; + status_.pull_out_path = path; + status_.pull_out_start_pose = start_pose; + status_.planner_type = planner_type; +} + +void StartPlannerModule::updateStatusIfNoSafePathFound() +{ if (status_.planner_type != PlannerType::FREESPACE) { const std::lock_guard lock(mutex_); status_.found_pull_out_path = false; From d6be0d2089c76f5530aef46f0361afaa21b54548 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 25 Oct 2023 17:15:40 +0900 Subject: [PATCH 066/202] feat(avoidance): add use_conservative_buffer_longitudinal (#5405) Signed-off-by: Takayuki Murooka --- .../config/avoidance/avoidance.param.yaml | 8 +++++ .../utils/avoidance/avoidance_module_data.hpp | 2 ++ .../avoidance/avoidance_module.cpp | 34 ++++++++++++++----- .../src/scene_module/avoidance/manager.cpp | 5 +++ 4 files changed, 40 insertions(+), 9 deletions(-) diff --git a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml index 25e42d20d144a..3d0a334cedf84 100644 --- a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml +++ b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml @@ -37,6 +37,7 @@ avoid_margin_lateral: 1.0 # [m] safety_buffer_lateral: 0.7 # [m] safety_buffer_longitudinal: 0.0 # [m] + use_conservative_buffer_longitudinal: true # [-] When set to true, the base_link2front is added to the longitudinal buffer before avoidance. truck: is_target: true execute_num: 1 @@ -47,6 +48,7 @@ avoid_margin_lateral: 1.0 safety_buffer_lateral: 0.7 safety_buffer_longitudinal: 0.0 + use_conservative_buffer_longitudinal: true bus: is_target: true execute_num: 1 @@ -57,6 +59,7 @@ avoid_margin_lateral: 1.0 safety_buffer_lateral: 0.7 safety_buffer_longitudinal: 0.0 + use_conservative_buffer_longitudinal: true trailer: is_target: true execute_num: 1 @@ -67,6 +70,7 @@ avoid_margin_lateral: 1.0 safety_buffer_lateral: 0.7 safety_buffer_longitudinal: 0.0 + use_conservative_buffer_longitudinal: true unknown: is_target: false execute_num: 1 @@ -77,6 +81,7 @@ avoid_margin_lateral: 1.0 safety_buffer_lateral: 0.7 safety_buffer_longitudinal: 0.0 + use_conservative_buffer_longitudinal: true bicycle: is_target: false execute_num: 1 @@ -87,6 +92,7 @@ avoid_margin_lateral: 1.0 safety_buffer_lateral: 1.0 safety_buffer_longitudinal: 1.0 + use_conservative_buffer_longitudinal: true motorcycle: is_target: false execute_num: 1 @@ -97,6 +103,7 @@ avoid_margin_lateral: 1.0 safety_buffer_lateral: 1.0 safety_buffer_longitudinal: 1.0 + use_conservative_buffer_longitudinal: true pedestrian: is_target: false execute_num: 1 @@ -107,6 +114,7 @@ avoid_margin_lateral: 1.0 safety_buffer_lateral: 1.0 safety_buffer_longitudinal: 1.0 + use_conservative_buffer_longitudinal: true lower_distance_for_polygon_expansion: 30.0 # [m] upper_distance_for_polygon_expansion: 100.0 # [m] 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 74464be0fa5ea..e881c8a0d3b18 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 @@ -71,6 +71,8 @@ struct ObjectParameter double safety_buffer_lateral{1.0}; double safety_buffer_longitudinal{0.0}; + + bool use_conservative_buffer_longitudinal{true}; }; struct AvoidanceParameters 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 84064a1c38bcb..5423cff11bfeb 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 @@ -631,7 +631,10 @@ void AvoidanceModule::fillDebugData( const auto o_front = data.stop_target_object.get(); const auto object_type = utils::getHighestProbLabel(o_front.object.classification); const auto object_parameter = parameters_->object_parameters.at(object_type); - const auto & base_link2front = planner_data_->parameters.base_link2front; + const auto & additional_buffer_longitudinal = + object_parameter.use_conservative_buffer_longitudinal + ? planner_data_->parameters.base_link2front + : 0.0; const auto & vehicle_width = planner_data_->parameters.vehicle_width; const auto max_avoid_margin = object_parameter.safety_buffer_lateral * o_front.distance_factor + @@ -640,7 +643,8 @@ void AvoidanceModule::fillDebugData( const auto variable = helper_.getSharpAvoidanceDistance( helper_.getShiftLength(o_front, utils::avoidance::isOnRight(o_front), max_avoid_margin)); const auto constant = helper_.getNominalPrepareDistance() + - object_parameter.safety_buffer_longitudinal + base_link2front; + object_parameter.safety_buffer_longitudinal + + additional_buffer_longitudinal; const auto total_avoid_distance = variable + constant; dead_pose_ = calcLongitudinalOffsetPose( @@ -894,7 +898,6 @@ AvoidOutlines AvoidanceModule::generateAvoidOutline( { // To be consistent with changes in the ego position, the current shift length is considered. const auto current_ego_shift = helper_.getEgoShift(); - const auto & base_link2front = planner_data_->parameters.base_link2front; const auto & base_link2rear = planner_data_->parameters.base_link2rear; // Calculate feasible shift length @@ -932,8 +935,12 @@ AvoidOutlines AvoidanceModule::generateAvoidOutline( // calculate remaining distance. const auto prepare_distance = helper_.getNominalPrepareDistance(); - const auto constant = - object_parameter.safety_buffer_longitudinal + base_link2front + prepare_distance; + const auto & additional_buffer_longitudinal = + object_parameter.use_conservative_buffer_longitudinal + ? planner_data_->parameters.base_link2front + : 0.0; + const auto constant = object_parameter.safety_buffer_longitudinal + + additional_buffer_longitudinal + prepare_distance; const auto has_enough_distance = object.longitudinal > constant + nominal_avoid_distance; const auto remaining_distance = object.longitudinal - constant; @@ -1053,7 +1060,12 @@ AvoidOutlines AvoidanceModule::generateAvoidOutline( AvoidLine al_avoid; { - const auto offset = object_parameter.safety_buffer_longitudinal + base_link2front; + const auto & additional_buffer_longitudinal = + object_parameter.use_conservative_buffer_longitudinal + ? planner_data_->parameters.base_link2front + : 0.0; + const auto offset = + object_parameter.safety_buffer_longitudinal + additional_buffer_longitudinal; const auto path_front_to_ego = avoid_data_.arclength_from_ego.at(avoid_data_.ego_closest_path_index); @@ -2807,7 +2819,6 @@ void AvoidanceModule::updateAvoidanceDebugData( double AvoidanceModule::calcDistanceToStopLine(const ObjectData & object) const { const auto & p = parameters_; - const auto & base_link2front = planner_data_->parameters.base_link2front; const auto & vehicle_width = planner_data_->parameters.vehicle_width; // D5 @@ -2823,7 +2834,8 @@ double AvoidanceModule::calcDistanceToStopLine(const ObjectData & object) const // D2: min_avoid_distance // D3: longitudinal_avoid_margin_front (margin + D5) // D4: o_front.longitudinal - // D5: base_link2front + // D5: additional_buffer_longitudinal (base_link2front or 0 depending on the + // use_conservative_buffer_longitudinal) const auto object_type = utils::getHighestProbLabel(object.object.classification); const auto object_parameter = parameters_->object_parameters.at(object_type); @@ -2832,8 +2844,12 @@ double AvoidanceModule::calcDistanceToStopLine(const ObjectData & object) const object_parameter.avoid_margin_lateral + 0.5 * vehicle_width; const auto variable = helper_.getMinAvoidanceDistance( helper_.getShiftLength(object, utils::avoidance::isOnRight(object), avoid_margin)); + const auto & additional_buffer_longitudinal = + object_parameter.use_conservative_buffer_longitudinal + ? planner_data_->parameters.base_link2front + : 0.0; const auto constant = p->min_prepare_distance + object_parameter.safety_buffer_longitudinal + - base_link2front + p->stop_buffer; + additional_buffer_longitudinal + p->stop_buffer; return object.longitudinal - std::min(variable + constant, p->stop_max_distance); } 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 763cf17890721..7988239e68071 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp @@ -82,6 +82,8 @@ AvoidanceModuleManager::AvoidanceModuleManager( getOrDeclareParameter(*node, ns + "safety_buffer_lateral"); param.safety_buffer_longitudinal = getOrDeclareParameter(*node, ns + "safety_buffer_longitudinal"); + param.use_conservative_buffer_longitudinal = + getOrDeclareParameter(*node, ns + "use_conservative_buffer_longitudinal"); return param; }; @@ -336,6 +338,9 @@ void AvoidanceModuleManager::updateModuleParams(const std::vector(parameters, ns + "safety_buffer_lateral", config.safety_buffer_lateral); updateParam( parameters, ns + "safety_buffer_longitudinal", config.safety_buffer_longitudinal); + updateParam( + parameters, ns + "use_conservative_buffer_longitudinal", + config.use_conservative_buffer_longitudinal); }; { From 5a76057f094782538de1191b388a8e3fff3323b9 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 25 Oct 2023 17:51:11 +0900 Subject: [PATCH 067/202] fix(behavior_path_planner): add guard to extend lane (#5406) Signed-off-by: kosuke55 --- planning/behavior_path_planner/src/utils/utils.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/planning/behavior_path_planner/src/utils/utils.cpp b/planning/behavior_path_planner/src/utils/utils.cpp index 35dd7675ae3fc..6e6198e30b13c 100644 --- a/planning/behavior_path_planner/src/utils/utils.cpp +++ b/planning/behavior_path_planner/src/utils/utils.cpp @@ -3104,6 +3104,8 @@ lanelet::ConstLanelets getCurrentLanesFromPath( lanelet::ConstLanelets extendNextLane( const std::shared_ptr route_handler, const lanelet::ConstLanelets & lanes) { + if (lanes.empty()) return lanes; + auto extended_lanes = lanes; // Add next lane @@ -3125,6 +3127,8 @@ lanelet::ConstLanelets extendNextLane( lanelet::ConstLanelets extendPrevLane( const std::shared_ptr route_handler, const lanelet::ConstLanelets & lanes) { + if (lanes.empty()) return lanes; + auto extended_lanes = lanes; // Add previous lane From 4eb0d459a8cf3d37efe14a79f0421872a73c19ee Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Wed, 25 Oct 2023 18:45:28 +0900 Subject: [PATCH 068/202] feat(map_loader): show intersection areas (#5401) Signed-off-by: satoshi-ota --- .../lanelet2_map_visualization_node.cpp | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_visualization_node.cpp b/map/map_loader/src/lanelet2_map_loader/lanelet2_map_visualization_node.cpp index c325f183fd783..082dc95d6500a 100644 --- a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_visualization_node.cpp +++ b/map/map_loader/src/lanelet2_map_loader/lanelet2_map_visualization_node.cpp @@ -125,6 +125,8 @@ void Lanelet2MapVisualizationNode::onMapBin( viz_lanelet_map, "no_obstacle_segmentation_area_for_run_out"); lanelet::ConstPolygons3d hatched_road_markings_area = lanelet::utils::query::getAllPolygonsByType(viz_lanelet_map, "hatched_road_markings"); + lanelet::ConstPolygons3d intersection_areas = + lanelet::utils::query::getAllPolygonsByType(viz_lanelet_map, "intersection_area"); std::vector no_parking_reg_elems = lanelet::utils::query::noParkingAreas(all_lanelets); lanelet::ConstLineStrings3d curbstones = lanelet::utils::query::curbstones(viz_lanelet_map); @@ -134,7 +136,7 @@ void Lanelet2MapVisualizationNode::onMapBin( cl_speed_bumps, cl_crosswalks, cl_parking_lots, cl_parking_spaces, cl_lanelet_id, cl_obstacle_polygons, cl_no_stopping_areas, cl_no_obstacle_segmentation_area, cl_no_obstacle_segmentation_area_for_run_out, cl_hatched_road_markings_area, - cl_hatched_road_markings_line, cl_no_parking_areas, cl_curbstones; + cl_hatched_road_markings_line, cl_no_parking_areas, cl_curbstones, cl_intersection_area; setColor(&cl_road, 0.27, 0.27, 0.27, 0.999); setColor(&cl_shoulder, 0.15, 0.15, 0.15, 0.999); setColor(&cl_cross, 0.27, 0.3, 0.27, 0.5); @@ -158,6 +160,7 @@ void Lanelet2MapVisualizationNode::onMapBin( setColor(&cl_hatched_road_markings_line, 0.5, 0.5, 0.5, 0.999); setColor(&cl_no_parking_areas, 0.42, 0.42, 0.42, 0.5); setColor(&cl_curbstones, 0.1, 0.1, 0.2, 0.999); + setColor(&cl_intersection_area, 0.16, 1.0, 0.69, 0.5); visualization_msgs::msg::MarkerArray map_marker_array; @@ -248,6 +251,10 @@ void Lanelet2MapVisualizationNode::onMapBin( &map_marker_array, lanelet::visualization::lineStringsAsMarkerArray(curbstones, "curbstone", cl_curbstones, 0.2)); + insertMarkerArray( + &map_marker_array, lanelet::visualization::intersectionAreaAsMarkerArray( + intersection_areas, cl_intersection_area)); + pub_marker_->publish(map_marker_array); } From 82a6c0c5d0e3a7a3803f92c9a1334047b80344c5 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 25 Oct 2023 20:27:30 +0900 Subject: [PATCH 069/202] fix(intersection): yield stuck stop (#5403) Signed-off-by: Takayuki Murooka --- .../src/scene_intersection.cpp | 12 ++---------- 1 file changed, 2 insertions(+), 10 deletions(-) diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp index 53a99a1ee6b4d..31b63413a6437 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -1064,16 +1064,8 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( const bool yield_stuck_detected = checkYieldStuckVehicle( planner_data_, path_lanelets, intersection_lanelets.first_attention_area()); if (yield_stuck_detected && stuck_stop_line_idx_opt) { - auto stuck_stop_line_idx = stuck_stop_line_idx_opt.value(); - if (is_private_area_ && planner_param_.stuck_vehicle.enable_private_area_stuck_disregard) { - if ( - default_stop_line_idx_opt && - fromEgoDist(stuck_stop_line_idx) < -planner_param_.common.stop_overshoot_margin) { - stuck_stop_line_idx = default_stop_line_idx_opt.value(); - } - } else { - return IntersectionModule::YieldStuckStop{closest_idx, stuck_stop_line_idx}; - } + const auto stuck_stop_line_idx = stuck_stop_line_idx_opt.value(); + return IntersectionModule::YieldStuckStop{closest_idx, stuck_stop_line_idx}; } // if attention area is empty, collision/occlusion detection is impossible From 801fd0dc48f7efbda6b92faffeabe281720b260b Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 26 Oct 2023 12:18:10 +0900 Subject: [PATCH 070/202] fix(goal_planner): fix hasEnoughDistance (#5411) Signed-off-by: kosuke55 --- .../src/scene_module/goal_planner/goal_planner_module.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index 87417bfe6a42d..241a820175ffe 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -1386,7 +1386,7 @@ bool GoalPlannerModule::hasEnoughDistance(const PullOverPath & pull_over_path) c // so need enough distance to restart. // distance to restart should be less than decide_path_distance. // otherwise, the goal would change immediately after departure. - const bool is_separated_path = status_.get_pull_over_path()->partial_paths.size() > 1; + const bool is_separated_path = pull_over_path.partial_paths.size() > 1; const double distance_to_start = calcSignedArcLength( pull_over_path.getFullPath().points, current_pose.position, pull_over_path.start_pose.position); const double distance_to_restart = parameters_->decide_path_distance / 2; From 98fe02b9d6cd618a002d9dbbf2e6707d2f95498f Mon Sep 17 00:00:00 2001 From: Shunsuke Miura <37187849+miursh@users.noreply.github.com> Date: Thu, 26 Oct 2023 15:13:54 +0900 Subject: [PATCH 071/202] feat(radar_tracks_msgs_converter): add an error message and prevent the node from crashing. (#5400) * add an error message and prevent the node from crashing. Signed-off-by: Shunsuke Miura * style(pre-commit): autofix --------- Signed-off-by: Shunsuke Miura Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../radar_tracks_msgs_converter_node.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/perception/radar_tracks_msgs_converter/src/radar_tracks_msgs_converter_node/radar_tracks_msgs_converter_node.cpp b/perception/radar_tracks_msgs_converter/src/radar_tracks_msgs_converter_node/radar_tracks_msgs_converter_node.cpp index 1122bf7b4b18e..d8b5599cc1ca7 100644 --- a/perception/radar_tracks_msgs_converter/src/radar_tracks_msgs_converter_node/radar_tracks_msgs_converter_node.cpp +++ b/perception/radar_tracks_msgs_converter/src/radar_tracks_msgs_converter_node/radar_tracks_msgs_converter_node.cpp @@ -244,6 +244,11 @@ TrackedObjects RadarTracksMsgsConverterNode::convertRadarTrackToTrackedObjects() std::atan2(compensated_velocity.y, compensated_velocity.x)); geometry_msgs::msg::PoseStamped transformed_pose_stamped{}; + if (transform_ == nullptr) { + RCLCPP_ERROR_THROTTLE( + get_logger(), *get_clock(), 5000, "getTransform failed. radar output will be empty."); + return tracked_objects; + } tf2::doTransform(radar_pose_stamped, transformed_pose_stamped, *transform_); kinematics.pose_with_covariance.pose = transformed_pose_stamped.pose; kinematics.pose_with_covariance.pose.orientation = From fdd671f149d967b9cb224d992d2979dd5617d217 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 26 Oct 2023 18:05:17 +0900 Subject: [PATCH 072/202] fix(behavior_path_planner): fix lane extension in getCurrentLanesFromPath (#5415) --- .../behavior_path_planner/utils/utils.hpp | 6 ++- .../behavior_path_planner/src/utils/utils.cpp | 40 ++++++++++++++----- 2 files changed, 33 insertions(+), 13 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp index f418c9c7300f7..326a6aded5e88 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp @@ -365,10 +365,12 @@ lanelet::ConstLanelets getCurrentLanesFromPath( const PathWithLaneId & path, const std::shared_ptr & planner_data); lanelet::ConstLanelets extendNextLane( - const std::shared_ptr route_handler, const lanelet::ConstLanelets & lanes); + const std::shared_ptr route_handler, const lanelet::ConstLanelets & lanes, + const bool only_in_route = false); lanelet::ConstLanelets extendPrevLane( - const std::shared_ptr route_handler, const lanelet::ConstLanelets & lanes); + const std::shared_ptr route_handler, const lanelet::ConstLanelets & lanes, + const bool only_in_route = false); lanelet::ConstLanelets extendLanes( const std::shared_ptr route_handler, const lanelet::ConstLanelets & lanes); diff --git a/planning/behavior_path_planner/src/utils/utils.cpp b/planning/behavior_path_planner/src/utils/utils.cpp index 6e6198e30b13c..9737db21a31a5 100644 --- a/planning/behavior_path_planner/src/utils/utils.cpp +++ b/planning/behavior_path_planner/src/utils/utils.cpp @@ -3084,7 +3084,8 @@ lanelet::ConstLanelets getCurrentLanesFromPath( auto current_lanes = route_handler->getLaneletSequence( current_lane, current_pose, p.backward_path_length, p.forward_path_length); - // Extend the 'current_lanes' with previous lanes until it contains 'front_lane_ids'. + // Extend the 'current_lanes' with previous lanes until it contains 'front_lane_ids' + // if the extended prior lanes is in same lane sequence with current lanes const auto front_lane_ids = path.points.front().lane_ids; auto have_front_lanes = [front_lane_ids](const auto & lanes) { return std::any_of(lanes.begin(), lanes.end(), [&](const auto & lane) { @@ -3092,17 +3093,23 @@ lanelet::ConstLanelets getCurrentLanesFromPath( front_lane_ids.end(); }); }; - while (!have_front_lanes(current_lanes)) { - const auto extended_lanes = extendPrevLane(route_handler, current_lanes); - if (extended_lanes.size() == current_lanes.size()) break; - current_lanes = extended_lanes; + auto extended_lanes = current_lanes; + while (rclcpp::ok()) { + const size_t pre_extension_size = extended_lanes.size(); // Get existing size before extension + extended_lanes = extendPrevLane(route_handler, extended_lanes, true); + if (extended_lanes.size() == pre_extension_size) break; + if (have_front_lanes(extended_lanes)) { + current_lanes = extended_lanes; + break; + } } return current_lanes; } lanelet::ConstLanelets extendNextLane( - const std::shared_ptr route_handler, const lanelet::ConstLanelets & lanes) + const std::shared_ptr route_handler, const lanelet::ConstLanelets & lanes, + const bool only_in_route) { if (lanes.empty()) return lanes; @@ -3111,21 +3118,27 @@ lanelet::ConstLanelets extendNextLane( // Add next lane const auto next_lanes = route_handler->getNextLanelets(extended_lanes.back()); if (!next_lanes.empty()) { + boost::optional target_next_lane; + if (!only_in_route) { + target_next_lane = next_lanes.front(); + } // use the next lane in route if it exists - auto target_next_lane = next_lanes.front(); for (const auto & next_lane : next_lanes) { if (route_handler->isRouteLanelet(next_lane)) { target_next_lane = next_lane; } } - extended_lanes.push_back(target_next_lane); + if (target_next_lane) { + extended_lanes.push_back(*target_next_lane); + } } return extended_lanes; } lanelet::ConstLanelets extendPrevLane( - const std::shared_ptr route_handler, const lanelet::ConstLanelets & lanes) + const std::shared_ptr route_handler, const lanelet::ConstLanelets & lanes, + const bool only_in_route) { if (lanes.empty()) return lanes; @@ -3134,14 +3147,19 @@ lanelet::ConstLanelets extendPrevLane( // Add previous lane const auto prev_lanes = route_handler->getPreviousLanelets(extended_lanes.front()); if (!prev_lanes.empty()) { + boost::optional target_prev_lane; + if (!only_in_route) { + target_prev_lane = prev_lanes.front(); + } // use the previous lane in route if it exists - auto target_prev_lane = prev_lanes.front(); for (const auto & prev_lane : prev_lanes) { if (route_handler->isRouteLanelet(prev_lane)) { target_prev_lane = prev_lane; } } - extended_lanes.insert(extended_lanes.begin(), target_prev_lane); + if (target_prev_lane) { + extended_lanes.insert(extended_lanes.begin(), *target_prev_lane); + } } return extended_lanes; } From 45792dfee3a930d8a0562abc10788404f94c9a67 Mon Sep 17 00:00:00 2001 From: Takeshi Miura <57553950+1222-takeshi@users.noreply.github.com> Date: Thu, 26 Oct 2023 18:32:20 +0900 Subject: [PATCH 073/202] feat(AEB): implement parameterized prediction time horizon and interval (#5413) * feat(AEB): implement parameterized prediction time horizon and interval Signed-off-by: 1222-takeshi * chore: update readme Signed-off-by: 1222-takeshi * style(pre-commit): autofix --------- Signed-off-by: 1222-takeshi Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../autonomous_emergency_braking/README.md | 35 ++++++++++--------- .../autonomous_emergency_braking.param.yaml | 7 ++-- .../autonomous_emergency_braking/node.hpp | 7 ++-- .../autonomous_emergency_braking/src/node.cpp | 20 +++++++---- 4 files changed, 43 insertions(+), 26 deletions(-) diff --git a/control/autonomous_emergency_braking/README.md b/control/autonomous_emergency_braking/README.md index d1cd80625f2ac..4eff1583d5df8 100644 --- a/control/autonomous_emergency_braking/README.md +++ b/control/autonomous_emergency_braking/README.md @@ -26,22 +26,25 @@ This module has following assumptions. ## Parameters -| Name | Unit | Type | Description | Default value | -| :------------------------ | :----- | :----- | :-------------------------------------------------------------------------- | :------------ | -| use_predicted_trajectory | [-] | bool | flag to use the predicted path from the control module | true | -| use_imu_path | [-] | bool | flag to use the predicted path generated by sensor data | true | -| voxel_grid_x | [m] | double | down sampling parameters of x-axis for voxel grid filter | 0.05 | -| voxel_grid_y | [m] | double | down sampling parameters of y-axis for voxel grid filter | 0.05 | -| voxel_grid_z | [m] | double | down sampling parameters of z-axis for voxel grid filter | 100000.0 | -| min_generated_path_length | [m] | double | minimum distance for a predicted path generated by sensors | 0.5 | -| expand_width | [m] | double | expansion width of the ego vehicle for the collision check | 0.1 | -| longitudinal_offset | [m] | double | longitudinal offset distance for collision check | 2.0 | -| t_response | [s] | double | response time for the ego to detect the front vehicle starting deceleration | 1.0 | -| a_ego_min | [m/ss] | double | maximum deceleration value of the ego vehicle | -3.0 | -| a_obj_min | [m/ss] | double | maximum deceleration value of objects | -3.0 | -| prediction_time_horizon | [s] | double | time horizon of the predicted path generated by sensors | 1.5 | -| prediction_time_interval | [s] | double | time interval of the predicted path generated by sensors | 0.1 | -| aeb_hz | [-] | double |  frequency at which AEB operates per second | 10 | +| Name | Unit | Type | Description | Default value | +| :--------------------------- | :----- | :----- | :-------------------------------------------------------------------------- | :------------ | +| publish_debug_pointcloud | [-] | bool | flag to publish the point cloud used for debugging | false | +| use_predicted_trajectory | [-] | bool | flag to use the predicted path from the control module | true | +| use_imu_path | [-] | bool | flag to use the predicted path generated by sensor data | true | +| voxel_grid_x | [m] | double | down sampling parameters of x-axis for voxel grid filter | 0.05 | +| voxel_grid_y | [m] | double | down sampling parameters of y-axis for voxel grid filter | 0.05 | +| voxel_grid_z | [m] | double | down sampling parameters of z-axis for voxel grid filter | 100000.0 | +| min_generated_path_length | [m] | double | minimum distance for a predicted path generated by sensors | 0.5 | +| expand_width | [m] | double | expansion width of the ego vehicle for the collision check | 0.1 | +| longitudinal_offset | [m] | double | longitudinal offset distance for collision check | 2.0 | +| t_response | [s] | double | response time for the ego to detect the front vehicle starting deceleration | 1.0 | +| a_ego_min | [m/ss] | double | maximum deceleration value of the ego vehicle | -3.0 | +| a_obj_min | [m/ss] | double | maximum deceleration value of objects | -3.0 | +| imu_prediction_time_horizon | [s] | double | time horizon of the predicted path generated by sensors | 1.5 | +| imu_prediction_time_interval | [s] | double | time interval of the predicted path generated by sensors | 0.1 | +| mpc_prediction_time_horizon | [s] | double | time horizon of the predicted path generated by mpc | 1.5 | +| mpc_prediction_time_interval | [s] | double | time interval of the predicted path generated by mpc | 0.1 | +| aeb_hz | [-] | double | frequency at which AEB operates per second | 10 | ## Inner-workings / Algorithms diff --git a/control/autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml b/control/autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml index 09db0feb34597..1a870aff7a843 100644 --- a/control/autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml +++ b/control/autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml @@ -1,5 +1,6 @@ /**: ros__parameters: + publish_debug_pointcloud: false use_predicted_trajectory: true use_imu_path: true voxel_grid_x: 0.05 @@ -11,7 +12,9 @@ t_response: 1.0 a_ego_min: -3.0 a_obj_min: -1.0 - prediction_time_horizon: 1.5 - prediction_time_interval: 0.1 + imu_prediction_time_horizon: 1.5 + imu_prediction_time_interval: 0.1 + mpc_prediction_time_horizon: 1.5 + mpc_prediction_time_interval: 0.1 collision_keeping_sec: 0.0 aeb_hz: 10.0 diff --git a/control/autonomous_emergency_braking/include/autonomous_emergency_braking/node.hpp b/control/autonomous_emergency_braking/include/autonomous_emergency_braking/node.hpp index a8f260795d485..27ec775110109 100644 --- a/control/autonomous_emergency_braking/include/autonomous_emergency_braking/node.hpp +++ b/control/autonomous_emergency_braking/include/autonomous_emergency_braking/node.hpp @@ -172,6 +172,7 @@ class AEB : public rclcpp::Node Updater updater_{this}; // member variables + bool publish_debug_pointcloud_; bool use_predicted_trajectory_; bool use_imu_path_; double voxel_grid_x_; @@ -183,8 +184,10 @@ class AEB : public rclcpp::Node double t_response_; double a_ego_min_; double a_obj_min_; - double prediction_time_horizon_; - double prediction_time_interval_; + double imu_prediction_time_horizon_; + double imu_prediction_time_interval_; + double mpc_prediction_time_horizon_; + double mpc_prediction_time_interval_; CollisionDataKeeper collision_data_keeper_; }; } // namespace autoware::motion::control::autonomous_emergency_braking diff --git a/control/autonomous_emergency_braking/src/node.cpp b/control/autonomous_emergency_braking/src/node.cpp index 0ccc9bc4a3dae..e88a5ee833612 100644 --- a/control/autonomous_emergency_braking/src/node.cpp +++ b/control/autonomous_emergency_braking/src/node.cpp @@ -125,6 +125,7 @@ AEB::AEB(const rclcpp::NodeOptions & node_options) updater_.add("aeb_emergency_stop", this, &AEB::onCheckCollision); // parameter + publish_debug_pointcloud_ = declare_parameter("publish_debug_pointcloud"); use_predicted_trajectory_ = declare_parameter("use_predicted_trajectory"); use_imu_path_ = declare_parameter("use_imu_path"); voxel_grid_x_ = declare_parameter("voxel_grid_x"); @@ -136,8 +137,10 @@ AEB::AEB(const rclcpp::NodeOptions & node_options) t_response_ = declare_parameter("t_response"); a_ego_min_ = declare_parameter("a_ego_min"); a_obj_min_ = declare_parameter("a_obj_min"); - prediction_time_horizon_ = declare_parameter("prediction_time_horizon"); - prediction_time_interval_ = declare_parameter("prediction_time_interval"); + imu_prediction_time_horizon_ = declare_parameter("imu_prediction_time_horizon"); + imu_prediction_time_interval_ = declare_parameter("imu_prediction_time_interval"); + mpc_prediction_time_horizon_ = declare_parameter("mpc_prediction_time_horizon"); + mpc_prediction_time_interval_ = declare_parameter("mpc_prediction_time_interval"); const auto collision_keeping_sec = declare_parameter("collision_keeping_sec"); collision_data_keeper_.setTimeout(collision_keeping_sec); @@ -227,7 +230,9 @@ void AEB::onPointCloud(const PointCloud2::ConstSharedPtr input_msg) obstacle_ros_pointcloud_ptr_ = std::make_shared(); pcl::toROSMsg(*no_height_filtered_pointcloud_ptr, *obstacle_ros_pointcloud_ptr_); obstacle_ros_pointcloud_ptr_->header = input_msg->header; - pub_obstacle_pointcloud_->publish(*obstacle_ros_pointcloud_ptr_); + if (publish_debug_pointcloud_) { + pub_obstacle_pointcloud_->publish(*obstacle_ros_pointcloud_ptr_); + } } bool AEB::isDataReady() @@ -392,8 +397,8 @@ void AEB::generateEgoPath( } constexpr double epsilon = 1e-6; - const double & dt = prediction_time_interval_; - const double & horizon = prediction_time_horizon_; + const double & dt = imu_prediction_time_interval_; + const double & horizon = imu_prediction_time_horizon_; for (double t = 0.0; t < horizon + epsilon; t += dt) { curr_x = curr_x + curr_v * std::cos(curr_yaw) * dt; curr_y = curr_y + curr_v * std::sin(curr_yaw) * dt; @@ -452,8 +457,11 @@ void AEB::generateEgoPath( geometry_msgs::msg::Pose map_pose; tf2::doTransform(predicted_traj.points.at(i).pose, map_pose, transform_stamped); path.at(i) = map_pose; - } + if (i * mpc_prediction_time_interval_ > mpc_prediction_time_horizon_) { + break; + } + } // create polygon polygons.resize(path.size()); for (size_t i = 0; i < path.size() - 1; ++i) { From 64c8ac88d666204d4a13dfb69c4213a8852a3679 Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Thu, 26 Oct 2023 19:44:20 +0900 Subject: [PATCH 074/202] refactor(landmark_based_localizer): refactored landmark_tf_caster (#5414) * Removed landmark_tf_caster node Signed-off-by: Shintaro SAKODA * Added maintainer Signed-off-by: Shintaro SAKODA * style(pre-commit): autofix * Renamed to landmark_parser Signed-off-by: Shintaro SAKODA * Added include Signed-off-by: Shintaro SAKODA * style(pre-commit): autofix * Added publish_landmark_markers Signed-off-by: Shintaro SAKODA * Removed unused package.xml Signed-off-by: Shintaro Sakoda * Changed from depend to build_depend Signed-off-by: Shintaro Sakoda * Fixed a local variable name Signed-off-by: Shintaro Sakoda * Fixed Marker to MarkerArray Signed-off-by: Shintaro Sakoda --------- Signed-off-by: Shintaro SAKODA Signed-off-by: Shintaro Sakoda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../ar_tag_based_localizer.launch.xml | 8 +- launch/tier4_localization_launch/package.xml | 1 - .../landmark_based_localizer/README.md | 22 +-- .../ar_tag_based_localizer/README.md | 12 +- .../ar_tag_based_localizer_core.hpp | 7 + .../launch/ar_tag_based_localizer.launch.xml | 2 + .../ar_tag_based_localizer/package.xml | 4 + .../src/ar_tag_based_localizer_core.cpp | 37 ++++- .../doc_image/node_diagram.drawio.svg | 96 +++++------ .../CMakeLists.txt | 9 +- .../landmark_parser/landmark_parser_core.hpp | 34 ++++ .../package.xml | 12 +- .../src/landmark_parser_core.cpp | 154 ++++++++++++++++++ .../config/landmark_tf_caster.param.yaml | 4 - .../landmark_tf_caster_core.hpp | 49 ------ .../launch/landmark_tf_caster.launch.xml | 12 -- .../src/landmark_tf_caster_core.cpp | 126 -------------- .../src/landmark_tf_caster_node.cpp | 22 --- 18 files changed, 296 insertions(+), 315 deletions(-) rename localization/landmark_based_localizer/{landmark_tf_caster => landmark_parser}/CMakeLists.txt (69%) create mode 100644 localization/landmark_based_localizer/landmark_parser/include/landmark_parser/landmark_parser_core.hpp rename localization/landmark_based_localizer/{landmark_tf_caster => landmark_parser}/package.xml (69%) create mode 100644 localization/landmark_based_localizer/landmark_parser/src/landmark_parser_core.cpp delete mode 100644 localization/landmark_based_localizer/landmark_tf_caster/config/landmark_tf_caster.param.yaml delete mode 100644 localization/landmark_based_localizer/landmark_tf_caster/include/landmark_tf_caster/landmark_tf_caster_core.hpp delete mode 100644 localization/landmark_based_localizer/landmark_tf_caster/launch/landmark_tf_caster.launch.xml delete mode 100644 localization/landmark_based_localizer/landmark_tf_caster/src/landmark_tf_caster_core.cpp delete mode 100644 localization/landmark_based_localizer/landmark_tf_caster/src/landmark_tf_caster_node.cpp diff --git a/launch/tier4_localization_launch/launch/pose_twist_estimator/ar_tag_based_localizer.launch.xml b/launch/tier4_localization_launch/launch/pose_twist_estimator/ar_tag_based_localizer.launch.xml index a767d2d253cff..181f470a00800 100644 --- a/launch/tier4_localization_launch/launch/pose_twist_estimator/ar_tag_based_localizer.launch.xml +++ b/launch/tier4_localization_launch/launch/pose_twist_estimator/ar_tag_based_localizer.launch.xml @@ -4,6 +4,7 @@ + @@ -12,12 +13,5 @@ - - - - - - - diff --git a/launch/tier4_localization_launch/package.xml b/launch/tier4_localization_launch/package.xml index 6b3b3d3bbbe01..f00752d1c14fc 100644 --- a/launch/tier4_localization_launch/package.xml +++ b/launch/tier4_localization_launch/package.xml @@ -21,7 +21,6 @@ eagleye_rt ekf_localizer gyro_odometer - landmark_tf_caster ndt_scan_matcher pointcloud_preprocessor pose_initializer diff --git a/localization/landmark_based_localizer/README.md b/localization/landmark_based_localizer/README.md index a8ebdc0c8f1e5..35d8d78e7015c 100644 --- a/localization/landmark_based_localizer/README.md +++ b/localization/landmark_based_localizer/README.md @@ -23,11 +23,11 @@ This calculated ego pose is passed to the EKF, where it is fused with the twist ![node diagram](./doc_image/node_diagram.drawio.svg) -### `landmark_tf_caster` node +### `landmark_parser` The definitions of the landmarks written to the map are introduced in the next section. See `Map Specifications`. -The `landmark_tf_caster` node publishes the TF from the map to the landmark. +The `landmark_parser` is a utility package to load landmarks from the map. - Translation : The center of the four vertices of the landmark - Rotation : Let the vertex numbers be 1, 2, 3, 4 counterclockwise as shown in the next section. Direction is defined as the cross product of the vector from 1 to 2 and the vector from 2 to 3. @@ -41,25 +41,9 @@ So, if the 4 vertices are considered as forming a tetrahedron and its volume exc - ar_tag_based_localizer - etc. -## Inputs / Outputs - -### `landmark_tf_caster` node - -#### Input - -| Name | Type | Description | -| :--------------------- | :------------------------------------------- | :--------------- | -| `~/input/lanelet2_map` | `autoware_auto_mapping_msgs::msg::HADMapBin` | Data of lanelet2 | - -#### Output - -| Name | Type | Description | -| :---------- | :------------------------------------- | :----------------- | -| `tf_static` | `geometry_msgs::msg::TransformStamped` | TF from map to tag | - ## Map specifications -For this package to work correctly, the poses of the landmarks must be specified in the Lanelet2 map format that `map_loader` and `landmark_tf_caster` can interpret. +For this package to work correctly, the poses of the landmarks must be specified in the Lanelet2 map format that `map_loader` and `landmark_parser` can interpret. The four vertices of a landmark are defined counterclockwise. diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/README.md b/localization/landmark_based_localizer/ar_tag_based_localizer/README.md index b212711f38a57..f0c54d6393f7e 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/README.md +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/README.md @@ -13,11 +13,12 @@ The positions and orientations of the AR-Tags are assumed to be written in the L #### Input -| Name | Type | Description | -| :-------------------- | :---------------------------------------------- | :------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | -| `~/input/image` | `sensor_msgs::msg::Image` | Camera Image | -| `~/input/camera_info` | `sensor_msgs::msg::CameraInfo` | Camera Info | -| `~/input/ekf_pose` | `geometry_msgs::msg::PoseWithCovarianceStamped` | EKF Pose without IMU correction. It is used to validate detected AR tags by filtering out False Positives. Only if the EKF Pose and the AR tag-detected Pose are within a certain temporal and spatial range, the AR tag-detected Pose is considered valid and published. | +| Name | Type | Description | +| :--------------------- | :---------------------------------------------- | :------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | +| `~/input/lanelet2_map` | `autoware_auto_mapping_msgs::msg::HADMapBin` | Data of lanelet2 | +| `~/input/image` | `sensor_msgs::msg::Image` | Camera Image | +| `~/input/camera_info` | `sensor_msgs::msg::CameraInfo` | Camera Info | +| `~/input/ekf_pose` | `geometry_msgs::msg::PoseWithCovarianceStamped` | EKF Pose without IMU correction. It is used to validate detected AR tags by filtering out False Positives. Only if the EKF Pose and the AR tag-detected Pose are within a certain temporal and spatial range, the AR tag-detected Pose is considered valid and published. | #### Output @@ -25,6 +26,7 @@ The positions and orientations of the AR-Tags are assumed to be written in the L | :------------------------------ | :---------------------------------------------- | :---------------------------------------------------------------------------------------- | | `~/output/pose_with_covariance` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Estimated Pose | | `~/debug/result` | `sensor_msgs::msg::Image` | [debug topic] Image in which marker detection results are superimposed on the input image | +| `~/debug/marker` | `visualization_msgs::msg::MarkerArray` | [debug topic] Loaded landmarks to visualize in Rviz as thin boards | | `/tf` | `geometry_msgs::msg::TransformStamped` | [debug topic] TF from camera to detected tag | | `/diagnostics` | `diagnostic_msgs::msg::DiagnosticArray` | Diagnostics outputs | diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/include/ar_tag_based_localizer/ar_tag_based_localizer_core.hpp b/localization/landmark_based_localizer/ar_tag_based_localizer/include/ar_tag_based_localizer/ar_tag_based_localizer_core.hpp index 37725dd06c34e..facd02e2b9b7b 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/include/ar_tag_based_localizer/ar_tag_based_localizer_core.hpp +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/include/ar_tag_based_localizer/ar_tag_based_localizer_core.hpp @@ -45,6 +45,8 @@ #ifndef AR_TAG_BASED_LOCALIZER__AR_TAG_BASED_LOCALIZER_CORE_HPP_ #define AR_TAG_BASED_LOCALIZER__AR_TAG_BASED_LOCALIZER_CORE_HPP_ +#include "landmark_parser/landmark_parser_core.hpp" + #include #include @@ -57,6 +59,7 @@ #include #include +#include #include #include #include @@ -68,6 +71,7 @@ class ArTagBasedLocalizer : public rclcpp::Node bool setup(); private: + void map_bin_callback(const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr & msg); void image_callback(const sensor_msgs::msg::Image::ConstSharedPtr & msg); void cam_info_callback(const sensor_msgs::msg::CameraInfo & msg); void ekf_pose_callback(const geometry_msgs::msg::PoseWithCovarianceStamped & msg); @@ -92,11 +96,13 @@ class ArTagBasedLocalizer : public rclcpp::Node std::unique_ptr it_; // Subscribers + rclcpp::Subscription::SharedPtr map_bin_sub_; rclcpp::Subscription::SharedPtr image_sub_; rclcpp::Subscription::SharedPtr cam_info_sub_; rclcpp::Subscription::SharedPtr ekf_pose_sub_; // Publishers + rclcpp::Publisher::SharedPtr marker_pub_; image_transport::Publisher image_pub_; rclcpp::Publisher::SharedPtr pose_pub_; rclcpp::Publisher::SharedPtr diag_pub_; @@ -106,6 +112,7 @@ class ArTagBasedLocalizer : public rclcpp::Node aruco::CameraParameters cam_param_; bool cam_info_received_; geometry_msgs::msg::PoseWithCovarianceStamped latest_ekf_pose_{}; + std::map landmark_map_; }; #endif // AR_TAG_BASED_LOCALIZER__AR_TAG_BASED_LOCALIZER_CORE_HPP_ diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/launch/ar_tag_based_localizer.launch.xml b/localization/landmark_based_localizer/ar_tag_based_localizer/launch/ar_tag_based_localizer.launch.xml index f6c10050b1826..6437455875cc2 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/launch/ar_tag_based_localizer.launch.xml +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/launch/ar_tag_based_localizer.launch.xml @@ -3,6 +3,7 @@ + @@ -11,6 +12,7 @@ + diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml b/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml index 216fa21bc951a..c0d1b00e35d3b 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml @@ -6,6 +6,8 @@ The ar_tag_based_localizer package Shintaro Sakoda Masahiro Sakamoto + Yamato Ando + Kento Yabuuchi Apache License 2.0 ament_cmake @@ -15,6 +17,8 @@ cv_bridge diagnostic_msgs image_transport + landmark_parser + lanelet2_extension rclcpp tf2_eigen tf2_geometry_msgs diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer_core.cpp b/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer_core.cpp index afa82ab3e0677..0492e07875a17 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer_core.cpp +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer_core.cpp @@ -110,6 +110,9 @@ bool ArTagBasedLocalizer::setup() /* Subscribers */ + map_bin_sub_ = this->create_subscription( + "~/input/lanelet2_map", rclcpp::QoS(10).durability(rclcpp::DurabilityPolicy::TransientLocal), + std::bind(&ArTagBasedLocalizer::map_bin_callback, this, std::placeholders::_1)); rclcpp::QoS qos_sub(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default)); qos_sub.best_effort(); image_sub_ = this->create_subscription( @@ -125,6 +128,11 @@ bool ArTagBasedLocalizer::setup() /* Publishers */ + rclcpp::QoS qos_marker = rclcpp::QoS(rclcpp::KeepLast(10)); + qos_marker.transient_local(); + qos_marker.reliable(); + marker_pub_ = + this->create_publisher("~/debug/marker", qos_marker); rclcpp::QoS qos_pub(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default)); image_pub_ = it_->advertise("~/debug/result", 1); pose_pub_ = this->create_publisher( @@ -136,6 +144,15 @@ bool ArTagBasedLocalizer::setup() return true; } +void ArTagBasedLocalizer::map_bin_callback( + const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr & msg) +{ + landmark_map_ = parse_landmark(msg, "apriltag_16h5", this->get_logger()); + const visualization_msgs::msg::MarkerArray marker_msg = + convert_to_marker_array_msg(landmark_map_); + marker_pub_->publish(marker_msg); +} + void ArTagBasedLocalizer::image_callback(const sensor_msgs::msg::Image::ConstSharedPtr & msg) { if ((image_pub_.getNumSubscribers() == 0) && (pose_pub_->get_subscription_count() == 0)) { @@ -290,16 +307,20 @@ void ArTagBasedLocalizer::publish_pose_as_base_link( } // Transform map to tag - geometry_msgs::msg::TransformStamped map_to_tag_tf; - try { - map_to_tag_tf = - tf_buffer_->lookupTransform("map", "tag_" + msg.header.frame_id, tf2::TimePointZero); - } catch (tf2::TransformException & ex) { - RCLCPP_INFO( - this->get_logger(), "Could not transform map to tag_%s: %s", msg.header.frame_id.c_str(), - ex.what()); + if (landmark_map_.count(msg.header.frame_id) == 0) { + RCLCPP_INFO_STREAM( + this->get_logger(), "frame_id(" << msg.header.frame_id << ") is not in landmark_map_"); return; } + const geometry_msgs::msg::Pose & tag_pose = landmark_map_.at(msg.header.frame_id); + geometry_msgs::msg::TransformStamped map_to_tag_tf; + map_to_tag_tf.header.stamp = msg.header.stamp; + map_to_tag_tf.header.frame_id = "map"; + map_to_tag_tf.child_frame_id = msg.header.frame_id; + map_to_tag_tf.transform.translation.x = tag_pose.position.x; + map_to_tag_tf.transform.translation.y = tag_pose.position.y; + map_to_tag_tf.transform.translation.z = tag_pose.position.z; + map_to_tag_tf.transform.rotation = tag_pose.orientation; // Transform camera to base_link geometry_msgs::msg::TransformStamped camera_to_base_link_tf; diff --git a/localization/landmark_based_localizer/doc_image/node_diagram.drawio.svg b/localization/landmark_based_localizer/doc_image/node_diagram.drawio.svg index 120a1f2aa3391..e592f06a5a86c 100644 --- a/localization/landmark_based_localizer/doc_image/node_diagram.drawio.svg +++ b/localization/landmark_based_localizer/doc_image/node_diagram.drawio.svg @@ -3,90 +3,84 @@ xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" version="1.1" - width="721px" + width="568px" height="331px" - viewBox="-0.5 -0.5 721 331" - content="<mxfile><diagram id="z_GJx55S16-dNHi1224P" name="ページ1">1VnLjpswFP2aLBsFG0iybF7TxVQdaSq1XSEHDFgDGBnn1a+vHQwE8ExIQiYqm+BjA/Y51/fhDOA83j8xlIbfqYejARh5+wFcDAAwgA3Ej0QOOWIDMwcCRjw1qAJeyV+swJFCN8TDWW0gpzTiJK2DLk0S7PIahhiju/own0b1r6YowC3g1UVRG/1FPB7m6ASMK/wbJkFYfNmwp3lPjIrBaiVZiDy6O4HgcgDnjFKe38X7OY4keQUv+XOrd3rLiTGc8C4PKCG2KNqotal58UOxWEY3iYfl+NEAznyacCWIAVR7TiPKjoPh6HgJvD0RNbctZhzvTyA1sSdMY8zZQQxRvcBSJCkrgaq5qygvsfCEblthSKkclG+uiBA3igs9L2aLl2eUeDFibwKdoUzwAWyxXkOu9ZkK0xCcsHPckSg64Wo+X1orMZ9Zxhl9wyc9tjvBa/++7MJxnV2zza4x0rBr9sCu1WL3Bw8lfaOvG053Ylkn7KbIfRMbKruU3NVqPteROwFraNt3Nl37ceTCsWZPr/iOZNzZER46Lt0iRlDi4hal2BN+TjUp4yENaIKiZYXOBCfs8Ftxfmz8kY3h2Crai/1p7+KgWu+yyhELsIKgwuQ8PuSZ4Qhxsq37Yx1r6tEXSsRnK+Nv6APNSf0VGd0wF6unGtyX0+gkR+Hp63KQWIaYj+hPaPIR36AXvo3x5/BtQqvGNxg3DD2fVIvv1ovAqC4cgPBuwk10wqU0wxdto0LHPeFHGYeWakkdDXVfaSgbh1NBe9U+Z6eu/VX7T8nxZTQ0xJU/dKuNjOs2AuGlNlIMpL6f4VvlN7RuFDGHo8BZywzAiW6M++8FoHY+cLz6CU1mcwcBTWyyNLHJ6iM2GTpS8Zt/PZcqzD+ES7uZoRqfyaXWP7koxgw5JPHpLeGln3D+WeGlFRWsbuFcE6fqLzImVicfdIV/MaFGvvOCdXLtcNrWwuw9tepsqNPWSkUxhSPM2ytGWZoX7D7Zyz0/SzEj4otY7l7xWlHh45cKmgmfESSiyxV0HIGyoJZG6qEsLD1HJgoJkgQ/aSoAKIA8Byt/FyQOxFIispZ+3pUUOB5hYjpUrnflIY6k38+G2Tbox39MGtYGZHbQdCA6/2FOb5fFbFdhsk7wnYwL/d0uxljya3S1zKLAua+X6EyBNjePVKXvCC5clPH/q65vxnfDmGqM6m5RyWyfnPTm1kxNiCkkfIDxaHOZSHk2J0apSGqQd3VG85iDi6b1aF3S/azH1nEq88OL664zxxdGPd85l+7oy7eyYtOWb91C9QPTpuYRILw2bbKbxynWeNhX4iSa1XF4Prz6UwEu/wE=</diagram></mxfile>" + viewBox="-0.5 -0.5 568 331" + content="<mxfile><diagram id="z_GJx55S16-dNHi1224P" name="ページ1">xZhLj5swEMc/TY6NMOaRHJvX9rBVV2qltqfIAQesAEbGefXT1w4GAng3JCGbHHbxH2Ps34xnxgzgND68MJSG36mPo4Fp+IcBnA1M0wVA/JXCMRegO8qFgBE/l0Al/CT/sBINpW6Jj7NaR05pxElaFz2aJNjjNQ0xRvf1bmsa1d+aogC3hJ8eitrqb+LzMFdHplvp3zAJwuLNwBnnd2JUdFYryULk0/2ZBOcDOGWU8vwqPkxxJNkVXPLnFu/cLSfGcMK7PGDmD+xQtFVrU/Pix2KxjG4TH8v+xgBO1jThyiDAVO0pjSg7dYbG6Sf09kTU3HaYcXw4k9TEXjCNMWdH0UXdNW0FqfAS1dxXyEstPMPtKA0pKwflyBUIcaFY6LlYLS6vKPFjxDZCnaBM8DAdsV4g1/pKhWsIJuwSOxJFZ6ym07m9EPOZZJzRDT6743gjvFo/li5063StNl1gaOhaPdC1W3R/8FDiM75uOd2LZZ3RTZG3ERsquxbuYjGd6uCOzBV0nAe7rvM8uNDV7OkF35OML/eEh0uP7hAjKPFwCyn2RZxTTcp4SAOaoGheqRPBhB3/KOanxl/ZGLp20Z4dzu/Ojqr1LlWOWICVBJUm5/EhZ4YjxMmuHo911NSjb5SI11bO37APtEb1ITK6ZR5WTzXYl9PoZI4i0tfNQWKZYj7Cn9DkI95mL7yB+zm8LWjXeJtuw9HzSbV4twYqd0gxEIQPM9xIZ7iUZviqbVTY8UD4yYxDW7WkHYG6rmwoG8dzg/Zq+5xO3fY37T9lji/GEICimrvXR9y6j0B4rY8UHel6neF7zQ+0YRSxJUfBciUrgGV0Z95/LwG164HTr5/UZBmNHWRqcpOtyU12H7kJ6KDizfp2lirNP4Wl06xQwWey1MYnD8WYoSVJ1vSe9NJPOv+s9NLKCna3dK7JU/WBwMjuFINuiC8W1JjvssE6hXY4btvC6r206uyo49ZKxWEKR5i3V4yyND+wr8lB7vlJihkRb8Ry94phxQkfv1XSRMSMIBG3PIHjJJQHaumkPsrCMnJk4iBBkuAXTYUAhZDXYOX/GYkDsZSIrGSc9ySCpU+YmA6V6134iCMZ97Nhtgt6Oia447q7mbI8aEYQXQCxxvfbxWofw14pEgdbg56KGgPxk3EQ49u0i2+WuEFXR7WeWZM26g3gjIeN3d5fMWlpE1+ktsEyRqnIgMi/Of095ZQLx13c92EJ0HJ0TGUxcXWRfuGsC+rJ8VJu1Nf6ZXmvrfW7xfUnbpfm9yJ4a451mmdv223uu5uzrGhW307z7tUHaDj/Dw==</diagram></mxfile>" > - - + + - Landmark Based - Localizer + Landmark Based + Localizer - + - Other Autoware - packages + Other Autoware + packages - - + + - - /twist_with_covariance + + /twist_with_covariance - - + + - - /image + + /image - - + + - - /pose_with_covariance + + /pose_with_covariance - + - /ar_tag_based_localizer + /ar_tag_based_localizer - + - /ekf_localizer + /ekf_localizer - - + + - - /camera_info + + /camera_info - - + + - - Lanelet2 + + Lanelet2 - - + + - - /tf_static + + Load once at startup - + - /landmark_tf_caster + /lanelet2_map_loader - - - - - /lanelet2_map_loader - - - + + - - /ekf_pose_with_covariance + + /ekf_pose_with_covariance diff --git a/localization/landmark_based_localizer/landmark_tf_caster/CMakeLists.txt b/localization/landmark_based_localizer/landmark_parser/CMakeLists.txt similarity index 69% rename from localization/landmark_based_localizer/landmark_tf_caster/CMakeLists.txt rename to localization/landmark_based_localizer/landmark_parser/CMakeLists.txt index 8d8cb546b6162..41f7c00d61383 100644 --- a/localization/landmark_based_localizer/landmark_tf_caster/CMakeLists.txt +++ b/localization/landmark_based_localizer/landmark_parser/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(landmark_tf_caster) +project(landmark_parser) find_package(autoware_cmake REQUIRED) autoware_package() @@ -12,13 +12,10 @@ endif() find_package(ament_cmake_auto REQUIRED) ament_auto_find_build_dependencies() -ament_auto_add_executable(landmark_tf_caster - src/landmark_tf_caster_node.cpp - src/landmark_tf_caster_core.cpp +ament_auto_add_library(landmark_parser + src/landmark_parser_core.cpp ) ament_auto_package( INSTALL_TO_SHARE - launch - config ) diff --git a/localization/landmark_based_localizer/landmark_parser/include/landmark_parser/landmark_parser_core.hpp b/localization/landmark_based_localizer/landmark_parser/include/landmark_parser/landmark_parser_core.hpp new file mode 100644 index 0000000000000..edf45c2a2997a --- /dev/null +++ b/localization/landmark_based_localizer/landmark_parser/include/landmark_parser/landmark_parser_core.hpp @@ -0,0 +1,34 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef LANDMARK_PARSER__LANDMARK_PARSER_CORE_HPP_ +#define LANDMARK_PARSER__LANDMARK_PARSER_CORE_HPP_ + +#include + +#include "autoware_auto_mapping_msgs/msg/had_map_bin.hpp" +#include +#include + +#include +#include + +std::map parse_landmark( + const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr & msg, + const std::string & target_subtype, const rclcpp::Logger & logger); + +visualization_msgs::msg::MarkerArray convert_to_marker_array_msg( + const std::map & landmarks); + +#endif // LANDMARK_PARSER__LANDMARK_PARSER_CORE_HPP_ diff --git a/localization/landmark_based_localizer/landmark_tf_caster/package.xml b/localization/landmark_based_localizer/landmark_parser/package.xml similarity index 69% rename from localization/landmark_based_localizer/landmark_tf_caster/package.xml rename to localization/landmark_based_localizer/landmark_parser/package.xml index 75f42b91f502a..e3daa93f81220 100644 --- a/localization/landmark_based_localizer/landmark_tf_caster/package.xml +++ b/localization/landmark_based_localizer/landmark_parser/package.xml @@ -1,22 +1,24 @@ - landmark_tf_caster + landmark_parser 0.0.0 - The landmark_tf_caster package + The landmark_parser package Shintaro Sakoda Masahiro Sakamoto + Yamato Ando + Kento Yabuuchi Apache License 2.0 ament_cmake autoware_cmake + eigen + autoware_auto_mapping_msgs + geometry_msgs lanelet2_extension rclcpp - tf2_eigen - tf2_geometry_msgs - tf2_ros ament_cmake diff --git a/localization/landmark_based_localizer/landmark_parser/src/landmark_parser_core.cpp b/localization/landmark_based_localizer/landmark_parser/src/landmark_parser_core.cpp new file mode 100644 index 0000000000000..c86b35b6115b4 --- /dev/null +++ b/localization/landmark_based_localizer/landmark_parser/src/landmark_parser_core.cpp @@ -0,0 +1,154 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "landmark_parser/landmark_parser_core.hpp" + +#include "lanelet2_extension/utility/message_conversion.hpp" + +#include + +#include +#include + +std::map parse_landmark( + const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr & msg, + const std::string & target_subtype, const rclcpp::Logger & logger) +{ + RCLCPP_INFO_STREAM(logger, "msg->format_version: " << msg->format_version); + RCLCPP_INFO_STREAM(logger, "msg->map_format: " << msg->map_format); + RCLCPP_INFO_STREAM(logger, "msg->map_version: " << msg->map_version); + RCLCPP_INFO_STREAM(logger, "msg->data.size(): " << msg->data.size()); + lanelet::LaneletMapPtr lanelet_map_ptr{std::make_shared()}; + lanelet::utils::conversion::fromBinMsg(*msg, lanelet_map_ptr); + + std::map landmark_map; + + for (const auto & poly : lanelet_map_ptr->polygonLayer) { + const std::string type{poly.attributeOr(lanelet::AttributeName::Type, "none")}; + if (type != "pose_marker") { + continue; + } + const std::string subtype{poly.attributeOr(lanelet::AttributeName::Subtype, "none")}; + if (subtype != target_subtype) { + continue; + } + + // Get marker_id + const std::string marker_id = poly.attributeOr("marker_id", "none"); + + // Get 4 vertices + const auto & vertices = poly.basicPolygon(); + if (vertices.size() != 4) { + RCLCPP_WARN_STREAM(logger, "vertices.size() (" << vertices.size() << ") != 4"); + continue; + } + + // 4 vertices represent the marker vertices in counterclockwise order + // Calculate the volume by considering it as a tetrahedron + const auto & v0 = vertices[0]; + const auto & v1 = vertices[1]; + const auto & v2 = vertices[2]; + const auto & v3 = vertices[3]; + const double volume = (v1 - v0).cross(v2 - v0).dot(v3 - v0) / 6.0; + RCLCPP_INFO_STREAM(logger, "volume = " << volume); + const double volume_threshold = 1e-5; + if (volume > volume_threshold) { + RCLCPP_WARN_STREAM( + logger, + "volume (" << volume << ") > threshold (" << volume_threshold << "), This is not plane."); + continue; + } + + // Calculate the center of the quadrilateral + const auto center = (v0 + v1 + v2 + v3) / 4.0; + + // Define axes + const auto x_axis = (v1 - v0).normalized(); + const auto y_axis = (v2 - v1).normalized(); + const auto z_axis = x_axis.cross(y_axis).normalized(); + + // Construct rotation matrix and convert it to quaternion + Eigen::Matrix3d rotation_matrix; + rotation_matrix << x_axis, y_axis, z_axis; + const Eigen::Quaterniond q{rotation_matrix}; + + // Create Pose + geometry_msgs::msg::Pose pose; + pose.position.x = center.x(); + pose.position.y = center.y(); + pose.position.z = center.z(); + pose.orientation.x = q.x(); + pose.orientation.y = q.y(); + pose.orientation.z = q.z(); + pose.orientation.w = q.w(); + + // Add to map + landmark_map[marker_id] = pose; + RCLCPP_INFO_STREAM(logger, "id: " << marker_id); + RCLCPP_INFO_STREAM( + logger, + "(x, y, z) = " << pose.position.x << ", " << pose.position.y << ", " << pose.position.z); + RCLCPP_INFO_STREAM( + logger, "q = " << pose.orientation.x << ", " << pose.orientation.y << ", " + << pose.orientation.z << ", " << pose.orientation.w); + } + + return landmark_map; +} + +visualization_msgs::msg::MarkerArray convert_to_marker_array_msg( + const std::map & landmarks) +{ + int32_t id = 0; + visualization_msgs::msg::MarkerArray marker_array; + for (const auto & [id_str, pose] : landmarks) { + // publish cube as a thin board + visualization_msgs::msg::Marker cube_marker; + cube_marker.header.frame_id = "map"; + cube_marker.header.stamp = rclcpp::Clock().now(); + cube_marker.ns = "landmark_cube"; + cube_marker.id = id; + cube_marker.type = visualization_msgs::msg::Marker::CUBE; + cube_marker.action = visualization_msgs::msg::Marker::ADD; + cube_marker.pose = pose; + cube_marker.scale.x = 1.0; + cube_marker.scale.y = 2.0; + cube_marker.scale.z = 0.1; + cube_marker.color.a = 0.5; + cube_marker.color.r = 0.0; + cube_marker.color.g = 1.0; + cube_marker.color.b = 0.0; + marker_array.markers.push_back(cube_marker); + + // publish text + visualization_msgs::msg::Marker text_marker; + text_marker.header.frame_id = "map"; + text_marker.header.stamp = rclcpp::Clock().now(); + text_marker.ns = "landmark_text"; + text_marker.id = id; + text_marker.type = visualization_msgs::msg::Marker::TEXT_VIEW_FACING; + text_marker.action = visualization_msgs::msg::Marker::ADD; + text_marker.pose = pose; + text_marker.text = "(" + id_str + ")"; + text_marker.scale.z = 0.5; + text_marker.color.a = 1.0; + text_marker.color.r = 1.0; + text_marker.color.g = 0.0; + text_marker.color.b = 0.0; + marker_array.markers.push_back(text_marker); + + id++; + } + return marker_array; +} diff --git a/localization/landmark_based_localizer/landmark_tf_caster/config/landmark_tf_caster.param.yaml b/localization/landmark_based_localizer/landmark_tf_caster/config/landmark_tf_caster.param.yaml deleted file mode 100644 index 2fe2869038e82..0000000000000 --- a/localization/landmark_based_localizer/landmark_tf_caster/config/landmark_tf_caster.param.yaml +++ /dev/null @@ -1,4 +0,0 @@ -/**: - ros__parameters: - # Tags with a volume greater than this value will not cast their pose - volume_threshold: 1e-5 # [m^3] diff --git a/localization/landmark_based_localizer/landmark_tf_caster/include/landmark_tf_caster/landmark_tf_caster_core.hpp b/localization/landmark_based_localizer/landmark_tf_caster/include/landmark_tf_caster/landmark_tf_caster_core.hpp deleted file mode 100644 index 0eb6706a0b5b0..0000000000000 --- a/localization/landmark_based_localizer/landmark_tf_caster/include/landmark_tf_caster/landmark_tf_caster_core.hpp +++ /dev/null @@ -1,49 +0,0 @@ -// Copyright 2023 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef LANDMARK_TF_CASTER__LANDMARK_TF_CASTER_CORE_HPP_ -#define LANDMARK_TF_CASTER__LANDMARK_TF_CASTER_CORE_HPP_ - -#include - -#include "autoware_auto_mapping_msgs/msg/had_map_bin.hpp" -#include - -#include -#include -#include - -#include - -class LandmarkTfCaster : public rclcpp::Node -{ -public: - LandmarkTfCaster(); - -private: - void map_bin_callback(const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr & msg); - void publish_tf(const lanelet::Polygon3d & poly); - - // Parameters - double volume_threshold_; - - // tf - std::unique_ptr tf_buffer_; - std::unique_ptr tf_broadcaster_; - - // Subscribers - rclcpp::Subscription::SharedPtr map_bin_sub_; -}; - -#endif // LANDMARK_TF_CASTER__LANDMARK_TF_CASTER_CORE_HPP_ diff --git a/localization/landmark_based_localizer/landmark_tf_caster/launch/landmark_tf_caster.launch.xml b/localization/landmark_based_localizer/landmark_tf_caster/launch/landmark_tf_caster.launch.xml deleted file mode 100644 index eeaba555cb6f5..0000000000000 --- a/localization/landmark_based_localizer/landmark_tf_caster/launch/landmark_tf_caster.launch.xml +++ /dev/null @@ -1,12 +0,0 @@ - - - - - - - - - - - - diff --git a/localization/landmark_based_localizer/landmark_tf_caster/src/landmark_tf_caster_core.cpp b/localization/landmark_based_localizer/landmark_tf_caster/src/landmark_tf_caster_core.cpp deleted file mode 100644 index 801e036415326..0000000000000 --- a/localization/landmark_based_localizer/landmark_tf_caster/src/landmark_tf_caster_core.cpp +++ /dev/null @@ -1,126 +0,0 @@ -// Copyright 2023 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "landmark_tf_caster/landmark_tf_caster_core.hpp" - -#include "lanelet2_extension/utility/message_conversion.hpp" - -#include -#include - -#include -#ifdef ROS_DISTRO_GALACTIC -#include -#else -#include -#endif - -LandmarkTfCaster::LandmarkTfCaster() : Node("landmark_tf_caster") -{ - // Parameters - volume_threshold_ = this->declare_parameter("volume_threshold", 1e-5); - - // tf - tf_buffer_ = std::make_unique(this->get_clock()); - tf_broadcaster_ = std::make_unique(this); - - // Subscribers - map_bin_sub_ = this->create_subscription( - "~/input/lanelet2_map", rclcpp::QoS(10).durability(rclcpp::DurabilityPolicy::TransientLocal), - std::bind(&LandmarkTfCaster::map_bin_callback, this, std::placeholders::_1)); - RCLCPP_INFO(this->get_logger(), "finish setup"); -} - -void LandmarkTfCaster::map_bin_callback( - const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr & msg) -{ - RCLCPP_INFO_STREAM(this->get_logger(), "msg->format_version: " << msg->format_version); - RCLCPP_INFO_STREAM(this->get_logger(), "msg->map_format: " << msg->map_format); - RCLCPP_INFO_STREAM(this->get_logger(), "msg->map_version: " << msg->map_version); - RCLCPP_INFO_STREAM(this->get_logger(), "msg->data.size(): " << msg->data.size()); - lanelet::LaneletMapPtr lanelet_map_ptr{std::make_shared()}; - lanelet::utils::conversion::fromBinMsg(*msg, lanelet_map_ptr); - for (const auto & poly : lanelet_map_ptr->polygonLayer) { - const std::string type{poly.attributeOr(lanelet::AttributeName::Type, "none")}; - if (type != "pose_marker") { - continue; - } - publish_tf(poly); - } -} - -void LandmarkTfCaster::publish_tf(const lanelet::Polygon3d & poly) -{ - // Get marker_id - const std::string marker_id = poly.attributeOr("marker_id", "none"); - - // Get 4 vertices - const auto & vertices = poly.basicPolygon(); - if (vertices.size() != 4) { - RCLCPP_WARN_STREAM(this->get_logger(), "vertices.size() (" << vertices.size() << ") != 4"); - return; - } - - // 4 vertices represent the marker vertices in counterclockwise order - // Calculate the volume by considering it as a tetrahedron - const auto & v0 = vertices[0]; - const auto & v1 = vertices[1]; - const auto & v2 = vertices[2]; - const auto & v3 = vertices[3]; - const double volume = (v1 - v0).cross(v2 - v0).dot(v3 - v0) / 6.0; - RCLCPP_INFO_STREAM(this->get_logger(), "volume = " << volume); - if (volume > volume_threshold_) { - RCLCPP_WARN_STREAM( - this->get_logger(), - "volume (" << volume << ") > threshold (" << volume_threshold_ << "), This is not plane."); - return; - } - - // Calculate the center of the quadrilateral - const auto center = (v0 + v1 + v2 + v3) / 4.0; - - // Define axes - const auto x_axis = (v1 - v0).normalized(); - const auto y_axis = (v2 - v1).normalized(); - const auto z_axis = x_axis.cross(y_axis).normalized(); - - // Construct rotation matrix and convert it to quaternion - Eigen::Matrix3d rotation_matrix; - rotation_matrix << x_axis, y_axis, z_axis; - const Eigen::Quaterniond q{rotation_matrix}; - - // Create transform - geometry_msgs::msg::TransformStamped tf; - tf.header.stamp = this->now(); - tf.header.frame_id = "map"; - tf.child_frame_id = "tag_" + marker_id; - tf.transform.translation.x = center.x(); - tf.transform.translation.y = center.y(); - tf.transform.translation.z = center.z(); - tf.transform.rotation.x = q.x(); - tf.transform.rotation.y = q.y(); - tf.transform.rotation.z = q.z(); - tf.transform.rotation.w = q.w(); - - // Publish transform - tf_broadcaster_->sendTransform(tf); - RCLCPP_INFO_STREAM(this->get_logger(), "id: " << marker_id); - RCLCPP_INFO_STREAM( - this->get_logger(), "(x, y, z) = " << tf.transform.translation.x << ", " - << tf.transform.translation.y << ", " - << tf.transform.translation.z); - RCLCPP_INFO_STREAM( - this->get_logger(), "q = " << tf.transform.rotation.x << ", " << tf.transform.rotation.y << ", " - << tf.transform.rotation.z << ", " << tf.transform.rotation.w); -} diff --git a/localization/landmark_based_localizer/landmark_tf_caster/src/landmark_tf_caster_node.cpp b/localization/landmark_based_localizer/landmark_tf_caster/src/landmark_tf_caster_node.cpp deleted file mode 100644 index 4c34e593e7552..0000000000000 --- a/localization/landmark_based_localizer/landmark_tf_caster/src/landmark_tf_caster_node.cpp +++ /dev/null @@ -1,22 +0,0 @@ -// Copyright 2023 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "landmark_tf_caster/landmark_tf_caster_core.hpp" - -int main(int argc, char ** argv) -{ - rclcpp::init(argc, argv); - rclcpp::spin(std::make_shared()); - rclcpp::shutdown(); -} From b4d5d90af6805e5cf5dc0e5d7d901020c0f0d7b7 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 26 Oct 2023 20:05:32 +0900 Subject: [PATCH 075/202] refactor(goal_planner): use updateData (#5416) Signed-off-by: kosuke55 upda --- .../goal_planner/goal_planner_module.hpp | 2 +- .../goal_planner/goal_planner_module.cpp | 45 +++++++++++-------- 2 files changed, 27 insertions(+), 20 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp index 343302a022a69..8b722d3316093 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp @@ -225,8 +225,8 @@ class GoalPlannerModule : public SceneModuleInterface [[deprecated]] ModuleStatus updateState() override; BehaviorModuleOutput plan() override; BehaviorModuleOutput planWaitingApproval() override; - void processOnEntry() override; void processOnExit() override; + void updateData() override; void setParameters(const std::shared_ptr & parameters); void acceptVisitor( [[maybe_unused]] const std::shared_ptr & visitor) const override diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index 241a820175ffe..2db3560d6e4f3 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -114,6 +114,13 @@ GoalPlannerModule::GoalPlannerModule( freespace_parking_timer_cb_group_); } + // Initialize safety checker + if (parameters_->safety_check_params.enable_safety_check) { + initializeSafetyCheckParameters(); + utils::start_goal_planner_common::initializeCollisionCheckDebugMap( + goal_planner_data_.collision_check); + } + status_.reset(); } @@ -232,6 +239,25 @@ BehaviorModuleOutput GoalPlannerModule::run() return plan(); } +void GoalPlannerModule::updateData() +{ + // Initialize Occupancy Grid Map + // This operation requires waiting for `planner_data_`, hence it is executed here instead of in + // the constructor. Ideally, this operation should only need to be performed once. + if ( + parameters_->use_occupancy_grid_for_goal_search || + parameters_->use_occupancy_grid_for_path_collision_check) { + initializeOccupancyGridMap(); + } + + updateOccupancyGrid(); + + // set current road lanes, pull over lanes, and drivable lane + setLanes(); + + generateGoalCandidates(); +} + void GoalPlannerModule::initializeOccupancyGridMap() { OccupancyGridMapParam occupancy_grid_map_param{}; @@ -256,22 +282,6 @@ void GoalPlannerModule::initializeSafetyCheckParameters() objects_filtering_params_, parameters_); } -void GoalPlannerModule::processOnEntry() -{ - // Initialize occupancy grid map - if ( - parameters_->use_occupancy_grid_for_goal_search || - parameters_->use_occupancy_grid_for_path_collision_check) { - initializeOccupancyGridMap(); - } - // Initialize safety checker - if (parameters_->safety_check_params.enable_safety_check) { - initializeSafetyCheckParameters(); - utils::start_goal_planner_common::initializeCollisionCheckDebugMap( - goal_planner_data_.collision_check); - } -} - void GoalPlannerModule::processOnExit() { resetPathCandidate(); @@ -562,8 +572,6 @@ BehaviorModuleOutput GoalPlannerModule::plan() resetPathCandidate(); resetPathReference(); - generateGoalCandidates(); - path_reference_ = getPreviousModuleOutput().reference_path; if (goal_planner_utils::isAllowedGoalModification(planner_data_->route_handler)) { @@ -984,7 +992,6 @@ BehaviorModuleOutput GoalPlannerModule::planWaitingApprovalWithGoalModification( { waitApproval(); - updateOccupancyGrid(); BehaviorModuleOutput out; out.modified_goal = plan().modified_goal; // update status_ out.path = std::make_shared(generateStopPath()); From f41abb37a6b7e2b00f2cc0f0efc762c34c73cc8a Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 26 Oct 2023 22:11:31 +0900 Subject: [PATCH 076/202] feat(goal_planner): calculate stop pose from closest goal candidate (#5410) * feat(goal_planner): calculate stop pose from closest goal candidate Signed-off-by: kosuke55 * style(pre-commit): autofix * Update planning/behavior_path_planner/src/utils/goal_planner/goal_searcher.cpp Co-authored-by: Kyoichi Sugahara * style(pre-commit): autofix * Update planning/behavior_path_planner/src/utils/goal_planner/goal_searcher.cpp * style(pre-commit): autofix --------- Signed-off-by: kosuke55 Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Kyoichi Sugahara --- .../goal_planner/goal_planner_module.hpp | 2 ++ .../utils/goal_planner/goal_searcher.hpp | 2 ++ .../utils/goal_planner/goal_searcher_base.hpp | 2 ++ .../goal_planner/goal_planner_module.cpp | 25 ++++++++++++------ .../src/utils/goal_planner/goal_searcher.cpp | 26 +++++++++++++++++++ 5 files changed, 49 insertions(+), 8 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp index 8b722d3316093..c5b2209c16f19 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp @@ -142,6 +142,7 @@ class PullOverStatus DEFINE_SETTER_GETTER(std::optional, modified_goal_pose) DEFINE_SETTER_GETTER(Pose, refined_goal_pose) DEFINE_SETTER_GETTER(GoalCandidates, goal_candidates) + DEFINE_SETTER_GETTER(Pose, closest_goal_candidate_pose) DEFINE_SETTER_GETTER(std::vector, pull_over_path_candidates) DEFINE_SETTER_GETTER(std::optional, closest_start_pose) @@ -174,6 +175,7 @@ class PullOverStatus std::optional modified_goal_pose_; Pose refined_goal_pose_{}; GoalCandidates goal_candidates_{}; + Pose closest_goal_candidate_pose_{}; // pull over path std::vector pull_over_path_candidates_; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_searcher.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_searcher.hpp index 2ed58b9678e70..2fc0acf1c5086 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_searcher.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_searcher.hpp @@ -35,6 +35,8 @@ class GoalSearcher : public GoalSearcherBase GoalCandidates search() override; void update(GoalCandidates & goal_candidates) const override; + GoalCandidate getClosetGoalCandidateAlongLanes( + const GoalCandidates & goal_candidates) const override; private: void countObjectsToAvoid( diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_searcher_base.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_searcher_base.hpp index ab319111f6da6..24c614e072b8f 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_searcher_base.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_searcher_base.hpp @@ -58,6 +58,8 @@ class GoalSearcherBase MultiPolygon2d getAreaPolygons() { return area_polygons_; } virtual GoalCandidates search() = 0; virtual void update([[maybe_unused]] GoalCandidates & goal_candidates) const { return; } + virtual GoalCandidate getClosetGoalCandidateAlongLanes( + const GoalCandidates & goal_candidates) const = 0; protected: GoalPlannerParameters parameters_{}; diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index 2db3560d6e4f3..f1118f2b7882a 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -557,6 +557,11 @@ void GoalPlannerModule::generateGoalCandidates() goal_searcher_->setPlannerData(planner_data_); goal_searcher_->setReferenceGoal(status_.get_refined_goal_pose()); status_.set_goal_candidates(goal_searcher_->search()); + const auto current_lanes = utils::getExtendedCurrentLanes( + planner_data_, parameters_->backward_goal_search_length, + parameters_->forward_goal_search_length, false); + status_.set_closest_goal_candidate_pose( + goal_searcher_->getClosetGoalCandidateAlongLanes(status_.get_goal_candidates()).goal_pose); } else { GoalCandidate goal_candidate{}; goal_candidate.goal_pose = goal_pose; @@ -564,6 +569,7 @@ void GoalPlannerModule::generateGoalCandidates() GoalCandidates goal_candidates{}; goal_candidates.push_back(goal_candidate); status_.set_goal_candidates(goal_candidates); + status_.set_closest_goal_candidate_pose(goal_pose); } } @@ -1089,20 +1095,23 @@ PathWithLaneId GoalPlannerModule::generateStopPath() // difference between the outer and inner sides) // 4. feasible stop const auto search_start_offset_pose = calcLongitudinalOffsetPose( - reference_path.points, status_.get_refined_goal_pose().position, - -parameters_->backward_goal_search_length - common_parameters.base_link2front - - approximate_pull_over_distance_); + reference_path.points, status_.get_closest_goal_candidate_pose().position, + -approximate_pull_over_distance_); if ( !status_.get_is_safe_static_objects() && !status_.get_closest_start_pose() && !search_start_offset_pose) { return generateFeasibleStopPath(); } - const Pose stop_pose = - status_.get_is_safe_static_objects() - ? status_.get_pull_over_path()->start_pose - : (status_.get_closest_start_pose() ? status_.get_closest_start_pose().value() - : *search_start_offset_pose); + const Pose stop_pose = [&]() -> Pose { + if (status_.get_is_safe_static_objects()) { + return status_.get_pull_over_path()->start_pose; + } + if (status_.get_closest_start_pose()) { + return status_.get_closest_start_pose().value(); + } + return *search_start_offset_pose; + }(); // if stop pose is closer than min_stop_distance, stop as soon as possible const double ego_to_stop_distance = calcSignedArcLengthFromEgo(reference_path, stop_pose); diff --git a/planning/behavior_path_planner/src/utils/goal_planner/goal_searcher.cpp b/planning/behavior_path_planner/src/utils/goal_planner/goal_searcher.cpp index 1e6dc1776359b..f498ecd9ed8ec 100644 --- a/planning/behavior_path_planner/src/utils/goal_planner/goal_searcher.cpp +++ b/planning/behavior_path_planner/src/utils/goal_planner/goal_searcher.cpp @@ -468,4 +468,30 @@ bool GoalSearcher::isInAreas(const LinearRing2d & footprint, const BasicPolygons return false; } +GoalCandidate GoalSearcher::getClosetGoalCandidateAlongLanes( + const GoalCandidates & goal_candidates) const +{ + const auto current_lanes = utils::getExtendedCurrentLanes( + planner_data_, parameters_.backward_goal_search_length, parameters_.forward_goal_search_length, + /*forward_only_in_route*/ false); + + // Define a lambda function to compute the arc length for a given goal candidate. + auto getGoalArcLength = [¤t_lanes](const auto & candidate) { + return lanelet::utils::getArcCoordinates(current_lanes, candidate.goal_pose).length; + }; + + // Find the closest goal candidate by comparing the arc lengths of each candidate. + const auto closest_goal_candidate = std::min_element( + goal_candidates.begin(), goal_candidates.end(), + [&getGoalArcLength](const auto & a, const auto & b) { + return getGoalArcLength(a) < getGoalArcLength(b); + }); + + if (closest_goal_candidate == goal_candidates.end()) { + return {}; // return empty GoalCandidate in case no valid candidates are found. + } + + return *closest_goal_candidate; +} + } // namespace behavior_path_planner From dfc83a0beb913be92f57157c7cbc433337effba3 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 26 Oct 2023 22:12:04 +0900 Subject: [PATCH 077/202] feat(goal_planner): do not decelerate before path candidates generation (#5412) refactor(goal_planner): use updateData upda use getPreviousModuleOutput also in waiting approval Signed-off-by: kosuke55 --- .../goal_planner/goal_planner_module.cpp | 15 +++++++++++---- 1 file changed, 11 insertions(+), 4 deletions(-) diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index f1118f2b7882a..32b54a4e39170 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -914,14 +914,16 @@ void GoalPlannerModule::decideVelocity() BehaviorModuleOutput GoalPlannerModule::planWithGoalModification() { + // if pull over path candidates generation is not finished, use previous module output + if (status_.get_pull_over_path_candidates().empty()) { + return getPreviousModuleOutput(); + } + constexpr double path_update_duration = 1.0; resetPathCandidate(); resetPathReference(); - // set current road lanes, pull over lanes, and drivable lane - setLanes(); - // Check if it needs to decide path status_.set_has_decided_path(hasDecidedPath()); @@ -996,6 +998,11 @@ BehaviorModuleOutput GoalPlannerModule::planWaitingApproval() BehaviorModuleOutput GoalPlannerModule::planWaitingApprovalWithGoalModification() { + // if pull over path candidates generation is not finished, use previous module output + if (status_.get_pull_over_path_candidates().empty()) { + return getPreviousModuleOutput(); + } + waitApproval(); BehaviorModuleOutput out; @@ -1038,7 +1045,7 @@ BehaviorModuleOutput GoalPlannerModule::planWaitingApprovalWithGoalModification( std::pair GoalPlannerModule::calcDistanceToPathChange() const { - const auto & full_path = status_.get_pull_over_path()->getFullPath(); + const auto full_path = status_.get_pull_over_path()->getFullPath(); const auto ego_segment_idx = motion_utils::findNearestSegmentIndex( full_path.points, planner_data_->self_odometry->pose.pose, std::numeric_limits::max(), From a1cbdcb2d4c3574f40520c478bcaba3d9e85b1f9 Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Thu, 26 Oct 2023 22:13:58 +0900 Subject: [PATCH 078/202] fix(lane_change): filter objects for skip parking objects (#5419) * fix(lane_change): filter objects for skip parking objects Signed-off-by: Fumiya Watanabe * Update planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp Co-authored-by: Kosuke Takeuchi --------- Signed-off-by: Fumiya Watanabe Co-authored-by: Kosuke Takeuchi --- .../scene_module/lane_change/normal.hpp | 3 ++ .../src/scene_module/lane_change/normal.cpp | 28 ++++++++++++++++--- 2 files changed, 27 insertions(+), 4 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp index 54883489f2fe6..dc9f44fbd53da 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp @@ -155,6 +155,9 @@ class NormalLaneChange : public LaneChangeBase const lanelet::ConstLanelets & target_lanes, const lanelet::ConstLanelets & target_backward_lanes) const; + std::vector filterObjectsInTargetLane( + const LaneChangeTargetObjects & objects, const lanelet::ConstLanelets & target_lanes) const; + //! @brief Check if the ego vehicle is in stuck by a stationary obstacle. //! @param obstacle_check_distance Distance to check ahead for any objects that might be //! obstructing ego path. It makes sense to use values like the maximum lane change distance. 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 de120592e7505..d887b570b753a 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 @@ -918,6 +918,24 @@ LaneChangeTargetObjectIndices NormalLaneChange::filterObject( return filtered_obj_indices; } +std::vector NormalLaneChange::filterObjectsInTargetLane( + const LaneChangeTargetObjects & objects, const lanelet::ConstLanelets & target_lanes) const +{ + const auto target_polygon = + utils::lane_change::createPolygon(target_lanes, 0.0, std::numeric_limits::max()); + std::vector filtered_objects{}; + if (target_polygon) { + for (auto & obj : objects.target_lane) { + const auto obj_polygon = tier4_autoware_utils::toPolygon2d(obj.initial_pose.pose, obj.shape); + if (boost::geometry::intersects(target_polygon.value(), obj_polygon)) { + filtered_objects.push_back(obj); + } + } + } + + return filtered_objects; +} + PathWithLaneId NormalLaneChange::getTargetSegment( const lanelet::ConstLanelets & target_lanes, const Pose & lane_changing_start_pose, const double target_lane_length, const double lane_changing_length, @@ -1296,11 +1314,13 @@ bool NormalLaneChange::getLaneChangePaths( } candidate_paths->push_back(*candidate_path); + + std::vector filtered_objects = + filterObjectsInTargetLane(target_objects, target_lanes); if ( - !is_stuck && - utils::lane_change::passParkedObject( - route_handler, *candidate_path, target_objects.target_lane, lane_change_buffer, - is_goal_in_route, *lane_change_parameters_, object_debug_)) { + !is_stuck && utils::lane_change::passParkedObject( + route_handler, *candidate_path, filtered_objects, lane_change_buffer, + is_goal_in_route, *lane_change_parameters_, object_debug_)) { debug_print( "Reject: parking vehicle exists in the target lane, and the ego is not in stuck. Skip " "lane change."); From a995f98cd42b50862d4b33c7d6648e4219d5f58d Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 26 Oct 2023 22:34:55 +0900 Subject: [PATCH 079/202] fix(avoidance): calculate road shoulder distance for prev and next lanelet (#5226) Signed-off-by: satoshi-ota --- .../src/utils/avoidance/utils.cpp | 23 +++++++++++++++---- 1 file changed, 18 insertions(+), 5 deletions(-) diff --git a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp index a9f40dad86ae4..725b528abad51 100644 --- a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp +++ b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp @@ -1037,25 +1037,38 @@ void filterTargetObjects( }; // current lanelet - update_road_to_shoulder_distance(overhang_lanelet); + { + update_road_to_shoulder_distance(overhang_lanelet); + + o.to_road_shoulder_distance = extendToRoadShoulderDistanceWithPolygon( + rh, target_line, o.to_road_shoulder_distance, overhang_lanelet, o.overhang_pose.position, + overhang_basic_pose, parameters->use_hatched_road_markings, + parameters->use_intersection_areas); + } + // previous lanelet lanelet::ConstLanelets previous_lanelet{}; if (rh->getPreviousLaneletsWithinRoute(overhang_lanelet, &previous_lanelet)) { update_road_to_shoulder_distance(previous_lanelet.front()); + + o.to_road_shoulder_distance = extendToRoadShoulderDistanceWithPolygon( + rh, target_line, o.to_road_shoulder_distance, previous_lanelet.front(), + o.overhang_pose.position, overhang_basic_pose, parameters->use_hatched_road_markings, + parameters->use_intersection_areas); } + // next lanelet lanelet::ConstLanelet next_lanelet{}; if (rh->getNextLaneletWithinRoute(overhang_lanelet, &next_lanelet)) { update_road_to_shoulder_distance(next_lanelet); - } - debug.bounds.push_back(target_line); - { o.to_road_shoulder_distance = extendToRoadShoulderDistanceWithPolygon( - rh, target_line, o.to_road_shoulder_distance, overhang_lanelet, o.overhang_pose.position, + rh, target_line, o.to_road_shoulder_distance, next_lanelet, o.overhang_pose.position, overhang_basic_pose, parameters->use_hatched_road_markings, parameters->use_intersection_areas); } + + debug.bounds.push_back(target_line); } // calculate avoid_margin dynamically From 27f28d679e226f53a9ce3c7501a61dcab783bfa5 Mon Sep 17 00:00:00 2001 From: Satoshi Tanaka <16330533+scepter914@users.noreply.github.com> Date: Fri, 27 Oct 2023 00:38:12 +0900 Subject: [PATCH 080/202] chore(radar_static_pointcloud_filter): fix copyright (#5316) Signed-off-by: scepter914 --- .../radar_static_pointcloud_filter.param.yaml | 14 -------------- .../radar_static_pointcloud_filter_node.cpp | 2 +- 2 files changed, 1 insertion(+), 15 deletions(-) diff --git a/sensing/radar_static_pointcloud_filter/config/radar_static_pointcloud_filter.param.yaml b/sensing/radar_static_pointcloud_filter/config/radar_static_pointcloud_filter.param.yaml index a429f7a065ffe..01f3a4cdd641a 100644 --- a/sensing/radar_static_pointcloud_filter/config/radar_static_pointcloud_filter.param.yaml +++ b/sensing/radar_static_pointcloud_filter/config/radar_static_pointcloud_filter.param.yaml @@ -1,17 +1,3 @@ -# Copyright 2023 Foxconn, 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. - /**: ros__parameters: doppler_velocity_sd: 4.0 diff --git a/sensing/radar_static_pointcloud_filter/src/radar_static_pointcloud_filter_node/radar_static_pointcloud_filter_node.cpp b/sensing/radar_static_pointcloud_filter/src/radar_static_pointcloud_filter_node/radar_static_pointcloud_filter_node.cpp index 772dcef753c11..0eda1eae627e7 100644 --- a/sensing/radar_static_pointcloud_filter/src/radar_static_pointcloud_filter_node/radar_static_pointcloud_filter_node.cpp +++ b/sensing/radar_static_pointcloud_filter/src/radar_static_pointcloud_filter_node/radar_static_pointcloud_filter_node.cpp @@ -1,4 +1,4 @@ -// Copyright 2022-2023 Foxconn, TIER IV, Inc. +// Copyright 2022 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. From e16ebd850a5fc44c902dd50d6b883b323bae6519 Mon Sep 17 00:00:00 2001 From: Alexey Panferov <37497658+lexavtanke@users.noreply.github.com> Date: Thu, 26 Oct 2023 18:50:13 +0300 Subject: [PATCH 081/202] build(tvm_utility): remove download logic from CMake and update documentation (#4923) * add include tier4_autoware_utils and dependency Signed-off-by: Alexey Panferov * remove downloading logic from Cmake, update documentation Signed-off-by: Alexey Panferov * build(tvm_utility): remove downloading logic from Cmake, update documentation Signed-off-by: Alexey Panferov * style(pre-commit): autofix * build(tvm_utility): fix lint_cmake error Signed-off-by: Alexey Panferov * build(tvm_utility): format warning message Signed-off-by: Alexey Panferov * build(tvm_utility): add logic to work with autoware_data folder, add nn config header and test image Signed-off-by: Alexey Panferov * style(pre-commit): autofix * style(pre-commit): autofix * build(tvm_utility): refactor, update InferenceEngineTVM constructor Signed-off-by: Alexey Panferov * style(pre-commit): autofix * build(tvm_utility): add lightweight model and test with it Signed-off-by: Alexey Panferov * build(tvm_utility): make building yolo_v2_tiny disable by default Signed-off-by: Alexey Panferov * build(tvm_utility): remove test artifact for yolo_v2_tiny Signed-off-by: Alexey Panferov * build(tvm_utility): update docs Signed-off-by: Alexey Panferov * build(tvm_utility): update docs Signed-off-by: Alexey Panferov * style(pre-commit): autofix * build(tvm_utility): update namespace in abs_model test Signed-off-by: Alexey Panferov * build(tvm_utility): rewrite yolo_v2_tiny as example Signed-off-by: Alexey Panferov * build(tvm_utility): clean comments in yolo_v2_tiny example main.cpp Signed-off-by: Alexey Panferov * build(tvm_utility): add launch file for yolo_v2_tiny example Signed-off-by: Alexey Panferov * build(tvm_utility): update yolo_v2_tiny example readme Signed-off-by: Alexey Panferov * style(pre-commit): autofix * build(tvm_utility): add model for arm based systems, need to be tested on device Signed-off-by: Alexey Panferov * style(pre-commit): autofix * style(pre-commit): autofix * build(tvm_utility): update config header for arm Signed-off-by: Alexey Panferov * style(pre-commit): autofix * build(tvm_utility): remove debug output Signed-off-by: Alexey Panferov * build(tvm_utility): add find_package conditional section Signed-off-by: Alexey Panferov * build(tvm_utility): fix lint_cmake errors Signed-off-by: Alexey Panferov * build(tvm_utility): remove coping model files during build Signed-off-by: Alexey Panferov * build(tvm_utility): update readme with new data folder structure Signed-off-by: Alexey Panferov * build(tvm_utility): fix spell check warnings Signed-off-by: Alexey Panferov * style(pre-commit): autofix * build(tvm_utility): add no model files guard to get_neural_network Signed-off-by: Alexey Panferov * style(pre-commit): autofix * build(tvm_utility): set back default paths in config headers Signed-off-by: Alexey Panferov * build(tvm_utility): add param file, update launch file Signed-off-by: Alexey Panferov * build(tvm_utility): add schema file, update node name Signed-off-by: Alexey Panferov * style(pre-commit): autofix * build(tvm_utility): fix json-schema-check Signed-off-by: Alexey Panferov * build(tvm_utility): fix json-schema-check Signed-off-by: Alexey Panferov * style(pre-commit): autofix * build(tvm_utility): add parameter table to example readme Signed-off-by: Alexey Panferov * build(tvm_utility): fix typo-error in description of schema.json Signed-off-by: Alexey Panferov * style(pre-commit): autofix * buiild(tvm_utility): fix spell-check warning and typo Signed-off-by: Alexey Panferov --------- Signed-off-by: Alexey Panferov Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .cspell-partial.json | 2 +- common/tvm_utility/.gitignore | 2 - common/tvm_utility/CMakeLists.txt | 80 ++++++++-- common/tvm_utility/README.md | 59 +++---- .../config/yolo_v2_tiny_example.param.yaml | 6 + .../abs_model_aarch64/deploy_graph.json | 36 +++++ .../models/abs_model_aarch64/deploy_lib.so | Bin 0 -> 14824 bytes .../abs_model_aarch64/deploy_param.params | Bin 0 -> 32 bytes .../inference_engine_tvm_config.hpp | 54 +++++++ .../models/abs_model_x86_64/deploy_graph.json | 36 +++++ .../models/abs_model_x86_64/deploy_lib.so | Bin 0 -> 18168 bytes .../abs_model_x86_64/deploy_param.params | Bin 0 -> 32 bytes .../inference_engine_tvm_config.hpp | 53 +++++++ .../inference_engine_tvm_config.hpp | 56 +++++++ .../{test => example}/yolo_v2_tiny/main.cpp | 88 +++++++---- .../include/tvm_utility/pipeline.hpp | 13 +- .../launch/yolo_v2_tiny_example.launch.xml | 23 +++ .../schema/yolo_v2_tiny_example.schema.json | 47 ++++++ common/tvm_utility/test/abs_model/main.cpp | 146 ++++++++++++++++++ .../tvm-utility-yolo-v2-tiny-tests.md | 45 ++++-- common/tvm_utility/tvm_utility-extras.cmake | 47 +----- 21 files changed, 649 insertions(+), 144 deletions(-) create mode 100644 common/tvm_utility/config/yolo_v2_tiny_example.param.yaml create mode 100644 common/tvm_utility/data/models/abs_model_aarch64/deploy_graph.json create mode 100755 common/tvm_utility/data/models/abs_model_aarch64/deploy_lib.so create mode 100644 common/tvm_utility/data/models/abs_model_aarch64/deploy_param.params create mode 100644 common/tvm_utility/data/models/abs_model_aarch64/inference_engine_tvm_config.hpp create mode 100644 common/tvm_utility/data/models/abs_model_x86_64/deploy_graph.json create mode 100644 common/tvm_utility/data/models/abs_model_x86_64/deploy_lib.so create mode 100644 common/tvm_utility/data/models/abs_model_x86_64/deploy_param.params create mode 100644 common/tvm_utility/data/models/abs_model_x86_64/inference_engine_tvm_config.hpp create mode 100644 common/tvm_utility/data/models/yolo_v2_tiny/inference_engine_tvm_config.hpp rename common/tvm_utility/{test => example}/yolo_v2_tiny/main.cpp (80%) create mode 100644 common/tvm_utility/launch/yolo_v2_tiny_example.launch.xml create mode 100644 common/tvm_utility/schema/yolo_v2_tiny_example.schema.json create mode 100644 common/tvm_utility/test/abs_model/main.cpp diff --git a/.cspell-partial.json b/.cspell-partial.json index f45ae8961c56b..13849ef298019 100644 --- a/.cspell-partial.json +++ b/.cspell-partial.json @@ -5,5 +5,5 @@ "perception/bytetrack/lib/**" ], "ignoreRegExpList": [], - "words": [] + "words": ["dltype", "tvmgen"] } diff --git a/common/tvm_utility/.gitignore b/common/tvm_utility/.gitignore index a09bb7234b379..e69de29bb2d1d 100644 --- a/common/tvm_utility/.gitignore +++ b/common/tvm_utility/.gitignore @@ -1,2 +0,0 @@ -artifacts/**/*.jpg -data/ diff --git a/common/tvm_utility/CMakeLists.txt b/common/tvm_utility/CMakeLists.txt index b49f141d9e2e4..c0a0d7385f615 100644 --- a/common/tvm_utility/CMakeLists.txt +++ b/common/tvm_utility/CMakeLists.txt @@ -29,15 +29,19 @@ set(TVM_UTILITY_NODE_LIB_HEADERS ament_auto_add_library(${PROJECT_NAME} SHARED ${TVM_UTILITY_NODE_LIB_HEADERS}) set_target_properties(${PROJECT_NAME} PROPERTIES LINKER_LANGUAGE CXX) -if(BUILD_TESTING) +set(BUILD_EXAMPLE OFF CACHE BOOL "enable build yolo_v2_tiny") + +if(BUILD_TESTING OR BUILD_EXAMPLE) + find_package(OpenCV REQUIRED) + set(tvm_runtime_DIR ${tvm_vendor_DIR}) + find_package(tvm_runtime CONFIG REQUIRED) # Get target backend set(${PROJECT_NAME}_BACKEND llvm CACHE STRING "${PROJECT_NAME} neural network backend") +endif() +if(BUILD_TESTING) # compile each folder inside test/ as a test case find_package(ament_cmake_gtest REQUIRED) - find_package(OpenCV REQUIRED) - set(tvm_runtime_DIR ${tvm_vendor_DIR}) - find_package(tvm_runtime CONFIG REQUIRED) set(TEST_ARTIFACTS "${CMAKE_CURRENT_LIST_DIR}/artifacts") file(GLOB TEST_CASES test/*) @@ -47,17 +51,11 @@ if(BUILD_TESTING) endif() # the folder name becomes the test case name file(RELATIVE_PATH TEST_CASE_NAME ${CMAKE_CURRENT_LIST_DIR}/test ${TEST_FOLDER}) - # Get neural network. set(NN_DEPENDENCY "") - get_neural_network(${TEST_CASE_NAME} ${${PROJECT_NAME}_BACKEND} NN_DEPENDENCY) + get_neural_network(${TEST_CASE_NAME}_${CMAKE_SYSTEM_PROCESSOR} ${${PROJECT_NAME}_BACKEND} NN_DEPENDENCY) if(NOT NN_DEPENDENCY STREQUAL "") - if(TEST_CASE_NAME STREQUAL "yolo_v2_tiny" AND - NOT EXISTS ${TEST_ARTIFACTS}/yolo_v2_tiny/test_image_0.jpg) - message(WARNING "Missing image artifact for yolo_v2_tiny, skipping test") - continue() - endif() # add all cpp files in the folder to the target file(GLOB TEST_CASE_SOURCES ${TEST_FOLDER}/*.cpp) ament_add_gtest(${TEST_CASE_NAME} ${TEST_CASE_SOURCES}) @@ -75,7 +73,7 @@ if(BUILD_TESTING) target_include_directories("${TEST_CASE_NAME}" SYSTEM PUBLIC "${OpenCV_INCLUDE_DIRS}" "${tvm_utility_FOUND_INCLUDE_DIRS}" - "data/models" + "data/models/${TEST_CASE_NAME}_${CMAKE_SYSTEM_PROCESSOR}" "include" ) @@ -93,5 +91,61 @@ if(BUILD_TESTING) endforeach() endif() +if(BUILD_EXAMPLE) + # compile each folder inside example/ as an example + find_package(rclcpp REQUIRED) + + set(EXAMPLE_ARTIFACTS "${CMAKE_CURRENT_LIST_DIR}/artifacts") + file(GLOB EXAMPLE_CASES example/*) + foreach(EXAMPLE_FOLDER ${EXAMPLE_CASES}) + if(NOT IS_DIRECTORY ${EXAMPLE_FOLDER}) + continue() + endif() + # the folder name becomes the example name + file(RELATIVE_PATH EXAMPLE_NAME ${CMAKE_CURRENT_LIST_DIR}/example ${EXAMPLE_FOLDER}) + # Get neural network. + set(NN_DEPENDENCY "") + get_neural_network(${EXAMPLE_NAME} ${${PROJECT_NAME}_BACKEND} NN_DEPENDENCY) + + if(NOT NN_DEPENDENCY STREQUAL "") + if(EXAMPLE_NAME STREQUAL "yolo_v2_tiny" AND + NOT EXISTS ${EXAMPLE_ARTIFACTS}/yolo_v2_tiny/test_image_0.jpg) + message(WARNING "Missing image artifact for yolo_v2_tiny, skipping example") + continue() + endif() + # add all cpp files in the folder to the target + file(GLOB EXAMPLE_SOURCES ${EXAMPLE_FOLDER}/*.cpp) + ament_auto_add_executable(${EXAMPLE_NAME} ${EXAMPLE_SOURCES}) + ament_target_dependencies(${EXAMPLE_NAME} + "ament_index_cpp" + "tvm_vendor" + "rclcpp" + ) + add_dependencies(${EXAMPLE_NAME} ${NN_DEPENDENCY}) + + target_link_libraries("${EXAMPLE_NAME}" + "${OpenCV_LIBRARIES}" + "${tvm_runtime_LIBRARIES}" + ) + + target_include_directories("${EXAMPLE_NAME}" SYSTEM PUBLIC + "${OpenCV_INCLUDE_DIRS}" + "${tvm_utility_FOUND_INCLUDE_DIRS}" + "data/models" + "include" + ) + + else() + message(WARNING "No model is generated for ${EXAMPLE_FOLDER} example") + endif() + + endforeach() +endif() + list(APPEND ${PROJECT_NAME}_CONFIG_EXTRAS "${PROJECT_NAME}-extras.cmake") -ament_auto_package() +# ament_auto_package() +ament_auto_package( + INSTALL_TO_SHARE + launch + config + artifacts) diff --git a/common/tvm_utility/README.md b/common/tvm_utility/README.md index 7d4874d5ed89a..4751428353886 100644 --- a/common/tvm_utility/README.md +++ b/common/tvm_utility/README.md @@ -41,7 +41,7 @@ The earliest supported version depends on each package making use of the inferen #### Models -Dependent packages are expected to use the `get_neural_network` cmake function from this package in order to get the compiled TVM models. +Dependent packages are expected to use the `get_neural_network` cmake function from this package in order to build proper external dependency. ### Error detection and handling @@ -50,76 +50,55 @@ error description. ### Neural Networks Provider -This package also provides a utility to get pre-compiled neural networks to packages using them for their inference. - The neural networks are compiled as part of the [Model Zoo](https://github.com/autowarefoundation/modelzoo/) CI pipeline and saved to an S3 bucket. -This package exports cmake variables and functions for ease of access to those neural networks. The `get_neural_network` function creates an abstraction for the artifact management. -The artifacts are saved under the source directory of the package making use of the function; under "data/". -Priority is given to user-provided files, under "data/user/${MODEL_NAME}/". -If there are no user-provided files, the function tries to reuse previously-downloaded artifacts. -If there are no previously-downloaded artifacts, and if the `DOWNLOAD_ARTIFACTS` cmake variable is set, they will be downloaded from the bucket. -Otherwise, nothing happens. +Users should check if model configuration header file is under "data/user/${MODEL_NAME}/". Otherwise, nothing happens and compilation of the package will be skipped. The structure inside of the source directory of the package making use of the function is as follow: ```{text} . ├── data -│ ├── downloads -│ │ ├── ${MODEL 1}-${ARCH 1}-{BACKEND 1}-{VERSION 1}.tar.gz -│ │ ├── ... -│ │ └── ${MODEL ...}-${ARCH ...}-{BACKEND ...}-{VERSION ...}.tar.gz -│ ├── models -│ │ ├── ${MODEL 1} -│ │ │ ├── ... -│ │ │ └── inference_engine_tvm_config.hpp -│ │ ├── ... -│ │ └── ${MODEL ...} -│ │ └── ... -│ └── user +│ └── models │ ├── ${MODEL 1} -│ │ ├── deploy_graph.json -│ │ ├── deploy_lib.so -│ │ ├── deploy_param.params │ │ └── inference_engine_tvm_config.hpp │ ├── ... │ └── ${MODEL ...} │ └── ... ``` -The `inference_engine_tvm_config.hpp` file needed for compilation by dependent packages is made available under "data/models/${MODEL_NAME}/inference_engine_tvm_config.hpp". +The `inference_engine_tvm_config.hpp` file needed for compilation by dependent packages should be available under "data/models/${MODEL_NAME}/inference_engine_tvm_config.hpp". Dependent packages can use the cmake `add_dependencies` function with the name provided in the `DEPENDENCY` output parameter of `get_neural_network` to ensure this file is created before it gets used. The other `deploy_*` files are installed to "models/${MODEL_NAME}/" under the `share` directory of the package. -The target version to be downloaded can be overwritten by setting the `MODELZOO_VERSION` cmake variable. - -#### Assumptions / Known limits - -If several packages make use of the same neural network, it will be downloaded once per package. - -In case a requested artifact doesn't exist in the S3 bucket, the error message from ExternalProject is not explicit enough for the user to understand what went wrong. +The other model files should be stored in autoware_data folder under package folder with the structure: -In case the user manually sets `MODELZOO_VERSION` to "latest", the archive will not be re-downloaded when it gets updated in the S3 bucket (it is not a problem for tagged versions as they are not expected to be updated). +```{text} +$HOME/autoware_data +| └──${package} +| └──models +| ├── ${MODEL 1} +| | ├── deploy_graph.json +| | ├── deploy_lib.so +| | └── deploy_param.params +| ├── ... +| └── ${MODEL ...} +| └── ... +``` #### Inputs / Outputs -Inputs: - -- `DOWNLOAD_ARTIFACTS` cmake variable; needs to be set to enable downloading the artifacts -- `MODELZOO_VERSION` cmake variable; can be used to overwrite the default target version of downloads - Outputs: -- `get_neural_network` cmake function; can be used to get a neural network compiled for a specific backend +- `get_neural_network` cmake function; create proper external dependency for a package with use of the model provided by the user. In/Out: - The `DEPENDENCY` argument of `get_neural_network` can be checked for the outcome of the function. - It is an empty string when the neural network couldn't be made available. + It is an empty string when the neural network wasn't provided by the user. ## Security considerations diff --git a/common/tvm_utility/config/yolo_v2_tiny_example.param.yaml b/common/tvm_utility/config/yolo_v2_tiny_example.param.yaml new file mode 100644 index 0000000000000..b63e4a99f97f2 --- /dev/null +++ b/common/tvm_utility/config/yolo_v2_tiny_example.param.yaml @@ -0,0 +1,6 @@ +/**: + ros__parameters: + image_filename: $(find-pkg-share tvm_utility)/artifacts/yolo_v2_tiny/test_image_0.jpg + label_filename: $(find-pkg-share tvm_utility)/artifacts/yolo_v2_tiny/labels.txt + anchor_filename: $(find-pkg-share tvm_utility)/artifacts/yolo_v2_tiny/anchors.csv + data_path: $(env HOME)/autoware_data diff --git a/common/tvm_utility/data/models/abs_model_aarch64/deploy_graph.json b/common/tvm_utility/data/models/abs_model_aarch64/deploy_graph.json new file mode 100644 index 0000000000000..b226c01747dca --- /dev/null +++ b/common/tvm_utility/data/models/abs_model_aarch64/deploy_graph.json @@ -0,0 +1,36 @@ +{ + "nodes": [ + { + "op": "null", + "name": "a", + "inputs": [] + }, + { + "op": "tvm_op", + "name": "tvmgen_default_fused_abs", + "attrs": { + "num_outputs": "1", + "num_inputs": "1", + "flatten_data": "0", + "func_name": "tvmgen_default_fused_abs", + "hash": "1be44995aa501758" + }, + "inputs": [[0, 0, 0]] + } + ], + "arg_nodes": [0], + "heads": [[1, 0, 0]], + "attrs": { + "dltype": ["list_str", ["float32", "float32"]], + "device_index": ["list_int", [1, 1]], + "storage_id": ["list_int", [0, 1]], + "shape": [ + "list_shape", + [ + [2, 2], + [2, 2] + ] + ] + }, + "node_row_ptr": [0, 1, 2] +} diff --git a/common/tvm_utility/data/models/abs_model_aarch64/deploy_lib.so b/common/tvm_utility/data/models/abs_model_aarch64/deploy_lib.so new file mode 100755 index 0000000000000000000000000000000000000000..e1ad7cebad73440094dcfe44edb5c60cc3605f77 GIT binary patch literal 14824 zcmeHOeQX@Zb$@$DipNipl5HtgVlEXXAZ_V*q$rtG?Py7Tkg_F5lBq(8Q!MxHmgHIY zLEY^sVkBEqVgrIzpjKtnX^|Q(;y*0ME$Bc_ZJ?;AASm3pC}=nhRMbsqBQ6*_Ze-Xk zbf~23d$aTIcK7aha;pB(LL=S2ncuvxoqaPqJ2O1Keb)}3q5vm9{54Q%zSc%GS+N+B z86+AEKpkE?;fsP-vKAQ}xtdjWfhhXXPIVzIef|Og3 za!lvttuPJPYM=%w{oauEUfL=7m=Z6gJ?~pl%KzqeQ7oa`Y#5lb++LI;KW{X(O2&QC zUZr*k$@X9>Z%5qQZK%VKzmbRbL+jta{m5vW`SnxpSa-g(zv=R+jlceYOi+Cz{-|BZ zzk2*tO2pfMKYG4(_@jFxjPhic2?f!NwII7zEz@O2gNClT*}7MPdM`*TwEkCCo`CU`+U z)GO2wnD*nZ16F}5{p5IiRN`G89CUp$kxJ?r%Sc#{Op-O!ItvDtCFAlwO@9S=Vd!ylKq$Q0}|)w&N!D} zYq#S;K|S&j2n%x#ockbEyy3t(J_(<9;Lgyy=9cj~`( z^uoDoemHXnz%$p5UVL%Rum4;akeAC?|1`jC+x3xL>w8_*3D;zVR>&e$uGrt{wfcXq#W)JzQVj zenk(!p_9!p)&<(@?Hl3HVgro*+7EqQ9dF!Ozw(KF?MnTl8e&~Fc733+w0<1x8$ruW zwINSE9O`I-v8naiOnWUHdYAJ1wZZn2XovE9G0!~BTCQHvUf+V{i&z(^x8=#7K#i6& z6fKu%({iz9?RCI>)48E@AL0G|70Ub)Wenu|OO&~Qb`;DfZr5@jHN&e15j&39U$mfK z=+klHU5ovi~=8zpU!AA3zdFyUjn#SP2CDPCvAH_W{CzjT^Ob5mvtTLJc^3TDdA?Cw zo#!Wk>O7Yls`GrlxjK)wygE-{MRlI<-d2_;{~dViI*uPA*4`ho{g0{~3zSu7LJ>eGRmI=x^_9sD-xCW*j3Pt6$Ub7_8ZX{iN%a(|77f zcOs?Of5``9ANlXT`@xWQ?%$8z)pwy8dVhPgz3-=QJ@xf&l>eZ%;lb|5w6nV(d;Dww zDPnIusx+TIjlc0HwX0Y@gL*!ME6=xRPr}uM`TW=d`bEC*c+X?~P$pxhEp@_(#W$;6 z$!tP5(vunW{`=Lw?saOVckyPmz?qp!W#dsbY^r_WR@T+kg}Q>%p(tOXRoIdZo{Yv4YAmCgqA|=UwS##m zYsAYuq@}fP>?X@yS!}?8?!IpI%U@QzmX_G$l-SUR53#z;y+xVcP2Iipgyo$?t(j@l zdn@=zC*mo?+Taa2(M;&-hCU9m%#<;0VkD5tq4Z=nVJ1azP*`%EI%Q;3BdKPS8N-TY zCSurNkyH|!8E2#xc8jIddV;DFYwr>s;Isc-Js`Cn54w8kiMboWO2?vR<`Lo+Pos>N zl7(8T*!tK6B)HiXNZ9(3RASl?y)13acn`W>ainpiCy<^;`U29| zkj^8W{WPCnM7oF+mv{>6JIc5ALCul7lr>H50$Ytd-$R`tq?B6mM{8`aA*Lavq~cG* z->(oGMG8YL>Yvv<=N~@nd*~Pc`gRLJw1yeQUjXep*HcIzC9V4++1OZneOz7P!>{w_4y<3;aK60p3^PeH46U zi$r@fl$vZ(*l%l=<#E~+#KikuykE1%hQ)p%W$%<_-naR@r=H*0m!;wVxSmfD3-4F* zUdXiEyx~2TDW9!~_h{zqqS&jXEWPI`NikTI`!P~Xyzi-=-u;wljzdXqKZ7O>Gd?99 z4cKgONmAb1VSCr}w*RA&KQGJNt~gDx?@!j_o{K26pHl5jBfQUjvlKop+l49bvyE)s ziVHFO!`Y;jRR@Fp!O;5NtSI$9-WLjn`h&gQHV*foFZN@24s(6@tF(+MoTlwyyRibI z5q*VyGnxQ$yE^w-ea?cCqDTBR{zMaRz|6B$co8o&+50a3YLtEVBO#_5<>6r@#8RV- zjUcfZ_V1D?)UL-|ZOyVeVh5#7`BKZuT7OIHsx>X=hd=kqa9x|S0;ALy#Htm`wAKEW zoh!FsH}ThkZxt0#GiC*jiaNpH@|DI$>`u#;qrST3KpfD8H&%l?#b`lM{;Q>#2;D3G z6iDEDZJd@G5x`VmxZ$>j2bMj6DeyA=FQ#vctP3hu{vXcy@K}bT;AXa?NqVfrbWi1w z5({sDtCziW>7&aAy7bd!BV9Jxt%}!KnNwiTG&Me^W0E5DjLbe?gkF=`pA?~YWOlI# z$>@hBIT)d?PMPIl4X_H%W? zgT3tMeMN}<94|s89@6M&S5ud#j$=QD62`KCA447=bV>4~PJVAVEB)Bjxgp(n4e)!z zjn@LdU)=aI2+48Ujn@H>?`}K*{GM>*^@aC|8?SVZr4e|1b@MkB&RMzfX5ja+8*hPW z`JQ&;%M0g{+;}U5?r6{@P2mV zrRRC5-j8qT)oMBY6lbN$Uznx1>->e;i5KTtj2GwGix-!N%iJ*fd6x&Vi+*UYfU6}q z-DM4YocC575I|`>Jc76nXKnNHJAk0FP^(& zhUXBc=k-1L!7v~zE+8$}p8Q-29|V$r4)rLsGRPkaY@mXke-w60``6Eep3=B|SKuG# zz2oNxhy#?4+t;KX?|4{`uUiGj4exl{j<~PP`ANI~mcDnsg#0R*_M{=i*LpB2egknj z-{?KZ_)USAo|Ak6akY$|vxt{FKlyS6{=XCYi}BCjY0#6+qne7=Qro#WydXkT%tynMxokt*oMCaY(vj10vErnAcPfew1bf9LB(5Ug zN7)T@>8Hy^x@@A$y>uC%%OEyjFjR4tu9N#&+-F8FcI+G4yeAWK#N+ zk&M!z*KJ>WXlVD&t%%||W_|mp6d2vM422RX+j__9e+7)MeE1cggb6^*OnVE!Tgppcln@({qnX=3v zhIBBTjm4wuV^I(#+&r3sV00#lk~X!{cFkckor$HAu7ZwrX)|t+fXq$DEeMJ>3tHw8 z%!>ySOsArTWkArJl0h>SMOiM{5_a_15}ZfHMj{qLt0~llm!L3UD+^~bfaiV^bR-0w zHN)9SeL5RP2@HH$jwL5joHxSZw0W3I*sD#>W2VE2!|z+`1^%vr^K0fKQm}qgr-I;&)+#rH7Uq)Jl=6Ri1q)8YfCK8-$P9ME67V& zERE1qj^+8giD^K*k8B@lVTJ9lmI^eagtI(+FP`pB%Xu{~l+XlNs|~`_Cih zl;`hara$w@^Ydf)CCt$JB(Ll8_cQ;Uj+dXyOn-#3v>wRv{GEMCPQjTESw!M8(;p*B zvBUB_pX9%T;*}rySPRdOpUaylOZU(6Jdd1}Q}h9>b0)USbRH|6^1S}ODCN7H!kA|{ zrvL1b=XK^*)fQwvyHu3tGR@zKhyCaI@oLrP;C^bCO67lr736=286;)-dptPtQeukd z`3rebAun51JJaI?G0$=gUn_%AU0S6p0Ij1rlUKeT0WU`UtsS=10jDtLy}YX`$WKZ6 zbshmv5xywpz3unRTHEm63ieqKeP46l$@;#O-{YzD6k)J}{KigOo0s2P9<3n1Ny>Y_ zoW1f?_BkDw`2$k^fDB-|9cl}XXO2tSSK`=}qJqq>vrGTtQSP47>v#0Z$SB E8<^D&`v3p{ literal 0 HcmV?d00001 diff --git a/common/tvm_utility/data/models/abs_model_aarch64/deploy_param.params b/common/tvm_utility/data/models/abs_model_aarch64/deploy_param.params new file mode 100644 index 0000000000000000000000000000000000000000..1011def01ed82125c7ff17bdeed9fabb523a92c7 GIT binary patch literal 32 Scmdl!hlSO@_vv>A8~^}u(F7F$ literal 0 HcmV?d00001 diff --git a/common/tvm_utility/data/models/abs_model_aarch64/inference_engine_tvm_config.hpp b/common/tvm_utility/data/models/abs_model_aarch64/inference_engine_tvm_config.hpp new file mode 100644 index 0000000000000..09c8c0beacebe --- /dev/null +++ b/common/tvm_utility/data/models/abs_model_aarch64/inference_engine_tvm_config.hpp @@ -0,0 +1,54 @@ +// Copyright 2021 Arm Limited and Contributors. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "tvm_utility/pipeline.hpp" + +#ifndef COMMON__TVM_UTILITY__DATA__MODELS__ABS_MODEL_AARCH64__INFERENCE_ENGINE_TVM_CONFIG_HPP_ // NOLINT +#define COMMON__TVM_UTILITY__DATA__MODELS__ABS_MODEL_AARCH64__INFERENCE_ENGINE_TVM_CONFIG_HPP_ + +namespace model_zoo +{ +namespace inf_test +{ +namespace engine_load +{ +namespace abs_model +{ + +static const tvm_utility::pipeline::InferenceEngineTVMConfig config{ + {0, 0, 0}, // modelzoo_version + + // cspell: ignore mtriple + "abs_model_aarch64", // network_name + "llvm -mtriple=aarch64-linux-gnu", // network_backend + + "deploy_lib.so", // network_module_path + "deploy_graph.json", // network_graph_path + "deploy_param.params", // network_params_path + + // cspell: ignore DLCPU + kDLCPU, // tvm_device_type + 0, // tvm_device_id + + {{"a", kDLFloat, 32, 1, {2, 2}}}, // network_inputs + + {{"output", kDLFloat, 32, 1, {2, 2}}} // network_outputs +}; + +} // namespace abs_model +} // namespace engine_load +} // namespace inf_test +} // namespace model_zoo +#endif // COMMON__TVM_UTILITY__DATA__MODELS__ABS_MODEL_AARCH64__INFERENCE_ENGINE_TVM_CONFIG_HPP_ + // NOLINT diff --git a/common/tvm_utility/data/models/abs_model_x86_64/deploy_graph.json b/common/tvm_utility/data/models/abs_model_x86_64/deploy_graph.json new file mode 100644 index 0000000000000..b226c01747dca --- /dev/null +++ b/common/tvm_utility/data/models/abs_model_x86_64/deploy_graph.json @@ -0,0 +1,36 @@ +{ + "nodes": [ + { + "op": "null", + "name": "a", + "inputs": [] + }, + { + "op": "tvm_op", + "name": "tvmgen_default_fused_abs", + "attrs": { + "num_outputs": "1", + "num_inputs": "1", + "flatten_data": "0", + "func_name": "tvmgen_default_fused_abs", + "hash": "1be44995aa501758" + }, + "inputs": [[0, 0, 0]] + } + ], + "arg_nodes": [0], + "heads": [[1, 0, 0]], + "attrs": { + "dltype": ["list_str", ["float32", "float32"]], + "device_index": ["list_int", [1, 1]], + "storage_id": ["list_int", [0, 1]], + "shape": [ + "list_shape", + [ + [2, 2], + [2, 2] + ] + ] + }, + "node_row_ptr": [0, 1, 2] +} diff --git a/common/tvm_utility/data/models/abs_model_x86_64/deploy_lib.so b/common/tvm_utility/data/models/abs_model_x86_64/deploy_lib.so new file mode 100644 index 0000000000000000000000000000000000000000..9a6d02817e048aa8030e6969f39cb4a5a50b62d2 GIT binary patch literal 18168 zcmeHP3v3+48J_dS$&rW8c|Z(l$p!^vLvr!ic{mRzcCejGutOXiutn)+eYa;H+{3-w z3wD%(+apDhv6>=80jUK+i>N>l5K=&DDQU{1rJ?~<2vpPtlt7|B6j}i;rMdq9&ir?~ zvwKcbBC4u4^6o$L{g3(Q--q}&%@i0nWww__BrJ5rxg7MsXkpa@en%D(! zUc?krc1n@u$V~_)Q6}tS9hE38$})Xk=n*A8>X|GBl_4qSxj>K1;ANs#y{W(&3UL0A zXb;f?Xc*F~f|6bZV5m1L^hSjq(QQJWs1J=mLLc#HLIW;zF^3sZl*P2|xDmnpU00e# z2VKr#MwIlrK@a^r+eBgCF6t{4m;IuBL@7L2?>soXaBSMTgT3_N(f#jy``6!k_IK~z zyC(bKV;|gm`*Y|E^6@&O9{N{5&CG5?tPrbbejZqN=%>%#zA^sxj1QiE09Ykc2XGV@ z?vfHXw$n`>{c*$Z27C_mZZ;b-klq*9Z!hE*u^DVgT$hVYE@L}Pd>*T9;Q+PiW`WmB zI8)VuL@KFf3@vS_DpNQ2bg2OES2T<1J@jv5};)MzZJ#bdic zQ0=+Ct99Gv>vW@2%NXtHbSllkjav8?JsH`irL}lmk9TU>WOxu*#;$~#&|*pO0I~ym z5`2hi*|?!bvl%_2YW*4B9vUCiu2Z7p42y9<_yK{}NbRNakqz7)_5qANrME4(2(`&N zYQeD&Q95D4rx6JBlm#cBkUe3+X{=b(%Gq)R$`L3>pd5j61j-R8N1z;mas>XbBJg+r zrJsdzfA)pODo-wBEVTDUqauGKl>4Rcuo;K^iuVD|Uw#bE{)H`&djN9L{S>6oc=J1` zH(vQBlGPK&g<$GCmgK|%f}ru>SBk<^_I?K>4Z^w$lcLlfSR=jG5F zr;T}FpjjC3<&Q@F3)_nN==NZ$ypUNG;=4=0*_gG!3E~eUOXh zhS3cjvZKT3#*JnU-ROo~Yi>2E{u~|4!M{ zm;~?R@GW!g(rFI=QG##e@OAJ|#p+2LhhLK5r5xUQpouW$dlvgb z`;5iaaEbnOl^Ga(mJ=E`7W;y4=Br`&*Bs_*p?z^%o%}PVv5~b9;!Zk`kGBcRU#v@97 zv#gHVIcM){aB^Q8FnmTV9l#g486%wy8|r{=h)^z3>X#^HT_WJgNGzemGKy{nLyuq_ z^lxOfxXVSF-0F%tthqJ|0c@&ks8g=ELaCixW2IH2u>mgPnRQkbb%HDFf_Q~ROCrX| zkS;d`E@?EL(u_vA%b8&UR~s9slVt|AAsu=GnruxEWD|PQ>>SuFiKh%|8AVGf*IF%UE%u$xsM&$ajudG~NSAXU%+vIjt`bP|1O+}*_-8f@d z%zk;+bxDqzahkj@2kYHDjOe>!VO=$Q=9wI+Q(+ysqt$F;Px&)D0fQDfJ3jKfK!T_yvov2&jf?Ai`jI5V^!51RW)1uGj8>bvJIE4 zy|QufWeB4_yk26pAZOh-b_ZZzgX1XR<{rS-s%r0gPnEB|s`~mWAC$g?Gt`g%9fKou zBA++69=25}dX>-Ip87f9I|0YIlv6nZ{|gbI{iC#BbS61%4pPQuiSiR-VADQZ+K0M8 z@M)}GBFeNM6~{a#;(vTPpThD^vAGoI7ED88Qz`A4zEAL{b2fWiP_dny)rfLoFKP=1 zXb-9~g_o(`w}m|HBsLT2|0B=+DcBMG{}!Qr>~j6IZ+FwxSHlg@j{a=Y$SSJ?%LDaG zgITi_yse==P`^A7tm8O?7m18V@lnV%z)|XPfmzwZaOOet!F-LXB7_Xy78myjTlQgB zST|*RZonRL9~@>V8zJ)`79N9B6C4j=0e9s$L&g-FfWk&7m|_9&bQ2UFg2Ve36gmZm zO@SB4ta3`_R8(S~*`CX*=2m*Es^>4LdUoT*Pj8$y+cO7xO+^4$bEdY`c&j$g-2mOx zTgfWsV*#4An0c$#&zJ$7rxM;;v#EZDFnbSSOOl3#PNO} z07w@UT048XGId=vu+A5Szb(;TIJW$7U381@*t!4^4u~_B)&=lviba)P!wB>$%9nDk zc+CSXg01M5wk$IeL(58c1oO6(!M%MDPYrl##M5#-t-#Yt9u7F)Epi^VqYa}5X}h2R z;Wh_Mu_Aw z$j@7f5c&D-B1C@PUxdid14W4Ze5DAHpMNMqP7gUUR`9di>1Vgo&u*um-A+Hdoql#Z z{p@!7*~s3r=k&AB>1UtQ&pwBrHGshU2nnZkoD}(>MP%~iWuC(KPgY4U*xSiX zT49*Ty^MZ`tqd7r!(T>j?`C)~7MW75A}vR~)`_bH%4KTA$eM z!-TI`5uW$5nT7ATtXwawc3w0W^;Q&qN#GZd);m^?m-!j3bL@CEbNe0l!tW)0cVm}_ zok}fMgy+3%E~DRlE7uEmA&RR!>@#vnUUrcSitU?h)OkPH-KReIMXiAWAS{=$b ztqNuQt9AfNIBia0ALV5Ru2U=Ut4FCn;93RoAqih3a9Zb*y;YF$SmG(BY1U!l&g+Y- z0knTgvOi+VJNpTaPdEQ@(PP@dbqFNtcBR^T2xL6aKYxR(Iw`r?|1HRPV9?3^@NE;H z>*znn1TOctj{vW58NZ(b&RoXPbZ9^YbB@Pqz&-FKpWM%{09-L`*-tA<;MW4~_B|l( z7 zA~6CgmXZpRhD{V!eO;+Y$%USZ4rJj$KG^Bl-rCi!wr_32&mY_RwzhU{z8YZo^pQX{ zl1Zt9S~7wkL1IGl-VL0Qp1))?#Gc*>^2gTJKjDRYY zxGKM_T!ZppS4+ggP=Crm%TTRpr$3Wn@TxR{Z_xnL`?CY;P_`e0p(l!REE!EvUhD5q z>$|8Fk0o`=Lz^iZPeDc8RzeF~)xk8rWXbTM@`cX$OM&<9v<#8I(_SoDmzNm<;C}-5 z@}$30WQZ;o`gEU9AsH3&j#fdg$*{j@$J`Z(~c z32j(Y2nuMM^cB%SqEx@^Kh=-xZnOz2EuQH2Nl^KhSdQN_pk>vkbs14ISHe8&mGo)- zMpTYBm5FMSKK-r}jY|&8{tQU^v>qf%&#}mV$sEJqb!C-y-$THM||5Lz8;Y|8O zp9GFo-yD!AEfi^-kO9&odQj4*bx@7aCplT4%0Gh)%8>s`3+E_jsGmzQ_6x|M|8hG? zUtac!aGE-3<29j=d26~x7!+YFut=YP-$O>mkhfdtKT3jv%Ca8t z`!R52422Uy|9C-@XJlD?Zikp0zwHfNUVfTE`b1|6eW@Duh|s@{F02qBJ(8baLVuBX zUM9=SWn2f#7}~x}=*xFZvMiPha~C-Uv_MeN!Sso WLaAsz33k&T#mBvnR!Ry|k^LLHo-jB7 literal 0 HcmV?d00001 diff --git a/common/tvm_utility/data/models/abs_model_x86_64/deploy_param.params b/common/tvm_utility/data/models/abs_model_x86_64/deploy_param.params new file mode 100644 index 0000000000000000000000000000000000000000..1011def01ed82125c7ff17bdeed9fabb523a92c7 GIT binary patch literal 32 Scmdl!hlSO@_vv>A8~^}u(F7F$ literal 0 HcmV?d00001 diff --git a/common/tvm_utility/data/models/abs_model_x86_64/inference_engine_tvm_config.hpp b/common/tvm_utility/data/models/abs_model_x86_64/inference_engine_tvm_config.hpp new file mode 100644 index 0000000000000..7a7e3ef97c1b3 --- /dev/null +++ b/common/tvm_utility/data/models/abs_model_x86_64/inference_engine_tvm_config.hpp @@ -0,0 +1,53 @@ +// Copyright 2021 Arm Limited and Contributors. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "tvm_utility/pipeline.hpp" + +#ifndef COMMON__TVM_UTILITY__DATA__MODELS__ABS_MODEL_X86_64__INFERENCE_ENGINE_TVM_CONFIG_HPP_ // NOLINT +#define COMMON__TVM_UTILITY__DATA__MODELS__ABS_MODEL_X86_64__INFERENCE_ENGINE_TVM_CONFIG_HPP_ + +namespace model_zoo +{ +namespace inf_test +{ +namespace engine_load +{ +namespace abs_model +{ + +static const tvm_utility::pipeline::InferenceEngineTVMConfig config{ + {0, 0, 0}, // modelzoo_version + + "abs_model_x86_64", // network_name + "llvm", // network_backend + + "deploy_lib.so", // network_module_path + "deploy_graph.json", // network_graph_path + "deploy_param.params", // network_params_path + + // cspell: ignore DLCPU + kDLCPU, // tvm_device_type + 0, // tvm_device_id + + {{"a", kDLFloat, 32, 1, {2, 2}}}, // network_inputs + + {{"output", kDLFloat, 32, 1, {2, 2}}} // network_outputs +}; + +} // namespace abs_model +} // namespace engine_load +} // namespace inf_test +} // namespace model_zoo +#endif // COMMON__TVM_UTILITY__DATA__MODELS__ABS_MODEL_X86_64__INFERENCE_ENGINE_TVM_CONFIG_HPP_ + // NOLINT diff --git a/common/tvm_utility/data/models/yolo_v2_tiny/inference_engine_tvm_config.hpp b/common/tvm_utility/data/models/yolo_v2_tiny/inference_engine_tvm_config.hpp new file mode 100644 index 0000000000000..45ff0d8ce33e3 --- /dev/null +++ b/common/tvm_utility/data/models/yolo_v2_tiny/inference_engine_tvm_config.hpp @@ -0,0 +1,56 @@ +// Copyright 2021 Arm Limited and Contributors. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "tvm_utility/pipeline.hpp" + +#ifndef COMMON__TVM_UTILITY__DATA__MODELS__YOLO_V2_TINY__INFERENCE_ENGINE_TVM_CONFIG_HPP_ // NOLINT +#define COMMON__TVM_UTILITY__DATA__MODELS__YOLO_V2_TINY__INFERENCE_ENGINE_TVM_CONFIG_HPP_ + +namespace model_zoo +{ +namespace perception +{ +namespace camera_obstacle_detection +{ +namespace yolo_v2_tiny +{ +namespace tensorflow_fp32_coco +{ + +static const tvm_utility::pipeline::InferenceEngineTVMConfig config{ + {3, 0, 0}, // modelzoo_version + + "yolo_v2_tiny", // network_name + "llvm", // network_backend + + // cspell: ignore DLCPU + "./deploy_lib.so", // network_module_path + "./deploy_graph.json", // network_graph_path + "./deploy_param.params", // network_params_path + + kDLCPU, // tvm_device_type + 0, // tvm_device_id + + {{"input", kDLFloat, 32, 1, {-1, 416, 416, 3}}}, // network_inputs + + {{"output", kDLFloat, 32, 1, {1, 13, 13, 425}}} // network_outputs +}; + +} // namespace tensorflow_fp32_coco +} // namespace yolo_v2_tiny +} // namespace camera_obstacle_detection +} // namespace perception +} // namespace model_zoo +#endif // COMMON__TVM_UTILITY__DATA__MODELS__YOLO_V2_TINY__INFERENCE_ENGINE_TVM_CONFIG_HPP_ + // NOLINT diff --git a/common/tvm_utility/test/yolo_v2_tiny/main.cpp b/common/tvm_utility/example/yolo_v2_tiny/main.cpp similarity index 80% rename from common/tvm_utility/test/yolo_v2_tiny/main.cpp rename to common/tvm_utility/example/yolo_v2_tiny/main.cpp index aac7900f423c2..8a89436170894 100644 --- a/common/tvm_utility/test/yolo_v2_tiny/main.cpp +++ b/common/tvm_utility/example/yolo_v2_tiny/main.cpp @@ -12,30 +12,21 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "gtest/gtest.h" #include "tvm_utility/pipeline.hpp" #include "yolo_v2_tiny/inference_engine_tvm_config.hpp" #include +#include #include +#include +#include #include #include #include using model_zoo::perception::camera_obstacle_detection::yolo_v2_tiny::tensorflow_fp32_coco::config; -// Name of file containing the human readable names of the classes. One class -// on each line. -static constexpr const char * LABEL_FILENAME = "./yolo_v2_tiny_artifacts/labels.txt"; - -// Name of file containing the anchor values for the network. Each line is one -// anchor. each anchor has 2 comma separated floating point values. -static constexpr const char * ANCHOR_FILENAME = "./yolo_v2_tiny_artifacts/anchors.csv"; - -// Filename of the image on which to run the inference -static constexpr const char * IMAGE_FILENAME = "./yolo_v2_tiny_artifacts/test_image_0.jpg"; - namespace tvm_utility { namespace yolo_v2_tiny @@ -118,16 +109,18 @@ class PreProcessorYoloV2Tiny : public tvm_utility::pipeline::PreProcessor> { public: - explicit PostProcessorYoloV2Tiny(tvm_utility::pipeline::InferenceEngineTVMConfig config) + explicit PostProcessorYoloV2Tiny( + tvm_utility::pipeline::InferenceEngineTVMConfig config, std::string label_filename, + std::string anchor_filename) : network_output_width(config.network_outputs[0].node_shape[1]), network_output_height(config.network_outputs[0].node_shape[2]), network_output_depth(config.network_outputs[0].node_shape[3]), network_output_datatype_bytes(config.network_outputs[0].tvm_dtype_bits / 8) { // Parse human readable names for the classes - std::ifstream label_file{LABEL_FILENAME}; + std::ifstream label_file{label_filename}; if (!label_file.good()) { - std::string label_filename = LABEL_FILENAME; + std::string label_filename = label_filename; throw std::runtime_error("unable to open label file:" + label_filename); } std::string line{}; @@ -136,9 +129,9 @@ class PostProcessorYoloV2Tiny : public tvm_utility::pipeline::PostProcessor> anchors{}; }; -TEST(PipelineExamples, SimplePipeline) +} // namespace yolo_v2_tiny +} // namespace tvm_utility + +bool check_near(double expected, double actual, double tolerance) +{ + return fabs(expected - actual) <= tolerance; +} + +int main(int argc, char * argv[]) { + // init node to use parameters + rclcpp::init(argc, argv); + auto node = rclcpp::Node::make_shared("yolo_v2_tiny_example"); + // Filename of the image on which to run the inference + node->declare_parameter("image_filename"); + // Name of file containing the human readable names of the classes. One class + // on each line. + node->declare_parameter("label_filename"); + // Name of file containing the anchor values for the network. Each line is one + // anchor. each anchor has 2 comma separated floating point values. + node->declare_parameter("anchor_filename"); + // Packages data and artifacts directory path. + node->declare_parameter("data_path"); + + RCLCPP_INFO(node->get_logger(), "Node started"); + // Instantiate the pipeline - using PrePT = PreProcessorYoloV2Tiny; + using PrePT = tvm_utility::yolo_v2_tiny::PreProcessorYoloV2Tiny; using IET = tvm_utility::pipeline::InferenceEngineTVM; - using PostPT = PostProcessorYoloV2Tiny; + using PostPT = tvm_utility::yolo_v2_tiny::PostProcessorYoloV2Tiny; PrePT PreP{config}; - IET IE{config, "tvm_utility"}; - PostPT PostP{config}; + IET IE{config, "tvm_utility", node->get_parameter("data_path").as_string()}; + PostPT PostP{ + config, node->get_parameter("label_filename").as_string(), + node->get_parameter("anchor_filename").as_string()}; tvm_utility::pipeline::Pipeline pipeline(PreP, IE, PostP); - auto version_status = IE.version_check({2, 0, 0}); - EXPECT_NE(version_status, tvm_utility::Version::Unsupported); - // Push data input the pipeline and get the output - auto output = pipeline.schedule(IMAGE_FILENAME); + auto output = pipeline.schedule(node->get_parameter("image_filename").as_string()); // Define reference vector containing expected values, expressed as hexadecimal integers std::vector int_output{0x3eb64594, 0x3f435656, 0x3ece1600, 0x3e99d381, @@ -271,11 +287,21 @@ TEST(PipelineExamples, SimplePipeline) } // Test: check if the generated output is equal to the reference - EXPECT_EQ(expected_output.size(), output.size()) << "Unexpected output size"; + if (expected_output.size() == output.size()) { + RCLCPP_INFO(node->get_logger(), "Model has proper output size"); + } else { + RCLCPP_INFO(node->get_logger(), "Model has unexpected output size"); + } + for (size_t i = 0; i < output.size(); ++i) { - EXPECT_NEAR(expected_output[i], output[i], 0.0001) << "at index: " << i; + if (check_near(expected_output[i], output[i], 0.0001)) { + std::cout << "Model has proper output at index: " << i << std::endl; + RCLCPP_INFO(node->get_logger(), "Model has proper output at index: %zu", i); + + } else { + RCLCPP_INFO(node->get_logger(), "Model has unexpected output at index: %zu", i); + } } + rclcpp::shutdown(); + return 0; } - -} // namespace yolo_v2_tiny -} // namespace tvm_utility diff --git a/common/tvm_utility/include/tvm_utility/pipeline.hpp b/common/tvm_utility/include/tvm_utility/pipeline.hpp index 8504da193214f..a053d5ee471be 100644 --- a/common/tvm_utility/include/tvm_utility/pipeline.hpp +++ b/common/tvm_utility/include/tvm_utility/pipeline.hpp @@ -224,12 +224,19 @@ typedef struct class InferenceEngineTVM : public InferenceEngine { public: - explicit InferenceEngineTVM(const InferenceEngineTVMConfig & config, const std::string & pkg_name) + explicit InferenceEngineTVM( + const InferenceEngineTVMConfig & config, const std::string & pkg_name, + const std::string & autoware_data_path = "") : config_(config) { // Get full network path - std::string network_prefix = ament_index_cpp::get_package_share_directory(pkg_name) + - "/models/" + config.network_name + "/"; + std::string network_prefix; + if (autoware_data_path == "") { + network_prefix = ament_index_cpp::get_package_share_directory(pkg_name) + "/models/" + + config.network_name + "/"; + } else { + network_prefix = autoware_data_path + "/" + pkg_name + "/models/" + config.network_name + "/"; + } std::string network_module_path = network_prefix + config.network_module_path; std::string network_graph_path = network_prefix + config.network_graph_path; std::string network_params_path = network_prefix + config.network_params_path; diff --git a/common/tvm_utility/launch/yolo_v2_tiny_example.launch.xml b/common/tvm_utility/launch/yolo_v2_tiny_example.launch.xml new file mode 100644 index 0000000000000..045a6fc9dfa27 --- /dev/null +++ b/common/tvm_utility/launch/yolo_v2_tiny_example.launch.xml @@ -0,0 +1,23 @@ + + + + + + + + + diff --git a/common/tvm_utility/schema/yolo_v2_tiny_example.schema.json b/common/tvm_utility/schema/yolo_v2_tiny_example.schema.json new file mode 100644 index 0000000000000..8ee1987f73a62 --- /dev/null +++ b/common/tvm_utility/schema/yolo_v2_tiny_example.schema.json @@ -0,0 +1,47 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for yolo_v2_tiny_example of tvm_utility", + "type": "object", + "definitions": { + "yolo_v2_tiny_example": { + "type": "object", + "properties": { + "image_filename": { + "type": "string", + "default": "$(find-pkg-share tvm_utility)/artifacts/yolo_v2_tiny/test_image_0.jpg", + "description": "Filename of the image on which to run the inference." + }, + "label_filename": { + "type": "string", + "default": "$(find-pkg-share tvm_utility)/artifacts/yolo_v2_tiny/labels.txt", + "description": "Name of file containing the human readable names of the classes. One class on each line." + }, + "anchor_filename": { + "type": "string", + "default": "$(find-pkg-share tvm_utility)/artifacts/yolo_v2_tiny/anchors.csv", + "description": "Name of file containing the anchor values for the network. Each line is one anchor. each anchor has 2 comma separated floating point values." + }, + "data_path": { + "type": "string", + "default": "$(env HOME)/autoware_data", + "description": "Packages data and artifacts directory path." + } + }, + "required": ["image_filename", "label_filename", "anchor_filename", "data_path"] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/yolo_v2_tiny_example" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} diff --git a/common/tvm_utility/test/abs_model/main.cpp b/common/tvm_utility/test/abs_model/main.cpp new file mode 100644 index 0000000000000..4bf1a69c0556b --- /dev/null +++ b/common/tvm_utility/test/abs_model/main.cpp @@ -0,0 +1,146 @@ +// Copyright 2021-2022 Arm Limited and Contributors. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "gtest/gtest.h" +#include "tvm_utility/pipeline.hpp" +// file for current arch x86 or arm is chosen in cmake file +#include +#include + +#include +#include +#include +#include +#include + +using model_zoo::inf_test::engine_load::abs_model::config; + +namespace tvm_utility +{ +namespace abs_model +{ + +class PreProcessorLinearModel : public tvm_utility::pipeline::PreProcessor> +{ +public: + explicit PreProcessorLinearModel(tvm_utility::pipeline::InferenceEngineTVMConfig config) + : network_input_a_width(config.network_inputs[0].node_shape[0]), + network_input_a_height(config.network_inputs[0].node_shape[1]), + network_input_datatype_bytes(config.network_inputs[0].tvm_dtype_bits / 8) + { + // Allocate input variable + std::vector shape_a{network_input_a_width, network_input_a_height}; + tvm_utility::pipeline::TVMArrayContainer a{ + shape_a, + config.network_inputs[0].tvm_dtype_code, + config.network_inputs[0].tvm_dtype_bits, + config.network_inputs[0].tvm_dtype_lanes, + config.tvm_device_type, + config.tvm_device_id}; + + output = a; + } + + // The cv::Mat can't be used as an input because it throws an exception when + // passed as a constant reference + tvm_utility::pipeline::TVMArrayContainerVector schedule(const std::vector & input) + { + float input_mat[2][2]; + input_mat[0][0] = input[0]; + input_mat[0][1] = input[1]; + input_mat[1][0] = input[2]; + input_mat[1][1] = input[3]; + + // Create cv::Mat from input array + cv::Mat a_input = cv::Mat(2, 2, CV_32F, &input_mat); + + TVMArrayCopyFromBytes( + output.getArray(), a_input.data, + network_input_a_width * network_input_a_height * network_input_datatype_bytes); + + return {output}; + } + +private: + int64_t network_input_a_width; + int64_t network_input_a_height; + int64_t network_input_datatype_bytes; + tvm_utility::pipeline::TVMArrayContainer output; +}; + +class PostProcessorLinearModel : public tvm_utility::pipeline::PostProcessor> +{ +public: + explicit PostProcessorLinearModel(tvm_utility::pipeline::InferenceEngineTVMConfig config) + : network_output_width(config.network_outputs[0].node_shape[0]), + network_output_height(config.network_outputs[0].node_shape[1]), + network_output_datatype_bytes(config.network_outputs[0].tvm_dtype_bits / 8) + { + } + + std::vector schedule(const tvm_utility::pipeline::TVMArrayContainerVector & input) + { + // Assert data is stored row-majored in input and the dtype is float + assert(input[0].getArray()->strides == nullptr); + assert(input[0].getArray()->dtype.bits == sizeof(float) * 8); + + // Copy the inference data to CPU memory + std::vector infer(network_output_width * network_output_height, 0.0f); + + TVMArrayCopyToBytes( + input[0].getArray(), infer.data(), + network_output_width * network_output_height * network_output_datatype_bytes); + + return infer; + } + +private: + int64_t network_output_width; + int64_t network_output_height; + int64_t network_output_datatype_bytes; +}; + +TEST(PipelineExamples, SimplePipeline) +{ + // // Instantiate the pipeline + using PrePT = PreProcessorLinearModel; + using IET = tvm_utility::pipeline::InferenceEngineTVM; + using PostPT = PostProcessorLinearModel; + + PrePT PreP{config}; + IET IE{config, "tvm_utility"}; + PostPT PostP{config}; + + tvm_utility::pipeline::Pipeline pipeline(PreP, IE, PostP); + + auto version_status = IE.version_check({2, 0, 0}); + EXPECT_NE(version_status, tvm_utility::Version::Unsupported); + + // create input array + std::vector input_arr{-1., -2., -3., 4.}; + // send it to the model + auto output = pipeline.schedule(input_arr); + + // define vector with expected values + std::vector expected_output{1., 2., 3., 4.}; + + // // Test: check if the generated output is equal to the reference + EXPECT_EQ(expected_output.size(), output.size()) << "Unexpected output size"; + for (size_t i = 0; i < output.size(); ++i) { + EXPECT_NEAR(expected_output[i], output[i], 0.0001) << "at index: " << i; + } +} + +} // namespace abs_model +} // namespace tvm_utility diff --git a/common/tvm_utility/tvm-utility-yolo-v2-tiny-tests.md b/common/tvm_utility/tvm-utility-yolo-v2-tiny-tests.md index 188918a8f74df..39bcc640c2147 100644 --- a/common/tvm_utility/tvm-utility-yolo-v2-tiny-tests.md +++ b/common/tvm_utility/tvm-utility-yolo-v2-tiny-tests.md @@ -7,20 +7,41 @@ output. ## Compiling the Example -1. Download an example image to be used as test input. this image needs to be - saved in the `artifacts/yolo_v2_tiny/` folder + -```sh -curl https://raw.githubusercontent.com/pjreddie/darknet/master/data/dog.jpg \ - > artifacts/yolo_v2_tiny/test_image_0.jpg -``` +1. Check if model was downloaded during the env preparation step by ansible and + models files exist in the folder $HOME/autoware_data/tvm_utility/models/yolo_v2_tiny. -1. Build and test with the `DOWNLOAD_ARTIFACTS` flag set. + If not you can download them manually, see [Manual Artifacts Downloading](https://github.com/autowarefoundation/autoware/tree/main/ansible/roles/artifacts). -```sh -colcon build --packages-up-to tvm_utility --cmake-args -DDOWNLOAD_ARTIFACTS=ON -colcon test --packages-select tvm_utility -``` +2. Download an example image to be used as test input. This image needs to be + saved in the `artifacts/yolo_v2_tiny/` folder. + + ```sh + curl https://raw.githubusercontent.com/pjreddie/darknet/master/data/dog.jpg \ + > artifacts/yolo_v2_tiny/test_image_0.jpg + ``` + +3. Build. + + ```sh + colcon build --packages-up-to tvm_utility --cmake-args -DBUILD_EXAMPLE=ON + ``` + +4. Run. + + ```sh + ros2 launch tvm_utility yolo_v2_tiny_example.launch.xml + ``` + +## Parameters + +| Name | Type | Default Value | Description | +| ----------------- | ------ | ----------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------- | +| `image_filename` | string | `$(find-pkg-share tvm_utility)/artifacts/yolo_v2_tiny/test_image_0.jpg` | Filename of the image on which to run the inference. | +| `label_filename` | string | `$(find-pkg-share tvm_utility)/artifacts/yolo_v2_tiny/labels.txt` | Name of file containing the human readable names of the classes. One class on each line. | +| `anchor_filename` | string | `$(find-pkg-share tvm_utility)/artifacts/yolo_v2_tiny/anchors.csv` | Name of file containing the anchor values for the network. Each line is one anchor. each anchor has 2 comma separated floating point values. | +| `data_path` | string | `$(env HOME)/autoware_data` | Packages data and artifacts directory path. | ## GPU backend @@ -28,5 +49,5 @@ Vulkan is supported by default by the tvm_vendor package. It can be selected by setting the `tvm_utility_BACKEND` variable: ```sh -colcon build --packages-up-to tvm_utility --cmake-args -DDOWNLOAD_ARTIFACTS=ON -Dtvm_utility_BACKEND=vulkan +colcon build --packages-up-to tvm_utility -Dtvm_utility_BACKEND=vulkan ``` diff --git a/common/tvm_utility/tvm_utility-extras.cmake b/common/tvm_utility/tvm_utility-extras.cmake index 4214aa4995f0f..414644c1fe041 100644 --- a/common/tvm_utility/tvm_utility-extras.cmake +++ b/common/tvm_utility/tvm_utility-extras.cmake @@ -12,12 +12,7 @@ # See the License for the specific language governing permissions and # limitations under the License. -# Get user-provided variables -set(DOWNLOAD_ARTIFACTS OFF CACHE BOOL "enable artifacts download") -set(MODELZOO_VERSION "3.0.0-20221221" CACHE STRING "targeted ModelZoo version") - # -# Download the selected neural network if it is not already present on disk. # Make inference_engine_tvm_config.hpp available under "data/models/${MODEL_NAME}/". # Install the TVM artifacts to "share/${PROJECT_NAME}/models/". # Return the name of the custom target in the DEPENDENCY parameter. @@ -34,48 +29,16 @@ function(get_neural_network MODEL_NAME MODEL_BACKEND DEPENDENCY) set(EXTERNALPROJECT_NAME ${MODEL_NAME}_${MODEL_BACKEND}) set(PREPROCESSING "") - # Prioritize user-provided models. - # cspell: ignore COPYONLY - if(IS_DIRECTORY "${DATA_PATH}/user/${MODEL_NAME}") - message(STATUS "Using user-provided model from ${DATA_PATH}/user/${MODEL_NAME}") - file(REMOVE_RECURSE "${DATA_PATH}/models/${MODEL_NAME}/") - configure_file( - "${DATA_PATH}/user/${MODEL_NAME}/inference_engine_tvm_config.hpp" - "${DATA_PATH}/models/${MODEL_NAME}/inference_engine_tvm_config.hpp" - COPYONLY - ) - if(EXISTS "${DATA_PATH}/user/${MODEL_NAME}/preprocessing_inference_engine_tvm_config.hpp") - configure_file( - "${DATA_PATH}/user/${MODEL_NAME}/preprocessing_inference_engine_tvm_config.hpp" - "${DATA_PATH}/models/${MODEL_NAME}/preprocessing_inference_engine_tvm_config.hpp" - COPYONLY - ) - endif() - set(SOURCE_DIR "${DATA_PATH}/user/${MODEL_NAME}") - set(INSTALL_DIRECTORY "${DATA_PATH}/user/${MODEL_NAME}") - else() - set(ARCHIVE_NAME "${MODEL_NAME}-${CMAKE_SYSTEM_PROCESSOR}-${MODEL_BACKEND}-${MODELZOO_VERSION}.tar.gz") - - # Use previously-downloaded archives if available. - set(DOWNLOAD_DIR "${DATA_PATH}/downloads") - if(DOWNLOAD_ARTIFACTS) - message(STATUS "Downloading ${ARCHIVE_NAME} ...") - if(NOT EXISTS "${DATA_PATH}/downloads/${ARCHIVE_NAME}") - set(URL "https://autoware-modelzoo.s3.us-east-2.amazonaws.com/models/${MODELZOO_VERSION}/${ARCHIVE_NAME}") - file(DOWNLOAD ${URL} "${DOWNLOAD_DIR}/${ARCHIVE_NAME}") - endif() - else() - message(WARNING "Skipped download for ${MODEL_NAME} (enable by setting DOWNLOAD_ARTIFACTS)") - set(${DEPENDENCY} "" PARENT_SCOPE) - return() - endif() + if(IS_DIRECTORY "${DATA_PATH}/models/${MODEL_NAME}") set(SOURCE_DIR "${DATA_PATH}/models/${MODEL_NAME}") set(INSTALL_DIRECTORY "${DATA_PATH}/models/${MODEL_NAME}") - file(ARCHIVE_EXTRACT INPUT "${DOWNLOAD_DIR}/${ARCHIVE_NAME}" DESTINATION "${SOURCE_DIR}") if(EXISTS "${DATA_PATH}/models/${MODEL_NAME}/preprocessing_inference_engine_tvm_config.hpp") set(PREPROCESSING "${DATA_PATH}/models/${MODEL_NAME}/preprocessing_inference_engine_tvm_config.hpp") endif() - + else() + message(WARNING "No model configuration files were provided") + set(${DEPENDENCY} "" PARENT_SCOPE) + return() endif() include(ExternalProject) From bfabbcaf9a87683e1bebc04ecf54c68eea567bec Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Fri, 27 Oct 2023 09:52:14 +0900 Subject: [PATCH 082/202] fix(ekf_localizer): remove unnecessary publishers (#5423) Signed-off-by: kminoda --- .../include/ekf_localizer/ekf_localizer.hpp | 4 --- .../ekf_localizer/src/ekf_localizer.cpp | 25 ------------------- 2 files changed, 29 deletions(-) diff --git a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp index 4fc2305cc7adc..3a7c2eb4b9f22 100644 --- a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp @@ -117,10 +117,6 @@ class EKFLocalizer : public rclcpp::Node rclcpp::Publisher::SharedPtr pub_twist_; //!< @brief ekf estimated twist with covariance publisher rclcpp::Publisher::SharedPtr pub_twist_cov_; - //!< @brief debug info publisher - rclcpp::Publisher::SharedPtr pub_debug_; - //!< @brief debug measurement pose publisher - rclcpp::Publisher::SharedPtr pub_measured_pose_; //!< @brief ekf estimated yaw bias publisher rclcpp::Publisher::SharedPtr pub_yaw_bias_; //!< @brief ekf estimated yaw bias publisher diff --git a/localization/ekf_localizer/src/ekf_localizer.cpp b/localization/ekf_localizer/src/ekf_localizer.cpp index b39112b1d8d62..6fea079da8ea6 100644 --- a/localization/ekf_localizer/src/ekf_localizer.cpp +++ b/localization/ekf_localizer/src/ekf_localizer.cpp @@ -109,10 +109,6 @@ EKFLocalizer::EKFLocalizer(const std::string & node_name, const rclcpp::NodeOpti z_filter_.set_proc_dev(1.0); roll_filter_.set_proc_dev(0.01); pitch_filter_.set_proc_dev(0.01); - - /* debug */ - pub_debug_ = create_publisher("debug", 1); - pub_measured_pose_ = create_publisher("debug/measured_pose", 1); } /* @@ -637,27 +633,6 @@ void EKFLocalizer::publishEstimateResult() odometry.pose = pose_cov.pose; odometry.twist = twist_cov.twist; pub_odom_->publish(odometry); - - /* debug measured pose */ - if (!pose_queue_.empty()) { - geometry_msgs::msg::PoseStamped p; - p.pose = pose_queue_.back()->pose.pose; - p.header.stamp = current_time; - pub_measured_pose_->publish(p); - } - - /* debug publish */ - double pose_yaw = 0.0; - if (!pose_queue_.empty()) { - pose_yaw = tf2::getYaw(pose_queue_.back()->pose.pose.orientation); - } - - tier4_debug_msgs::msg::Float64MultiArrayStamped msg; - msg.stamp = current_time; - msg.data.push_back(tier4_autoware_utils::rad2deg(X(IDX::YAW))); // [0] ekf yaw angle - msg.data.push_back(tier4_autoware_utils::rad2deg(pose_yaw)); // [1] measurement yaw angle - msg.data.push_back(tier4_autoware_utils::rad2deg(X(IDX::YAWB))); // [2] yaw bias - pub_debug_->publish(msg); } void EKFLocalizer::publishDiagnostics() From 025f2cd7101fd1200aaabb930a8c3590f1212c31 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Fri, 27 Oct 2023 14:50:38 +0900 Subject: [PATCH 083/202] refactor(ekf_localizer): remove current_ekf_pose and so on (#5422) * refactor(ekf_localizer): remote current_ekf_pose and so on Signed-off-by: kminoda * still build failes due to one current_ekf_twist_ Signed-off-by: kminoda * now works Signed-off-by: kminoda * style(pre-commit): autofix --------- Signed-off-by: kminoda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../include/kalman_filter/kalman_filter.hpp | 6 +- common/kalman_filter/src/kalman_filter.cpp | 6 +- .../include/ekf_localizer/ekf_localizer.hpp | 24 ++++-- .../ekf_localizer/src/ekf_localizer.cpp | 83 +++++++++++-------- 4 files changed, 71 insertions(+), 48 deletions(-) diff --git a/common/kalman_filter/include/kalman_filter/kalman_filter.hpp b/common/kalman_filter/include/kalman_filter/kalman_filter.hpp index 79a47bde3a1b2..b500cffb92279 100644 --- a/common/kalman_filter/include/kalman_filter/kalman_filter.hpp +++ b/common/kalman_filter/include/kalman_filter/kalman_filter.hpp @@ -109,20 +109,20 @@ class KalmanFilter * @brief get current kalman filter state * @param x kalman filter state */ - void getX(Eigen::MatrixXd & x); + void getX(Eigen::MatrixXd & x) const; /** * @brief get current kalman filter covariance * @param P kalman filter covariance */ - void getP(Eigen::MatrixXd & P); + void getP(Eigen::MatrixXd & P) const; /** * @brief get component of current kalman filter state * @param i index of kalman filter state * @return value of i's component of the kalman filter state x[i] */ - double getXelement(unsigned int i); + double getXelement(unsigned int i) const; /** * @brief calculate kalman filter state and covariance by prediction model with A, B, Q matrix. diff --git a/common/kalman_filter/src/kalman_filter.cpp b/common/kalman_filter/src/kalman_filter.cpp index 937819ffb0275..450d40936db2e 100644 --- a/common/kalman_filter/src/kalman_filter.cpp +++ b/common/kalman_filter/src/kalman_filter.cpp @@ -77,15 +77,15 @@ void KalmanFilter::setR(const Eigen::MatrixXd & R) { R_ = R; } -void KalmanFilter::getX(Eigen::MatrixXd & x) +void KalmanFilter::getX(Eigen::MatrixXd & x) const { x = x_; } -void KalmanFilter::getP(Eigen::MatrixXd & P) +void KalmanFilter::getP(Eigen::MatrixXd & P) const { P = P_; } -double KalmanFilter::getXelement(unsigned int i) +double KalmanFilter::getXelement(unsigned int i) const { return x_(i); } diff --git a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp index 3a7c2eb4b9f22..8da982b8c0dfa 100644 --- a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp @@ -89,7 +89,7 @@ class Simple1DFilter return; }; void set_proc_dev(const double proc_dev) { proc_dev_x_c_ = proc_dev; } - double get_x() { return x_; } + double get_x() const { return x_; } private: bool initialized_; @@ -186,13 +186,6 @@ class EKFLocalizer : public rclcpp::Node AgedObjectQueue pose_queue_; AgedObjectQueue twist_queue_; - geometry_msgs::msg::PoseStamped current_ekf_pose_; //!< @brief current estimated pose - geometry_msgs::msg::PoseStamped - current_biased_ekf_pose_; //!< @brief current estimated pose without yaw bias correction - geometry_msgs::msg::TwistStamped current_ekf_twist_; //!< @brief current estimated twist - std::array current_pose_covariance_; - std::array current_twist_covariance_; - /** * @brief computes update & prediction of EKF for each ekf_dt_[s] time */ @@ -257,10 +250,23 @@ class EKFLocalizer : public rclcpp::Node */ void setCurrentResult(); + /** + * @brief get current ekf pose + */ + geometry_msgs::msg::PoseStamped getCurrentEKFPose(bool get_biased_yaw) const; + + /** + * @brief get current ekf twist + */ + geometry_msgs::msg::TwistStamped getCurrentEKFTwist() const; + /** * @brief publish current EKF estimation result */ - void publishEstimateResult(); + void publishEstimateResult( + const geometry_msgs::msg::PoseStamped & current_ekf_pose, + const geometry_msgs::msg::PoseStamped & current_biased_ekf_pose, + const geometry_msgs::msg::TwistStamped & current_ekf_twist); /** * @brief publish diagnostics message diff --git a/localization/ekf_localizer/src/ekf_localizer.cpp b/localization/ekf_localizer/src/ekf_localizer.cpp index 6fea079da8ea6..b05ec80627570 100644 --- a/localization/ekf_localizer/src/ekf_localizer.cpp +++ b/localization/ekf_localizer/src/ekf_localizer.cpp @@ -232,6 +232,17 @@ void EKFLocalizer::timerCallback() } twist_no_update_count_ = twist_is_updated ? 0 : (twist_no_update_count_ + 1); + const geometry_msgs::msg::PoseStamped current_ekf_pose = getCurrentEKFPose(false); + const geometry_msgs::msg::PoseStamped current_biased_ekf_pose = getCurrentEKFPose(true); + const geometry_msgs::msg::TwistStamped current_ekf_twist = getCurrentEKFTwist(); + + /* publish ekf result */ + publishEstimateResult(current_ekf_pose, current_biased_ekf_pose, current_ekf_twist); + publishDiagnostics(); +} + +geometry_msgs::msg::PoseStamped EKFLocalizer::getCurrentEKFPose(bool get_biased_yaw) const +{ const double x = ekf_.getXelement(IDX::X); const double y = ekf_.getXelement(IDX::Y); const double z = z_filter_.get_x(); @@ -242,27 +253,32 @@ void EKFLocalizer::timerCallback() const double roll = roll_filter_.get_x(); const double pitch = pitch_filter_.get_x(); const double yaw = biased_yaw + yaw_bias; - const double vx = ekf_.getXelement(IDX::VX); - const double wz = ekf_.getXelement(IDX::WZ); - - current_ekf_pose_.header.frame_id = params_.pose_frame_id; - current_ekf_pose_.header.stamp = this->now(); - current_ekf_pose_.pose.position = tier4_autoware_utils::createPoint(x, y, z); - current_ekf_pose_.pose.orientation = - tier4_autoware_utils::createQuaternionFromRPY(roll, pitch, yaw); - current_biased_ekf_pose_ = current_ekf_pose_; - current_biased_ekf_pose_.pose.orientation = - tier4_autoware_utils::createQuaternionFromRPY(roll, pitch, biased_yaw); + geometry_msgs::msg::PoseStamped current_ekf_pose; + current_ekf_pose.header.frame_id = params_.pose_frame_id; + current_ekf_pose.header.stamp = this->now(); + current_ekf_pose.pose.position = tier4_autoware_utils::createPoint(x, y, z); + if (get_biased_yaw) { + current_ekf_pose.pose.orientation = + tier4_autoware_utils::createQuaternionFromRPY(roll, pitch, biased_yaw); + } else { + current_ekf_pose.pose.orientation = + tier4_autoware_utils::createQuaternionFromRPY(roll, pitch, yaw); + } + return current_ekf_pose; +} - current_ekf_twist_.header.frame_id = "base_link"; - current_ekf_twist_.header.stamp = this->now(); - current_ekf_twist_.twist.linear.x = vx; - current_ekf_twist_.twist.angular.z = wz; +geometry_msgs::msg::TwistStamped EKFLocalizer::getCurrentEKFTwist() const +{ + const double vx = ekf_.getXelement(IDX::VX); + const double wz = ekf_.getXelement(IDX::WZ); - /* publish ekf result */ - publishEstimateResult(); - publishDiagnostics(); + geometry_msgs::msg::TwistStamped current_ekf_twist; + current_ekf_twist.header.frame_id = "base_link"; + current_ekf_twist.header.stamp = this->now(); + current_ekf_twist.twist.linear.x = vx; + current_ekf_twist.twist.angular.z = wz; + return current_ekf_twist; } void EKFLocalizer::showCurrentX() @@ -282,12 +298,12 @@ void EKFLocalizer::timerTFCallback() return; } - if (current_ekf_pose_.header.frame_id == "") { + if (params_.pose_frame_id == "") { return; } geometry_msgs::msg::TransformStamped transform_stamped; - transform_stamped = tier4_autoware_utils::pose2transform(current_ekf_pose_, "base_link"); + transform_stamped = tier4_autoware_utils::pose2transform(getCurrentEKFPose(false), "base_link"); transform_stamped.header.stamp = this->now(); tf_br_->sendTransform(transform_stamped); } @@ -338,8 +354,6 @@ void EKFLocalizer::callbackInitialPose( X(IDX::X) = initialpose->pose.pose.position.x + transform.transform.translation.x; X(IDX::Y) = initialpose->pose.pose.position.y + transform.transform.translation.y; - current_ekf_pose_.pose.position.z = - initialpose->pose.pose.position.z + transform.transform.translation.z; X(IDX::YAW) = tf2::getYaw(initialpose->pose.pose.orientation) + tf2::getYaw(transform.transform.rotation); X(IDX::YAWB) = 0.0; @@ -488,7 +502,7 @@ bool EKFLocalizer::measurementUpdatePose(const geometry_msgs::msg::PoseWithCovar // Considering change of z value due to measurement pose delay const auto rpy = tier4_autoware_utils::getRPY(pose.pose.pose.orientation); - const double dz_delay = current_ekf_twist_.twist.linear.x * delay_time * std::sin(-rpy.y); + const double dz_delay = ekf_.getXelement(IDX::VX) * delay_time * std::sin(-rpy.y); geometry_msgs::msg::PoseWithCovarianceStamped pose_with_z_delay; pose_with_z_delay = pose; pose_with_z_delay.pose.pose.position.z += dz_delay; @@ -586,36 +600,39 @@ bool EKFLocalizer::measurementUpdateTwist( /* * publishEstimateResult */ -void EKFLocalizer::publishEstimateResult() +void EKFLocalizer::publishEstimateResult( + const geometry_msgs::msg::PoseStamped & current_ekf_pose, + const geometry_msgs::msg::PoseStamped & current_biased_ekf_pose, + const geometry_msgs::msg::TwistStamped & current_ekf_twist) { rclcpp::Time current_time = this->now(); const Eigen::MatrixXd X = ekf_.getLatestX(); const Eigen::MatrixXd P = ekf_.getLatestP(); /* publish latest pose */ - pub_pose_->publish(current_ekf_pose_); - pub_biased_pose_->publish(current_biased_ekf_pose_); + pub_pose_->publish(current_ekf_pose); + pub_biased_pose_->publish(current_biased_ekf_pose); /* publish latest pose with covariance */ geometry_msgs::msg::PoseWithCovarianceStamped pose_cov; pose_cov.header.stamp = current_time; - pose_cov.header.frame_id = current_ekf_pose_.header.frame_id; - pose_cov.pose.pose = current_ekf_pose_.pose; + pose_cov.header.frame_id = current_ekf_pose.header.frame_id; + pose_cov.pose.pose = current_ekf_pose.pose; pose_cov.pose.covariance = ekfCovarianceToPoseMessageCovariance(P); pub_pose_cov_->publish(pose_cov); geometry_msgs::msg::PoseWithCovarianceStamped biased_pose_cov = pose_cov; - biased_pose_cov.pose.pose = current_biased_ekf_pose_.pose; + biased_pose_cov.pose.pose = current_biased_ekf_pose.pose; pub_biased_pose_cov_->publish(biased_pose_cov); /* publish latest twist */ - pub_twist_->publish(current_ekf_twist_); + pub_twist_->publish(current_ekf_twist); /* publish latest twist with covariance */ geometry_msgs::msg::TwistWithCovarianceStamped twist_cov; twist_cov.header.stamp = current_time; - twist_cov.header.frame_id = current_ekf_twist_.header.frame_id; - twist_cov.twist.twist = current_ekf_twist_.twist; + twist_cov.header.frame_id = current_ekf_twist.header.frame_id; + twist_cov.twist.twist = current_ekf_twist.twist; twist_cov.twist.covariance = ekfCovarianceToTwistMessageCovariance(P); pub_twist_cov_->publish(twist_cov); @@ -628,7 +645,7 @@ void EKFLocalizer::publishEstimateResult() /* publish latest odometry */ nav_msgs::msg::Odometry odometry; odometry.header.stamp = current_time; - odometry.header.frame_id = current_ekf_pose_.header.frame_id; + odometry.header.frame_id = current_ekf_pose.header.frame_id; odometry.child_frame_id = "base_link"; odometry.pose = pose_cov.pose; odometry.twist = twist_cov.twist; From 06d27aa743e1fb29087bbdb78422f8d13a64c17d Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Fri, 27 Oct 2023 15:00:17 +0900 Subject: [PATCH 084/202] chore: update CODEOWNERS (#5350) Signed-off-by: GitHub Co-authored-by: github-actions --- .github/CODEOWNERS | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 9de27f82ffcef..e298dccefd827 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -88,13 +88,15 @@ launch/tier4_system_launch/** akihiro.sakurai@tier4.jp fumihito.ito@tier4.jp launch/tier4_vehicle_launch/** yukihiro.saito@tier4.jp localization/ekf_localizer/** koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp takamasa.horibe@tier4.jp takeshi.ishita@tier4.jp yamato.ando@tier4.jp localization/gyro_odometer/** masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp -localization/landmark_based_localizer/ar_tag_based_localizer/** masahiro.sakamoto@tier4.jp shintaro.sakoda@tier4.jp -localization/landmark_based_localizer/landmark_tf_caster/** masahiro.sakamoto@tier4.jp shintaro.sakoda@tier4.jp +localization/landmark_based_localizer/ar_tag_based_localizer/** kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp shintaro.sakoda@tier4.jp yamato.ando@tier4.jp +localization/landmark_based_localizer/landmark_parser/** kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp shintaro.sakoda@tier4.jp yamato.ando@tier4.jp localization/localization_error_monitor/** koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp +localization/localization_util/** kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp shintaro.sakoda@tier4.jp yamato.ando@tier4.jp localization/ndt_scan_matcher/** kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp localization/pose2twist/** masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp localization/pose_initializer/** isamu.takagi@tier4.jp masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp localization/stop_filter/** koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp +localization/tree_structured_parzen_estimator/** kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp shintaro.sakoda@tier4.jp yamato.ando@tier4.jp localization/twist2accel/** koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp localization/yabloc/yabloc_common/** kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp localization/yabloc/yabloc_image_processing/** kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp @@ -152,7 +154,7 @@ perception/traffic_light_ssd_fine_detector/** daisuke.nishimatsu@tier4.jp perception/traffic_light_visualization/** yukihiro.saito@tier4.jp planning/behavior_path_planner/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp yutaka.shimizu@tier4.jp zulfaqar.azmi@tier4.jp planning/behavior_velocity_blind_spot_module/** mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp -planning/behavior_velocity_crosswalk_module/** satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp +planning/behavior_velocity_crosswalk_module/** kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_detection_area_module/** kyoichi.sugahara@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_intersection_module/** kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_no_drivable_lane_module/** ahmed.ebrahim@leodrive.ai fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp @@ -179,7 +181,7 @@ planning/obstacle_cruise_planner/** kosuke.takeuchi@tier4.jp satoshi.ota@tier4.j planning/obstacle_stop_planner/** berkay@leodrive.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp planning/obstacle_velocity_limiter/** maxime.clement@tier4.jp planning/path_smoother/** maxime.clement@tier4.jp takayuki.murooka@tier4.jp -planning/planning_debug_tools/** taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp +planning/planning_debug_tools/** taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp planning/planning_test_utils/** kyoichi.sugahara@tier4.jp takamasa.horibe@tier4.jp planning/planning_validator/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp planning/route_handler/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp mamoru.sobue@tier4.jp takayuki.murooka@tier4.jp yutaka.shimizu@tier4.jp zulfaqar.azmi@tier4.jp @@ -221,7 +223,6 @@ system/emergency_handler/** makoto.kurihara@tier4.jp system/mrm_comfortable_stop_operator/** makoto.kurihara@tier4.jp system/mrm_emergency_stop_operator/** makoto.kurihara@tier4.jp system/system_diagnostic_graph/** isamu.takagi@tier4.jp -system/system_diagnostic_monitor/** isamu.takagi@tier4.jp system/system_error_monitor/** fumihito.ito@tier4.jp system/system_monitor/** akihiro.sakurai@tier4.jp fumihito.ito@tier4.jp system/topic_state_monitor/** ryohsuke.mitsudome@tier4.jp From 4e58c9a51fc9b69416e3dba73bbea1b86a2c4041 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Fri, 27 Oct 2023 15:13:14 +0900 Subject: [PATCH 085/202] refactor(ekf_localizer): use struct for diag info (#5421) * refactor(ekf_localizer): use struct for diag info Signed-off-by: kminoda * fix Signed-off-by: kminoda * style(pre-commit): autofix * update Signed-off-by: kminoda * style(pre-commit): autofix * move diag_info to ekf_localizer.hpp Signed-off-by: kminoda * remove diag.hpp Signed-off-by: kminoda --------- Signed-off-by: kminoda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../include/ekf_localizer/ekf_localizer.hpp | 39 +++++++---- .../ekf_localizer/src/ekf_localizer.cpp | 70 ++++++++++--------- 2 files changed, 60 insertions(+), 49 deletions(-) diff --git a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp index 8da982b8c0dfa..719185da4306a 100644 --- a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp @@ -49,6 +49,28 @@ #include #include +struct EKFDiagnosticInfo +{ + EKFDiagnosticInfo() + : no_update_count(0), + queue_size(0), + is_passed_delay_gate(true), + delay_time(0), + delay_time_threshold(0), + is_passed_mahalanobis_gate(true), + mahalanobis_distance(0) + { + } + + size_t no_update_count; + size_t queue_size; + bool is_passed_delay_gate; + double delay_time; + double delay_time_threshold; + bool is_passed_mahalanobis_gate; + double mahalanobis_distance; +}; + class Simple1DFilter { public: @@ -167,21 +189,8 @@ class EKFLocalizer : public rclcpp::Node bool is_activated_; - size_t pose_no_update_count_; - size_t pose_queue_size_; - bool pose_is_passed_delay_gate_; - double pose_delay_time_; - double pose_delay_time_threshold_; - bool pose_is_passed_mahalanobis_gate_; - double pose_mahalanobis_distance_; - - size_t twist_no_update_count_; - size_t twist_queue_size_; - bool twist_is_passed_delay_gate_; - double twist_delay_time_; - double twist_delay_time_threshold_; - bool twist_is_passed_mahalanobis_gate_; - double twist_mahalanobis_distance_; + EKFDiagnosticInfo pose_diag_info_; + EKFDiagnosticInfo twist_diag_info_; AgedObjectQueue pose_queue_; AgedObjectQueue twist_queue_; diff --git a/localization/ekf_localizer/src/ekf_localizer.cpp b/localization/ekf_localizer/src/ekf_localizer.cpp index b05ec80627570..c39e38c8d438d 100644 --- a/localization/ekf_localizer/src/ekf_localizer.cpp +++ b/localization/ekf_localizer/src/ekf_localizer.cpp @@ -176,12 +176,12 @@ void EKFLocalizer::timerCallback() /* pose measurement update */ - pose_queue_size_ = pose_queue_.size(); - pose_is_passed_delay_gate_ = true; - pose_delay_time_ = 0.0; - pose_delay_time_threshold_ = 0.0; - pose_is_passed_mahalanobis_gate_ = true; - pose_mahalanobis_distance_ = 0.0; + pose_diag_info_.queue_size = pose_queue_.size(); + pose_diag_info_.is_passed_delay_gate = true; + pose_diag_info_.delay_time = 0.0; + pose_diag_info_.delay_time_threshold = 0.0; + pose_diag_info_.is_passed_mahalanobis_gate = true; + pose_diag_info_.mahalanobis_distance = 0.0; bool pose_is_updated = false; @@ -201,16 +201,16 @@ void EKFLocalizer::timerCallback() DEBUG_INFO(get_logger(), "[EKF] measurementUpdatePose calc time = %f [ms]", stop_watch_.toc()); DEBUG_INFO(get_logger(), "------------------------- end Pose -------------------------\n"); } - pose_no_update_count_ = pose_is_updated ? 0 : (pose_no_update_count_ + 1); + pose_diag_info_.no_update_count = pose_is_updated ? 0 : (pose_diag_info_.no_update_count + 1); /* twist measurement update */ - twist_queue_size_ = twist_queue_.size(); - twist_is_passed_delay_gate_ = true; - twist_delay_time_ = 0.0; - twist_delay_time_threshold_ = 0.0; - twist_is_passed_mahalanobis_gate_ = true; - twist_mahalanobis_distance_ = 0.0; + twist_diag_info_.queue_size = twist_queue_.size(); + twist_diag_info_.is_passed_delay_gate = true; + twist_diag_info_.delay_time = 0.0; + twist_diag_info_.delay_time_threshold = 0.0; + twist_diag_info_.is_passed_mahalanobis_gate = true; + twist_diag_info_.mahalanobis_distance = 0.0; bool twist_is_updated = false; @@ -230,7 +230,7 @@ void EKFLocalizer::timerCallback() DEBUG_INFO(get_logger(), "[EKF] measurementUpdateTwist calc time = %f [ms]", stop_watch_.toc()); DEBUG_INFO(get_logger(), "------------------------- end Twist -------------------------\n"); } - twist_no_update_count_ = twist_is_updated ? 0 : (twist_no_update_count_ + 1); + twist_diag_info_.no_update_count = twist_is_updated ? 0 : (twist_diag_info_.no_update_count + 1); const geometry_msgs::msg::PoseStamped current_ekf_pose = getCurrentEKFPose(false); const geometry_msgs::msg::PoseStamped current_biased_ekf_pose = getCurrentEKFPose(true); @@ -446,12 +446,12 @@ bool EKFLocalizer::measurementUpdatePose(const geometry_msgs::msg::PoseWithCovar delay_time = std::max(delay_time, 0.0); - int delay_step = std::roundf(delay_time / ekf_dt_); + const int delay_step = std::roundf(delay_time / ekf_dt_); - pose_delay_time_ = std::max(delay_time, pose_delay_time_); - pose_delay_time_threshold_ = params_.extend_state_step * ekf_dt_; + pose_diag_info_.delay_time = std::max(delay_time, pose_diag_info_.delay_time); + pose_diag_info_.delay_time_threshold = params_.extend_state_step * ekf_dt_; if (delay_step >= params_.extend_state_step) { - pose_is_passed_delay_gate_ = false; + pose_diag_info_.is_passed_delay_gate = false; warning_.warnThrottle( poseDelayStepWarningMessage(delay_time, params_.extend_state_step, ekf_dt_), 2000); return false; @@ -482,9 +482,9 @@ bool EKFLocalizer::measurementUpdatePose(const geometry_msgs::msg::PoseWithCovar const Eigen::MatrixXd P_y = P_curr.block(0, 0, dim_y, dim_y); const double distance = mahalanobis(y_ekf, y, P_y); - pose_mahalanobis_distance_ = std::max(distance, pose_mahalanobis_distance_); + pose_diag_info_.mahalanobis_distance = std::max(distance, pose_diag_info_.mahalanobis_distance); if (distance > params_.pose_gate_dist) { - pose_is_passed_mahalanobis_gate_ = false; + pose_diag_info_.is_passed_mahalanobis_gate = false; warning_.warnThrottle(mahalanobisWarningMessage(distance, params_.pose_gate_dist), 2000); warning_.warnThrottle("Ignore the measurement data.", 2000); return false; @@ -542,12 +542,12 @@ bool EKFLocalizer::measurementUpdateTwist( } delay_time = std::max(delay_time, 0.0); - int delay_step = std::roundf(delay_time / ekf_dt_); + const int delay_step = std::roundf(delay_time / ekf_dt_); - twist_delay_time_ = std::max(delay_time, twist_delay_time_); - twist_delay_time_threshold_ = params_.extend_state_step * ekf_dt_; + twist_diag_info_.delay_time = std::max(delay_time, twist_diag_info_.delay_time); + twist_diag_info_.delay_time_threshold = params_.extend_state_step * ekf_dt_; if (delay_step >= params_.extend_state_step) { - twist_is_passed_delay_gate_ = false; + twist_diag_info_.is_passed_delay_gate = false; warning_.warnThrottle( twistDelayStepWarningMessage(delay_time, params_.extend_state_step, ekf_dt_), 2000); return false; @@ -571,9 +571,9 @@ bool EKFLocalizer::measurementUpdateTwist( const Eigen::MatrixXd P_y = P_curr.block(4, 4, dim_y, dim_y); const double distance = mahalanobis(y_ekf, y, P_y); - twist_mahalanobis_distance_ = std::max(distance, twist_mahalanobis_distance_); + twist_diag_info_.mahalanobis_distance = std::max(distance, twist_diag_info_.mahalanobis_distance); if (distance > params_.twist_gate_dist) { - twist_is_passed_mahalanobis_gate_ = false; + twist_diag_info_.is_passed_mahalanobis_gate = false; warning_.warnThrottle(mahalanobisWarningMessage(distance, params_.twist_gate_dist), 2000); warning_.warnThrottle("Ignore the measurement data.", 2000); return false; @@ -660,23 +660,25 @@ void EKFLocalizer::publishDiagnostics() if (is_activated_) { diag_status_array.push_back(checkMeasurementUpdated( - "pose", pose_no_update_count_, params_.pose_no_update_count_threshold_warn, + "pose", pose_diag_info_.no_update_count, params_.pose_no_update_count_threshold_warn, params_.pose_no_update_count_threshold_error)); - diag_status_array.push_back(checkMeasurementQueueSize("pose", pose_queue_size_)); + diag_status_array.push_back(checkMeasurementQueueSize("pose", pose_diag_info_.queue_size)); diag_status_array.push_back(checkMeasurementDelayGate( - "pose", pose_is_passed_delay_gate_, pose_delay_time_, pose_delay_time_threshold_)); + "pose", pose_diag_info_.is_passed_delay_gate, pose_diag_info_.delay_time, + pose_diag_info_.delay_time_threshold)); diag_status_array.push_back(checkMeasurementMahalanobisGate( - "pose", pose_is_passed_mahalanobis_gate_, pose_mahalanobis_distance_, + "pose", pose_diag_info_.is_passed_mahalanobis_gate, pose_diag_info_.mahalanobis_distance, params_.pose_gate_dist)); diag_status_array.push_back(checkMeasurementUpdated( - "twist", twist_no_update_count_, params_.twist_no_update_count_threshold_warn, + "twist", twist_diag_info_.no_update_count, params_.twist_no_update_count_threshold_warn, params_.twist_no_update_count_threshold_error)); - diag_status_array.push_back(checkMeasurementQueueSize("twist", twist_queue_size_)); + diag_status_array.push_back(checkMeasurementQueueSize("twist", twist_diag_info_.queue_size)); diag_status_array.push_back(checkMeasurementDelayGate( - "twist", twist_is_passed_delay_gate_, twist_delay_time_, twist_delay_time_threshold_)); + "twist", twist_diag_info_.is_passed_delay_gate, twist_diag_info_.delay_time, + twist_diag_info_.delay_time_threshold)); diag_status_array.push_back(checkMeasurementMahalanobisGate( - "twist", twist_is_passed_mahalanobis_gate_, twist_mahalanobis_distance_, + "twist", twist_diag_info_.is_passed_mahalanobis_gate, twist_diag_info_.mahalanobis_distance, params_.twist_gate_dist)); } From 0af019ef4b3218122641e3cd883dffa7ebdf1a79 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Fri, 27 Oct 2023 16:38:20 +0900 Subject: [PATCH 086/202] fix(goal_planner): visualize stop wall (#5408) Signed-off-by: kosuke55 --- .../include/behavior_path_planner/utils/path_utils.hpp | 2 ++ .../scene_module/goal_planner/goal_planner_module.cpp | 2 ++ planning/behavior_path_planner/src/utils/path_utils.cpp | 9 +++++++++ 3 files changed, 13 insertions(+) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_utils.hpp index b42502d9edec8..a9cbf859dd9d8 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_utils.hpp @@ -104,6 +104,8 @@ PathWithLaneId calcCenterLinePath( const std::optional & prev_module_path = std::nullopt); PathWithLaneId combinePath(const PathWithLaneId & path1, const PathWithLaneId & path2); + +boost::optional getFirstStopPoseFromPath(const PathWithLaneId & path); } // namespace behavior_path_planner::utils #endif // BEHAVIOR_PATH_PLANNER__UTILS__PATH_UTILS_HPP_ diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index 32b54a4e39170..d6f80697d9fd6 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -775,6 +775,7 @@ void GoalPlannerModule::setStopPath(BehaviorModuleOutput & output) } else { // not_safe -> not_safe: use previous stop path output.path = status_.get_prev_stop_path(); + stop_pose_ = utils::getFirstStopPoseFromPath(*output.path); RCLCPP_WARN_THROTTLE( getLogger(), *clock_, 5000, "Not found safe pull_over path, use previous stop path"); } @@ -804,6 +805,7 @@ void GoalPlannerModule::setStopPathFromCurrentPath(BehaviorModuleOutput & output } else { // not_safe safe(no feasible stop path found) -> not_safe: use previous stop path output.path = status_.get_prev_stop_path_after_approval(); + stop_pose_ = utils::getFirstStopPoseFromPath(*output.path); RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 5000, "Collision detected, use previous stop path"); } output.reference_path = getPreviousModuleOutput().reference_path; diff --git a/planning/behavior_path_planner/src/utils/path_utils.cpp b/planning/behavior_path_planner/src/utils/path_utils.cpp index 3ac3c09ba0d97..a6d7bc0040c23 100644 --- a/planning/behavior_path_planner/src/utils/path_utils.cpp +++ b/planning/behavior_path_planner/src/utils/path_utils.cpp @@ -580,4 +580,13 @@ PathWithLaneId combinePath(const PathWithLaneId & path1, const PathWithLaneId & return filtered_path; } +boost::optional getFirstStopPoseFromPath(const PathWithLaneId & path) +{ + for (const auto & p : path.points) { + if (std::abs(p.point.longitudinal_velocity_mps) < 0.01) { + return p.point.pose; + } + } + return boost::none; +} } // namespace behavior_path_planner::utils From b97ea6e64ed4217edebdd9a2a970b5e386ef5bf6 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez <33620+esteve@users.noreply.github.com> Date: Fri, 27 Oct 2023 11:04:22 +0200 Subject: [PATCH 087/202] build(tracking_object_merger): remove no longer needed nlohmann_json dependency (#5429) Signed-off-by: Esteve Fernandez --- perception/tracking_object_merger/CMakeLists.txt | 2 -- .../data_association/data_association.hpp | 2 -- 2 files changed, 4 deletions(-) diff --git a/perception/tracking_object_merger/CMakeLists.txt b/perception/tracking_object_merger/CMakeLists.txt index 108749c5f91a7..ed5aa76afbfd9 100644 --- a/perception/tracking_object_merger/CMakeLists.txt +++ b/perception/tracking_object_merger/CMakeLists.txt @@ -7,7 +7,6 @@ endif() find_package(autoware_cmake REQUIRED) autoware_package() -find_package(nlohmann_json REQUIRED) # for debug # find dependencies @@ -36,7 +35,6 @@ ament_auto_add_library(decorative_tracker_merger_node SHARED target_link_libraries(decorative_tracker_merger_node mu_successive_shortest_path Eigen3::Eigen - nlohmann_json::nlohmann_json # for debug ) rclcpp_components_register_node(decorative_tracker_merger_node diff --git a/perception/tracking_object_merger/include/tracking_object_merger/data_association/data_association.hpp b/perception/tracking_object_merger/include/tracking_object_merger/data_association/data_association.hpp index 05fc9f6caccb5..a62a39d11c192 100644 --- a/perception/tracking_object_merger/include/tracking_object_merger/data_association/data_association.hpp +++ b/perception/tracking_object_merger/include/tracking_object_merger/data_association/data_association.hpp @@ -19,8 +19,6 @@ #ifndef TRACKING_OBJECT_MERGER__DATA_ASSOCIATION__DATA_ASSOCIATION_HPP_ #define TRACKING_OBJECT_MERGER__DATA_ASSOCIATION__DATA_ASSOCIATION_HPP_ -// #include // for debug json library - #include #include #include From 29d34df028a4e0fa7f3482e0f7243be206dfc18f Mon Sep 17 00:00:00 2001 From: takeshi-iwanari Date: Fri, 27 Oct 2023 18:21:54 +0900 Subject: [PATCH 088/202] fix(system_monitor): output command line (#5430) * fix(system_monitor): output command line Signed-off-by: takeshi.iwanari * style(pre-commit): autofix --------- Signed-off-by: takeshi.iwanari Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../process_monitor/process_monitor.hpp | 2 +- .../src/process_monitor/process_monitor.cpp | 18 +++++++++++++----- 2 files changed, 14 insertions(+), 6 deletions(-) diff --git a/system/system_monitor/include/system_monitor/process_monitor/process_monitor.hpp b/system/system_monitor/include/system_monitor/process_monitor/process_monitor.hpp index 42bd2a3ea9236..ec2a90c6b27e4 100644 --- a/system/system_monitor/include/system_monitor/process_monitor/process_monitor.hpp +++ b/system/system_monitor/include/system_monitor/process_monitor/process_monitor.hpp @@ -94,7 +94,7 @@ class ProcessMonitor : public rclcpp::Node * @param [out] command output command line * @return true if success to get command line name */ - bool getCommandLineFromPiD(const std::string & pid, std::string * command); + bool getCommandLineFromPiD(const std::string & pid, std::string & command); /** * @brief get top-rated processes diff --git a/system/system_monitor/src/process_monitor/process_monitor.cpp b/system/system_monitor/src/process_monitor/process_monitor.cpp index 6f58339f2ff4b..1173431b0f7c2 100644 --- a/system/system_monitor/src/process_monitor/process_monitor.cpp +++ b/system/system_monitor/src/process_monitor/process_monitor.cpp @@ -414,14 +414,22 @@ void ProcessMonitor::getHighMemoryProcesses(const std::string & output) getTopratedProcesses(&memory_tasks_, &p2); } -bool ProcessMonitor::getCommandLineFromPiD(const std::string & pid, std::string * command) +bool ProcessMonitor::getCommandLineFromPiD(const std::string & pid, std::string & command) { std::string commandLineFilePath = "/proc/" + pid + "/cmdline"; - std::ifstream commandFile(commandLineFilePath); + std::ifstream commandFile(commandLineFilePath, std::ios::in | std::ios::binary); + if (commandFile.is_open()) { - std::getline(commandFile, *command); + std::vector buffer; + std::copy( + std::istream_iterator(commandFile), std::istream_iterator(), + std::back_inserter(buffer)); commandFile.close(); - return true; + std::replace( + buffer.begin(), buffer.end(), '\0', + ' '); // 0x00 is used as delimiter in /cmdline instead of 0x20 (space) + command = std::string(buffer.begin(), buffer.end()); + return (buffer.size() > 0) ? true : false; // cmdline is empty if it is kernel process } else { return false; } @@ -478,7 +486,7 @@ void ProcessMonitor::getTopratedProcesses( std::string program_name; std::getline(stream, program_name); - bool flag_find_command_line = getCommandLineFromPiD(info.processId, &info.commandName); + bool flag_find_command_line = getCommandLineFromPiD(info.processId, info.commandName); if (!flag_find_command_line) { info.commandName = program_name; // if command line is not found, use program name instead From 25e8b3f5617de201db4f197be48615ff574b12f1 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Fri, 27 Oct 2023 18:25:37 +0900 Subject: [PATCH 089/202] refactor(goal_planner): rebuild state transition (#5371)" (#5399)" (#5417) * refactor(goal_planner): rebuild state transition (#5371)" (#5399)" This reverts commit 92f78a476d47bf0811cbb69315fd403be574224f. * fix: increment path idx Signed-off-by: kosuke55 * refactor Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 --- .../goal_planner/goal_planner_module.hpp | 31 +++++----- .../goal_planner/goal_planner_module.cpp | 61 ++++++------------- 2 files changed, 36 insertions(+), 56 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp index c5b2209c16f19..df21bad862cc9 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp @@ -135,10 +135,8 @@ class PullOverStatus DEFINE_SETTER_GETTER(bool, has_decided_velocity) DEFINE_SETTER_GETTER(bool, has_requested_approval) DEFINE_SETTER_GETTER(bool, is_ready) - DEFINE_SETTER_GETTER(std::shared_ptr, last_approved_time) DEFINE_SETTER_GETTER(std::shared_ptr, last_increment_time) DEFINE_SETTER_GETTER(std::shared_ptr, last_path_update_time) - DEFINE_SETTER_GETTER(std::shared_ptr, last_approved_pose) DEFINE_SETTER_GETTER(std::optional, modified_goal_pose) DEFINE_SETTER_GETTER(Pose, refined_goal_pose) DEFINE_SETTER_GETTER(GoalCandidates, goal_candidates) @@ -166,10 +164,8 @@ class PullOverStatus bool is_ready_{false}; // save last time and pose - std::shared_ptr last_approved_time_; std::shared_ptr last_increment_time_; std::shared_ptr last_path_update_time_; - std::shared_ptr last_approved_pose_; // goal modification std::optional modified_goal_pose_; @@ -199,6 +195,14 @@ struct GoalPlannerDebugData std::vector ego_polygons_expanded{}; }; +struct LastApprovalData +{ + LastApprovalData(rclcpp::Time time, Pose pose) : time(time), pose(pose) {} + + rclcpp::Time time{}; + Pose pose{}; +}; + class GoalPlannerModule : public SceneModuleInterface { public: @@ -219,14 +223,11 @@ class GoalPlannerModule : public SceneModuleInterface } } - // TODO(someone): remove this, and use base class function - [[deprecated]] BehaviorModuleOutput run() override; - bool isExecutionRequested() const override; - bool isExecutionReady() const override; - // TODO(someone): remove this, and use base class function - [[deprecated]] ModuleStatus updateState() override; + CandidateOutput planCandidate() const override; BehaviorModuleOutput plan() override; BehaviorModuleOutput planWaitingApproval() override; + bool isExecutionRequested() const override; + bool isExecutionReady() const override; void processOnExit() override; void updateData() override; void setParameters(const std::shared_ptr & parameters); @@ -235,15 +236,15 @@ class GoalPlannerModule : public SceneModuleInterface { } - // not used, but need to override - CandidateOutput planCandidate() const override { return CandidateOutput{}; }; - private: + // The start_planner activates when it receives a new route, + // so there is no need to terminate the goal planner. + // If terminating it, it may switch to lane following and could generate an inappropriate path. bool canTransitSuccessState() override { return false; } bool canTransitFailureState() override { return false; } - bool canTransitIdleToRunningState() override { return false; } + bool canTransitIdleToRunningState() override { return true; } mutable StartGoalPlannerData goal_planner_data_; @@ -276,6 +277,8 @@ class GoalPlannerModule : public SceneModuleInterface std::recursive_mutex mutex_; PullOverStatus status_; + std::unique_ptr last_approval_data_{nullptr}; + // approximate distance from the start point to the end point of pull_over. // this is used as an assumed value to decelerate, etc., before generating the actual path. const double approximate_pull_over_distance_{20.0}; diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index d6f80697d9fd6..8b6ac5394c3d4 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -227,18 +227,6 @@ void GoalPlannerModule::onFreespaceParkingTimer() } } -BehaviorModuleOutput GoalPlannerModule::run() -{ - current_state_ = ModuleStatus::RUNNING; - updateOccupancyGrid(); - - if (!isActivated()) { - return planWaitingApproval(); - } - - return plan(); -} - void GoalPlannerModule::updateData() { // Initialize Occupancy Grid Map @@ -287,6 +275,8 @@ void GoalPlannerModule::processOnExit() resetPathCandidate(); resetPathReference(); debug_marker_.markers.clear(); + status_.reset(); + last_approval_data_.reset(); } bool GoalPlannerModule::isExecutionRequested() const @@ -448,13 +438,6 @@ Pose GoalPlannerModule::calcRefinedGoal(const Pose & goal_pose) const return refined_goal_pose; } -ModuleStatus GoalPlannerModule::updateState() -{ - // start_planner module will be run when setting new goal, so not need finishing pull_over module. - // Finishing it causes wrong lane_following path generation. - return current_state_; -} - bool GoalPlannerModule::planFreespacePath() { goal_searcher_->setPlannerData(planner_data_); @@ -914,6 +897,12 @@ void GoalPlannerModule::decideVelocity() status_.set_has_decided_velocity(true); } +CandidateOutput GoalPlannerModule::planCandidate() const +{ + return CandidateOutput( + status_.get_pull_over_path() ? status_.get_pull_over_path()->getFullPath() : PathWithLaneId()); +} + BehaviorModuleOutput GoalPlannerModule::planWithGoalModification() { // if pull over path candidates generation is not finished, use previous module output @@ -931,14 +920,9 @@ BehaviorModuleOutput GoalPlannerModule::planWithGoalModification() // Use decided path if (status_.get_has_decided_path()) { - if (isActivated() && isWaitingApproval()) { - { - const std::lock_guard lock(mutex_); - status_.set_last_approved_time(std::make_shared(clock_->now())); - status_.set_last_approved_pose( - std::make_shared(planner_data_->self_odometry->pose.pose)); - } - clearWaitingApproval(); + if (isActivated() && !last_approval_data_) { + last_approval_data_ = + std::make_unique(clock_->now(), planner_data_->self_odometry->pose.pose); decideVelocity(); } transitionToNextPathIfFinishingCurrentPath(); @@ -954,7 +938,7 @@ BehaviorModuleOutput GoalPlannerModule::planWithGoalModification() // set output and status BehaviorModuleOutput output{}; setOutput(output); - path_candidate_ = std::make_shared(status_.get_pull_over_path()->getFullPath()); + path_candidate_ = std::make_shared(planCandidate().path_candidate); path_reference_ = getPreviousModuleOutput().reference_path; // return to lane parking if it is possible @@ -1005,16 +989,11 @@ BehaviorModuleOutput GoalPlannerModule::planWaitingApprovalWithGoalModification( return getPreviousModuleOutput(); } - waitApproval(); - BehaviorModuleOutput out; out.modified_goal = plan().modified_goal; // update status_ out.path = std::make_shared(generateStopPath()); out.reference_path = getPreviousModuleOutput().reference_path; - path_candidate_ = - status_.get_is_safe_static_objects() - ? std::make_shared(status_.get_pull_over_path()->getFullPath()) - : out.path; + path_candidate_ = std::make_shared(planCandidate().path_candidate); path_reference_ = getPreviousModuleOutput().reference_path; const auto distance_to_path_change = calcDistanceToPathChange(); @@ -1191,12 +1170,11 @@ PathWithLaneId GoalPlannerModule::generateFeasibleStopPath() void GoalPlannerModule::transitionToNextPathIfFinishingCurrentPath() { - if (isActivated() && status_.get_last_approved_time()) { + if (isActivated() && last_approval_data_) { // if using arc_path and finishing current_path, get next path // enough time for turn signal - const bool has_passed_enough_time = - (clock_->now() - *status_.get_last_approved_time()).seconds() > - planner_data_->parameters.turn_signal_search_time; + const bool has_passed_enough_time = (clock_->now() - last_approval_data_->time).seconds() > + planner_data_->parameters.turn_signal_search_time; if (hasFinishedCurrentPath() && has_passed_enough_time && status_.get_require_increment()) { if (incrementPathIndex()) { @@ -1331,10 +1309,9 @@ TurnSignalInfo GoalPlannerModule::calcTurnSignalInfo() const { // ego decelerates so that current pose is the point `turn_light_on_threshold_time` seconds // before starting pull_over - turn_signal.desired_start_point = - status_.get_last_approved_pose() && status_.get_has_decided_path() - ? *status_.get_last_approved_pose() - : current_pose; + turn_signal.desired_start_point = last_approval_data_ && status_.get_has_decided_path() + ? last_approval_data_->pose + : current_pose; turn_signal.desired_end_point = end_pose; turn_signal.required_start_point = start_pose; turn_signal.required_end_point = end_pose; From 124dcf41a83ece1c6f16b700867bd697040230f5 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Sat, 28 Oct 2023 16:00:55 +0900 Subject: [PATCH 090/202] fix(goal_planner): do not generate path candidates before execution (#5433) Signed-off-by: kosuke55 --- .../goal_planner/goal_planner_module.cpp | 17 ++++++++++++++++- 1 file changed, 16 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index 8b6ac5394c3d4..3c470cef2c935 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -146,6 +146,17 @@ void GoalPlannerModule::onTimer() if (status_.get_goal_candidates().empty()) { return; } + + if (!isExecutionRequested()) { + return; + } + + if ( + !planner_data_ || + !goal_planner_utils::isAllowedGoalModification(planner_data_->route_handler)) { + return; + } + const auto goal_candidates = status_.get_goal_candidates(); // generate valid pull over path candidates and calculate closest start pose @@ -229,6 +240,10 @@ void GoalPlannerModule::onFreespaceParkingTimer() void GoalPlannerModule::updateData() { + if (getCurrentStatus() == ModuleStatus::IDLE) { + return; + } + // Initialize Occupancy Grid Map // This operation requires waiting for `planner_data_`, hence it is executed here instead of in // the constructor. Ideally, this operation should only need to be performed once. @@ -990,7 +1005,7 @@ BehaviorModuleOutput GoalPlannerModule::planWaitingApprovalWithGoalModification( } BehaviorModuleOutput out; - out.modified_goal = plan().modified_goal; // update status_ + out.modified_goal = planWithGoalModification().modified_goal; // update status_ out.path = std::make_shared(generateStopPath()); out.reference_path = getPreviousModuleOutput().reference_path; path_candidate_ = std::make_shared(planCandidate().path_candidate); From 02b2be9081978c04544ee3cc0f308e5d2f459af0 Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Mon, 30 Oct 2023 01:37:47 +0900 Subject: [PATCH 091/202] fix(lane_change): separate backward buffer for blocking object (#5434) * fix(lane_change): separate backward buffer for blocking object Signed-off-by: Fumiya Watanabe * Update planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp Co-authored-by: Kosuke Takeuchi * style(pre-commit): autofix --------- Signed-off-by: Fumiya Watanabe Co-authored-by: Kosuke Takeuchi Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../config/lane_change/lane_change.param.yaml | 1 + .../behavior_path_planner/parameters.hpp | 1 + .../behavior_path_planner/utils/utils.hpp | 2 +- .../src/behavior_path_planner_node.cpp | 2 + .../scene_module/lane_change/interface.cpp | 4 +- .../src/scene_module/lane_change/normal.cpp | 39 ++++++++++++------- .../src/utils/lane_change/utils.cpp | 4 +- .../behavior_path_planner/src/utils/utils.cpp | 5 +-- 8 files changed, 35 insertions(+), 23 deletions(-) diff --git a/planning/behavior_path_planner/config/lane_change/lane_change.param.yaml b/planning/behavior_path_planner/config/lane_change/lane_change.param.yaml index d3c0a22e867f9..f98eac5315006 100644 --- a/planning/behavior_path_planner/config/lane_change/lane_change.param.yaml +++ b/planning/behavior_path_planner/config/lane_change/lane_change.param.yaml @@ -5,6 +5,7 @@ prepare_duration: 4.0 # [s] backward_length_buffer_for_end_of_lane: 3.0 # [m] + backward_length_buffer_for_blocking_object: 3.0 # [m] lane_change_finish_judge_buffer: 2.0 # [m] lane_changing_lateral_jerk: 0.5 # [m/s3] diff --git a/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp b/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp index a4e6fc18ab050..5dceeeff3aada 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp @@ -92,6 +92,7 @@ struct BehaviorPathPlannerParameters double backward_path_length; double forward_path_length; double backward_length_buffer_for_end_of_lane; + double backward_length_buffer_for_blocking_object; double backward_length_buffer_for_end_of_pull_over; double backward_length_buffer_for_end_of_pull_out; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp index 326a6aded5e88..38c2620096ca2 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp @@ -392,7 +392,7 @@ bool checkPathRelativeAngle(const PathWithLaneId & path, const double angle_thre double calcMinimumLaneChangeLength( const BehaviorPathPlannerParameters & common_param, const std::vector & shift_intervals, - const double length_to_intersection = 0.0); + const double backward_buffer, const double length_to_intersection = 0.0); lanelet::ConstLanelets getLaneletsFromPath( const PathWithLaneId & path, const std::shared_ptr & route_handler); diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index 0777822650dfb..bd46bf069e846 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -340,6 +340,8 @@ BehaviorPathPlannerParameters BehaviorPathPlannerNode::getCommonParam() // lane change parameters p.backward_length_buffer_for_end_of_lane = declare_parameter("lane_change.backward_length_buffer_for_end_of_lane"); + p.backward_length_buffer_for_blocking_object = + declare_parameter("lane_change.backward_length_buffer_for_blocking_object"); p.lane_changing_lateral_jerk = declare_parameter("lane_change.lane_changing_lateral_jerk"); p.lane_change_prepare_duration = declare_parameter("lane_change.prepare_duration"); diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp index 22c8ac022ad1a..be3b78803c4c6 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp @@ -453,8 +453,8 @@ TurnSignalInfo LaneChangeInterface::getCurrentTurnSignalInfo( const auto & common_parameter = module_type_->getCommonParam(); const auto shift_intervals = route_handler->getLateralIntervalsToPreferredLane(current_lanes.back()); - const double next_lane_change_buffer = - utils::calcMinimumLaneChangeLength(common_parameter, shift_intervals); + const double next_lane_change_buffer = utils::calcMinimumLaneChangeLength( + common_parameter, shift_intervals, common_parameter.backward_length_buffer_for_end_of_lane); const double & nearest_dist_threshold = common_parameter.ego_nearest_dist_threshold; const double & nearest_yaw_threshold = common_parameter.ego_nearest_yaw_threshold; const double & base_to_front = common_parameter.base_link2front; 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 d887b570b753a..58a8e7e181e35 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 @@ -200,8 +200,9 @@ void NormalLaneChange::insertStopPoint( } const auto shift_intervals = route_handler->getLateralIntervalsToPreferredLane(lanelets.back()); - const double lane_change_buffer = - utils::calcMinimumLaneChangeLength(getCommonParam(), shift_intervals, 0.0); + const double lane_change_buffer = utils::calcMinimumLaneChangeLength( + getCommonParam(), shift_intervals, getCommonParam().backward_length_buffer_for_end_of_lane, + 0.0); const auto getDistanceAlongLanelet = [&](const geometry_msgs::msg::Pose & target) { return utils::getSignedDistance(path.points.front().point.pose, target, lanelets); @@ -263,10 +264,14 @@ void NormalLaneChange::insertStopPoint( const auto rss_dist = calcRssDistance( 0.0, planner_data_->parameters.minimum_lane_changing_velocity, lane_change_parameters_->rss_params); + const double lane_change_buffer_for_blocking_object = utils::calcMinimumLaneChangeLength( + getCommonParam(), shift_intervals, + getCommonParam().backward_length_buffer_for_blocking_object, 0.0); - const auto stopping_distance_for_obj = distance_to_ego_lane_obj - lane_change_buffer - - stop_point_buffer - rss_dist - - getCommonParam().base_link2front; + const auto stopping_distance_for_obj = + distance_to_ego_lane_obj - lane_change_buffer_for_blocking_object - + getCommonParam().backward_length_buffer_for_blocking_object - rss_dist - + getCommonParam().base_link2front; // If the target lane in the lane change section is blocked by a stationary obstacle, there // is no reason for stopping with a lane change margin. Instead, stop right behind the @@ -461,8 +466,9 @@ bool NormalLaneChange::isNearEndOfCurrentLanes( const auto & current_pose = getEgoPose(); const auto shift_intervals = route_handler->getLateralIntervalsToPreferredLane(current_lanes.back()); - const auto lane_change_buffer = - utils::calcMinimumLaneChangeLength(planner_data_->parameters, shift_intervals); + const auto lane_change_buffer = utils::calcMinimumLaneChangeLength( + planner_data_->parameters, shift_intervals, + getCommonParam().backward_length_buffer_for_end_of_lane); auto distance_to_end = utils::getDistanceToEndOfLane(current_pose, current_lanes); @@ -989,8 +995,8 @@ bool NormalLaneChange::hasEnoughLength( const double lane_change_length = path.info.length.sum(); const auto shift_intervals = route_handler.getLateralIntervalsToPreferredLane(target_lanes.back(), direction); - double minimum_lane_change_length_to_preferred_lane = - utils::calcMinimumLaneChangeLength(common_parameters, shift_intervals); + double minimum_lane_change_length_to_preferred_lane = utils::calcMinimumLaneChangeLength( + common_parameters, shift_intervals, common_parameters.backward_length_buffer_for_end_of_lane); if (lane_change_length > utils::getDistanceToEndOfLane(current_pose, current_lanes)) { return false; @@ -1086,9 +1092,11 @@ bool NormalLaneChange::getLaneChangePaths( const auto is_goal_in_route = route_handler.isInGoalRouteSection(target_lanes.back()); const double lane_change_buffer = utils::calcMinimumLaneChangeLength( - common_parameters, route_handler.getLateralIntervalsToPreferredLane(current_lanes.back())); + common_parameters, route_handler.getLateralIntervalsToPreferredLane(current_lanes.back()), + common_parameters.backward_length_buffer_for_end_of_lane); const double next_lane_change_buffer = utils::calcMinimumLaneChangeLength( - common_parameters, route_handler.getLateralIntervalsToPreferredLane(target_lanes.back())); + common_parameters, route_handler.getLateralIntervalsToPreferredLane(target_lanes.back()), + common_parameters.backward_length_buffer_for_end_of_lane); const auto dist_to_end_of_current_lanes = utils::getDistanceToEndOfLane(getEgoPose(), current_lanes); @@ -1489,8 +1497,8 @@ bool NormalLaneChange::getAbortPath() const auto direction = getDirection(); const auto shift_intervals = route_handler->getLateralIntervalsToPreferredLane( selected_path.info.current_lanes.back(), direction); - const double minimum_lane_change_length = - utils::calcMinimumLaneChangeLength(common_param, shift_intervals); + const double minimum_lane_change_length = utils::calcMinimumLaneChangeLength( + common_param, shift_intervals, common_param.backward_length_buffer_for_end_of_lane); const auto & lane_changing_path = selected_path.path; const auto lane_changing_end_pose_idx = std::invoke([&]() { @@ -1743,8 +1751,9 @@ bool NormalLaneChange::isVehicleStuck( : utils::getDistanceToEndOfLane(getEgoPose(), current_lanes); const auto shift_intervals = route_handler->getLateralIntervalsToPreferredLane(current_lanes.back()); - const double lane_change_buffer = - utils::calcMinimumLaneChangeLength(getCommonParam(), shift_intervals, 0.0); + const double lane_change_buffer = utils::calcMinimumLaneChangeLength( + getCommonParam(), shift_intervals, getCommonParam().backward_length_buffer_for_end_of_lane, + 0.0); const double stop_point_buffer = getCommonParam().backward_length_buffer_for_end_of_lane; const double terminal_judge_buffer = lane_change_buffer + stop_point_buffer + 1.0; if (distance_to_terminal < terminal_judge_buffer) { diff --git a/planning/behavior_path_planner/src/utils/lane_change/utils.cpp b/planning/behavior_path_planner/src/utils/lane_change/utils.cpp index d5867c40824d2..fb2a96f1d5cbd 100644 --- a/planning/behavior_path_planner/src/utils/lane_change/utils.cpp +++ b/planning/behavior_path_planner/src/utils/lane_change/utils.cpp @@ -604,8 +604,8 @@ bool hasEnoughLengthToLaneChangeAfterAbort( { const auto shift_intervals = route_handler.getLateralIntervalsToPreferredLane(current_lanes.back(), direction); - const double minimum_lane_change_length = - utils::calcMinimumLaneChangeLength(common_param, shift_intervals); + const double minimum_lane_change_length = utils::calcMinimumLaneChangeLength( + common_param, shift_intervals, common_param.backward_length_buffer_for_end_of_lane); const auto abort_plus_lane_change_length = abort_return_dist + minimum_lane_change_length; if (abort_plus_lane_change_length > utils::getDistanceToEndOfLane(current_pose, current_lanes)) { return false; diff --git a/planning/behavior_path_planner/src/utils/utils.cpp b/planning/behavior_path_planner/src/utils/utils.cpp index 9737db21a31a5..3ab20e7f76718 100644 --- a/planning/behavior_path_planner/src/utils/utils.cpp +++ b/planning/behavior_path_planner/src/utils/utils.cpp @@ -3310,7 +3310,7 @@ bool checkPathRelativeAngle(const PathWithLaneId & path, const double angle_thre double calcMinimumLaneChangeLength( const BehaviorPathPlannerParameters & common_param, const std::vector & shift_intervals, - const double length_to_intersection) + const double backward_buffer, const double length_to_intersection) { if (shift_intervals.empty()) { return 0.0; @@ -3328,8 +3328,7 @@ double calcMinimumLaneChangeLength( PathShifter::calcShiftTimeFromJerk(shift_interval, lateral_jerk, max_lateral_acc); accumulated_length += vel * t + finish_judge_buffer; } - accumulated_length += - common_param.backward_length_buffer_for_end_of_lane * (shift_intervals.size() - 1.0); + accumulated_length += backward_buffer * (shift_intervals.size() - 1.0); return accumulated_length; } From 0c5abbd7d30d3bc6df7eabcd3d8b57a5739ae86a Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Mon, 30 Oct 2023 08:47:30 +0900 Subject: [PATCH 092/202] refactor(ar_tag_based_localizer): add test (#5425) * Added test to ar_tag_based_localizer Signed-off-by: Shintaro Sakoda * Fixed to follow clang-tidy Signed-off-by: Shintaro Sakoda * Renamed files Signed-off-by: Shintaro Sakoda * style(pre-commit): autofix * Added include Signed-off-by: Shintaro Sakoda --------- Signed-off-by: Shintaro Sakoda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../ar_tag_based_localizer/CMakeLists.txt | 17 ++++- ...er_core.cpp => ar_tag_based_localizer.cpp} | 9 +-- .../ar_tag_based_localizer.hpp} | 8 +-- ..._tag_based_localizer_node.cpp => main.cpp} | 2 +- .../ar_tag_based_localizer/test/test.cpp | 67 +++++++++++++++++++ 5 files changed, 92 insertions(+), 11 deletions(-) rename localization/landmark_based_localizer/ar_tag_based_localizer/src/{ar_tag_based_localizer_core.cpp => ar_tag_based_localizer.cpp} (98%) rename localization/landmark_based_localizer/ar_tag_based_localizer/{include/ar_tag_based_localizer/ar_tag_based_localizer_core.hpp => src/ar_tag_based_localizer.hpp} (95%) rename localization/landmark_based_localizer/ar_tag_based_localizer/src/{ar_tag_based_localizer_node.cpp => main.cpp} (97%) create mode 100644 localization/landmark_based_localizer/ar_tag_based_localizer/test/test.cpp diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/CMakeLists.txt b/localization/landmark_based_localizer/ar_tag_based_localizer/CMakeLists.txt index 15aecd1f8ded9..d625064b8f6cb 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/CMakeLists.txt +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/CMakeLists.txt @@ -15,8 +15,8 @@ ament_auto_find_build_dependencies() find_package(OpenCV REQUIRED) ament_auto_add_executable(ar_tag_based_localizer - src/ar_tag_based_localizer_node.cpp - src/ar_tag_based_localizer_core.cpp + src/main.cpp + src/ar_tag_based_localizer.cpp ) target_include_directories(ar_tag_based_localizer SYSTEM PUBLIC @@ -24,6 +24,19 @@ target_include_directories(ar_tag_based_localizer ) target_link_libraries(ar_tag_based_localizer ${OpenCV_LIBRARIES}) +if(BUILD_TESTING) + find_package(ament_cmake_gtest REQUIRED) + ament_auto_add_gtest(test_ar_tag_based_localizer + test/test.cpp + src/ar_tag_based_localizer.cpp + ) + target_include_directories(test_ar_tag_based_localizer + SYSTEM PUBLIC + ${OpenCV_INCLUDE_DIRS} + ) + target_link_libraries(test_ar_tag_based_localizer ${OpenCV_LIBRARIES}) +endif() + ament_auto_package( INSTALL_TO_SHARE launch diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer_core.cpp b/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp similarity index 98% rename from localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer_core.cpp rename to localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp index 0492e07875a17..73e7b8b7e3587 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer_core.cpp +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp @@ -42,7 +42,7 @@ or implied, of Rafael Muñoz Salinas. ********************************/ -#include "ar_tag_based_localizer/ar_tag_based_localizer_core.hpp" +#include "ar_tag_based_localizer.hpp" #include #include @@ -51,14 +51,15 @@ #include #include +#include #ifdef ROS_DISTRO_GALACTIC #include #else #include #endif -ArTagBasedLocalizer::ArTagBasedLocalizer() -: Node("ar_tag_based_localizer"), cam_info_received_(false) +ArTagBasedLocalizer::ArTagBasedLocalizer(const rclcpp::NodeOptions & options) +: Node("ar_tag_based_localizer", options), cam_info_received_(false) { } @@ -219,7 +220,7 @@ void ArTagBasedLocalizer::image_callback(const sensor_msgs::msg::Image::ConstSha image_pub_.publish(out_msg.toImageMsg()); } - const int detected_tags = markers.size(); + const int detected_tags = static_cast(markers.size()); diagnostic_msgs::msg::DiagnosticStatus diag_status; diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/include/ar_tag_based_localizer/ar_tag_based_localizer_core.hpp b/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.hpp similarity index 95% rename from localization/landmark_based_localizer/ar_tag_based_localizer/include/ar_tag_based_localizer/ar_tag_based_localizer_core.hpp rename to localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.hpp index facd02e2b9b7b..6bd66eead653f 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/include/ar_tag_based_localizer/ar_tag_based_localizer_core.hpp +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.hpp @@ -42,8 +42,8 @@ or implied, of Rafael Muñoz Salinas. ********************************/ -#ifndef AR_TAG_BASED_LOCALIZER__AR_TAG_BASED_LOCALIZER_CORE_HPP_ -#define AR_TAG_BASED_LOCALIZER__AR_TAG_BASED_LOCALIZER_CORE_HPP_ +#ifndef AR_TAG_BASED_LOCALIZER_HPP_ +#define AR_TAG_BASED_LOCALIZER_HPP_ #include "landmark_parser/landmark_parser_core.hpp" @@ -67,7 +67,7 @@ class ArTagBasedLocalizer : public rclcpp::Node { public: - ArTagBasedLocalizer(); + explicit ArTagBasedLocalizer(const rclcpp::NodeOptions & options = rclcpp::NodeOptions()); bool setup(); private: @@ -115,4 +115,4 @@ class ArTagBasedLocalizer : public rclcpp::Node std::map landmark_map_; }; -#endif // AR_TAG_BASED_LOCALIZER__AR_TAG_BASED_LOCALIZER_CORE_HPP_ +#endif // AR_TAG_BASED_LOCALIZER_HPP_ diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer_node.cpp b/localization/landmark_based_localizer/ar_tag_based_localizer/src/main.cpp similarity index 97% rename from localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer_node.cpp rename to localization/landmark_based_localizer/ar_tag_based_localizer/src/main.cpp index 92d2e35ee3c1b..cbcd57b4b222a 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer_node.cpp +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/src/main.cpp @@ -42,7 +42,7 @@ or implied, of Rafael Muñoz Salinas. ********************************/ -#include "ar_tag_based_localizer/ar_tag_based_localizer_core.hpp" +#include "ar_tag_based_localizer.hpp" int main(int argc, char ** argv) { diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/test/test.cpp b/localization/landmark_based_localizer/ar_tag_based_localizer/test/test.cpp new file mode 100644 index 0000000000000..6b302ee6bc862 --- /dev/null +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/test/test.cpp @@ -0,0 +1,67 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "../src/ar_tag_based_localizer.hpp" + +#include + +#include +#include + +#include +#include +#include + +class TestArTagBasedLocalizer : public ::testing::Test +{ +protected: + void SetUp() override + { + const std::string yaml_path = + "../../install/ar_tag_based_localizer/share/ar_tag_based_localizer/config/" + "ar_tag_based_localizer.param.yaml"; + + rcl_params_t * params_st = rcl_yaml_node_struct_init(rcl_get_default_allocator()); + if (!rcl_parse_yaml_file(yaml_path.c_str(), params_st)) { + std::cout << "Failed to parse yaml file" << std::endl; + return; + } + + const rclcpp::ParameterMap param_map = rclcpp::parameter_map_from(params_st, ""); + rclcpp::NodeOptions node_options; + for (const auto & param_pair : param_map) { + for (const auto & param : param_pair.second) { + node_options.parameter_overrides().push_back(param); + } + } + node_ = std::make_shared(node_options); + rcl_yaml_node_struct_fini(params_st); + } + + std::shared_ptr node_; +}; + +TEST_F(TestArTagBasedLocalizer, test_setup) // NOLINT +{ + EXPECT_TRUE(node_->setup()); +} + +int main(int argc, char ** argv) +{ + rclcpp::init(argc, argv); + ::testing::InitGoogleTest(&argc, argv); + int result = RUN_ALL_TESTS(); + rclcpp::shutdown(); + return result; +} From 65f0a71b75eb4ea438153e4e154c296502f058ab Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 30 Oct 2023 10:29:27 +0900 Subject: [PATCH 093/202] feat(behavior_path_planner): subscribe traffic light recognition result (#5436) feat(avoidance): use traffic light signal info Signed-off-by: satoshi-ota --- .../behavior_planning.launch.py | 4 +++ .../behavior_planning.launch.xml | 1 + .../config/behavior_path_planner.param.yaml | 1 + .../behavior_path_planner_node.hpp | 3 +++ .../behavior_path_planner/data_manager.hpp | 27 +++++++++++++++++++ .../behavior_path_planner/parameters.hpp | 1 + planning/behavior_path_planner/package.xml | 1 + .../src/behavior_path_planner_node.cpp | 16 +++++++++++ 8 files changed, 54 insertions(+) diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py index 62d4c5b7188ee..f535fe1184d74 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py @@ -84,6 +84,10 @@ def launch_setup(context, *args, **kwargs): "~/input/costmap", "/planning/scenario_planning/parking/costmap_generator/occupancy_grid", ), + ( + "~/input/traffic_signals", + "/perception/traffic_light_recognition/traffic_signals", + ), ("~/input/odometry", "/localization/kinematic_state"), ("~/input/accel", "/localization/acceleration"), ("~/input/scenario", "/planning/scenario_planning/scenario"), diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml index 4ff862c7852c6..8ffa682030a99 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml @@ -8,6 +8,7 @@ + diff --git a/planning/behavior_path_planner/config/behavior_path_planner.param.yaml b/planning/behavior_path_planner/config/behavior_path_planner.param.yaml index d333cbfd778cb..b4d323de45cde 100644 --- a/planning/behavior_path_planner/config/behavior_path_planner.param.yaml +++ b/planning/behavior_path_planner/config/behavior_path_planner.param.yaml @@ -2,6 +2,7 @@ ros__parameters: verbose: false max_iteration_num: 100 + traffic_light_signal_timeout: 1.0 planning_hz: 10.0 backward_path_length: 5.0 forward_path_length: 300.0 diff --git a/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp b/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp index 420a5a8aa6ee5..1a9b23be00a3f 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp @@ -58,6 +58,7 @@ using autoware_auto_planning_msgs::msg::Path; using autoware_auto_planning_msgs::msg::PathWithLaneId; using autoware_auto_vehicle_msgs::msg::HazardLightsCommand; using autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand; +using autoware_perception_msgs::msg::TrafficSignalArray; using autoware_planning_msgs::msg::LaneletRoute; using autoware_planning_msgs::msg::PoseWithUuidStamped; using nav_msgs::msg::OccupancyGrid; @@ -93,6 +94,7 @@ class BehaviorPathPlannerNode : public rclcpp::Node rclcpp::Subscription::SharedPtr perception_subscriber_; rclcpp::Subscription::SharedPtr occupancy_grid_subscriber_; rclcpp::Subscription::SharedPtr costmap_subscriber_; + rclcpp::Subscription::SharedPtr traffic_signals_subscriber_; rclcpp::Subscription::SharedPtr lateral_offset_subscriber_; rclcpp::Subscription::SharedPtr operation_mode_subscriber_; rclcpp::Publisher::SharedPtr path_publisher_; @@ -136,6 +138,7 @@ class BehaviorPathPlannerNode : public rclcpp::Node void onPerception(const PredictedObjects::ConstSharedPtr msg); void onOccupancyGrid(const OccupancyGrid::ConstSharedPtr msg); void onCostMap(const OccupancyGrid::ConstSharedPtr msg); + void onTrafficSignals(const TrafficSignalArray::ConstSharedPtr msg); void onMap(const HADMapBin::ConstSharedPtr map_msg); void onRoute(const LaneletRoute::ConstSharedPtr route_msg); void onOperationMode(const OperationModeState::ConstSharedPtr msg); diff --git a/planning/behavior_path_planner/include/behavior_path_planner/data_manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/data_manager.hpp index 9280a81e643ca..ca58144464731 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/data_manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/data_manager.hpp @@ -20,6 +20,7 @@ #include "behavior_path_planner/utils/drivable_area_expansion/parameters.hpp" #include "motion_utils/trajectory/trajectory.hpp" +#include #include #include @@ -28,6 +29,7 @@ #include #include #include +#include #include #include #include @@ -39,6 +41,7 @@ #include #include +#include #include #include #include @@ -51,6 +54,7 @@ using autoware_auto_perception_msgs::msg::PredictedObjects; using autoware_auto_planning_msgs::msg::PathWithLaneId; using autoware_auto_vehicle_msgs::msg::HazardLightsCommand; using autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand; +using autoware_perception_msgs::msg::TrafficSignal; using autoware_planning_msgs::msg::PoseWithUuidStamped; using geometry_msgs::msg::AccelWithCovarianceStamped; using geometry_msgs::msg::PoseStamped; @@ -59,8 +63,15 @@ using nav_msgs::msg::Odometry; using route_handler::RouteHandler; using tier4_planning_msgs::msg::LateralOffset; using PlanResult = PathWithLaneId::SharedPtr; +using lanelet::TrafficLight; using unique_identifier_msgs::msg::UUID; +struct TrafficSignalStamped +{ + builtin_interfaces::msg::Time stamp; + TrafficSignal signal; +}; + struct BoolStamped { explicit BoolStamped(bool in_data) : data(in_data) {} @@ -145,6 +156,7 @@ struct PlannerData std::optional prev_modified_goal{}; std::optional prev_route_id{}; std::shared_ptr route_handler{std::make_shared()}; + std::map traffic_light_id_map; BehaviorPathPlannerParameters parameters{}; drivable_area_expansion::DrivableAreaExpansionParameters drivable_area_expansion_parameters{}; @@ -162,6 +174,21 @@ struct PlannerData route_handler, path, turn_signal_info, current_pose, current_vel, parameters, debug_data); } + std::optional getTrafficSignal(const int id) const + { + if (traffic_light_id_map.count(id) == 0) { + return std::nullopt; + } + + const auto elapsed_time = + (rclcpp::Clock{RCL_ROS_TIME}.now() - traffic_light_id_map.at(id).stamp).seconds(); + if (elapsed_time > parameters.traffic_light_signal_timeout) { + return std::nullopt; + } + + return traffic_light_id_map.at(id); + } + template size_t findEgoIndex(const std::vector & points) const { diff --git a/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp b/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp index 5dceeeff3aada..1998e7b99dd65 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp @@ -77,6 +77,7 @@ struct BehaviorPathPlannerParameters { bool verbose; size_t max_iteration_num{100}; + double traffic_light_signal_timeout{1.0}; ModuleConfigParameters config_avoidance; ModuleConfigParameters config_avoidance_by_lc; diff --git a/planning/behavior_path_planner/package.xml b/planning/behavior_path_planner/package.xml index 24ee1056e5a47..95ad5f1efb9ac 100644 --- a/planning/behavior_path_planner/package.xml +++ b/planning/behavior_path_planner/package.xml @@ -46,6 +46,7 @@ autoware_auto_planning_msgs autoware_auto_tf2 autoware_auto_vehicle_msgs + autoware_perception_msgs behaviortree_cpp_v3 freespace_planning_algorithms geometry_msgs diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index bd46bf069e846..ef44bee663985 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -106,6 +106,10 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod costmap_subscriber_ = create_subscription( "~/input/costmap", 1, std::bind(&BehaviorPathPlannerNode::onCostMap, this, _1), createSubscriptionOptions(this)); + traffic_signals_subscriber_ = + this->create_subscription( + "~/input/traffic_signals", 1, std::bind(&BehaviorPathPlannerNode::onTrafficSignals, this, _1), + createSubscriptionOptions(this)); lateral_offset_subscriber_ = this->create_subscription( "~/input/lateral_offset", 1, std::bind(&BehaviorPathPlannerNode::onLateralOffset, this, _1), createSubscriptionOptions(this)); @@ -277,6 +281,7 @@ BehaviorPathPlannerParameters BehaviorPathPlannerNode::getCommonParam() p.verbose = declare_parameter("verbose"); p.max_iteration_num = declare_parameter("max_iteration_num"); + p.traffic_light_signal_timeout = declare_parameter("traffic_light_signal_timeout"); const auto get_scene_module_manager_param = [&](std::string && ns) { ModuleConfigParameters config; @@ -934,6 +939,17 @@ void BehaviorPathPlannerNode::onCostMap(const OccupancyGrid::ConstSharedPtr msg) const std::lock_guard lock(mutex_pd_); planner_data_->costmap = msg; } +void BehaviorPathPlannerNode::onTrafficSignals(const TrafficSignalArray::ConstSharedPtr msg) +{ + std::lock_guard lock(mutex_pd_); + + for (const auto & signal : msg->signals) { + TrafficSignalStamped traffic_signal; + traffic_signal.stamp = msg->stamp; + traffic_signal.signal = signal; + planner_data_->traffic_light_id_map[signal.traffic_signal_id] = traffic_signal; + } +} void BehaviorPathPlannerNode::onMap(const HADMapBin::ConstSharedPtr msg) { const std::lock_guard lock(mutex_map_); From 6632d79aa04841de805b442999882906b3f659b6 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Mon, 30 Oct 2023 12:18:02 +0900 Subject: [PATCH 094/202] feat(radar_object_tracker): tune radar object tracker node for untrustable radar input (#5409) * fix include file Signed-off-by: yoshiri * switchable trust/untrust input yaw and twist information via parameters Signed-off-by: yoshiri * Set measurement count threshold tunable Signed-off-by: yoshiri * enable to switch off acceleration estimation Signed-off-by: yoshiri * add constant turn rate tracker model Signed-off-by: yoshiri * tune default parameters Signed-off-by: yoshiri * set orientation unreliable when object is yaw input is not trusted Signed-off-by: yoshiri * set ekf parameter to static so that it reduces yaml loading function calls Signed-off-by: yoshiri * fix launch file to load tracking_config_directory as arguments Signed-off-by: yoshiri * update readme Signed-off-by: yoshiri --------- Signed-off-by: yoshiri --- .../radar_object_tracker/CMakeLists.txt | 1 + perception/radar_object_tracker/README.md | 11 +- .../config/data_association_matrix.param.yaml | 8 +- .../config/default_tracker.param.yaml | 14 +- .../config/radar_object_tracker.param.yaml | 9 +- .../constant_turn_rate_motion_tracker.yaml | 36 + .../tracking/linear_motion_tracker.yaml | 24 +- .../radar_object_tracker_node.hpp | 2 + .../constant_turn_rate_motion_tracker.hpp | 112 ++++ .../tracker/model/linear_motion_tracker.hpp | 23 +- .../radar_object_tracker/tracker/tracker.hpp | 1 + .../launch/radar_object_tracker.launch.xml | 4 +- .../radar_object_tracker_node.cpp | 8 +- .../constant_turn_rate_motion_tracker.cpp | 624 ++++++++++++++++++ .../tracker/model/linear_motion_tracker.cpp | 125 +++- 15 files changed, 931 insertions(+), 71 deletions(-) create mode 100644 perception/radar_object_tracker/config/tracking/constant_turn_rate_motion_tracker.yaml create mode 100644 perception/radar_object_tracker/include/radar_object_tracker/tracker/model/constant_turn_rate_motion_tracker.hpp create mode 100644 perception/radar_object_tracker/src/tracker/model/constant_turn_rate_motion_tracker.cpp diff --git a/perception/radar_object_tracker/CMakeLists.txt b/perception/radar_object_tracker/CMakeLists.txt index 424e2b2d2c13e..3e3afacadd00f 100644 --- a/perception/radar_object_tracker/CMakeLists.txt +++ b/perception/radar_object_tracker/CMakeLists.txt @@ -27,6 +27,7 @@ ament_auto_add_library(radar_object_tracker_node SHARED src/radar_object_tracker_node/radar_object_tracker_node.cpp src/tracker/model/tracker_base.cpp src/tracker/model/linear_motion_tracker.cpp + src/tracker/model/constant_turn_rate_motion_tracker.cpp src/utils/utils.cpp src/data_association/data_association.cpp ) diff --git a/perception/radar_object_tracker/README.md b/perception/radar_object_tracker/README.md index 739a4a745ff6c..395bc025c2821 100644 --- a/perception/radar_object_tracker/README.md +++ b/perception/radar_object_tracker/README.md @@ -46,7 +46,7 @@ See more details in the [models.md](models.md). | `publish_rate` | double | 10.0 | The rate at which to publish the output messages | | `world_frame_id` | string | "map" | The frame ID of the world coordinate system | | `enable_delay_compensation` | bool | false | Whether to enable delay compensation. If set to `true`, output topic is published by timer with `publish_rate`. | -| `tracking_config_directory` | string | "" | The directory containing the tracking configuration files | +| `tracking_config_directory` | string | "./config/tracking/" | The directory containing the tracking configuration files | | `enable_logging` | bool | false | Whether to enable logging | | `logging_file_path` | string | "/tmp/association_log.json" | The path to the file where logs should be written | | `tracker_lifetime` | double | 1.0 | The lifetime of the tracker in seconds | @@ -65,6 +65,15 @@ See more details in the [models.md](models.md). See more details in the [models.md](models.md). +### Tracker parameters + +Currently, this package supports the following trackers: + +- `linear_motion_tracker` +- `constant_turn_rate_motion_tracker` + +Default settings for each tracker are defined in the [./config/tracking/](./config/tracking/), and described in [models.md](models.md). + ## Assumptions / Known limits diff --git a/perception/radar_object_tracker/config/data_association_matrix.param.yaml b/perception/radar_object_tracker/config/data_association_matrix.param.yaml index 104d790d185db..69628414e67d4 100644 --- a/perception/radar_object_tracker/config/data_association_matrix.param.yaml +++ b/perception/radar_object_tracker/config/data_association_matrix.param.yaml @@ -14,10 +14,10 @@ max_dist_matrix: #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN [4.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, #UNKNOWN - 4.0, 4.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #CAR - 4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #TRUCK - 4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #BUS - 4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #TRAILER + 4.0, 8.0, 8.0, 8.0, 8.0, 1.0, 1.0, 1.0, #CAR + 4.0, 6.0, 8.0, 8.0, 8.0, 1.0, 1.0, 1.0, #TRUCK + 4.0, 6.0, 8.0, 8.0, 8.0, 1.0, 1.0, 1.0, #BUS + 4.0, 6.0, 8.0, 8.0, 8.0, 1.0, 1.0, 1.0, #TRAILER 3.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0, #MOTORBIKE 3.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0, #BICYCLE 2.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0] #PEDESTRIAN diff --git a/perception/radar_object_tracker/config/default_tracker.param.yaml b/perception/radar_object_tracker/config/default_tracker.param.yaml index 757125202d69b..6c26034860e1b 100644 --- a/perception/radar_object_tracker/config/default_tracker.param.yaml +++ b/perception/radar_object_tracker/config/default_tracker.param.yaml @@ -1,9 +1,9 @@ /**: ros__parameters: - car_tracker: "linear_motion_tracker" - truck_tracker: "linear_motion_tracker" - bus_tracker: "linear_motion_tracker" - trailer_tracker: "linear_motion_tracker" - pedestrian_tracker: "linear_motion_tracker" - bicycle_tracker: "linear_motion_tracker" - motorcycle_tracker: "linear_motion_tracker" + car_tracker: "constant_turn_rate_motion_tracker" + truck_tracker: "constant_turn_rate_motion_tracker" + bus_tracker: "constant_turn_rate_motion_tracker" + trailer_tracker: "constant_turn_rate_motion_tracker" + pedestrian_tracker: "constant_turn_rate_motion_tracker" + bicycle_tracker: "constant_turn_rate_motion_tracker" + motorcycle_tracker: "constant_turn_rate_motion_tracker" diff --git a/perception/radar_object_tracker/config/radar_object_tracker.param.yaml b/perception/radar_object_tracker/config/radar_object_tracker.param.yaml index f80adffb41090..d2c0841cf372e 100644 --- a/perception/radar_object_tracker/config/radar_object_tracker.param.yaml +++ b/perception/radar_object_tracker/config/radar_object_tracker.param.yaml @@ -4,12 +4,11 @@ # basic settings world_frame_id: "map" tracker_lifetime: 1.0 # [sec] - # if empty, use default config declared in this package - tracking_config_directory: "" + measurement_count_threshold: 3 # object will be published if it is tracked more than this threshold # delay compensate parameters publish_rate: 10.0 - enable_delay_compensation: false + enable_delay_compensation: true # logging enable_logging: false @@ -18,10 +17,10 @@ # filtering ## 1. distance based filtering: remove closer objects than this threshold use_distance_based_noise_filtering: true - minimum_range_threshold: 70.0 # [m] + minimum_range_threshold: 60.0 # [m] ## 2. lanelet map based filtering use_map_based_noise_filtering: true max_distance_from_lane: 5.0 # [m] max_angle_diff_from_lane: 0.785398 # [rad] (45 deg) - max_lateral_velocity: 5.0 # [m/s] + max_lateral_velocity: 7.0 # [m/s] diff --git a/perception/radar_object_tracker/config/tracking/constant_turn_rate_motion_tracker.yaml b/perception/radar_object_tracker/config/tracking/constant_turn_rate_motion_tracker.yaml new file mode 100644 index 0000000000000..f80f881cabf03 --- /dev/null +++ b/perception/radar_object_tracker/config/tracking/constant_turn_rate_motion_tracker.yaml @@ -0,0 +1,36 @@ +default: + # This file defines the parameters for the linear motion tracker. + # All this parameter coordinate is assumed to be in the vehicle coordinate system. + # So, the x axis is pointing to the front of the vehicle, y axis is pointing to the left of the vehicle. + ekf_params: + # random walk noise is used to model the acceleration noise + process_noise_std: # [m/s^2] + x: 0.5 + y: 0.5 + yaw: 0.1 + vx: 1.0 # assume 1m/s velocity noise + wz: 0.4 + measurement_noise_std: + x: 4.0 # [m] + y: 4.0 # [m] + # y: 0.02 # rad/m if use_polar_coordinate_in_measurement_noise is true + yaw: 0.2 # [rad] + vx: 10 # [m/s] + initial_covariance_std: + x: 3.0 # [m] + y: 6.0 # [m] + yaw: 10.0 # [rad] + vx: 100.0 # [m/s] + wz: 10.0 # [rad/s] + # input flag + trust_yaw_input: false # set true if yaw input of sensor is reliable + trust_twist_input: false # set true if twist input of sensor is reliable + use_polar_coordinate_in_measurement_noise: false # set true if you want to define the measurement noise in polar coordinate + assume_zero_yaw_rate: false # set true if you want to assume zero yaw rate + # output limitation + limit: + max_speed: 80.0 # [m/s] + # low pass filter is used to smooth the yaw and shape estimation + low_pass_filter: + time_constant: 1.0 # [s] + sampling_time: 0.1 # [s] diff --git a/perception/radar_object_tracker/config/tracking/linear_motion_tracker.yaml b/perception/radar_object_tracker/config/tracking/linear_motion_tracker.yaml index 71367f4575193..5e813558a2bff 100644 --- a/perception/radar_object_tracker/config/tracking/linear_motion_tracker.yaml +++ b/perception/radar_object_tracker/config/tracking/linear_motion_tracker.yaml @@ -7,22 +7,28 @@ default: process_noise_std: # [m/s^2] ax: 0.98 # assume 0.1G acceleration noise ay: 0.98 - vx: 0.1 # assume 0.1m/s velocity noise - vy: 0.1 + vx: 1.0 # assume 1m/s velocity noise + vy: 1.0 x: 1.0 # assume 1m position noise y: 1.0 measurement_noise_std: x: 0.6 # [m] - y: 0.9 # [m] - vx: 0.4 # [m/s] - vy: 1 # [m/s] + # y: 4.0 # [m] + y: 0.01 # rad/m if use_polar_coordinate_in_measurement_noise is true + vx: 10 # [m/s] + vy: 100 # [m/s] initial_covariance_std: x: 3.0 # [m] y: 6.0 # [m] - vx: 1.0 # [m/s] - vy: 5.0 # [m/s] - ax: 0.5 # [m/s^2] - ay: 1.0 # [m/s^2] + vx: 1000.0 # [m/s] + vy: 1000.0 # [m/s] + ax: 1000.0 # [m/s^2] + ay: 1000.0 # [m/s^2] + estimate_acc: false # set true if you want to estimate the acceleration + # input flag + trust_yaw_input: false # set true if yaw input of sensor is reliable + trust_twist_input: false # set true if twist input of sensor is reliable + use_polar_coordinate_in_measurement_noise: true # set true if you want to define the measurement noise in polar coordinate # output limitation limit: max_speed: 80.0 # [m/s] diff --git a/perception/radar_object_tracker/include/radar_object_tracker/radar_object_tracker_node/radar_object_tracker_node.hpp b/perception/radar_object_tracker/include/radar_object_tracker/radar_object_tracker_node/radar_object_tracker_node.hpp index 415ff24b34cc3..9a3fdf602a3ca 100644 --- a/perception/radar_object_tracker/include/radar_object_tracker/radar_object_tracker_node/radar_object_tracker_node.hpp +++ b/perception/radar_object_tracker/include/radar_object_tracker/radar_object_tracker_node/radar_object_tracker_node.hpp @@ -76,6 +76,8 @@ class RadarObjectTrackerNode : public rclcpp::Node float tracker_lifetime_; std::map tracker_map_; + int measurement_count_threshold_; + void onMeasurement( const autoware_auto_perception_msgs::msg::DetectedObjects::ConstSharedPtr input_objects_msg); void onTimer(); diff --git a/perception/radar_object_tracker/include/radar_object_tracker/tracker/model/constant_turn_rate_motion_tracker.hpp b/perception/radar_object_tracker/include/radar_object_tracker/tracker/model/constant_turn_rate_motion_tracker.hpp new file mode 100644 index 0000000000000..ac4b2cd1a0acb --- /dev/null +++ b/perception/radar_object_tracker/include/radar_object_tracker/tracker/model/constant_turn_rate_motion_tracker.hpp @@ -0,0 +1,112 @@ +// Copyright 2020 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef RADAR_OBJECT_TRACKER__TRACKER__MODEL__CONSTANT_TURN_RATE_MOTION_TRACKER_HPP_ +#define RADAR_OBJECT_TRACKER__TRACKER__MODEL__CONSTANT_TURN_RATE_MOTION_TRACKER_HPP_ + +#include "radar_object_tracker/tracker/model/tracker_base.hpp" + +#include + +#include + +using Label = autoware_auto_perception_msgs::msg::ObjectClassification; +class ConstantTurnRateMotionTracker : public Tracker // means constant turn rate motion tracker +{ +private: + autoware_auto_perception_msgs::msg::DetectedObject object_; + rclcpp::Logger logger_; + +private: + KalmanFilter ekf_; + rclcpp::Time last_update_time_; + enum IDX { X = 0, Y = 1, YAW = 2, VX = 3, WZ = 4 }; + + struct EkfParams + { + // dimension + char dim_x = 5; + // system noise + double q_cov_x; + double q_cov_y; + double q_cov_yaw; + double q_cov_vx; + double q_cov_wz; + // measurement noise + double r_cov_x; + double r_cov_y; + double r_cov_yaw; + double r_cov_vx; + // initial state covariance + double p0_cov_x; + double p0_cov_y; + double p0_cov_yaw; + double p0_cov_vx; + double p0_cov_wz; + }; + static EkfParams ekf_params_; + + // limitation + static double max_vx_; + // rough tracking parameters + float z_; + + // lpf parameter + static double filter_tau_; // time constant of 1st order low pass filter + static double filter_dt_; // sampling time of 1st order low pass filter + + // static flags + static bool is_initialized_; + static bool trust_yaw_input_; + static bool trust_twist_input_; + static bool use_polar_coordinate_in_measurement_noise_; + static bool assume_zero_yaw_rate_; + +private: + struct BoundingBox + { + double length; + double width; + double height; + }; + struct Cylinder + { + double width; + double height; + }; + BoundingBox bounding_box_; + Cylinder cylinder_; + +public: + ConstantTurnRateMotionTracker( + const rclcpp::Time & time, const autoware_auto_perception_msgs::msg::DetectedObject & object, + const std::string & tracker_param_file, const std::uint8_t & label); + + static void loadDefaultModelParameters(const std::string & path); + bool predict(const rclcpp::Time & time) override; + bool predict(const double dt, KalmanFilter & ekf) const; + bool measure( + const autoware_auto_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time, + const geometry_msgs::msg::Transform & self_transform) override; + bool measureWithPose( + const autoware_auto_perception_msgs::msg::DetectedObject & object, + const geometry_msgs::msg::Transform & self_transform); + bool measureWithShape(const autoware_auto_perception_msgs::msg::DetectedObject & object); + bool getTrackedObject( + const rclcpp::Time & time, + autoware_auto_perception_msgs::msg::TrackedObject & object) const override; + virtual ~ConstantTurnRateMotionTracker() {} +}; + +#endif // RADAR_OBJECT_TRACKER__TRACKER__MODEL__CONSTANT_TURN_RATE_MOTION_TRACKER_HPP_ diff --git a/perception/radar_object_tracker/include/radar_object_tracker/tracker/model/linear_motion_tracker.hpp b/perception/radar_object_tracker/include/radar_object_tracker/tracker/model/linear_motion_tracker.hpp index 108e79c043ba0..77caa7a266481 100644 --- a/perception/radar_object_tracker/include/radar_object_tracker/tracker/model/linear_motion_tracker.hpp +++ b/perception/radar_object_tracker/include/radar_object_tracker/tracker/model/linear_motion_tracker.hpp @@ -56,18 +56,25 @@ class LinearMotionTracker : public Tracker double p0_cov_vy; double p0_cov_ax; double p0_cov_ay; - } ekf_params_; + }; + static EkfParams ekf_params_; // limitation - double max_vx_; - double max_vy_; + static double max_vx_; + static double max_vy_; // rough tracking parameters float z_; float yaw_; // lpf parameter - double filter_tau_; // time constant of 1st order low pass filter - double filter_dt_; // sampling time of 1st order low pass filter + static double filter_tau_; // time constant of 1st order low pass filter + static double filter_dt_; // sampling time of 1st order low pass filter + + static bool is_initialized_; + static bool estimate_acc_; + static bool trust_yaw_input_; + static bool trust_twist_input_; + static bool use_polar_coordinate_in_measurement_noise_; private: struct BoundingBox @@ -89,13 +96,15 @@ class LinearMotionTracker : public Tracker const rclcpp::Time & time, const autoware_auto_perception_msgs::msg::DetectedObject & object, const std::string & tracker_param_file, const std::uint8_t & label); - void loadDefaultModelParameters(const std::string & path); + static void loadDefaultModelParameters(const std::string & path); bool predict(const rclcpp::Time & time) override; bool predict(const double dt, KalmanFilter & ekf) const; bool measure( const autoware_auto_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time, const geometry_msgs::msg::Transform & self_transform) override; - bool measureWithPose(const autoware_auto_perception_msgs::msg::DetectedObject & object); + bool measureWithPose( + const autoware_auto_perception_msgs::msg::DetectedObject & object, + const geometry_msgs::msg::Transform & self_transform); bool measureWithShape(const autoware_auto_perception_msgs::msg::DetectedObject & object); bool getTrackedObject( const rclcpp::Time & time, diff --git a/perception/radar_object_tracker/include/radar_object_tracker/tracker/tracker.hpp b/perception/radar_object_tracker/include/radar_object_tracker/tracker/tracker.hpp index 7da940912a253..70045e6b16a07 100644 --- a/perception/radar_object_tracker/include/radar_object_tracker/tracker/tracker.hpp +++ b/perception/radar_object_tracker/include/radar_object_tracker/tracker/tracker.hpp @@ -15,6 +15,7 @@ #ifndef RADAR_OBJECT_TRACKER__TRACKER__TRACKER_HPP_ #define RADAR_OBJECT_TRACKER__TRACKER__TRACKER_HPP_ +#include "model/constant_turn_rate_motion_tracker.hpp" #include "model/linear_motion_tracker.hpp" #include "model/tracker_base.hpp" diff --git a/perception/radar_object_tracker/launch/radar_object_tracker.launch.xml b/perception/radar_object_tracker/launch/radar_object_tracker.launch.xml index e2d30c1b69d19..6e6813d3e40ff 100644 --- a/perception/radar_object_tracker/launch/radar_object_tracker.launch.xml +++ b/perception/radar_object_tracker/launch/radar_object_tracker.launch.xml @@ -4,8 +4,9 @@ - + + @@ -17,6 +18,7 @@ + diff --git a/perception/radar_object_tracker/src/radar_object_tracker_node/radar_object_tracker_node.cpp b/perception/radar_object_tracker/src/radar_object_tracker_node/radar_object_tracker_node.cpp index 6b02836e1f933..6d801302ab6c5 100644 --- a/perception/radar_object_tracker/src/radar_object_tracker_node/radar_object_tracker_node.cpp +++ b/perception/radar_object_tracker/src/radar_object_tracker_node/radar_object_tracker_node.cpp @@ -207,6 +207,7 @@ RadarObjectTrackerNode::RadarObjectTrackerNode(const rclcpp::NodeOptions & node_ // Parameters tracker_lifetime_ = declare_parameter("tracker_lifetime"); double publish_rate = declare_parameter("publish_rate"); + measurement_count_threshold_ = declare_parameter("measurement_count_threshold"); world_frame_id_ = declare_parameter("world_frame_id"); bool enable_delay_compensation{declare_parameter("enable_delay_compensation")}; tracker_config_directory_ = declare_parameter("tracking_config_directory"); @@ -363,6 +364,10 @@ std::shared_ptr RadarObjectTrackerNode::createNewTracker( if (tracker == "linear_motion_tracker") { std::string config_file = tracker_config_directory_ + "linear_motion_tracker.yaml"; return std::make_shared(time, object, config_file, label); + } else if (tracker == "constant_turn_rate_motion_tracker") { + std::string config_file = + tracker_config_directory_ + "constant_turn_rate_motion_tracker.yaml"; + return std::make_shared(time, object, config_file, label); } else { // not implemented yet so put warning RCLCPP_WARN(get_logger(), "Tracker %s is not implemented yet", tracker.c_str()); @@ -530,8 +535,7 @@ void RadarObjectTrackerNode::sanitizeTracker( inline bool RadarObjectTrackerNode::shouldTrackerPublish( const std::shared_ptr tracker) const { - constexpr int measurement_count_threshold = 3; - if (tracker->getTotalMeasurementCount() < measurement_count_threshold) { + if (tracker->getTotalMeasurementCount() < measurement_count_threshold_) { return false; } return true; diff --git a/perception/radar_object_tracker/src/tracker/model/constant_turn_rate_motion_tracker.cpp b/perception/radar_object_tracker/src/tracker/model/constant_turn_rate_motion_tracker.cpp new file mode 100644 index 0000000000000..5815fe34a68a9 --- /dev/null +++ b/perception/radar_object_tracker/src/tracker/model/constant_turn_rate_motion_tracker.cpp @@ -0,0 +1,624 @@ +// Copyright 2020 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. +// +// +// Author: v1.0 Yukihiro Saito +// + +#include "radar_object_tracker/tracker/model/constant_turn_rate_motion_tracker.hpp" + +#include "radar_object_tracker/utils/utils.hpp" + +#include +#include + +#include +#include +#include +#include + +#ifdef ROS_DISTRO_GALACTIC +#include +#else +#include +#endif + +#define EIGEN_MPL2_ONLY +#include +#include +#include +#include + +#include + +using Label = autoware_auto_perception_msgs::msg::ObjectClassification; + +// init static member variables +bool ConstantTurnRateMotionTracker::is_initialized_ = false; +ConstantTurnRateMotionTracker::EkfParams ConstantTurnRateMotionTracker::ekf_params_; +double ConstantTurnRateMotionTracker::max_vx_; +double ConstantTurnRateMotionTracker::filter_tau_; +double ConstantTurnRateMotionTracker::filter_dt_; +bool ConstantTurnRateMotionTracker::assume_zero_yaw_rate_; +bool ConstantTurnRateMotionTracker::trust_yaw_input_; +bool ConstantTurnRateMotionTracker::trust_twist_input_; +bool ConstantTurnRateMotionTracker::use_polar_coordinate_in_measurement_noise_; + +ConstantTurnRateMotionTracker::ConstantTurnRateMotionTracker( + const rclcpp::Time & time, const autoware_auto_perception_msgs::msg::DetectedObject & object, + const std::string & tracker_param_file, const std::uint8_t & /*label*/) +: Tracker(time, object.classification), + logger_(rclcpp::get_logger("ConstantTurnRateMotionTracker")), + last_update_time_(time), + z_(object.kinematics.pose_with_covariance.pose.position.z) +{ + object_ = object; + + // load setting from yaml file + if (!is_initialized_) { + loadDefaultModelParameters(tracker_param_file); // currently not using label + is_initialized_ = true; + } + + // shape initialization + bounding_box_ = {0.5, 0.5, 1.7}; + cylinder_ = {0.3, 1.7}; + + // initialize X matrix and position + Eigen::MatrixXd X(ekf_params_.dim_x, 1); + X(IDX::X) = object.kinematics.pose_with_covariance.pose.position.x; + X(IDX::Y) = object.kinematics.pose_with_covariance.pose.position.y; + const auto yaw = tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation); + z_ = object.kinematics.pose_with_covariance.pose.position.z; + X(IDX::YAW) = yaw; + // radar object usually have twist + if (object.kinematics.has_twist) { + const auto v = object.kinematics.twist_with_covariance.twist.linear.x; + X(IDX::VX) = v; + } else { + X(IDX::VX) = 0.0; + } + // init turn rate + X(IDX::WZ) = 0.0; + + // initialize P matrix + Eigen::MatrixXd P = Eigen::MatrixXd::Zero(ekf_params_.dim_x, ekf_params_.dim_x); + + // create rotation matrix to rotate covariance matrix + const double cos_yaw = std::cos(yaw); + const double sin_yaw = std::sin(yaw); + // 2d rotation matrix + Eigen::Matrix2d R; + R << cos_yaw, -sin_yaw, sin_yaw, cos_yaw; + + // covariance matrix in the target vehicle coordinate system + Eigen::Matrix2d P_xy_local; + P_xy_local << ekf_params_.p0_cov_x, 0.0, 0.0, ekf_params_.p0_cov_y; + + // Rotated covariance matrix + // covariance is rotated by 2D rotation matrix R + // P′=R P RT + Eigen::Matrix2d P_xy, P_v_xy; + + // Rotate the covariance matrix according to the vehicle yaw + // because p0_cov_x and y are in the vehicle coordinate system. + if (object.kinematics.has_position_covariance) { + P_xy_local << object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_X], + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_Y], + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_X], + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_Y]; + P_xy = R * P_xy_local * R.transpose(); + } else { + // rotate + P_xy = R * P_xy_local * R.transpose(); + } + // put value in P matrix + P.block<2, 2>(IDX::X, IDX::X) = P_xy; + + // covariance often written in object frame + if (object.kinematics.has_twist_covariance) { + const auto vx_cov = object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::X_X]; + // const auto vy_cov = + // object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::Y_Y]; + P(IDX::VX, IDX::VX) = vx_cov; + } else { + P(IDX::VX, IDX::VX) = ekf_params_.p0_cov_vx; + } + + P(IDX::YAW, IDX::YAW) = ekf_params_.p0_cov_yaw; + P(IDX::WZ, IDX::WZ) = ekf_params_.p0_cov_wz; + + // init shape + if (object.shape.type == autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX) { + bounding_box_ = { + object.shape.dimensions.x, object.shape.dimensions.y, object.shape.dimensions.z}; + } else if (object.shape.type == autoware_auto_perception_msgs::msg::Shape::CYLINDER) { + cylinder_ = {object.shape.dimensions.x, object.shape.dimensions.z}; + } + + ekf_.init(X, P); +} + +void ConstantTurnRateMotionTracker::loadDefaultModelParameters(const std::string & path) +{ + YAML::Node config = YAML::LoadFile(path); + // initialize ekf params + const float q_stddev_x = + config["default"]["ekf_params"]["process_noise_std"]["x"].as(); // [m] + const float q_stddev_y = + config["default"]["ekf_params"]["process_noise_std"]["y"].as(); // [m] + const float q_stddev_yaw = + config["default"]["ekf_params"]["process_noise_std"]["yaw"].as(); // [rad] + const float q_stddev_vx = + config["default"]["ekf_params"]["process_noise_std"]["vx"].as(); // [m/s] + const float q_stddev_wz = + config["default"]["ekf_params"]["process_noise_std"]["wz"].as(); // [m/s] + const float r_stddev_x = + config["default"]["ekf_params"]["measurement_noise_std"]["x"].as(); // [m] + const float r_stddev_y = + config["default"]["ekf_params"]["measurement_noise_std"]["y"].as(); // [m] + const float r_stddev_yaw = + config["default"]["ekf_params"]["measurement_noise_std"]["yaw"].as(); // [rad] + const float r_stddev_vx = + config["default"]["ekf_params"]["measurement_noise_std"]["vx"].as(); // [m/s] + const float p0_stddev_x = + config["default"]["ekf_params"]["initial_covariance_std"]["x"].as(); // [m/s] + const float p0_stddev_y = + config["default"]["ekf_params"]["initial_covariance_std"]["y"].as(); // [m/s] + const float p0_stddev_yaw = + config["default"]["ekf_params"]["initial_covariance_std"]["yaw"].as(); // [rad] + const float p0_stddev_vx = + config["default"]["ekf_params"]["initial_covariance_std"]["vx"].as(); // [m/(s)] + const float p0_stddev_wz = + config["default"]["ekf_params"]["initial_covariance_std"]["wz"].as(); // [rad/s] + assume_zero_yaw_rate_ = config["default"]["assume_zero_yaw_rate"].as(); // default false + trust_yaw_input_ = config["default"]["trust_yaw_input"].as(); // default false + trust_twist_input_ = config["default"]["trust_twist_input"].as(); // default false + use_polar_coordinate_in_measurement_noise_ = + config["default"]["use_polar_coordinate_in_measurement_noise"].as(); // default false + ekf_params_.q_cov_x = std::pow(q_stddev_x, 2.0); + ekf_params_.q_cov_y = std::pow(q_stddev_y, 2.0); + ekf_params_.q_cov_yaw = std::pow(q_stddev_yaw, 2.0); + ekf_params_.q_cov_vx = std::pow(q_stddev_vx, 2.0); + ekf_params_.q_cov_wz = std::pow(q_stddev_wz, 2.0); + ekf_params_.r_cov_x = std::pow(r_stddev_x, 2.0); + ekf_params_.r_cov_y = std::pow(r_stddev_y, 2.0); + ekf_params_.r_cov_yaw = std::pow(r_stddev_yaw, 2.0); + ekf_params_.r_cov_vx = std::pow(r_stddev_vx, 2.0); + ekf_params_.p0_cov_x = std::pow(p0_stddev_x, 2.0); + ekf_params_.p0_cov_y = std::pow(p0_stddev_y, 2.0); + ekf_params_.p0_cov_yaw = std::pow(p0_stddev_yaw, 2.0); + ekf_params_.p0_cov_vx = std::pow(p0_stddev_vx, 2.0); + ekf_params_.p0_cov_wz = std::pow(p0_stddev_wz, 2.0); + + // lpf filter parameters + filter_tau_ = config["default"]["low_pass_filter"]["time_constant"].as(); // [s] + filter_dt_ = config["default"]["low_pass_filter"]["sampling_time"].as(); // [s] + + // limitation + // (TODO): this may be written in another yaml file based on classify result + const float max_speed_kmph = config["default"]["limit"]["max_speed"].as(); // [km/h] + max_vx_ = tier4_autoware_utils::kmph2mps(max_speed_kmph); // [m/s] +} + +bool ConstantTurnRateMotionTracker::predict(const rclcpp::Time & time) +{ + const double dt = (time - last_update_time_).seconds(); + bool ret = predict(dt, ekf_); + if (ret) { + last_update_time_ = time; + } + return ret; +} + +bool ConstantTurnRateMotionTracker::predict(const double dt, KalmanFilter & ekf) const +{ + /* == Nonlinear model == + * + * x_{k+1} = x_k + vx_k * cos(yaw_k) * dt + * y_{k+1} = y_k + vx_k * sin(yaw_k) * dt + * yaw_{k+1} = yaw_k + (wz_k) * dt + * vx_{k+1} = vx_k + * wz_{k+1} = wz_k + * + */ + + /* == Linearized model == + * + * A = [ 1, 0, -vx*sin(yaw)*dt, cos(yaw)*dt, 0] + * [ 0, 1, vx*cos(yaw)*dt, sin(yaw)*dt, 0] + * [ 0, 0, 1, 0, dt] + * [ 0, 0, 0, 1, 0] + * [ 0, 0, 0, 0, 1] + */ + + const double yaw_rate_coeff = assume_zero_yaw_rate_ ? 0.0 : 1.0; + + // X t + Eigen::MatrixXd X_t(ekf_params_.dim_x, 1); // predicted state + ekf.getX(X_t); + const auto x = X_t(IDX::X); + const auto y = X_t(IDX::Y); + const auto yaw = X_t(IDX::YAW); + const auto vx = X_t(IDX::VX); + const auto wz = X_t(IDX::WZ); + + // X t+1 + Eigen::MatrixXd X_next_t(ekf_params_.dim_x, 1); + X_next_t(IDX::X) = x + vx * std::cos(yaw) * dt; + X_next_t(IDX::Y) = y + vx * std::sin(yaw) * dt; + X_next_t(IDX::YAW) = yaw + wz * dt * yaw_rate_coeff; + X_next_t(IDX::VX) = vx; + X_next_t(IDX::WZ) = wz * yaw_rate_coeff; + + // A: state transition matrix + Eigen::MatrixXd A = Eigen::MatrixXd::Identity(ekf_params_.dim_x, ekf_params_.dim_x); + A(IDX::X, IDX::YAW) = -vx * std::sin(yaw) * dt; + A(IDX::Y, IDX::YAW) = vx * std::cos(yaw) * dt; + A(IDX::X, IDX::VX) = std::cos(yaw) * dt; + A(IDX::Y, IDX::VX) = std::sin(yaw) * dt; + A(IDX::YAW, IDX::WZ) = dt * yaw_rate_coeff; + + // Q: system noise + Eigen::MatrixXd Q = Eigen::MatrixXd::Zero(ekf_params_.dim_x, ekf_params_.dim_x); + + // Rotate the covariance matrix according to the vehicle yaw + // because q_cov_x and y are in the vehicle coordinate system. + Eigen::MatrixXd Q_xy_local = Eigen::MatrixXd::Zero(2, 2); + Eigen::MatrixXd Q_xy_global = Eigen::MatrixXd::Zero(2, 2); + Q_xy_local << ekf_params_.q_cov_x, 0.0, 0.0, ekf_params_.q_cov_y; + Eigen::MatrixXd R = Eigen::MatrixXd::Zero(2, 2); + R << cos(yaw), -sin(yaw), sin(yaw), cos(yaw); + Q_xy_global = R * Q_xy_local * R.transpose(); + Q.block<2, 2>(IDX::X, IDX::X) = Q_xy_global; + + Q(IDX::YAW, IDX::YAW) = ekf_params_.q_cov_yaw; + Q(IDX::VX, IDX::VX) = ekf_params_.q_cov_vx; + Q(IDX::WZ, IDX::WZ) = ekf_params_.q_cov_wz; + + // may be unused + Eigen::MatrixXd B = Eigen::MatrixXd::Zero(ekf_params_.dim_x, ekf_params_.dim_x); + Eigen::MatrixXd u = Eigen::MatrixXd::Zero(ekf_params_.dim_x, 1); + + // call kalman filter library + if (!ekf.predict(X_next_t, A, Q)) { + RCLCPP_WARN(logger_, "Cannot predict"); + } + + return true; +} + +bool ConstantTurnRateMotionTracker::measureWithPose( + const autoware_auto_perception_msgs::msg::DetectedObject & object, + const geometry_msgs::msg::Transform & self_transform) +{ + // Observation pattern will be: + // 1. x, y, vx, vy + // 2. x, y + // 3. vx, vy (Do not consider this right now) + // + // We handle this measurements by stacking observation matrix, measurement vector and measurement + // covariance + // - observation matrix: C + // - measurement vector : Y + // - measurement covariance: R + + // get current state + Eigen::MatrixXd X(ekf_params_.dim_x, 1); + ekf_.getX(X); + const auto yaw_state = X(IDX::YAW); + + // rotation matrix + Eigen::Matrix2d RotationYaw; + if (trust_yaw_input_) { + const auto yaw = tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation); + RotationYaw << std::cos(yaw), -std::sin(yaw), std::sin(yaw), std::cos(yaw); + } else { + RotationYaw << std::cos(yaw_state), -std::sin(yaw_state), std::sin(yaw_state), + std::cos(yaw_state); + } + const auto base_link_yaw = tf2::getYaw(self_transform.rotation); + Eigen::Matrix2d RotationBaseLink; + RotationBaseLink << std::cos(base_link_yaw), -std::sin(base_link_yaw), std::sin(base_link_yaw), + std::cos(base_link_yaw); + + // depth from base_link to object + const auto dx = + object.kinematics.pose_with_covariance.pose.position.x - self_transform.translation.x; + const auto dy = + object.kinematics.pose_with_covariance.pose.position.y - self_transform.translation.y; + Eigen::Vector2d pose_diff_in_map(dx, dy); + Eigen::Vector2d pose_diff_in_base_link = RotationBaseLink * pose_diff_in_map; + const auto depth = abs(pose_diff_in_base_link(0)); + + // gather matrices as vector + std::vector C_list; + std::vector Y_list; + std::vector R_block_list; + + // 1. add position measurement + const bool enable_position_measurement = true; // assume position is always measured + if (enable_position_measurement) { + Eigen::MatrixXd Cxy = Eigen::MatrixXd::Zero(2, ekf_params_.dim_x); + Cxy(0, IDX::X) = 1; + Cxy(1, IDX::Y) = 1; + C_list.push_back(Cxy); + + Eigen::MatrixXd Yxy = Eigen::MatrixXd::Zero(2, 1); + Yxy << object.kinematics.pose_with_covariance.pose.position.x, + object.kinematics.pose_with_covariance.pose.position.y; + Y_list.push_back(Yxy); + + // covariance need to be rotated since it is in the vehicle coordinate system + Eigen::MatrixXd Rxy_local = Eigen::MatrixXd::Zero(2, 2); + Eigen::MatrixXd Rxy = Eigen::MatrixXd::Zero(2, 2); + if (!object.kinematics.has_position_covariance) { + // switch noise covariance in polar coordinate or cartesian coordinate + const auto r_cov_y = use_polar_coordinate_in_measurement_noise_ + ? depth * depth * ekf_params_.r_cov_x + : ekf_params_.r_cov_y; + Rxy_local << ekf_params_.r_cov_x, 0, 0, r_cov_y; // xy in base_link coordinate + Rxy = RotationBaseLink * Rxy_local * RotationBaseLink.transpose(); + } else { + Rxy_local << object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_X], + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_Y], + object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_X], + object.kinematics.pose_with_covariance + .covariance[utils::MSG_COV_IDX::Y_Y]; // xy in vehicle coordinate + Rxy = RotationYaw * Rxy_local * RotationYaw.transpose(); + } + R_block_list.push_back(Rxy); + } + + // 2. add yaw measurement + const bool object_has_orientation = object.kinematics.orientation_availability > + 0; // 0: not available, 1: sign unknown, 2: available + const bool enable_yaw_measurement = trust_yaw_input_ && object_has_orientation; + + if (enable_yaw_measurement) { + Eigen::MatrixXd Cyaw = Eigen::MatrixXd::Zero(1, ekf_params_.dim_x); + Cyaw(0, IDX::YAW) = 1; + C_list.push_back(Cyaw); + + Eigen::MatrixXd Yyaw = Eigen::MatrixXd::Zero(1, 1); + const auto yaw = [&] { + auto obj_yaw = tier4_autoware_utils::normalizeRadian( + tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation)); + while (M_PI_2 <= yaw_state - obj_yaw) { + obj_yaw = obj_yaw + M_PI; + } + while (M_PI_2 <= obj_yaw - yaw_state) { + obj_yaw = obj_yaw - M_PI; + } + return obj_yaw; + }(); + + Yyaw << yaw; + Y_list.push_back(Yyaw); + + Eigen::MatrixXd Ryaw = Eigen::MatrixXd::Zero(1, 1); + Ryaw << ekf_params_.r_cov_yaw; + R_block_list.push_back(Ryaw); + } + + // 3. add linear velocity measurement + const bool enable_velocity_measurement = object.kinematics.has_twist && trust_twist_input_; + if (enable_velocity_measurement) { + Eigen::MatrixXd C_vx = Eigen::MatrixXd::Zero(1, ekf_params_.dim_x); + C_vx(0, IDX::VX) = 1; + C_list.push_back(C_vx); + + // measure absolute velocity + Eigen::MatrixXd Vx = Eigen::MatrixXd::Zero(1, 1); + Vx << object.kinematics.twist_with_covariance.twist.linear.x; + + Eigen::Matrix2d R_vx = Eigen::MatrixXd::Zero(1, 1); + if (!object.kinematics.has_twist_covariance) { + R_vx << ekf_params_.r_cov_vx; + } else { + R_vx << object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::X_X]; + } + R_block_list.push_back(R_vx); + } + + // 4. sum up matrices + const auto row_number = std::accumulate( + C_list.begin(), C_list.end(), 0, + [](const auto & sum, const auto & C) { return sum + C.rows(); }); + if (row_number == 0) { + RCLCPP_WARN(logger_, "No measurement is available"); + return false; + } + + // stacking matrices vertically or diagonally + const auto C = utils::stackMatricesVertically(C_list); + const auto Y = utils::stackMatricesVertically(Y_list); + const auto R = utils::stackMatricesDiagonally(R_block_list); + + // 4. EKF update + if (!ekf_.update(Y, C, R)) { + RCLCPP_WARN(logger_, "Cannot update"); + } + + // 5. normalize: limit vx + { + Eigen::MatrixXd X_t(ekf_params_.dim_x, 1); + Eigen::MatrixXd P_t(ekf_params_.dim_x, ekf_params_.dim_x); + ekf_.getX(X_t); + ekf_.getP(P_t); + if (!(-max_vx_ <= X_t(IDX::VX) && X_t(IDX::VX) <= max_vx_)) { + X_t(IDX::VX) = X_t(IDX::VX) < 0 ? -max_vx_ : max_vx_; + } + ekf_.init(X_t, P_t); + } + + // 6. Filter z + // first order low pass filter + const float gain = filter_tau_ / (filter_tau_ + filter_dt_); + z_ = gain * z_ + (1.0 - gain) * object.kinematics.pose_with_covariance.pose.position.z; + return true; +} + +bool ConstantTurnRateMotionTracker::measureWithShape( + const autoware_auto_perception_msgs::msg::DetectedObject & object) +{ + // just use first order low pass filter + const float gain = filter_tau_ / (filter_tau_ + filter_dt_); + + if (object.shape.type == autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX) { + bounding_box_.length = gain * bounding_box_.length + (1.0 - gain) * object.shape.dimensions.x; + bounding_box_.width = gain * bounding_box_.width + (1.0 - gain) * object.shape.dimensions.y; + bounding_box_.height = gain * bounding_box_.height + (1.0 - gain) * object.shape.dimensions.z; + } else if (object.shape.type == autoware_auto_perception_msgs::msg::Shape::CYLINDER) { + cylinder_.width = gain * cylinder_.width + (1.0 - gain) * object.shape.dimensions.x; + cylinder_.height = gain * cylinder_.height + (1.0 - gain) * object.shape.dimensions.z; + } else { + return false; + } + + return true; +} + +bool ConstantTurnRateMotionTracker::measure( + const autoware_auto_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time, + const geometry_msgs::msg::Transform & self_transform) +{ + const auto & current_classification = getClassification(); + object_ = object; + if (object_recognition_utils::getHighestProbLabel(object.classification) == Label::UNKNOWN) { + setClassification(current_classification); + } + + if (0.01 /*10msec*/ < std::fabs((time - last_update_time_).seconds())) { + RCLCPP_WARN( + logger_, "There is a large gap between predicted time and measurement time. (%f)", + (time - last_update_time_).seconds()); + } + + measureWithPose(object, self_transform); + measureWithShape(object); + + // (void)self_transform; // currently do not use self vehicle position + return true; +} + +bool ConstantTurnRateMotionTracker::getTrackedObject( + const rclcpp::Time & time, autoware_auto_perception_msgs::msg::TrackedObject & object) const +{ + object = object_recognition_utils::toTrackedObject(object_); + object.object_id = getUUID(); + object.classification = getClassification(); + + // predict kinematics + KalmanFilter tmp_ekf_for_no_update = ekf_; + const double dt = (time - last_update_time_).seconds(); + if (0.001 /*1msec*/ < dt) { + predict(dt, tmp_ekf_for_no_update); + } + Eigen::MatrixXd X_t(ekf_params_.dim_x, 1); // predicted state + Eigen::MatrixXd P(ekf_params_.dim_x, ekf_params_.dim_x); // predicted state + tmp_ekf_for_no_update.getX(X_t); + tmp_ekf_for_no_update.getP(P); + + auto & pose_with_cov = object.kinematics.pose_with_covariance; + auto & twist_with_cov = object.kinematics.twist_with_covariance; + // rotation matrix with yaw_ + Eigen::Matrix2d R_yaw = Eigen::Matrix2d::Zero(); + R_yaw << std::cos(X_t(IDX::YAW)), -std::sin(X_t(IDX::YAW)), std::sin(X_t(IDX::YAW)), + std::cos(X_t(IDX::YAW)); + const Eigen::Matrix2d R_yaw_inv = R_yaw.transpose(); + + // position + pose_with_cov.pose.position.x = X_t(IDX::X); + pose_with_cov.pose.position.y = X_t(IDX::Y); + pose_with_cov.pose.position.z = z_; + // quaternion + { + double roll, pitch, yaw; + tf2::Quaternion original_quaternion; + tf2::fromMsg(object_.kinematics.pose_with_covariance.pose.orientation, original_quaternion); + tf2::Matrix3x3(original_quaternion).getRPY(roll, pitch, yaw); + tf2::Quaternion filtered_quaternion; + filtered_quaternion.setRPY(roll, pitch, X_t(IDX::YAW)); + pose_with_cov.pose.orientation.x = filtered_quaternion.x(); + pose_with_cov.pose.orientation.y = filtered_quaternion.y(); + pose_with_cov.pose.orientation.z = filtered_quaternion.z(); + pose_with_cov.pose.orientation.w = filtered_quaternion.w(); + if (trust_yaw_input_) { + object.kinematics.orientation_availability = + autoware_auto_perception_msgs::msg::TrackedObjectKinematics::SIGN_UNKNOWN; + } else { + object.kinematics.orientation_availability = + autoware_auto_perception_msgs::msg::TrackedObjectKinematics::UNAVAILABLE; + } + } + // twist + // twist need to converted to local coordinate + const auto vx = X_t(IDX::VX); + twist_with_cov.twist.linear.x = vx; + + // ===== covariance transformation ===== + // since covariance in EKF is in map coordinate and output should be in object coordinate, + // we need to transform covariance + Eigen::Matrix2d P_xy_map; + P_xy_map << P(IDX::X, IDX::X), P(IDX::X, IDX::Y), P(IDX::Y, IDX::X), P(IDX::Y, IDX::Y); + + // rotate covariance with -yaw + Eigen::Matrix2d P_xy = R_yaw_inv * P_xy_map * R_yaw_inv.transpose(); + + // position covariance + constexpr double no_info_cov = 1e9; // no information + constexpr double z_cov = 1. * 1.; // TODO(yukkysaito) Currently tentative + constexpr double yaw_cov = 0.1 * 0.1; // TODO(yukkysaito) Currently tentative + + pose_with_cov.covariance[utils::MSG_COV_IDX::X_X] = P_xy(IDX::X, IDX::X); + pose_with_cov.covariance[utils::MSG_COV_IDX::X_Y] = P_xy(IDX::X, IDX::Y); + pose_with_cov.covariance[utils::MSG_COV_IDX::Y_X] = P_xy(IDX::Y, IDX::X); + pose_with_cov.covariance[utils::MSG_COV_IDX::Y_Y] = P_xy(IDX::Y, IDX::Y); + pose_with_cov.covariance[utils::MSG_COV_IDX::Z_Z] = z_cov; + pose_with_cov.covariance[utils::MSG_COV_IDX::ROLL_ROLL] = no_info_cov; + pose_with_cov.covariance[utils::MSG_COV_IDX::PITCH_PITCH] = no_info_cov; + pose_with_cov.covariance[utils::MSG_COV_IDX::YAW_YAW] = yaw_cov; + + // twist covariance + constexpr double vz_cov = 0.2 * 0.2; // TODO(Yoshi Ri) Currently tentative + constexpr double wz_cov = 0.2 * 0.2; // TODO(yukkysaito) Currently tentative + + twist_with_cov.covariance[utils::MSG_COV_IDX::X_X] = P(IDX::VX, IDX::VX); + twist_with_cov.covariance[utils::MSG_COV_IDX::X_Y] = 0.0; + twist_with_cov.covariance[utils::MSG_COV_IDX::Y_X] = 0.0; + twist_with_cov.covariance[utils::MSG_COV_IDX::Y_Y] = no_info_cov; + twist_with_cov.covariance[utils::MSG_COV_IDX::Z_Z] = vz_cov; + twist_with_cov.covariance[utils::MSG_COV_IDX::ROLL_ROLL] = no_info_cov; + twist_with_cov.covariance[utils::MSG_COV_IDX::PITCH_PITCH] = no_info_cov; + twist_with_cov.covariance[utils::MSG_COV_IDX::YAW_YAW] = wz_cov; + + // set shape + if (object.shape.type == autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX) { + object.shape.dimensions.x = bounding_box_.length; + object.shape.dimensions.y = bounding_box_.width; + object.shape.dimensions.z = bounding_box_.height; + } else if (object.shape.type == autoware_auto_perception_msgs::msg::Shape::CYLINDER) { + object.shape.dimensions.x = cylinder_.width; + object.shape.dimensions.y = cylinder_.width; + object.shape.dimensions.z = cylinder_.height; + } else if (object.shape.type == autoware_auto_perception_msgs::msg::Shape::POLYGON) { + const auto origin_yaw = tf2::getYaw(object_.kinematics.pose_with_covariance.pose.orientation); + const auto ekf_pose_yaw = tf2::getYaw(pose_with_cov.pose.orientation); + object.shape.footprint = + tier4_autoware_utils::rotatePolygon(object.shape.footprint, origin_yaw - ekf_pose_yaw); + } + + return true; +} diff --git a/perception/radar_object_tracker/src/tracker/model/linear_motion_tracker.cpp b/perception/radar_object_tracker/src/tracker/model/linear_motion_tracker.cpp index f6814ceb8c246..8369d04fbe225 100644 --- a/perception/radar_object_tracker/src/tracker/model/linear_motion_tracker.cpp +++ b/perception/radar_object_tracker/src/tracker/model/linear_motion_tracker.cpp @@ -44,9 +44,21 @@ using Label = autoware_auto_perception_msgs::msg::ObjectClassification; +// initialize static parameter +bool LinearMotionTracker::is_initialized_ = false; +LinearMotionTracker::EkfParams LinearMotionTracker::ekf_params_; +double LinearMotionTracker::max_vx_; +double LinearMotionTracker::max_vy_; +double LinearMotionTracker::filter_tau_; +double LinearMotionTracker::filter_dt_; +bool LinearMotionTracker::estimate_acc_; +bool LinearMotionTracker::trust_yaw_input_; +bool LinearMotionTracker::trust_twist_input_; +bool LinearMotionTracker::use_polar_coordinate_in_measurement_noise_; + LinearMotionTracker::LinearMotionTracker( const rclcpp::Time & time, const autoware_auto_perception_msgs::msg::DetectedObject & object, - const std::string & /*tracker_param_file*/, const std::uint8_t & /*label*/) + const std::string & tracker_param_file, const std::uint8_t & /*label*/) : Tracker(time, object.classification), logger_(rclcpp::get_logger("LinearMotionTracker")), last_update_time_(time), @@ -55,11 +67,13 @@ LinearMotionTracker::LinearMotionTracker( object_ = object; // load setting from yaml file - const std::string default_setting_file = - ament_index_cpp::get_package_share_directory("radar_object_tracker") + - "/config/tracking/linear_motion_tracker.yaml"; - loadDefaultModelParameters(default_setting_file); - // loadModelParameters(tracker_param_file, label); + if (!is_initialized_) { + loadDefaultModelParameters(tracker_param_file); + is_initialized_ = true; + } + // shape initialization + bounding_box_ = {0.5, 0.5, 1.7}; + cylinder_ = {0.3, 1.7}; // initialize X matrix and position Eigen::MatrixXd X(ekf_params_.dim_x, 1); @@ -193,6 +207,12 @@ void LinearMotionTracker::loadDefaultModelParameters(const std::string & path) config["default"]["ekf_params"]["initial_covariance_std"]["ax"].as(); // [m/(s*s)] const float p0_stddev_ay = config["default"]["ekf_params"]["initial_covariance_std"]["ay"].as(); // [m/(s*s)] + estimate_acc_ = config["default"]["ekf_params"]["estimate_acc"].as(); + trust_yaw_input_ = config["default"]["trust_yaw_input"].as(false); // default false + trust_twist_input_ = config["default"]["trust_twist_input"].as(false); // default false + use_polar_coordinate_in_measurement_noise_ = + config["default"]["use_polar_coordinate_in_measurement_noise"].as( + false); // default false ekf_params_.q_cov_ax = std::pow(q_stddev_ax, 2.0); ekf_params_.q_cov_ay = std::pow(q_stddev_ay, 2.0); ekf_params_.q_cov_vx = std::pow(q_stddev_vx, 2.0); @@ -219,11 +239,6 @@ void LinearMotionTracker::loadDefaultModelParameters(const std::string & path) const float max_speed_kmph = config["default"]["limit"]["max_speed"].as(); // [km/h] max_vx_ = tier4_autoware_utils::kmph2mps(max_speed_kmph); // [m/s] max_vy_ = tier4_autoware_utils::kmph2mps(max_speed_kmph); // [rad/s] - - // shape initialization - // (TODO): this may be written in another yaml file based on classify result - bounding_box_ = {0.5, 0.5, 1.7}; - cylinder_ = {0.3, 1.7}; } bool LinearMotionTracker::predict(const rclcpp::Time & time) @@ -257,6 +272,8 @@ bool LinearMotionTracker::predict(const double dt, KalmanFilter & ekf) const * 0, 0, 0, 0, 1, 0, * 0, 0, 0, 0, 0, 1] */ + // estimate acc + const double acc_coeff = estimate_acc_ ? 1.0 : 0.0; // X t Eigen::MatrixXd X_t(ekf_params_.dim_x, 1); // predicted state @@ -270,10 +287,10 @@ bool LinearMotionTracker::predict(const double dt, KalmanFilter & ekf) const // X t+1 Eigen::MatrixXd X_next_t(ekf_params_.dim_x, 1); - X_next_t(IDX::X) = x + vx * dt + 0.5 * ax * dt * dt; - X_next_t(IDX::Y) = y + vy * dt + 0.5 * ay * dt * dt; - X_next_t(IDX::VX) = vx + ax * dt; - X_next_t(IDX::VY) = vy + ay * dt; + X_next_t(IDX::X) = x + vx * dt + 0.5 * ax * dt * dt * acc_coeff; + X_next_t(IDX::Y) = y + vy * dt + 0.5 * ay * dt * dt * acc_coeff; + X_next_t(IDX::VX) = vx + ax * dt * acc_coeff; + X_next_t(IDX::VY) = vy + ay * dt * acc_coeff; X_next_t(IDX::AX) = ax; X_next_t(IDX::AY) = ay; @@ -281,10 +298,10 @@ bool LinearMotionTracker::predict(const double dt, KalmanFilter & ekf) const Eigen::MatrixXd A = Eigen::MatrixXd::Identity(ekf_params_.dim_x, ekf_params_.dim_x); A(IDX::X, IDX::VX) = dt; A(IDX::Y, IDX::VY) = dt; - A(IDX::X, IDX::AX) = 0.5 * dt * dt; - A(IDX::Y, IDX::AY) = 0.5 * dt * dt; - A(IDX::VX, IDX::AX) = dt; - A(IDX::VY, IDX::AY) = dt; + A(IDX::X, IDX::AX) = 0.5 * dt * dt * acc_coeff; + A(IDX::Y, IDX::AY) = 0.5 * dt * dt * acc_coeff; + A(IDX::VX, IDX::AX) = dt * acc_coeff; + A(IDX::VY, IDX::AY) = dt * acc_coeff; // Q: system noise Eigen::MatrixXd Q = Eigen::MatrixXd::Zero(ekf_params_.dim_x, ekf_params_.dim_x); @@ -333,7 +350,8 @@ bool LinearMotionTracker::predict(const double dt, KalmanFilter & ekf) const } bool LinearMotionTracker::measureWithPose( - const autoware_auto_perception_msgs::msg::DetectedObject & object) + const autoware_auto_perception_msgs::msg::DetectedObject & object, + const geometry_msgs::msg::Transform & self_transform) { // Observation pattern will be: // 1. x, y, vx, vy @@ -348,8 +366,25 @@ bool LinearMotionTracker::measureWithPose( // rotation matrix Eigen::Matrix2d RotationYaw; - const auto yaw = tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation); - RotationYaw << std::cos(yaw), -std::sin(yaw), std::sin(yaw), std::cos(yaw); + if (trust_yaw_input_) { + const auto yaw = tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation); + RotationYaw << std::cos(yaw), -std::sin(yaw), std::sin(yaw), std::cos(yaw); + } else { + RotationYaw << std::cos(yaw_), -std::sin(yaw_), std::sin(yaw_), std::cos(yaw_); + } + const auto base_link_yaw = tf2::getYaw(self_transform.rotation); + Eigen::Matrix2d RotationBaseLink; + RotationBaseLink << std::cos(base_link_yaw), -std::sin(base_link_yaw), std::sin(base_link_yaw), + std::cos(base_link_yaw); + + // depth from base_link to object + const auto dx = + object.kinematics.pose_with_covariance.pose.position.x - self_transform.translation.x; + const auto dy = + object.kinematics.pose_with_covariance.pose.position.y - self_transform.translation.y; + Eigen::Vector2d pose_diff_in_map(dx, dy); + Eigen::Vector2d pose_diff_in_base_link = RotationBaseLink * pose_diff_in_map; + const auto depth = abs(pose_diff_in_base_link(0)); // gather matrices as vector std::vector C_list; @@ -371,21 +406,27 @@ bool LinearMotionTracker::measureWithPose( // covariance need to be rotated since it is in the vehicle coordinate system Eigen::MatrixXd Rxy_local = Eigen::MatrixXd::Zero(2, 2); + Eigen::MatrixXd Rxy = Eigen::MatrixXd::Zero(2, 2); if (!object.kinematics.has_position_covariance) { - Rxy_local << ekf_params_.r_cov_x, 0, 0, ekf_params_.r_cov_y; + // switch noise covariance in polar coordinate or cartesian coordinate + const auto r_cov_y = use_polar_coordinate_in_measurement_noise_ + ? depth * depth * ekf_params_.r_cov_x + : ekf_params_.r_cov_y; + Rxy_local << ekf_params_.r_cov_x, 0, 0, r_cov_y; // xy in base_link coordinate + Rxy = RotationBaseLink * Rxy_local * RotationBaseLink.transpose(); } else { Rxy_local << object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_X], object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::X_Y], object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_X], - object.kinematics.pose_with_covariance.covariance[utils::MSG_COV_IDX::Y_Y]; + object.kinematics.pose_with_covariance + .covariance[utils::MSG_COV_IDX::Y_Y]; // xy in vehicle coordinate + Rxy = RotationYaw * Rxy_local * RotationYaw.transpose(); } - Eigen::MatrixXd Rxy = Eigen::MatrixXd::Zero(2, 2); - Rxy = RotationYaw * Rxy_local * RotationYaw.transpose(); R_block_list.push_back(Rxy); } // 2. add linear velocity measurement - const bool enable_velocity_measurement = object.kinematics.has_twist; + const bool enable_velocity_measurement = object.kinematics.has_twist && trust_twist_input_; if (enable_velocity_measurement) { Eigen::MatrixXd C_vx_vy = Eigen::MatrixXd::Zero(2, ekf_params_.dim_x); C_vx_vy(0, IDX::VX) = 1; @@ -401,14 +442,15 @@ bool LinearMotionTracker::measureWithPose( Y_list.push_back(Vxy); Eigen::Matrix2d R_v_xy_local = Eigen::MatrixXd::Zero(2, 2); + Eigen::MatrixXd R_v_xy = Eigen::MatrixXd::Zero(2, 2); if (!object.kinematics.has_twist_covariance) { R_v_xy_local << ekf_params_.r_cov_vx, 0, 0, ekf_params_.r_cov_vy; + R_v_xy = RotationBaseLink * R_v_xy_local * RotationBaseLink.transpose(); } else { R_v_xy_local << object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::X_X], 0, 0, object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::Y_Y]; + R_v_xy = RotationYaw * R_v_xy_local * RotationYaw.transpose(); } - Eigen::MatrixXd R_v_xy = Eigen::MatrixXd::Zero(2, 2); - R_v_xy = RotationYaw * R_v_xy_local * RotationYaw.transpose(); R_block_list.push_back(R_v_xy); } @@ -453,8 +495,16 @@ bool LinearMotionTracker::measureWithPose( // first order low pass filter const float gain = filter_tau_ / (filter_tau_ + filter_dt_); z_ = gain * z_ + (1.0 - gain) * object.kinematics.pose_with_covariance.pose.position.z; - yaw_ = gain * yaw_ + (1.0 - gain) * yaw; - + // get yaw from twist atan + Eigen::MatrixXd X_t(ekf_params_.dim_x, 1); + ekf_.getX(X_t); + const auto twist_yaw = + std::atan2(X_t(IDX::VY), X_t(IDX::VX)); // calc from lateral and longitudinal velocity + if (trust_yaw_input_) { + yaw_ = gain * yaw_ + (1.0 - gain) * twist_yaw; + } else { + yaw_ = twist_yaw; + } return true; } @@ -494,10 +544,10 @@ bool LinearMotionTracker::measure( (time - last_update_time_).seconds()); } - measureWithPose(object); + measureWithPose(object, self_transform); measureWithShape(object); - (void)self_transform; // currently do not use self vehicle position + // (void)self_transform; // currently do not use self vehicle position return true; } @@ -543,8 +593,13 @@ bool LinearMotionTracker::getTrackedObject( pose_with_cov.pose.orientation.y = filtered_quaternion.y(); pose_with_cov.pose.orientation.z = filtered_quaternion.z(); pose_with_cov.pose.orientation.w = filtered_quaternion.w(); - object.kinematics.orientation_availability = - autoware_auto_perception_msgs::msg::TrackedObjectKinematics::SIGN_UNKNOWN; + if (trust_yaw_input_) { + object.kinematics.orientation_availability = + autoware_auto_perception_msgs::msg::TrackedObjectKinematics::SIGN_UNKNOWN; + } else { + object.kinematics.orientation_availability = + autoware_auto_perception_msgs::msg::TrackedObjectKinematics::UNAVAILABLE; + } } // twist // twist need to converted to local coordinate From 2ee44a36161ef7598208ba45b516b35d334aba26 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 30 Oct 2023 21:34:05 +0900 Subject: [PATCH 095/202] feat(avoidance): improve force avoidance judge logic in order to suppress unnecessary avoidance path (#5441) * refactor(avoidance): cleanup force avoidance params Signed-off-by: satoshi-ota * feat(avoidance): improve force avoidance judgement Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../config/avoidance/avoidance.param.yaml | 17 ++- .../utils/avoidance/avoidance_module_data.hpp | 3 + .../utils/avoidance/utils.hpp | 3 + .../behavior_path_planner/utils/utils.hpp | 2 + .../src/scene_module/avoidance/manager.cpp | 24 ++-- .../src/scene_module/lane_change/manager.cpp | 24 ++-- .../src/utils/avoidance/utils.cpp | 117 ++++++++++++------ .../behavior_path_planner/src/utils/utils.cpp | 11 ++ 8 files changed, 140 insertions(+), 61 deletions(-) diff --git a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml index 3d0a334cedf84..b0f736916ebda 100644 --- a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml +++ b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml @@ -9,7 +9,6 @@ # avoidance module common setting enable_bound_clipping: false - enable_force_avoidance_for_stopped_vehicle: false enable_yield_maneuver: true enable_yield_maneuver_during_shifting: false enable_cancel_maneuver: false @@ -120,11 +119,6 @@ # For target object filtering target_filtering: - # params for avoidance of not-parked objects - threshold_time_force_avoidance_for_stopped_vehicle: 10.0 # [s] - object_ignore_section_traffic_light_in_front_distance: 30.0 # [m] - object_ignore_section_crosswalk_in_front_distance: 30.0 # [m] - object_ignore_section_crosswalk_behind_distance: 30.0 # [m] # detection range object_check_goal_distance: 20.0 # [m] # filtering parking objects @@ -141,6 +135,17 @@ max_forward_distance: 150.0 # [m] backward_distance: 10.0 # [m] + # params for avoidance of vehicle type objects that are ambiguous as to whether they are parked. + force_avoidance: + enable: false # [-] + time_threshold: 1.0 # [s] + ignore_area: + traffic_light: + front_distance: 100.0 # [m] + crosswalk: + front_distance: 30.0 # [m] + behind_distance: 30.0 # [m] + # For safety check safety_check: # safety check configuration 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 e881c8a0d3b18..7976399a7ed40 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 @@ -381,6 +381,9 @@ struct ObjectData // avoidance target // is stoppable under the constraints bool is_stoppable{false}; + // is within intersection area + bool is_within_intersection{false}; + // unavoidable reason std::string reason{""}; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp index 0237fb458ea0b..b8b4efb7aed57 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp @@ -39,6 +39,9 @@ bool isWithinCrosswalk( const ObjectData & object, const std::shared_ptr & overall_graphs); +bool isWithinIntersection( + const ObjectData & object, const std::shared_ptr & route_handler); + bool isTargetObjectType( const PredictedObject & object, const std::shared_ptr & parameters); diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp index 38c2620096ca2..bfa83c43b061c 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp @@ -330,6 +330,8 @@ std::optional getSignedDistanceFromBoundary( Polygon2d toPolygon2d(const lanelet::ConstLanelet & lanelet); +Polygon2d toPolygon2d(const lanelet::BasicPolygon2d & polygon); + std::vector getTargetLaneletPolygons( const lanelet::ConstLanelets & lanelets, const Pose & pose, const double check_length, const std::string & target_type); 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 7988239e68071..33c6982f99fd9 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp @@ -43,8 +43,6 @@ AvoidanceModuleManager::AvoidanceModuleManager( getOrDeclareParameter(*node, ns + "resample_interval_for_output"); p.enable_bound_clipping = getOrDeclareParameter(*node, ns + "enable_bound_clipping"); p.enable_cancel_maneuver = getOrDeclareParameter(*node, ns + "enable_cancel_maneuver"); - p.enable_force_avoidance_for_stopped_vehicle = - getOrDeclareParameter(*node, ns + "enable_force_avoidance_for_stopped_vehicle"); p.enable_yield_maneuver = getOrDeclareParameter(*node, ns + "enable_yield_maneuver"); p.enable_yield_maneuver_during_shifting = getOrDeclareParameter(*node, ns + "enable_yield_maneuver_during_shifting"); @@ -108,14 +106,6 @@ AvoidanceModuleManager::AvoidanceModuleManager( // target filtering { std::string ns = "avoidance.target_filtering."; - p.threshold_time_force_avoidance_for_stopped_vehicle = getOrDeclareParameter( - *node, ns + "threshold_time_force_avoidance_for_stopped_vehicle"); - p.object_ignore_section_traffic_light_in_front_distance = getOrDeclareParameter( - *node, ns + "object_ignore_section_traffic_light_in_front_distance"); - p.object_ignore_section_crosswalk_in_front_distance = getOrDeclareParameter( - *node, ns + "object_ignore_section_crosswalk_in_front_distance"); - p.object_ignore_section_crosswalk_behind_distance = - getOrDeclareParameter(*node, ns + "object_ignore_section_crosswalk_behind_distance"); p.object_check_goal_distance = getOrDeclareParameter(*node, ns + "object_check_goal_distance"); p.threshold_distance_object_is_on_center = @@ -128,6 +118,20 @@ AvoidanceModuleManager::AvoidanceModuleManager( getOrDeclareParameter(*node, ns + "object_last_seen_threshold"); } + { + std::string ns = "avoidance.target_filtering.force_avoidance."; + p.enable_force_avoidance_for_stopped_vehicle = + getOrDeclareParameter(*node, ns + "enable"); + p.threshold_time_force_avoidance_for_stopped_vehicle = + getOrDeclareParameter(*node, ns + "time_threshold"); + p.object_ignore_section_traffic_light_in_front_distance = + getOrDeclareParameter(*node, ns + "ignore_area.traffic_light.front_distance"); + p.object_ignore_section_crosswalk_in_front_distance = + getOrDeclareParameter(*node, ns + "ignore_area.crosswalk.front_distance"); + p.object_ignore_section_crosswalk_behind_distance = + getOrDeclareParameter(*node, ns + "ignore_area.crosswalk.behind_distance"); + } + { std::string ns = "avoidance.target_filtering.detection_area."; p.use_static_detection_area = getOrDeclareParameter(*node, ns + "static"); 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 78e05c940a814..ee7b45de09e93 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 @@ -275,8 +275,6 @@ AvoidanceByLaneChangeModuleManager::AvoidanceByLaneChangeModuleManager( getOrDeclareParameter(*node, ns + "resample_interval_for_planning"); p.resample_interval_for_output = getOrDeclareParameter(*node, ns + "resample_interval_for_output"); - p.enable_force_avoidance_for_stopped_vehicle = - getOrDeclareParameter(*node, ns + "enable_force_avoidance_for_stopped_vehicle"); } // target object @@ -320,14 +318,6 @@ AvoidanceByLaneChangeModuleManager::AvoidanceByLaneChangeModuleManager( // target filtering { std::string ns = "avoidance.target_filtering."; - p.threshold_time_force_avoidance_for_stopped_vehicle = getOrDeclareParameter( - *node, ns + "threshold_time_force_avoidance_for_stopped_vehicle"); - p.object_ignore_section_traffic_light_in_front_distance = getOrDeclareParameter( - *node, ns + "object_ignore_section_traffic_light_in_front_distance"); - p.object_ignore_section_crosswalk_in_front_distance = getOrDeclareParameter( - *node, ns + "object_ignore_section_crosswalk_in_front_distance"); - p.object_ignore_section_crosswalk_behind_distance = - getOrDeclareParameter(*node, ns + "object_ignore_section_crosswalk_behind_distance"); p.object_check_goal_distance = getOrDeclareParameter(*node, ns + "object_check_goal_distance"); p.threshold_distance_object_is_on_center = @@ -340,6 +330,20 @@ AvoidanceByLaneChangeModuleManager::AvoidanceByLaneChangeModuleManager( getOrDeclareParameter(*node, ns + "object_last_seen_threshold"); } + { + std::string ns = "avoidance.target_filtering.force_avoidance."; + p.enable_force_avoidance_for_stopped_vehicle = + getOrDeclareParameter(*node, ns + "enable"); + p.threshold_time_force_avoidance_for_stopped_vehicle = + getOrDeclareParameter(*node, ns + "time_threshold"); + p.object_ignore_section_traffic_light_in_front_distance = + getOrDeclareParameter(*node, ns + "ignore_area.traffic_light.front_distance"); + p.object_ignore_section_crosswalk_in_front_distance = + getOrDeclareParameter(*node, ns + "ignore_area.crosswalk.front_distance"); + p.object_ignore_section_crosswalk_behind_distance = + getOrDeclareParameter(*node, ns + "ignore_area.crosswalk.behind_distance"); + } + { std::string ns = "avoidance.target_filtering.detection_area."; p.use_static_detection_area = getOrDeclareParameter(*node, ns + "static"); diff --git a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp index 725b528abad51..54a1c0c649916 100644 --- a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp +++ b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp @@ -292,6 +292,81 @@ bool isWithinCrosswalk( return false; } +bool isWithinIntersection( + const ObjectData & object, const std::shared_ptr & route_handler) +{ + const std::string id = object.overhang_lanelet.attributeOr("intersection_area", "else"); + if (id == "else") { + return false; + } + + const auto object_polygon = tier4_autoware_utils::toPolygon2d(object.object); + + const auto polygon = route_handler->getLaneletMapPtr()->polygonLayer.get(std::atoi(id.c_str())); + + return boost::geometry::within( + object_polygon, utils::toPolygon2d(lanelet::utils::to2D(polygon.basicPolygon()))); +} + +bool isForceAvoidanceTarget( + ObjectData & object, const lanelet::ConstLanelets & extend_lanelets, + const std::shared_ptr & planner_data, + const std::shared_ptr & parameters) +{ + if (!parameters->enable_force_avoidance_for_stopped_vehicle) { + return false; + } + + const auto stop_time_longer_than_threshold = + object.stop_time > parameters->threshold_time_force_avoidance_for_stopped_vehicle; + + if (!stop_time_longer_than_threshold) { + return false; + } + + if (object.is_within_intersection) { + RCLCPP_DEBUG(rclcpp::get_logger(__func__), "object is in the intersection area."); + return false; + } + + const auto rh = planner_data->route_handler; + + if ( + !!rh->getRoutingGraphPtr()->right(object.overhang_lanelet) && + !!rh->getRoutingGraphPtr()->left(object.overhang_lanelet)) { + RCLCPP_DEBUG(rclcpp::get_logger(__func__), "object isn't on the edge lane."); + return false; + } + + const auto & ego_pose = planner_data->self_odometry->pose.pose; + const auto & object_pose = object.object.kinematics.initial_pose_with_covariance.pose; + + // force avoidance for stopped vehicle + bool not_parked_object = true; + + // check traffic light + const auto to_traffic_light = utils::getDistanceToNextTrafficLight(object_pose, extend_lanelets); + { + not_parked_object = + to_traffic_light < parameters->object_ignore_section_traffic_light_in_front_distance; + } + + // check crosswalk + const auto to_crosswalk = + utils::getDistanceToCrosswalk(ego_pose, extend_lanelets, *rh->getOverallGraphPtr()) - + object.longitudinal; + { + const auto stop_for_crosswalk = + to_crosswalk < parameters->object_ignore_section_crosswalk_in_front_distance && + to_crosswalk > -1.0 * parameters->object_ignore_section_crosswalk_behind_distance; + not_parked_object = not_parked_object || stop_for_crosswalk; + } + + object.to_stop_factor_distance = std::min(to_traffic_light, to_crosswalk); + + return !not_parked_object; +} + double calcShiftLength( const bool & is_object_on_right, const double & overhang_dist, const double & avoid_margin) { @@ -1127,42 +1202,14 @@ void filterTargetObjects( continue; } - // from here condition check for vehicle type objects. + o.is_within_intersection = isWithinIntersection(o, rh); - const auto stop_time_longer_than_threshold = - o.stop_time > parameters->threshold_time_force_avoidance_for_stopped_vehicle; - - if (stop_time_longer_than_threshold && parameters->enable_force_avoidance_for_stopped_vehicle) { - // force avoidance for stopped vehicle - bool not_parked_object = true; - - // check traffic light - const auto to_traffic_light = - utils::getDistanceToNextTrafficLight(object_pose, extend_lanelets); - { - not_parked_object = - to_traffic_light < parameters->object_ignore_section_traffic_light_in_front_distance; - } - - // check crosswalk - const auto to_crosswalk = - utils::getDistanceToCrosswalk(ego_pose, extend_lanelets, *rh->getOverallGraphPtr()) - - o.longitudinal; - { - const auto stop_for_crosswalk = - to_crosswalk < parameters->object_ignore_section_crosswalk_in_front_distance && - to_crosswalk > -1.0 * parameters->object_ignore_section_crosswalk_behind_distance; - not_parked_object = not_parked_object || stop_for_crosswalk; - } - - o.to_stop_factor_distance = std::min(to_traffic_light, to_crosswalk); - - if (!not_parked_object) { - o.last_seen = now; - o.avoid_margin = avoid_margin; - data.target_objects.push_back(o); - continue; - } + // from here condition check for vehicle type objects. + if (isForceAvoidanceTarget(o, extend_lanelets, planner_data, parameters)) { + o.last_seen = now; + o.avoid_margin = avoid_margin; + data.target_objects.push_back(o); + continue; } // Object is on center line -> ignore. diff --git a/planning/behavior_path_planner/src/utils/utils.cpp b/planning/behavior_path_planner/src/utils/utils.cpp index 3ab20e7f76718..37a628f54607e 100644 --- a/planning/behavior_path_planner/src/utils/utils.cpp +++ b/planning/behavior_path_planner/src/utils/utils.cpp @@ -2708,6 +2708,17 @@ Polygon2d toPolygon2d(const lanelet::ConstLanelet & lanelet) : tier4_autoware_utils::inverseClockwise(polygon); } +Polygon2d toPolygon2d(const lanelet::BasicPolygon2d & polygon) +{ + Polygon2d ret; + for (const auto & p : polygon) { + ret.outer().emplace_back(p.x(), p.y()); + } + ret.outer().push_back(ret.outer().front()); + + return tier4_autoware_utils::isClockwise(ret) ? ret : tier4_autoware_utils::inverseClockwise(ret); +} + std::vector getTargetLaneletPolygons( const lanelet::PolygonLayer & map_polygons, lanelet::ConstLanelets & lanelets, const Pose & pose, const double check_length, const std::string & target_type) From 49af2650accb154985e413df9b93f2a531811407 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 31 Oct 2023 10:48:04 +0900 Subject: [PATCH 096/202] fix(behavior_path_planner): fix turn signal endless loop (#5444) Signed-off-by: kosuke55 --- .../src/turn_signal_decider.cpp | 24 ++++--------------- 1 file changed, 5 insertions(+), 19 deletions(-) diff --git a/planning/behavior_path_planner/src/turn_signal_decider.cpp b/planning/behavior_path_planner/src/turn_signal_decider.cpp index 3fe30b11e3a57..d1b8bdc806bf4 100644 --- a/planning/behavior_path_planner/src/turn_signal_decider.cpp +++ b/planning/behavior_path_planner/src/turn_signal_decider.cpp @@ -165,30 +165,16 @@ boost::optional TurnSignalDecider::getIntersectionTurnSignalInfo const std::string lane_attribute = current_lane.attributeOr("turn_direction", std::string("none")); - // check next lanes - auto next_lanes = route_handler.getNextLanelets(current_lane); - if (next_lanes.empty()) { + // check next lane has the same attribute + lanelet::ConstLanelet next_lane{}; + if (!route_handler.getNextLaneletWithinRoute(current_lane, &next_lane)) { break; } - - // filter next lanes with same attribute in the path - std::vector next_lanes_in_path{}; - std::copy_if( - next_lanes.begin(), next_lanes.end(), std::back_inserter(next_lanes_in_path), - [&](const auto & next_lane) { - const bool is_in_unique_ids = - std::find(unique_lane_ids.begin(), unique_lane_ids.end(), next_lane.id()) != - unique_lane_ids.end(); - const bool has_same_attribute = - next_lane.attributeOr("turn_direction", std::string("none")) == lane_attribute; - return is_in_unique_ids && has_same_attribute; - }); - if (next_lanes_in_path.empty()) { + if (next_lane.attributeOr("turn_direction", std::string("none")) != lane_attribute) { break; } - // assume that the next lane in the path is only one - current_lane = next_lanes_in_path.front(); + current_lane = next_lane; } if (!combined_lane_elems.empty()) { From a194589eb0983ebbc5b77d5eebd6990e1ec8eb0f Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Tue, 31 Oct 2023 14:05:32 +0900 Subject: [PATCH 097/202] chore(intersection): add debug plotter (#5432) Signed-off-by: Mamoru Sobue --- .cspell-partial.json | 2 +- .../CMakeLists.txt | 5 + .../config/intersection.param.yaml | 3 + .../scripts/ttc.py | 287 ++++++++++++++++++ .../src/manager.cpp | 1 + .../src/scene_intersection.cpp | 58 +++- .../src/scene_intersection.hpp | 7 + .../src/util.cpp | 31 +- .../src/util.hpp | 12 +- 9 files changed, 393 insertions(+), 13 deletions(-) create mode 100755 planning/behavior_velocity_intersection_module/scripts/ttc.py diff --git a/.cspell-partial.json b/.cspell-partial.json index 13849ef298019..e231eddd712ea 100644 --- a/.cspell-partial.json +++ b/.cspell-partial.json @@ -5,5 +5,5 @@ "perception/bytetrack/lib/**" ], "ignoreRegExpList": [], - "words": ["dltype", "tvmgen"] + "words": ["dltype", "tvmgen", "quantizer", "imageio", "mimsave"] } diff --git a/planning/behavior_velocity_intersection_module/CMakeLists.txt b/planning/behavior_velocity_intersection_module/CMakeLists.txt index 8ff78dac06716..9e7eb196cd0c1 100644 --- a/planning/behavior_velocity_intersection_module/CMakeLists.txt +++ b/planning/behavior_velocity_intersection_module/CMakeLists.txt @@ -20,3 +20,8 @@ target_link_libraries(${PROJECT_NAME} ) ament_auto_package(INSTALL_TO_SHARE config) + +install(PROGRAMS + scripts/ttc.py + DESTINATION lib/${PROJECT_NAME} +) diff --git a/planning/behavior_velocity_intersection_module/config/intersection.param.yaml b/planning/behavior_velocity_intersection_module/config/intersection.param.yaml index 82a5f65622d0b..adbc7b3e087d6 100644 --- a/planning/behavior_velocity_intersection_module/config/intersection.param.yaml +++ b/planning/behavior_velocity_intersection_module/config/intersection.param.yaml @@ -83,6 +83,9 @@ attention_lane_curvature_calculation_ds: 0.5 static_occlusion_with_traffic_light_timeout: 3.5 + debug: + ttc: [0] + enable_rtc: intersection: false # If set to true, the scene modules require approval from the rtc (request to cooperate) function. If set to false, the modules can be executed without requiring rtc approval intersection_to_occlusion: false diff --git a/planning/behavior_velocity_intersection_module/scripts/ttc.py b/planning/behavior_velocity_intersection_module/scripts/ttc.py new file mode 100755 index 0000000000000..e4633981570d1 --- /dev/null +++ b/planning/behavior_velocity_intersection_module/scripts/ttc.py @@ -0,0 +1,287 @@ +#!/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 dataclasses import dataclass +from itertools import cycle +import math +from threading import Lock +import time + +import imageio +import matplotlib +import matplotlib.pyplot as plt +import numpy as np +import rclpy +from rclpy.node import Node +from tier4_debug_msgs.msg import Float64MultiArrayStamped + +matplotlib.use("TKAgg") + + +@dataclass +class NPC: + x: float + y: float + th: float + width: float + height: float + speed: float + dangerous: bool + ref_object_enter_time: float + ref_object_exit_time: float + collision_start_time: float + collision_start_dist: float + collision_end_time: float + collision_end_dist: float + pred_x: list[float] + pred_y: list[float] + + def __init__(self, data: list[float]): + self.x = data[0] + self.y = data[1] + self.th = data[2] + self.width = data[3] + self.height = data[4] + self.speed = data[5] + self.dangerous = bool(int(data[6])) + self.ref_object_enter_time = data[7] + self.ref_object_exit_time = data[8] + self.collision_start_time = data[9] + self.collision_start_dist = data[10] + self.collision_end_time = data[11] + self.collision_end_dist = data[12] + self.first_collision_x = data[13] + self.first_collision_y = data[14] + self.last_collision_x = data[15] + self.last_collision_y = data[16] + self.pred_x = data[17:58:2] + self.pred_y = data[18:58:2] + + +class TTCVisualizer(Node): + def __init__(self, args): + super().__init__("ttc_visualizer") + self.ttc_dist_pub = self.create_subscription( + Float64MultiArrayStamped, + "/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/intersection/ego_ttc", + self.on_ego_ttc, + 1, + ) + self.ttc_time_pub = self.create_subscription( + Float64MultiArrayStamped, + "/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/intersection/object_ttc", + self.on_object_ttc, + 1, + ) + self.args = args + self.lane_id = args.lane_id + self.ego_ttc_data = None + self.object_ttc_data = None + self.npc_vehicles = [] + self.images = [] + self.last_sub = time.time() + + self.plot_timer = self.create_timer(0.2, self.on_plot_timer) + self.fig = plt.figure(figsize=(13, 6)) + self.ttc_ax = self.fig.add_subplot(1, 2, 1) + self.ttc_vel_ax = self.ttc_ax.twinx() + self.world_ax = self.fig.add_subplot(1, 2, 2) + self.lock = Lock() + self.color_list = [ + "#e41a1c", + "#377eb8", + "#4daf4a", + "#984ea3", + "#ff7f00", + "#ffff33", + "#a65628", + "#f781bf", + ] + plt.ion() + plt.show(block=False) + + def plot_ttc(self): + self.ttc_ax.cla() + self.ttc_vel_ax.cla() + + n_ttc_data = int(self.ego_ttc_data.layout.dim[1].size) + ego_ttc_time = self.ego_ttc_data.data[n_ttc_data : 2 * n_ttc_data] + ego_ttc_dist = self.ego_ttc_data.data[2 * n_ttc_data : 3 * n_ttc_data] + + self.ttc_ax.grid() + self.ttc_ax.set_xlabel("ego time") + self.ttc_ax.set_ylabel("ego dist") + time_dist_plot = self.ttc_ax.plot(ego_ttc_time, ego_ttc_dist, label="time-dist", c="orange") + self.ttc_ax.set_xlim(min(ego_ttc_time) - 2.0, max(ego_ttc_time) + 3.0) + self.ttc_ax.set_ylim(min(ego_ttc_dist) - 2.0, max(ego_ttc_dist) + 3.0) + for npc, color in zip(self.npc_vehicles, cycle(self.color_list)): + t0, t1 = npc.collision_start_time, npc.collision_end_time + d0, d1 = npc.collision_start_dist, npc.collision_end_dist + self.ttc_ax.fill( + [t0, t0, t1, t1, 0, 0], + [d0, 0, 0, d1, d1, d0], + c=color, + alpha=0.2, + ) + + dd = [d1 - d0 for d0, d1 in zip(ego_ttc_dist, ego_ttc_dist[1:])] + dt = [t1 - t0 for t0, t1 in zip(ego_ttc_time, ego_ttc_time[1:])] + v = [d / t for d, t in zip(dd, dt)] + self.ttc_vel_ax.yaxis.set_label_position("right") + self.ttc_vel_ax.set_ylabel("ego velocity") + self.ttc_vel_ax.set_ylim(0.0, max(v) + 1.0) + time_velocity_plot = self.ttc_vel_ax.plot(ego_ttc_time[1:], v, label="time-v", c="red") + + lines = time_dist_plot + time_velocity_plot + labels = [line.get_label() for line in lines] + self.ttc_ax.legend(lines, labels, loc="upper left") + + def plot_world(self): + detect_range = self.args.range + self.world_ax.cla() + n_ttc_data = int(self.ego_ttc_data.layout.dim[1].size) + ego_path_x = self.ego_ttc_data.data[3 * n_ttc_data : 4 * n_ttc_data] + ego_path_y = self.ego_ttc_data.data[4 * n_ttc_data : 5 * n_ttc_data] + self.world_ax.set_aspect("equal") + self.world_ax.scatter(ego_path_x[0], ego_path_y[0], marker="x", c="red", s=15) + min_x, max_x = min(ego_path_x), max(ego_path_x) + min_y, max_y = min(ego_path_y), max(ego_path_y) + x_dir = 1 if ego_path_x[-1] > ego_path_x[0] else -1 + y_dir = 1 if ego_path_y[-1] > ego_path_y[0] else -1 + min_x = min_x - detect_range if x_dir == 1 else min_x - 20 + max_x = max_x + detect_range if x_dir == -1 else max_x + 20 + min_y = min_y - detect_range if y_dir == 1 else min_y - 20 + max_y = max_y + detect_range if y_dir == -1 else max_y + 20 + self.world_ax.set_xlim(min_x, max_x) + self.world_ax.set_ylim(min_y, max_y) + arrows = [ + (x0, y0, math.atan2(x1 - x0, y1 - y0)) + for (x0, y0, x1, y1) in zip( + ego_path_x[0:-1:5], + ego_path_y[0:-1:5], + ego_path_x[4:-1:5], + ego_path_y[4:-1:5], + ) + ] + for x, y, th in arrows: + self.world_ax.arrow( + x, + y, + math.sin(th) * 0.5, + math.cos(th) * 0.5, + head_width=0.1, + head_length=0.1, + ) + + for npc, color in zip(self.npc_vehicles, cycle(self.color_list)): + x, y, th, w, h = npc.x, npc.y, npc.th, npc.width, npc.height + bbox = np.array( + [ + [-w / 2, -h / 2], + [+w / 2, -h / 2], + [+w / 2, +h / 2], + [-w / 2, +h / 2], + [-w / 2, -h / 2], + ] + ).transpose() + Rth = np.array([[math.cos(th), -math.sin(th)], [math.sin(th), math.cos(th)]]) + bbox_rot = Rth @ bbox + self.world_ax.fill(bbox_rot[0, :] + x, bbox_rot[1, :] + y, color, alpha=0.5) + self.world_ax.plot( + [npc.first_collision_x, npc.last_collision_x], + [npc.first_collision_y, npc.last_collision_y], + c=color, + linewidth=3.0, + ) + if npc.dangerous: + self.world_ax.plot(npc.pred_x, npc.pred_y, c=color, linewidth=1.5) + else: + self.world_ax.plot(npc.pred_x, npc.pred_y, c=color, linestyle="--") + + self.world_ax.plot(ego_path_x, ego_path_y, c="k", linestyle="--") + + def cleanup(self): + if self.args.save: + kwargs_write = {"fps": self.args.fps, "quantizer": "nq"} + imageio.mimsave("./" + self.args.gif + ".gif", self.images, **kwargs_write) + + def on_plot_timer(self): + with self.lock: + if (not self.ego_ttc_data) or (not self.object_ttc_data): + return + + if not self.last_sub: + return + + now = time.time() + if (now - self.last_sub) > 1.0: + print("elapsed more than 1sec from last sub, exit/save fig") + self.cleanup() + + self.plot_ttc() + self.plot_world() + self.fig.canvas.flush_events() + + if self.args.save: + image = np.frombuffer(self.fig.canvas.tostring_rgb(), dtype="uint8") + image = image.reshape(self.fig.canvas.get_width_height()[::-1] + (3,)) + self.images.append(image) + + def on_ego_ttc(self, msg): + with self.lock: + if int(msg.data[0]) == self.lane_id: + self.ego_ttc_data = msg + self.last_sub = time.time() + + def parse_npc_vehicles(self): + self.npc_vehicles = [] + n_npc_vehicles = int(self.object_ttc_data.layout.dim[0].size) + npc_data_size = int(self.object_ttc_data.layout.dim[1].size) + for i in range(1, n_npc_vehicles): + data = self.object_ttc_data.data[i * npc_data_size : (i + 1) * npc_data_size] + self.npc_vehicles.append(NPC(data)) + + def on_object_ttc(self, msg): + with self.lock: + if int(msg.data[0]) == self.lane_id: + self.object_ttc_data = msg + self.parse_npc_vehicles() + self.last_sub = time.time() + + +if __name__ == "__main__": + parser = argparse.ArgumentParser() + parser.add_argument( + "--lane_id", + type=int, + required=True, + help="lane_id to analyze", + ) + parser.add_argument( + "--range", + type=float, + default=60, + help="detect range for drawing", + ) + parser.add_argument("-s", "--save", action="store_true", help="flag to save gif") + parser.add_argument("--gif", type=str, default="ttc", help="filename of gif file") + parser.add_argument("--fps", type=float, default=5, help="fps of gif") + args = parser.parse_args() + + rclpy.init() + visualizer = TTCVisualizer(args) + rclpy.spin(visualizer) diff --git a/planning/behavior_velocity_intersection_module/src/manager.cpp b/planning/behavior_velocity_intersection_module/src/manager.cpp index 3c0d7fa0b4f1c..5c5f5eac16b81 100644 --- a/planning/behavior_velocity_intersection_module/src/manager.cpp +++ b/planning/behavior_velocity_intersection_module/src/manager.cpp @@ -181,6 +181,7 @@ IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node) getOrDeclareParameter(node, ns + ".occlusion.attention_lane_curvature_calculation_ds"); ip.occlusion.static_occlusion_with_traffic_light_timeout = getOrDeclareParameter( node, ns + ".occlusion.static_occlusion_with_traffic_light_timeout"); + ip.debug.ttc = getOrDeclareParameter>(node, ns + ".debug.ttc"); } void IntersectionModuleManager::launchNewModules( diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp index 31b63413a6437..c3b429680ab91 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -138,6 +138,10 @@ IntersectionModule::IntersectionModule( decision_state_pub_ = node_.create_publisher("~/debug/intersection/decision_state", 1); + ego_ttc_pub_ = node_.create_publisher( + "~/debug/intersection/ego_ttc", 1); + object_ttc_pub_ = node_.create_publisher( + "~/debug/intersection/object_ttc", 1); } void IntersectionModule::initializeRTCStatus() @@ -1465,12 +1469,22 @@ bool IntersectionModule::checkCollision( // check collision between target_objects predicted path and ego lane // cut the predicted path at passing_time + tier4_debug_msgs::msg::Float64MultiArrayStamped ego_ttc_time_array; const auto time_distance_array = util::calcIntersectionPassingTime( - path, planner_data_, associative_ids_, closest_idx, last_intersection_stop_line_candidate_idx, - time_delay, planner_param_.common.intersection_velocity, + path, planner_data_, lane_id_, associative_ids_, closest_idx, + last_intersection_stop_line_candidate_idx, time_delay, + planner_param_.common.intersection_velocity, planner_param_.collision_detection.minimum_ego_predicted_velocity, planner_param_.collision_detection.use_upstream_velocity, - planner_param_.collision_detection.minimum_upstream_velocity); + planner_param_.collision_detection.minimum_upstream_velocity, &ego_ttc_time_array); + + if ( + std::find(planner_param_.debug.ttc.begin(), planner_param_.debug.ttc.end(), lane_id_) != + planner_param_.debug.ttc.end()) { + ego_ttc_time_array.stamp = path.header.stamp; + ego_ttc_pub_->publish(ego_ttc_time_array); + } + const double passing_time = time_distance_array.back().first; util::cutPredictPathWithDuration(target_objects, clock_, passing_time); @@ -1552,6 +1566,19 @@ bool IntersectionModule::checkCollision( return (object2collision > margin) || (object2collision < 0); }; // check collision between predicted_path and ego_area + tier4_debug_msgs::msg::Float64MultiArrayStamped object_ttc_time_array; + object_ttc_time_array.layout.dim.resize(3); + object_ttc_time_array.layout.dim.at(0).label = "objects"; + object_ttc_time_array.layout.dim.at(0).size = 1; // incremented in the loop, first row is lane_id + object_ttc_time_array.layout.dim.at(1).label = + "[x, y, th, length, width, speed, dangerous, ref_obj_enter_time, ref_obj_exit_time, " + "start_time, start_dist, " + "end_time, end_dist, first_collision_x, first_collision_y, last_collision_x, last_collision_y, " + "prd_x[0], ... pred_x[19], pred_y[0], ... pred_y[19]]"; + object_ttc_time_array.layout.dim.at(1).size = 57; + for (unsigned i = 0; i < object_ttc_time_array.layout.dim.at(1).size; ++i) { + object_ttc_time_array.data.push_back(lane_id_); + } bool collision_detected = false; for (const auto & target_object : target_objects->all_attention_objects) { const auto & object = target_object.object; @@ -1650,6 +1677,24 @@ bool IntersectionModule::checkCollision( break; } } + object_ttc_time_array.layout.dim.at(0).size++; + const auto & pos = object.kinematics.initial_pose_with_covariance.pose.position; + const auto & shape = object.shape; + object_ttc_time_array.data.insert( + object_ttc_time_array.data.end(), + {pos.x, pos.y, tf2::getYaw(object.kinematics.initial_pose_with_covariance.pose.orientation), + shape.dimensions.x, shape.dimensions.y, + object.kinematics.initial_twist_with_covariance.twist.linear.x, + 1.0 * static_cast(collision_detected), ref_object_enter_time, ref_object_exit_time, + start_time_distance_itr->first, start_time_distance_itr->second, + end_time_distance_itr->first, end_time_distance_itr->second, first_itr->position.x, + first_itr->position.y, last_itr->position.x, last_itr->position.y}); + for (unsigned i = 0; i < 20; i++) { + const auto & pos = + predicted_path.path.at(std::min(i, predicted_path.path.size() - 1)).position; + object_ttc_time_array.data.push_back(pos.x); + object_ttc_time_array.data.push_back(pos.y); + } if (collision_detected) { debug_data_.conflicting_targets.objects.push_back(object); break; @@ -1657,6 +1702,13 @@ bool IntersectionModule::checkCollision( } } + if ( + std::find(planner_param_.debug.ttc.begin(), planner_param_.debug.ttc.end(), lane_id_) != + planner_param_.debug.ttc.end()) { + object_ttc_time_array.stamp = path.header.stamp; + object_ttc_pub_->publish(object_ttc_time_array); + } + return collision_detected; } diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp index 93fec171ec0d2..c794ef6c53aad 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp @@ -24,6 +24,7 @@ #include #include +#include #include #include @@ -150,6 +151,10 @@ class IntersectionModule : public SceneModuleInterface double attention_lane_curvature_calculation_ds; double static_occlusion_with_traffic_light_timeout; } occlusion; + struct Debug + { + std::vector ttc; + } debug; }; enum OcclusionType { @@ -363,6 +368,8 @@ class IntersectionModule : public SceneModuleInterface util::DebugData debug_data_; rclcpp::Publisher::SharedPtr decision_state_pub_; + rclcpp::Publisher::SharedPtr ego_ttc_pub_; + rclcpp::Publisher::SharedPtr object_ttc_pub_; }; } // namespace behavior_velocity_planner diff --git a/planning/behavior_velocity_intersection_module/src/util.cpp b/planning/behavior_velocity_intersection_module/src/util.cpp index 25eaaf4d8cb9d..c27a2ad218ffb 100644 --- a/planning/behavior_velocity_intersection_module/src/util.cpp +++ b/planning/behavior_velocity_intersection_module/src/util.cpp @@ -1305,10 +1305,12 @@ void cutPredictPathWithDuration( TimeDistanceArray calcIntersectionPassingTime( const autoware_auto_planning_msgs::msg::PathWithLaneId & path, - const std::shared_ptr & planner_data, const std::set & associative_ids, - const size_t closest_idx, const size_t last_intersection_stop_line_candidate_idx, - const double time_delay, const double intersection_velocity, const double minimum_ego_velocity, - const bool use_upstream_velocity, const double minimum_upstream_velocity) + const std::shared_ptr & planner_data, const lanelet::Id lane_id, + const std::set & associative_ids, const size_t closest_idx, + const size_t last_intersection_stop_line_candidate_idx, const double time_delay, + const double intersection_velocity, const double minimum_ego_velocity, + const bool use_upstream_velocity, const double minimum_upstream_velocity, + tier4_debug_msgs::msg::Float64MultiArrayStamped * debug_ttc_array) { double dist_sum = 0.0; int assigned_lane_found = false; @@ -1374,7 +1376,26 @@ TimeDistanceArray calcIntersectionPassingTime( time_distance_array.emplace_back(passing_time, dist_sum); } - + debug_ttc_array->layout.dim.resize(3); + debug_ttc_array->layout.dim.at(0).label = "lane_id_@[0][0], ttc_time, ttc_dist, path_x, path_y"; + debug_ttc_array->layout.dim.at(0).size = 5; + debug_ttc_array->layout.dim.at(1).label = "values"; + debug_ttc_array->layout.dim.at(1).size = time_distance_array.size(); + for (unsigned i = 0; i < time_distance_array.size(); ++i) { + debug_ttc_array->data.push_back(lane_id); + } + for (const auto & [t, d] : time_distance_array) { + debug_ttc_array->data.push_back(t); + } + for (const auto & [t, d] : time_distance_array) { + debug_ttc_array->data.push_back(d); + } + for (const auto & p : smoothed_reference_path.points) { + debug_ttc_array->data.push_back(p.point.pose.position.x); + } + for (const auto & p : smoothed_reference_path.points) { + debug_ttc_array->data.push_back(p.point.pose.position.y); + } return time_distance_array; } diff --git a/planning/behavior_velocity_intersection_module/src/util.hpp b/planning/behavior_velocity_intersection_module/src/util.hpp index 5faacd4325b06..11aab06ff1d94 100644 --- a/planning/behavior_velocity_intersection_module/src/util.hpp +++ b/planning/behavior_velocity_intersection_module/src/util.hpp @@ -20,6 +20,8 @@ #include +#include + #include #include #include @@ -146,10 +148,12 @@ void cutPredictPathWithDuration( TimeDistanceArray calcIntersectionPassingTime( const autoware_auto_planning_msgs::msg::PathWithLaneId & path, - const std::shared_ptr & planner_data, const std::set & associative_ids, - const size_t closest_idx, const size_t last_intersection_stop_line_candidate_idx, - const double time_delay, const double intersection_velocity, const double minimum_ego_velocity, - const bool use_upstream_velocity, const double minimum_upstream_velocity); + const std::shared_ptr & planner_data, const lanelet::Id lane_id, + const std::set & associative_ids, const size_t closest_idx, + const size_t last_intersection_stop_line_candidate_idx, const double time_delay, + const double intersection_velocity, const double minimum_ego_velocity, + const bool use_upstream_velocity, const double minimum_upstream_velocity, + tier4_debug_msgs::msg::Float64MultiArrayStamped * debug_ttc_array); double calcDistanceUntilIntersectionLanelet( const lanelet::ConstLanelet & assigned_lanelet, From 9628276d68807fd90a1bfc6d304776eabb7e7cc1 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 31 Oct 2023 18:25:53 +0900 Subject: [PATCH 098/202] fix(avoidance): discard envelope polygon if the objects move long distance (#5388) * fix(avoidance): discard envelope polygon if the objects move long distance Signed-off-by: satoshi-ota * Update planning/behavior_path_planner/src/utils/avoidance/utils.cpp Co-authored-by: Kyoichi Sugahara * Update planning/behavior_path_planner/src/utils/avoidance/utils.cpp Co-authored-by: Kyoichi Sugahara --------- Signed-off-by: satoshi-ota Co-authored-by: Kyoichi Sugahara --- .../src/utils/avoidance/utils.cpp | 27 ++++++++++++++----- 1 file changed, 21 insertions(+), 6 deletions(-) diff --git a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp index 54a1c0c649916..2e441907b6d19 100644 --- a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp +++ b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp @@ -754,26 +754,41 @@ void fillObjectEnvelopePolygon( return; } - const auto envelope_poly = + const auto one_shot_envelope_poly = createEnvelopePolygon(object_data, closest_pose, envelope_buffer_margin); - if (boost::geometry::within(envelope_poly, same_id_obj->envelope_poly)) { + // If the one_shot_envelope_poly is within the registered envelope, use the registered one + if (boost::geometry::within(one_shot_envelope_poly, same_id_obj->envelope_poly)) { object_data.envelope_poly = same_id_obj->envelope_poly; return; } std::vector unions; - boost::geometry::union_(envelope_poly, same_id_obj->envelope_poly, unions); + boost::geometry::union_(one_shot_envelope_poly, same_id_obj->envelope_poly, unions); + // If union fails, use the current envelope if (unions.empty()) { - object_data.envelope_poly = - createEnvelopePolygon(object_data, closest_pose, envelope_buffer_margin); + object_data.envelope_poly = one_shot_envelope_poly; return; } boost::geometry::correct(unions.front()); - object_data.envelope_poly = createEnvelopePolygon(unions.front(), closest_pose, 0.0); + const auto multi_step_envelope_poly = createEnvelopePolygon(unions.front(), closest_pose, 0.0); + + const auto object_polygon = tier4_autoware_utils::toPolygon2d(object_data.object); + const auto object_polygon_area = boost::geometry::area(object_polygon); + const auto envelope_polygon_area = boost::geometry::area(multi_step_envelope_poly); + + // keep multi-step envelope polygon. + constexpr double THRESHOLD = 5.0; + if (envelope_polygon_area < object_polygon_area * THRESHOLD) { + object_data.envelope_poly = multi_step_envelope_poly; + return; + } + + // use latest one-shot envelope polygon. + object_data.envelope_poly = one_shot_envelope_poly; } void fillObjectMovingTime( From 19988807d80c5af85ad89b58a723c8891c84e9a8 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 31 Oct 2023 18:41:23 +0900 Subject: [PATCH 099/202] feat(avoidance): use traffic light signal info (#5395) * feat(utils): add function to calculate shift start/end point Signed-off-by: satoshi-ota * feat(avoidance): add new parameter Signed-off-by: satoshi-ota * feat(avoidance): set shift start/end point with module taking traffic signal into account Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../config/avoidance/avoidance.param.yaml | 9 +- .../utils/avoidance/avoidance_module_data.hpp | 15 +- .../utils/avoidance/utils.hpp | 10 ++ .../avoidance/avoidance_module.cpp | 66 ++++++--- .../src/scene_module/avoidance/manager.cpp | 12 +- .../src/utils/avoidance/utils.cpp | 140 ++++++++++++++++++ 6 files changed, 228 insertions(+), 24 deletions(-) diff --git a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml index b0f736916ebda..96b6ca452bbcc 100644 --- a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml +++ b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml @@ -191,11 +191,18 @@ # avoidance distance parameters longitudinal: prepare_time: 2.0 # [s] - remain_buffer_distance: 30.0 # [m] min_prepare_distance: 1.0 # [m] min_slow_down_speed: 1.38 # [m/s] buf_slow_down_speed: 0.56 # [m/s] nominal_avoidance_speed: 8.33 # [m/s] + # return dead line + return_dead_line: + goal: + enable: true # [-] + buffer: 30.0 # [m] + traffic_light: + enable: true # [-] + buffer: 3.0 # [m] # For yield maneuver yield: 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 7976399a7ed40..c8b87c7b4759f 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 @@ -112,6 +112,14 @@ struct AvoidanceParameters // use intersection area for avoidance bool use_intersection_areas{false}; + // consider avoidance return dead line + bool enable_dead_line_for_goal{false}; + bool enable_dead_line_for_traffic_light{false}; + + // module try to return original path to keep this distance from edge point of the path. + double dead_line_buffer_for_goal{0.0}; + double dead_line_buffer_for_traffic_light{0.0}; + // max deceleration for double max_deceleration{0.0}; @@ -217,9 +225,6 @@ struct AvoidanceParameters // nominal avoidance sped double nominal_avoidance_speed{0.0}; - // module try to return original path to keep this distance from edge point of the path. - double remain_buffer_distance{0.0}; - // The margin is configured so that the generated avoidance trajectory does not come near to the // road shoulder. double soft_road_shoulder_margin{1.0}; @@ -517,6 +522,10 @@ struct AvoidancePlanningData bool found_avoidance_path{false}; double to_stop_line{std::numeric_limits::max()}; + + double to_start_point{std::numeric_limits::lowest()}; + + double to_return_point{std::numeric_limits::max()}; }; /* diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp index b8b4efb7aed57..2e04935e37336 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp @@ -172,6 +172,16 @@ std::pair separateObjectsByPath( DrivableLanes generateExpandDrivableLanes( const lanelet::ConstLanelet & lanelet, const std::shared_ptr & planner_data, const std::shared_ptr & parameters); + +double calcDistanceToReturnDeadLine( + const lanelet::ConstLanelets & lanelets, const PathWithLaneId & path, + const std::shared_ptr & planner_data, + const std::shared_ptr & parameters); + +double calcDistanceToAvoidStartLine( + const lanelet::ConstLanelets & lanelets, const PathWithLaneId & path, + const std::shared_ptr & planner_data, + const std::shared_ptr & parameters); } // namespace behavior_path_planner::utils::avoidance #endif // BEHAVIOR_PATH_PLANNER__UTILS__AVOIDANCE__UTILS_HPP_ 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 5423cff11bfeb..9e4a3a928c4ca 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 @@ -288,6 +288,12 @@ void AvoidanceModule::fillFundamentalData(AvoidancePlanningData & data, DebugDat data.reference_path, 0, data.reference_path.points.size(), calcSignedArcLength(data.reference_path.points, getEgoPosition(), 0)); + data.to_return_point = utils::avoidance::calcDistanceToReturnDeadLine( + data.current_lanelets, data.reference_path_rough, planner_data_, parameters_); + + data.to_start_point = utils::avoidance::calcDistanceToAvoidStartLine( + data.current_lanelets, data.reference_path_rough, planner_data_, parameters_); + // target objects for avoidance fillAvoidanceTargetObjects(data, debug); @@ -1066,18 +1072,35 @@ AvoidOutlines AvoidanceModule::generateAvoidOutline( : 0.0; const auto offset = object_parameter.safety_buffer_longitudinal + additional_buffer_longitudinal; + const auto to_shift_end = o.longitudinal - offset; const auto path_front_to_ego = avoid_data_.arclength_from_ego.at(avoid_data_.ego_closest_path_index); - al_avoid.start_longitudinal = - std::max(o.longitudinal - offset - feasible_avoid_distance, 1e-3); + // start point (use previous linear shift length as start shift length.) + al_avoid.start_longitudinal = [&]() { + const auto nearest_avoid_distance = std::max(to_shift_end - feasible_avoid_distance, 1e-3); + + if (data.to_start_point > to_shift_end) { + return nearest_avoid_distance; + } + + const auto minimum_avoid_distance = + helper_.getMinAvoidanceDistance(feasible_shift_length.get() - current_ego_shift); + const auto furthest_avoid_distance = std::max(to_shift_end - minimum_avoid_distance, 1e-3); + + return std::clamp(data.to_start_point, nearest_avoid_distance, furthest_avoid_distance); + }(); + al_avoid.start_idx = utils::avoidance::findPathIndexFromArclength( avoid_data_.arclength_from_ego, al_avoid.start_longitudinal + path_front_to_ego); al_avoid.start = avoid_data_.reference_path.points.at(al_avoid.start_idx).point.pose; al_avoid.start_shift_length = helper_.getLinearShift(al_avoid.start.position); + // end point al_avoid.end_shift_length = feasible_shift_length.get(); - al_avoid.end_longitudinal = o.longitudinal - offset; + al_avoid.end_longitudinal = to_shift_end; + + // misc al_avoid.id = getOriginalShiftLineUniqueId(); al_avoid.object = o; al_avoid.object_on_right = utils::avoidance::isOnRight(o); @@ -1086,18 +1109,24 @@ AvoidOutlines AvoidanceModule::generateAvoidOutline( AvoidLine al_return; { const auto offset = object_parameter.safety_buffer_longitudinal + base_link2rear + o.length; - // The end_margin also has the purpose of preventing the return path from NOT being - // triggered at the end point. - const auto return_remaining_distance = std::max( - data.arclength_from_ego.back() - o.longitudinal - offset - - parameters_->remain_buffer_distance, - 0.0); + const auto to_shift_start = o.longitudinal + offset; + // start point al_return.start_shift_length = feasible_shift_length.get(); + al_return.start_longitudinal = to_shift_start; + + // end point + al_return.end_longitudinal = [&]() { + if (data.to_return_point > to_shift_start) { + return std::clamp( + data.to_return_point, to_shift_start, feasible_return_distance + to_shift_start); + } + + return to_shift_start + feasible_return_distance; + }(); al_return.end_shift_length = 0.0; - al_return.start_longitudinal = o.longitudinal + offset; - al_return.end_longitudinal = - o.longitudinal + offset + std::min(feasible_return_distance, return_remaining_distance); + + // misc al_return.id = getOriginalShiftLineUniqueId(); al_return.object = o; al_return.object_on_right = utils::avoidance::isOnRight(o); @@ -1795,7 +1824,9 @@ AvoidLineArray AvoidanceModule::addReturnShiftLine( return ret; } - const auto remaining_distance = arclength_from_ego.back() - parameters_->remain_buffer_distance; + const auto remaining_distance = std::min( + arclength_from_ego.back() - parameters_->dead_line_buffer_for_goal, + avoid_data_.to_return_point); // If the avoidance point has already been set, the return shift must be set after the point. const auto last_sl_distance = avoid_data_.arclength_from_ego.at(last_sl.end_idx); @@ -2859,8 +2890,8 @@ void AvoidanceModule::insertReturnDeadLine( { const auto & data = avoid_data_; - if (!planner_data_->route_handler->isInGoalRouteSection(data.current_lanelets.back())) { - RCLCPP_DEBUG(getLogger(), "goal is far enough."); + if (data.to_return_point > planner_data_->parameters.forward_path_length) { + RCLCPP_DEBUG(getLogger(), "return dead line is far enough."); return; } @@ -2872,10 +2903,7 @@ void AvoidanceModule::insertReturnDeadLine( } const auto min_return_distance = helper_.getMinAvoidanceDistance(shift_length); - - const auto to_goal = calcSignedArcLength( - shifted_path.path.points, getEgoPosition(), shifted_path.path.points.size() - 1); - const auto to_stop_line = to_goal - min_return_distance - parameters_->remain_buffer_distance; + const auto to_stop_line = data.to_return_point - min_return_distance; // If we don't need to consider deceleration constraints, insert a deceleration point // and return immediately 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 33c6982f99fd9..6ed67fc817f28 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp @@ -223,13 +223,23 @@ AvoidanceModuleManager::AvoidanceModuleManager( std::string ns = "avoidance.avoidance.longitudinal."; p.prepare_time = getOrDeclareParameter(*node, ns + "prepare_time"); p.min_prepare_distance = getOrDeclareParameter(*node, ns + "min_prepare_distance"); - p.remain_buffer_distance = getOrDeclareParameter(*node, ns + "remain_buffer_distance"); p.min_slow_down_speed = getOrDeclareParameter(*node, ns + "min_slow_down_speed"); p.buf_slow_down_speed = getOrDeclareParameter(*node, ns + "buf_slow_down_speed"); p.nominal_avoidance_speed = getOrDeclareParameter(*node, ns + "nominal_avoidance_speed"); } + // avoidance maneuver (return shift dead line) + { + std::string ns = "avoidance.avoidance.return_dead_line."; + p.enable_dead_line_for_goal = getOrDeclareParameter(*node, ns + "goal.enable"); + p.enable_dead_line_for_traffic_light = + getOrDeclareParameter(*node, ns + "traffic_light.enable"); + p.dead_line_buffer_for_goal = getOrDeclareParameter(*node, ns + "goal.buffer"); + p.dead_line_buffer_for_traffic_light = + getOrDeclareParameter(*node, ns + "traffic_light.buffer"); + } + // yield { std::string ns = "avoidance.yield."; diff --git a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp index 2e441907b6d19..f1bbb3bc28a36 100644 --- a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp +++ b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp @@ -48,6 +48,7 @@ namespace behavior_path_planner::utils::avoidance { +using autoware_perception_msgs::msg::TrafficSignalElement; using motion_utils::calcLongitudinalOffsetPoint; using motion_utils::calcSignedArcLength; using motion_utils::findNearestIndex; @@ -225,6 +226,86 @@ void pushUniqueVector(T & base_vector, const T & additional_vector) { base_vector.insert(base_vector.end(), additional_vector.begin(), additional_vector.end()); } + +bool hasTrafficLightCircleColor(const TrafficSignal & tl_state, const uint8_t & lamp_color) +{ + const auto it_lamp = + std::find_if(tl_state.elements.begin(), tl_state.elements.end(), [&lamp_color](const auto & x) { + return x.shape == TrafficSignalElement::CIRCLE && x.color == lamp_color; + }); + + return it_lamp != tl_state.elements.end(); +} + +bool hasTrafficLightShape(const TrafficSignal & tl_state, const uint8_t & lamp_shape) +{ + const auto it_lamp = std::find_if( + tl_state.elements.begin(), tl_state.elements.end(), + [&lamp_shape](const auto & x) { return x.shape == lamp_shape; }); + + return it_lamp != tl_state.elements.end(); +} + +bool isTrafficSignalStop(const lanelet::ConstLanelet & lanelet, const TrafficSignal & tl_state) +{ + if (hasTrafficLightCircleColor(tl_state, TrafficSignalElement::GREEN)) { + return false; + } + + if (hasTrafficLightCircleColor(tl_state, TrafficSignalElement::UNKNOWN)) { + return false; + } + + const std::string turn_direction = lanelet.attributeOr("turn_direction", "else"); + + if (turn_direction == "else") { + return true; + } + if ( + turn_direction == "right" && + hasTrafficLightShape(tl_state, TrafficSignalElement::RIGHT_ARROW)) { + return false; + } + if ( + turn_direction == "left" && hasTrafficLightShape(tl_state, TrafficSignalElement::LEFT_ARROW)) { + return false; + } + if ( + turn_direction == "straight" && + hasTrafficLightShape(tl_state, TrafficSignalElement::UP_ARROW)) { + return false; + } + + return true; +} + +std::optional calcDistanceToRedTrafficLight( + const lanelet::ConstLanelets & lanelets, const PathWithLaneId & path, + const std::shared_ptr & planner_data) +{ + for (const auto & lanelet : lanelets) { + for (const auto & element : lanelet.regulatoryElementsAs()) { + const auto traffic_signal_stamped = planner_data->getTrafficSignal(element->id()); + if (!traffic_signal_stamped.has_value()) { + continue; + } + + if (!isTrafficSignalStop(lanelet, traffic_signal_stamped.value().signal)) { + continue; + } + + const auto & ego_pos = planner_data->self_odometry->pose.pose.position; + lanelet::ConstLineString3d stop_line = *(element->stopLine()); + const auto x = 0.5 * (stop_line.front().x() + stop_line.back().x()); + const auto y = 0.5 * (stop_line.front().y() + stop_line.back().y()); + const auto z = 0.5 * (stop_line.front().z() + stop_line.back().z()); + + return calcSignedArcLength(path.points, ego_pos, tier4_autoware_utils::createPoint(x, y, z)); + } + } + + return std::nullopt; +} } // namespace bool isOnRight(const ObjectData & obj) @@ -1902,4 +1983,63 @@ DrivableLanes generateExpandDrivableLanes( return current_drivable_lanes; } + +double calcDistanceToAvoidStartLine( + const lanelet::ConstLanelets & lanelets, const PathWithLaneId & path, + const std::shared_ptr & planner_data, + const std::shared_ptr & parameters) +{ + if (lanelets.empty()) { + return std::numeric_limits::lowest(); + } + + double distance_to_return_dead_line = std::numeric_limits::lowest(); + + // dead line stop factor(traffic light) + if (parameters->enable_dead_line_for_traffic_light) { + const auto to_traffic_light = calcDistanceToRedTrafficLight(lanelets, path, planner_data); + if (to_traffic_light.has_value()) { + distance_to_return_dead_line = std::max( + distance_to_return_dead_line, + to_traffic_light.value() + parameters->dead_line_buffer_for_traffic_light); + } + } + + return distance_to_return_dead_line; +} + +double calcDistanceToReturnDeadLine( + const lanelet::ConstLanelets & lanelets, const PathWithLaneId & path, + const std::shared_ptr & planner_data, + const std::shared_ptr & parameters) +{ + if (lanelets.empty()) { + return std::numeric_limits::max(); + } + + double distance_to_return_dead_line = std::numeric_limits::max(); + + // dead line stop factor(traffic light) + if (parameters->enable_dead_line_for_traffic_light) { + const auto to_traffic_light = calcDistanceToRedTrafficLight(lanelets, path, planner_data); + if (to_traffic_light.has_value()) { + distance_to_return_dead_line = std::min( + distance_to_return_dead_line, + to_traffic_light.value() - parameters->dead_line_buffer_for_traffic_light); + } + } + + // dead line for goal + if (parameters->enable_dead_line_for_goal) { + if (planner_data->route_handler->isInGoalRouteSection(lanelets.back())) { + const auto & ego_pos = planner_data->self_odometry->pose.pose.position; + const auto to_goal_distance = + calcSignedArcLength(path.points, ego_pos, path.points.size() - 1); + distance_to_return_dead_line = std::min( + distance_to_return_dead_line, to_goal_distance - parameters->dead_line_buffer_for_goal); + } + } + + return distance_to_return_dead_line; +} } // namespace behavior_path_planner::utils::avoidance From a2b114da5f16d097b45128e29a4f94a325967030 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Tue, 31 Oct 2023 23:12:42 +0900 Subject: [PATCH 100/202] feat(map_based_prediciton): use orientation reliability in prediction (#5435) * replace object yaw with lanelets yaw when object orientation is unavailable Signed-off-by: yoshiri * fix unintended behavior: add escape and move replace state before path generation Signed-off-by: yoshiri * Update perception/map_based_prediction/src/map_based_prediction_node.cpp Co-authored-by: Kyoichi Sugahara --------- Signed-off-by: yoshiri Co-authored-by: Kyoichi Sugahara --- .../src/map_based_prediction_node.cpp | 38 ++++++++++++++++++- 1 file changed, 36 insertions(+), 2 deletions(-) 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 08fc06330b1d8..2ceb22fd6e7b9 100644 --- a/perception/map_based_prediction/src/map_based_prediction_node.cpp +++ b/perception/map_based_prediction/src/map_based_prediction_node.cpp @@ -687,6 +687,32 @@ lanelet::Lanelets getLeftOppositeLanelets( return opposite_lanelets; } + +void replaceObjectYawWithLaneletsYaw( + const LaneletsData & current_lanelets, TrackedObject & transformed_object) +{ + // return if no lanelet is found + if (current_lanelets.empty()) return; + auto & pose_with_cov = transformed_object.kinematics.pose_with_covariance; + // for each lanelet, calc lanelet angle and calculate mean angle + double sum_x = 0.0; + double sum_y = 0.0; + for (const auto & current_lanelet : current_lanelets) { + const auto lanelet_angle = + lanelet::utils::getLaneletAngle(current_lanelet.lanelet, pose_with_cov.pose.position); + sum_x += std::cos(lanelet_angle); + sum_y += std::sin(lanelet_angle); + } + const double mean_yaw_angle = std::atan2(sum_y, sum_x); + double roll, pitch, yaw; + tf2::Quaternion original_quaternion; + tf2::fromMsg(pose_with_cov.pose.orientation, original_quaternion); + tf2::Matrix3x3(original_quaternion).getRPY(roll, pitch, yaw); + tf2::Quaternion filtered_quaternion; + filtered_quaternion.setRPY(roll, pitch, mean_yaw_angle); + pose_with_cov.pose.orientation = tf2::toMsg(filtered_quaternion); +} + } // namespace MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_options) @@ -929,11 +955,19 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt getDebugMarker(object, max_prob_path->maneuver, debug_markers.markers.size()); debug_markers.markers.push_back(debug_marker); + // Fix object angle if its orientation unreliable (e.g. far object by radar sensor) + // This prevent bending predicted path + TrackedObject yaw_fixed_transformed_object = transformed_object; + if ( + transformed_object.kinematics.orientation_availability == + autoware_auto_perception_msgs::msg::TrackedObjectKinematics::UNAVAILABLE) { + replaceObjectYawWithLaneletsYaw(current_lanelets, yaw_fixed_transformed_object); + } // Generate Predicted Path std::vector predicted_paths; for (const auto & ref_path : ref_paths) { - PredictedPath predicted_path = - path_generator_->generatePathForOnLaneVehicle(transformed_object, ref_path.path); + PredictedPath predicted_path = path_generator_->generatePathForOnLaneVehicle( + yaw_fixed_transformed_object, ref_path.path); if (predicted_path.path.empty()) { continue; } From 17b02d34759edf1ea8f36efa2da5db75beef18e5 Mon Sep 17 00:00:00 2001 From: Takeshi Miura Date: Wed, 1 Nov 2023 13:22:39 +0900 Subject: [PATCH 101/202] feat(vehicle_cmd_gate): improve debug marker activation (#5426) * feat(vehicle_cmd_gate): improve filter marker logic Signed-off-by: 1222-takeshi * feat: update filtered logic Signed-off-by: 1222-takeshi * chore: update README.md Signed-off-by: 1222-takeshi * feat: update parameter Signed-off-by: 1222-takeshi * feat: add condition for filtering marker Signed-off-by: 1222-takeshi * refactor: add publishMarker function Signed-off-by: 1222-takeshi --------- Signed-off-by: 1222-takeshi --- control/vehicle_cmd_gate/README.md | 2 ++ .../config/vehicle_cmd_gate.param.yaml | 2 ++ .../vehicle_cmd_gate/src/vehicle_cmd_gate.cpp | 31 ++++++++++++++++++- .../vehicle_cmd_gate/src/vehicle_cmd_gate.hpp | 8 +++++ 4 files changed, 42 insertions(+), 1 deletion(-) diff --git a/control/vehicle_cmd_gate/README.md b/control/vehicle_cmd_gate/README.md index 231c2c5022138..6ec2da84a7b6c 100644 --- a/control/vehicle_cmd_gate/README.md +++ b/control/vehicle_cmd_gate/README.md @@ -50,6 +50,8 @@ | `check_external_emergency_heartbeat` | bool | true when checking heartbeat for emergency stop | | `system_emergency_heartbeat_timeout` | double | timeout for system emergency | | `external_emergency_stop_heartbeat_timeout` | double | timeout for external emergency | +| `filter_activated_count_threshold` | int | threshold for filter activation | +| `filter_activated_velocity_threshold` | double | velocity threshold for filter activation | | `stop_hold_acceleration` | double | longitudinal acceleration cmd when vehicle should stop | | `emergency_acceleration` | double | longitudinal acceleration cmd when vehicle stop with emergency | | `moderate_stop_service_acceleration` | double | longitudinal acceleration cmd when vehicle stop with moderate stop service | diff --git a/control/vehicle_cmd_gate/config/vehicle_cmd_gate.param.yaml b/control/vehicle_cmd_gate/config/vehicle_cmd_gate.param.yaml index 191e894622af7..7ad685217f13d 100644 --- a/control/vehicle_cmd_gate/config/vehicle_cmd_gate.param.yaml +++ b/control/vehicle_cmd_gate/config/vehicle_cmd_gate.param.yaml @@ -6,6 +6,8 @@ check_external_emergency_heartbeat: false use_start_request: false enable_cmd_limit_filter: true + filter_activated_count_threshold: 5 + filter_activated_velocity_threshold: 1.0 external_emergency_stop_heartbeat_timeout: 0.0 stop_hold_acceleration: -1.5 emergency_acceleration: -2.4 diff --git a/control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp b/control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp index e681bc22cd24b..1bed4ee67f412 100644 --- a/control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp +++ b/control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp @@ -77,6 +77,10 @@ VehicleCmdGate::VehicleCmdGate(const rclcpp::NodeOptions & node_options) create_publisher("~/is_filter_activated", durable_qos); filter_activated_marker_pub_ = create_publisher("~/is_filter_activated/marker", durable_qos); + filter_activated_marker_raw_pub_ = + create_publisher("~/is_filter_activated/marker_raw", durable_qos); + filter_activated_flag_pub_ = + create_publisher("~/is_filter_activated/flag", durable_qos); // Subscriber external_emergency_stop_heartbeat_sub_ = create_subscription( @@ -160,6 +164,9 @@ VehicleCmdGate::VehicleCmdGate(const rclcpp::NodeOptions & node_options) declare_parameter("moderate_stop_service_acceleration"); stop_check_duration_ = declare_parameter("stop_check_duration"); enable_cmd_limit_filter_ = declare_parameter("enable_cmd_limit_filter"); + filter_activated_count_threshold_ = declare_parameter("filter_activated_count_threshold"); + filter_activated_velocity_threshold_ = + declare_parameter("filter_activated_velocity_threshold"); // Vehicle Parameter const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo(); @@ -572,7 +579,7 @@ AckermannControlCommand VehicleCmdGate::filterControlCommand(const AckermannCont is_filter_activated.stamp = now(); is_filter_activated_pub_->publish(is_filter_activated); - filter_activated_marker_pub_->publish(createMarkerArray(is_filter_activated)); + publishMarkers(is_filter_activated); return out; } @@ -787,6 +794,28 @@ MarkerArray VehicleCmdGate::createMarkerArray(const IsFilterActivated & filter_a return msg; } +void VehicleCmdGate::publishMarkers(const IsFilterActivated & filter_activated) +{ + BoolStamped filter_activated_flag; + if (filter_activated.is_activated) { + filter_activated_count_++; + } else { + filter_activated_count_ = 0; + } + if ( + filter_activated_count_ >= filter_activated_count_threshold_ && + std::fabs(current_kinematics_.twist.twist.linear.x) >= filter_activated_velocity_threshold_ && + current_operation_mode_.mode == OperationModeState::AUTONOMOUS) { + filter_activated_marker_pub_->publish(createMarkerArray(filter_activated)); + filter_activated_flag.data = true; + } else { + filter_activated_flag.data = false; + } + + filter_activated_flag.stamp = now(); + filter_activated_flag_pub_->publish(filter_activated_flag); + filter_activated_marker_raw_pub_->publish(createMarkerArray(filter_activated)); +} } // namespace vehicle_cmd_gate #include diff --git a/control/vehicle_cmd_gate/src/vehicle_cmd_gate.hpp b/control/vehicle_cmd_gate/src/vehicle_cmd_gate.hpp index 8f0a6aa14d08b..c36aab240ae79 100644 --- a/control/vehicle_cmd_gate/src/vehicle_cmd_gate.hpp +++ b/control/vehicle_cmd_gate/src/vehicle_cmd_gate.hpp @@ -62,6 +62,7 @@ using autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand; using geometry_msgs::msg::AccelWithCovarianceStamped; using std_srvs::srv::Trigger; using tier4_control_msgs::msg::GateMode; +using tier4_debug_msgs::msg::BoolStamped; using tier4_external_api_msgs::msg::Emergency; using tier4_external_api_msgs::msg::Heartbeat; using tier4_external_api_msgs::srv::SetEmergency; @@ -106,6 +107,8 @@ class VehicleCmdGate : public rclcpp::Node rclcpp::Publisher::SharedPtr operation_mode_pub_; rclcpp::Publisher::SharedPtr is_filter_activated_pub_; rclcpp::Publisher::SharedPtr filter_activated_marker_pub_; + rclcpp::Publisher::SharedPtr filter_activated_marker_raw_pub_; + rclcpp::Publisher::SharedPtr filter_activated_flag_pub_; // Subscription rclcpp::Subscription::SharedPtr external_emergency_stop_heartbeat_sub_; @@ -123,11 +126,13 @@ class VehicleCmdGate : public rclcpp::Node bool is_engaged_; bool is_system_emergency_ = false; bool is_external_emergency_stop_ = false; + bool is_filtered_marker_published_ = false; double current_steer_ = 0; GateMode current_gate_mode_; MrmState current_mrm_state_; Odometry current_kinematics_; double current_acceleration_ = 0.0; + int filter_activated_count_ = 0; // Heartbeat std::shared_ptr emergency_state_heartbeat_received_time_; @@ -172,6 +177,8 @@ class VehicleCmdGate : public rclcpp::Node double emergency_acceleration_; double moderate_stop_service_acceleration_; bool enable_cmd_limit_filter_; + int filter_activated_count_threshold_; + double filter_activated_velocity_threshold_; // Service rclcpp::Service::SharedPtr srv_engage_; @@ -236,6 +243,7 @@ class VehicleCmdGate : public rclcpp::Node // debug MarkerArray createMarkerArray(const IsFilterActivated & filter_activated); + void publishMarkers(const IsFilterActivated & filter_activated); std::unique_ptr logger_configure_; }; From 75f7357e78a1300f78d01fd2f3d7772416c9fd97 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Wed, 1 Nov 2023 19:21:41 +0900 Subject: [PATCH 102/202] fix(pid_longitudinal_control): not check steering convergence when moving (#5456) Signed-off-by: Takamasa Horibe --- .../src/pid_longitudinal_controller.cpp | 11 +++++++---- 1 file changed, 7 insertions(+), 4 deletions(-) diff --git a/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp b/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp index a134fd775155b..d13e628f2e1d4 100644 --- a/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp +++ b/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp @@ -497,8 +497,13 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d stop_dist > p.drive_state_stop_dist + p.drive_state_offset_stop_dist; const bool departure_condition_from_stopped = stop_dist > p.drive_state_stop_dist; - const bool keep_stopped_condition = - m_enable_keep_stopped_until_steer_convergence && !lateral_sync_data_.is_steer_converged; + // NOTE: the same velocity threshold as motion_utils::searchZeroVelocity + static constexpr double vel_epsilon = 1e-3; + + // Let vehicle start after the steering is converged for control accuracy + const bool keep_stopped_condition = std::fabs(current_vel) < vel_epsilon && + m_enable_keep_stopped_until_steer_convergence && + !lateral_sync_data_.is_steer_converged; const bool stopping_condition = stop_dist < p.stopping_state_stop_dist; @@ -528,8 +533,6 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d ? (clock_->now() - *m_last_running_time).seconds() > p.stopped_state_entry_duration_time : false; - static constexpr double vel_epsilon = - 1e-3; // NOTE: the same velocity threshold as motion_utils::searchZeroVelocity const double current_vel_cmd = std::fabs(m_trajectory.points.at(control_data.nearest_idx).longitudinal_velocity_mps); const bool emergency_condition = m_enable_overshoot_emergency && From 64e2ab33dfcfd8a32dc76fe9de0396209a0f5c41 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Wed, 1 Nov 2023 20:55:46 +0900 Subject: [PATCH 103/202] feat(system_diagnostic_graph): unify units and add file path substitution (#5447) Signed-off-by: Takagi, Isamu --- system/system_diagnostic_graph/CMakeLists.txt | 18 +- .../example/example_0.yaml | 25 +- .../example/example_1.yaml | 12 +- .../example/example_2.yaml | 4 +- system/system_diagnostic_graph/package.xml | 1 + .../src/core/config.cpp | 316 ++++++++++-------- .../src/core/config.hpp | 108 +++--- .../src/core/debug.cpp | 27 +- .../src/core/error.hpp | 65 ++++ .../src/core/exprs.cpp | 216 ------------ .../src/core/exprs.hpp | 104 ------ .../src/core/graph.cpp | 166 ++++----- .../src/core/graph.hpp | 15 +- .../src/core/modes.cpp | 15 +- .../src/core/modes.hpp | 16 +- .../src/core/nodes.cpp | 157 --------- .../src/core/nodes.hpp | 114 ------- .../src/core/types.hpp | 9 +- .../src/core/units.cpp | 164 +++++++++ .../src/core/units.hpp | 119 +++++++ system/system_diagnostic_graph/src/main.cpp | 6 +- .../test/files/field-not-found.yaml | 2 + .../test/files/file-not-found.yaml | 2 + .../test/files/graph-circulation.yaml | 9 + .../test/files/invalid-dict-type.yaml | 1 + .../test/files/invalid-list-type.yaml | 3 + .../test/files/path-conflict.yaml | 5 + .../test/files/path-not-found.yaml | 5 + .../test/files/unknown-node-type.yaml | 2 + .../test/files/unknown-substitution.yaml | 2 + .../system_diagnostic_graph/test/src/test.cpp | 88 +++++ system/system_diagnostic_graph/util/debug.py | 85 ----- 32 files changed, 848 insertions(+), 1033 deletions(-) create mode 100644 system/system_diagnostic_graph/src/core/error.hpp delete mode 100644 system/system_diagnostic_graph/src/core/exprs.cpp delete mode 100644 system/system_diagnostic_graph/src/core/exprs.hpp delete mode 100644 system/system_diagnostic_graph/src/core/nodes.cpp delete mode 100644 system/system_diagnostic_graph/src/core/nodes.hpp create mode 100644 system/system_diagnostic_graph/src/core/units.cpp create mode 100644 system/system_diagnostic_graph/src/core/units.hpp create mode 100644 system/system_diagnostic_graph/test/files/field-not-found.yaml create mode 100644 system/system_diagnostic_graph/test/files/file-not-found.yaml create mode 100644 system/system_diagnostic_graph/test/files/graph-circulation.yaml create mode 100644 system/system_diagnostic_graph/test/files/invalid-dict-type.yaml create mode 100644 system/system_diagnostic_graph/test/files/invalid-list-type.yaml create mode 100644 system/system_diagnostic_graph/test/files/path-conflict.yaml create mode 100644 system/system_diagnostic_graph/test/files/path-not-found.yaml create mode 100644 system/system_diagnostic_graph/test/files/unknown-node-type.yaml create mode 100644 system/system_diagnostic_graph/test/files/unknown-substitution.yaml create mode 100644 system/system_diagnostic_graph/test/src/test.cpp delete mode 100755 system/system_diagnostic_graph/util/debug.py diff --git a/system/system_diagnostic_graph/CMakeLists.txt b/system/system_diagnostic_graph/CMakeLists.txt index 81d8ba39b3d1b..142aa94eeef69 100644 --- a/system/system_diagnostic_graph/CMakeLists.txt +++ b/system/system_diagnostic_graph/CMakeLists.txt @@ -4,13 +4,15 @@ project(system_diagnostic_graph) find_package(autoware_cmake REQUIRED) autoware_package() -ament_auto_add_executable(aggregator +ament_auto_add_library(${PROJECT_NAME} SHARED src/core/config.cpp src/core/debug.cpp src/core/graph.cpp - src/core/nodes.cpp - src/core/exprs.cpp + src/core/units.cpp src/core/modes.cpp +) + +ament_auto_add_executable(aggregator src/main.cpp ) @@ -18,9 +20,11 @@ ament_auto_add_executable(converter src/tool.cpp ) -install( - PROGRAMS util/debug.py - DESTINATION lib/${PROJECT_NAME} -) +if(BUILD_TESTING) + get_filename_component(RESOURCE_PATH ${CMAKE_CURRENT_SOURCE_DIR}/test/files ABSOLUTE) + ament_auto_add_gtest(gtest_${PROJECT_NAME} test/src/test.cpp) + target_compile_definitions(gtest_${PROJECT_NAME} PRIVATE TEST_RESOURCE_PATH="${RESOURCE_PATH}") + target_include_directories(gtest_${PROJECT_NAME} PRIVATE src) +endif() ament_auto_package(INSTALL_TO_SHARE config example launch) diff --git a/system/system_diagnostic_graph/example/example_0.yaml b/system/system_diagnostic_graph/example/example_0.yaml index 0ee6e59c8e121..fc4436bba1595 100644 --- a/system/system_diagnostic_graph/example/example_0.yaml +++ b/system/system_diagnostic_graph/example/example_0.yaml @@ -1,32 +1,37 @@ files: - - { package: system_diagnostic_graph, path: example/example_1.yaml } - - { package: system_diagnostic_graph, path: example/example_2.yaml } + - { path: $(find-pkg-share system_diagnostic_graph)/example/example_1.yaml } + - { path: $(find-pkg-share system_diagnostic_graph)/example/example_2.yaml } nodes: - path: /autoware/modes/stop - type: debug-ok + type: ok - path: /autoware/modes/autonomous type: and list: - - { type: link, path: /functions/pose_estimation } - - { type: link, path: /functions/obstacle_detection } + - { type: link, link: /functions/pose_estimation } + - { type: link, link: /functions/obstacle_detection } - path: /autoware/modes/local type: and list: - - { type: link, path: /external/joystick_command } + - { type: link, link: /external/joystick_command } - path: /autoware/modes/remote type: and list: - - { type: link, path: /external/remote_command } + - { type: link, link: /external/remote_command } - path: /autoware/modes/emergency-stop - type: debug-ok + type: ok - path: /autoware/modes/comfortable-stop - type: debug-ok + type: and + list: + - { type: link, link: /functions/obstacle_detection } - path: /autoware/modes/pull-over - type: debug-ok + type: and + list: + - { type: link, link: /functions/pose_estimation } + - { type: link, link: /functions/obstacle_detection } diff --git a/system/system_diagnostic_graph/example/example_1.yaml b/system/system_diagnostic_graph/example/example_1.yaml index 5ba93ec3059e4..07d4951b89446 100644 --- a/system/system_diagnostic_graph/example/example_1.yaml +++ b/system/system_diagnostic_graph/example/example_1.yaml @@ -2,22 +2,22 @@ nodes: - path: /functions/pose_estimation type: and list: - - { type: link, path: /sensing/lidars/top } + - { type: link, link: /sensing/lidars/top } - path: /functions/obstacle_detection type: or list: - - { type: link, path: /sensing/lidars/front } - - { type: link, path: /sensing/radars/front } + - { type: link, link: /sensing/lidars/front } + - { type: link, link: /sensing/radars/front } - path: /sensing/lidars/top type: diag - name: "lidar_driver/top: status" + diag: "lidar_driver/top: status" - path: /sensing/lidars/front type: diag - name: "lidar_driver/front: status" + diag: "lidar_driver/front: status" - path: /sensing/radars/front type: diag - name: "radar_driver/front: status" + diag: "radar_driver/front: status" diff --git a/system/system_diagnostic_graph/example/example_2.yaml b/system/system_diagnostic_graph/example/example_2.yaml index f61f4accbfec8..a03701b661ba9 100644 --- a/system/system_diagnostic_graph/example/example_2.yaml +++ b/system/system_diagnostic_graph/example/example_2.yaml @@ -1,8 +1,8 @@ nodes: - path: /external/joystick_command type: diag - name: "external_command_checker: joystick_command" + diag: "external_command_checker: joystick_command" - path: /external/remote_command type: diag - name: "external_command_checker: remote_command" + diag: "external_command_checker: remote_command" diff --git a/system/system_diagnostic_graph/package.xml b/system/system_diagnostic_graph/package.xml index ffc0c6c7d5385..7855edcde9c62 100644 --- a/system/system_diagnostic_graph/package.xml +++ b/system/system_diagnostic_graph/package.xml @@ -15,6 +15,7 @@ tier4_system_msgs yaml_cpp_vendor + ament_cmake_gtest ament_lint_auto autoware_lint_common diff --git a/system/system_diagnostic_graph/src/core/config.cpp b/system/system_diagnostic_graph/src/core/config.cpp index 305860af32840..2339e96f3951f 100644 --- a/system/system_diagnostic_graph/src/core/config.cpp +++ b/system/system_diagnostic_graph/src/core/config.cpp @@ -14,11 +14,15 @@ #include "config.hpp" +#include "error.hpp" + #include #include #include +#include #include +#include #include // DEBUG @@ -27,235 +31,265 @@ namespace system_diagnostic_graph { -ErrorMarker::ErrorMarker(const std::string & file) +template +void extend(std::vector & u, const std::vector & v) { - file_ = file; + u.insert(u.end(), v.begin(), v.end()); } -std::string ErrorMarker::str() const +template +auto enumerate(const std::vector & v) { - if (type_.empty()) { - return file_; - } - - std::string result = type_; - for (const auto & index : indices_) { - result += "-" + std::to_string(index); + std::vector> result; + for (size_t i = 0; i < v.size(); ++i) { + result.push_back(std::make_pair(i, v[i])); } - return result + " in " + file_; -} - -ErrorMarker ErrorMarker::type(const std::string & type) const -{ - ErrorMarker mark = *this; - mark.type_ = type; - return mark; + return result; } -ErrorMarker ErrorMarker::index(size_t index) const +ConfigData::ConfigData(const std::string & path) { - ErrorMarker mark = *this; - mark.indices_.push_back(index); - return mark; + file = path; } -ConfigObject::ConfigObject(const ErrorMarker & mark, YAML::Node yaml, const std::string & type) +ConfigData ConfigData::load(YAML::Node yaml) { if (!yaml.IsMap()) { - throw create_error(mark, type + " is not a dict type"); + throw error("object is not a dict type", *this); } for (const auto & kv : yaml) { - dict_[kv.first.as()] = kv.second; + object[kv.first.as()] = kv.second; } - mark_ = mark; - type_ = type; + return *this; } -ErrorMarker ConfigObject::mark() const +ConfigData ConfigData::type(const std::string & name) const { - return mark_; + ConfigData data(file); + data.mark = name; + return data; } -std::optional ConfigObject::take_yaml(const std::string & name) +ConfigData ConfigData::node(const size_t index) const { - if (!dict_.count(name)) { - return std::nullopt; - } - const auto yaml = dict_.at(name); - dict_.erase(name); - return yaml; + ConfigData data(file); + data.mark = mark + "-" + std::to_string(index); + return data; } -std::string ConfigObject::take_text(const std::string & name) +std::string ConfigData::take_text(const std::string & name) { - if (!dict_.count(name)) { - throw create_error(mark_, "object has no '" + name + "' field"); + if (!object.count(name)) { + throw error("required field is not found", name, *this); } - const auto yaml = dict_.at(name); - dict_.erase(name); + const auto yaml = object.at(name); + object.erase(name); return yaml.as(); } -std::string ConfigObject::take_text(const std::string & name, const std::string & fail) +std::string ConfigData::take_text(const std::string & name, const std::string & fail) { - if (!dict_.count(name)) { + if (!object.count(name)) { return fail; } - const auto yaml = dict_.at(name); - dict_.erase(name); + const auto yaml = object.at(name); + object.erase(name); return yaml.as(); } -std::vector ConfigObject::take_list(const std::string & name) +std::vector ConfigData::take_list(const std::string & name) { - if (!dict_.count(name)) { + if (!object.count(name)) { return std::vector(); } - const auto yaml = dict_.at(name); - dict_.erase(name); + const auto yaml = object.at(name); + object.erase(name); if (!yaml.IsSequence()) { - throw ConfigError("the '" + name + "' field is not a list type"); + throw error("field is not a list type", name, *this); } return std::vector(yaml.begin(), yaml.end()); } -bool ConfigFilter::check(const std::string & mode) const +void check_config_nodes(const std::vector & nodes) { - if (!excludes.empty() && excludes.count(mode) != 0) return false; - if (!includes.empty() && includes.count(mode) == 0) return false; - return true; -} + std::unordered_map path_count; + for (const auto & node : nodes) { + path_count[node->path] += 1; + } -ConfigError create_error(const ErrorMarker & mark, const std::string & message) -{ - (void)mark; - return ConfigError(message); + path_count.erase(""); + for (const auto & [path, count] : path_count) { + if (1 < count) { + throw error("object path is not unique", path); + } + } } -ConfigFilter parse_mode_filter(const ErrorMarker & mark, std::optional yaml) +void resolve_link_nodes(std::vector & nodes) { - std::unordered_set excludes; - std::unordered_set includes; - if (yaml) { - ConfigObject dict(mark, yaml.value(), "mode filter"); + std::vector filtered; + std::unordered_map links; + std::unordered_map paths; - for (const auto & mode : dict.take_list("except")) { - excludes.emplace(mode.as()); + for (const auto & node : nodes) { + links[node] = node; + paths[node->path] = node; + } + + for (const auto & node : nodes) { + if (node->type == "link" && node->path == "") { + const auto link = node->data.take_text("link"); + if (!paths.count(link)) { + throw error("link path is not found", link, node->data); + } + links[node] = paths.at(link); + } else { + filtered.push_back(node); } - for (const auto & mode : dict.take_list("only")) { - includes.emplace(mode.as()); + } + nodes = filtered; + + for (const auto & node : nodes) { + for (auto & child : node->children) { + child = links.at(child); } } - return ConfigFilter{excludes, includes}; } -FileConfig parse_file_config(const ErrorMarker & mark, YAML::Node yaml) +std::string complement_node_type(ConfigData & data) { - ConfigObject dict(mark, yaml, "file object"); - const auto relative_path = dict.take_text("path"); - const auto package_name = dict.take_text("package"); - const auto package_path = ament_index_cpp::get_package_share_directory(package_name); - return FileConfig{mark, package_path + "/" + relative_path}; + if (data.object.count("diag")) { + return "diag"; + } + return data.take_text("type"); } -NodeConfig parse_node_config(const ErrorMarker & mark, YAML::Node yaml) +std::string resolve_substitution(const std::string & substitution, const ConfigData & data) { - ConfigObject dict(mark, yaml, "node object"); - const auto path = dict.take_text("path"); - const auto mode = parse_mode_filter(dict.mark(), dict.take_yaml("mode")); - return NodeConfig{path, mode, dict}; + std::stringstream ss(substitution); + std::string word; + std::vector words; + while (getline(ss, word, ' ')) { + words.push_back(word); + } + + if (words.size() == 2 && words[0] == "find-pkg-share") { + return ament_index_cpp::get_package_share_directory(words[1]); + } + if (words.size() == 1 && words[0] == "dirname") { + return std::filesystem::path(data.file).parent_path(); + } + throw error("unknown substitution", substitution, data); } -ExprConfig parse_expr_config(const ErrorMarker & mark, YAML::Node yaml) +std::string resolve_file_path(const std::string & path, const ConfigData & data) { - ConfigObject dict(mark, yaml, "expr object"); - return parse_expr_config(dict); + static const std::regex pattern(R"(\$\(([^()]*)\))"); + std::smatch m; + std::string result = path; + while (std::regex_search(result, m, pattern)) { + const std::string prefix = m.prefix(); + const std::string suffix = m.suffix(); + result = prefix + resolve_substitution(m.str(1), data) + suffix; + } + return result; } -ExprConfig parse_expr_config(ConfigObject & dict) +PathConfig::SharedPtr parse_path_config(const ConfigData & data) { - const auto type = dict.take_text("type"); - const auto mode = parse_mode_filter(dict.mark(), dict.take_yaml("mode")); - return ExprConfig{type, mode, dict}; + const auto path = std::make_shared(data); + path->original = path->data.take_text("path"); + path->resolved = resolve_file_path(path->original, path->data); + return path; } -void dump(const ConfigFile & config) +UnitConfig::SharedPtr parse_node_config(const ConfigData & data) { - std::cout << "=================================================================" << std::endl; - std::cout << config.mark.str() << std::endl; - for (const auto & file : config.files) { - std::cout << " - f: " << file.path << " (" << file.mark.str() << ")" << std::endl; - } - for (const auto & unit : config.units) { - std::cout << " - u: " << unit.path << " (" << unit.dict.mark().str() << ")" << std::endl; + const auto node = std::make_shared(data); + node->path = node->data.take_text("path", ""); + node->type = node->data.take_text("type", ""); + + if (node->type.empty()) { + node->type = complement_node_type(node->data); } - for (const auto & diag : config.diags) { - std::cout << " - d: " << diag.path << " (" << diag.dict.mark().str() << ")" << std::endl; + + for (const auto & [index, yaml] : enumerate(node->data.take_list("list"))) { + const auto child = data.node(index).load(yaml); + node->children.push_back(parse_node_config(child)); } + return node; } -template -auto apply(const ErrorMarker & mark, F & func, const std::vector & list) +FileConfig::SharedPtr parse_file_config(const ConfigData & data) { - std::vector result; - for (size_t i = 0; i < list.size(); ++i) { - result.push_back(func(mark.index(i), list[i])); + const auto file = std::make_shared(data); + const auto path_data = data.type("file"); + const auto node_data = data.type("node"); + const auto paths = file->data.take_list("files"); + const auto nodes = file->data.take_list("nodes"); + + for (const auto & [index, yaml] : enumerate(paths)) { + const auto path = path_data.node(index).load(yaml); + file->paths.push_back(parse_path_config(path)); } - return result; + for (const auto & [index, yaml] : enumerate(nodes)) { + const auto node = node_data.node(index).load(yaml); + file->nodes.push_back(parse_node_config(node)); + } + return file; } -ConfigFile load_config_file(const FileConfig & file) +FileConfig::SharedPtr load_file_config(PathConfig & config) { - if (!std::filesystem::exists(file.path)) { - throw create_error(file.mark, "config file '" + file.path + "' does not exist"); + const auto path = std::filesystem::path(config.resolved); + if (!std::filesystem::exists(path)) { + throw error("file is not found", path, config.data); } + const auto file = ConfigData(path).load(YAML::LoadFile(path)); + return parse_file_config(file); +} - const auto yaml = YAML::LoadFile(file.path); - const auto mark = ErrorMarker(file.path); - auto dict = ConfigObject(mark, yaml, "config file"); +RootConfig load_root_config(const PathConfig::SharedPtr root) +{ + std::vector paths; + paths.push_back(root); + + std::vector files; + for (size_t i = 0; i < paths.size(); ++i) { + const auto path = paths[i]; + const auto file = load_file_config(*path); + files.push_back(file); + extend(paths, file->paths); + } - std::vector units; - std::vector diags; - for (const auto & node : dict.take_list("nodes")) { - const auto type = node["type"].as(); - if (type == "diag") { - diags.push_back(node); - } else { - units.push_back(node); - } + std::vector nodes; + for (const auto & file : files) { + extend(nodes, file->nodes); } + for (size_t i = 0; i < nodes.size(); ++i) { + const auto node = nodes[i]; + extend(nodes, node->children); + } + + check_config_nodes(nodes); + resolve_link_nodes(nodes); - ConfigFile config(mark); - config.files = apply(mark.type("file"), parse_file_config, dict.take_list("files")); - config.units = apply(mark.type("unit"), parse_node_config, units); - config.diags = apply(mark.type("diag"), parse_node_config, diags); + RootConfig config; + config.files = files; + config.nodes = nodes; return config; } -ConfigFile load_config_root(const std::string & path) +RootConfig load_root_config(const std::string & path) { - const auto mark = ErrorMarker("root file"); - std::vector configs; - configs.push_back(load_config_file(FileConfig{mark, path})); - - // Use an index because updating the vector invalidates the iterator. - for (size_t i = 0; i < configs.size(); ++i) { - for (const auto & file : configs[i].files) { - configs.push_back(load_config_file(file)); - } - } - - ConfigFile result(mark); - for (const auto & config : configs) { - result.files.insert(result.files.end(), config.files.begin(), config.files.end()); - result.units.insert(result.units.end(), config.units.begin(), config.units.end()); - result.diags.insert(result.diags.end(), config.diags.begin(), config.diags.end()); - } - return result; + const auto root = std::make_shared(ConfigData("root-file")); + root->original = path; + root->resolved = path; + return load_root_config(root); } } // namespace system_diagnostic_graph diff --git a/system/system_diagnostic_graph/src/core/config.hpp b/system/system_diagnostic_graph/src/core/config.hpp index 4d679ef575944..d959f5b6be8aa 100644 --- a/system/system_diagnostic_graph/src/core/config.hpp +++ b/system/system_diagnostic_graph/src/core/config.hpp @@ -18,94 +18,92 @@ #include #include -#include -#include #include #include -#include #include namespace system_diagnostic_graph { -struct ConfigError : public std::runtime_error +struct ConfigData { - using runtime_error::runtime_error; -}; - -class ErrorMarker -{ -public: - explicit ErrorMarker(const std::string & file = ""); - std::string str() const; - ErrorMarker type(const std::string & type) const; - ErrorMarker index(size_t index) const; - -private: - std::string file_; - std::string type_; - std::vector indices_; -}; + explicit ConfigData(const std::string & file); + ConfigData load(YAML::Node yaml); + ConfigData type(const std::string & name) const; + ConfigData node(const size_t index) const; -class ConfigObject -{ -public: - ConfigObject(const ErrorMarker & mark, YAML::Node yaml, const std::string & type); - ErrorMarker mark() const; - std::optional take_yaml(const std::string & name); std::string take_text(const std::string & name); std::string take_text(const std::string & name, const std::string & fail); std::vector take_list(const std::string & name); -private: - ErrorMarker mark_; - std::string type_; - std::unordered_map dict_; + std::string file; + std::string mark; + std::unordered_map object; }; -struct ConfigFilter +struct BaseConfig { - bool check(const std::string & mode) const; - std::unordered_set excludes; - std::unordered_set includes; + explicit BaseConfig(const ConfigData & data) : data(data) {} + ConfigData data; }; -struct ExprConfig +struct PathConfig : public BaseConfig { - std::string type; - ConfigFilter mode; - ConfigObject dict; + using SharedPtr = std::shared_ptr; + using BaseConfig::BaseConfig; + std::string original; + std::string resolved; }; -struct NodeConfig +struct UnitConfig : public BaseConfig { + using SharedPtr = std::shared_ptr; + using BaseConfig::BaseConfig; + std::string type; std::string path; - ConfigFilter mode; - ConfigObject dict; + std::vector children; }; -struct FileConfig +struct FileConfig : public BaseConfig { - ErrorMarker mark; - std::string path; + using SharedPtr = std::shared_ptr; + using BaseConfig::BaseConfig; + std::vector paths; + std::vector nodes; }; -struct ConfigFile +struct RootConfig { - explicit ConfigFile(const ErrorMarker & mark) : mark(mark) {} - ErrorMarker mark; - std::vector files; - std::vector units; - std::vector diags; + std::vector files; + std::vector nodes; }; -using ConfigDict = std::unordered_map; +template +T error(const std::string & text, const ConfigData & data) +{ + const auto hint = data.mark.empty() ? data.file : data.mark + ":" + data.file; + return T(text + " (" + hint + ")"); +} + +template +T error(const std::string & text) +{ + return T(text); +} -ConfigError create_error(const ErrorMarker & mark, const std::string & message); -ConfigFile load_config_root(const std::string & path); +template +T error(const std::string & text, const std::string & value, const ConfigData & data) +{ + return error(text + ": " + value, data); +} + +template +T error(const std::string & text, const std::string & value) +{ + return error(text + ": " + value); +} -ExprConfig parse_expr_config(const ErrorMarker & mark, YAML::Node yaml); -ExprConfig parse_expr_config(ConfigObject & dict); +RootConfig load_root_config(const std::string & path); } // namespace system_diagnostic_graph diff --git a/system/system_diagnostic_graph/src/core/debug.cpp b/system/system_diagnostic_graph/src/core/debug.cpp index ed696573521a7..f14177f4571ad 100644 --- a/system/system_diagnostic_graph/src/core/debug.cpp +++ b/system/system_diagnostic_graph/src/core/debug.cpp @@ -15,8 +15,8 @@ #include "debug.hpp" #include "graph.hpp" -#include "nodes.hpp" #include "types.hpp" +#include "units.hpp" #include #include @@ -36,7 +36,9 @@ void Graph::debug() { std::vector lines; for (const auto & node : nodes_) { - lines.push_back(node->debug()); + const auto level_name = level_names.at(node->level()); + const auto index_name = std::to_string(node->index()); + lines.push_back({"unit", index_name, level_name, node->path(), "-----"}); } std::array widths = {}; @@ -57,25 +59,4 @@ void Graph::debug() } } -DiagDebugData UnitNode::debug() const -{ - const auto level_name = level_names.at(level()); - const auto index_name = std::to_string(index()); - return {"unit", index_name, level_name, path_, "-----"}; -} - -DiagDebugData DiagNode::debug() const -{ - const auto level_name = level_names.at(level()); - const auto index_name = std::to_string(index()); - return {"diag", index_name, level_name, path_, name_}; -} - -DiagDebugData UnknownNode::debug() const -{ - const auto level_name = level_names.at(level()); - const auto index_name = std::to_string(index()); - return {"test", index_name, level_name, path_, "-----"}; -} - } // namespace system_diagnostic_graph diff --git a/system/system_diagnostic_graph/src/core/error.hpp b/system/system_diagnostic_graph/src/core/error.hpp new file mode 100644 index 0000000000000..2c10d659f2df4 --- /dev/null +++ b/system/system_diagnostic_graph/src/core/error.hpp @@ -0,0 +1,65 @@ +// Copyright 2023 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef CORE__ERROR_HPP_ +#define CORE__ERROR_HPP_ + +#include + +namespace system_diagnostic_graph +{ + +struct Exception : public std::runtime_error +{ + using runtime_error::runtime_error; +}; + +class FileNotFound : public Exception +{ + using Exception::Exception; +}; + +class UnknownType : public Exception +{ + using Exception::Exception; +}; + +class InvalidType : public Exception +{ + using Exception::Exception; +}; + +class FieldNotFound : public Exception +{ + using Exception::Exception; +}; + +class PathConflict : public Exception +{ + using Exception::Exception; +}; + +class PathNotFound : public Exception +{ + using Exception::Exception; +}; + +class GraphStructure : public Exception +{ + using Exception::Exception; +}; + +} // namespace system_diagnostic_graph + +#endif // CORE__ERROR_HPP_ diff --git a/system/system_diagnostic_graph/src/core/exprs.cpp b/system/system_diagnostic_graph/src/core/exprs.cpp deleted file mode 100644 index 22281f939cad2..0000000000000 --- a/system/system_diagnostic_graph/src/core/exprs.cpp +++ /dev/null @@ -1,216 +0,0 @@ -// Copyright 2023 The Autoware Contributors -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "exprs.hpp" - -#include "nodes.hpp" - -#include -#include -#include -#include -#include - -// DEBUG -#include - -namespace system_diagnostic_graph -{ - -using LinkStatus = std::vector>; - -void extend(LinkStatus & a, const LinkStatus & b) -{ - a.insert(a.end(), b.begin(), b.end()); -} - -void extend_false(LinkStatus & a, const LinkStatus & b) -{ - for (const auto & p : b) { - a.push_back(std::make_pair(p.first, false)); - } -} - -auto create_expr_list(ExprInit & exprs, ConfigObject & config) -{ - std::vector> result; - const auto list = config.take_list("list"); - for (size_t i = 0; i < list.size(); ++i) { - auto dict = parse_expr_config(config.mark().index(i), list[i]); - auto expr = exprs.create(dict); - if (expr) { - result.push_back(std::move(expr)); - } - } - return result; -} - -ConstExpr::ConstExpr(const DiagnosticLevel level) -{ - level_ = level; -} - -ExprStatus ConstExpr::eval() const -{ - ExprStatus status; - status.level = level_; - return status; -} - -std::vector ConstExpr::get_dependency() const -{ - return {}; -} - -LinkExpr::LinkExpr(ExprInit & exprs, ConfigObject & config) -{ - // TODO(Takagi, Isamu): remove - (void)config; - (void)exprs; -} - -void LinkExpr::init(ConfigObject & config, std::unordered_map nodes) -{ - const auto path = config.take_text("path"); - if (!nodes.count(path)) { - throw ConfigError("node path '" + path + "' does not exist"); - } - node_ = nodes.at(path); -} - -ExprStatus LinkExpr::eval() const -{ - ExprStatus status; - status.level = node_->level(); - status.links.push_back(std::make_pair(node_, true)); - return status; -} - -std::vector LinkExpr::get_dependency() const -{ - return {node_}; -} - -AndExpr::AndExpr(ExprInit & exprs, ConfigObject & config, bool short_circuit) -{ - list_ = create_expr_list(exprs, config); - short_circuit_ = short_circuit; -} - -ExprStatus AndExpr::eval() const -{ - if (list_.empty()) { - ExprStatus status; - status.level = DiagnosticStatus::OK; - return status; - } - - ExprStatus status; - status.level = DiagnosticStatus::OK; - for (const auto & expr : list_) { - const auto result = expr->eval(); - status.level = std::max(status.level, result.level); - extend(status.links, result.links); - if (short_circuit_ && status.level != DiagnosticStatus::OK) { - break; - } - } - status.level = std::min(status.level, DiagnosticStatus::ERROR); - return status; -} - -std::vector AndExpr::get_dependency() const -{ - std::vector depends; - for (const auto & expr : list_) { - const auto nodes = expr->get_dependency(); - depends.insert(depends.end(), nodes.begin(), nodes.end()); - } - return depends; -} - -OrExpr::OrExpr(ExprInit & exprs, ConfigObject & config) -{ - list_ = create_expr_list(exprs, config); -} - -ExprStatus OrExpr::eval() const -{ - if (list_.empty()) { - ExprStatus status; - status.level = DiagnosticStatus::OK; - return status; - } - - ExprStatus status; - status.level = DiagnosticStatus::ERROR; - for (const auto & expr : list_) { - const auto result = expr->eval(); - status.level = std::min(status.level, result.level); - extend(status.links, result.links); - } - status.level = std::min(status.level, DiagnosticStatus::ERROR); - return status; -} - -std::vector OrExpr::get_dependency() const -{ - std::vector depends; - for (const auto & expr : list_) { - const auto nodes = expr->get_dependency(); - depends.insert(depends.end(), nodes.begin(), nodes.end()); - } - return depends; -} - -ExprInit::ExprInit(const std::string & mode) -{ - mode_ = mode; -} - -std::unique_ptr ExprInit::create(ExprConfig config) -{ - if (!config.mode.check(mode_)) { - return nullptr; - } - if (config.type == "link") { - auto expr = std::make_unique(*this, config.dict); - links_.push_back(std::make_pair(expr.get(), config.dict)); - return expr; - } - if (config.type == "and") { - return std::make_unique(*this, config.dict, false); - } - if (config.type == "short-circuit-and") { - return std::make_unique(*this, config.dict, true); - } - if (config.type == "or") { - return std::make_unique(*this, config.dict); - } - if (config.type == "debug-ok") { - return std::make_unique(DiagnosticStatus::OK); - } - if (config.type == "debug-warn") { - return std::make_unique(DiagnosticStatus::WARN); - } - if (config.type == "debug-error") { - return std::make_unique(DiagnosticStatus::ERROR); - } - if (config.type == "debug-stale") { - return std::make_unique(DiagnosticStatus::STALE); - } - throw ConfigError("unknown expr type: " + config.type + " " + config.dict.mark().str()); -} - -} // namespace system_diagnostic_graph diff --git a/system/system_diagnostic_graph/src/core/exprs.hpp b/system/system_diagnostic_graph/src/core/exprs.hpp deleted file mode 100644 index f582e019d5691..0000000000000 --- a/system/system_diagnostic_graph/src/core/exprs.hpp +++ /dev/null @@ -1,104 +0,0 @@ -// Copyright 2023 The Autoware Contributors -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef CORE__EXPRS_HPP_ -#define CORE__EXPRS_HPP_ - -#include "config.hpp" -#include "types.hpp" - -#include -#include -#include -#include -#include - -namespace system_diagnostic_graph -{ - -struct ExprStatus -{ - DiagnosticLevel level; - std::vector> links; -}; - -class BaseExpr -{ -public: - virtual ~BaseExpr() = default; - virtual ExprStatus eval() const = 0; - virtual std::vector get_dependency() const = 0; -}; - -class ConstExpr : public BaseExpr -{ -public: - explicit ConstExpr(const DiagnosticLevel level); - ExprStatus eval() const override; - std::vector get_dependency() const override; - -private: - DiagnosticLevel level_; -}; - -class LinkExpr : public BaseExpr -{ -public: - LinkExpr(ExprInit & exprs, ConfigObject & config); - void init(ConfigObject & config, std::unordered_map nodes); - ExprStatus eval() const override; - std::vector get_dependency() const override; - -private: - BaseNode * node_; -}; - -class AndExpr : public BaseExpr -{ -public: - AndExpr(ExprInit & exprs, ConfigObject & config, bool short_circuit); - ExprStatus eval() const override; - std::vector get_dependency() const override; - -private: - bool short_circuit_; - std::vector> list_; -}; - -class OrExpr : public BaseExpr -{ -public: - OrExpr(ExprInit & exprs, ConfigObject & config); - ExprStatus eval() const override; - std::vector get_dependency() const override; - -private: - std::vector> list_; -}; - -class ExprInit -{ -public: - explicit ExprInit(const std::string & mode); - std::unique_ptr create(ExprConfig config); - auto get() const { return links_; } - -private: - std::string mode_; - std::vector> links_; -}; - -} // namespace system_diagnostic_graph - -#endif // CORE__EXPRS_HPP_ diff --git a/system/system_diagnostic_graph/src/core/graph.cpp b/system/system_diagnostic_graph/src/core/graph.cpp index b4fd1d15827f3..96e9bcff5bfd9 100644 --- a/system/system_diagnostic_graph/src/core/graph.cpp +++ b/system/system_diagnostic_graph/src/core/graph.cpp @@ -15,8 +15,8 @@ #include "graph.hpp" #include "config.hpp" -#include "exprs.hpp" -#include "nodes.hpp" +#include "error.hpp" +#include "units.hpp" #include #include @@ -31,12 +31,12 @@ namespace system_diagnostic_graph { -void topological_sort(std::vector> & input) +BaseUnit::UniquePtrList topological_sort(BaseUnit::UniquePtrList && input) { - std::unordered_map degrees; - std::deque nodes; - std::deque result; - std::deque buffer; + std::unordered_map degrees; + std::deque nodes; + std::deque result; + std::deque buffer; // Create a list of raw pointer nodes. for (const auto & node : input) { @@ -45,8 +45,8 @@ void topological_sort(std::vector> & input) // Count degrees of each node. for (const auto & node : nodes) { - for (const auto & link : node->links()) { - ++degrees[link]; + for (const auto & child : node->children()) { + ++degrees[child]; } } @@ -61,9 +61,9 @@ void topological_sort(std::vector> & input) while (!buffer.empty()) { const auto node = buffer.front(); buffer.pop_front(); - for (const auto & link : node->links()) { - if (--degrees[link] == 0) { - buffer.push_back(link); + for (const auto & child : node->children()) { + if (--degrees[child] == 0) { + buffer.push_back(child); } } result.push_back(node); @@ -71,22 +71,51 @@ void topological_sort(std::vector> & input) // Detect circulation because the result does not include the nodes on the loop. if (result.size() != nodes.size()) { - throw ConfigError("detect graph circulation"); + throw error("detect graph circulation"); } // Reverse the result to process from leaf node. - result = std::deque(result.rbegin(), result.rend()); + result = std::deque(result.rbegin(), result.rend()); // Replace node vector. - std::unordered_map indices; + std::unordered_map indices; for (size_t i = 0; i < result.size(); ++i) { indices[result[i]] = i; } - std::vector> sorted(input.size()); + std::vector> sorted(input.size()); for (auto & node : input) { sorted[indices[node.get()]] = std::move(node); } - input = std::move(sorted); + return sorted; +} + +BaseUnit::UniquePtr make_node(const UnitConfig::SharedPtr & config) +{ + if (config->type == "diag") { + return std::make_unique(config->path); + } + if (config->type == "and") { + return std::make_unique(config->path, false); + } + if (config->type == "short-circuit-and") { + return std::make_unique(config->path, true); + } + if (config->type == "or") { + return std::make_unique(config->path); + } + if (config->type == "ok") { + return std::make_unique(config->path, DiagnosticStatus::OK); + } + if (config->type == "warn") { + return std::make_unique(config->path, DiagnosticStatus::WARN); + } + if (config->type == "error") { + return std::make_unique(config->path, DiagnosticStatus::ERROR); + } + if (config->type == "stale") { + return std::make_unique(config->path, DiagnosticStatus::STALE); + } + throw error("unknown node type", config->type, config->data); } Graph::Graph() @@ -101,99 +130,80 @@ Graph::~Graph() void Graph::init(const std::string & file, const std::string & mode) { - ConfigFile root = load_config_root(file); + (void)mode; // TODO(Takagi, Isamu) - std::vector> nodes; - std::unordered_map diags; - std::unordered_map paths; - ExprInit exprs(mode); + BaseUnit::UniquePtrList nodes; + BaseUnit::NodeDict dict; - for (auto & config : root.units) { - if (config.mode.check(mode)) { - auto node = std::make_unique(config.path); - nodes.push_back(std::move(node)); - } - } - for (auto & config : root.diags) { - if (config.mode.check(mode)) { - auto node = std::make_unique(config.path, config.dict); - diags[node->name()] = node.get(); - nodes.push_back(std::move(node)); - } + for (const auto & config : load_root_config(file).nodes) { + const auto node = nodes.emplace_back(make_node(config)).get(); + dict.configs[config] = node; + dict.paths[config->path] = node; } + dict.paths.erase(""); - // TODO(Takagi, Isamu): unknown diag names - { - auto node = std::make_unique("/unknown"); - unknown_ = node.get(); - nodes.push_back(std::move(node)); + for (const auto & [config, node] : dict.configs) { + node->init(config, dict); } - for (const auto & node : nodes) { - paths[node->path()] = node.get(); - } + // Sort units in topological order for update dependencies. + nodes = topological_sort(std::move(nodes)); - for (auto & config : root.units) { - if (paths.count(config.path)) { - paths.at(config.path)->create(config.dict, exprs); - } - } - for (auto & config : root.diags) { - if (paths.count(config.path)) { - paths.at(config.path)->create(config.dict, exprs); - } + for (size_t index = 0; index < nodes.size(); ++index) { + nodes[index]->set_index(index); } - for (auto & [link, config] : exprs.get()) { - link->init(config, paths); - } - - // Sort unit nodes in topological order for update dependencies. - topological_sort(nodes); - - // Set the link index for the ros message. - for (size_t i = 0; i < nodes.size(); ++i) { - nodes[i]->set_index(i); + for (const auto & node : nodes) { + const auto diag = dynamic_cast(node.get()); + if (diag) { + diags_[diag->name()] = diag; + std::cout << diag->name() << std::endl; + } } - nodes_ = std::move(nodes); - diags_ = diags; } -void Graph::callback(const DiagnosticArray & array, const rclcpp::Time & stamp) +void Graph::callback(const rclcpp::Time & stamp, const DiagnosticArray & array) { for (const auto & status : array.status) { const auto iter = diags_.find(status.name); if (iter != diags_.end()) { - iter->second->callback(status, stamp); + iter->second->callback(stamp, status); } else { - unknown_->callback(status, stamp); + // TODO(Takagi, Isamu) + std::cout << "unknown diag: " << status.name << std::endl; } } } -void Graph::update(const rclcpp::Time & stamp) +DiagnosticGraph Graph::report(const rclcpp::Time & stamp) { for (const auto & node : nodes_) { node->update(stamp); } - stamp_ = stamp; -} -DiagnosticGraph Graph::message() const -{ - DiagnosticGraph result; - result.stamp = stamp_; - result.nodes.reserve(nodes_.size()); + DiagnosticGraph message; + message.stamp = stamp; + message.nodes.reserve(nodes_.size()); for (const auto & node : nodes_) { - result.nodes.push_back(node->report()); + const auto report = node->report(); + DiagnosticNode temp; + temp.status.name = node->path(); + temp.status.level = report.level; + for (const auto & [ref, used] : report.links) { + DiagnosticLink link; + link.index = ref->index(); + link.used = used; + temp.links.push_back(link); + } + message.nodes.push_back(temp); } - return result; + return message; } -std::vector Graph::nodes() const +std::vector Graph::nodes() const { - std::vector result; + std::vector result; result.reserve(nodes_.size()); for (const auto & node : nodes_) { result.push_back(node.get()); diff --git a/system/system_diagnostic_graph/src/core/graph.hpp b/system/system_diagnostic_graph/src/core/graph.hpp index e0060c9111592..366f6b457e272 100644 --- a/system/system_diagnostic_graph/src/core/graph.hpp +++ b/system/system_diagnostic_graph/src/core/graph.hpp @@ -34,19 +34,16 @@ class Graph final Graph(); ~Graph(); - void init(const std::string & file, const std::string & mode); - void callback(const DiagnosticArray & array, const rclcpp::Time & stamp); - void update(const rclcpp::Time & stamp); - DiagnosticGraph message() const; - std::vector nodes() const; + void init(const std::string & file, const std::string & mode = ""); + void callback(const rclcpp::Time & stamp, const DiagnosticArray & array); + DiagnosticGraph report(const rclcpp::Time & stamp); + std::vector nodes() const; void debug(); private: - std::vector> nodes_; - std::unordered_map diags_; - UnknownNode * unknown_; - rclcpp::Time stamp_; + std::vector> nodes_; + std::unordered_map diags_; }; } // namespace system_diagnostic_graph diff --git a/system/system_diagnostic_graph/src/core/modes.cpp b/system/system_diagnostic_graph/src/core/modes.cpp index 0ca18f84b0407..96944bd50f81a 100644 --- a/system/system_diagnostic_graph/src/core/modes.cpp +++ b/system/system_diagnostic_graph/src/core/modes.cpp @@ -15,7 +15,8 @@ #include "modes.hpp" #include "config.hpp" -#include "nodes.hpp" +#include "error.hpp" +#include "units.hpp" #include #include @@ -24,22 +25,22 @@ namespace system_diagnostic_graph { -OperationModes::OperationModes(rclcpp::Node & node, const std::vector & graph) +OperationModes::OperationModes(rclcpp::Node & node, const std::vector & graph) { pub_ = node.create_publisher("/system/operation_mode/availability", rclcpp::QoS(1)); - using PathNodes = std::unordered_map; - PathNodes paths; + using PathDict = std::unordered_map; + PathDict paths; for (const auto & node : graph) { paths[node->path()] = node; } - const auto find_node = [](const PathNodes & paths, const std::string & name) { + const auto find_node = [](const PathDict & paths, const std::string & name) { const auto iter = paths.find(name); if (iter != paths.end()) { return iter->second; } - throw ConfigError("summary node '" + name + "' does node exist"); + throw error("summary node is not found", name); }; // clang-format off @@ -55,7 +56,7 @@ OperationModes::OperationModes(rclcpp::Node & node, const std::vectorlevel() == DiagnosticStatus::OK; }; + const auto is_ok = [](const BaseUnit * node) { return node->level() == DiagnosticStatus::OK; }; // clang-format off Availability message; diff --git a/system/system_diagnostic_graph/src/core/modes.hpp b/system/system_diagnostic_graph/src/core/modes.hpp index ead1ec10dce93..47a31b8d2a152 100644 --- a/system/system_diagnostic_graph/src/core/modes.hpp +++ b/system/system_diagnostic_graph/src/core/modes.hpp @@ -29,7 +29,7 @@ namespace system_diagnostic_graph class OperationModes { public: - explicit OperationModes(rclcpp::Node & node, const std::vector & graph); + OperationModes(rclcpp::Node & node, const std::vector & graph); void update(const rclcpp::Time & stamp) const; private: @@ -37,13 +37,13 @@ class OperationModes rclcpp::TimerBase::SharedPtr timer_; rclcpp::Publisher::SharedPtr pub_; - BaseNode * stop_mode_; - BaseNode * autonomous_mode_; - BaseNode * local_mode_; - BaseNode * remote_mode_; - BaseNode * emergency_stop_mrm_; - BaseNode * comfortable_stop_mrm_; - BaseNode * pull_over_mrm_; + BaseUnit * stop_mode_; + BaseUnit * autonomous_mode_; + BaseUnit * local_mode_; + BaseUnit * remote_mode_; + BaseUnit * emergency_stop_mrm_; + BaseUnit * comfortable_stop_mrm_; + BaseUnit * pull_over_mrm_; }; } // namespace system_diagnostic_graph diff --git a/system/system_diagnostic_graph/src/core/nodes.cpp b/system/system_diagnostic_graph/src/core/nodes.cpp deleted file mode 100644 index bbc4bb4d42561..0000000000000 --- a/system/system_diagnostic_graph/src/core/nodes.cpp +++ /dev/null @@ -1,157 +0,0 @@ -// Copyright 2023 The Autoware Contributors -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "nodes.hpp" - -#include "exprs.hpp" - -#include - -#include -#include - -namespace system_diagnostic_graph -{ - -BaseNode::BaseNode(const std::string & path) : path_(path) -{ - index_ = 0; -} - -UnitNode::UnitNode(const std::string & path) : BaseNode(path) -{ - level_ = DiagnosticStatus::STALE; -} - -UnitNode::~UnitNode() -{ - // for unique_ptr -} - -void UnitNode::create(ConfigObject & config, ExprInit & exprs) -{ - expr_ = exprs.create(parse_expr_config(config)); -} - -void UnitNode::update(const rclcpp::Time &) -{ - const auto result = expr_->eval(); - level_ = result.level; - links_.clear(); - for (const auto & [node, used] : result.links) { - DiagnosticLink link; - link.index = node->index(); - link.used = used; - links_.push_back(link); - } -} - -DiagnosticNode UnitNode::report() const -{ - DiagnosticNode message; - message.status.level = level_; - message.status.name = path_; - message.links = links_; - return message; -} - -DiagnosticLevel UnitNode::level() const -{ - return level_; -} - -std::vector UnitNode::links() const -{ - return expr_->get_dependency(); -} - -DiagNode::DiagNode(const std::string & path, ConfigObject & config) : BaseNode(path) -{ - timeout_ = 3.0; // TODO(Takagi, Isamu): parameterize - name_ = config.take_text("name"); - - status_.level = DiagnosticStatus::STALE; -} - -void DiagNode::create(ConfigObject &, ExprInit &) -{ -} - -void DiagNode::update(const rclcpp::Time & stamp) -{ - if (time_) { - const auto elapsed = (stamp - time_.value()).seconds(); - if (timeout_ < elapsed) { - status_ = DiagnosticStatus(); - status_.level = DiagnosticStatus::STALE; - time_ = std::nullopt; - } - } -} - -DiagnosticNode DiagNode::report() const -{ - DiagnosticNode message; - message.status = status_; - message.status.name = path_; - return message; -} - -DiagnosticLevel DiagNode::level() const -{ - return status_.level; -} - -void DiagNode::callback(const DiagnosticStatus & status, const rclcpp::Time & stamp) -{ - status_ = status; - time_ = stamp; -} - -UnknownNode::UnknownNode(const std::string & path) : BaseNode(path) -{ -} - -void UnknownNode::create(ConfigObject &, ExprInit &) -{ -} - -void UnknownNode::update(const rclcpp::Time & stamp) -{ - (void)stamp; -} - -DiagnosticNode UnknownNode::report() const -{ - DiagnosticNode message; - message.status.name = path_; - for (const auto & diag : diagnostics_) { - diagnostic_msgs::msg::KeyValue kv; - kv.key = diag.first; - message.status.values.push_back(kv); - } - return message; -} - -DiagnosticLevel UnknownNode::level() const -{ - return DiagnosticStatus::WARN; -} - -void UnknownNode::callback(const DiagnosticStatus & status, const rclcpp::Time & stamp) -{ - diagnostics_[status.name] = stamp; -} - -} // namespace system_diagnostic_graph diff --git a/system/system_diagnostic_graph/src/core/nodes.hpp b/system/system_diagnostic_graph/src/core/nodes.hpp deleted file mode 100644 index 1a849cf58b268..0000000000000 --- a/system/system_diagnostic_graph/src/core/nodes.hpp +++ /dev/null @@ -1,114 +0,0 @@ -// Copyright 2023 The Autoware Contributors -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef CORE__NODES_HPP_ -#define CORE__NODES_HPP_ - -#include "config.hpp" -#include "debug.hpp" -#include "types.hpp" - -#include - -#include -#include -#include -#include -#include -#include - -namespace system_diagnostic_graph -{ - -class BaseNode -{ -public: - explicit BaseNode(const std::string & path); - virtual ~BaseNode() = default; - virtual void create(ConfigObject & config, ExprInit & exprs) = 0; - virtual void update(const rclcpp::Time & stamp) = 0; - virtual DiagnosticNode report() const = 0; - virtual DiagnosticLevel level() const = 0; - virtual DiagDebugData debug() const = 0; - virtual std::vector links() const = 0; - - std::string path() const { return path_; } - - size_t index() const { return index_; } - void set_index(const size_t index) { index_ = index; } - -protected: - const std::string path_; - size_t index_; -}; - -class UnitNode : public BaseNode -{ -public: - explicit UnitNode(const std::string & path); - ~UnitNode() override; - void create(ConfigObject & config, ExprInit & exprs) override; - void update(const rclcpp::Time & stamp) override; - DiagnosticNode report() const override; - DiagnosticLevel level() const override; - DiagDebugData debug() const override; - std::vector links() const override; - -private: - std::unique_ptr expr_; - std::vector links_; - DiagnosticLevel level_; -}; - -class DiagNode : public BaseNode -{ -public: - DiagNode(const std::string & path, ConfigObject & config); - void create(ConfigObject & config, ExprInit & exprs) override; - void update(const rclcpp::Time & stamp) override; - DiagnosticNode report() const override; - DiagnosticLevel level() const override; - DiagDebugData debug() const override; - std::vector links() const override { return {}; } - std::string name() const { return name_; } - - void callback(const DiagnosticStatus & status, const rclcpp::Time & stamp); - -private: - double timeout_; - std::optional time_; - std::string name_; - DiagnosticStatus status_; -}; - -class UnknownNode : public BaseNode -{ -public: - explicit UnknownNode(const std::string & path); - void create(ConfigObject & config, ExprInit & exprs) override; - void update(const rclcpp::Time & stamp) override; - DiagnosticNode report() const override; - DiagnosticLevel level() const override; - DiagDebugData debug() const override; - std::vector links() const override { return {}; } - - void callback(const DiagnosticStatus & status, const rclcpp::Time & stamp); - -private: - std::map diagnostics_; -}; - -} // namespace system_diagnostic_graph - -#endif // CORE__NODES_HPP_ diff --git a/system/system_diagnostic_graph/src/core/types.hpp b/system/system_diagnostic_graph/src/core/types.hpp index 2adfbb3f9d4ef..c0b901d1e4511 100644 --- a/system/system_diagnostic_graph/src/core/types.hpp +++ b/system/system_diagnostic_graph/src/core/types.hpp @@ -31,13 +31,8 @@ using tier4_system_msgs::msg::DiagnosticLink; using tier4_system_msgs::msg::DiagnosticNode; using DiagnosticLevel = DiagnosticStatus::_level_type; -class BaseNode; -class UnitNode; -class DiagNode; -class UnknownNode; - -class BaseExpr; -class ExprInit; +class BaseUnit; +class DiagUnit; } // namespace system_diagnostic_graph diff --git a/system/system_diagnostic_graph/src/core/units.cpp b/system/system_diagnostic_graph/src/core/units.cpp new file mode 100644 index 0000000000000..7cdd7c3e1266e --- /dev/null +++ b/system/system_diagnostic_graph/src/core/units.cpp @@ -0,0 +1,164 @@ +// Copyright 2023 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "units.hpp" + +#include +#include +#include +#include + +namespace system_diagnostic_graph +{ + +using LinkList = std::vector>; + +void merge(LinkList & a, const LinkList & b, bool uses) +{ + for (const auto & [node, used] : b) { + a.push_back(std::make_pair(node, used && uses)); + } +} + +auto resolve(const BaseUnit::NodeDict & dict, const std::vector & children) +{ + std::vector result; + for (const auto & child : children) { + result.push_back(dict.configs.at(child)); + } + return result; +} + +auto resolve(const BaseUnit::NodeDict & dict, const std::string & path) +{ + std::vector result; + result.push_back(dict.paths.at(path)); + return result; +} + +BaseUnit::BaseUnit(const std::string & path) : path_(path) +{ + index_ = 0; + level_ = DiagnosticStatus::OK; +} + +BaseUnit::NodeData BaseUnit::status() const +{ + if (path_.empty()) { + return {level_, links_}; + } else { + return {level_, {std::make_pair(this, true)}}; + } +} + +BaseUnit::NodeData BaseUnit::report() const +{ + return {level_, links_}; +} + +void DiagUnit::init(const UnitConfig::SharedPtr & config, const NodeDict &) +{ + timeout_ = 3.0; // TODO(Takagi, Isamu): parameterize + name_ = config->data.take_text("diag"); +} + +void DiagUnit::update(const rclcpp::Time & stamp) +{ + if (diagnostics_) { + const auto updated = diagnostics_.value().first; + const auto elapsed = (stamp - updated).seconds(); + if (timeout_ < elapsed) { + diagnostics_ = std::nullopt; + } + } + + if (diagnostics_) { + level_ = diagnostics_.value().second.level; + } else { + level_ = DiagnosticStatus::STALE; + } +} + +void DiagUnit::callback(const rclcpp::Time & stamp, const DiagnosticStatus & status) +{ + diagnostics_ = std::make_pair(stamp, status); +} + +AndUnit::AndUnit(const std::string & path, bool short_circuit) : BaseUnit(path) +{ + short_circuit_ = short_circuit; +} + +void AndUnit::init(const UnitConfig::SharedPtr & config, const NodeDict & dict) +{ + children_ = resolve(dict, config->children); +} + +void AndUnit::update(const rclcpp::Time &) +{ + if (children_.empty()) { + return; + } + + bool uses = true; + level_ = DiagnosticStatus::OK; + links_ = LinkList(); + + for (const auto & child : children_) { + const auto status = child->status(); + level_ = std::max(level_, status.level); + merge(links_, status.links, uses); + if (short_circuit_ && level_ != DiagnosticStatus::OK) { + uses = false; + } + } + level_ = std::min(level_, DiagnosticStatus::ERROR); +} + +void OrUnit::init(const UnitConfig::SharedPtr & config, const NodeDict & dict) +{ + children_ = resolve(dict, config->children); +} + +void OrUnit::update(const rclcpp::Time &) +{ + if (children_.empty()) { + return; + } + + level_ = DiagnosticStatus::ERROR; + links_ = LinkList(); + + for (const auto & child : children_) { + const auto status = child->status(); + level_ = std::min(level_, status.level); + merge(links_, status.links, true); + } + level_ = std::min(level_, DiagnosticStatus::ERROR); +} + +DebugUnit::DebugUnit(const std::string & path, DiagnosticLevel level) : BaseUnit(path) +{ + level_ = level; // overwrite +} + +void DebugUnit::init(const UnitConfig::SharedPtr &, const NodeDict &) +{ +} + +void DebugUnit::update(const rclcpp::Time &) +{ +} + +} // namespace system_diagnostic_graph diff --git a/system/system_diagnostic_graph/src/core/units.hpp b/system/system_diagnostic_graph/src/core/units.hpp new file mode 100644 index 0000000000000..ad5fa4c4bc090 --- /dev/null +++ b/system/system_diagnostic_graph/src/core/units.hpp @@ -0,0 +1,119 @@ +// Copyright 2023 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef CORE__UNITS_HPP_ +#define CORE__UNITS_HPP_ + +#include "config.hpp" +#include "types.hpp" + +#include + +#include +#include +#include +#include +#include +#include + +namespace system_diagnostic_graph +{ + +class BaseUnit +{ +public: + struct NodeDict + { + std::unordered_map configs; + std::unordered_map paths; + }; + struct NodeData + { + DiagnosticLevel level; + std::vector> links; + }; + using UniquePtr = std::unique_ptr; + using UniquePtrList = std::vector>; + + explicit BaseUnit(const std::string & path); + virtual ~BaseUnit() = default; + virtual void init(const UnitConfig::SharedPtr & config, const NodeDict & dict) = 0; + virtual void update(const rclcpp::Time & stamp) = 0; + + NodeData status() const; + NodeData report() const; + DiagnosticLevel level() const { return level_; } + + auto path() const { return path_; } + auto children() const { return children_; } + + size_t index() const { return index_; } + void set_index(const size_t index) { index_ = index; } + +protected: + DiagnosticLevel level_; + std::string path_; + std::vector children_; + std::vector> links_; + +private: + size_t index_; +}; + +class DiagUnit : public BaseUnit +{ +public: + using BaseUnit::BaseUnit; + void init(const UnitConfig::SharedPtr & config, const NodeDict & dict) override; + void update(const rclcpp::Time & stamp) override; + + std::string name() const { return name_; } + void callback(const rclcpp::Time & stamp, const DiagnosticStatus & status); + +private: + double timeout_; + std::optional> diagnostics_; + std::string name_; +}; + +class AndUnit : public BaseUnit +{ +public: + AndUnit(const std::string & path, bool short_circuit); + void init(const UnitConfig::SharedPtr & config, const NodeDict & dict) override; + void update(const rclcpp::Time & stamp) override; + +private: + bool short_circuit_; +}; + +class OrUnit : public BaseUnit +{ +public: + using BaseUnit::BaseUnit; + void init(const UnitConfig::SharedPtr & config, const NodeDict & dict) override; + void update(const rclcpp::Time & stamp) override; +}; + +class DebugUnit : public BaseUnit +{ +public: + DebugUnit(const std::string & path, DiagnosticLevel level); + void init(const UnitConfig::SharedPtr & config, const NodeDict & dict) override; + void update(const rclcpp::Time & stamp) override; +}; + +} // namespace system_diagnostic_graph + +#endif // CORE__UNITS_HPP_ diff --git a/system/system_diagnostic_graph/src/main.cpp b/system/system_diagnostic_graph/src/main.cpp index 722ddcf833577..7db35d1fd2551 100644 --- a/system/system_diagnostic_graph/src/main.cpp +++ b/system/system_diagnostic_graph/src/main.cpp @@ -58,16 +58,14 @@ MainNode::~MainNode() void MainNode::on_timer() { const auto stamp = now(); - graph_.update(stamp); + pub_graph_->publish(graph_.report(stamp)); graph_.debug(); - pub_graph_->publish(graph_.message()); - if (modes_) modes_->update(stamp); } void MainNode::on_diag(const DiagnosticArray::ConstSharedPtr msg) { - graph_.callback(*msg, now()); + graph_.callback(now(), *msg); } } // namespace system_diagnostic_graph diff --git a/system/system_diagnostic_graph/test/files/field-not-found.yaml b/system/system_diagnostic_graph/test/files/field-not-found.yaml new file mode 100644 index 0000000000000..9e2b3708c049a --- /dev/null +++ b/system/system_diagnostic_graph/test/files/field-not-found.yaml @@ -0,0 +1,2 @@ +nodes: + - test-type: test-type diff --git a/system/system_diagnostic_graph/test/files/file-not-found.yaml b/system/system_diagnostic_graph/test/files/file-not-found.yaml new file mode 100644 index 0000000000000..ffc83b42096f0 --- /dev/null +++ b/system/system_diagnostic_graph/test/files/file-not-found.yaml @@ -0,0 +1,2 @@ +files: + - { path: $(dirname)/fake-file-name.yaml } diff --git a/system/system_diagnostic_graph/test/files/graph-circulation.yaml b/system/system_diagnostic_graph/test/files/graph-circulation.yaml new file mode 100644 index 0000000000000..4c014bdcec3f9 --- /dev/null +++ b/system/system_diagnostic_graph/test/files/graph-circulation.yaml @@ -0,0 +1,9 @@ +nodes: + - path: /foo/bar + type: and + list: + - { type: link, link: /foo/baz } + - path: /foo/baz + type: and + list: + - { type: link, link: /foo/bar } diff --git a/system/system_diagnostic_graph/test/files/invalid-dict-type.yaml b/system/system_diagnostic_graph/test/files/invalid-dict-type.yaml new file mode 100644 index 0000000000000..6499b05ab8b7d --- /dev/null +++ b/system/system_diagnostic_graph/test/files/invalid-dict-type.yaml @@ -0,0 +1 @@ +nodes: test-object diff --git a/system/system_diagnostic_graph/test/files/invalid-list-type.yaml b/system/system_diagnostic_graph/test/files/invalid-list-type.yaml new file mode 100644 index 0000000000000..4fc5d96c08c62 --- /dev/null +++ b/system/system_diagnostic_graph/test/files/invalid-list-type.yaml @@ -0,0 +1,3 @@ +nodes: + - type: and + list: test-list diff --git a/system/system_diagnostic_graph/test/files/path-conflict.yaml b/system/system_diagnostic_graph/test/files/path-conflict.yaml new file mode 100644 index 0000000000000..ea3e536b74216 --- /dev/null +++ b/system/system_diagnostic_graph/test/files/path-conflict.yaml @@ -0,0 +1,5 @@ +nodes: + - path: /foo/bar + type: and + - path: /foo/bar + type: and diff --git a/system/system_diagnostic_graph/test/files/path-not-found.yaml b/system/system_diagnostic_graph/test/files/path-not-found.yaml new file mode 100644 index 0000000000000..6b0b10dfa94f4 --- /dev/null +++ b/system/system_diagnostic_graph/test/files/path-not-found.yaml @@ -0,0 +1,5 @@ +nodes: + - path: /foo/bar + type: and + - link: /foo/baz + type: link diff --git a/system/system_diagnostic_graph/test/files/unknown-node-type.yaml b/system/system_diagnostic_graph/test/files/unknown-node-type.yaml new file mode 100644 index 0000000000000..a3d66fbfa43cb --- /dev/null +++ b/system/system_diagnostic_graph/test/files/unknown-node-type.yaml @@ -0,0 +1,2 @@ +nodes: + - type: test-type diff --git a/system/system_diagnostic_graph/test/files/unknown-substitution.yaml b/system/system_diagnostic_graph/test/files/unknown-substitution.yaml new file mode 100644 index 0000000000000..7286321c30439 --- /dev/null +++ b/system/system_diagnostic_graph/test/files/unknown-substitution.yaml @@ -0,0 +1,2 @@ +files: + - { path: $(dummy) } diff --git a/system/system_diagnostic_graph/test/src/test.cpp b/system/system_diagnostic_graph/test/src/test.cpp new file mode 100644 index 0000000000000..b763179be0791 --- /dev/null +++ b/system/system_diagnostic_graph/test/src/test.cpp @@ -0,0 +1,88 @@ +// Copyright 2023 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "core/error.hpp" +#include "core/graph.hpp" + +#include + +#include +#include + +using namespace system_diagnostic_graph; // NOLINT(build/namespaces) + +std::filesystem::path resource(const std::string & path) +{ + return std::filesystem::path(TEST_RESOURCE_PATH) / path; +} + +TEST(ConfigFile, RootNotFound) +{ + Graph graph; + EXPECT_THROW(graph.init(resource("fake-file-name.yaml")), FileNotFound); +} + +TEST(ConfigFile, FileNotFound) +{ + Graph graph; + EXPECT_THROW(graph.init(resource("file-not-found.yaml")), FileNotFound); +} + +TEST(ConfigFile, UnknownSubstitution) +{ + Graph graph; + EXPECT_THROW(graph.init(resource("unknown-substitution.yaml")), UnknownType); +} + +TEST(ConfigFile, UnknownNodeType) +{ + Graph graph; + EXPECT_THROW(graph.init(resource("unknown-node-type.yaml")), UnknownType); +} + +TEST(ConfigFile, InvalidDictType) +{ + Graph graph; + EXPECT_THROW(graph.init(resource("invalid-dict-type.yaml")), InvalidType); +} + +TEST(ConfigFile, InvalidListType) +{ + Graph graph; + EXPECT_THROW(graph.init(resource("invalid-list-type.yaml")), InvalidType); +} + +TEST(ConfigFile, FieldNotFound) +{ + Graph graph; + EXPECT_THROW(graph.init(resource("field-not-found.yaml")), FieldNotFound); +} + +TEST(ConfigFile, PathConflict) +{ + Graph graph; + EXPECT_THROW(graph.init(resource("path-conflict.yaml")), PathConflict); +} + +TEST(ConfigFile, PathNotFound) +{ + Graph graph; + EXPECT_THROW(graph.init(resource("path-not-found.yaml")), PathNotFound); +} + +TEST(ConfigFile, GraphCirculation) +{ + Graph graph; + EXPECT_THROW(graph.init(resource("graph-circulation.yaml")), GraphStructure); +} diff --git a/system/system_diagnostic_graph/util/debug.py b/system/system_diagnostic_graph/util/debug.py deleted file mode 100755 index dac917a26a2f6..0000000000000 --- a/system/system_diagnostic_graph/util/debug.py +++ /dev/null @@ -1,85 +0,0 @@ -#!/usr/bin/env python3 - -# Copyright 2023 The Autoware Contributors -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -import rclpy -from rclpy.node import Node -from rclpy.qos import QoSDurabilityPolicy -from rclpy.qos import QoSProfile -from tier4_system_msgs.msg import DiagnosticGraph - - -class StructNode(Node): - def __init__(self): - super().__init__("system_diagnostic_graph_tools_struct") - qos_struct = QoSProfile(depth=1, durability=QoSDurabilityPolicy.TRANSIENT_LOCAL) - self.sub_struct = self.create_subscription( - DiagnosticGraph, "/diagnostics_graph/struct", self.callback, qos_struct - ) - self.message = None - - def callback(self, msg): - self.message = msg - - -class NodeSpinner: - def __init__(self, time): - self.time = time - self.wait = True - - def on_timer(self): - self.wait = False - - def spin(self, node): - timer = node.create_timer(self.time, self.on_timer) - while self.wait: - rclpy.spin_once(node) - node.destroy_timer(timer) - - -class GraphNode: - def __init__(self, msg): - self.name = msg.name - self.links = msg.links - - -class GraphStruct: - def __init__(self, msg): - self.nodes = [GraphNode(node) for node in msg.nodes] - - @staticmethod - def Subscribe(): - spin = NodeSpinner(1.0) - node = StructNode() - spin.spin(node) - return GraphStruct(node.message) - - def visualize(self): - from graphviz import Digraph - - graph = Digraph() - graph.attr("node", shape="box") - for node in self.nodes: - graph.node(node.name) - for link in node.links: - graph.edge(node.name, self.nodes[link].name) - graph.view() - - -if __name__ == "__main__": - rclpy.init() - graph = GraphStruct.Subscribe() - rclpy.shutdown() - graph.visualize() From 9beb798860c8ea505d8482332ab9d66d835c44b9 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Thu, 2 Nov 2023 11:50:22 +0900 Subject: [PATCH 104/202] fix(simple_planning_simulator): initialize variables (#5460) Signed-off-by: Takamasa Horibe --- .../simple_planning_simulator_core.hpp | 46 +++++++++---------- 1 file changed, 23 insertions(+), 23 deletions(-) diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp b/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp index 4b25dba8b16ee..b0df04285ac9f 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp +++ b/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp @@ -171,36 +171,36 @@ class PLANNING_SIMULATOR_PUBLIC SimplePlanningSimulator : public rclcpp::Node tf2_ros::TransformListener tf_listener_; /* received & published topics */ - PoseWithCovarianceStamped::ConstSharedPtr initial_pose_; - TwistStamped initial_twist_; - VelocityReport current_velocity_; - Odometry current_odometry_; - SteeringReport current_steer_; - AckermannControlCommand current_ackermann_cmd_; - AckermannControlCommand current_manual_ackermann_cmd_; - GearCommand current_gear_cmd_; - GearCommand current_manual_gear_cmd_; - TurnIndicatorsCommand::ConstSharedPtr current_turn_indicators_cmd_ptr_; - HazardLightsCommand::ConstSharedPtr current_hazard_lights_cmd_ptr_; - Trajectory::ConstSharedPtr current_trajectory_ptr_; - bool simulate_motion_; //!< stop vehicle motion simulation if false - ControlModeReport current_control_mode_; - bool enable_road_slope_simulation_; + PoseWithCovarianceStamped::ConstSharedPtr initial_pose_{}; + TwistStamped initial_twist_{}; + VelocityReport current_velocity_{}; + Odometry current_odometry_{}; + SteeringReport current_steer_{}; + AckermannControlCommand current_ackermann_cmd_{}; + AckermannControlCommand current_manual_ackermann_cmd_{}; + GearCommand current_gear_cmd_{}; + GearCommand current_manual_gear_cmd_{}; + TurnIndicatorsCommand::ConstSharedPtr current_turn_indicators_cmd_ptr_{}; + HazardLightsCommand::ConstSharedPtr current_hazard_lights_cmd_ptr_{}; + Trajectory::ConstSharedPtr current_trajectory_ptr_{}; + bool simulate_motion_ = true; //!< stop vehicle motion simulation if false + ControlModeReport current_control_mode_{}; + bool enable_road_slope_simulation_ = true; /* frame_id */ - std::string simulated_frame_id_; //!< @brief simulated vehicle frame id - std::string origin_frame_id_; //!< @brief map frame_id + std::string simulated_frame_id_ = ""; //!< @brief simulated vehicle frame id + std::string origin_frame_id_ = ""; //!< @brief map frame_id /* flags */ - bool is_initialized_; //!< @brief flag to check the initial position is set - bool add_measurement_noise_; //!< @brief flag to add measurement noise + bool is_initialized_ = false; //!< @brief flag to check the initial position is set + bool add_measurement_noise_ = false; //!< @brief flag to add measurement noise - DeltaTime delta_time_; //!< @brief to calculate delta time + DeltaTime delta_time_{}; //!< @brief to calculate delta time - MeasurementNoiseGenerator measurement_noise_; //!< @brief for measurement noise + MeasurementNoiseGenerator measurement_noise_{}; //!< @brief for measurement noise - double x_stddev_; //!< @brief x standard deviation for dummy covariance in map coordinate - double y_stddev_; //!< @brief y standard deviation for dummy covariance in map coordinate + double x_stddev_ = 0.0; //!< @brief x standard deviation for dummy covariance in map coordinate + double y_stddev_ = 0.0; //!< @brief y standard deviation for dummy covariance in map coordinate /* vehicle model */ enum class VehicleModelType { From 012de2116cf5ef6a4ea7cbb8b787807a2027ad19 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Thu, 2 Nov 2023 11:54:00 +0900 Subject: [PATCH 105/202] fix(planning_validator): not publish diag before data is ready (#5461) Signed-off-by: Takamasa Horibe --- .../planning_validator/planning_validator.hpp | 2 +- .../src/planning_validator.cpp | 33 ++++++++++--------- 2 files changed, 18 insertions(+), 17 deletions(-) diff --git a/planning/planning_validator/include/planning_validator/planning_validator.hpp b/planning/planning_validator/include/planning_validator/planning_validator.hpp index ef570b57773bb..037c7fb0f4e95 100644 --- a/planning/planning_validator/include/planning_validator/planning_validator.hpp +++ b/planning/planning_validator/include/planning_validator/planning_validator.hpp @@ -109,7 +109,7 @@ class PlanningValidator : public rclcpp::Node int diag_error_count_threshold_ = 0; bool display_on_terminal_ = true; - Updater diag_updater_{this}; + std::shared_ptr diag_updater_ = nullptr; PlanningValidatorStatus validation_status_; ValidationParams validation_params_; // for thresholds diff --git a/planning/planning_validator/src/planning_validator.cpp b/planning/planning_validator/src/planning_validator.cpp index 875781d47b25d..58af2c08ccb22 100644 --- a/planning/planning_validator/src/planning_validator.cpp +++ b/planning/planning_validator/src/planning_validator.cpp @@ -47,10 +47,6 @@ PlanningValidator::PlanningValidator(const rclcpp::NodeOptions & options) setupParameters(); - if (publish_diag_) { - setupDiag(); - } - logger_configure_ = std::make_unique(this); } @@ -112,39 +108,40 @@ void PlanningValidator::setStatus( void PlanningValidator::setupDiag() { + diag_updater_ = std::make_shared(this); auto & d = diag_updater_; - d.setHardwareID("planning_validator"); + d->setHardwareID("planning_validator"); std::string ns = "trajectory_validation_"; - d.add(ns + "finite", [&](auto & stat) { + d->add(ns + "finite", [&](auto & stat) { setStatus(stat, validation_status_.is_valid_finite_value, "infinite value is found"); }); - d.add(ns + "interval", [&](auto & stat) { + d->add(ns + "interval", [&](auto & stat) { setStatus(stat, validation_status_.is_valid_interval, "points interval is too long"); }); - d.add(ns + "relative_angle", [&](auto & stat) { + d->add(ns + "relative_angle", [&](auto & stat) { setStatus(stat, validation_status_.is_valid_relative_angle, "relative angle is too large"); }); - d.add(ns + "curvature", [&](auto & stat) { + d->add(ns + "curvature", [&](auto & stat) { setStatus(stat, validation_status_.is_valid_curvature, "curvature is too large"); }); - d.add(ns + "lateral_acceleration", [&](auto & stat) { + d->add(ns + "lateral_acceleration", [&](auto & stat) { setStatus(stat, validation_status_.is_valid_lateral_acc, "lateral acceleration is too large"); }); - d.add(ns + "acceleration", [&](auto & stat) { + d->add(ns + "acceleration", [&](auto & stat) { setStatus(stat, validation_status_.is_valid_longitudinal_max_acc, "acceleration is too large"); }); - d.add(ns + "deceleration", [&](auto & stat) { + d->add(ns + "deceleration", [&](auto & stat) { setStatus(stat, validation_status_.is_valid_longitudinal_min_acc, "deceleration is too large"); }); - d.add(ns + "steering", [&](auto & stat) { + d->add(ns + "steering", [&](auto & stat) { setStatus(stat, validation_status_.is_valid_steering, "expected steering is too large"); }); - d.add(ns + "steering_rate", [&](auto & stat) { + d->add(ns + "steering_rate", [&](auto & stat) { setStatus( stat, validation_status_.is_valid_steering_rate, "expected steering rate is too large"); }); - d.add(ns + "velocity_deviation", [&](auto & stat) { + d->add(ns + "velocity_deviation", [&](auto & stat) { setStatus( stat, validation_status_.is_valid_velocity_deviation, "velocity deviation is too large"); }); @@ -174,11 +171,15 @@ void PlanningValidator::onTrajectory(const Trajectory::ConstSharedPtr msg) if (!isDataReady()) return; + if (publish_diag_ && !diag_updater_) { + setupDiag(); // run setup after all data is ready. + } + debug_pose_publisher_->clearMarkers(); validate(*current_trajectory_); - diag_updater_.force_update(); + diag_updater_->force_update(); publishTrajectory(); From 4e00bf2c9d650b66a50ea1b984e2f574422df2c1 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Thu, 2 Nov 2023 12:21:37 +0900 Subject: [PATCH 106/202] fix(lane_change): stop point activated too early (#5402) * fix(lane_change): stop point activated too early Signed-off-by: Muhammad Zulfaqar Azmi * refactor Signed-off-by: Zulfaqar Azmi * fix dead node Signed-off-by: Muhammad Zulfaqar Azmi --------- Signed-off-by: Muhammad Zulfaqar Azmi Signed-off-by: Zulfaqar Azmi --- .../src/scene_module/lane_change/normal.cpp | 47 +++++++++++++------ 1 file changed, 33 insertions(+), 14 deletions(-) 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 58a8e7e181e35..f2c6782b3ef6e 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 @@ -222,6 +222,23 @@ void NormalLaneChange::insertStopPoint( const auto target_objects = getTargetObjects(status_.current_lanes, status_.target_lanes); double stopping_distance = distance_to_terminal - lane_change_buffer - stop_point_buffer; + const auto is_valid_start_point = std::invoke([&]() -> bool { + auto lc_start_point = lanelet::utils::conversion::toLaneletPoint( + status_.lane_change_path.info.lane_changing_start.position); + const auto target_neighbor_preferred_lane_poly_2d = + utils::lane_change::getTargetNeighborLanesPolygon( + *route_handler, status_.current_lanes, type_); + return boost::geometry::covered_by( + lanelet::traits::to2D(lc_start_point), target_neighbor_preferred_lane_poly_2d); + }); + + if (!is_valid_start_point) { + const auto stop_point = utils::insertStopPoint(stopping_distance, path); + setStopPose(stop_point.point.pose); + + return; + } + // calculate minimum distance from path front to the stationary object on the ego lane. const auto distance_to_ego_lane_obj = [&]() -> double { double distance_to_obj = distance_to_terminal; @@ -646,7 +663,8 @@ double NormalLaneChange::calcMaximumLaneChangeLength( const auto shift_intervals = getRouteHandler()->getLateralIntervalsToPreferredLane(current_terminal_lanelet); return utils::lane_change::calcMaximumLaneChangeLength( - getEgoVelocity(), getCommonParam(), shift_intervals, max_acc); + std::max(getCommonParam().minimum_lane_changing_velocity, getEgoVelocity()), getCommonParam(), + shift_intervals, max_acc); } std::vector NormalLaneChange::sampleLongitudinalAccValues( @@ -1250,6 +1268,20 @@ bool NormalLaneChange::getLaneChangePaths( boost::geometry::covered_by(lc_start_point, target_neighbor_preferred_lane_poly_2d) || boost::geometry::covered_by(lc_start_point, target_lane_poly_2d); + LaneChangeInfo lane_change_info; + lane_change_info.longitudinal_acceleration = + LaneChangePhaseInfo{longitudinal_acc_on_prepare, longitudinal_acc_on_lane_changing}; + lane_change_info.duration = LaneChangePhaseInfo{prepare_duration, lane_changing_time}; + lane_change_info.velocity = + LaneChangePhaseInfo{prepare_velocity, initial_lane_changing_velocity}; + lane_change_info.length = LaneChangePhaseInfo{prepare_length, lane_changing_length}; + lane_change_info.current_lanes = current_lanes; + lane_change_info.target_lanes = target_lanes; + lane_change_info.lane_changing_start = prepare_segment.points.back().point.pose; + lane_change_info.lane_changing_end = target_segment.points.front().point.pose; + lane_change_info.lateral_acceleration = lateral_acc; + lane_change_info.terminal_lane_changing_velocity = terminal_lane_changing_velocity; + if (!is_valid_start_point) { debug_print( "Reject: lane changing points are not inside of the target preferred lanes or its " @@ -1269,21 +1301,8 @@ bool NormalLaneChange::getLaneChangePaths( continue; } - LaneChangeInfo lane_change_info; - lane_change_info.longitudinal_acceleration = - LaneChangePhaseInfo{longitudinal_acc_on_prepare, longitudinal_acc_on_lane_changing}; - lane_change_info.duration = LaneChangePhaseInfo{prepare_duration, lane_changing_time}; - lane_change_info.velocity = - LaneChangePhaseInfo{prepare_velocity, initial_lane_changing_velocity}; - lane_change_info.length = LaneChangePhaseInfo{prepare_length, lane_changing_length}; - lane_change_info.current_lanes = current_lanes; - lane_change_info.target_lanes = target_lanes; - lane_change_info.lane_changing_start = prepare_segment.points.back().point.pose; - lane_change_info.lane_changing_end = target_segment.points.front().point.pose; lane_change_info.shift_line = utils::lane_change::getLaneChangingShiftLine( prepare_segment, target_segment, target_lane_reference_path, shift_length); - lane_change_info.lateral_acceleration = lateral_acc; - lane_change_info.terminal_lane_changing_velocity = terminal_lane_changing_velocity; const auto candidate_path = utils::lane_change::constructCandidatePath( lane_change_info, prepare_segment, target_segment, target_lane_reference_path, From 70e3c79fd88c2f9a4e6da6674fa90ed9c106b51d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Thu, 2 Nov 2023 08:08:56 +0300 Subject: [PATCH 107/202] fix(raw_vehicle_cmd_converter): return false if table is empty (#5463) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- vehicle/raw_vehicle_cmd_converter/src/csv_loader.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/vehicle/raw_vehicle_cmd_converter/src/csv_loader.cpp b/vehicle/raw_vehicle_cmd_converter/src/csv_loader.cpp index 7e42551454e24..a6a331a0e7324 100644 --- a/vehicle/raw_vehicle_cmd_converter/src/csv_loader.cpp +++ b/vehicle/raw_vehicle_cmd_converter/src/csv_loader.cpp @@ -85,6 +85,10 @@ bool CSVLoader::validateMap(const Map & map, const bool is_col_decent) bool CSVLoader::validateData(const Table & table, const std::string & csv_path) { + if (table.empty()) { + std::cerr << "The table is empty." << std::endl; + return false; + } if (table[0].size() < 2) { std::cerr << "Cannot read " << csv_path.c_str() << " CSV file should have at least 2 column" << std::endl; From 5fc1bd856a5f3d87881c545693263475b4583a46 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 2 Nov 2023 16:23:14 +0900 Subject: [PATCH 108/202] refactor(tier4_planning_launch): use xml style launch (#5448) * refactor(tier4_planning_launch): use xml style launch Signed-off-by: satoshi-ota * refactor(tier4_planning_launch): remove python style launch Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../launch/planning.launch.xml | 39 +-- .../scenario_planning/lane_driving.launch.xml | 10 +- .../behavior_planning.launch.py | 322 ------------------ .../behavior_planning.launch.xml | 170 +++++++-- .../behavior_planning/compare_map.launch.py | 89 ----- .../vector_map_inside_area_filter.launch.py | 88 ----- .../scenario_planning.launch.xml | 10 +- 7 files changed, 149 insertions(+), 579 deletions(-) delete mode 100644 launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py delete mode 100644 launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/compare_map.launch.py delete mode 100644 launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/vector_map_inside_area_filter.launch.py diff --git a/launch/tier4_planning_launch/launch/planning.launch.xml b/launch/tier4_planning_launch/launch/planning.launch.xml index 6ace3f423d1bc..61020a503fd4c 100644 --- a/launch/tier4_planning_launch/launch/planning.launch.xml +++ b/launch/tier4_planning_launch/launch/planning.launch.xml @@ -1,35 +1,8 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - @@ -40,9 +13,6 @@ - - - @@ -59,14 +29,7 @@ - - - - - - - - + diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving.launch.xml index 5f17256df6b5c..b8df4722b8087 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving.launch.xml @@ -6,12 +6,10 @@ - - - - - - + + + + diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py deleted file mode 100644 index f535fe1184d74..0000000000000 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py +++ /dev/null @@ -1,322 +0,0 @@ -# Copyright 2021-2023 TIER IV, Inc. All rights reserved. -# -# 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 launch -from launch.actions import DeclareLaunchArgument -from launch.actions import GroupAction -from launch.actions import IncludeLaunchDescription -from launch.actions import OpaqueFunction -from launch.actions import SetLaunchConfiguration -from launch.conditions import IfCondition -from launch.conditions import UnlessCondition -from launch.launch_description_sources import PythonLaunchDescriptionSource -from launch.substitutions import LaunchConfiguration -from launch.substitutions import PythonExpression -from launch_ros.actions import ComposableNodeContainer -from launch_ros.descriptions import ComposableNode -from launch_ros.substitutions import FindPackageShare -import yaml - - -def launch_setup(context, *args, **kwargs): - # vehicle information parameter - vehicle_param_path = LaunchConfiguration("vehicle_param_file").perform(context) - with open(vehicle_param_path, "r") as f: - vehicle_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - # common parameter - with open(LaunchConfiguration("common_param_path").perform(context), "r") as f: - common_param = yaml.safe_load(f)["/**"]["ros__parameters"] - # nearest search parameter - with open(LaunchConfiguration("nearest_search_param_path").perform(context), "r") as f: - nearest_search_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - # behavior path planner - with open(LaunchConfiguration("side_shift_param_path").perform(context), "r") as f: - side_shift_param = yaml.safe_load(f)["/**"]["ros__parameters"] - with open(LaunchConfiguration("avoidance_param_path").perform(context), "r") as f: - avoidance_param = yaml.safe_load(f)["/**"]["ros__parameters"] - with open(LaunchConfiguration("avoidance_by_lc_param_path").perform(context), "r") as f: - avoidance_by_lc_param = yaml.safe_load(f)["/**"]["ros__parameters"] - with open(LaunchConfiguration("dynamic_avoidance_param_path").perform(context), "r") as f: - dynamic_avoidance_param = yaml.safe_load(f)["/**"]["ros__parameters"] - with open(LaunchConfiguration("lane_change_param_path").perform(context), "r") as f: - lane_change_param = yaml.safe_load(f)["/**"]["ros__parameters"] - with open(LaunchConfiguration("goal_planner_param_path").perform(context), "r") as f: - goal_planner_param = yaml.safe_load(f)["/**"]["ros__parameters"] - with open(LaunchConfiguration("start_planner_param_path").perform(context), "r") as f: - start_planner_param = yaml.safe_load(f)["/**"]["ros__parameters"] - with open(LaunchConfiguration("drivable_area_expansion_param_path").perform(context), "r") as f: - drivable_area_expansion_param = yaml.safe_load(f)["/**"]["ros__parameters"] - with open(LaunchConfiguration("scene_module_manager_param_path").perform(context), "r") as f: - scene_module_manager_param = yaml.safe_load(f)["/**"]["ros__parameters"] - with open(LaunchConfiguration("behavior_path_planner_param_path").perform(context), "r") as f: - behavior_path_planner_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - glog_component = ComposableNode( - package="glog_component", - plugin="GlogComponent", - name="glog_component", - ) - - behavior_path_planner_component = ComposableNode( - package="behavior_path_planner", - plugin="behavior_path_planner::BehaviorPathPlannerNode", - name="behavior_path_planner", - namespace="", - remappings=[ - ("~/input/route", LaunchConfiguration("input_route_topic_name")), - ("~/input/vector_map", LaunchConfiguration("map_topic_name")), - ("~/input/perception", "/perception/object_recognition/objects"), - ("~/input/occupancy_grid_map", "/perception/occupancy_grid_map/map"), - ( - "~/input/costmap", - "/planning/scenario_planning/parking/costmap_generator/occupancy_grid", - ), - ( - "~/input/traffic_signals", - "/perception/traffic_light_recognition/traffic_signals", - ), - ("~/input/odometry", "/localization/kinematic_state"), - ("~/input/accel", "/localization/acceleration"), - ("~/input/scenario", "/planning/scenario_planning/scenario"), - ("~/output/path", "path_with_lane_id"), - ("~/output/turn_indicators_cmd", "/planning/turn_indicators_cmd"), - ("~/output/hazard_lights_cmd", "/planning/hazard_lights_cmd"), - ("~/output/modified_goal", "/planning/scenario_planning/modified_goal"), - ("~/output/stop_reasons", "/planning/scenario_planning/status/stop_reasons"), - ], - parameters=[ - common_param, - nearest_search_param, - side_shift_param, - avoidance_param, - avoidance_by_lc_param, - dynamic_avoidance_param, - lane_change_param, - goal_planner_param, - start_planner_param, - drivable_area_expansion_param, - scene_module_manager_param, - behavior_path_planner_param, - vehicle_param, - { - "lane_change.enable_collision_check_at_prepare_phase": LaunchConfiguration( - "use_experimental_lane_change_function" - ), - "lane_change.use_predicted_path_outside_lanelet": LaunchConfiguration( - "use_experimental_lane_change_function" - ), - "lane_change.use_all_predicted_path": LaunchConfiguration( - "use_experimental_lane_change_function" - ), - }, - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - # smoother param - with open( - LaunchConfiguration("motion_velocity_smoother_param_path").perform(context), "r" - ) as f: - motion_velocity_smoother_param = yaml.safe_load(f)["/**"]["ros__parameters"] - with open( - LaunchConfiguration("behavior_velocity_smoother_type_param_path").perform(context), "r" - ) as f: - behavior_velocity_smoother_type_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - # behavior velocity planner - behavior_velocity_planner_common_param_path = LaunchConfiguration( - "behavior_velocity_planner_common_param_path" - ).perform(context) - behavior_velocity_planner_module_param_paths = LaunchConfiguration( - "behavior_velocity_planner_module_param_paths" - ).perform(context) - - behavior_velocity_planner_params_paths = [ - behavior_velocity_planner_common_param_path, - *yaml.safe_load(behavior_velocity_planner_module_param_paths), - ] - - behavior_velocity_planner_params = {} - for path in behavior_velocity_planner_params_paths: - with open(path) as f: - behavior_velocity_planner_params.update(yaml.safe_load(f)["/**"]["ros__parameters"]) - - behavior_velocity_planner_component = ComposableNode( - package="behavior_velocity_planner", - plugin="behavior_velocity_planner::BehaviorVelocityPlannerNode", - name="behavior_velocity_planner", - namespace="", - remappings=[ - ("~/input/path_with_lane_id", "path_with_lane_id"), - ("~/input/vector_map", "/map/vector_map"), - ("~/input/vehicle_odometry", "/localization/kinematic_state"), - ("~/input/accel", "/localization/acceleration"), - ("~/input/dynamic_objects", "/perception/object_recognition/objects"), - ( - "~/input/no_ground_pointcloud", - "/perception/obstacle_segmentation/pointcloud", - ), - ( - "~/input/compare_map_filtered_pointcloud", - "compare_map_filtered/pointcloud", - ), - ( - "~/input/vector_map_inside_area_filtered_pointcloud", - "vector_map_inside_area_filtered/pointcloud", - ), - ( - "~/input/traffic_signals", - "/perception/traffic_light_recognition/traffic_signals", - ), - ( - "~/input/external_velocity_limit_mps", - "/planning/scenario_planning/max_velocity_default", - ), - ("~/input/virtual_traffic_light_states", "/awapi/tmp/virtual_traffic_light_states"), - ( - "~/input/occupancy_grid", - "/perception/occupancy_grid_map/map", - ), - ("~/output/path", "path"), - ("~/output/stop_reasons", "/planning/scenario_planning/status/stop_reasons"), - ( - "~/output/infrastructure_commands", - "/planning/scenario_planning/status/infrastructure_commands", - ), - ("~/output/traffic_signal", "debug/traffic_signal"), - ], - parameters=[ - nearest_search_param, - behavior_velocity_planner_params, - vehicle_param, - common_param, - motion_velocity_smoother_param, - behavior_velocity_smoother_type_param, - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - container = ComposableNodeContainer( - name="behavior_planning_container", - namespace="", - package="rclcpp_components", - executable=LaunchConfiguration("container_executable"), - composable_node_descriptions=[ - behavior_path_planner_component, - behavior_velocity_planner_component, - glog_component, - ], - output="screen", - ) - - # This condition is true if run_out module is enabled and its detection method is Points - run_out_module = "behavior_velocity_planner::RunOutModulePlugin" - run_out_method = behavior_velocity_planner_params.get("run_out", {}).get("detection_method") - launch_run_out = run_out_module in behavior_velocity_planner_params["launch_modules"] - launch_run_out_with_points_method = launch_run_out and run_out_method == "Points" - - # load compare map for run_out module - load_compare_map = IncludeLaunchDescription( - PythonLaunchDescriptionSource( - [ - FindPackageShare("tier4_planning_launch"), - "/launch/scenario_planning/lane_driving/behavior_planning/compare_map.launch.py", - ], - ), - launch_arguments={ - "use_pointcloud_container": LaunchConfiguration("use_pointcloud_container"), - "container_name": LaunchConfiguration("container_name"), - "use_multithread": "true", - }.items(), - # launch compare map only when run_out module is enabled and detection method is Points - condition=IfCondition(PythonExpression(str(launch_run_out_with_points_method))), - ) - - load_vector_map_inside_area_filter = IncludeLaunchDescription( - PythonLaunchDescriptionSource( - [ - FindPackageShare("tier4_planning_launch"), - "/launch/scenario_planning/lane_driving/behavior_planning/vector_map_inside_area_filter.launch.py", - ] - ), - launch_arguments={ - "use_pointcloud_container": LaunchConfiguration("use_pointcloud_container"), - "container_name": LaunchConfiguration("container_name"), - "use_multithread": "true", - "polygon_type": "no_obstacle_segmentation_area_for_run_out", - }.items(), - # launch vector map filter only when run_out module is enabled and detection method is Points - condition=IfCondition(PythonExpression(str(launch_run_out_with_points_method))), - ) - - group = GroupAction( - [ - container, - load_compare_map, - load_vector_map_inside_area_filter, - ] - ) - - return [group] - - -def generate_launch_description(): - launch_arguments = [] - - def add_launch_arg(name: str, default_value=None, description=None): - launch_arguments.append( - DeclareLaunchArgument(name, default_value=default_value, description=description) - ) - - # vehicle parameter - add_launch_arg("vehicle_param_file") - - # interface parameter - add_launch_arg( - "input_route_topic_name", "/planning/mission_planning/route", "input topic of route" - ) - add_launch_arg("map_topic_name", "/map/vector_map", "input topic of map") - - # package parameter - add_launch_arg("use_experimental_lane_change_function") - - # component - add_launch_arg("use_intra_process", "false", "use ROS 2 component container communication") - add_launch_arg("use_multithread", "false", "use multithread") - - # for points filter of run out module - add_launch_arg("use_pointcloud_container", "true") - add_launch_arg("container_name", "pointcloud_container") - - set_container_executable = SetLaunchConfiguration( - "container_executable", - "component_container", - condition=UnlessCondition(LaunchConfiguration("use_multithread")), - ) - set_container_mt_executable = SetLaunchConfiguration( - "container_executable", - "component_container_mt", - condition=IfCondition(LaunchConfiguration("use_multithread")), - ) - - return launch.LaunchDescription( - launch_arguments - + [ - set_container_executable, - set_container_mt_executable, - ] - + [OpaqueFunction(function=launch_setup)] - ) diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml index 8ffa682030a99..4df5152e2ebce 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml @@ -1,31 +1,147 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/compare_map.launch.py b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/compare_map.launch.py deleted file mode 100644 index 474afb4da7d5d..0000000000000 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/compare_map.launch.py +++ /dev/null @@ -1,89 +0,0 @@ -# Copyright 2022 TIER IV, Inc. All rights reserved. -# -# 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. - -from launch import LaunchDescription -from launch.actions import DeclareLaunchArgument -from launch.actions import SetLaunchConfiguration -from launch.conditions import IfCondition -from launch.conditions import UnlessCondition -from launch.substitutions import LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer -from launch_ros.actions import LoadComposableNodes -from launch_ros.descriptions import ComposableNode - - -def generate_launch_description(): - def add_launch_arg(name: str, default_value=None): - return DeclareLaunchArgument(name, default_value=default_value) - - set_container_executable = SetLaunchConfiguration( - "container_executable", - "component_container", - condition=UnlessCondition(LaunchConfiguration("use_multithread")), - ) - - set_container_mt_executable = SetLaunchConfiguration( - "container_executable", - "component_container_mt", - condition=IfCondition(LaunchConfiguration("use_multithread")), - ) - - composable_nodes = [ - ComposableNode( - package="compare_map_segmentation", - plugin="compare_map_segmentation::VoxelDistanceBasedCompareMapFilterComponent", - name="voxel_distance_based_compare_map_filter_node", - remappings=[ - ("input", "/perception/obstacle_segmentation/pointcloud"), - ("map", "/map/pointcloud_map"), - ("output", "compare_map_filtered/pointcloud"), - ], - parameters=[ - { - "distance_threshold": 0.7, - } - ], - extra_arguments=[ - {"use_intra_process_comms": False} # this node has QoS of transient local - ], - ), - ] - - compare_map_container = ComposableNodeContainer( - name="compare_map_container", - namespace="", - package="rclcpp_components", - executable=LaunchConfiguration("container_executable"), - composable_node_descriptions=composable_nodes, - condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")), - output="screen", - ) - - load_composable_nodes = LoadComposableNodes( - composable_node_descriptions=composable_nodes, - target_container=LaunchConfiguration("container_name"), - condition=IfCondition(LaunchConfiguration("use_pointcloud_container")), - ) - - return LaunchDescription( - [ - add_launch_arg("use_multithread", "true"), - add_launch_arg("use_pointcloud_container", "true"), - add_launch_arg("container_name", "compare_map_container"), - set_container_executable, - set_container_mt_executable, - compare_map_container, - load_composable_nodes, - ] - ) diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/vector_map_inside_area_filter.launch.py b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/vector_map_inside_area_filter.launch.py deleted file mode 100644 index 4b3d071dacd7f..0000000000000 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/vector_map_inside_area_filter.launch.py +++ /dev/null @@ -1,88 +0,0 @@ -# Copyright 2022 TIER IV, Inc. All rights reserved. -# -# 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. - -from launch import LaunchDescription -from launch.actions import DeclareLaunchArgument -from launch.actions import SetLaunchConfiguration -from launch.conditions import IfCondition -from launch.conditions import UnlessCondition -from launch.substitutions import LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer -from launch_ros.actions import LoadComposableNodes -from launch_ros.descriptions import ComposableNode - - -def generate_launch_description(): - def add_launch_arg(name: str, default_value=None): - return DeclareLaunchArgument(name, default_value=default_value) - - set_container_executable = SetLaunchConfiguration( - "container_executable", - "component_container", - condition=UnlessCondition(LaunchConfiguration("use_multithread")), - ) - - set_container_mt_executable = SetLaunchConfiguration( - "container_executable", - "component_container_mt", - condition=IfCondition(LaunchConfiguration("use_multithread")), - ) - - composable_nodes = [ - ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::VectorMapInsideAreaFilterComponent", - name="vector_map_inside_area_filter_node", - remappings=[ - ("input", "compare_map_filtered/pointcloud"), - ("input/vector_map", "/map/vector_map"), - ("output", "vector_map_inside_area_filtered/pointcloud"), - ], - parameters=[ - { - "polygon_type": LaunchConfiguration("polygon_type"), - } - ], - # this node has QoS of transient local - extra_arguments=[{"use_intra_process_comms": False}], - ), - ] - - vector_map_area_filter_container = ComposableNodeContainer( - name="vector_map_area_filter_container", - namespace="", - package="rclcpp_components", - executable=LaunchConfiguration("container_executable"), - composable_node_descriptions=composable_nodes, - condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")), - output="screen", - ) - - load_composable_nodes = LoadComposableNodes( - composable_node_descriptions=composable_nodes, - target_container=LaunchConfiguration("container_name"), - condition=IfCondition(LaunchConfiguration("use_pointcloud_container")), - ) - - return LaunchDescription( - [ - add_launch_arg("use_multithread", "true"), - add_launch_arg("use_pointcloud_container", "true"), - add_launch_arg("container_name", "vector_map_area_filter_container"), - set_container_executable, - set_container_mt_executable, - vector_map_area_filter_container, - load_composable_nodes, - ] - ) 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 b293c5836817d..d06dfa214c275 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 @@ -50,15 +50,7 @@ - - - - - - - - - + From 3caaa34524697d37f43c1a19ece21052ce1ba423 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Thu, 2 Nov 2023 18:20:05 +0900 Subject: [PATCH 109/202] docs(logger_level_reconfigure): update readme (#5471) Signed-off-by: Takamasa Horibe --- common/tier4_logging_level_configure_rviz_plugin/README.md | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/common/tier4_logging_level_configure_rviz_plugin/README.md b/common/tier4_logging_level_configure_rviz_plugin/README.md index c3523ed802205..8df17a82e3de7 100644 --- a/common/tier4_logging_level_configure_rviz_plugin/README.md +++ b/common/tier4_logging_level_configure_rviz_plugin/README.md @@ -3,3 +3,7 @@ This package provides an rviz_plugin that can easily change the logger level of each node ![tier4_logging_level_configure_rviz_plugin](tier4_logging_level_configure_rviz_plugin.png) + +This plugin dispatches services to the "logger name" associated with "nodes" specified in YAML, adjusting the logger level. + +As of November 2023, in ROS 2 Humble, users are required to initiate a service server in the node to use this feature. (This might be integrated into ROS standards in the future.) For easy service server generation, you can use the [LoggerLevelConfigure](https://github.com/autowarefoundation/autoware.universe/blob/main/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/logger_level_configure.hpp) utility. From 477030bb7f2e074da48707d9769e2301538c807f Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Thu, 2 Nov 2023 23:12:34 +0900 Subject: [PATCH 110/202] chore(map_loader): update readme (#5468) * chore(map_loader): update readme Signed-off-by: kminoda * make the annotation bold Signed-off-by: kminoda * fix Signed-off-by: kminoda --------- Signed-off-by: kminoda --- map/map_loader/README.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/map/map_loader/README.md b/map/map_loader/README.md index e39b6d66af86c..65d9594cb7415 100644 --- a/map/map_loader/README.md +++ b/map/map_loader/README.md @@ -14,6 +14,8 @@ Currently, it supports the following two types: - Send partial pointcloud map loading via ROS 2 service - Send differential pointcloud map loading via ROS 2 service +NOTE: **We strongly recommend to use divided maps when using large pointcloud map to enable the latter two features (partial and differential load). Please go through the prerequisites section for more details, and follow the instruction for dividing the map and preparing the metadata.** + ### Prerequisites #### Prerequisites on pointcloud map file(s) From fc5e41f8334ac9d627a8fd94fc23f95aa82045a8 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Thu, 2 Nov 2023 19:05:16 +0300 Subject: [PATCH 111/202] ci(sync-files): add mkdocs_macros module (#5475) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .github/sync-files.yaml | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/.github/sync-files.yaml b/.github/sync-files.yaml index f9cb3065f12a7..4aecdc3f8a1ed 100644 --- a/.github/sync-files.yaml +++ b/.github/sync-files.yaml @@ -84,4 +84,8 @@ sd "/edit/main/docs/" "/edit/main/" {source} sd "docs_dir: .*" "docs_dir: ." {source} sd "assets/(\w+)" "docs/assets/\$1" {source} + sd -- \ + " - macros" \ + " - macros: + module_name: mkdocs_macros" {source} - source: docs/assets/js/mathjax.js From b56c72104e880e162b1d77dba5372c43c6cbf562 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Fri, 3 Nov 2023 02:48:00 +0300 Subject: [PATCH 112/202] ci(sync-files): change stale label to type:stale (#5474) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * fix a single space in mkdocs_macro Signed-off-by: M. Fatih Cırıt --- .github/sync-files.yaml | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/.github/sync-files.yaml b/.github/sync-files.yaml index 4aecdc3f8a1ed..632a0f53ec190 100644 --- a/.github/sync-files.yaml +++ b/.github/sync-files.yaml @@ -12,6 +12,8 @@ - source: .github/PULL_REQUEST_TEMPLATE/standard-change.md - source: .github/dependabot.yaml - source: .github/stale.yml + pre-commands: | + sd "staleLabel: stale" "staleLabel: type:stale" {source} - source: .github/workflows/cancel-previous-workflows.yaml - source: .github/workflows/github-release.yaml - source: .github/workflows/pre-commit.yaml @@ -87,5 +89,5 @@ sd -- \ " - macros" \ " - macros: - module_name: mkdocs_macros" {source} + module_name: mkdocs_macros" {source} - source: docs/assets/js/mathjax.js From 6787bb23cf9454c1495d9819abeac9db2c5f45e2 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Fri, 3 Nov 2023 13:25:03 +0300 Subject: [PATCH 113/202] ci(sync-files): change stale label to status:stale (#5474) (#5478) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .github/sync-files.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/sync-files.yaml b/.github/sync-files.yaml index 632a0f53ec190..4d316b9fb2481 100644 --- a/.github/sync-files.yaml +++ b/.github/sync-files.yaml @@ -13,7 +13,7 @@ - source: .github/dependabot.yaml - source: .github/stale.yml pre-commands: | - sd "staleLabel: stale" "staleLabel: type:stale" {source} + sd "staleLabel: stale" "staleLabel: status:stale" {source} - source: .github/workflows/cancel-previous-workflows.yaml - source: .github/workflows/github-release.yaml - source: .github/workflows/pre-commit.yaml From 9f3f89bce8da9e35fd38350c8e338081d873efc4 Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Fri, 3 Nov 2023 10:31:22 +0000 Subject: [PATCH 114/202] chore: sync files (#5216) Signed-off-by: GitHub Co-authored-by: github-actions --- .github/stale.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/stale.yml b/.github/stale.yml index 84928d1b815ee..bc99e4383cafd 100644 --- a/.github/stale.yml +++ b/.github/stale.yml @@ -4,7 +4,7 @@ daysUntilClose: false # Label to use when marking as stale -staleLabel: stale +staleLabel: status:stale # Comment to post when marking as stale markComment: > From 34ce9a99b0c6c6bd877f9b172ed890353e7c9600 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Fri, 3 Nov 2023 13:58:49 +0300 Subject: [PATCH 115/202] ci(pr-labeler): update the labeler.yaml to include "component:" (#5476) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .github/labeler.yaml | 30 +++++++++++++++--------------- 1 file changed, 15 insertions(+), 15 deletions(-) diff --git a/.github/labeler.yaml b/.github/labeler.yaml index 205a24fc7e8f6..540add45fd24e 100644 --- a/.github/labeler.yaml +++ b/.github/labeler.yaml @@ -1,4 +1,4 @@ -ci: +"component:ci": - .github/**/* - "*.json" - "*.yaml" @@ -6,36 +6,36 @@ ci: - .clang-format - .gitignore - .prettierignore -documentation: +"component:documentation": - docs/**/* - "**/*.md" - "**/*.rst" - "**/*.jpg" - "**/*.png" - "**/*.svg" -common: +"component:common": - common/**/* -control: +"component:control": - control/**/* -evaluator: +"component:evaluator": - evaluator/**/* -launch: +"component:launch": - launch/**/* -localization: +"component:localization": - localization/**/* -map: +"component:map": - map/**/* -perception: +"component:perception": - perception/**/* -planning: +"component:planning": - planning/**/* -sensing: +"component:sensing": - sensing/**/* -simulator: +"component:simulator": - simulator/**/* -system: +"component:system": - system/**/* -tools: +"component:tools": - tools/**/* -vehicle: +"component:vehicle": - vehicle/**/* From b43178bfafa6cbac259ce88fbc94b71dd0e3902d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Fri, 3 Nov 2023 14:11:13 +0300 Subject: [PATCH 116/202] ci(pr-labeler): update the labeler.yaml to mark ci and documentation as "type:" (#5479) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .github/labeler.yaml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/labeler.yaml b/.github/labeler.yaml index 540add45fd24e..c3efa2a1a2b15 100644 --- a/.github/labeler.yaml +++ b/.github/labeler.yaml @@ -1,4 +1,4 @@ -"component:ci": +"type:ci": - .github/**/* - "*.json" - "*.yaml" @@ -6,7 +6,7 @@ - .clang-format - .gitignore - .prettierignore -"component:documentation": +"type:documentation": - docs/**/* - "**/*.md" - "**/*.rst" From 7c7bce87aa0b7c1731e4dd75014d047d180db223 Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Fri, 3 Nov 2023 11:43:58 +0000 Subject: [PATCH 117/202] chore: sync files (#5480) Signed-off-by: GitHub Co-authored-by: github-actions --- .github/workflows/sync-files.yaml | 4 ++-- .github/workflows/update-codeowners-from-packages.yaml | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/.github/workflows/sync-files.yaml b/.github/workflows/sync-files.yaml index b9dc5907a50c4..5025e6c8bd7a7 100644 --- a/.github/workflows/sync-files.yaml +++ b/.github/workflows/sync-files.yaml @@ -28,6 +28,6 @@ jobs: with: token: ${{ steps.generate-token.outputs.token }} pr-labels: | - bot - sync-files + tag:bot + tag:sync-files auto-merge-method: squash diff --git a/.github/workflows/update-codeowners-from-packages.yaml b/.github/workflows/update-codeowners-from-packages.yaml index 055d2b02a799a..7898dfe09177a 100644 --- a/.github/workflows/update-codeowners-from-packages.yaml +++ b/.github/workflows/update-codeowners-from-packages.yaml @@ -28,6 +28,6 @@ jobs: with: token: ${{ steps.generate-token.outputs.token }} pr-labels: | - bot - update-codeowners-from-packages + tag:bot + tag:update-codeowners-from-packages auto-merge-method: squash From 726fbd63239a21da86bb4b3c4d91cf33421b34ef Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Fri, 3 Nov 2023 16:48:13 +0300 Subject: [PATCH 118/202] ci(openai-pr-reviewer): update the bot label (#5481) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .github/workflows/openai-pr-reviewer.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/openai-pr-reviewer.yaml b/.github/workflows/openai-pr-reviewer.yaml index 0ba732b580204..4ecbd93198276 100644 --- a/.github/workflows/openai-pr-reviewer.yaml +++ b/.github/workflows/openai-pr-reviewer.yaml @@ -21,7 +21,7 @@ jobs: prevent-no-label-execution: uses: autowarefoundation/autoware-github-actions/.github/workflows/prevent-no-label-execution.yaml@v1 with: - label: openai-pr-reviewer + label: tag:openai-pr-reviewer review: needs: prevent-no-label-execution if: ${{ needs.prevent-no-label-execution.outputs.run == 'true' }} From d37f6b3b3e06a524b81a5feab4f2c65ddb081021 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Fri, 3 Nov 2023 16:53:56 +0300 Subject: [PATCH 119/202] ci(build-and-test-differential): update the required tag (#5482) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .github/workflows/build-and-test-differential.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml index e32dccda70b25..e95f4d46a147b 100644 --- a/.github/workflows/build-and-test-differential.yaml +++ b/.github/workflows/build-and-test-differential.yaml @@ -11,7 +11,7 @@ jobs: prevent-no-label-execution: uses: autowarefoundation/autoware-github-actions/.github/workflows/prevent-no-label-execution.yaml@v1 with: - label: run-build-and-test-differential + label: tag:run-build-and-test-differential build-and-test-differential: needs: prevent-no-label-execution From d351ae0e8ebd27eed9ce0de30aaa783c5a830593 Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Fri, 3 Nov 2023 17:58:29 +0300 Subject: [PATCH 120/202] chore: sync files (#5483) Signed-off-by: GitHub Co-authored-by: github-actions --- .github/dependabot.yaml | 4 ++-- .github/workflows/deploy-docs.yaml | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/.github/dependabot.yaml b/.github/dependabot.yaml index 3f3bf243f639d..0264c035357bd 100644 --- a/.github/dependabot.yaml +++ b/.github/dependabot.yaml @@ -6,5 +6,5 @@ updates: interval: daily open-pull-requests-limit: 1 labels: - - bot - - github-actions + - tag:bot + - type:github-actions diff --git a/.github/workflows/deploy-docs.yaml b/.github/workflows/deploy-docs.yaml index 5f2d09d414806..b48d70dbacb0c 100644 --- a/.github/workflows/deploy-docs.yaml +++ b/.github/workflows/deploy-docs.yaml @@ -22,7 +22,7 @@ jobs: prevent-no-label-execution: uses: autowarefoundation/autoware-github-actions/.github/workflows/prevent-no-label-execution.yaml@v1 with: - label: deploy-docs + label: tag:deploy-docs deploy-docs: needs: prevent-no-label-execution From e1e9f575b90e513dd241d4ce9ec765ec0a9c4694 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Sat, 4 Nov 2023 20:10:12 +0900 Subject: [PATCH 121/202] feat(simple_planning_simulator): add steer dead band (#5477) * feat(simple_planning_simulator): add steer dead band Signed-off-by: kosuke55 * Update simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp Co-authored-by: Takamasa Horibe * Update simulator/simple_planning_simulator/README.md Co-authored-by: Takamasa Horibe * update params Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 Co-authored-by: Takamasa Horibe --- simulator/simple_planning_simulator/README.md | 1 + .../sim_model_delay_steer_acc.hpp | 4 +++- .../sim_model_delay_steer_acc_geared.hpp | 4 +++- .../sim_model_delay_steer_vel.hpp | 4 +++- ...mple_planning_simulator_default.param.yaml | 1 + .../simple_planning_simulator_core.cpp | 7 +++--- .../sim_model_delay_steer_acc.cpp | 19 ++++++++++++---- .../sim_model_delay_steer_acc_geared.cpp | 20 +++++++++++++---- .../sim_model_delay_steer_vel.cpp | 22 ++++++++++++++----- 9 files changed, 62 insertions(+), 20 deletions(-) diff --git a/simulator/simple_planning_simulator/README.md b/simulator/simple_planning_simulator/README.md index ceecacfe8cd8c..75f77489daada 100644 --- a/simulator/simple_planning_simulator/README.md +++ b/simulator/simple_planning_simulator/README.md @@ -74,6 +74,7 @@ The table below shows which models correspond to what parameters. The model name | vel_time_delay | double | dead time for the velocity input | x | x | x | o | x | x | 0.25 | [s] | | acc_time_constant | double | time constant of the 1st-order acceleration dynamics | x | x | x | x | o | o | 0.1 | [s] | | steer_time_constant | double | time constant of the 1st-order steering dynamics | x | x | x | o | o | o | 0.27 | [s] | +| steer_dead_band | double | dead band for steering angle | x | x | x | o | o | o | 0.0 | [rad] | | vel_time_constant | double | time constant of the 1st-order velocity dynamics | x | x | x | o | x | x | 0.5 | [s] | | vel_lim | double | limit of velocity | x | x | x | o | o | o | 50.0 | [m/s] | | vel_rate_lim | double | limit of acceleration | x | x | x | o | o | o | 7.0 | [m/ss] | diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.hpp b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.hpp index 9e7c101e76407..289c607a18d90 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.hpp +++ b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.hpp @@ -39,11 +39,12 @@ class SimModelDelaySteerAcc : public SimModelInterface * @param [in] acc_time_constant time constant for 1D model of accel dynamics * @param [in] steer_delay time delay for steering command [s] * @param [in] steer_time_constant time constant for 1D model of steering dynamics + * @param [in] steer_dead_band dead band for steering angle [rad] */ SimModelDelaySteerAcc( double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, double dt, double acc_delay, double acc_time_constant, double steer_delay, - double steer_time_constant); + double steer_time_constant, double steer_dead_band); /** * @brief default destructor @@ -79,6 +80,7 @@ class SimModelDelaySteerAcc : public SimModelInterface const double acc_time_constant_; //!< @brief time constant for accel dynamics const double steer_delay_; //!< @brief time delay for steering command [s] const double steer_time_constant_; //!< @brief time constant for steering dynamics + const double steer_dead_band_; //!< @brief dead band for steering angle [rad] /** * @brief set queue buffer for input command diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.hpp b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.hpp index 1beec46a48ee9..3bda878f8cd76 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.hpp +++ b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.hpp @@ -39,11 +39,12 @@ class SimModelDelaySteerAccGeared : public SimModelInterface * @param [in] acc_time_constant time constant for 1D model of accel dynamics * @param [in] steer_delay time delay for steering command [s] * @param [in] steer_time_constant time constant for 1D model of steering dynamics + * @param [in] steer_dead_band dead band for steering angle [rad] */ SimModelDelaySteerAccGeared( double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, double dt, double acc_delay, double acc_time_constant, double steer_delay, - double steer_time_constant); + double steer_time_constant, double steer_dead_band); /** * @brief default destructor @@ -79,6 +80,7 @@ class SimModelDelaySteerAccGeared : public SimModelInterface const double acc_time_constant_; //!< @brief time constant for accel dynamics const double steer_delay_; //!< @brief time delay for steering command [s] const double steer_time_constant_; //!< @brief time constant for steering dynamics + const double steer_dead_band_; //!< @brief dead band for steering angle [rad] /** * @brief set queue buffer for input command diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.hpp b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.hpp index 30cf5d3c7c24a..5c1ec55d522bf 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.hpp +++ b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.hpp @@ -42,11 +42,12 @@ class SimModelDelaySteerVel : public SimModelInterface * @param [in] vx_time_constant time constant for 1D model of velocity dynamics * @param [in] steer_delay time delay for steering command [s] * @param [in] steer_time_constant time constant for 1D model of steering dynamics + * @param [in] steer_dead_band dead band for steering angle [rad] */ SimModelDelaySteerVel( double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, double dt, double vx_delay, double vx_time_constant, double steer_delay, - double steer_time_constant); + double steer_time_constant, double steer_dead_band); /** * @brief destructor @@ -84,6 +85,7 @@ class SimModelDelaySteerVel : public SimModelInterface const double steer_delay_; //!< @brief time delay for angular-velocity command [s] const double steer_time_constant_; //!< @brief time constant for 1D model of angular-velocity dynamics + const double steer_dead_band_; //!< @brief dead band for steering angle [rad] /** * @brief set queue buffer for input command diff --git a/simulator/simple_planning_simulator/param/simple_planning_simulator_default.param.yaml b/simulator/simple_planning_simulator/param/simple_planning_simulator_default.param.yaml index d7c002a1fcaa9..dbd56bf9e9bff 100644 --- a/simulator/simple_planning_simulator/param/simple_planning_simulator_default.param.yaml +++ b/simulator/simple_planning_simulator/param/simple_planning_simulator_default.param.yaml @@ -14,6 +14,7 @@ acc_time_constant: 0.1 steer_time_delay: 0.1 steer_time_constant: 0.1 + steer_dead_band: 0.0 x_stddev: 0.0001 # x standard deviation for dummy covariance in map coordinate y_stddev: 0.0001 # y standard deviation for dummy covariance in map coordinate diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp index fb6a5457e8f05..d7e25860c8abf 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp @@ -229,6 +229,7 @@ void SimplePlanningSimulator::initialize_vehicle_model() const double vel_time_constant = declare_parameter("vel_time_constant", 0.5); const double steer_time_delay = declare_parameter("steer_time_delay", 0.24); const double steer_time_constant = declare_parameter("steer_time_constant", 0.27); + const double steer_dead_band = declare_parameter("steer_dead_band", 0.0); const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo(); const double wheelbase = vehicle_info.wheel_base_m; @@ -245,17 +246,17 @@ void SimplePlanningSimulator::initialize_vehicle_model() vehicle_model_type_ = VehicleModelType::DELAY_STEER_VEL; vehicle_model_ptr_ = std::make_shared( vel_lim, steer_lim, vel_rate_lim, steer_rate_lim, wheelbase, timer_sampling_time_ms_ / 1000.0, - vel_time_delay, vel_time_constant, steer_time_delay, steer_time_constant); + vel_time_delay, vel_time_constant, steer_time_delay, steer_time_constant, steer_dead_band); } else if (vehicle_model_type_str == "DELAY_STEER_ACC") { vehicle_model_type_ = VehicleModelType::DELAY_STEER_ACC; vehicle_model_ptr_ = std::make_shared( vel_lim, steer_lim, vel_rate_lim, steer_rate_lim, wheelbase, timer_sampling_time_ms_ / 1000.0, - acc_time_delay, acc_time_constant, steer_time_delay, steer_time_constant); + acc_time_delay, acc_time_constant, steer_time_delay, steer_time_constant, steer_dead_band); } else if (vehicle_model_type_str == "DELAY_STEER_ACC_GEARED") { vehicle_model_type_ = VehicleModelType::DELAY_STEER_ACC_GEARED; vehicle_model_ptr_ = std::make_shared( vel_lim, steer_lim, vel_rate_lim, steer_rate_lim, wheelbase, timer_sampling_time_ms_ / 1000.0, - acc_time_delay, acc_time_constant, steer_time_delay, steer_time_constant); + acc_time_delay, acc_time_constant, steer_time_delay, steer_time_constant, steer_dead_band); } else { throw std::invalid_argument("Invalid vehicle_model_type: " + vehicle_model_type_str); } diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.cpp index 870444acb5215..964157cdeb64c 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.cpp @@ -19,7 +19,7 @@ SimModelDelaySteerAcc::SimModelDelaySteerAcc( double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, double dt, double acc_delay, double acc_time_constant, double steer_delay, - double steer_time_constant) + double steer_time_constant, double steer_dead_band) : SimModelInterface(6 /* dim x */, 2 /* dim u */), MIN_TIME_CONSTANT(0.03), vx_lim_(vx_lim), @@ -30,7 +30,8 @@ SimModelDelaySteerAcc::SimModelDelaySteerAcc( acc_delay_(acc_delay), acc_time_constant_(std::max(acc_time_constant, MIN_TIME_CONSTANT)), steer_delay_(steer_delay), - steer_time_constant_(std::max(steer_time_constant, MIN_TIME_CONSTANT)) + steer_time_constant_(std::max(steer_time_constant, MIN_TIME_CONSTANT)), + steer_dead_band_(steer_dead_band) { initializeInputQueue(dt); } @@ -105,8 +106,18 @@ Eigen::VectorXd SimModelDelaySteerAcc::calcModel( const double steer = state(IDX::STEER); const double acc_des = sat(input(IDX_U::ACCX_DES), vx_rate_lim_, -vx_rate_lim_); const double steer_des = sat(input(IDX_U::STEER_DES), steer_lim_, -steer_lim_); - double steer_rate = -(steer - steer_des) / steer_time_constant_; - steer_rate = sat(steer_rate, steer_rate_lim_, -steer_rate_lim_); + const double steer_diff = steer - steer_des; + const double steer_diff_with_dead_band = std::invoke([&]() { + if (steer_diff > steer_dead_band_) { + return steer_diff - steer_dead_band_; + } else if (steer_diff < -steer_dead_band_) { + return steer_diff + steer_dead_band_; + } else { + return 0.0; + } + }); + const double steer_rate = + sat(-steer_diff_with_dead_band / steer_time_constant_, steer_rate_lim_, -steer_rate_lim_); Eigen::VectorXd d_state = Eigen::VectorXd::Zero(dim_x_); d_state(IDX::X) = vel * cos(yaw); diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.cpp index 5170ed914e0f1..76669c9490fc6 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.cpp @@ -21,7 +21,7 @@ SimModelDelaySteerAccGeared::SimModelDelaySteerAccGeared( double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, double dt, double acc_delay, double acc_time_constant, double steer_delay, - double steer_time_constant) + double steer_time_constant, double steer_dead_band) : SimModelInterface(6 /* dim x */, 2 /* dim u */), MIN_TIME_CONSTANT(0.03), vx_lim_(vx_lim), @@ -32,7 +32,9 @@ SimModelDelaySteerAccGeared::SimModelDelaySteerAccGeared( acc_delay_(acc_delay), acc_time_constant_(std::max(acc_time_constant, MIN_TIME_CONSTANT)), steer_delay_(steer_delay), - steer_time_constant_(std::max(steer_time_constant, MIN_TIME_CONSTANT)) + steer_time_constant_(std::max(steer_time_constant, MIN_TIME_CONSTANT)), + steer_dead_band_(steer_dead_band) + { initializeInputQueue(dt); } @@ -113,8 +115,18 @@ Eigen::VectorXd SimModelDelaySteerAccGeared::calcModel( const double steer = state(IDX::STEER); const double acc_des = sat(input(IDX_U::ACCX_DES), vx_rate_lim_, -vx_rate_lim_); const double steer_des = sat(input(IDX_U::STEER_DES), steer_lim_, -steer_lim_); - double steer_rate = -(steer - steer_des) / steer_time_constant_; - steer_rate = sat(steer_rate, steer_rate_lim_, -steer_rate_lim_); + const double steer_diff = steer - steer_des; + const double steer_diff_with_dead_band = std::invoke([&]() { + if (steer_diff > steer_dead_band_) { + return steer_diff - steer_dead_band_; + } else if (steer_diff < -steer_dead_band_) { + return steer_diff + steer_dead_band_; + } else { + return 0.0; + } + }); + const double steer_rate = + sat(-steer_diff_with_dead_band / steer_time_constant_, steer_rate_lim_, -steer_rate_lim_); Eigen::VectorXd d_state = Eigen::VectorXd::Zero(dim_x_); d_state(IDX::X) = vel * cos(yaw); diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.cpp index 1ac71fbb58c23..6d155ee921107 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.cpp @@ -19,7 +19,7 @@ SimModelDelaySteerVel::SimModelDelaySteerVel( double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, double dt, double vx_delay, double vx_time_constant, double steer_delay, - double steer_time_constant) + double steer_time_constant, double steer_dead_band) : SimModelInterface(5 /* dim x */, 2 /* dim u */), MIN_TIME_CONSTANT(0.03), vx_lim_(vx_lim), @@ -30,7 +30,8 @@ SimModelDelaySteerVel::SimModelDelaySteerVel( vx_delay_(vx_delay), vx_time_constant_(std::max(vx_time_constant, MIN_TIME_CONSTANT)), steer_delay_(steer_delay), - steer_time_constant_(std::max(steer_time_constant, MIN_TIME_CONSTANT)) + steer_time_constant_(std::max(steer_time_constant, MIN_TIME_CONSTANT)), + steer_dead_band_(steer_dead_band) { initializeInputQueue(dt); } @@ -106,11 +107,20 @@ Eigen::VectorXd SimModelDelaySteerVel::calcModel( const double delay_input_vx = input(IDX_U::VX_DES); const double delay_input_steer = input(IDX_U::STEER_DES); const double delay_vx_des = sat(delay_input_vx, vx_lim_, -vx_lim_); + const double vx_rate = sat(-(vx - delay_vx_des) / vx_time_constant_, vx_rate_lim_, -vx_rate_lim_); const double delay_steer_des = sat(delay_input_steer, steer_lim_, -steer_lim_); - double vx_rate = -(vx - delay_vx_des) / vx_time_constant_; - double steer_rate = -(steer - delay_steer_des) / steer_time_constant_; - vx_rate = sat(vx_rate, vx_rate_lim_, -vx_rate_lim_); - steer_rate = sat(steer_rate, steer_rate_lim_, -steer_rate_lim_); + const double steer_diff = steer - delay_steer_des; + const double steer_diff_with_dead_band = std::invoke([&]() { + if (steer_diff > steer_dead_band_) { + return steer_diff - steer_dead_band_; + } else if (steer_diff < -steer_dead_band_) { + return steer_diff + steer_dead_band_; + } else { + return 0.0; + } + }); + const double steer_rate = + sat(-steer_diff_with_dead_band / steer_time_constant_, steer_rate_lim_, -steer_rate_lim_); Eigen::VectorXd d_state = Eigen::VectorXd::Zero(dim_x_); d_state(IDX::X) = vx * cos(yaw); From ee20545d032706d5bb6d42472865f4cffe4e1772 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Sun, 5 Nov 2023 02:11:34 +0900 Subject: [PATCH 122/202] refactor(mpc_lateral_controller): add debug info of qp solver (#5459) * add debug info of qp solver Signed-off-by: kyoichi-sugahara * no info for EigenLeastSquareLLT Signed-off-by: kyoichi-sugahara * return 0 in base class --------- Signed-off-by: kyoichi-sugahara Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../qp_solver/qp_solver_interface.hpp | 4 ++++ .../mpc_lateral_controller/qp_solver/qp_solver_osqp.hpp | 4 ++++ .../qp_solver/qp_solver_unconstraint_fast.hpp | 7 +++++++ control/mpc_lateral_controller/src/mpc.cpp | 6 ++++++ 4 files changed, 21 insertions(+) diff --git a/control/mpc_lateral_controller/include/mpc_lateral_controller/qp_solver/qp_solver_interface.hpp b/control/mpc_lateral_controller/include/mpc_lateral_controller/qp_solver/qp_solver_interface.hpp index e7aa644ad63f9..ca30bd30e4dd1 100644 --- a/control/mpc_lateral_controller/include/mpc_lateral_controller/qp_solver/qp_solver_interface.hpp +++ b/control/mpc_lateral_controller/include/mpc_lateral_controller/qp_solver/qp_solver_interface.hpp @@ -45,6 +45,10 @@ class QPSolverInterface const Eigen::MatrixXd & h_mat, const Eigen::MatrixXd & f_vec, const Eigen::MatrixXd & a, const Eigen::VectorXd & lb, const Eigen::VectorXd & ub, const Eigen::VectorXd & lb_a, const Eigen::VectorXd & ub_a, Eigen::VectorXd & u) = 0; + + virtual int64_t getTakenIter() const { return 0; } + virtual double getRunTime() const { return 0.0; } + virtual double getObjVal() const { return 0.0; } }; } // namespace autoware::motion::control::mpc_lateral_controller #endif // MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_INTERFACE_HPP_ diff --git a/control/mpc_lateral_controller/include/mpc_lateral_controller/qp_solver/qp_solver_osqp.hpp b/control/mpc_lateral_controller/include/mpc_lateral_controller/qp_solver/qp_solver_osqp.hpp index cdb590faab84d..2611f94da324f 100644 --- a/control/mpc_lateral_controller/include/mpc_lateral_controller/qp_solver/qp_solver_osqp.hpp +++ b/control/mpc_lateral_controller/include/mpc_lateral_controller/qp_solver/qp_solver_osqp.hpp @@ -53,6 +53,10 @@ class QPSolverOSQP : public QPSolverInterface const Eigen::VectorXd & lb, const Eigen::VectorXd & ub, const Eigen::VectorXd & lb_a, const Eigen::VectorXd & ub_a, Eigen::VectorXd & u) override; + int64_t getTakenIter() const override { return osqpsolver_.getTakenIter(); } + double getRunTime() const override { return osqpsolver_.getRunTime(); } + double getObjVal() const override { return osqpsolver_.getObjVal(); } + private: autoware::common::osqp::OSQPInterface osqpsolver_; rclcpp::Logger logger_; diff --git a/control/mpc_lateral_controller/include/mpc_lateral_controller/qp_solver/qp_solver_unconstraint_fast.hpp b/control/mpc_lateral_controller/include/mpc_lateral_controller/qp_solver/qp_solver_unconstraint_fast.hpp index 3a6bd2b25832b..ef337eaaa8528 100644 --- a/control/mpc_lateral_controller/include/mpc_lateral_controller/qp_solver/qp_solver_unconstraint_fast.hpp +++ b/control/mpc_lateral_controller/include/mpc_lateral_controller/qp_solver/qp_solver_unconstraint_fast.hpp @@ -53,6 +53,13 @@ class QPSolverEigenLeastSquareLLT : public QPSolverInterface const Eigen::MatrixXd & h_mat, const Eigen::MatrixXd & f_vec, const Eigen::MatrixXd & a, const Eigen::VectorXd & lb, const Eigen::VectorXd & ub, const Eigen::VectorXd & lb_a, const Eigen::VectorXd & ub_a, Eigen::VectorXd & u) override; + + int64_t getTakenIter() const override { return 1; }; + // TODO(someone): calculate runtime and object value, otherwise just return 0 by base class + // double getRunTime() const override { return 0.0; } + // double getObjVal() const override { return 0.0; } + +private: }; } // namespace autoware::motion::control::mpc_lateral_controller #endif // MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_UNCONSTRAINT_FAST_HPP_ diff --git a/control/mpc_lateral_controller/src/mpc.cpp b/control/mpc_lateral_controller/src/mpc.cpp index 0d7aa8aa8b2e6..6bd885b78beb7 100644 --- a/control/mpc_lateral_controller/src/mpc.cpp +++ b/control/mpc_lateral_controller/src/mpc.cpp @@ -147,6 +147,9 @@ Float32MultiArrayStamped MPC::generateDiagData( const double wz_predicted = current_velocity * std::tan(mpc_data.predicted_steer) / wb; const double wz_measured = current_velocity * std::tan(mpc_data.steer) / wb; const double wz_command = current_velocity * std::tan(ctrl_cmd.steering_tire_angle) / wb; + const int iteration_num = m_qpsolver_ptr->getTakenIter(); + const double runtime = m_qpsolver_ptr->getRunTime(); + const double objective_value = m_qpsolver_ptr->getObjVal(); typedef decltype(diagnostic.data)::value_type DiagnosticValueType; const auto append_diag = [&](const auto & val) -> void { @@ -170,6 +173,9 @@ Float32MultiArrayStamped MPC::generateDiagData( append_diag(nearest_k); // [15] nearest path curvature (not smoothed) append_diag(mpc_data.predicted_steer); // [16] predicted steer append_diag(wz_predicted); // [17] angular velocity from predicted steer + append_diag(iteration_num); // [18] iteration number + append_diag(runtime); // [19] runtime of the latest problem solved + append_diag(objective_value); // [20] objective value of the latest problem solved return diagnostic; } From e628971abcbae78f2414567b62decdcc3da73456 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 6 Nov 2023 12:24:38 +0900 Subject: [PATCH 123/202] feat(planning_topic_converter): add new package (#5484) Signed-off-by: satoshi-ota --- .../planning_topic_converter/CMakeLists.txt | 24 +++++++ planning/planning_topic_converter/README.md | 34 +++++++++ .../converter_base.hpp | 51 ++++++++++++++ .../path_to_trajectory.hpp | 45 ++++++++++++ planning/planning_topic_converter/package.xml | 29 ++++++++ .../src/path_to_trajectory.cpp | 69 +++++++++++++++++++ 6 files changed, 252 insertions(+) create mode 100644 planning/planning_topic_converter/CMakeLists.txt create mode 100644 planning/planning_topic_converter/README.md create mode 100644 planning/planning_topic_converter/include/planning_topic_converter/converter_base.hpp create mode 100644 planning/planning_topic_converter/include/planning_topic_converter/path_to_trajectory.hpp create mode 100644 planning/planning_topic_converter/package.xml create mode 100644 planning/planning_topic_converter/src/path_to_trajectory.cpp diff --git a/planning/planning_topic_converter/CMakeLists.txt b/planning/planning_topic_converter/CMakeLists.txt new file mode 100644 index 0000000000000..75b63d26c316f --- /dev/null +++ b/planning/planning_topic_converter/CMakeLists.txt @@ -0,0 +1,24 @@ +cmake_minimum_required(VERSION 3.5) +project(planning_topic_converter) + +### Compile options +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 17) +endif() +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic -Werror) +endif() + +find_package(ament_cmake_auto REQUIRED) +ament_auto_find_build_dependencies() + +ament_auto_add_library(planning_topic_converter SHARED + src/path_to_trajectory.cpp +) + +rclcpp_components_register_node(planning_topic_converter + PLUGIN "planning_topic_converter::PathToTrajectory" + EXECUTABLE path_to_trajectory_converter +) + +ament_auto_package() diff --git a/planning/planning_topic_converter/README.md b/planning/planning_topic_converter/README.md new file mode 100644 index 0000000000000..7be6979e62281 --- /dev/null +++ b/planning/planning_topic_converter/README.md @@ -0,0 +1,34 @@ +# Planning Topic Converter + +## Purpose + +This package provides tools that convert topic type among types are defined in . + +## Inner-workings / Algorithms + +### Usage example + +The tools in this package are provided as composable ROS 2 component nodes, so that they can be spawned into an existing process, launched from launch files, or invoked from the command line. + +```xml + + + + + + + + + +``` + +## Parameters + +| Name | Type | Description | +| :------------- | :----- | :----------------- | +| `input_topic` | string | input topic name. | +| `output_topic` | string | output topic name. | + +## Assumptions / Known limits + +## Future extensions / Unimplemented parts diff --git a/planning/planning_topic_converter/include/planning_topic_converter/converter_base.hpp b/planning/planning_topic_converter/include/planning_topic_converter/converter_base.hpp new file mode 100644 index 0000000000000..a093d9a952029 --- /dev/null +++ b/planning/planning_topic_converter/include/planning_topic_converter/converter_base.hpp @@ -0,0 +1,51 @@ +// 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. + +#ifndef PLANNING_TOPIC_CONVERTER__CONVERTER_BASE_HPP_ +#define PLANNING_TOPIC_CONVERTER__CONVERTER_BASE_HPP_ + +#include "rclcpp/rclcpp.hpp" + +#include +#include + +namespace planning_topic_converter +{ + +template +class ConverterBase : public rclcpp::Node +{ +public: + ConverterBase(const std::string & node_name, const rclcpp::NodeOptions & options) + : rclcpp::Node(node_name, options) + { + const auto input_topic = this->declare_parameter("input_topic"); + const auto output_topic = this->declare_parameter("output_topic"); + + pub_ = this->create_publisher(output_topic, 1); + sub_ = this->create_subscription( + input_topic, 1, std::bind(&ConverterBase::process, this, std::placeholders::_1)); + } + +protected: + virtual void process(const typename InputType::ConstSharedPtr msg) = 0; + typename rclcpp::Publisher::SharedPtr pub_; + typename rclcpp::Subscription::SharedPtr sub_; + +private: +}; + +} // namespace planning_topic_converter + +#endif // PLANNING_TOPIC_CONVERTER__CONVERTER_BASE_HPP_ diff --git a/planning/planning_topic_converter/include/planning_topic_converter/path_to_trajectory.hpp b/planning/planning_topic_converter/include/planning_topic_converter/path_to_trajectory.hpp new file mode 100644 index 0000000000000..f214f2a4d5e2a --- /dev/null +++ b/planning/planning_topic_converter/include/planning_topic_converter/path_to_trajectory.hpp @@ -0,0 +1,45 @@ +// 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. + +#ifndef PLANNING_TOPIC_CONVERTER__PATH_TO_TRAJECTORY_HPP_ +#define PLANNING_TOPIC_CONVERTER__PATH_TO_TRAJECTORY_HPP_ + +#include "planning_topic_converter/converter_base.hpp" +#include "rclcpp/rclcpp.hpp" + +#include +#include + +#include + +namespace planning_topic_converter +{ + +using autoware_auto_planning_msgs::msg::Path; +using autoware_auto_planning_msgs::msg::PathPoint; +using autoware_auto_planning_msgs::msg::Trajectory; +using autoware_auto_planning_msgs::msg::TrajectoryPoint; + +class PathToTrajectory : public ConverterBase +{ +public: + explicit PathToTrajectory(const rclcpp::NodeOptions & options); + +private: + void process(const Path::ConstSharedPtr msg) override; +}; + +} // namespace planning_topic_converter + +#endif // PLANNING_TOPIC_CONVERTER__PATH_TO_TRAJECTORY_HPP_ diff --git a/planning/planning_topic_converter/package.xml b/planning/planning_topic_converter/package.xml new file mode 100644 index 0000000000000..d07d59f3d2c89 --- /dev/null +++ b/planning/planning_topic_converter/package.xml @@ -0,0 +1,29 @@ + + + planning_topic_converter + 0.1.0 + The planning_topic_converter package + + Satoshi OTA + Shumpei Wakabayashi + Kosuke Takeuchi + + Apache License 2.0 + + Satoshi OTA + + ament_cmake_auto + + autoware_auto_planning_msgs + motion_utils + rclcpp + rclcpp_components + tier4_autoware_utils + + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/planning/planning_topic_converter/src/path_to_trajectory.cpp b/planning/planning_topic_converter/src/path_to_trajectory.cpp new file mode 100644 index 0000000000000..5362686617fc7 --- /dev/null +++ b/planning/planning_topic_converter/src/path_to_trajectory.cpp @@ -0,0 +1,69 @@ +// 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. + +#include "planning_topic_converter/path_to_trajectory.hpp" + +#include +#include + +namespace planning_topic_converter +{ +namespace +{ +TrajectoryPoint convertToTrajectoryPoint(const PathPoint & point) +{ + TrajectoryPoint traj_point; + traj_point.pose = tier4_autoware_utils::getPose(point); + traj_point.longitudinal_velocity_mps = point.longitudinal_velocity_mps; + traj_point.lateral_velocity_mps = point.lateral_velocity_mps; + traj_point.heading_rate_rps = point.heading_rate_rps; + return traj_point; +} + +std::vector convertToTrajectoryPoints(const std::vector & points) +{ + std::vector traj_points; + for (const auto & point : points) { + const auto traj_point = convertToTrajectoryPoint(point); + traj_points.push_back(traj_point); + } + return traj_points; +} + +Trajectory createTrajectory( + const std_msgs::msg::Header & header, const std::vector & trajectory_points) +{ + auto trajectory = motion_utils::convertToTrajectory(trajectory_points); + trajectory.header = header; + + return trajectory; +} +} // namespace + +PathToTrajectory::PathToTrajectory(const rclcpp::NodeOptions & options) +: ConverterBase("path_to_trajectory_converter", options) +{ +} + +void PathToTrajectory::process(const Path::ConstSharedPtr msg) +{ + const auto trajectory_points = convertToTrajectoryPoints(msg->points); + const auto output = createTrajectory(msg->header, trajectory_points); + pub_->publish(output); +} + +} // namespace planning_topic_converter + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(planning_topic_converter::PathToTrajectory) From 6b0a81f7ba5582b8d7bc4154e9adcd3aeaa34c3b Mon Sep 17 00:00:00 2001 From: Yuxuan Liu <619684051@qq.com> Date: Mon, 6 Nov 2023 12:58:33 +0800 Subject: [PATCH 124/202] feat(camera_view_plugin): add camera view plugin package (#5472) * add camera view plugin package Signed-off-by: Owen-Liuyuxuan * add readme for short cut Signed-off-by: Owen-Liuyuxuan * style(pre-commit): autofix * change name Signed-off-by: Owen-Liuyuxuan * style(pre-commit): autofix * fix license Signed-off-by: Owen-Liuyuxuan * fix license Signed-off-by: Owen-Liuyuxuan * style(pre-commit): autofix --------- Signed-off-by: Owen-Liuyuxuan Co-authored-by: Owen-Liuyuxuan Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../CMakeLists.txt | 30 ++ .../tier4_camera_view_rviz_plugin/README.md | 9 + .../icons/classes/BirdEyeViewTool.png | Bin 0 -> 18815 bytes .../icons/classes/ThirdPersonViewTool.png | Bin 0 -> 18815 bytes .../tier4_camera_view_rviz_plugin/package.xml | 31 +++ .../plugins/plugin_description.xml | 24 ++ .../src/bird_eye_view_controller.cpp | 242 ++++++++++++++++ .../src/bird_eye_view_controller.hpp | 112 ++++++++ .../src/bird_eye_view_tool.cpp | 167 ++++++++++++ .../src/bird_eye_view_tool.hpp | 144 ++++++++++ .../src/third_person_view_controller.cpp | 258 ++++++++++++++++++ .../src/third_person_view_controller.hpp | 94 +++++++ .../src/third_person_view_tool.cpp | 173 ++++++++++++ .../src/third_person_view_tool.hpp | 144 ++++++++++ 14 files changed, 1428 insertions(+) create mode 100644 common/tier4_camera_view_rviz_plugin/CMakeLists.txt create mode 100644 common/tier4_camera_view_rviz_plugin/README.md create mode 100644 common/tier4_camera_view_rviz_plugin/icons/classes/BirdEyeViewTool.png create mode 100644 common/tier4_camera_view_rviz_plugin/icons/classes/ThirdPersonViewTool.png create mode 100644 common/tier4_camera_view_rviz_plugin/package.xml create mode 100644 common/tier4_camera_view_rviz_plugin/plugins/plugin_description.xml create mode 100644 common/tier4_camera_view_rviz_plugin/src/bird_eye_view_controller.cpp create mode 100644 common/tier4_camera_view_rviz_plugin/src/bird_eye_view_controller.hpp create mode 100644 common/tier4_camera_view_rviz_plugin/src/bird_eye_view_tool.cpp create mode 100644 common/tier4_camera_view_rviz_plugin/src/bird_eye_view_tool.hpp create mode 100644 common/tier4_camera_view_rviz_plugin/src/third_person_view_controller.cpp create mode 100644 common/tier4_camera_view_rviz_plugin/src/third_person_view_controller.hpp create mode 100644 common/tier4_camera_view_rviz_plugin/src/third_person_view_tool.cpp create mode 100644 common/tier4_camera_view_rviz_plugin/src/third_person_view_tool.hpp diff --git a/common/tier4_camera_view_rviz_plugin/CMakeLists.txt b/common/tier4_camera_view_rviz_plugin/CMakeLists.txt new file mode 100644 index 0000000000000..8ae8efef1e4b9 --- /dev/null +++ b/common/tier4_camera_view_rviz_plugin/CMakeLists.txt @@ -0,0 +1,30 @@ +cmake_minimum_required(VERSION 3.14) +project(tier4_camera_view_rviz_plugin) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +find_package(Qt5 REQUIRED Core Widgets) +set(QT_LIBRARIES Qt5::Widgets) +set(CMAKE_AUTOMOC ON) +set(CMAKE_INCLUDE_CURRENT_DIR ON) + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) + add_compile_options(-Wno-unused-parameter) +endif() + +ament_auto_add_library(${PROJECT_NAME} SHARED + src/third_person_view_controller.cpp + src/third_person_view_tool.cpp + src/bird_eye_view_tool.cpp + src/bird_eye_view_controller.cpp +) + +target_link_libraries(${PROJECT_NAME} + ${QT_LIBRARIES} +) + +pluginlib_export_plugin_description_file(rviz_common plugins/plugin_description.xml) + +ament_auto_package(INSTALL_TO_SHARE icons) diff --git a/common/tier4_camera_view_rviz_plugin/README.md b/common/tier4_camera_view_rviz_plugin/README.md new file mode 100644 index 0000000000000..99480d5a92e1c --- /dev/null +++ b/common/tier4_camera_view_rviz_plugin/README.md @@ -0,0 +1,9 @@ +# tier4_camera_view_rviz_plugin + +## ThirdPersonView Tool + +Add the `tier4_camera_view_rviz_plugin/ThirdPersonViewTool` tool to the RViz. Push the button, the camera will focus on the vehicle and set the target frame to `base_link`. Short cut key 'o'. + +## BirdEyeView Tool + +Add the `tier4_camera_view_rviz_plugin/BirdEyeViewTool` tool to the RViz. Push the button, the camera will turn to the BEV view, the target frame is consistent with the latest frame. Short cut key 'r'. diff --git a/common/tier4_camera_view_rviz_plugin/icons/classes/BirdEyeViewTool.png b/common/tier4_camera_view_rviz_plugin/icons/classes/BirdEyeViewTool.png new file mode 100644 index 0000000000000000000000000000000000000000..6a67573717ae18b6008e00077defb27256415663 GIT binary patch literal 18815 zcmc#)ig}7!VL~0BI3P>4u>jX{5WQyQGE==@gXiZcsv`yJ3)ShVHnpzyIKV zx%UIl!@PCQ*=Oy&*IwtGaAid)9L!gkAP@*gMjEOL0wKly`$K;YTnXsp8Ulf2BxRtY zY95&f%V-`irs2ZJD-E_>W|QJ#$f(lDGUzn9FhfdJ6ls+f7g13tl1h)8=nGVpD&-eU zEXJbkUMvxiN-bt%sdy?0Ws#;2U}Tww$D9k?tJrv3b90N4w6q7mY>Vu>j)cq`Gq>&g ztxVotd7x=_%0QrfCTU6#h!Tqc9R&LG1r-?ts`)>?Y`h5pRS_lWag8OXawfXJHk9@r zwSCxzbPRm-g9n1hq$!Q)8a9)#!i(M_cz&h|6vnpsyKVD7twGSL0-4KL6Q=BD1ZeP- zzfzYzWVM-q+?d)>KwJl;5;rOeaVP-p8?mb$R~c z!r4STVAB1bJ?W`Q1N^wk6a>;QVI%JxOu}Vf{^G|)Co3MGH{(9RMV<;nHU4Za)%KSC z`;I=`QN*K~)?CjlT%q3CJ0d$G%J_7^;$JI4Ms3f{6oyJDbjK_N!4ju2 z&$?3P$rm$WTureE-aq`r%H%qf&xx}1+^E65XE7*U*@ASHv#;8ex#{Xeuo?I&+x*og zCp;~E10-qE582|U!y4K~`SF#B31Gjpj3?LDSx6hf<#=NRr5x>o;P$^l9osYrEfL{WYjQydU9;g?K5#3k=W*FphTCuCHewl5&`Uu9F)(f>MMOxB>pE z88huBN|GrNq|eH~M(ELpl-tdZkMhs%;OV+^2?6{7^3=m>h4(Sn1AF4SLTeDL;O9g! zBWaM6c%X0DechlP8B_BUQ^1_B5ImG0q$&AGba@Q1!Sx#uv;b)FNlKJ%FF!gu4goAi z+jugMiX+lt3%Db%$x}1fa)yh%A&xxGW-Lle9BaRZcr(Jl8YJvmXVoM8b*d?nDn zr>xqjT|4gjOmgjyb!-I_L=1WSO(};jF5)F9(KK9k$6juv0YKyrQRHz_DK~8jI2)+w zm-Yt$QfvYLhOutzxp@d+SUG4qO=vJ%C2^D=7atD;N#3;^c;DQzmR&&!oPfkcBJT}x-4FY#kT02m@DxoqS-{xT|$ z3PAj4Y06h5S$bR{FjZhmf2ImPCOB3Cm{OLqda0jhqvfLSxmZ+?A2<^h+z64sYjMk*OaM^512bTNz1yJX#3oL;p>F~$69vB)J^K&J0kyCuHxo2qc9?N7 zpx^)Vh!`XhEMW3-8hQ#=jbwx3L_Yk3cspR5f1h~;US}c=&En=n$AFqJRa-Trw&}AF z#AgA`>wx2@JWAg4l9l5}1GY|0Z9CNsXNdgw(z**Vj@S4BOp0I}AA5Z|Zl~>Z3kVbj zqQ+>~?`j3P7S~|HAAK#cX8I@4)zn@Yx%DiDRJ@~c4bTC4ySPXJL&So)v8RA@6#{J%M_y$DCRzdd0*FPR zEH--gPG5+|{w5Yegr~;hMSkzb)vYj91mGV5xcRrf*}fIu`8(Gk(oJHQTMWSTlpe3W z7U|f@97Ozui1Pqn>xtK!34&Gp1$<#-lg>4RGs7K!6%!+v&|>f%Vhw^400u&sGY~q5 zJ^R2hK)+x%+?N_ujGMppd5=D@{V_pS_0HC2*7x*eApoKv>S`$MhIW>f zMXBEn^5P16FfqDGOxdOTX$;a&7%;G-28$P)$1&8Il!2^?K;(-9A|F432ZYVYM^|}I z3>OV1q`?mb9wc7}dJzwJ)_0FSe8o7Cm(><8hzS0{vBcWu7VZ9!xVd$!*%0qZqPEJb=%hJ$Z_L zz~Miu9bQOq9)39Df;+w>C4k8SnA^IR``!NH4|SUf61t|;@Y}Cs7L7w2kT8`ufki#> z(|*WcvwwZbRQK{xx%^U^9it@ui(i`PZ(a!{U!?$lf%er!QwQi?Jq@BTnXsQ0^KiZy z)@H)?s!l`=|Lg4jvo;>IFs7CP;9l8V4UpAo>sjIq#`%v=kuRv~Dh zsiW)pz26t!@MhZgf>?_yj35jsQu16~;-8_l{?rj9%$d(V-9L6Mv^t{|GGZ5-C`W&WqNh29e6d|hsvmvzE$*g zQmyMXe|TD_9?2}u%kdXf_x#(4xd=B4sAmzB{R*=+ZDMv*{0=ZZw`U z1zHnRLzGA%_kVvk=&UnLH`*nK6OLz)IZ+1RaP z$_a6)pzGO}t0_(S2EeN@?u0pWGf^QOT;Fy&fIf+061Vv&k6#eQ9E?CJbN7 zR~KK=eS#kf?q9C)BZqF)@T7l`iF(-E2|R4|?91b}4Ez)Kk2FyYsGq$iY-#*_u@~1} zergZr={EWSme9lc1Lvw@G~X6iq*U zJ>6TJJ1l)Wu8Wk+%I_jO@X>ttg#2Gtvr6H&5?wENhU3wfOD|1HK$EE0JWPIo?o%@w7QX>1z=lRIcDYmm^RdaH!J$U0qdKjR{v?Nj@k8=mLg z!QaffX+{G^hFLx>yzv{!{4I7+*?C}Mw;W;Akw&+^oGNB zKbo1D;RxOCe8*HY+Wq2Z{a&$bq>kL0E*5uqV%bZU97(Rgg}axR>R3#V{3&SGo$cMU zo>il+6}(CD_7>Sn+RG>LD*ZH>q}A^P_|jLN;2-ZSZ)e^-CR7g&UCtF)C)#ml2sjLp zna0G_?3W<_14PCTp7u%y`1jJLdPCb;WW==}ZA1fH$8?tCsR>bJF?vJ$I|J{? zlTYZ~d#P!IC7nc5MI zRsbBkP4l%D7PaBB{&6DKt4yR^NwBqPM*lr^I~U=AH?+LJ*&C$ZAXr^~8P$6rvc|OQ z@5*T^JLt$TP5T0t(=wiG^sXg zEd~AVuZVrio-s!T&LrqYTve>D*P81_=>7;qF3oJb%9-_$ zl7tF5{GK`$Y)Po@y_Df6U|SUSg7!xbv_*4yVe!Q#Ebc;ZcwoSK)rHUB2ho1zr!2(h z%dVk7oadz}SQ849EKz@)p|3b8py_+bZq+KNZ|#0KdDLC_ZhWXy#9XXyyOh3&D_KBd$d5r~dZ&@?gHCJhG5mniAQ@R>y{O zFvmlJ?JS~a-%K~9k;T?h@u&=-btl<6W(Mr?#p_#Nvx_0v`ilrR<$^+%&Dej}o4vNPn* z;owRb6rB0y*XFvkd6OhCQqGB6I?r)a!X@j6i&CJJ1K0a?>M~fR$7l@HLqkBtR{DNi z#>_e~=e6CHkiV3$L3^TB!NYiWD6Xr+?LjRJ218fc9?44c9VrfHEASeRf4u5=;4Pz2 zbmAarlXGC+<}+MNXuEB2%{j_j84W=YGt*J6aB$pdMP%f^yA?e@n6EWm{~fLLbbmH# zB#6dX=5Pv<(zsg%*jkAKL5r0knZM%tivqc1CatP(x82cXPdwWwcmjs-W@q|ImYY99 zYwlE~Y-hze~lk`x3mjPB!27mzk`xg^y;8^_L_ahVv6~)|t~mfqeU``w(TZ zxrTjOPssfK`oySR$6>Am1>m)tK+)!_P=0!6FfqlwTf!xubMJn*u$lh(uwJ8c<*Bgn zDIx;XIk9`S^Zs-&ZN{2BW%h21L^x#Hy{t&3#$u%2EIrNNs9uMGjS4;G4WkVIc79S?9<_)}5sGh^o2GGu01pfp6?z7wr_`sf6M}tS@hT zNCXk5MDOIEc)b#>BL5Byp4r;f?uV$qGqs%c8FpR1U>>e-v`u`iQ65*US#Q)pH|_z0GX?kiG%%(LOU!%Ckq@v`f@JK|pfX2{xiK)~<5soB5N zZ^n6hgiX)Z0q$xxBO+$zshAz%JT;G?R^ui!yaQF=CYolEefA_D418x5EBtuv6S_T# zt>8C5ZK^P2{Tk3jP{74C9i5Z*XB90Em|L^1Lp$Ty?ZVFx%zQ38_!1Hlo_wx*Jxm>5 z;cSTnM62^vnW0! zv(<%*u%dQ#ZEdDm`^UPysNb89-plAwdG@K0)y_jBD-qUQUN%)_5(TsN78%{K)f*=5FXVTI-5jC-M0r)_e2{Uu>Io;LFZ)WTSayCh zH$y%7yq?2_WZ>t-lJJ(ErM5;8)CMsVjU&indTZFQ!V%ji9)yN-+O%Xp_zMN?x2c&~ z$h26bQIZIOY$0|Hl-A{A>HW>D%Vl99Us^*}%6q+6(o_lL&Dq|Mo_&23{zG+CyVGoa zZdPuB-3?-rE;hgTQB^{1j%hnpE81vUZxe{q7+r62)9R zQjuMBfm(#Ms?@4Z$;Ik^iw9oWqRW`6isW|}$3~+7uuRp_uSRo5+uoV%o;%fYOqe&( z|2-;yrIE5RJ-g8wo6hVoIj1wlF#nl)eXp0d4XYB-b^eG|Cv?<)1s7iS_r5%WWTvIf z2b#SW2vI-|e@Dud15=%5ScGn5xI-4JpMXeprsukuG_&3pJ9vw|;{D{iSX$ZsyN-QS zIkazCCe z5tjTIqBD|W;A`f4 z(o2%2vBi}U($ZixbedSg2KMZ`WSTOQSc*AmMXpEHQN>d_Ts3UpJGs9*!n#G=T_Pyr zRXRI_^rJ$49%InZRr>IOdrQ?H&qWVYSv0t<)_MjA=@l6!>}m{uAv-nCbu4CkNL1I0 zszx2HgbeMhEPPFWT{;-iq%i3PmyXoFdjD&`g5k23{NZw;w9<>q|Iu^oZgl-bE6dSw z^mlKsUR{#$i%`XX%3&%n7Tqbvr-=iv3Vn!kYG;%8(aknQHmT914|hK(l9+ATj)ON8U+A7k}qtQoh z(o1n!2r2de-qqvX8LPa^T2)TVwotK{{5PUlaF}h}t$?CyJIDXX_j2AsLij`a@Rsi6 zT9`WmSJ@(5~J3(YDA@J|o3An#c=nA#EWWa`laHX*T$SjobapA&u?(UWP+Q{C%@7Q}QA^ zJNv{`cm#_$-9Pc`0QTcIA;7WaQ;?NPKQ)wA2wg2XAF*`a%1+DL{Ei|8qxs#0>_+qE zIygdQ6ZJGXrnY0=Ug)~OeO>jx(RvJib8E2<`5+hRj<=UQ`XSK&;bJyBjKUK-vv>=H zGCKa(@!Sj)ME<{YC-0A1b(Bqx63NF8LaQ+pwr7++?Y;83W-@6>tv_S?kk#VM|MVs2LY-DySvyPfa--K5g8|I^)y zxR)i5=c%cxpXe{y&Af@{;>*~{b02i&{aB_$54p;>&#@87qjme%iw$;g@1y3hdBV!k zZH`JGW7Tng^Ak~%}#;Q-2Kv@J$5 zPoiIQ%EmkU-JkTeJJ;0SF{mVKykranq(ebDsHb&e)<5FL`@L~x6=ryQdf$-7vCQ0< zVKw1(9v>zMv~Hr4MzS?k%k=W&z-eNFmOLHeG{ZZM>d@B7MqQoA_xwa^NGPaDE9_=G zqs6AdhWYsONzd@+OaTr-8XOBq(wvBuPJ?Raqs7jrj-Q(vB?55luOh~nXxNd`{VH~I zM;8yWZJr7r(}dDk^xNhxwsalXR!sA1N(T6xx8%3 z9i?;He4?%(U&RqXs^zm7y_}z_XZ`rKJWdqi+!lDPbqjFCc03mCyq$|H4*?12d18Xu zsc9-IL6-9k#5yU9z|37?M|bFc*A_tKQa1XE*M2$dVt-b%RtQm5BcL!+`EtBIz{=SB z>EVhR7s6-iy&6K2n(c0w;sbP}fDO(N@z^>W*1LXDq9TP$lSj^&IGFi{KpGIP-++mV zR2tI$TwO=$)6FcJ+Rs%5-rd7wzS5;BWefCwh}pkOiJM7&g&1R6o^Ft!tBsfjK$~LV zchl!;(BZ>dy(Cy;~wVJ*0yFzq6!EcXR5$rY?4gI54mUi2JbS2$QJGSQ5Xyxt;M>AF4Sv@28`bN@} zlqwK4bFtGi`_*QHwN9+3#N)ub$|i36r9T2zdP63$?>Q-i9luzG2$gB(w!3~+Q&2P3 ztg~7hwvPLAu**HR*1BKO`siW+cbQb!0_qL(aGzg2%;p*MKf-C??dsxN<>Sk(?%vrz zzc_PV+EeGDFeZ;i84*ZtW=H3=#2j|W^|ND<(N6Ys^vYL`H`p!um`KLX43QJ|#XvZ& z5VNDI>gv4*nZ&heTY8$rMpSG1;mfQ=IFry0%W*2X;r!dHgLxC(0(fUSoX7 zwNjEXD0t!s_`m5$=5BFW$;8yBAcYLBacVr_p>vrk2KwkD((ynWWJf^m6M0>Rs^j&K zcuG{Bb;k~FsXL?edF#}7S zHZDLmq@^Y_Y4fI*ecn|MwalQipJKC!`&+AEi=Oxumg^tYvS0s6v}&dED>#4Eap zAJNq9yf;-G>9>swxt+fKLmkVyKVy>_Z%8^@94F5{sE|(%yu=RF} zU|f+?>1X;0!Jp9#;p0r9dszlE)NBFz%Xb>g4B!|F;iIe%Rte_9u|W9MNnz3b-6obM zRP{c^sD1ZD1@8DThqDat@NK>7r_aG&(BpD|3!JTXho#kHn#b%IMn={-%208He(I{j z8s5K{sLB<8*d9?YNvdlAkE1Xq4M&^5V`}zED!eajyno=M;-hVhny2RT;+R}Z9r4hs zHg0|z%N0-eaMaHz%=Q`>bdt9ENtBg7zrZD9*0FRwt#|ss^{%z@XNh|0y-*Iz&V$F+ z5b1tlj^6+i1CSkW24b4a6t9GRb-61JetIWG3TakcE8lU{iJ1*WfY zhT3M?F_AEMwx8^2o>J9?B73d2M-Ao0yblIV=w|pGk7+ zChG0Dy~rHOK1Z}(>0iZDOF^?7HV2aYQZklSUv5SgTzl!7E#o4p(rOC24ScRx|^VD=~3JdRynp4w?)W(5A0 z)_C3;5w{#ut;AeK9af+D3$6?#Btje>?{BQL*L-vD2I8Ik7Vg!@QnLe zppa1pgsr!=`wq1_mTHZ}C3xl@K9Vf_gQQRAD_36GdaZ87H=x1+REu&}7i5gjPv`MP z?=NN3^VvFySA4Is?wUDmnv~`eOyF%d=CNUipe$ZOJ}FZgXz3+QW*Yt>xpMko-JL05 zks6_=q<8Zb!SRc%GSdhvd#^TbuH?h6Nef0sA3Wjvs`Q+zGw6AI#HO>wHLBBX;iyJI zFZ5A$b~Ji_KEX=v=l0q7@oKkklDfM5JEnZw<(BE1>)c*>-8TRsJgfKBDNYu#C!HGU zbLvbP6<#?=;4iU0T&Pb*LBnMo{A)%V&E)8oVNDoVfNMGIGqDC~Tscy8s*HW5h(C^+ zG%$nRO&>=ccGarn_c)}SF|TH0#$7Cx8+pN%20+veAhSU?RF1MOcSo&5t!{_L=^j!S zwpKQodunYpRvLi#(OCA4LtJoKXSCHK;j8k9qyr5?e~KQ|t>1+SXe) z>)&;E*Mlsb=gfL7YJkKP1nqI#dXEOw6i8@(OKrTvK3jR+J9~Xn-iY+EwA~bLWlsRR z23NE2O*dU)=1+e<1VW`GQj_6h3MbAnyDHL5QY*f|gl9W++|d2#xN2PS<3Ii9G|AA= zOQyQ5g5I}YLVzr($N9aHm+H&mo*)(pv+|j@cP5Nnz1nAZ%$JsKX2hLXNhUIS$$QnG z1AL<~%s^invTXLbb=gI`FD6^i`_j_7{ay3FG_nui=Feq_SET$RM11j`*GRQ*M5-@2 zd2E<{+liz^%K)8H_K-`#W19`%J018J8$M5t{XUL%67!Kv?T5Y6%HoSPfj9xo@SRNA zO&i%cnz)EbdPRxH)73v%VP9f)rk1ApgoAeZVYB+))9p8Bqd4&bBR~*`oNY>09O~N2 z!Rp>7KnHX=U8>;-697~ZJ_sN<+Irs|Hl_`;G1z694OixT`*V|Cz_YBGLc(tM@Kohm z>JD&MYd3Xf+B|B;lk$xwEPD9_~%=V(vx(C@a6Y-H$#=bfVOn57$&>rkwrVs4#bi zIXh7e(IM6w&y9tw+~I(;y6HV5=yM_(oXxC~r9=|;e>##2d}?n{dgmZtm$kdn2_X2$ zZn1&1c*eQwvMIIRLX^A-fxxJ(8WBPe?||LSuy z{t{iR`A!>-41uqe*4_8|FWHQLq|ffyeq*aJzDYNo!z||t!@KwR;k$ICGOlv)`wp!Q zFe7=&V)-C1g>f{5f5E>X@5^pc*;|x_)H3t0Wj(Hdf}t6f7dj;Lm3y|b61$Fgis3HI zZZTE=iadp@o=Y|={({-`cL3Mp!SitW{cQ0t++xA?d#mq<7jHsy-_FH#^te&BG6e9=TM4K?yE4$gLtJB{QzeetB zryUa6*x1vKi=Ur?^*FjI-@8jse%C$IlbLGM)=y!06b)*c>gqrMkCt)IoHxxwf;h>K zI$ZxUI0Qd&(@HM3+nD1SE<}@A-dyZ1FM9v|iBvCi@E-ah@k7-!4x7-5u`g+?MqO*l zm)P-Zzu$iR6iAlY+w9>D6kT>tx3it8Zf2XNw7OwQn=-dqz_;&l(OUI~)JrvPrtJfn zwVGJjkAIYJ@iHeSyf)eOw~G0ZJld2UGPIIZu3h{4455%Qbz6lZW74FexmYeYM;8aI z$K-h3Y^GFFCuw>-YX)_9?Ig^9A4wx1xQ2#eYVG!-LK}|bv$R8@eqlJgC_fD*}q9KhIE1f_i#O7_ zT)%x`)T#K2OJP6!v6Vb?t~cc+MQq6?;as!glC6mA<(e z<%lFRX`h0@1C67z0NHWh|ZjuVZ|V8t@FP@kIUYdtPp)2I9s3B_BXeBp}-ZP z5|l~AJ-|-~e7adHXKm6rZHQ~nBqb!qRwUhuE_?tsh^Kl=Hlz{jJv5 z%a`iA?S8PdtMf0~>M^6t2;7z3^z?rn(s|R}N+Jo!JO1-*rxQyqqw0F6X>RM!ACLOT zz2%2LmeJ%LT4#%}#EGCHI_{2UWy@EDyhONJs|(RvT?Z?St5 zJe~uJKn9oH8ehO#Qs>h$z{xbsOPOK-DR@vG_GmD%r#DqpIINVFeAg~=yeiV@S@ycUgHP|m(|5vgek*ZEH4RdwK{d$6jL>+4X z`4ChMuWjS9nJF{!ij95ygn<6)v21l;z0gZ@UjZab`9s9KK++(ZU}hS#jlPp@YHsdX+N+j<%}bAm_k9)T8@LAgyH4JzSyw>)>XO5eYZ-f(KZq4CZ8KAE}&p33a#nAw#ZL!zhkYZa0_fy&Jh12UfTAj4W?< z)O2(X-CC!M1+7n}8-n0j-m&cbyUhc#29lDYkyrH{#~wfcNz*@%?SyYHR3jK#qYkg` zfOxt;Xp>!NetI3?-j2$*c6E0peFJ1k0qtRyN~0J}eb0QIcI)6yPMaCaqc?e?=5%L0 z!wWTLgHwtNdLFYf->C5f&&TSGJKKO9egTz|q7H=dL_|bSuP9CLa~>76 znCtPqJkWLkR->ldp7iOcx({hE83#s3x$hnxA+ElF{8rgnRi*qnM5H$vfR4=(~l-hR-WQi)59iT6|TZNDzuRd5R$FCqNF)uguYRz#H!g{_d46@8|;6d)C31g+?wwl9UWUN!_7@iU(y8@`IP%@=plBH%=02yJ&ynGhwto!JlUOX z4ZlnR=UHTX(m73bJ`MY1G35^fepmv;GCh*P+1Gq7e{QeWW1q~jSlc~K9=z&1x!R5Sw+>Pg|4d7B*QMP1eov^xZ{boH28L>~l{Zhb#6){LZ zm@6K(L>wtG?EU!}!s|J9nZo{zoX5(&q`-6B*F~kgn1RWbz(S1+KjtWyba%eqCgn)S zFN@z*^(@_A3M$`75z6`%5E_kQVPm~8vUW(0-)Xpgi@MOw2BBVq0JDHsQp!G~mGIp` zt+g8jO^5Tn$1Dr}bH1cx#Vy}6vXegp0~5m=T_@{(WO?uY<)bNy2_cW;Z}e~9$_)RA z&R+=3N)8DzIPSQK_PD=ZR~&XP^$^GwPJke6@_WV`6v&1R5CO#>3rm*Q23Pe8MP7zS zN4FFUff1Z$-rRg+ zUOSJkl&izPHIn6>?4GZlL7(#}f01PSSIocavf%MkVJQEWW_pySvMFl!k06}^LD&vwY0rFM7Sdo{5 z!^6JOK>wyp&Wqx=>r``x(>dQU>14zTUKY_wnmZX{if`ugWtEtf5;FbfaR!RPMaJd=iiHkN)+{o zw=7_sEj@pbvWiNnS(}3oHAP5B$P(ALz1hl~T>aEY-XZhaZD8r8xs7nX)xEONDCjv; zOUTNmo&)Iqji8`liKzLOKAgKFJ{IZWuJ!WaoUryyAsQa}xqK??8(ZCEx7KBV%c+g} zKb}#TJ3DI#oj_gNy)Lv4->#&&w<8@3lV0qv{JbmRz6E=*>$kXAjlB;|IzAm_X;uCB zv75{DlZUCPX_L_PUzBOWE8nZ-zMA|iD#R`FU!}FRHDgRnO#Q#U-C^A-YHAzgg4T%^ zfT5UUrP9zgG!1;~y?UlKy%*}N2#Hw+^T|{6+|stQd7Vod9abu&XJ-I|3zTY{NPshIIhMP4(e)?%0Uv@SDj|pppr_Jb?SU%^oes09s*d=hLG% ze`5g7Pg|}#S=k6d+Fsg@%%xAxPEJlx7nk#=$7MiN?f*(I2$fs2BE8qna6zlDpw#AvWn%g%t!02^>Yj~m`Jc$>iH%XJ+e zZKMxoZxEm;V0$ox2?Us2H~)s3I>H<)HIzL9C2*B2%2% zuoz$qGG)~AC_jk0_89l)-w}Kjrep=sU*p1KA%bo<^)Jj!7x@I^8msO> z4>V)boi5cC6{?m%cYKi1zpQXO7Sj9MjcR~0ZwA;qj*h|~Zix)e+JeBwbFm_`UgUBj zgZ3CD_k(a;jH;dGQ*p3Bd%O`FzipXyFXu?vx-t zRRt(cFcEnGVV%fzDOH|TTM%e0EhS#yS{w_?&t<&+7NqhCIwh;+O2Q)sTsc~YfC3bU zq)x}416#3Ue7ioXI|D~PEaz~kUWr15fPZx;b=F9Tzwr0+<&|tGXq@ z-!p+0U!6Y(5C2L=UkFUuSvc=t6~zQS+H_VW)Q7oK9zW$`$z@cCY7+mxgHfQ2uQhZ-Bg6F)mmEz|j=0p4I}11k?as_b+mA%#j1I8iXEwQXk2s&yQGt+}5bJPGb zYs;@L`=D=*mVrBcjz(@?+%AG&0^6ZbXHPVwwQtYzgjukZEJ2bVC7?Lfli&RQ%4ql> zZ3Bjstq?yQBdHTP-^B*^9^)d5i0V_-08a5k6bqU|cZ>@XF)H;$15M;U%QGN@6}Z0a%$-dB3&%`n1N7*~lrtIJ9})K!Z&`SKbd?mA;INup)SGh_}|FuM4}K3U^9Fb8+f3I)=dOLQaPRBqE3YvwXIT1%t;9*xKkQh>Kn}+ z;Q<4<$i;f+^O`#E1n{wLZ`^)rpKs3y{DkQ8RNlH1vu<1qB`m4Ar|D>VgG6BuM+f>~Dm_|t=53>L+p^5?Ap9utF zppJ$KnZyZs@R1KmMUXW&i^`seS3FLP#h)k*_YGfPxP+Lf^-x z_sPQj+kVNDcrI(6;l2Q!R|cD$^7tp7bf7;!t@&f~h=LG73c#aHVNd&EsO|JDJ9OOx z4GDygnsW{dr3{vF5xpd#k62wqCZIlHJHXZfU5XlU_yV<>Rk0;H^GfkD(N zC8;^cd!U6lfJ^KX0@2Cm4 zd=8d)ev_63t*c7*w-JRN1{3v+Dme+gIiEr$x928QNy2pGAlduak_Nks{AB%r4d$fH zGhrW1qRbq8d%BIF&*L}E-fw%oD&cP&m%}Rqb%t5mz_v?@_2O7|JOgdKNWi}S@&06z zP{QC}7)~36DkZQSelp`cI3;!}dXmDmA1C4Sk2IJkXca2?Rq1CeU5pr=Z$Eb|MA79r zy57rE7PN*8KqGRYA39>(eT2c|(NGsfr{%mU54|>P>rf=dU$a zVl0M^67U>rcEgp*DN>+P_xfhO3&BA|ja^IR9nZ)3c|`h+cLeVW#xuq+3uv}nG%A6$ z#JM=Sf#pn?8f_ORN$Xqfs`b>*IN!zY+eSWe1i~INHf-G~8xDL(&1R?cv=sOgWv}k5 zvteF@Dw-i34yuxg_Ahk2WZ_t?;YIDiHl87$aT0m1go-04L)r0u>_1x^n=umxKkx@T zXKB)YVqzl*IYMPkmI~jo$xVn-{?=xiJ8`YE6AE&DmVLZJomVQhqu;I!nEhjZSW}A& z9aUJDnK_|~5?EL>2L>l;*|=qJIbzC{IPFmO%Mz2JRMpR3A?xzA_EP8?g@56F6FM$q zslHsKdNUki-|0=HpNsVPE(Hds%j;8TT#?q*MZ~(-<~C%b_A2|X}`fHdwvLeljj~n5@a2L|D4uGt&g#XQX&30uL+(&sRQi{`=)W|ELz*%Z{nK;cEHSxzI zsrA`<4Rz6Z8InRbWPpDMuP7)CHtM(&gT2jMVmcA6EvW4pd-}Qk^8M1f ztkSjGqJ~jOXiyi^+0T{nVA#S8`(S%RprmWLq)G}RWd2UQ3q_lH)oTEP+*uVvg!LsN zp4D^TqM1J4uq;@HeYBs!V3ZI;JIi2~d7$Bqe6W{zYP=5{*J{>)N}3r95vhNZ5{>PP zuI(%1IF+xoU4$(JU!{WLTR0_#*HMh#ml-ls=i#wjLt?A2l@z+gU?w4~g&W3HA^s`4 z4F}UB7IHlO-A+nWfeRdy@gjRdiHelQl{X=Mi%^&FKd0*<@l5nI+3Vc#h{rC$Kmoe- zvpZ3bMn*|-qZj5396y5q;CzC9kn7s`b9To2s502|i^nLOu-LIIk#*-sAS;X19xv|T z{0*ls}liCZmq|f?Z;8zxgGkM?Er0=gxe!}5B)Cfts%zx+KRG~>%xK$^Qwgd zxLTF&cv9bZ<-o^?!iTp33(@-}y0vl_)2I~G)HF}92jl3v=#<)O=E7Rmdy2oglf|Hk z9aQ(|WOUn)IJ?Ev)&Fx6bF6)kaLn)DLr)thofgM!&@~!rT^O7bt@e5Or7|3fA$%9Z zdcgKVh^j?@4Sr`l^A=M|1^Pj?Yjm{L@U2TTmvgF?=HwY>`I&p}76Dqk08?8TUT-A< znh@%m4Kr8Z2eAG|xkt@vbVWTWWo?7J*w`48u>8$6i$5I*42V{tPKX%OlI`)B z()!3ib)k>8#b55^e=w>k^6=B1ZbJ{JnSv5WmCH4hd6f6{<7;|@XRLCWiDm99yGhA{}Wd_r0D9El$(X5~ZD@6Yeq%JJ_WnN-%QoT_^& zls{`|J%9EnfAEk~Gyx};)G-ocS*iS3?;B@s#A40HNR)|D9E{SnkxmA^FH@JMsvova zX8&ayT=lAu;Am_z@Z2<%$ z6{BjEfS{w}t2VXwOJOAH%tlL96JNh1#=Wf*>*+C=wXQ*vNIs(oaU1*ElJg~AWBoz3 zYsEM6%XU&tu#eu|7g)PJi(C|&tXR}Xn&hnaxd#gx>+j>0Lv??-YpZnq{-}DCX85D* z_dAPe6Sn6vuwUIAo->ylZ}KI6nQVFL;mT@J6n=}jh-Pjuf%pEv++Pdkdj*Zwp7DBP zrhTtVw6{gZP)&6$66l-|HJ4w8%;eg~^EPs4nrqIew2C|SrN%S*vk{KJr_g;`Y{qKK za@>)WYnnH1$Y7g~H208STe0$q*DizuUr(^Zw@=B+o)Nq~aS$e4yGfT@>daH^DKIsz z)cwow6@MRvpi+T4eltCU8Nd3QQI$>-+ zFgW?Ai;?m(M6`3~3t0MUNoj|7dB1(@$eb{5jiAiUXxRcsX%N7syb8a-?5DbXQY&dt z%QtBuucYrm*1Dmz5?dn{A0>WU5x4YjETQ|M(8cAmSNvkb`2Ku7q`f}>zYyO<$8g@x zUzs*Gk#M%Gr7AVQ9ITO)uwuolOW^S4&Y0P4a>%SIVE2Gjj|O|=mQu{^v#Iu?g_u(5R=+V-wf&8^chyn4kgY80C{bYAldhLKCoo`h9f)w_=Um8!5STwbwF{_U3Tizp{AyHC84h8bs|GATle zy3F*$Rqlvr6MURu^<;ctoJ-C-Z#8oO_$tvow?$;EY1DOi-(^S-2TIzlGbRuwb&;-U z7yZw0dus6-cg1D}!{`%wA1C;jA;~pKJ=T-XVnJJKHRncn?@V?ZaEO-)De!(_{cb?PQZM`vF>be}<$+yB>x!n%iMG>Ka&r0;UkQJwE7Mk z$`Z}Z4DInTXYHvlPzHtdM7q)!O@~4(CDCwL6=&P!6H8`ZIu8IG){ebnFOOsgJi5#J zo*23$q%3OfclD3VJx10L$%S6mR#0O{Z-fm;yH{W~(%~1?#@9nDw|X-FV4WFNNE?u= zNsUpZB9>X39R6ko>B{E@palselu!fi@;2{*99+kw!vd7==a0k1U~mtD?VxZfC+5?F zS*Nm{8|Z%mvGF+lu?k#)zW_q@WO_h`!~-H-wk-C(55!&CS9;0~tCO{qo!|0Ld`A4R z!?{Ezel$sA7!Q>QFASC6a)j3Q9elimCP?JOd_Bc7+iW%D38BRl_}=XI4MruG!$~Y! z)#3G0Ing0FLqmnq)N|04xKy0c__kp$%3zYQ=jbnv1!pZF??**9r5!AA6QQz8HaBac z-)DvlmLg^;&QlPoDNzVPj2csI+Sp_GZ>Y~5tTw?OOsB`~G>Igi6#!z}vZxRn z_mZ3%^Wj5E=1-Gbo9g3YL(lz--KY}z4P9;Rev`lWf1j9yQ{VAp+Sf5=7Hy=={c`2yJadWY-BAQd=Lk{ z_R5BjK&)=KT9B)gLV{1>rb2!28ThgAIW#%qO5B*yF`N0*A1srvHd0v*yWIk#^?)Ts zM5jSs*i*xFz2D7|(i500ZVx1J5^<9kp}e$hGHAC2LutRtBH%ytYf07!h%N|p$O_p@ zM76*Ze2pGv`4>e77PC@W+j}V~VvZ$pJA7_u0J6SUt6#Bso7y)~k6x^LN|Y_7g&3t~ zc23kDyJ8C;xg3Hmb~#>n;^|83;U1180$1Uh7VPe5U0Yj3=xI`|HIDic);1 z%Zx)#tB~cm_w^{1mrymqhd`i6ceMi`P*4dL1i~7qi~&@l{y)Y0VJg~EDlzW{YoEjk QxT*u><#`b=z=h}h2b9~@i2wiq literal 0 HcmV?d00001 diff --git a/common/tier4_camera_view_rviz_plugin/icons/classes/ThirdPersonViewTool.png b/common/tier4_camera_view_rviz_plugin/icons/classes/ThirdPersonViewTool.png new file mode 100644 index 0000000000000000000000000000000000000000..6a67573717ae18b6008e00077defb27256415663 GIT binary patch literal 18815 zcmc#)ig}7!VL~0BI3P>4u>jX{5WQyQGE==@gXiZcsv`yJ3)ShVHnpzyIKV zx%UIl!@PCQ*=Oy&*IwtGaAid)9L!gkAP@*gMjEOL0wKly`$K;YTnXsp8Ulf2BxRtY zY95&f%V-`irs2ZJD-E_>W|QJ#$f(lDGUzn9FhfdJ6ls+f7g13tl1h)8=nGVpD&-eU zEXJbkUMvxiN-bt%sdy?0Ws#;2U}Tww$D9k?tJrv3b90N4w6q7mY>Vu>j)cq`Gq>&g ztxVotd7x=_%0QrfCTU6#h!Tqc9R&LG1r-?ts`)>?Y`h5pRS_lWag8OXawfXJHk9@r zwSCxzbPRm-g9n1hq$!Q)8a9)#!i(M_cz&h|6vnpsyKVD7twGSL0-4KL6Q=BD1ZeP- zzfzYzWVM-q+?d)>KwJl;5;rOeaVP-p8?mb$R~c z!r4STVAB1bJ?W`Q1N^wk6a>;QVI%JxOu}Vf{^G|)Co3MGH{(9RMV<;nHU4Za)%KSC z`;I=`QN*K~)?CjlT%q3CJ0d$G%J_7^;$JI4Ms3f{6oyJDbjK_N!4ju2 z&$?3P$rm$WTureE-aq`r%H%qf&xx}1+^E65XE7*U*@ASHv#;8ex#{Xeuo?I&+x*og zCp;~E10-qE582|U!y4K~`SF#B31Gjpj3?LDSx6hf<#=NRr5x>o;P$^l9osYrEfL{WYjQydU9;g?K5#3k=W*FphTCuCHewl5&`Uu9F)(f>MMOxB>pE z88huBN|GrNq|eH~M(ELpl-tdZkMhs%;OV+^2?6{7^3=m>h4(Sn1AF4SLTeDL;O9g! zBWaM6c%X0DechlP8B_BUQ^1_B5ImG0q$&AGba@Q1!Sx#uv;b)FNlKJ%FF!gu4goAi z+jugMiX+lt3%Db%$x}1fa)yh%A&xxGW-Lle9BaRZcr(Jl8YJvmXVoM8b*d?nDn zr>xqjT|4gjOmgjyb!-I_L=1WSO(};jF5)F9(KK9k$6juv0YKyrQRHz_DK~8jI2)+w zm-Yt$QfvYLhOutzxp@d+SUG4qO=vJ%C2^D=7atD;N#3;^c;DQzmR&&!oPfkcBJT}x-4FY#kT02m@DxoqS-{xT|$ z3PAj4Y06h5S$bR{FjZhmf2ImPCOB3Cm{OLqda0jhqvfLSxmZ+?A2<^h+z64sYjMk*OaM^512bTNz1yJX#3oL;p>F~$69vB)J^K&J0kyCuHxo2qc9?N7 zpx^)Vh!`XhEMW3-8hQ#=jbwx3L_Yk3cspR5f1h~;US}c=&En=n$AFqJRa-Trw&}AF z#AgA`>wx2@JWAg4l9l5}1GY|0Z9CNsXNdgw(z**Vj@S4BOp0I}AA5Z|Zl~>Z3kVbj zqQ+>~?`j3P7S~|HAAK#cX8I@4)zn@Yx%DiDRJ@~c4bTC4ySPXJL&So)v8RA@6#{J%M_y$DCRzdd0*FPR zEH--gPG5+|{w5Yegr~;hMSkzb)vYj91mGV5xcRrf*}fIu`8(Gk(oJHQTMWSTlpe3W z7U|f@97Ozui1Pqn>xtK!34&Gp1$<#-lg>4RGs7K!6%!+v&|>f%Vhw^400u&sGY~q5 zJ^R2hK)+x%+?N_ujGMppd5=D@{V_pS_0HC2*7x*eApoKv>S`$MhIW>f zMXBEn^5P16FfqDGOxdOTX$;a&7%;G-28$P)$1&8Il!2^?K;(-9A|F432ZYVYM^|}I z3>OV1q`?mb9wc7}dJzwJ)_0FSe8o7Cm(><8hzS0{vBcWu7VZ9!xVd$!*%0qZqPEJb=%hJ$Z_L zz~Miu9bQOq9)39Df;+w>C4k8SnA^IR``!NH4|SUf61t|;@Y}Cs7L7w2kT8`ufki#> z(|*WcvwwZbRQK{xx%^U^9it@ui(i`PZ(a!{U!?$lf%er!QwQi?Jq@BTnXsQ0^KiZy z)@H)?s!l`=|Lg4jvo;>IFs7CP;9l8V4UpAo>sjIq#`%v=kuRv~Dh zsiW)pz26t!@MhZgf>?_yj35jsQu16~;-8_l{?rj9%$d(V-9L6Mv^t{|GGZ5-C`W&WqNh29e6d|hsvmvzE$*g zQmyMXe|TD_9?2}u%kdXf_x#(4xd=B4sAmzB{R*=+ZDMv*{0=ZZw`U z1zHnRLzGA%_kVvk=&UnLH`*nK6OLz)IZ+1RaP z$_a6)pzGO}t0_(S2EeN@?u0pWGf^QOT;Fy&fIf+061Vv&k6#eQ9E?CJbN7 zR~KK=eS#kf?q9C)BZqF)@T7l`iF(-E2|R4|?91b}4Ez)Kk2FyYsGq$iY-#*_u@~1} zergZr={EWSme9lc1Lvw@G~X6iq*U zJ>6TJJ1l)Wu8Wk+%I_jO@X>ttg#2Gtvr6H&5?wENhU3wfOD|1HK$EE0JWPIo?o%@w7QX>1z=lRIcDYmm^RdaH!J$U0qdKjR{v?Nj@k8=mLg z!QaffX+{G^hFLx>yzv{!{4I7+*?C}Mw;W;Akw&+^oGNB zKbo1D;RxOCe8*HY+Wq2Z{a&$bq>kL0E*5uqV%bZU97(Rgg}axR>R3#V{3&SGo$cMU zo>il+6}(CD_7>Sn+RG>LD*ZH>q}A^P_|jLN;2-ZSZ)e^-CR7g&UCtF)C)#ml2sjLp zna0G_?3W<_14PCTp7u%y`1jJLdPCb;WW==}ZA1fH$8?tCsR>bJF?vJ$I|J{? zlTYZ~d#P!IC7nc5MI zRsbBkP4l%D7PaBB{&6DKt4yR^NwBqPM*lr^I~U=AH?+LJ*&C$ZAXr^~8P$6rvc|OQ z@5*T^JLt$TP5T0t(=wiG^sXg zEd~AVuZVrio-s!T&LrqYTve>D*P81_=>7;qF3oJb%9-_$ zl7tF5{GK`$Y)Po@y_Df6U|SUSg7!xbv_*4yVe!Q#Ebc;ZcwoSK)rHUB2ho1zr!2(h z%dVk7oadz}SQ849EKz@)p|3b8py_+bZq+KNZ|#0KdDLC_ZhWXy#9XXyyOh3&D_KBd$d5r~dZ&@?gHCJhG5mniAQ@R>y{O zFvmlJ?JS~a-%K~9k;T?h@u&=-btl<6W(Mr?#p_#Nvx_0v`ilrR<$^+%&Dej}o4vNPn* z;owRb6rB0y*XFvkd6OhCQqGB6I?r)a!X@j6i&CJJ1K0a?>M~fR$7l@HLqkBtR{DNi z#>_e~=e6CHkiV3$L3^TB!NYiWD6Xr+?LjRJ218fc9?44c9VrfHEASeRf4u5=;4Pz2 zbmAarlXGC+<}+MNXuEB2%{j_j84W=YGt*J6aB$pdMP%f^yA?e@n6EWm{~fLLbbmH# zB#6dX=5Pv<(zsg%*jkAKL5r0knZM%tivqc1CatP(x82cXPdwWwcmjs-W@q|ImYY99 zYwlE~Y-hze~lk`x3mjPB!27mzk`xg^y;8^_L_ahVv6~)|t~mfqeU``w(TZ zxrTjOPssfK`oySR$6>Am1>m)tK+)!_P=0!6FfqlwTf!xubMJn*u$lh(uwJ8c<*Bgn zDIx;XIk9`S^Zs-&ZN{2BW%h21L^x#Hy{t&3#$u%2EIrNNs9uMGjS4;G4WkVIc79S?9<_)}5sGh^o2GGu01pfp6?z7wr_`sf6M}tS@hT zNCXk5MDOIEc)b#>BL5Byp4r;f?uV$qGqs%c8FpR1U>>e-v`u`iQ65*US#Q)pH|_z0GX?kiG%%(LOU!%Ckq@v`f@JK|pfX2{xiK)~<5soB5N zZ^n6hgiX)Z0q$xxBO+$zshAz%JT;G?R^ui!yaQF=CYolEefA_D418x5EBtuv6S_T# zt>8C5ZK^P2{Tk3jP{74C9i5Z*XB90Em|L^1Lp$Ty?ZVFx%zQ38_!1Hlo_wx*Jxm>5 z;cSTnM62^vnW0! zv(<%*u%dQ#ZEdDm`^UPysNb89-plAwdG@K0)y_jBD-qUQUN%)_5(TsN78%{K)f*=5FXVTI-5jC-M0r)_e2{Uu>Io;LFZ)WTSayCh zH$y%7yq?2_WZ>t-lJJ(ErM5;8)CMsVjU&indTZFQ!V%ji9)yN-+O%Xp_zMN?x2c&~ z$h26bQIZIOY$0|Hl-A{A>HW>D%Vl99Us^*}%6q+6(o_lL&Dq|Mo_&23{zG+CyVGoa zZdPuB-3?-rE;hgTQB^{1j%hnpE81vUZxe{q7+r62)9R zQjuMBfm(#Ms?@4Z$;Ik^iw9oWqRW`6isW|}$3~+7uuRp_uSRo5+uoV%o;%fYOqe&( z|2-;yrIE5RJ-g8wo6hVoIj1wlF#nl)eXp0d4XYB-b^eG|Cv?<)1s7iS_r5%WWTvIf z2b#SW2vI-|e@Dud15=%5ScGn5xI-4JpMXeprsukuG_&3pJ9vw|;{D{iSX$ZsyN-QS zIkazCCe z5tjTIqBD|W;A`f4 z(o2%2vBi}U($ZixbedSg2KMZ`WSTOQSc*AmMXpEHQN>d_Ts3UpJGs9*!n#G=T_Pyr zRXRI_^rJ$49%InZRr>IOdrQ?H&qWVYSv0t<)_MjA=@l6!>}m{uAv-nCbu4CkNL1I0 zszx2HgbeMhEPPFWT{;-iq%i3PmyXoFdjD&`g5k23{NZw;w9<>q|Iu^oZgl-bE6dSw z^mlKsUR{#$i%`XX%3&%n7Tqbvr-=iv3Vn!kYG;%8(aknQHmT914|hK(l9+ATj)ON8U+A7k}qtQoh z(o1n!2r2de-qqvX8LPa^T2)TVwotK{{5PUlaF}h}t$?CyJIDXX_j2AsLij`a@Rsi6 zT9`WmSJ@(5~J3(YDA@J|o3An#c=nA#EWWa`laHX*T$SjobapA&u?(UWP+Q{C%@7Q}QA^ zJNv{`cm#_$-9Pc`0QTcIA;7WaQ;?NPKQ)wA2wg2XAF*`a%1+DL{Ei|8qxs#0>_+qE zIygdQ6ZJGXrnY0=Ug)~OeO>jx(RvJib8E2<`5+hRj<=UQ`XSK&;bJyBjKUK-vv>=H zGCKa(@!Sj)ME<{YC-0A1b(Bqx63NF8LaQ+pwr7++?Y;83W-@6>tv_S?kk#VM|MVs2LY-DySvyPfa--K5g8|I^)y zxR)i5=c%cxpXe{y&Af@{;>*~{b02i&{aB_$54p;>&#@87qjme%iw$;g@1y3hdBV!k zZH`JGW7Tng^Ak~%}#;Q-2Kv@J$5 zPoiIQ%EmkU-JkTeJJ;0SF{mVKykranq(ebDsHb&e)<5FL`@L~x6=ryQdf$-7vCQ0< zVKw1(9v>zMv~Hr4MzS?k%k=W&z-eNFmOLHeG{ZZM>d@B7MqQoA_xwa^NGPaDE9_=G zqs6AdhWYsONzd@+OaTr-8XOBq(wvBuPJ?Raqs7jrj-Q(vB?55luOh~nXxNd`{VH~I zM;8yWZJr7r(}dDk^xNhxwsalXR!sA1N(T6xx8%3 z9i?;He4?%(U&RqXs^zm7y_}z_XZ`rKJWdqi+!lDPbqjFCc03mCyq$|H4*?12d18Xu zsc9-IL6-9k#5yU9z|37?M|bFc*A_tKQa1XE*M2$dVt-b%RtQm5BcL!+`EtBIz{=SB z>EVhR7s6-iy&6K2n(c0w;sbP}fDO(N@z^>W*1LXDq9TP$lSj^&IGFi{KpGIP-++mV zR2tI$TwO=$)6FcJ+Rs%5-rd7wzS5;BWefCwh}pkOiJM7&g&1R6o^Ft!tBsfjK$~LV zchl!;(BZ>dy(Cy;~wVJ*0yFzq6!EcXR5$rY?4gI54mUi2JbS2$QJGSQ5Xyxt;M>AF4Sv@28`bN@} zlqwK4bFtGi`_*QHwN9+3#N)ub$|i36r9T2zdP63$?>Q-i9luzG2$gB(w!3~+Q&2P3 ztg~7hwvPLAu**HR*1BKO`siW+cbQb!0_qL(aGzg2%;p*MKf-C??dsxN<>Sk(?%vrz zzc_PV+EeGDFeZ;i84*ZtW=H3=#2j|W^|ND<(N6Ys^vYL`H`p!um`KLX43QJ|#XvZ& z5VNDI>gv4*nZ&heTY8$rMpSG1;mfQ=IFry0%W*2X;r!dHgLxC(0(fUSoX7 zwNjEXD0t!s_`m5$=5BFW$;8yBAcYLBacVr_p>vrk2KwkD((ynWWJf^m6M0>Rs^j&K zcuG{Bb;k~FsXL?edF#}7S zHZDLmq@^Y_Y4fI*ecn|MwalQipJKC!`&+AEi=Oxumg^tYvS0s6v}&dED>#4Eap zAJNq9yf;-G>9>swxt+fKLmkVyKVy>_Z%8^@94F5{sE|(%yu=RF} zU|f+?>1X;0!Jp9#;p0r9dszlE)NBFz%Xb>g4B!|F;iIe%Rte_9u|W9MNnz3b-6obM zRP{c^sD1ZD1@8DThqDat@NK>7r_aG&(BpD|3!JTXho#kHn#b%IMn={-%208He(I{j z8s5K{sLB<8*d9?YNvdlAkE1Xq4M&^5V`}zED!eajyno=M;-hVhny2RT;+R}Z9r4hs zHg0|z%N0-eaMaHz%=Q`>bdt9ENtBg7zrZD9*0FRwt#|ss^{%z@XNh|0y-*Iz&V$F+ z5b1tlj^6+i1CSkW24b4a6t9GRb-61JetIWG3TakcE8lU{iJ1*WfY zhT3M?F_AEMwx8^2o>J9?B73d2M-Ao0yblIV=w|pGk7+ zChG0Dy~rHOK1Z}(>0iZDOF^?7HV2aYQZklSUv5SgTzl!7E#o4p(rOC24ScRx|^VD=~3JdRynp4w?)W(5A0 z)_C3;5w{#ut;AeK9af+D3$6?#Btje>?{BQL*L-vD2I8Ik7Vg!@QnLe zppa1pgsr!=`wq1_mTHZ}C3xl@K9Vf_gQQRAD_36GdaZ87H=x1+REu&}7i5gjPv`MP z?=NN3^VvFySA4Is?wUDmnv~`eOyF%d=CNUipe$ZOJ}FZgXz3+QW*Yt>xpMko-JL05 zks6_=q<8Zb!SRc%GSdhvd#^TbuH?h6Nef0sA3Wjvs`Q+zGw6AI#HO>wHLBBX;iyJI zFZ5A$b~Ji_KEX=v=l0q7@oKkklDfM5JEnZw<(BE1>)c*>-8TRsJgfKBDNYu#C!HGU zbLvbP6<#?=;4iU0T&Pb*LBnMo{A)%V&E)8oVNDoVfNMGIGqDC~Tscy8s*HW5h(C^+ zG%$nRO&>=ccGarn_c)}SF|TH0#$7Cx8+pN%20+veAhSU?RF1MOcSo&5t!{_L=^j!S zwpKQodunYpRvLi#(OCA4LtJoKXSCHK;j8k9qyr5?e~KQ|t>1+SXe) z>)&;E*Mlsb=gfL7YJkKP1nqI#dXEOw6i8@(OKrTvK3jR+J9~Xn-iY+EwA~bLWlsRR z23NE2O*dU)=1+e<1VW`GQj_6h3MbAnyDHL5QY*f|gl9W++|d2#xN2PS<3Ii9G|AA= zOQyQ5g5I}YLVzr($N9aHm+H&mo*)(pv+|j@cP5Nnz1nAZ%$JsKX2hLXNhUIS$$QnG z1AL<~%s^invTXLbb=gI`FD6^i`_j_7{ay3FG_nui=Feq_SET$RM11j`*GRQ*M5-@2 zd2E<{+liz^%K)8H_K-`#W19`%J018J8$M5t{XUL%67!Kv?T5Y6%HoSPfj9xo@SRNA zO&i%cnz)EbdPRxH)73v%VP9f)rk1ApgoAeZVYB+))9p8Bqd4&bBR~*`oNY>09O~N2 z!Rp>7KnHX=U8>;-697~ZJ_sN<+Irs|Hl_`;G1z694OixT`*V|Cz_YBGLc(tM@Kohm z>JD&MYd3Xf+B|B;lk$xwEPD9_~%=V(vx(C@a6Y-H$#=bfVOn57$&>rkwrVs4#bi zIXh7e(IM6w&y9tw+~I(;y6HV5=yM_(oXxC~r9=|;e>##2d}?n{dgmZtm$kdn2_X2$ zZn1&1c*eQwvMIIRLX^A-fxxJ(8WBPe?||LSuy z{t{iR`A!>-41uqe*4_8|FWHQLq|ffyeq*aJzDYNo!z||t!@KwR;k$ICGOlv)`wp!Q zFe7=&V)-C1g>f{5f5E>X@5^pc*;|x_)H3t0Wj(Hdf}t6f7dj;Lm3y|b61$Fgis3HI zZZTE=iadp@o=Y|={({-`cL3Mp!SitW{cQ0t++xA?d#mq<7jHsy-_FH#^te&BG6e9=TM4K?yE4$gLtJB{QzeetB zryUa6*x1vKi=Ur?^*FjI-@8jse%C$IlbLGM)=y!06b)*c>gqrMkCt)IoHxxwf;h>K zI$ZxUI0Qd&(@HM3+nD1SE<}@A-dyZ1FM9v|iBvCi@E-ah@k7-!4x7-5u`g+?MqO*l zm)P-Zzu$iR6iAlY+w9>D6kT>tx3it8Zf2XNw7OwQn=-dqz_;&l(OUI~)JrvPrtJfn zwVGJjkAIYJ@iHeSyf)eOw~G0ZJld2UGPIIZu3h{4455%Qbz6lZW74FexmYeYM;8aI z$K-h3Y^GFFCuw>-YX)_9?Ig^9A4wx1xQ2#eYVG!-LK}|bv$R8@eqlJgC_fD*}q9KhIE1f_i#O7_ zT)%x`)T#K2OJP6!v6Vb?t~cc+MQq6?;as!glC6mA<(e z<%lFRX`h0@1C67z0NHWh|ZjuVZ|V8t@FP@kIUYdtPp)2I9s3B_BXeBp}-ZP z5|l~AJ-|-~e7adHXKm6rZHQ~nBqb!qRwUhuE_?tsh^Kl=Hlz{jJv5 z%a`iA?S8PdtMf0~>M^6t2;7z3^z?rn(s|R}N+Jo!JO1-*rxQyqqw0F6X>RM!ACLOT zz2%2LmeJ%LT4#%}#EGCHI_{2UWy@EDyhONJs|(RvT?Z?St5 zJe~uJKn9oH8ehO#Qs>h$z{xbsOPOK-DR@vG_GmD%r#DqpIINVFeAg~=yeiV@S@ycUgHP|m(|5vgek*ZEH4RdwK{d$6jL>+4X z`4ChMuWjS9nJF{!ij95ygn<6)v21l;z0gZ@UjZab`9s9KK++(ZU}hS#jlPp@YHsdX+N+j<%}bAm_k9)T8@LAgyH4JzSyw>)>XO5eYZ-f(KZq4CZ8KAE}&p33a#nAw#ZL!zhkYZa0_fy&Jh12UfTAj4W?< z)O2(X-CC!M1+7n}8-n0j-m&cbyUhc#29lDYkyrH{#~wfcNz*@%?SyYHR3jK#qYkg` zfOxt;Xp>!NetI3?-j2$*c6E0peFJ1k0qtRyN~0J}eb0QIcI)6yPMaCaqc?e?=5%L0 z!wWTLgHwtNdLFYf->C5f&&TSGJKKO9egTz|q7H=dL_|bSuP9CLa~>76 znCtPqJkWLkR->ldp7iOcx({hE83#s3x$hnxA+ElF{8rgnRi*qnM5H$vfR4=(~l-hR-WQi)59iT6|TZNDzuRd5R$FCqNF)uguYRz#H!g{_d46@8|;6d)C31g+?wwl9UWUN!_7@iU(y8@`IP%@=plBH%=02yJ&ynGhwto!JlUOX z4ZlnR=UHTX(m73bJ`MY1G35^fepmv;GCh*P+1Gq7e{QeWW1q~jSlc~K9=z&1x!R5Sw+>Pg|4d7B*QMP1eov^xZ{boH28L>~l{Zhb#6){LZ zm@6K(L>wtG?EU!}!s|J9nZo{zoX5(&q`-6B*F~kgn1RWbz(S1+KjtWyba%eqCgn)S zFN@z*^(@_A3M$`75z6`%5E_kQVPm~8vUW(0-)Xpgi@MOw2BBVq0JDHsQp!G~mGIp` zt+g8jO^5Tn$1Dr}bH1cx#Vy}6vXegp0~5m=T_@{(WO?uY<)bNy2_cW;Z}e~9$_)RA z&R+=3N)8DzIPSQK_PD=ZR~&XP^$^GwPJke6@_WV`6v&1R5CO#>3rm*Q23Pe8MP7zS zN4FFUff1Z$-rRg+ zUOSJkl&izPHIn6>?4GZlL7(#}f01PSSIocavf%MkVJQEWW_pySvMFl!k06}^LD&vwY0rFM7Sdo{5 z!^6JOK>wyp&Wqx=>r``x(>dQU>14zTUKY_wnmZX{if`ugWtEtf5;FbfaR!RPMaJd=iiHkN)+{o zw=7_sEj@pbvWiNnS(}3oHAP5B$P(ALz1hl~T>aEY-XZhaZD8r8xs7nX)xEONDCjv; zOUTNmo&)Iqji8`liKzLOKAgKFJ{IZWuJ!WaoUryyAsQa}xqK??8(ZCEx7KBV%c+g} zKb}#TJ3DI#oj_gNy)Lv4->#&&w<8@3lV0qv{JbmRz6E=*>$kXAjlB;|IzAm_X;uCB zv75{DlZUCPX_L_PUzBOWE8nZ-zMA|iD#R`FU!}FRHDgRnO#Q#U-C^A-YHAzgg4T%^ zfT5UUrP9zgG!1;~y?UlKy%*}N2#Hw+^T|{6+|stQd7Vod9abu&XJ-I|3zTY{NPshIIhMP4(e)?%0Uv@SDj|pppr_Jb?SU%^oes09s*d=hLG% ze`5g7Pg|}#S=k6d+Fsg@%%xAxPEJlx7nk#=$7MiN?f*(I2$fs2BE8qna6zlDpw#AvWn%g%t!02^>Yj~m`Jc$>iH%XJ+e zZKMxoZxEm;V0$ox2?Us2H~)s3I>H<)HIzL9C2*B2%2% zuoz$qGG)~AC_jk0_89l)-w}Kjrep=sU*p1KA%bo<^)Jj!7x@I^8msO> z4>V)boi5cC6{?m%cYKi1zpQXO7Sj9MjcR~0ZwA;qj*h|~Zix)e+JeBwbFm_`UgUBj zgZ3CD_k(a;jH;dGQ*p3Bd%O`FzipXyFXu?vx-t zRRt(cFcEnGVV%fzDOH|TTM%e0EhS#yS{w_?&t<&+7NqhCIwh;+O2Q)sTsc~YfC3bU zq)x}416#3Ue7ioXI|D~PEaz~kUWr15fPZx;b=F9Tzwr0+<&|tGXq@ z-!p+0U!6Y(5C2L=UkFUuSvc=t6~zQS+H_VW)Q7oK9zW$`$z@cCY7+mxgHfQ2uQhZ-Bg6F)mmEz|j=0p4I}11k?as_b+mA%#j1I8iXEwQXk2s&yQGt+}5bJPGb zYs;@L`=D=*mVrBcjz(@?+%AG&0^6ZbXHPVwwQtYzgjukZEJ2bVC7?Lfli&RQ%4ql> zZ3Bjstq?yQBdHTP-^B*^9^)d5i0V_-08a5k6bqU|cZ>@XF)H;$15M;U%QGN@6}Z0a%$-dB3&%`n1N7*~lrtIJ9})K!Z&`SKbd?mA;INup)SGh_}|FuM4}K3U^9Fb8+f3I)=dOLQaPRBqE3YvwXIT1%t;9*xKkQh>Kn}+ z;Q<4<$i;f+^O`#E1n{wLZ`^)rpKs3y{DkQ8RNlH1vu<1qB`m4Ar|D>VgG6BuM+f>~Dm_|t=53>L+p^5?Ap9utF zppJ$KnZyZs@R1KmMUXW&i^`seS3FLP#h)k*_YGfPxP+Lf^-x z_sPQj+kVNDcrI(6;l2Q!R|cD$^7tp7bf7;!t@&f~h=LG73c#aHVNd&EsO|JDJ9OOx z4GDygnsW{dr3{vF5xpd#k62wqCZIlHJHXZfU5XlU_yV<>Rk0;H^GfkD(N zC8;^cd!U6lfJ^KX0@2Cm4 zd=8d)ev_63t*c7*w-JRN1{3v+Dme+gIiEr$x928QNy2pGAlduak_Nks{AB%r4d$fH zGhrW1qRbq8d%BIF&*L}E-fw%oD&cP&m%}Rqb%t5mz_v?@_2O7|JOgdKNWi}S@&06z zP{QC}7)~36DkZQSelp`cI3;!}dXmDmA1C4Sk2IJkXca2?Rq1CeU5pr=Z$Eb|MA79r zy57rE7PN*8KqGRYA39>(eT2c|(NGsfr{%mU54|>P>rf=dU$a zVl0M^67U>rcEgp*DN>+P_xfhO3&BA|ja^IR9nZ)3c|`h+cLeVW#xuq+3uv}nG%A6$ z#JM=Sf#pn?8f_ORN$Xqfs`b>*IN!zY+eSWe1i~INHf-G~8xDL(&1R?cv=sOgWv}k5 zvteF@Dw-i34yuxg_Ahk2WZ_t?;YIDiHl87$aT0m1go-04L)r0u>_1x^n=umxKkx@T zXKB)YVqzl*IYMPkmI~jo$xVn-{?=xiJ8`YE6AE&DmVLZJomVQhqu;I!nEhjZSW}A& z9aUJDnK_|~5?EL>2L>l;*|=qJIbzC{IPFmO%Mz2JRMpR3A?xzA_EP8?g@56F6FM$q zslHsKdNUki-|0=HpNsVPE(Hds%j;8TT#?q*MZ~(-<~C%b_A2|X}`fHdwvLeljj~n5@a2L|D4uGt&g#XQX&30uL+(&sRQi{`=)W|ELz*%Z{nK;cEHSxzI zsrA`<4Rz6Z8InRbWPpDMuP7)CHtM(&gT2jMVmcA6EvW4pd-}Qk^8M1f ztkSjGqJ~jOXiyi^+0T{nVA#S8`(S%RprmWLq)G}RWd2UQ3q_lH)oTEP+*uVvg!LsN zp4D^TqM1J4uq;@HeYBs!V3ZI;JIi2~d7$Bqe6W{zYP=5{*J{>)N}3r95vhNZ5{>PP zuI(%1IF+xoU4$(JU!{WLTR0_#*HMh#ml-ls=i#wjLt?A2l@z+gU?w4~g&W3HA^s`4 z4F}UB7IHlO-A+nWfeRdy@gjRdiHelQl{X=Mi%^&FKd0*<@l5nI+3Vc#h{rC$Kmoe- zvpZ3bMn*|-qZj5396y5q;CzC9kn7s`b9To2s502|i^nLOu-LIIk#*-sAS;X19xv|T z{0*ls}liCZmq|f?Z;8zxgGkM?Er0=gxe!}5B)Cfts%zx+KRG~>%xK$^Qwgd zxLTF&cv9bZ<-o^?!iTp33(@-}y0vl_)2I~G)HF}92jl3v=#<)O=E7Rmdy2oglf|Hk z9aQ(|WOUn)IJ?Ev)&Fx6bF6)kaLn)DLr)thofgM!&@~!rT^O7bt@e5Or7|3fA$%9Z zdcgKVh^j?@4Sr`l^A=M|1^Pj?Yjm{L@U2TTmvgF?=HwY>`I&p}76Dqk08?8TUT-A< znh@%m4Kr8Z2eAG|xkt@vbVWTWWo?7J*w`48u>8$6i$5I*42V{tPKX%OlI`)B z()!3ib)k>8#b55^e=w>k^6=B1ZbJ{JnSv5WmCH4hd6f6{<7;|@XRLCWiDm99yGhA{}Wd_r0D9El$(X5~ZD@6Yeq%JJ_WnN-%QoT_^& zls{`|J%9EnfAEk~Gyx};)G-ocS*iS3?;B@s#A40HNR)|D9E{SnkxmA^FH@JMsvova zX8&ayT=lAu;Am_z@Z2<%$ z6{BjEfS{w}t2VXwOJOAH%tlL96JNh1#=Wf*>*+C=wXQ*vNIs(oaU1*ElJg~AWBoz3 zYsEM6%XU&tu#eu|7g)PJi(C|&tXR}Xn&hnaxd#gx>+j>0Lv??-YpZnq{-}DCX85D* z_dAPe6Sn6vuwUIAo->ylZ}KI6nQVFL;mT@J6n=}jh-Pjuf%pEv++Pdkdj*Zwp7DBP zrhTtVw6{gZP)&6$66l-|HJ4w8%;eg~^EPs4nrqIew2C|SrN%S*vk{KJr_g;`Y{qKK za@>)WYnnH1$Y7g~H208STe0$q*DizuUr(^Zw@=B+o)Nq~aS$e4yGfT@>daH^DKIsz z)cwow6@MRvpi+T4eltCU8Nd3QQI$>-+ zFgW?Ai;?m(M6`3~3t0MUNoj|7dB1(@$eb{5jiAiUXxRcsX%N7syb8a-?5DbXQY&dt z%QtBuucYrm*1Dmz5?dn{A0>WU5x4YjETQ|M(8cAmSNvkb`2Ku7q`f}>zYyO<$8g@x zUzs*Gk#M%Gr7AVQ9ITO)uwuolOW^S4&Y0P4a>%SIVE2Gjj|O|=mQu{^v#Iu?g_u(5R=+V-wf&8^chyn4kgY80C{bYAldhLKCoo`h9f)w_=Um8!5STwbwF{_U3Tizp{AyHC84h8bs|GATle zy3F*$Rqlvr6MURu^<;ctoJ-C-Z#8oO_$tvow?$;EY1DOi-(^S-2TIzlGbRuwb&;-U z7yZw0dus6-cg1D}!{`%wA1C;jA;~pKJ=T-XVnJJKHRncn?@V?ZaEO-)De!(_{cb?PQZM`vF>be}<$+yB>x!n%iMG>Ka&r0;UkQJwE7Mk z$`Z}Z4DInTXYHvlPzHtdM7q)!O@~4(CDCwL6=&P!6H8`ZIu8IG){ebnFOOsgJi5#J zo*23$q%3OfclD3VJx10L$%S6mR#0O{Z-fm;yH{W~(%~1?#@9nDw|X-FV4WFNNE?u= zNsUpZB9>X39R6ko>B{E@palselu!fi@;2{*99+kw!vd7==a0k1U~mtD?VxZfC+5?F zS*Nm{8|Z%mvGF+lu?k#)zW_q@WO_h`!~-H-wk-C(55!&CS9;0~tCO{qo!|0Ld`A4R z!?{Ezel$sA7!Q>QFASC6a)j3Q9elimCP?JOd_Bc7+iW%D38BRl_}=XI4MruG!$~Y! z)#3G0Ing0FLqmnq)N|04xKy0c__kp$%3zYQ=jbnv1!pZF??**9r5!AA6QQz8HaBac z-)DvlmLg^;&QlPoDNzVPj2csI+Sp_GZ>Y~5tTw?OOsB`~G>Igi6#!z}vZxRn z_mZ3%^Wj5E=1-Gbo9g3YL(lz--KY}z4P9;Rev`lWf1j9yQ{VAp+Sf5=7Hy=={c`2yJadWY-BAQd=Lk{ z_R5BjK&)=KT9B)gLV{1>rb2!28ThgAIW#%qO5B*yF`N0*A1srvHd0v*yWIk#^?)Ts zM5jSs*i*xFz2D7|(i500ZVx1J5^<9kp}e$hGHAC2LutRtBH%ytYf07!h%N|p$O_p@ zM76*Ze2pGv`4>e77PC@W+j}V~VvZ$pJA7_u0J6SUt6#Bso7y)~k6x^LN|Y_7g&3t~ zc23kDyJ8C;xg3Hmb~#>n;^|83;U1180$1Uh7VPe5U0Yj3=xI`|HIDic);1 z%Zx)#tB~cm_w^{1mrymqhd`i6ceMi`P*4dL1i~7qi~&@l{y)Y0VJg~EDlzW{YoEjk QxT*u><#`b=z=h}h2b9~@i2wiq literal 0 HcmV?d00001 diff --git a/common/tier4_camera_view_rviz_plugin/package.xml b/common/tier4_camera_view_rviz_plugin/package.xml new file mode 100644 index 0000000000000..0ede5e37b8287 --- /dev/null +++ b/common/tier4_camera_view_rviz_plugin/package.xml @@ -0,0 +1,31 @@ + + + + tier4_camera_view_rviz_plugin + 0.0.0 + The autoware camera view rviz plugin package + Yuxuan Liu + Makoto Yabuta + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + + autoware_ad_api_specs + component_interface_utils + geometry_msgs + libqt5-core + libqt5-gui + libqt5-widgets + rclcpp + rviz_common + rviz_default_plugins + + ament_lint_auto + autoware_lint_common + + + ament_cmake + + + diff --git a/common/tier4_camera_view_rviz_plugin/plugins/plugin_description.xml b/common/tier4_camera_view_rviz_plugin/plugins/plugin_description.xml new file mode 100644 index 0000000000000..ab522b80de26a --- /dev/null +++ b/common/tier4_camera_view_rviz_plugin/plugins/plugin_description.xml @@ -0,0 +1,24 @@ + + + + + Control the camera for bird-eye view. + + + + + Bird-eye-view Tool. This tool requires the corresponding BirdEyeViewController. + + + + + Control the camera for third-person view. + + + + + Third-person-view Tool. This tool requires the corresponding ThirdPersonViewController. + + + + diff --git a/common/tier4_camera_view_rviz_plugin/src/bird_eye_view_controller.cpp b/common/tier4_camera_view_rviz_plugin/src/bird_eye_view_controller.cpp new file mode 100644 index 0000000000000..bd5c3349d3c35 --- /dev/null +++ b/common/tier4_camera_view_rviz_plugin/src/bird_eye_view_controller.cpp @@ -0,0 +1,242 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +/* + * Copyright (c) 2009, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include "bird_eye_view_controller.hpp" + +#include "rviz_common/display_context.hpp" +#include "rviz_common/properties/bool_property.hpp" +#include "rviz_common/properties/float_property.hpp" +#include "rviz_common/viewport_mouse_event.hpp" +#include "rviz_rendering/objects/shape.hpp" +#include "rviz_rendering/orthographic.hpp" + +#include +#include +#include +#include +#include +#include + +namespace tier4_camera_view_rviz_plugin +{ +static const Ogre::Quaternion ROBOT_TO_CAMERA_ROTATION = + Ogre::Quaternion(Ogre::Radian(-Ogre::Math::HALF_PI), Ogre::Vector3::UNIT_Y) * + Ogre::Quaternion(Ogre::Radian(-Ogre::Math::HALF_PI), Ogre::Vector3::UNIT_Z); + +static const float PITCH_LIMIT_LOW = -Ogre::Math::HALF_PI + 0.001; +static const float PITCH_LIMIT_HIGH = Ogre::Math::HALF_PI - 0.001; + +BirdEyeViewController::BirdEyeViewController() : dragging_(false) +{ + scale_property_ = new rviz_common::properties::FloatProperty( + "Scale", 10, "How much to scale up the size of things in the scene.", this); + angle_property_ = new rviz_common::properties::FloatProperty( + "Angle", 0, "Angle around the Z axis to rotate.", this); + x_property_ = + new rviz_common::properties::FloatProperty("X", 0, "X component of camera position.", this); + y_property_ = + new rviz_common::properties::FloatProperty("Y", 0, "Y component of camera position.", this); +} + +BirdEyeViewController::~BirdEyeViewController() +{ +} + +void BirdEyeViewController::onInitialize() +{ + FramePositionTrackingViewController::onInitialize(); + + camera_->setProjectionType(Ogre::PT_ORTHOGRAPHIC); + auto camera_parent = getCameraParent(camera_); + camera_parent->setFixedYawAxis(false); + invert_z_->hide(); +} + +void BirdEyeViewController::reset() +{ + scale_property_->setFloat(10); + angle_property_->setFloat(0); + x_property_->setFloat(0); + y_property_->setFloat(0); +} + +void BirdEyeViewController::handleMouseEvent(rviz_common::ViewportMouseEvent & event) +{ + if (event.shift()) { + setStatus("Left-Click: Move X/Y."); + } else { + setStatus( + "Left-Click: Rotate. Middle-Click: Move X/Y. Right-Click:: Zoom. " + "Shift: More options."); + } + + bool moved = false; + + int32_t diff_x = 0; + int32_t diff_y = 0; + + if (event.type == QEvent::MouseButtonPress) { + dragging_ = true; + } else if (event.type == QEvent::MouseButtonRelease) { + dragging_ = false; + } else if (dragging_ && event.type == QEvent::MouseMove) { + diff_x = event.x - event.last_x; + diff_y = event.y - event.last_y; + moved = true; + } + + if (event.left() && !event.shift()) { + setCursor(Rotate2D); + angle_property_->add(diff_x * 0.005); + orientCamera(); + } else if (event.middle() || (event.shift() && event.left())) { + setCursor(MoveXY); + float scale = scale_property_->getFloat(); + move_camera(-diff_x / scale, diff_y / scale); + } else if (event.right()) { + setCursor(Zoom); + scale_property_->multiply(1.0 - diff_y * 0.01); + } else { + setCursor(event.shift() ? MoveXY : Rotate2D); + } + + if (event.wheel_delta != 0) { + int diff = event.wheel_delta; + scale_property_->multiply(1.0 - (-diff) * 0.001); + + moved = true; + } + + if (moved) { + context_->queueRender(); + emitConfigChanged(); + } +} + +void BirdEyeViewController::orientCamera() +{ + camera_->setOrientation( + Ogre::Quaternion(Ogre::Radian(angle_property_->getFloat()), Ogre::Vector3::UNIT_Z)); +} + +void BirdEyeViewController::mimic(rviz_common::ViewController * source_view) +{ + FramePositionTrackingViewController::mimic(source_view); + + if (BirdEyeViewController * source_ortho = qobject_cast(source_view)) { + scale_property_->setFloat(source_ortho->scale_property_->getFloat()); + angle_property_->setFloat(source_ortho->angle_property_->getFloat()); + x_property_->setFloat(source_ortho->x_property_->getFloat()); + y_property_->setFloat(source_ortho->y_property_->getFloat()); + } else { + auto source_camera_parent = getCameraParent(source_view->getCamera()); + setPosition(source_camera_parent->getPosition()); + } +} +void BirdEyeViewController::update(float dt, float ros_dt) +{ + FramePositionTrackingViewController::update(dt, ros_dt); + updateCamera(); +} + +void BirdEyeViewController::lookAt(const Ogre::Vector3 & point) +{ + setPosition(point - target_scene_node_->getPosition()); +} + +void BirdEyeViewController::onTargetFrameChanged( + const Ogre::Vector3 & old_reference_position, + const Ogre::Quaternion & /*old_reference_orientation*/) +{ + move_camera( + old_reference_position.x - reference_position_.x, + old_reference_position.y - reference_position_.y); +} + +void BirdEyeViewController::updateCamera() +{ + orientCamera(); + + float width = camera_->getViewport()->getActualWidth(); + float height = camera_->getViewport()->getActualHeight(); + + float scale = scale_property_->getFloat(); + Ogre::Matrix4 proj = rviz_rendering::buildScaledOrthoMatrix( + -width / scale / 2, width / scale / 2, -height / scale / 2, height / scale / 2, + camera_->getNearClipDistance(), camera_->getFarClipDistance()); + camera_->setCustomProjectionMatrix(true, proj); + + // For Z, we use half of the far-clip distance set in + // selection_context.cpp, so that the shader program which computes + // depth can see equal distances above and below the Z=0 plane. + auto camera_parent = getCameraParent(camera_); + camera_parent->setPosition(x_property_->getFloat(), y_property_->getFloat(), 500); +} + +Ogre::SceneNode * BirdEyeViewController::getCameraParent(Ogre::Camera * camera) +{ + auto camera_parent = camera->getParentSceneNode(); + + if (!camera_parent) { + throw std::runtime_error("camera's parent scene node pointer unexpectedly nullptr"); + } + return camera_parent; +} + +void BirdEyeViewController::setPosition(const Ogre::Vector3 & pos_rel_target) +{ + x_property_->setFloat(pos_rel_target.x); + y_property_->setFloat(pos_rel_target.y); +} + +void BirdEyeViewController::move_camera(float dx, float dy) +{ + float angle = angle_property_->getFloat(); + x_property_->add(dx * cos(angle) - dy * sin(angle)); + y_property_->add(dx * sin(angle) + dy * cos(angle)); +} + +} // namespace tier4_camera_view_rviz_plugin + +#include +PLUGINLIB_EXPORT_CLASS( + tier4_camera_view_rviz_plugin::BirdEyeViewController, rviz_common::ViewController) diff --git a/common/tier4_camera_view_rviz_plugin/src/bird_eye_view_controller.hpp b/common/tier4_camera_view_rviz_plugin/src/bird_eye_view_controller.hpp new file mode 100644 index 0000000000000..3c0091740bd59 --- /dev/null +++ b/common/tier4_camera_view_rviz_plugin/src/bird_eye_view_controller.hpp @@ -0,0 +1,112 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +/* + * Copyright (c) 2012, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef BIRD_EYE_VIEW_CONTROLLER_HPP_ +#define BIRD_EYE_VIEW_CONTROLLER_HPP_ + +#include "rviz_common/frame_position_tracking_view_controller.hpp" + +#include +#include + +namespace rviz_common +{ +namespace properties +{ +class FloatProperty; +class Shape; +class VectorProperty; +} // namespace properties +} // namespace rviz_common + +namespace tier4_camera_view_rviz_plugin +{ +/** @brief A first-person camera, controlled by yaw, pitch, and position. */ +class BirdEyeViewController : public rviz_common::FramePositionTrackingViewController +{ + Q_OBJECT + +public: + BirdEyeViewController(); + + ~BirdEyeViewController() override; + + void onInitialize() override; + + void handleMouseEvent(rviz_common::ViewportMouseEvent & evt) override; + + void lookAt(const Ogre::Vector3 & point) override; + + void reset() override; + + /** @brief Configure the settings of this view controller to give, + * as much as possible, a similar view as that given by the + * @param source_view. + * + * @param source_view must return a valid @c Ogre::Camera* from getCamera(). */ + void mimic(rviz_common::ViewController * source_view) override; + + void update(float dt, float ros_dt) override; + +protected: + void onTargetFrameChanged( + const Ogre::Vector3 & old_reference_position, + const Ogre::Quaternion & old_reference_orientation) override; + + /** Set the camera orientation based on angle_. */ + void orientCamera(); + + void setPosition(const Ogre::Vector3 & pos_rel_target); + void move_camera(float x, float y); + void updateCamera(); + Ogre::SceneNode * getCameraParent(Ogre::Camera * camera); + + rviz_common::properties::FloatProperty * scale_property_; + rviz_common::properties::FloatProperty * angle_property_; + rviz_common::properties::FloatProperty * x_property_; + rviz_common::properties::FloatProperty * y_property_; + bool dragging_; +}; + +} // namespace tier4_camera_view_rviz_plugin + +#endif // BIRD_EYE_VIEW_CONTROLLER_HPP_ diff --git a/common/tier4_camera_view_rviz_plugin/src/bird_eye_view_tool.cpp b/common/tier4_camera_view_rviz_plugin/src/bird_eye_view_tool.cpp new file mode 100644 index 0000000000000..0c50f1ae1a0f4 --- /dev/null +++ b/common/tier4_camera_view_rviz_plugin/src/bird_eye_view_tool.cpp @@ -0,0 +1,167 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +/* + * UOS-ROS packages - Robot Operating System code by the University of Osnabrück + * Copyright (C) 2014 University of Osnabrück + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without modification, are permitted + * provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, this list of conditions + * and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, this list of + * conditions and the following disclaimer in the documentation and/or other materials provided with + * the distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR + * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND + * FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR + * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, + * DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, + * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY + * WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + * route_set_tool.cpp + * + * Author: Henning Deeken {hdeeken@uos.de} + * + */ + +#include "bird_eye_view_tool.hpp" + +#include "rviz_common/display_context.hpp" +#include "rviz_common/view_manager.hpp" + +#include + +namespace tier4_camera_view_rviz_plugin +{ +BirdEyeViewTool::BirdEyeViewTool() +{ + shortcut_key_ = 'r'; +} + +BirdEyeViewTool::~BirdEyeViewTool() +{ +} + +void BirdEyeViewTool::onInitialize() +{ + setName("Bird Eye View"); + + step_length_property_ = new rviz_common::properties::FloatProperty( + "Step Length", 0.1, "The length by with the position is updated on each step.", + getPropertyContainer(), SLOT(setOffset()), this); + + boost_property_ = new rviz_common::properties::FloatProperty( + "Boost Property", 0.5, "Gives the boost factor which is applied if pressing shift.", + getPropertyContainer(), SLOT(setBoost()), this); + + fly_property_ = new rviz_common::properties::BoolProperty( + "Fly Mode", false, "In fly mode it is possible to move along the z axis as well.", + getPropertyContainer(), SLOT(setFlyMode()), this); + + left_hand_property_ = new rviz_common::properties::BoolProperty( + "Left Hand Mode", false, "In left hand mode one uses the arrows to move around", + getPropertyContainer(), SLOT(setLeftHandMode()), this); + + fallback_view_controller_property_ = new rviz_common::properties::EnumProperty( + "Fallback ViewController", QString("tier4_camera_view_rviz_plugin/BirdEyeView"), + "Determines to which view controller the control switches, if the tool is deactivated.", + getPropertyContainer(), SLOT(setFallbackViewController()), this); + + m_pos_offset = 0.1; + m_boost = 0.5; + m_fly_mode = false; + m_left_hand_mode = false; + + // temporarily disabled + // setFallbackToolProperty(); + setFallbackViewControllerProperty(); +} + +void BirdEyeViewTool::setFallbackViewControllerProperty() +{ + fallback_view_controller_property_->clearOptions(); + m_view_controller_classes.clear(); + + m_view_controller_classes = context_->getViewManager()->getDeclaredClassIdsFromFactory(); + + for (int i = 0; i < m_view_controller_classes.size(); i++) { + if (m_view_controller_classes[i] != QString("tier4_camera_view_rviz_plugin/BirdEyeView")) { + fallback_view_controller_property_->addOption(m_view_controller_classes[i], i); + m_view_controller.push_back(context_->getViewManager()->getViewAt(i)); + } + } + + fallback_view_controller_property_->show(); + setFallbackViewController(); +} + +// temporarily disabled +// void BirdEyeViewTool::setFallbackToolProperty() +// { +// fallback_tool_property_->clearOptions(); +// m_tools.clear(); + +// m_tool_classes = context_->getToolManager()->getToolClasses(); + +// for (int i = 0; i < m_tool_classes.size(); i++) { +// if (m_tool_classes[i] != getClassId()) { +// fallback_tool_property_->addOption(m_tool_classes[i], i); +// m_tools.push_back(context_->getToolManager()->getTool(i)); +// } +// } + +// fallback_tool_property_->show(); +// setFallbackTool(); +// } + +void BirdEyeViewTool::activate() +{ + context_->getViewManager()->setCurrentViewControllerType( + QString("tier4_camera_view_rviz_plugin/BirdEyeView")); + context_->getViewManager()->getCurrent()->reset(); + + // temporarily disabled + // setFallbackToolProperty(); + setFallbackViewControllerProperty(); +} + +void BirdEyeViewTool::deactivate() +{ +} + +int BirdEyeViewTool::processKeyEvent(QKeyEvent * event, rviz_common::RenderPanel * panel) +{ + return 0; +} + +int BirdEyeViewTool::processMouseEvent(rviz_common::ViewportMouseEvent & event) +{ + if (event.panel->getViewController()) { + event.panel->getViewController()->handleMouseEvent(event); + setCursor(event.panel->getViewController()->getCursor()); + } + return 0; +} + +} // namespace tier4_camera_view_rviz_plugin + +#include +PLUGINLIB_EXPORT_CLASS(tier4_camera_view_rviz_plugin::BirdEyeViewTool, rviz_common::Tool) diff --git a/common/tier4_camera_view_rviz_plugin/src/bird_eye_view_tool.hpp b/common/tier4_camera_view_rviz_plugin/src/bird_eye_view_tool.hpp new file mode 100644 index 0000000000000..212cdd49c13bd --- /dev/null +++ b/common/tier4_camera_view_rviz_plugin/src/bird_eye_view_tool.hpp @@ -0,0 +1,144 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +/* + * UOS-ROS packages - Robot Operating System code by the University of Osnabrück + * Copyright (C) 2014 University of Osnabrück + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without modification, are permitted + * provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, this list of conditions + * and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, this list of + * conditions and the following disclaimer in the documentation and/or other materials provided with + * the distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR + * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND + * FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR + * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF + * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, + * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + * route_set_tool.h + * + * Author: Henning Deeken + * + */ + +#ifndef BIRD_EYE_VIEW_TOOL_HPP_ +#define BIRD_EYE_VIEW_TOOL_HPP_ + +#include "bird_eye_view_controller.hpp" +#include "rviz_common/properties/bool_property.hpp" +#include "rviz_common/properties/enum_property.hpp" +#include "rviz_common/properties/float_property.hpp" +#include "rviz_common/render_panel.hpp" +#include "rviz_common/tool.hpp" +#include "rviz_common/viewport_mouse_event.hpp" + +#include +#include +#include + +#include +#include + +/** + * + *@class BirdEyeViewTool + * + *@brief Implements a rviz tool that allows to navigate in a ego-shooter mode. + */ + +namespace tier4_camera_view_rviz_plugin +{ + +class FPSMotionConfigWidget; +class BirdEyeViewTool : public rviz_common::Tool +{ + Q_OBJECT + +public: + BirdEyeViewTool(); + ~BirdEyeViewTool(); + virtual void onInitialize(); + virtual void activate(); + virtual void deactivate(); + + virtual int processKeyEvent(QKeyEvent * event, rviz_common::RenderPanel * panel); + virtual int processMouseEvent(rviz_common::ViewportMouseEvent & event); + +private Q_SLOTS: + void setOffset() { m_pos_offset = static_cast(step_length_property_->getFloat()); } + void setBoost() + { + if (boost_property_->getFloat() < 0.0) { + m_boost = 0.0; + } else if (boost_property_->getFloat() > 1.0) { + m_boost = 1.0; + } else { + m_boost = static_cast(boost_property_->getFloat()); + } + } + + void setFlyMode() { m_fly_mode = fly_property_->getBool(); } + void setLeftHandMode() { m_left_hand_mode = left_hand_property_->getBool(); } + // temporarily disabled + // void setFallbackTool() { m_fallback_tool = m_tools.at(fallback_tool_property_->getOptionInt()); + // } + void setFallbackViewController() + { + m_fallback_view_controller = + m_view_controller_classes.at(fallback_view_controller_property_->getOptionInt()); + } + +private: + Ogre::SceneNode * m_sceneNode; + + bool m_fly_mode; + bool m_left_hand_mode; + bool m_removed_select; + + double m_pos_offset; + double m_boost; + + QStringList m_tool_classes; + // temporarily disabled + // std::vector m_tools; + // rviz_common::Tool *m_fallback_tool; + + QStringList m_view_controller_classes; + QString m_fallback_view_controller; + std::vector m_view_controller; + + rviz_common::properties::FloatProperty * step_length_property_; + rviz_common::properties::FloatProperty * boost_property_; + rviz_common::properties::BoolProperty * fly_property_; + rviz_common::properties::BoolProperty * left_hand_property_; + // temporarily disabled + // rviz_common::properties::EnumProperty *fallback_tool_property_; + rviz_common::properties::EnumProperty * fallback_view_controller_property_; + + // temporarily disabled + // void setFallbackToolProperty(); + void setFallbackViewControllerProperty(); +}; +} // namespace tier4_camera_view_rviz_plugin +#endif // BIRD_EYE_VIEW_TOOL_HPP_ diff --git a/common/tier4_camera_view_rviz_plugin/src/third_person_view_controller.cpp b/common/tier4_camera_view_rviz_plugin/src/third_person_view_controller.cpp new file mode 100644 index 0000000000000..9f4306a9d982a --- /dev/null +++ b/common/tier4_camera_view_rviz_plugin/src/third_person_view_controller.cpp @@ -0,0 +1,258 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +/* + * Copyright (c) 2009, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include "third_person_view_controller.hpp" + +#include "rviz_common/display_context.hpp" +#include "rviz_common/properties/bool_property.hpp" +#include "rviz_common/properties/float_property.hpp" +#include "rviz_common/properties/tf_frame_property.hpp" +#include "rviz_common/properties/vector_property.hpp" +#include "rviz_common/viewport_mouse_event.hpp" +#include "rviz_rendering/objects/shape.hpp" + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +namespace tier4_camera_view_rviz_plugin +{ +static const float PITCH_START = Ogre::Math::HALF_PI / 3; +static const float YAW_START = Ogre::Math::PI; +static const float DISTANCE_START = 30; +static const float FOCAL_SHAPE_SIZE_START = 0.05; +static const bool FOCAL_SHAPE_FIXED_SIZE = true; +static const char * TARGET_FRAME_START = "base_link"; + +// move camera up so the focal point appears in the lower image half +static const float CAMERA_OFFSET = 0.2; + +void ThirdPersonViewController::onInitialize() +{ + OrbitViewController::onInitialize(); + focal_shape_->setColor(0.0f, 1.0f, 1.0f, 0.5f); +} + +void ThirdPersonViewController::reset() +{ + yaw_property_->setFloat(YAW_START); + pitch_property_->setFloat(PITCH_START); + distance_property_->setFloat(DISTANCE_START); + focal_shape_size_property_->setFloat(FOCAL_SHAPE_SIZE_START); + focal_shape_fixed_size_property_->setBool(false); + updateFocalShapeSize(); + focal_point_property_->setVector(Ogre::Vector3::ZERO); +} + +std::pair ThirdPersonViewController::intersectGroundPlane(Ogre::Ray mouse_ray) +{ + // convert rays into reference frame + mouse_ray.setOrigin(target_scene_node_->convertWorldToLocalPosition(mouse_ray.getOrigin())); + mouse_ray.setDirection( + target_scene_node_->convertWorldToLocalOrientation(Ogre::Quaternion::IDENTITY) * + mouse_ray.getDirection()); + + Ogre::Plane ground_plane(Ogre::Vector3::UNIT_Z, 0); + + std::pair intersection = mouse_ray.intersects(ground_plane); + return std::make_pair(intersection.first, mouse_ray.getPoint(intersection.second)); +} + +void ThirdPersonViewController::handleMouseEvent(rviz_common::ViewportMouseEvent & event) +{ + if (event.shift()) { + setStatus("Left-Click: Move X/Y. Right-Click:: Zoom."); + } else { + setStatus( + "Left-Click: Rotate. Middle-Click: Move X/Y. Right-Click:: Move Z. " + " Shift: More options."); + } + + int32_t diff_x = 0; + int32_t diff_y = 0; + + bool moved = false; + if (event.type == QEvent::MouseButtonPress) { + focal_shape_->getRootNode()->setVisible(true); + moved = true; + } else if (event.type == QEvent::MouseButtonRelease) { + focal_shape_->getRootNode()->setVisible(false); + moved = true; + } else if (event.type == QEvent::MouseMove) { + diff_x = event.x - event.last_x; + diff_y = event.y - event.last_y; + moved = true; + } + + if (event.left() && !event.shift()) { + setCursor(Rotate3D); + yaw(diff_x * 0.005); + pitch(-diff_y * 0.005); + } else if (event.middle() || (event.left() && event.shift())) { + setCursor(MoveXY); + // handle mouse movement + int width = camera_->getViewport()->getActualWidth(); + int height = camera_->getViewport()->getActualHeight(); + + Ogre::Ray mouse_ray = camera_->getCameraToViewportRay( + event.x / static_cast(width), event.y / static_cast(height)); + + Ogre::Ray last_mouse_ray = camera_->getCameraToViewportRay( + event.last_x / static_cast(width), event.last_y / static_cast(height)); + + auto last_intersect_pair = intersectGroundPlane(last_mouse_ray); + auto intersect_pair = intersectGroundPlane(mouse_ray); + + if (last_intersect_pair.first && intersect_pair.first) { + Ogre::Vector3 motion = intersect_pair.second - last_intersect_pair.second; + + // When dragging near the horizon, the motion can get out of + // control. This throttles it to an arbitrary limit per mouse + // event. + float motion_distance_limit = 1; /*meter*/ + if (motion.length() > motion_distance_limit) { + motion.normalise(); + motion *= motion_distance_limit; + } + + focal_point_property_->add(motion); + emitConfigChanged(); + } + } else if (event.right()) { + setCursor(Zoom); + zoom(-diff_y * 0.1 * (distance_property_->getFloat() / 10.0f)); + } else { + setCursor(event.shift() ? MoveXY : Rotate3D); + } + + if (event.wheel_delta != 0) { + int diff = event.wheel_delta; + zoom(diff * 0.001 * distance_property_->getFloat()); + moved = true; + } + + if (moved) { + context_->queueRender(); + } +} + +void ThirdPersonViewController::mimic(rviz_common::ViewController * source_view) +{ + FramePositionTrackingViewController::mimic(source_view); + + target_frame_property_->setValue(TARGET_FRAME_START); + getNewTransform(); + + Ogre::Camera * source_camera = source_view->getCamera(); + + Ogre::Ray camera_dir_ray(source_camera->getRealPosition(), source_camera->getRealDirection()); + Ogre::Ray camera_down_ray(source_camera->getRealPosition(), -1.0f * source_camera->getRealUp()); + + auto camera_intersection = intersectGroundPlane(camera_dir_ray); + auto camera_down_intersection = intersectGroundPlane(camera_down_ray); + + if (camera_intersection.first && camera_down_intersection.first) { + // Set a focal point by intersecting with the ground plane from above. This will be possible + // if some part of the ground plane is visible in the view and the camera is above the z-plane. + float l_b = source_camera->getRealPosition().distance(camera_intersection.second); + float l_a = source_camera->getRealPosition().distance(camera_down_intersection.second); + + distance_property_->setFloat((l_b * l_a) / (CAMERA_OFFSET * l_b + l_a)); + Ogre::Vector3 position_offset = + source_camera->getRealUp() * distance_property_->getFloat() * CAMERA_OFFSET; + + camera_dir_ray.setOrigin(source_camera->getRealPosition() - position_offset); + auto new_focal_point = intersectGroundPlane(camera_dir_ray); + focal_point_property_->setVector(new_focal_point.second - reference_position_); + + calculatePitchYawFromPosition( + source_camera->getParentSceneNode()->getPosition() - position_offset); + } +} + +void ThirdPersonViewController::updateCamera() +{ + OrbitViewController::updateCamera(); + camera_->getParentSceneNode()->setPosition( + camera_->getParentSceneNode()->getPosition() + + camera_->getParentSceneNode()->getLocalAxes() * Ogre::Vector3::UNIT_Y * + distance_property_->getFloat() * CAMERA_OFFSET); +} + +void ThirdPersonViewController::updateTargetSceneNode() +{ + if (FramePositionTrackingViewController::getNewTransform()) { + target_scene_node_->setPosition(reference_position_); + Ogre::Radian ref_yaw = reference_orientation_.getRoll( + false); // OGRE camera frame looks along -Z, so they call rotation around Z "roll". + Ogre::Quaternion ref_yaw_quat(Ogre::Math::Cos(ref_yaw / 2), 0, 0, Ogre::Math::Sin(ref_yaw / 2)); + target_scene_node_->setOrientation(ref_yaw_quat); + + context_->queueRender(); + } +} + +void ThirdPersonViewController::lookAt(const Ogre::Vector3 & point) +{ + Ogre::Vector3 camera_position = camera_->getParentSceneNode()->getPosition(); + Ogre::Vector3 new_focal_point = + target_scene_node_->getOrientation().Inverse() * (point - target_scene_node_->getPosition()); + new_focal_point.z = 0; + distance_property_->setFloat(new_focal_point.distance(camera_position)); + focal_point_property_->setVector(new_focal_point); + + calculatePitchYawFromPosition(camera_position); +} + +} // namespace tier4_camera_view_rviz_plugin + +#include +PLUGINLIB_EXPORT_CLASS( + tier4_camera_view_rviz_plugin::ThirdPersonViewController, rviz_common::ViewController) diff --git a/common/tier4_camera_view_rviz_plugin/src/third_person_view_controller.hpp b/common/tier4_camera_view_rviz_plugin/src/third_person_view_controller.hpp new file mode 100644 index 0000000000000..fef036ceccda3 --- /dev/null +++ b/common/tier4_camera_view_rviz_plugin/src/third_person_view_controller.hpp @@ -0,0 +1,94 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +/* + * Copyright (c) 2012, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef THIRD_PERSON_VIEW_CONTROLLER_HPP_ +#define THIRD_PERSON_VIEW_CONTROLLER_HPP_ + +#include "rviz_default_plugins/view_controllers/orbit/orbit_view_controller.hpp" + +#include + +#include + +namespace Ogre +{ +class SceneNode; +} + +namespace tier4_camera_view_rviz_plugin +{ +class TfFrameProperty; + +/** + * \brief Like the orbit view controller, but focal point moves only in the x-y plane. + */ +class ThirdPersonViewController : public rviz_default_plugins::view_controllers::OrbitViewController +{ + Q_OBJECT + +public: + void onInitialize() override; + + void handleMouseEvent(rviz_common::ViewportMouseEvent & evt) override; + + void lookAt(const Ogre::Vector3 & point) override; + + void reset() override; + + /** @brief Configure the settings of this view controller to give, + * as much as possible, a similar view as that given by the + * @a source_view. + * + * @a source_view must return a valid @c Ogre::Camera* from getCamera(). */ + void mimic(rviz_common::ViewController * source_view) override; + +protected: + void updateCamera() override; + + void updateTargetSceneNode() override; + + std::pair intersectGroundPlane(Ogre::Ray mouse_ray); +}; + +} // namespace tier4_camera_view_rviz_plugin + +#endif // THIRD_PERSON_VIEW_CONTROLLER_HPP_ diff --git a/common/tier4_camera_view_rviz_plugin/src/third_person_view_tool.cpp b/common/tier4_camera_view_rviz_plugin/src/third_person_view_tool.cpp new file mode 100644 index 0000000000000..09c7fe0c2677a --- /dev/null +++ b/common/tier4_camera_view_rviz_plugin/src/third_person_view_tool.cpp @@ -0,0 +1,173 @@ +// Copyright 2023-2024 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +/* + * UOS-ROS packages - Robot Operating System code by the University of Osnabrück + * Copyright (C) 2014 University of Osnabrück + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without modification, are permitted + * provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, this list of conditions + * and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, this list of + * conditions and the following disclaimer in the documentation and/or other materials provided with + * the distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR + * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND + * FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR + * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, + * DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, + * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY + * WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + * route_set_tool.cpp + * + * Author: Henning Deeken {hdeeken@uos.de} + * + * + */ + +#include "third_person_view_tool.hpp" + +#include "rviz_common/display_context.hpp" +#include "rviz_common/view_manager.hpp" + +#include + +namespace tier4_camera_view_rviz_plugin +{ +ThirdPersonViewTool::ThirdPersonViewTool() +{ + shortcut_key_ = 'o'; +} + +ThirdPersonViewTool::~ThirdPersonViewTool() +{ +} + +void ThirdPersonViewTool::onInitialize() +{ + setName("Third Person View"); + + step_length_property_ = new rviz_common::properties::FloatProperty( + "Step Length", 0.1, "The length by with the position is updated on each step.", + getPropertyContainer(), SLOT(setOffset()), this); + + boost_property_ = new rviz_common::properties::FloatProperty( + "Boost Property", 0.5, "Gives the boost factor which is applied if pressing shift.", + getPropertyContainer(), SLOT(setBoost()), this); + + fly_property_ = new rviz_common::properties::BoolProperty( + "Fly Mode", false, "In fly mode it is possible to move along the z axis as well.", + getPropertyContainer(), SLOT(setFlyMode()), this); + + left_hand_property_ = new rviz_common::properties::BoolProperty( + "Left Hand Mode", false, "In left hand mode one uses the arrows to move around", + getPropertyContainer(), SLOT(setLeftHandMode()), this); + + // temporarily disabled + // fallback_tool_property_ = new rviz_common::properties::EnumProperty( + // "Fallback Tool", QString("tier4_camera_view_rviz_plugin/ThirdPersonViewTool"), + // "Determines to which tool the control switches, if the tool is deactivated.", + // getPropertyContainer(), SLOT(setFallbackTool()), this); + fallback_view_controller_property_ = new rviz_common::properties::EnumProperty( + "Fallback ViewController", QString("tier4_camera_view_rviz_plugin/ThirdPersonView"), + "Determines to which view controller the control switches, if the tool is deactivated.", + getPropertyContainer(), SLOT(setFallbackViewController()), this); + + m_pos_offset = 0.1; + m_boost = 0.5; + m_fly_mode = false; + m_left_hand_mode = false; + + // temporarily disabled + // setFallbackToolProperty(); + setFallbackViewControllerProperty(); +} + +void ThirdPersonViewTool::setFallbackViewControllerProperty() +{ + fallback_view_controller_property_->clearOptions(); + m_view_controller_classes.clear(); + + m_view_controller_classes = context_->getViewManager()->getDeclaredClassIdsFromFactory(); + + for (int i = 0; i < m_view_controller_classes.size(); i++) { + if (m_view_controller_classes[i] != QString("tier4_camera_view_rviz_plugin/ThirdPersonView")) { + fallback_view_controller_property_->addOption(m_view_controller_classes[i], i); + m_view_controller.push_back(context_->getViewManager()->getViewAt(i)); + } + } + + fallback_view_controller_property_->show(); + setFallbackViewController(); +} + +// temporarily disabled +// void ThirdPersonViewTool::setFallbackToolProperty() +// { +// fallback_tool_property_->clearOptions(); +// m_tools.clear(); + +// m_tool_classes = context_->getToolManager()->getToolClasses(); + +// for (int i = 0; i < m_tool_classes.size(); i++) { +// if (m_tool_classes[i] != getClassId()) { +// fallback_tool_property_->addOption(m_tool_classes[i], i); +// m_tools.push_back(context_->getToolManager()->getTool(i)); +// } +// } + +// fallback_tool_property_->show(); +// setFallbackTool(); +// } + +void ThirdPersonViewTool::activate() +{ + context_->getViewManager()->setCurrentViewControllerType( + QString("tier4_camera_view_rviz_plugin/ThirdPersonView")); + context_->getViewManager()->getCurrent()->reset(); + + // temporarily disabled + // setFallbackToolProperty(); + setFallbackViewControllerProperty(); +} + +void ThirdPersonViewTool::deactivate() +{ +} + +int ThirdPersonViewTool::processKeyEvent(QKeyEvent * event, rviz_common::RenderPanel * panel) +{ + return 0; +} + +int ThirdPersonViewTool::processMouseEvent(rviz_common::ViewportMouseEvent & event) +{ + if (event.panel->getViewController()) { + event.panel->getViewController()->handleMouseEvent(event); + setCursor(event.panel->getViewController()->getCursor()); + } + return 0; +} + +} // namespace tier4_camera_view_rviz_plugin + +#include +PLUGINLIB_EXPORT_CLASS(tier4_camera_view_rviz_plugin::ThirdPersonViewTool, rviz_common::Tool) diff --git a/common/tier4_camera_view_rviz_plugin/src/third_person_view_tool.hpp b/common/tier4_camera_view_rviz_plugin/src/third_person_view_tool.hpp new file mode 100644 index 0000000000000..37d0db13b4629 --- /dev/null +++ b/common/tier4_camera_view_rviz_plugin/src/third_person_view_tool.hpp @@ -0,0 +1,144 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +/* + * UOS-ROS packages - Robot Operating System code by the University of Osnabrück + * Copyright (C) 2014 University of Osnabrück + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without modification, are permitted + * provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, this list of conditions + * and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, this list of + * conditions and the following disclaimer in the documentation and/or other materials provided with + * the distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR + * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND + * FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR + * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF + * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, + * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + * route_set_tool.h + * + * Author: Henning Deeken + * + */ + +#ifndef THIRD_PERSON_VIEW_TOOL_HPP_ +#define THIRD_PERSON_VIEW_TOOL_HPP_ + +#include "rviz_common/properties/bool_property.hpp" +#include "rviz_common/properties/enum_property.hpp" +#include "rviz_common/properties/float_property.hpp" +#include "rviz_common/render_panel.hpp" +#include "rviz_common/tool.hpp" +#include "rviz_common/viewport_mouse_event.hpp" +#include "third_person_view_controller.hpp" + +#include +#include +#include + +#include +#include + +/** + * + *@class ThirdPersonViewTool + * + *@brief Implements a rviz tool that allows to navigate in a ego-shooter mode. + */ + +namespace tier4_camera_view_rviz_plugin +{ + +class FPSMotionConfigWidget; +class ThirdPersonViewTool : public rviz_common::Tool +{ + Q_OBJECT + +public: + ThirdPersonViewTool(); + ~ThirdPersonViewTool(); + virtual void onInitialize(); + virtual void activate(); + virtual void deactivate(); + + virtual int processKeyEvent(QKeyEvent * event, rviz_common::RenderPanel * panel); + virtual int processMouseEvent(rviz_common::ViewportMouseEvent & event); + +private Q_SLOTS: + void setOffset() { m_pos_offset = static_cast(step_length_property_->getFloat()); } + void setBoost() + { + if (boost_property_->getFloat() < 0.0) { + m_boost = 0.0; + } else if (boost_property_->getFloat() > 1.0) { + m_boost = 1.0; + } else { + m_boost = static_cast(boost_property_->getFloat()); + } + } + + void setFlyMode() { m_fly_mode = fly_property_->getBool(); } + void setLeftHandMode() { m_left_hand_mode = left_hand_property_->getBool(); } + // temporarily disabled + // void setFallbackTool() { m_fallback_tool = m_tools.at(fallback_tool_property_->getOptionInt()); + // } + void setFallbackViewController() + { + m_fallback_view_controller = + m_view_controller_classes.at(fallback_view_controller_property_->getOptionInt()); + } + +private: + Ogre::SceneNode * m_sceneNode; + + bool m_fly_mode; + bool m_left_hand_mode; + bool m_removed_select; + + double m_pos_offset; + double m_boost; + + QStringList m_tool_classes; + // temporarily disabled + // std::vector m_tools; + // rviz_common::Tool *m_fallback_tool; + + QStringList m_view_controller_classes; + QString m_fallback_view_controller; + std::vector m_view_controller; + + rviz_common::properties::FloatProperty * step_length_property_; + rviz_common::properties::FloatProperty * boost_property_; + rviz_common::properties::BoolProperty * fly_property_; + rviz_common::properties::BoolProperty * left_hand_property_; + // temporarily disabled + // rviz_common::properties::EnumProperty *fallback_tool_property_; + rviz_common::properties::EnumProperty * fallback_view_controller_property_; + + // temporarily disabled + // void setFallbackToolProperty(); + void setFallbackViewControllerProperty(); +}; +} // namespace tier4_camera_view_rviz_plugin +#endif // THIRD_PERSON_VIEW_TOOL_HPP_ From f952b6ef3f089d12c89c586de577d8faa58519fc Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 6 Nov 2023 16:10:55 +0900 Subject: [PATCH 125/202] refactor(tier4_planning_launch): use xml style launch (#5470) * refactor(tier4_planning_launch): use xml style launch Signed-off-by: satoshi-ota * refactor(tier4_planning_launch): remove python style launch Signed-off-by: satoshi-ota * fix(tier4_plannning_launch): fix namespace Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../launch/planning.launch.xml | 8 - .../scenario_planning/lane_driving.launch.xml | 11 +- .../motion_planning/motion_planning.launch.py | 387 ------------------ .../motion_planning.launch.xml | 224 ++++++++-- .../scenario_planning.launch.xml | 2 +- launch/tier4_planning_launch/package.xml | 1 + 6 files changed, 200 insertions(+), 433 deletions(-) delete mode 100644 launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py diff --git a/launch/tier4_planning_launch/launch/planning.launch.xml b/launch/tier4_planning_launch/launch/planning.launch.xml index 61020a503fd4c..bf81125286256 100644 --- a/launch/tier4_planning_launch/launch/planning.launch.xml +++ b/launch/tier4_planning_launch/launch/planning.launch.xml @@ -5,14 +5,6 @@ - - - - - - - - diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving.launch.xml index b8df4722b8087..73e466afc0bda 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving.launch.xml @@ -17,12 +17,11 @@ - - - - - - + + + + + diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py deleted file mode 100644 index d8c5d7825f19d..0000000000000 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py +++ /dev/null @@ -1,387 +0,0 @@ -# Copyright 2021 Tier IV, Inc. All rights reserved. -# -# 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 launch -from launch.actions import DeclareLaunchArgument -from launch.actions import GroupAction -from launch.actions import OpaqueFunction -from launch.actions import SetLaunchConfiguration -from launch.conditions import IfCondition -from launch.conditions import LaunchConfigurationEquals -from launch.conditions import UnlessCondition -from launch.substitutions import LaunchConfiguration -from launch.substitutions import PythonExpression -from launch_ros.actions import ComposableNodeContainer -from launch_ros.actions import LoadComposableNodes -from launch_ros.descriptions import ComposableNode -import yaml - - -def launch_setup(context, *args, **kwargs): - # vehicle information param path - vehicle_info_param_path = LaunchConfiguration("vehicle_param_file").perform(context) - with open(vehicle_info_param_path, "r") as f: - vehicle_info_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - # planning common param path - with open(LaunchConfiguration("common_param_path").perform(context), "r") as f: - common_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - # nearest search parameter - with open(LaunchConfiguration("nearest_search_param_path").perform(context), "r") as f: - nearest_search_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - # path smoother - smoother_output_path_topic = "path_smoother/path" - with open(LaunchConfiguration("elastic_band_smoother_param_path").perform(context), "r") as f: - elastic_band_smoother_param = yaml.safe_load(f)["/**"]["ros__parameters"] - elastic_band_smoother_component = ComposableNode( - package="path_smoother", - plugin="path_smoother::ElasticBandSmoother", - name="elastic_band_smoother", - namespace="", - remappings=[ - ("~/input/path", LaunchConfiguration("input_path_topic")), - ("~/input/odometry", "/localization/kinematic_state"), - ("~/output/path", smoother_output_path_topic), - ], - parameters=[ - nearest_search_param, - elastic_band_smoother_param, - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - planner_input_path_topic = PythonExpression( - [ - "'", - LaunchConfiguration("input_path_topic"), - "' if '", - LaunchConfiguration("path_smoother_type"), - "' == 'none'", - " else '", - smoother_output_path_topic, - "'", - ] - ) - # obstacle avoidance planner - with open( - LaunchConfiguration("obstacle_avoidance_planner_param_path").perform(context), "r" - ) as f: - obstacle_avoidance_planner_param = yaml.safe_load(f)["/**"]["ros__parameters"] - obstacle_avoidance_planner_component = ComposableNode( - package="obstacle_avoidance_planner", - plugin="obstacle_avoidance_planner::ObstacleAvoidancePlanner", - name="obstacle_avoidance_planner", - namespace="", - remappings=[ - ("~/input/path", planner_input_path_topic), - ("~/input/odometry", "/localization/kinematic_state"), - ("~/output/path", "obstacle_avoidance_planner/trajectory"), - ], - parameters=[ - nearest_search_param, - obstacle_avoidance_planner_param, - vehicle_info_param, - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - # path sampler - with open(LaunchConfiguration("path_sampler_param_path").perform(context), "r") as f: - path_sampler_param = yaml.safe_load(f)["/**"]["ros__parameters"] - path_sampler_component = ComposableNode( - package="path_sampler", - plugin="path_sampler::PathSampler", - name="path_sampler", - namespace="", - remappings=[ - ("~/input/path", planner_input_path_topic), - ("~/input/odometry", "/localization/kinematic_state"), - ("~/output/path", "obstacle_avoidance_planner/trajectory"), - ], - parameters=[ - nearest_search_param, - path_sampler_param, - vehicle_info_param, - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - # obstacle velocity limiter - with open( - LaunchConfiguration("obstacle_velocity_limiter_param_path").perform(context), "r" - ) as f: - obstacle_velocity_limiter_param = yaml.safe_load(f)["/**"]["ros__parameters"] - obstacle_velocity_limiter_component = ComposableNode( - package="obstacle_velocity_limiter", - plugin="obstacle_velocity_limiter::ObstacleVelocityLimiterNode", - name="obstacle_velocity_limiter", - namespace="", - remappings=[ - ("~/input/trajectory", "obstacle_avoidance_planner/trajectory"), - ("~/input/odometry", "/localization/kinematic_state"), - ("~/input/dynamic_obstacles", "/perception/object_recognition/objects"), - ("~/input/occupancy_grid", "/perception/occupancy_grid_map/map"), - ("~/input/obstacle_pointcloud", "/perception/obstacle_segmentation/pointcloud"), - ("~/input/map", "/map/vector_map"), - ("~/output/debug_markers", "debug_markers"), - ("~/output/trajectory", "obstacle_velocity_limiter/trajectory"), - ], - parameters=[ - obstacle_velocity_limiter_param, - vehicle_info_param, - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - # surround obstacle checker - with open( - LaunchConfiguration("surround_obstacle_checker_param_path").perform(context), "r" - ) as f: - surround_obstacle_checker_param = yaml.safe_load(f)["/**"]["ros__parameters"] - surround_obstacle_checker_component = ComposableNode( - package="surround_obstacle_checker", - plugin="surround_obstacle_checker::SurroundObstacleCheckerNode", - name="surround_obstacle_checker", - namespace="", - remappings=[ - ("~/output/no_start_reason", "/planning/scenario_planning/status/no_start_reason"), - ("~/output/stop_reasons", "/planning/scenario_planning/status/stop_reasons"), - ("~/output/max_velocity", "/planning/scenario_planning/max_velocity_candidates"), - ( - "~/output/velocity_limit_clear_command", - "/planning/scenario_planning/clear_velocity_limit", - ), - ( - "~/input/pointcloud", - "/perception/obstacle_segmentation/pointcloud", - ), - ("~/input/objects", "/perception/object_recognition/objects"), - ("~/input/odometry", "/localization/kinematic_state"), - ], - parameters=[ - surround_obstacle_checker_param, - vehicle_info_param, - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - # obstacle stop planner - with open(LaunchConfiguration("obstacle_stop_planner_param_path").perform(context), "r") as f: - obstacle_stop_planner_param = yaml.safe_load(f)["/**"]["ros__parameters"] - with open( - LaunchConfiguration("obstacle_stop_planner_acc_param_path").perform(context), "r" - ) as f: - obstacle_stop_planner_acc_param = yaml.safe_load(f)["/**"]["ros__parameters"] - obstacle_stop_planner_component = ComposableNode( - package="obstacle_stop_planner", - plugin="motion_planning::ObstacleStopPlannerNode", - name="obstacle_stop_planner", - namespace="", - remappings=[ - ("~/output/stop_reason", "/planning/scenario_planning/status/stop_reason"), - ("~/output/stop_reasons", "/planning/scenario_planning/status/stop_reasons"), - ("~/output/max_velocity", "/planning/scenario_planning/max_velocity_candidates"), - ( - "~/output/velocity_limit_clear_command", - "/planning/scenario_planning/clear_velocity_limit", - ), - ("~/output/trajectory", "/planning/scenario_planning/lane_driving/trajectory"), - ("~/input/acceleration", "/localization/acceleration"), - ( - "~/input/pointcloud", - "/perception/obstacle_segmentation/pointcloud", - ), - ("~/input/objects", "/perception/object_recognition/objects"), - ("~/input/odometry", "/localization/kinematic_state"), - ("~/input/trajectory", "obstacle_velocity_limiter/trajectory"), - ], - parameters=[ - nearest_search_param, - common_param, - obstacle_stop_planner_param, - obstacle_stop_planner_acc_param, - vehicle_info_param, - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - # obstacle cruise planner - with open(LaunchConfiguration("obstacle_cruise_planner_param_path").perform(context), "r") as f: - obstacle_cruise_planner_param = yaml.safe_load(f)["/**"]["ros__parameters"] - obstacle_cruise_planner_component = ComposableNode( - package="obstacle_cruise_planner", - plugin="motion_planning::ObstacleCruisePlannerNode", - name="obstacle_cruise_planner", - namespace="", - remappings=[ - ("~/input/trajectory", "obstacle_velocity_limiter/trajectory"), - ("~/input/odometry", "/localization/kinematic_state"), - ("~/input/acceleration", "/localization/acceleration"), - ("~/input/objects", "/perception/object_recognition/objects"), - ("~/output/trajectory", "/planning/scenario_planning/lane_driving/trajectory"), - ("~/output/velocity_limit", "/planning/scenario_planning/max_velocity_candidates"), - ("~/output/clear_velocity_limit", "/planning/scenario_planning/clear_velocity_limit"), - ("~/output/stop_reasons", "/planning/scenario_planning/status/stop_reasons"), - ], - parameters=[ - nearest_search_param, - common_param, - obstacle_cruise_planner_param, - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - obstacle_cruise_planner_relay_component = ComposableNode( - package="topic_tools", - plugin="topic_tools::RelayNode", - name="obstacle_cruise_planner_relay", - namespace="", - parameters=[ - {"input_topic": "obstacle_velocity_limiter/trajectory"}, - {"output_topic": "/planning/scenario_planning/lane_driving/trajectory"}, - {"type": "autoware_auto_planning_msgs/msg/Trajectory"}, - ], - extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ) - - container = ComposableNodeContainer( - name="motion_planning_container", - namespace="", - package="rclcpp_components", - executable=LaunchConfiguration("container_executable"), - composable_node_descriptions=[ - obstacle_velocity_limiter_component, - ], - ) - - obstacle_stop_planner_loader = LoadComposableNodes( - composable_node_descriptions=[obstacle_stop_planner_component], - target_container=container, - condition=LaunchConfigurationEquals("cruise_planner_type", "obstacle_stop_planner"), - ) - - obstacle_cruise_planner_loader = LoadComposableNodes( - composable_node_descriptions=[obstacle_cruise_planner_component], - target_container=container, - condition=LaunchConfigurationEquals("cruise_planner_type", "obstacle_cruise_planner"), - ) - - obstacle_cruise_planner_relay_loader = LoadComposableNodes( - composable_node_descriptions=[obstacle_cruise_planner_relay_component], - target_container=container, - condition=LaunchConfigurationEquals("cruise_planner_type", "none"), - ) - - smoother_loader = LoadComposableNodes( - composable_node_descriptions=[elastic_band_smoother_component], - target_container=container, - condition=LaunchConfigurationEquals("path_smoother_type", "elastic_band"), - ) - - obstacle_avoidance_planner_loader = LoadComposableNodes( - composable_node_descriptions=[obstacle_avoidance_planner_component], - target_container=container, - condition=LaunchConfigurationEquals("path_planner_type", "obstacle_avoidance_planner"), - ) - - path_sampler_loader = LoadComposableNodes( - composable_node_descriptions=[path_sampler_component], - target_container=container, - condition=LaunchConfigurationEquals("path_planner_type", "path_sampler"), - ) - - surround_obstacle_checker_loader = LoadComposableNodes( - composable_node_descriptions=[surround_obstacle_checker_component], - target_container=container, - condition=IfCondition(LaunchConfiguration("use_surround_obstacle_check")), - ) - - glog_component = ComposableNode( - package="glog_component", - plugin="GlogComponent", - name="glog_component", - ) - glog_component_loader = LoadComposableNodes( - composable_node_descriptions=[glog_component], - target_container=container, - ) - - group = GroupAction( - [ - container, - smoother_loader, - obstacle_avoidance_planner_loader, - path_sampler_loader, - obstacle_stop_planner_loader, - obstacle_cruise_planner_loader, - obstacle_cruise_planner_relay_loader, - surround_obstacle_checker_loader, - glog_component_loader, - ] - ) - return [group] - - -def generate_launch_description(): - launch_arguments = [] - - def add_launch_arg(name: str, default_value=None, description=None): - launch_arguments.append( - DeclareLaunchArgument(name, default_value=default_value, description=description) - ) - - # vehicle parameter - add_launch_arg("vehicle_param_file") - - # interface parameter - add_launch_arg( - "input_path_topic", - "/planning/scenario_planning/lane_driving/behavior_planning/path", - "input path topic of obstacle_avoidance_planner", - ) - - # package parameter - add_launch_arg("use_surround_obstacle_check") # launch surround_obstacle_checker or not - add_launch_arg( - "cruise_planner_type" - ) # select from "obstacle_stop_planner", "obstacle_cruise_planner", "none" - add_launch_arg( - "path_planner_type", "obstacle_avoidance_planner" - ) # select from "obstacle_avoidance_planner", "path_sampler" - add_launch_arg("path_smoother_type", "elastic_band") # select from "elastic_band", "none" - - add_launch_arg("use_intra_process", "false", "use ROS 2 component container communication") - add_launch_arg("use_multithread", "false", "use multithread") - - set_container_executable = SetLaunchConfiguration( - "container_executable", - "component_container", - condition=UnlessCondition(LaunchConfiguration("use_multithread")), - ) - set_container_mt_executable = SetLaunchConfiguration( - "container_executable", - "component_container_mt", - condition=IfCondition(LaunchConfiguration("use_multithread")), - ) - - return launch.LaunchDescription( - launch_arguments - + [ - set_container_executable, - set_container_mt_executable, - ] - + [OpaqueFunction(function=launch_setup)] - ) diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml index 3f7650486e69d..45fa85f0d77fb 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml @@ -1,42 +1,204 @@ - - - + + - - + + + - + - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - + - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 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 d06dfa214c275..8c015892d06b5 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 @@ -26,7 +26,7 @@ - + diff --git a/launch/tier4_planning_launch/package.xml b/launch/tier4_planning_launch/package.xml index 5988d34cded88..8f9d8f5ea079d 100644 --- a/launch/tier4_planning_launch/package.xml +++ b/launch/tier4_planning_launch/package.xml @@ -67,6 +67,7 @@ obstacle_cruise_planner obstacle_stop_planner planning_evaluator + planning_topic_converter planning_validator scenario_selector surround_obstacle_checker From c7aa19eefebed079c9e96ab1d2c187a25ece0c35 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Mon, 6 Nov 2023 18:33:51 +0900 Subject: [PATCH 126/202] feat(localization): enable logging_level_configure (#5487) * feat(localization): enable logging_level_configure * style(pre-commit): autofix * update logger config Signed-off-by: kminoda * fix pre-commit Signed-off-by: kminoda * add tier4_autoware_utils in dependency Signed-off-by: kminoda * add tier4_autoware_utils in dependency Signed-off-by: kminoda --------- Signed-off-by: kminoda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../config/logger_config.yaml | 24 +++++++++++++++++++ .../include/ekf_localizer/ekf_localizer.hpp | 4 ++++ .../ekf_localizer/src/ekf_localizer.cpp | 2 ++ .../gyro_odometer/gyro_odometer_core.hpp | 2 ++ .../gyro_odometer/src/gyro_odometer_core.cpp | 1 + .../localization_error_monitor/node.hpp | 6 +++++ .../localization_error_monitor/package.xml | 1 + .../localization_error_monitor/src/node.cpp | 2 ++ .../ndt_scan_matcher_core.hpp | 2 ++ .../src/ndt_scan_matcher_core.cpp | 2 ++ localization/pose_initializer/package.xml | 1 + .../pose_initializer_core.cpp | 1 + .../pose_initializer_core.hpp | 2 ++ 13 files changed, 50 insertions(+) diff --git a/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml b/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml index 97c3104242026..9fb84b8efc1d4 100644 --- a/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml +++ b/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml @@ -1,5 +1,29 @@ # logger_config.yaml +# ============================================================ +# localization +# ============================================================ + +ndt_scan_matcher: + - node_name: /localization/pose_estimator/ndt_scan_matcher + logger_name: localization.pose_estimator.ndt_scan_matcher + +gyro_odometer: + - node_name: /localization/twist_estimator/gyro_odometer + logger_name: localization.twist_estimator.gyro_odometer + +pose_initializer: + - node_name: /localization/util/pose_initializer_node + logger_name: localization.util.pose_initializer_node + +ekf_localizer: + - node_name: /localization/pose_twist_fusion_filter/ekf_localizer + logger_name: localization.pose_twist_fusion_filter.ekf_localizer + +localization_error_monitor: + - node_name: /localization/localization_error_monitor + logger_name: localization.localization_error_monitor + # ============================================================ # planning # ============================================================ diff --git a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp index 719185da4306a..e51a4b6d8124f 100644 --- a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp @@ -23,6 +23,7 @@ #include #include #include +#include #include #include @@ -166,6 +167,9 @@ class EKFLocalizer : public rclcpp::Node //!< @brief tf broadcaster std::shared_ptr tf_br_; + //!< @brief logger configure module + std::unique_ptr logger_configure_; + //!< @brief extended kalman filter instance. TimeDelayKalmanFilter ekf_; Simple1DFilter z_filter_; diff --git a/localization/ekf_localizer/src/ekf_localizer.cpp b/localization/ekf_localizer/src/ekf_localizer.cpp index c39e38c8d438d..34ae32dccff44 100644 --- a/localization/ekf_localizer/src/ekf_localizer.cpp +++ b/localization/ekf_localizer/src/ekf_localizer.cpp @@ -104,6 +104,8 @@ EKFLocalizer::EKFLocalizer(const std::string & node_name, const rclcpp::NodeOpti tf_br_ = std::make_shared( std::shared_ptr(this, [](auto) {})); + logger_configure_ = std::make_unique(this); + initEKF(); z_filter_.set_proc_dev(1.0); diff --git a/localization/gyro_odometer/include/gyro_odometer/gyro_odometer_core.hpp b/localization/gyro_odometer/include/gyro_odometer/gyro_odometer_core.hpp index 97d4a02472f2d..3a6358e62c21a 100644 --- a/localization/gyro_odometer/include/gyro_odometer/gyro_odometer_core.hpp +++ b/localization/gyro_odometer/include/gyro_odometer/gyro_odometer_core.hpp @@ -15,6 +15,7 @@ #ifndef GYRO_ODOMETER__GYRO_ODOMETER_CORE_HPP_ #define GYRO_ODOMETER__GYRO_ODOMETER_CORE_HPP_ +#include "tier4_autoware_utils/ros/logger_level_configure.hpp" #include "tier4_autoware_utils/ros/msg_covariance.hpp" #include "tier4_autoware_utils/ros/transform_listener.hpp" @@ -63,6 +64,7 @@ class GyroOdometer : public rclcpp::Node twist_with_covariance_pub_; std::shared_ptr transform_listener_; + std::unique_ptr logger_configure_; std::string output_frame_; double message_timeout_sec_; diff --git a/localization/gyro_odometer/src/gyro_odometer_core.cpp b/localization/gyro_odometer/src/gyro_odometer_core.cpp index 2412fd5d57602..c14c48ffb2046 100644 --- a/localization/gyro_odometer/src/gyro_odometer_core.cpp +++ b/localization/gyro_odometer/src/gyro_odometer_core.cpp @@ -108,6 +108,7 @@ GyroOdometer::GyroOdometer(const rclcpp::NodeOptions & options) imu_arrived_(false) { transform_listener_ = std::make_shared(this); + logger_configure_ = std::make_unique(this); vehicle_twist_sub_ = create_subscription( "vehicle/twist_with_covariance", rclcpp::QoS{100}, diff --git a/localization/localization_error_monitor/include/localization_error_monitor/node.hpp b/localization/localization_error_monitor/include/localization_error_monitor/node.hpp index 7bdc87d5d47f2..296b278004333 100644 --- a/localization/localization_error_monitor/include/localization_error_monitor/node.hpp +++ b/localization/localization_error_monitor/include/localization_error_monitor/node.hpp @@ -17,11 +17,14 @@ #include #include +#include #include #include #include +#include + struct Ellipse { double long_radius; @@ -39,6 +42,9 @@ class LocalizationErrorMonitor : public rclcpp::Node rclcpp::Publisher::SharedPtr diag_pub_; rclcpp::TimerBase::SharedPtr timer_; + + std::unique_ptr logger_configure_; + double scale_; double error_ellipse_size_; double warn_ellipse_size_; diff --git a/localization/localization_error_monitor/package.xml b/localization/localization_error_monitor/package.xml index 4cc5599fd81a9..266ae6c848834 100644 --- a/localization/localization_error_monitor/package.xml +++ b/localization/localization_error_monitor/package.xml @@ -20,6 +20,7 @@ nav_msgs tf2 tf2_geometry_msgs + tier4_autoware_utils visualization_msgs ament_cmake_ros diff --git a/localization/localization_error_monitor/src/node.cpp b/localization/localization_error_monitor/src/node.cpp index 43795d4036d42..f47372a0158b2 100644 --- a/localization/localization_error_monitor/src/node.cpp +++ b/localization/localization_error_monitor/src/node.cpp @@ -53,6 +53,8 @@ LocalizationErrorMonitor::LocalizationErrorMonitor() : Node("localization_error_ this->create_publisher("debug/ellipse_marker", durable_qos); diag_pub_ = this->create_publisher("/diagnostics", 10); + + logger_configure_ = std::make_unique(this); } visualization_msgs::msg::Marker LocalizationErrorMonitor::createEllipseMarker( diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp index e5f46b5022b51..09fc08a97a3ac 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp @@ -22,6 +22,7 @@ #include "ndt_scan_matcher/map_update_module.hpp" #include +#include #include #include @@ -204,6 +205,7 @@ class NDTScanMatcher : public rclcpp::Node std::shared_ptr tf2_listener_module_; std::unique_ptr map_module_; std::unique_ptr map_update_module_; + std::unique_ptr logger_configure_; // cspell: ignore degrounded bool estimate_scores_for_degrounded_scan_; diff --git a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp index b38e3f0826184..ac30b09df1c8e 100644 --- a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp +++ b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp @@ -246,6 +246,8 @@ NDTScanMatcher::NDTScanMatcher() } else { map_module_ = std::make_unique(this, &ndt_ptr_mtx_, ndt_ptr_, main_callback_group); } + + logger_configure_ = std::make_unique(this); } void NDTScanMatcher::timer_diagnostic() diff --git a/localization/pose_initializer/package.xml b/localization/pose_initializer/package.xml index f8333d89fa8ac..1a1a8e48b7e3b 100644 --- a/localization/pose_initializer/package.xml +++ b/localization/pose_initializer/package.xml @@ -21,6 +21,7 @@ motion_utils rclcpp std_srvs + tier4_autoware_utils tier4_localization_msgs ament_cmake_cppcheck diff --git a/localization/pose_initializer/src/pose_initializer/pose_initializer_core.cpp b/localization/pose_initializer/src/pose_initializer/pose_initializer_core.cpp index 6614cbf56008e..4585414c20b0d 100644 --- a/localization/pose_initializer/src/pose_initializer/pose_initializer_core.cpp +++ b/localization/pose_initializer/src/pose_initializer/pose_initializer_core.cpp @@ -54,6 +54,7 @@ PoseInitializer::PoseInitializer() : Node("pose_initializer") stop_check_duration_ = declare_parameter("stop_check_duration"); stop_check_ = std::make_unique(this, stop_check_duration_ + 1.0); } + logger_configure_ = std::make_unique(this); change_state(State::Message::UNINITIALIZED); } diff --git a/localization/pose_initializer/src/pose_initializer/pose_initializer_core.hpp b/localization/pose_initializer/src/pose_initializer/pose_initializer_core.hpp index fa04146cf529e..014c8e9bf6e04 100644 --- a/localization/pose_initializer/src/pose_initializer/pose_initializer_core.hpp +++ b/localization/pose_initializer/src/pose_initializer/pose_initializer_core.hpp @@ -18,6 +18,7 @@ #include #include #include +#include #include @@ -55,6 +56,7 @@ class PoseInitializer : public rclcpp::Node std::unique_ptr stop_check_; std::unique_ptr ekf_localization_trigger_; std::unique_ptr ndt_localization_trigger_; + std::unique_ptr logger_configure_; double stop_check_duration_; void change_state(State::Message::_state_type state); void on_initialize( From b73330ba6060c3791d33ac81439a0022bd171c5e Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Mon, 6 Nov 2023 19:11:40 +0900 Subject: [PATCH 127/202] refactor(ekf_localizer): isolate ekf into independent module (#5424) * refactor(ekf_localizer): use struct for diag info Signed-off-by: kminoda * fix Signed-off-by: kminoda * style(pre-commit): autofix * update Signed-off-by: kminoda * style(pre-commit): autofix * move diag_info to ekf_localizer.hpp Signed-off-by: kminoda * remove diag.hpp Signed-off-by: kminoda * refactor(ekf_localizer): remote current_ekf_pose and so on Signed-off-by: kminoda * fix(ekf_localizer): remove unnecessary publishers Signed-off-by: kminoda * still build failes due to one current_ekf_twist_ Signed-off-by: kminoda * now works Signed-off-by: kminoda * style(pre-commit): autofix * refactor(ekf_localizer): isolate ekf into module Signed-off-by: kminoda * style(pre-commit): autofix * update Signed-off-by: kminoda * style(pre-commit): autofix * remove commentou Signed-off-by: kminoda * minor fix Signed-off-by: kminoda * remove unnecessary headers Signed-off-by: kminoda * update print logs Signed-off-by: kminoda * include memory Signed-off-by: kminoda * ekf_ to kalman_filter_ Signed-off-by: kminoda * style(pre-commit): autofix * remove duplicated struct declaration Signed-off-by: kminoda * reflected comments Signed-off-by: kminoda * style(pre-commit): autofix --------- Signed-off-by: kminoda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- localization/ekf_localizer/CMakeLists.txt | 1 + .../include/ekf_localizer/ekf_localizer.hpp | 75 +--- .../include/ekf_localizer/ekf_module.hpp | 97 +++++ .../ekf_localizer/src/ekf_localizer.cpp | 354 ++---------------- localization/ekf_localizer/src/ekf_module.cpp | 317 ++++++++++++++++ 5 files changed, 454 insertions(+), 390 deletions(-) create mode 100644 localization/ekf_localizer/include/ekf_localizer/ekf_module.hpp create mode 100644 localization/ekf_localizer/src/ekf_module.cpp diff --git a/localization/ekf_localizer/CMakeLists.txt b/localization/ekf_localizer/CMakeLists.txt index 05c91bff13867..45d420bafff10 100644 --- a/localization/ekf_localizer/CMakeLists.txt +++ b/localization/ekf_localizer/CMakeLists.txt @@ -21,6 +21,7 @@ ament_auto_add_library(ekf_localizer_lib SHARED src/measurement.cpp src/state_transition.cpp src/warning_message.cpp + src/ekf_module.cpp ) target_link_libraries(ekf_localizer_lib Eigen3::Eigen) diff --git a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp index e51a4b6d8124f..e2ffff2195645 100644 --- a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp @@ -16,11 +16,10 @@ #define EKF_LOCALIZER__EKF_LOCALIZER_HPP_ #include "ekf_localizer/aged_object_queue.hpp" +#include "ekf_localizer/ekf_module.hpp" #include "ekf_localizer/hyper_parameters.hpp" #include "ekf_localizer/warning.hpp" -#include -#include #include #include #include @@ -50,28 +49,6 @@ #include #include -struct EKFDiagnosticInfo -{ - EKFDiagnosticInfo() - : no_update_count(0), - queue_size(0), - is_passed_delay_gate(true), - delay_time(0), - delay_time_threshold(0), - is_passed_mahalanobis_gate(true), - mahalanobis_distance(0) - { - } - - size_t no_update_count; - size_t queue_size; - bool is_passed_delay_gate; - double delay_time; - double delay_time_threshold; - bool is_passed_mahalanobis_gate; - double mahalanobis_distance; -}; - class Simple1DFilter { public: @@ -128,7 +105,7 @@ class EKFLocalizer : public rclcpp::Node EKFLocalizer(const std::string & node_name, const rclcpp::NodeOptions & options); private: - const Warning warning_; + const std::shared_ptr warning_; //!< @brief ekf estimated pose publisher rclcpp::Publisher::SharedPtr pub_pose_; @@ -171,7 +148,7 @@ class EKFLocalizer : public rclcpp::Node std::unique_ptr logger_configure_; //!< @brief extended kalman filter instance. - TimeDelayKalmanFilter ekf_; + std::unique_ptr ekf_module_; Simple1DFilter z_filter_; Simple1DFilter roll_filter_; Simple1DFilter pitch_filter_; @@ -181,10 +158,6 @@ class EKFLocalizer : public rclcpp::Node double ekf_rate_; double ekf_dt_; - /* parameters */ - - int dim_x_; //!< @brief dimension of EKF state - /* process noise variance for discrete model */ double proc_cov_yaw_d_; //!< @brief discrete yaw process noise double proc_cov_yaw_bias_d_; //!< @brief discrete yaw bias process noise @@ -224,33 +197,11 @@ class EKFLocalizer : public rclcpp::Node */ void callbackInitialPose(geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg); - /** - * @brief initialization of EKF - */ - void initEKF(); - /** * @brief update predict frequency */ void updatePredictFrequency(); - /** - * @brief compute EKF prediction - */ - void predictKinematicsModel(); - - /** - * @brief compute EKF update with pose measurement - * @param pose measurement value - */ - bool measurementUpdatePose(const geometry_msgs::msg::PoseWithCovarianceStamped & pose); - - /** - * @brief compute EKF update with pose measurement - * @param twist measurement value - */ - bool measurementUpdateTwist(const geometry_msgs::msg::TwistWithCovarianceStamped & twist); - /** * @brief get transform from frame_id */ @@ -258,21 +209,6 @@ class EKFLocalizer : public rclcpp::Node std::string parent_frame, std::string child_frame, geometry_msgs::msg::TransformStamped & transform); - /** - * @brief set current EKF estimation result to current_ekf_pose_ & current_ekf_twist_ - */ - void setCurrentResult(); - - /** - * @brief get current ekf pose - */ - geometry_msgs::msg::PoseStamped getCurrentEKFPose(bool get_biased_yaw) const; - - /** - * @brief get current ekf twist - */ - geometry_msgs::msg::TwistStamped getCurrentEKFTwist() const; - /** * @brief publish current EKF estimation result */ @@ -286,11 +222,6 @@ class EKFLocalizer : public rclcpp::Node */ void publishDiagnostics(); - /** - * @brief for debug - */ - void showCurrentX(); - /** * @brief update simple1DFilter */ diff --git a/localization/ekf_localizer/include/ekf_localizer/ekf_module.hpp b/localization/ekf_localizer/include/ekf_localizer/ekf_module.hpp new file mode 100644 index 0000000000000..873060c75fcfc --- /dev/null +++ b/localization/ekf_localizer/include/ekf_localizer/ekf_module.hpp @@ -0,0 +1,97 @@ +// Copyright 2018-2019 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef EKF_LOCALIZER__EKF_MODULE_HPP_ +#define EKF_LOCALIZER__EKF_MODULE_HPP_ + +#include "ekf_localizer/hyper_parameters.hpp" +#include "ekf_localizer/state_index.hpp" +#include "ekf_localizer/warning.hpp" + +#include +#include +#include + +#include +#include +#include +#include +#include + +#include + +struct EKFDiagnosticInfo +{ + EKFDiagnosticInfo() + : no_update_count(0), + queue_size(0), + is_passed_delay_gate(true), + delay_time(0), + delay_time_threshold(0), + is_passed_mahalanobis_gate(true), + mahalanobis_distance(0) + { + } + + size_t no_update_count; + size_t queue_size; + bool is_passed_delay_gate; + double delay_time; + double delay_time_threshold; + bool is_passed_mahalanobis_gate; + double mahalanobis_distance; +}; + +class EKFModule +{ +private: + using PoseWithCovariance = geometry_msgs::msg::PoseWithCovarianceStamped; + using TwistWithCovariance = geometry_msgs::msg::TwistWithCovarianceStamped; + using Pose = geometry_msgs::msg::PoseStamped; + using Twist = geometry_msgs::msg::TwistStamped; + +public: + EKFModule(std::shared_ptr warning, const HyperParameters params); + + void initialize( + const PoseWithCovariance & initial_pose, + const geometry_msgs::msg::TransformStamped & transform); + + geometry_msgs::msg::PoseStamped getCurrentPose( + const rclcpp::Time & current_time, const double z, const double roll, const double pitch, + bool get_biased_yaw) const; + geometry_msgs::msg::TwistStamped getCurrentTwist(const rclcpp::Time & current_time) const; + double getYawBias() const; + std::array getCurrentPoseCovariance() const; + std::array getCurrentTwistCovariance() const; + + void predictWithDelay(const double dt); + bool measurementUpdatePose( + const PoseWithCovariance & pose, const double dt, const rclcpp::Time & t_curr, + EKFDiagnosticInfo & pose_diag_info); + bool measurementUpdateTwist( + const TwistWithCovariance & twist, const double dt, const rclcpp::Time & t_curr, + EKFDiagnosticInfo & twist_diag_info); + geometry_msgs::msg::PoseWithCovarianceStamped compensatePoseWithZDelay( + const PoseWithCovariance & pose, const double delay_time); + +private: + TimeDelayKalmanFilter kalman_filter_; + + std::shared_ptr warning_; + const int dim_x_; + const HyperParameters params_; +}; + +#endif // EKF_LOCALIZER__EKF_MODULE_HPP_ diff --git a/localization/ekf_localizer/src/ekf_localizer.cpp b/localization/ekf_localizer/src/ekf_localizer.cpp index 34ae32dccff44..5dd78a00f2fbd 100644 --- a/localization/ekf_localizer/src/ekf_localizer.cpp +++ b/localization/ekf_localizer/src/ekf_localizer.cpp @@ -14,16 +14,8 @@ #include "ekf_localizer/ekf_localizer.hpp" -#include "ekf_localizer/covariance.hpp" #include "ekf_localizer/diagnostics.hpp" -#include "ekf_localizer/mahalanobis.hpp" -#include "ekf_localizer/matrix_types.hpp" -#include "ekf_localizer/measurement.hpp" -#include "ekf_localizer/numeric.hpp" -#include "ekf_localizer/state_index.hpp" -#include "ekf_localizer/state_transition.hpp" #include "ekf_localizer/string.hpp" -#include "ekf_localizer/warning.hpp" #include "ekf_localizer/warning_message.hpp" #include @@ -44,20 +36,16 @@ // clang-format off #define PRINT_MAT(X) std::cout << #X << ":\n" << X << std::endl << std::endl #define DEBUG_INFO(...) {if (params_.show_debug_info) {RCLCPP_INFO(__VA_ARGS__);}} -#define DEBUG_PRINT_MAT(X) {\ - if (params_.show_debug_info) {std::cout << #X << ": " << X << std::endl;}\ -} // clang-format on using std::placeholders::_1; EKFLocalizer::EKFLocalizer(const std::string & node_name, const rclcpp::NodeOptions & node_options) : rclcpp::Node(node_name, node_options), - warning_(this), + warning_(std::make_shared(this)), params_(this), ekf_rate_(params_.ekf_rate), ekf_dt_(params_.ekf_dt), - dim_x_(6 /* x, y, yaw, yaw_bias, vx, wz */), pose_queue_(params_.pose_smoothing_steps), twist_queue_(params_.twist_smoothing_steps) { @@ -104,10 +92,9 @@ EKFLocalizer::EKFLocalizer(const std::string & node_name, const rclcpp::NodeOpti tf_br_ = std::make_shared( std::shared_ptr(this, [](auto) {})); + ekf_module_ = std::make_unique(warning_, params_); logger_configure_ = std::make_unique(this); - initEKF(); - z_filter_.set_proc_dev(1.0); roll_filter_.set_proc_dev(0.01); pitch_filter_.set_proc_dev(0.01); @@ -120,7 +107,7 @@ void EKFLocalizer::updatePredictFrequency() { if (last_predict_time_) { if (get_clock()->now() < *last_predict_time_) { - warning_.warn("Detected jump back in time"); + warning_->warn("Detected jump back in time"); } else { ekf_rate_ = 1.0 / (get_clock()->now() - *last_predict_time_).seconds(); DEBUG_INFO(get_logger(), "[EKF] update ekf_rate_ to %f hz", ekf_rate_); @@ -141,7 +128,7 @@ void EKFLocalizer::updatePredictFrequency() void EKFLocalizer::timerCallback() { if (!is_activated_) { - warning_.warnThrottle( + warning_->warnThrottle( "The node is not activated. Provide initial pose to pose_initializer", 2000); publishDiagnostics(); return; @@ -155,29 +142,11 @@ void EKFLocalizer::timerCallback() /* predict model in EKF */ stop_watch_.tic(); DEBUG_INFO(get_logger(), "------------------------- start prediction -------------------------"); - - const Eigen::MatrixXd X_curr = ekf_.getLatestX(); - DEBUG_PRINT_MAT(X_curr.transpose()); - - const Eigen::MatrixXd P_curr = ekf_.getLatestP(); - - const double dt = ekf_dt_; - - const Vector6d X_next = predictNextState(X_curr, dt); - const Matrix6d A = createStateTransitionMatrix(X_curr, dt); - const Matrix6d Q = processNoiseCovariance(proc_cov_yaw_d_, proc_cov_vx_d_, proc_cov_wz_d_); - - ekf_.predictWithDelay(X_next, A, Q); - - // debug - const Eigen::MatrixXd X_result = ekf_.getLatestX(); - DEBUG_PRINT_MAT(X_result.transpose()); - DEBUG_PRINT_MAT((X_result - X_curr).transpose()); + ekf_module_->predictWithDelay(ekf_dt_); DEBUG_INFO(get_logger(), "[EKF] predictKinematicsModel calc time = %f [ms]", stop_watch_.toc()); DEBUG_INFO(get_logger(), "------------------------- end prediction -------------------------\n"); /* pose measurement update */ - pose_diag_info_.queue_size = pose_queue_.size(); pose_diag_info_.is_passed_delay_gate = true; pose_diag_info_.delay_time = 0.0; @@ -192,12 +161,19 @@ void EKFLocalizer::timerCallback() stop_watch_.tic(); // save the initial size because the queue size can change in the loop + const auto t_curr = this->now(); const size_t n = pose_queue_.size(); for (size_t i = 0; i < n; ++i) { const auto pose = pose_queue_.pop_increment_age(); - bool is_updated = measurementUpdatePose(*pose); + bool is_updated = ekf_module_->measurementUpdatePose(*pose, ekf_dt_, t_curr, pose_diag_info_); if (is_updated) { pose_is_updated = true; + + // Update Simple 1D filter with considering change of z value due to measurement pose delay + const double delay_time = + (t_curr - pose->header.stamp).seconds() + params_.pose_additional_delay; + const auto pose_with_z_delay = ekf_module_->compensatePoseWithZDelay(*pose, delay_time); + updateSimple1DFilters(pose_with_z_delay, params_.pose_smoothing_steps); } } DEBUG_INFO(get_logger(), "[EKF] measurementUpdatePose calc time = %f [ms]", stop_watch_.toc()); @@ -206,7 +182,6 @@ void EKFLocalizer::timerCallback() pose_diag_info_.no_update_count = pose_is_updated ? 0 : (pose_diag_info_.no_update_count + 1); /* twist measurement update */ - twist_diag_info_.queue_size = twist_queue_.size(); twist_diag_info_.is_passed_delay_gate = true; twist_diag_info_.delay_time = 0.0; @@ -221,10 +196,12 @@ void EKFLocalizer::timerCallback() stop_watch_.tic(); // save the initial size because the queue size can change in the loop + const auto t_curr = this->now(); const size_t n = twist_queue_.size(); for (size_t i = 0; i < n; ++i) { const auto twist = twist_queue_.pop_increment_age(); - bool is_updated = measurementUpdateTwist(*twist); + bool is_updated = + ekf_module_->measurementUpdateTwist(*twist, ekf_dt_, t_curr, twist_diag_info_); if (is_updated) { twist_is_updated = true; } @@ -234,61 +211,19 @@ void EKFLocalizer::timerCallback() } twist_diag_info_.no_update_count = twist_is_updated ? 0 : (twist_diag_info_.no_update_count + 1); - const geometry_msgs::msg::PoseStamped current_ekf_pose = getCurrentEKFPose(false); - const geometry_msgs::msg::PoseStamped current_biased_ekf_pose = getCurrentEKFPose(true); - const geometry_msgs::msg::TwistStamped current_ekf_twist = getCurrentEKFTwist(); - - /* publish ekf result */ - publishEstimateResult(current_ekf_pose, current_biased_ekf_pose, current_ekf_twist); - publishDiagnostics(); -} - -geometry_msgs::msg::PoseStamped EKFLocalizer::getCurrentEKFPose(bool get_biased_yaw) const -{ - const double x = ekf_.getXelement(IDX::X); - const double y = ekf_.getXelement(IDX::Y); const double z = z_filter_.get_x(); - - const double biased_yaw = ekf_.getXelement(IDX::YAW); - const double yaw_bias = ekf_.getXelement(IDX::YAWB); - const double roll = roll_filter_.get_x(); const double pitch = pitch_filter_.get_x(); - const double yaw = biased_yaw + yaw_bias; - - geometry_msgs::msg::PoseStamped current_ekf_pose; - current_ekf_pose.header.frame_id = params_.pose_frame_id; - current_ekf_pose.header.stamp = this->now(); - current_ekf_pose.pose.position = tier4_autoware_utils::createPoint(x, y, z); - if (get_biased_yaw) { - current_ekf_pose.pose.orientation = - tier4_autoware_utils::createQuaternionFromRPY(roll, pitch, biased_yaw); - } else { - current_ekf_pose.pose.orientation = - tier4_autoware_utils::createQuaternionFromRPY(roll, pitch, yaw); - } - return current_ekf_pose; -} + const geometry_msgs::msg::PoseStamped current_ekf_pose = + ekf_module_->getCurrentPose(this->now(), z, roll, pitch, false); + const geometry_msgs::msg::PoseStamped current_biased_ekf_pose = + ekf_module_->getCurrentPose(this->now(), z, roll, pitch, true); + const geometry_msgs::msg::TwistStamped current_ekf_twist = + ekf_module_->getCurrentTwist(this->now()); -geometry_msgs::msg::TwistStamped EKFLocalizer::getCurrentEKFTwist() const -{ - const double vx = ekf_.getXelement(IDX::VX); - const double wz = ekf_.getXelement(IDX::WZ); - - geometry_msgs::msg::TwistStamped current_ekf_twist; - current_ekf_twist.header.frame_id = "base_link"; - current_ekf_twist.header.stamp = this->now(); - current_ekf_twist.twist.linear.x = vx; - current_ekf_twist.twist.angular.z = wz; - return current_ekf_twist; -} - -void EKFLocalizer::showCurrentX() -{ - if (params_.show_debug_info) { - const Eigen::MatrixXd X = ekf_.getLatestX(); - DEBUG_PRINT_MAT(X.transpose()); - } + /* publish ekf result */ + publishEstimateResult(current_ekf_pose, current_biased_ekf_pose, current_ekf_twist); + publishDiagnostics(); } /* @@ -304,8 +239,13 @@ void EKFLocalizer::timerTFCallback() return; } + const double z = z_filter_.get_x(); + const double roll = roll_filter_.get_x(); + const double pitch = pitch_filter_.get_x(); + geometry_msgs::msg::TransformStamped transform_stamped; - transform_stamped = tier4_autoware_utils::pose2transform(getCurrentEKFPose(false), "base_link"); + transform_stamped = tier4_autoware_utils::pose2transform( + ekf_module_->getCurrentPose(this->now(), z, roll, pitch, false), "base_link"); transform_stamped.header.stamp = this->now(); tf_br_->sendTransform(transform_stamped); } @@ -329,7 +269,7 @@ bool EKFLocalizer::getTransformFromTF( transform = tf_buffer.lookupTransform(parent_frame, child_frame, tf2::TimePointZero); return true; } catch (tf2::TransformException & ex) { - warning_.warn(ex.what()); + warning_->warn(ex.what()); rclcpp::sleep_for(std::chrono::milliseconds(100)); } } @@ -348,33 +288,7 @@ void EKFLocalizer::callbackInitialPose( get_logger(), "[EKF] TF transform failed. parent = %s, child = %s", params_.pose_frame_id.c_str(), initialpose->header.frame_id.c_str()); } - - Eigen::MatrixXd X(dim_x_, 1); - Eigen::MatrixXd P = Eigen::MatrixXd::Zero(dim_x_, dim_x_); - - // TODO(mitsudome-r) need mutex - - X(IDX::X) = initialpose->pose.pose.position.x + transform.transform.translation.x; - X(IDX::Y) = initialpose->pose.pose.position.y + transform.transform.translation.y; - X(IDX::YAW) = - tf2::getYaw(initialpose->pose.pose.orientation) + tf2::getYaw(transform.transform.rotation); - X(IDX::YAWB) = 0.0; - X(IDX::VX) = 0.0; - X(IDX::WZ) = 0.0; - - using COV_IDX = tier4_autoware_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; - P(IDX::X, IDX::X) = initialpose->pose.covariance[COV_IDX::X_X]; - P(IDX::Y, IDX::Y) = initialpose->pose.covariance[COV_IDX::Y_Y]; - P(IDX::YAW, IDX::YAW) = initialpose->pose.covariance[COV_IDX::YAW_YAW]; - - if (params_.enable_yaw_bias_estimation) { - P(IDX::YAWB, IDX::YAWB) = 0.0001; - } - P(IDX::VX, IDX::VX) = 0.01; - P(IDX::WZ, IDX::WZ) = 0.01; - - ekf_.init(X, P, params_.extend_state_step); - + ekf_module_->initialize(*initialpose, transform); initSimple1DFilters(*initialpose); } @@ -405,200 +319,6 @@ void EKFLocalizer::callbackTwistWithCovariance( twist_queue_.push(msg); } -/* - * initEKF - */ -void EKFLocalizer::initEKF() -{ - Eigen::MatrixXd X = Eigen::MatrixXd::Zero(dim_x_, 1); - Eigen::MatrixXd P = Eigen::MatrixXd::Identity(dim_x_, dim_x_) * 1.0E15; // for x & y - P(IDX::YAW, IDX::YAW) = 50.0; // for yaw - if (params_.enable_yaw_bias_estimation) { - P(IDX::YAWB, IDX::YAWB) = 50.0; // for yaw bias - } - P(IDX::VX, IDX::VX) = 1000.0; // for vx - P(IDX::WZ, IDX::WZ) = 50.0; // for wz - - ekf_.init(X, P, params_.extend_state_step); -} - -/* - * measurementUpdatePose - */ -bool EKFLocalizer::measurementUpdatePose(const geometry_msgs::msg::PoseWithCovarianceStamped & pose) -{ - if (pose.header.frame_id != params_.pose_frame_id) { - warning_.warnThrottle( - fmt::format( - "pose frame_id is %s, but pose_frame is set as %s. They must be same.", - pose.header.frame_id.c_str(), params_.pose_frame_id.c_str()), - 2000); - } - const Eigen::MatrixXd X_curr = ekf_.getLatestX(); - DEBUG_PRINT_MAT(X_curr.transpose()); - - constexpr int dim_y = 3; // pos_x, pos_y, yaw, depending on Pose output - const rclcpp::Time t_curr = this->now(); - - /* Calculate delay step */ - double delay_time = (t_curr - pose.header.stamp).seconds() + params_.pose_additional_delay; - if (delay_time < 0.0) { - warning_.warnThrottle(poseDelayTimeWarningMessage(delay_time), 1000); - } - - delay_time = std::max(delay_time, 0.0); - - const int delay_step = std::roundf(delay_time / ekf_dt_); - - pose_diag_info_.delay_time = std::max(delay_time, pose_diag_info_.delay_time); - pose_diag_info_.delay_time_threshold = params_.extend_state_step * ekf_dt_; - if (delay_step >= params_.extend_state_step) { - pose_diag_info_.is_passed_delay_gate = false; - warning_.warnThrottle( - poseDelayStepWarningMessage(delay_time, params_.extend_state_step, ekf_dt_), 2000); - return false; - } - DEBUG_INFO(get_logger(), "delay_time: %f [s]", delay_time); - - /* Set yaw */ - double yaw = tf2::getYaw(pose.pose.pose.orientation); - const double ekf_yaw = ekf_.getXelement(delay_step * dim_x_ + IDX::YAW); - const double yaw_error = normalizeYaw(yaw - ekf_yaw); // normalize the error not to exceed 2 pi - yaw = yaw_error + ekf_yaw; - - /* Set measurement matrix */ - Eigen::MatrixXd y(dim_y, 1); - y << pose.pose.pose.position.x, pose.pose.pose.position.y, yaw; - - if (hasNan(y) || hasInf(y)) { - warning_.warn( - "[EKF] pose measurement matrix includes NaN of Inf. ignore update. check pose message."); - return false; - } - - /* Gate */ - const Eigen::Vector3d y_ekf( - ekf_.getXelement(delay_step * dim_x_ + IDX::X), ekf_.getXelement(delay_step * dim_x_ + IDX::Y), - ekf_yaw); - const Eigen::MatrixXd P_curr = ekf_.getLatestP(); - const Eigen::MatrixXd P_y = P_curr.block(0, 0, dim_y, dim_y); - - const double distance = mahalanobis(y_ekf, y, P_y); - pose_diag_info_.mahalanobis_distance = std::max(distance, pose_diag_info_.mahalanobis_distance); - if (distance > params_.pose_gate_dist) { - pose_diag_info_.is_passed_mahalanobis_gate = false; - warning_.warnThrottle(mahalanobisWarningMessage(distance, params_.pose_gate_dist), 2000); - warning_.warnThrottle("Ignore the measurement data.", 2000); - return false; - } - - DEBUG_PRINT_MAT(y.transpose()); - DEBUG_PRINT_MAT(y_ekf.transpose()); - DEBUG_PRINT_MAT((y - y_ekf).transpose()); - - const Eigen::Matrix C = poseMeasurementMatrix(); - const Eigen::Matrix3d R = - poseMeasurementCovariance(pose.pose.covariance, params_.pose_smoothing_steps); - - ekf_.updateWithDelay(y, C, R, delay_step); - - // Considering change of z value due to measurement pose delay - const auto rpy = tier4_autoware_utils::getRPY(pose.pose.pose.orientation); - const double dz_delay = ekf_.getXelement(IDX::VX) * delay_time * std::sin(-rpy.y); - geometry_msgs::msg::PoseWithCovarianceStamped pose_with_z_delay; - pose_with_z_delay = pose; - pose_with_z_delay.pose.pose.position.z += dz_delay; - - updateSimple1DFilters(pose_with_z_delay, params_.pose_smoothing_steps); - - // debug - const Eigen::MatrixXd X_result = ekf_.getLatestX(); - DEBUG_PRINT_MAT(X_result.transpose()); - DEBUG_PRINT_MAT((X_result - X_curr).transpose()); - - return true; -} - -/* - * measurementUpdateTwist - */ -bool EKFLocalizer::measurementUpdateTwist( - const geometry_msgs::msg::TwistWithCovarianceStamped & twist) -{ - if (twist.header.frame_id != "base_link") { - RCLCPP_WARN_THROTTLE( - get_logger(), *get_clock(), std::chrono::milliseconds(2000).count(), - "twist frame_id must be base_link"); - } - - const Eigen::MatrixXd X_curr = ekf_.getLatestX(); - DEBUG_PRINT_MAT(X_curr.transpose()); - - constexpr int dim_y = 2; // vx, wz - const rclcpp::Time t_curr = this->now(); - - /* Calculate delay step */ - double delay_time = (t_curr - twist.header.stamp).seconds() + params_.twist_additional_delay; - if (delay_time < 0.0) { - warning_.warnThrottle(twistDelayTimeWarningMessage(delay_time), 1000); - } - delay_time = std::max(delay_time, 0.0); - - const int delay_step = std::roundf(delay_time / ekf_dt_); - - twist_diag_info_.delay_time = std::max(delay_time, twist_diag_info_.delay_time); - twist_diag_info_.delay_time_threshold = params_.extend_state_step * ekf_dt_; - if (delay_step >= params_.extend_state_step) { - twist_diag_info_.is_passed_delay_gate = false; - warning_.warnThrottle( - twistDelayStepWarningMessage(delay_time, params_.extend_state_step, ekf_dt_), 2000); - return false; - } - DEBUG_INFO(get_logger(), "delay_time: %f [s]", delay_time); - - /* Set measurement matrix */ - Eigen::MatrixXd y(dim_y, 1); - y << twist.twist.twist.linear.x, twist.twist.twist.angular.z; - - if (hasNan(y) || hasInf(y)) { - warning_.warn( - "[EKF] twist measurement matrix includes NaN of Inf. ignore update. check twist message."); - return false; - } - - const Eigen::Vector2d y_ekf( - ekf_.getXelement(delay_step * dim_x_ + IDX::VX), - ekf_.getXelement(delay_step * dim_x_ + IDX::WZ)); - const Eigen::MatrixXd P_curr = ekf_.getLatestP(); - const Eigen::MatrixXd P_y = P_curr.block(4, 4, dim_y, dim_y); - - const double distance = mahalanobis(y_ekf, y, P_y); - twist_diag_info_.mahalanobis_distance = std::max(distance, twist_diag_info_.mahalanobis_distance); - if (distance > params_.twist_gate_dist) { - twist_diag_info_.is_passed_mahalanobis_gate = false; - warning_.warnThrottle(mahalanobisWarningMessage(distance, params_.twist_gate_dist), 2000); - warning_.warnThrottle("Ignore the measurement data.", 2000); - return false; - } - - DEBUG_PRINT_MAT(y.transpose()); - DEBUG_PRINT_MAT(y_ekf.transpose()); - DEBUG_PRINT_MAT((y - y_ekf).transpose()); - - const Eigen::Matrix C = twistMeasurementMatrix(); - const Eigen::Matrix2d R = - twistMeasurementCovariance(twist.twist.covariance, params_.twist_smoothing_steps); - - ekf_.updateWithDelay(y, C, R, delay_step); - - // debug - const Eigen::MatrixXd X_result = ekf_.getLatestX(); - DEBUG_PRINT_MAT(X_result.transpose()); - DEBUG_PRINT_MAT((X_result - X_curr).transpose()); - - return true; -} - /* * publishEstimateResult */ @@ -608,8 +328,6 @@ void EKFLocalizer::publishEstimateResult( const geometry_msgs::msg::TwistStamped & current_ekf_twist) { rclcpp::Time current_time = this->now(); - const Eigen::MatrixXd X = ekf_.getLatestX(); - const Eigen::MatrixXd P = ekf_.getLatestP(); /* publish latest pose */ pub_pose_->publish(current_ekf_pose); @@ -620,7 +338,7 @@ void EKFLocalizer::publishEstimateResult( pose_cov.header.stamp = current_time; pose_cov.header.frame_id = current_ekf_pose.header.frame_id; pose_cov.pose.pose = current_ekf_pose.pose; - pose_cov.pose.covariance = ekfCovarianceToPoseMessageCovariance(P); + pose_cov.pose.covariance = ekf_module_->getCurrentPoseCovariance(); pub_pose_cov_->publish(pose_cov); geometry_msgs::msg::PoseWithCovarianceStamped biased_pose_cov = pose_cov; @@ -635,13 +353,13 @@ void EKFLocalizer::publishEstimateResult( twist_cov.header.stamp = current_time; twist_cov.header.frame_id = current_ekf_twist.header.frame_id; twist_cov.twist.twist = current_ekf_twist.twist; - twist_cov.twist.covariance = ekfCovarianceToTwistMessageCovariance(P); + twist_cov.twist.covariance = ekf_module_->getCurrentTwistCovariance(); pub_twist_cov_->publish(twist_cov); /* publish yaw bias */ tier4_debug_msgs::msg::Float64Stamped yawb; yawb.stamp = current_time; - yawb.data = X(IDX::YAWB); + yawb.data = ekf_module_->getYawBias(); pub_yaw_bias_->publish(yawb); /* publish latest odometry */ diff --git a/localization/ekf_localizer/src/ekf_module.cpp b/localization/ekf_localizer/src/ekf_module.cpp new file mode 100644 index 0000000000000..0a5e3c98c96c8 --- /dev/null +++ b/localization/ekf_localizer/src/ekf_module.cpp @@ -0,0 +1,317 @@ +// Copyright 2018-2019 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "ekf_localizer/ekf_module.hpp" + +#include "ekf_localizer/covariance.hpp" +#include "ekf_localizer/mahalanobis.hpp" +#include "ekf_localizer/matrix_types.hpp" +#include "ekf_localizer/measurement.hpp" +#include "ekf_localizer/numeric.hpp" +#include "ekf_localizer/state_transition.hpp" +#include "ekf_localizer/warning_message.hpp" + +#include +#include + +#include +#include +#include + +// clang-format off +#define DEBUG_PRINT_MAT(X) {\ + if (params_.show_debug_info) {std::cout << #X << ": " << X << std::endl;}\ +} +// clang-format on + +EKFModule::EKFModule(std::shared_ptr warning, const HyperParameters params) +: warning_(std::move(warning)), + dim_x_(6), // x, y, yaw, yaw_bias, vx, wz + params_(params) +{ + Eigen::MatrixXd X = Eigen::MatrixXd::Zero(dim_x_, 1); + Eigen::MatrixXd P = Eigen::MatrixXd::Identity(dim_x_, dim_x_) * 1.0E15; // for x & y + P(IDX::YAW, IDX::YAW) = 50.0; // for yaw + if (params_.enable_yaw_bias_estimation) { + P(IDX::YAWB, IDX::YAWB) = 50.0; // for yaw bias + } + P(IDX::VX, IDX::VX) = 1000.0; // for vx + P(IDX::WZ, IDX::WZ) = 50.0; // for wz + + kalman_filter_.init(X, P, params_.extend_state_step); +} + +void EKFModule::initialize( + const PoseWithCovariance & initial_pose, const geometry_msgs::msg::TransformStamped & transform) +{ + Eigen::MatrixXd X(dim_x_, 1); + Eigen::MatrixXd P = Eigen::MatrixXd::Zero(dim_x_, dim_x_); + + X(IDX::X) = initial_pose.pose.pose.position.x + transform.transform.translation.x; + X(IDX::Y) = initial_pose.pose.pose.position.y + transform.transform.translation.y; + X(IDX::YAW) = + tf2::getYaw(initial_pose.pose.pose.orientation) + tf2::getYaw(transform.transform.rotation); + X(IDX::YAWB) = 0.0; + X(IDX::VX) = 0.0; + X(IDX::WZ) = 0.0; + + using COV_IDX = tier4_autoware_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; + P(IDX::X, IDX::X) = initial_pose.pose.covariance[COV_IDX::X_X]; + P(IDX::Y, IDX::Y) = initial_pose.pose.covariance[COV_IDX::Y_Y]; + P(IDX::YAW, IDX::YAW) = initial_pose.pose.covariance[COV_IDX::YAW_YAW]; + + if (params_.enable_yaw_bias_estimation) { + P(IDX::YAWB, IDX::YAWB) = 0.0001; + } + P(IDX::VX, IDX::VX) = 0.01; + P(IDX::WZ, IDX::WZ) = 0.01; + + kalman_filter_.init(X, P, params_.extend_state_step); +} + +geometry_msgs::msg::PoseStamped EKFModule::getCurrentPose( + const rclcpp::Time & current_time, const double z, const double roll, const double pitch, + bool get_biased_yaw) const +{ + const double x = kalman_filter_.getXelement(IDX::X); + const double y = kalman_filter_.getXelement(IDX::Y); + const double biased_yaw = kalman_filter_.getXelement(IDX::YAW); + const double yaw_bias = kalman_filter_.getXelement(IDX::YAWB); + const double yaw = biased_yaw + yaw_bias; + Pose current_ekf_pose; + current_ekf_pose.header.frame_id = params_.pose_frame_id; + current_ekf_pose.header.stamp = current_time; + current_ekf_pose.pose.position = tier4_autoware_utils::createPoint(x, y, z); + if (get_biased_yaw) { + current_ekf_pose.pose.orientation = + tier4_autoware_utils::createQuaternionFromRPY(roll, pitch, biased_yaw); + } else { + current_ekf_pose.pose.orientation = + tier4_autoware_utils::createQuaternionFromRPY(roll, pitch, yaw); + } + return current_ekf_pose; +} + +geometry_msgs::msg::TwistStamped EKFModule::getCurrentTwist(const rclcpp::Time & current_time) const +{ + const double vx = kalman_filter_.getXelement(IDX::VX); + const double wz = kalman_filter_.getXelement(IDX::WZ); + + Twist current_ekf_twist; + current_ekf_twist.header.frame_id = "base_link"; + current_ekf_twist.header.stamp = current_time; + current_ekf_twist.twist.linear.x = vx; + current_ekf_twist.twist.angular.z = wz; + return current_ekf_twist; +} + +std::array EKFModule::getCurrentPoseCovariance() const +{ + return ekfCovarianceToPoseMessageCovariance(kalman_filter_.getLatestP()); +} + +std::array EKFModule::getCurrentTwistCovariance() const +{ + return ekfCovarianceToTwistMessageCovariance(kalman_filter_.getLatestP()); +} + +double EKFModule::getYawBias() const +{ + return kalman_filter_.getLatestX()(IDX::YAWB); +} + +void EKFModule::predictWithDelay(const double dt) +{ + const Eigen::MatrixXd X_curr = kalman_filter_.getLatestX(); + const Eigen::MatrixXd P_curr = kalman_filter_.getLatestP(); + + const double proc_cov_vx_d = std::pow(params_.proc_stddev_vx_c * dt, 2.0); + const double proc_cov_wz_d = std::pow(params_.proc_stddev_wz_c * dt, 2.0); + const double proc_cov_yaw_d = std::pow(params_.proc_stddev_yaw_c * dt, 2.0); + + const Vector6d X_next = predictNextState(X_curr, dt); + const Matrix6d A = createStateTransitionMatrix(X_curr, dt); + const Matrix6d Q = processNoiseCovariance(proc_cov_yaw_d, proc_cov_vx_d, proc_cov_wz_d); + kalman_filter_.predictWithDelay(X_next, A, Q); +} + +bool EKFModule::measurementUpdatePose( + const PoseWithCovariance & pose, const double dt, const rclcpp::Time & t_curr, + EKFDiagnosticInfo & pose_diag_info) +{ + if (pose.header.frame_id != params_.pose_frame_id) { + warning_->warnThrottle( + fmt::format( + "pose frame_id is %s, but pose_frame is set as %s. They must be same.", + pose.header.frame_id.c_str(), params_.pose_frame_id.c_str()), + 2000); + } + const Eigen::MatrixXd X_curr = kalman_filter_.getLatestX(); + DEBUG_PRINT_MAT(X_curr.transpose()); + + constexpr int dim_y = 3; // pos_x, pos_y, yaw, depending on Pose output + + /* Calculate delay step */ + double delay_time = (t_curr - pose.header.stamp).seconds() + params_.pose_additional_delay; + if (delay_time < 0.0) { + warning_->warnThrottle(poseDelayTimeWarningMessage(delay_time), 1000); + } + + delay_time = std::max(delay_time, 0.0); + + const int delay_step = std::roundf(delay_time / dt); + + pose_diag_info.delay_time = std::max(delay_time, pose_diag_info.delay_time); + pose_diag_info.delay_time_threshold = params_.extend_state_step * dt; + if (delay_step >= params_.extend_state_step) { + pose_diag_info.is_passed_delay_gate = false; + warning_->warnThrottle( + poseDelayStepWarningMessage(delay_time, params_.extend_state_step, dt), 2000); + return false; + } + + /* Set yaw */ + double yaw = tf2::getYaw(pose.pose.pose.orientation); + const double ekf_yaw = kalman_filter_.getXelement(delay_step * dim_x_ + IDX::YAW); + const double yaw_error = normalizeYaw(yaw - ekf_yaw); // normalize the error not to exceed 2 pi + yaw = yaw_error + ekf_yaw; + + /* Set measurement matrix */ + Eigen::MatrixXd y(dim_y, 1); + y << pose.pose.pose.position.x, pose.pose.pose.position.y, yaw; + + if (hasNan(y) || hasInf(y)) { + warning_->warn( + "[EKF] pose measurement matrix includes NaN of Inf. ignore update. check pose message."); + return false; + } + + /* Gate */ + const Eigen::Vector3d y_ekf( + kalman_filter_.getXelement(delay_step * dim_x_ + IDX::X), + kalman_filter_.getXelement(delay_step * dim_x_ + IDX::Y), ekf_yaw); + const Eigen::MatrixXd P_curr = kalman_filter_.getLatestP(); + const Eigen::MatrixXd P_y = P_curr.block(0, 0, dim_y, dim_y); + + const double distance = mahalanobis(y_ekf, y, P_y); + pose_diag_info.mahalanobis_distance = std::max(distance, pose_diag_info.mahalanobis_distance); + if (distance > params_.pose_gate_dist) { + pose_diag_info.is_passed_mahalanobis_gate = false; + warning_->warnThrottle(mahalanobisWarningMessage(distance, params_.pose_gate_dist), 2000); + warning_->warnThrottle("Ignore the measurement data.", 2000); + return false; + } + + DEBUG_PRINT_MAT(y.transpose()); + DEBUG_PRINT_MAT(y_ekf.transpose()); + DEBUG_PRINT_MAT((y - y_ekf).transpose()); + + const Eigen::Matrix C = poseMeasurementMatrix(); + const Eigen::Matrix3d R = + poseMeasurementCovariance(pose.pose.covariance, params_.pose_smoothing_steps); + + kalman_filter_.updateWithDelay(y, C, R, delay_step); + + // debug + const Eigen::MatrixXd X_result = kalman_filter_.getLatestX(); + DEBUG_PRINT_MAT(X_result.transpose()); + DEBUG_PRINT_MAT((X_result - X_curr).transpose()); + + return true; +} + +geometry_msgs::msg::PoseWithCovarianceStamped EKFModule::compensatePoseWithZDelay( + const PoseWithCovariance & pose, const double delay_time) +{ + const auto rpy = tier4_autoware_utils::getRPY(pose.pose.pose.orientation); + const double dz_delay = kalman_filter_.getXelement(IDX::VX) * delay_time * std::sin(-rpy.y); + PoseWithCovariance pose_with_z_delay; + pose_with_z_delay = pose; + pose_with_z_delay.pose.pose.position.z += dz_delay; + return pose_with_z_delay; +} + +bool EKFModule::measurementUpdateTwist( + const TwistWithCovariance & twist, const double dt, const rclcpp::Time & t_curr, + EKFDiagnosticInfo & twist_diag_info) +{ + if (twist.header.frame_id != "base_link") { + warning_->warnThrottle("twist frame_id must be base_link", 2000); + } + + const Eigen::MatrixXd X_curr = kalman_filter_.getLatestX(); + DEBUG_PRINT_MAT(X_curr.transpose()); + + constexpr int dim_y = 2; // vx, wz + + /* Calculate delay step */ + double delay_time = (t_curr - twist.header.stamp).seconds() + params_.twist_additional_delay; + if (delay_time < 0.0) { + warning_->warnThrottle(twistDelayTimeWarningMessage(delay_time), 1000); + } + delay_time = std::max(delay_time, 0.0); + + const int delay_step = std::roundf(delay_time / dt); + + twist_diag_info.delay_time = std::max(delay_time, twist_diag_info.delay_time); + twist_diag_info.delay_time_threshold = params_.extend_state_step * dt; + if (delay_step >= params_.extend_state_step) { + twist_diag_info.is_passed_delay_gate = false; + warning_->warnThrottle( + twistDelayStepWarningMessage(delay_time, params_.extend_state_step, dt), 2000); + return false; + } + + /* Set measurement matrix */ + Eigen::MatrixXd y(dim_y, 1); + y << twist.twist.twist.linear.x, twist.twist.twist.angular.z; + + if (hasNan(y) || hasInf(y)) { + warning_->warn( + "[EKF] twist measurement matrix includes NaN of Inf. ignore update. check twist message."); + return false; + } + + const Eigen::Vector2d y_ekf( + kalman_filter_.getXelement(delay_step * dim_x_ + IDX::VX), + kalman_filter_.getXelement(delay_step * dim_x_ + IDX::WZ)); + const Eigen::MatrixXd P_curr = kalman_filter_.getLatestP(); + const Eigen::MatrixXd P_y = P_curr.block(4, 4, dim_y, dim_y); + + const double distance = mahalanobis(y_ekf, y, P_y); + twist_diag_info.mahalanobis_distance = std::max(distance, twist_diag_info.mahalanobis_distance); + if (distance > params_.twist_gate_dist) { + twist_diag_info.is_passed_mahalanobis_gate = false; + warning_->warnThrottle(mahalanobisWarningMessage(distance, params_.twist_gate_dist), 2000); + warning_->warnThrottle("Ignore the measurement data.", 2000); + return false; + } + + DEBUG_PRINT_MAT(y.transpose()); + DEBUG_PRINT_MAT(y_ekf.transpose()); + DEBUG_PRINT_MAT((y - y_ekf).transpose()); + + const Eigen::Matrix C = twistMeasurementMatrix(); + const Eigen::Matrix2d R = + twistMeasurementCovariance(twist.twist.covariance, params_.twist_smoothing_steps); + + kalman_filter_.updateWithDelay(y, C, R, delay_step); + + // debug + const Eigen::MatrixXd X_result = kalman_filter_.getLatestX(); + DEBUG_PRINT_MAT(X_result.transpose()); + DEBUG_PRINT_MAT((X_result - X_curr).transpose()); + + return true; +} From 6b0bbde0a3a8dbfdf28cd6f1f440fa076b7ed31b Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Mon, 6 Nov 2023 19:51:14 +0900 Subject: [PATCH 128/202] feat(ndt_scan_matcher): use glog (#5465) * feat(ndt_scan_matcher): use glog Signed-off-by: kminoda * style(pre-commit): autofix * update Signed-off-by: kminoda * style(pre-commit): autofix --------- Signed-off-by: kminoda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- localization/ndt_scan_matcher/CMakeLists.txt | 3 ++- localization/ndt_scan_matcher/package.xml | 1 + localization/ndt_scan_matcher/src/ndt_scan_matcher_node.cpp | 5 +++++ 3 files changed, 8 insertions(+), 1 deletion(-) diff --git a/localization/ndt_scan_matcher/CMakeLists.txt b/localization/ndt_scan_matcher/CMakeLists.txt index 79491a85a0a66..6fe61cd25bc6e 100644 --- a/localization/ndt_scan_matcher/CMakeLists.txt +++ b/localization/ndt_scan_matcher/CMakeLists.txt @@ -22,6 +22,7 @@ else() endif() endif() +find_package(glog REQUIRED) find_package(PCL REQUIRED COMPONENTS common io registration) include_directories(${PCL_INCLUDE_DIRS}) @@ -34,7 +35,7 @@ ament_auto_add_executable(ndt_scan_matcher ) link_directories(${PCL_LIBRARY_DIRS}) -target_link_libraries(ndt_scan_matcher ${PCL_LIBRARIES}) +target_link_libraries(ndt_scan_matcher ${PCL_LIBRARIES} glog::glog) if(BUILD_TESTING) add_ros_test( diff --git a/localization/ndt_scan_matcher/package.xml b/localization/ndt_scan_matcher/package.xml index a9083c4ae0ae4..dcfdd77cb5a18 100644 --- a/localization/ndt_scan_matcher/package.xml +++ b/localization/ndt_scan_matcher/package.xml @@ -18,6 +18,7 @@ diagnostic_msgs fmt geometry_msgs + libgoogle-glog-dev libpcl-all-dev localization_util nav_msgs diff --git a/localization/ndt_scan_matcher/src/ndt_scan_matcher_node.cpp b/localization/ndt_scan_matcher/src/ndt_scan_matcher_node.cpp index be6b398d7738e..d5ea544d3c5e5 100644 --- a/localization/ndt_scan_matcher/src/ndt_scan_matcher_node.cpp +++ b/localization/ndt_scan_matcher/src/ndt_scan_matcher_node.cpp @@ -16,8 +16,13 @@ #include +#include + int main(int argc, char ** argv) { + google::InitGoogleLogging(argv[0]); + google::InstallFailureSignalHandler(); + rclcpp::init(argc, argv); auto ndt_scan_matcher = std::make_shared(); rclcpp::executors::MultiThreadedExecutor exec; From 7789be489dc437d2f2c2b62dba0ddbf27746ff09 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Mon, 6 Nov 2023 20:57:28 +0900 Subject: [PATCH 129/202] Logger level update (#5494) * address ordering Signed-off-by: Takamasa Horibe * add grouping Signed-off-by: Takamasa Horibe * remove unused comment Signed-off-by: Takamasa Horibe --------- Signed-off-by: Takamasa Horibe --- .../config/logger_config.yaml | 140 ++++++++-------- .../logging_level_configure.hpp | 22 ++- .../src/logging_level_configure.cpp | 154 ++++++++++++------ 3 files changed, 189 insertions(+), 127 deletions(-) diff --git a/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml b/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml index 9fb84b8efc1d4..23a5123d8d8e2 100644 --- a/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml +++ b/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml @@ -3,85 +3,85 @@ # ============================================================ # localization # ============================================================ +Localization: + ndt_scan_matcher: + - node_name: /localization/pose_estimator/ndt_scan_matcher + logger_name: localization.pose_estimator.ndt_scan_matcher -ndt_scan_matcher: - - node_name: /localization/pose_estimator/ndt_scan_matcher - logger_name: localization.pose_estimator.ndt_scan_matcher + gyro_odometer: + - node_name: /localization/twist_estimator/gyro_odometer + logger_name: localization.twist_estimator.gyro_odometer -gyro_odometer: - - node_name: /localization/twist_estimator/gyro_odometer - logger_name: localization.twist_estimator.gyro_odometer + pose_initializer: + - node_name: /localization/util/pose_initializer_node + logger_name: localization.util.pose_initializer_node -pose_initializer: - - node_name: /localization/util/pose_initializer_node - logger_name: localization.util.pose_initializer_node + ekf_localizer: + - node_name: /localization/pose_twist_fusion_filter/ekf_localizer + logger_name: localization.pose_twist_fusion_filter.ekf_localizer -ekf_localizer: - - node_name: /localization/pose_twist_fusion_filter/ekf_localizer - logger_name: localization.pose_twist_fusion_filter.ekf_localizer - -localization_error_monitor: - - node_name: /localization/localization_error_monitor - logger_name: localization.localization_error_monitor + localization_error_monitor: + - node_name: /localization/localization_error_monitor + logger_name: localization.localization_error_monitor # ============================================================ # planning # ============================================================ - -behavior_path_planner: - - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner - logger_name: planning.scenario_planning.lane_driving.behavior_planning.behavior_path_planner - - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner - logger_name: tier4_autoware_utils - -behavior_path_planner_avoidance: - - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner - logger_name: planning.scenario_planning.lane_driving.behavior_planning.behavior_path_planner.avoidance - -behavior_path_planner_lane_change: - - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner - logger_name: lane_change - -behavior_velocity_planner: - - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner - logger_name: planning.scenario_planning.lane_driving.behavior_planning.behavior_velocity_planner - - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner - logger_name: tier4_autoware_utils - -behavior_velocity_planner_intersection: - - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner - logger_name: planning.scenario_planning.lane_driving.behavior_planning.behavior_velocity_planner.intersection - -motion_obstacle_avoidance: - - node_name: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner - logger_name: planning.scenario_planning.lane_driving.motion_planning.obstacle_avoidance_planner - - node_name: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner - logger_name: tier4_autoware_utils - -motion_velocity_smoother: - - node_name: /planning/scenario_planning/motion_velocity_smoother - logger_name: planning.scenario_planning.motion_velocity_smoother - - node_name: /planning/scenario_planning/motion_velocity_smoother - logger_name: tier4_autoware_utils +Planning: + behavior_path_planner: + - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner + logger_name: planning.scenario_planning.lane_driving.behavior_planning.behavior_path_planner + - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner + logger_name: tier4_autoware_utils + + behavior_path_planner_avoidance: + - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner + logger_name: planning.scenario_planning.lane_driving.behavior_planning.behavior_path_planner.avoidance + + behavior_path_planner_lane_change: + - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner + logger_name: lane_change + + behavior_velocity_planner: + - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner + logger_name: planning.scenario_planning.lane_driving.behavior_planning.behavior_velocity_planner + - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner + logger_name: tier4_autoware_utils + + behavior_velocity_planner_intersection: + - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner + logger_name: planning.scenario_planning.lane_driving.behavior_planning.behavior_velocity_planner.intersection + + motion_obstacle_avoidance: + - node_name: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner + logger_name: planning.scenario_planning.lane_driving.motion_planning.obstacle_avoidance_planner + - node_name: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner + logger_name: tier4_autoware_utils + + motion_velocity_smoother: + - node_name: /planning/scenario_planning/motion_velocity_smoother + logger_name: planning.scenario_planning.motion_velocity_smoother + - node_name: /planning/scenario_planning/motion_velocity_smoother + logger_name: tier4_autoware_utils # ============================================================ # control # ============================================================ - -lateral_controller: - - node_name: /control/trajectory_follower/controller_node_exe - logger_name: control.trajectory_follower.controller_node_exe.lateral_controller - - node_name: /control/trajectory_follower/controller_node_exe - logger_name: tier4_autoware_utils - -longitudinal_controller: - - node_name: /control/trajectory_follower/controller_node_exe - logger_name: control.trajectory_follower.controller_node_exe.longitudinal_controller - - node_name: /control/trajectory_follower/controller_node_exe - logger_name: tier4_autoware_utils - -vehicle_cmd_gate: - - node_name: /control/vehicle_cmd_gate - logger_name: control.vehicle_cmd_gate - - node_name: /control/vehicle_cmd_gate - logger_name: tier4_autoware_utils +Control: + lateral_controller: + - node_name: /control/trajectory_follower/controller_node_exe + logger_name: control.trajectory_follower.controller_node_exe.lateral_controller + - node_name: /control/trajectory_follower/controller_node_exe + logger_name: tier4_autoware_utils + + longitudinal_controller: + - node_name: /control/trajectory_follower/controller_node_exe + logger_name: control.trajectory_follower.controller_node_exe.longitudinal_controller + - node_name: /control/trajectory_follower/controller_node_exe + logger_name: tier4_autoware_utils + + vehicle_cmd_gate: + - node_name: /control/vehicle_cmd_gate + logger_name: control.vehicle_cmd_gate + - node_name: /control/vehicle_cmd_gate + logger_name: tier4_autoware_utils diff --git a/common/tier4_logging_level_configure_rviz_plugin/include/tier4_logging_level_configure_rviz_plugin/logging_level_configure.hpp b/common/tier4_logging_level_configure_rviz_plugin/include/tier4_logging_level_configure_rviz_plugin/logging_level_configure.hpp index 4d9b81ffb86bf..37d70b494c74e 100644 --- a/common/tier4_logging_level_configure_rviz_plugin/include/tier4_logging_level_configure_rviz_plugin/logging_level_configure.hpp +++ b/common/tier4_logging_level_configure_rviz_plugin/include/tier4_logging_level_configure_rviz_plugin/logging_level_configure.hpp @@ -34,7 +34,21 @@ namespace rviz_plugin { - +struct LoggerInfo +{ + QString node_name; + QString logger_name; +}; +struct ButtonInfo +{ + QString button_name; + std::vector logger_info_vec; +}; +struct LoggerNamespaceInfo +{ + QString ns; // group namespace + std::vector button_info_vec; +}; class LoggingLevelConfigureRvizPlugin : public rviz_common::Panel { Q_OBJECT // This macro is needed for Qt to handle slots and signals @@ -48,8 +62,7 @@ class LoggingLevelConfigureRvizPlugin : public rviz_common::Panel QMap buttonGroups_; rclcpp::Node::SharedPtr raw_node_; - // node_logger_map_[button_name] = {node_name, logger_name} - std::map>> node_logger_map_; + std::vector display_info_vec_; // client_map_[node_name] = service_client std::unordered_map::SharedPtr> @@ -62,6 +75,9 @@ class LoggingLevelConfigureRvizPlugin : public rviz_common::Panel int getMaxModuleNameWidth(QLabel * containerLabel); void setLoggerNodeMap(); + ButtonInfo getButtonInfoFromNamespace(const QString & ns); + std::vector getNodeLoggerNameFromButtonName(const QString button_name); + private Q_SLOTS: void onButtonClick(QPushButton * button, const QString & name, const QString & level); void updateButtonColors( diff --git a/common/tier4_logging_level_configure_rviz_plugin/src/logging_level_configure.cpp b/common/tier4_logging_level_configure_rviz_plugin/src/logging_level_configure.cpp index b15c0f0f735fa..72ecf361c96d5 100644 --- a/common/tier4_logging_level_configure_rviz_plugin/src/logging_level_configure.cpp +++ b/common/tier4_logging_level_configure_rviz_plugin/src/logging_level_configure.cpp @@ -14,6 +14,7 @@ #include "yaml-cpp/yaml.h" +#include #include #include #include @@ -36,56 +37,72 @@ void LoggingLevelConfigureRvizPlugin::onInitialize() setLoggerNodeMap(); - QVBoxLayout * layout = new QVBoxLayout; + QVBoxLayout * mainLayout = new QVBoxLayout; QStringList levels = {"DEBUG", "INFO", "WARN", "ERROR", "FATAL"}; constexpr int height = 20; - for (const auto & item : node_logger_map_) { - const auto & target_node_name = item.first; - - QHBoxLayout * hLayout = new QHBoxLayout; - - // Create a QLabel to display the node name. - QLabel * label = new QLabel(target_node_name); - label->setFixedHeight(height); // Set fixed height for the button - label->setFixedWidth(getMaxModuleNameWidth(label)); - - hLayout->addWidget(label); // Add the QLabel to the hLayout. - - QButtonGroup * group = new QButtonGroup(this); - for (const QString & level : levels) { - QPushButton * btn = new QPushButton(level); - btn->setFixedHeight(height); // Set fixed height for the button - hLayout->addWidget(btn); // Add each QPushButton to the hLayout. - group->addButton(btn); - button_map_[target_node_name][level] = btn; - connect(btn, &QPushButton::clicked, this, [this, btn, target_node_name, level]() { - this->onButtonClick(btn, target_node_name, level); - }); + + // Iterate over the namespaces + for (const auto & ns_group_info : display_info_vec_) { + // Create a group box for each namespace + QGroupBox * groupBox = new QGroupBox(ns_group_info.ns); + QVBoxLayout * groupLayout = new QVBoxLayout; + + // Iterate over the node/logger pairs within this namespace + for (const auto & button_info : ns_group_info.button_info_vec) { + const auto & button_name = button_info.button_name; + + QHBoxLayout * hLayout = new QHBoxLayout; + + // Create a QLabel to display the node name + QLabel * label = new QLabel(button_name); + label->setFixedHeight(height); + label->setFixedWidth(getMaxModuleNameWidth(label)); + + hLayout->addWidget(label); + + // Create a button group for each node + QButtonGroup * buttonGroup = new QButtonGroup(this); + + // Create buttons for each logging level + for (const QString & level : levels) { + QPushButton * button = new QPushButton(level); + button->setFixedHeight(height); + hLayout->addWidget(button); + buttonGroup->addButton(button); + button_map_[button_name][level] = button; + connect(button, &QPushButton::clicked, this, [this, button, button_name, level]() { + this->onButtonClick(button, button_name, level); + }); + } + + // Set the "INFO" button as checked by default and change its color + updateButtonColors(button_name, button_map_[button_name]["INFO"], "INFO"); + + buttonGroups_[button_name] = buttonGroup; + groupLayout->addLayout(hLayout); // Add the horizontal layout to the group layout } - // Set the "INFO" button as checked by default and change its color. - updateButtonColors(target_node_name, button_map_[target_node_name]["INFO"], "INFO"); - buttonGroups_[target_node_name] = group; - layout->addLayout(hLayout); + groupBox->setLayout(groupLayout); // Set the group layout to the group box + mainLayout->addWidget(groupBox); // Add the group box to the main layout } - // Create a QWidget to hold the layout. + // Create a QWidget to hold the main layout QWidget * containerWidget = new QWidget; - containerWidget->setLayout(layout); + containerWidget->setLayout(mainLayout); - // Create a QScrollArea to make the layout scrollable. + // Create a QScrollArea to make the layout scrollable QScrollArea * scrollArea = new QScrollArea; scrollArea->setWidget(containerWidget); scrollArea->setWidgetResizable(true); - // Set the QScrollArea as the layout of the main widget. - QVBoxLayout * mainLayout = new QVBoxLayout; - mainLayout->addWidget(scrollArea); - setLayout(mainLayout); + // Set the QScrollArea as the layout of the main widget + QVBoxLayout * scrollLayout = new QVBoxLayout; + scrollLayout->addWidget(scrollArea); + setLayout(scrollLayout); - // set up service clients + // Setup service clients const auto & nodes = getNodeList(); for (const QString & node : nodes) { const auto client = raw_node_->create_client( @@ -99,9 +116,10 @@ int LoggingLevelConfigureRvizPlugin::getMaxModuleNameWidth(QLabel * label) { int max_width = 0; QFontMetrics metrics(label->font()); - for (const auto & item : node_logger_map_) { - const auto & target_module_name = item.first; - max_width = std::max(metrics.horizontalAdvance(target_module_name), max_width); + for (const auto & ns_info : display_info_vec_) { + for (const auto & b : ns_info.button_info_vec) { + max_width = std::max(metrics.horizontalAdvance(b.button_name), max_width); + } } return max_width; } @@ -110,11 +128,12 @@ int LoggingLevelConfigureRvizPlugin::getMaxModuleNameWidth(QLabel * label) QStringList LoggingLevelConfigureRvizPlugin::getNodeList() { QStringList nodes; - for (const auto & item : node_logger_map_) { - const auto & node_logger_vec = item.second; - for (const auto & node_logger_pair : node_logger_vec) { - if (!nodes.contains(node_logger_pair.first)) { - nodes.append(node_logger_pair.first); + for (const auto & d : display_info_vec_) { + for (const auto & b : d.button_info_vec) { + for (const auto & info : b.logger_info_vec) { + if (!nodes.contains(info.node_name)) { + nodes.append(info.node_name); + } } } } @@ -132,16 +151,15 @@ void LoggingLevelConfigureRvizPlugin::onButtonClick( << std::string(future.get()->success ? "success!" : "failed...") << std::endl; }; - for (const auto & node_logger_map : node_logger_map_[target_module_name]) { - const auto node_name = node_logger_map.first; - const auto logger_name = node_logger_map.second; + const auto node_logger_vec = getNodeLoggerNameFromButtonName(target_module_name); + for (const auto & data : node_logger_vec) { const auto req = std::make_shared(); - req->logger_name = logger_name.toStdString(); + req->logger_name = data.logger_name.toStdString(); req->level = level.toStdString(); std::cerr << "logger level of " << req->logger_name << " is set to " << req->level << std::endl; - client_map_[node_name]->async_send_request(req, callback); + client_map_[data.node_name]->async_send_request(req, callback); } updateButtonColors( @@ -197,14 +215,42 @@ void LoggingLevelConfigureRvizPlugin::setLoggerNodeMap() YAML::Node config = YAML::LoadFile(filename); for (YAML::const_iterator it = config.begin(); it != config.end(); ++it) { - const auto key = QString::fromStdString(it->first.as()); - const YAML::Node values = it->second; - for (size_t i = 0; i < values.size(); i++) { - const auto node_name = QString::fromStdString(values[i]["node_name"].as()); - const auto logger_name = QString::fromStdString(values[i]["logger_name"].as()); - node_logger_map_[key].push_back({node_name, logger_name}); + const auto ns = QString::fromStdString(it->first.as()); + const YAML::Node ns_config = it->second; + + LoggerNamespaceInfo display_data; + display_data.ns = ns; + + for (YAML::const_iterator ns_it = ns_config.begin(); ns_it != ns_config.end(); ++ns_it) { + const auto key = QString::fromStdString(ns_it->first.as()); + ButtonInfo button_data; + button_data.button_name = key; + const YAML::Node values = ns_it->second; + for (size_t i = 0; i < values.size(); i++) { + LoggerInfo data; + data.node_name = QString::fromStdString(values[i]["node_name"].as()); + data.logger_name = QString::fromStdString(values[i]["logger_name"].as()); + button_data.logger_info_vec.push_back(data); + } + display_data.button_info_vec.push_back(button_data); + } + display_info_vec_.push_back(display_data); + } +} + +std::vector LoggingLevelConfigureRvizPlugin::getNodeLoggerNameFromButtonName( + const QString button_name) +{ + for (const auto & ns_level : display_info_vec_) { + for (const auto & button : ns_level.button_info_vec) { + if (button.button_name == button_name) { + return button.logger_info_vec; + } } } + RCLCPP_ERROR( + raw_node_->get_logger(), "Failed to find target name: %s", button_name.toStdString().c_str()); + return {}; } } // namespace rviz_plugin From 72e96fccc7b293a362a7b635036570052406c086 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Tue, 7 Nov 2023 09:38:50 +0900 Subject: [PATCH 130/202] feat(ekf_localizer, system_error_monitor): system_error_monitor handles ekf diags (#5467) * fix(ekf_localizer): change default parameter for no update count Signed-off-by: kminoda * add ekf in system_error_monitor Signed-off-by: kminoda * style(pre-commit): autofix --------- Signed-off-by: kminoda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../ekf_localizer/config/ekf_localizer.param.yaml | 4 ++-- .../diagnostic_aggregator/localization.param.yaml | 10 ++++++++++ 2 files changed, 12 insertions(+), 2 deletions(-) diff --git a/localization/ekf_localizer/config/ekf_localizer.param.yaml b/localization/ekf_localizer/config/ekf_localizer.param.yaml index 667217d2591dc..1c16624605907 100644 --- a/localization/ekf_localizer/config/ekf_localizer.param.yaml +++ b/localization/ekf_localizer/config/ekf_localizer.param.yaml @@ -24,9 +24,9 @@ # for diagnostics pose_no_update_count_threshold_warn: 50 - pose_no_update_count_threshold_error: 250 + pose_no_update_count_threshold_error: 100 twist_no_update_count_threshold_warn: 50 - twist_no_update_count_threshold_error: 250 + twist_no_update_count_threshold_error: 100 # for velocity measurement limitation (Set 0.0 if you want to ignore) threshold_observable_velocity_mps: 0.0 # [m/s] diff --git a/system/system_error_monitor/config/diagnostic_aggregator/localization.param.yaml b/system/system_error_monitor/config/diagnostic_aggregator/localization.param.yaml index f82f7d732f5dc..a0b13a899a6ba 100644 --- a/system/system_error_monitor/config/diagnostic_aggregator/localization.param.yaml +++ b/system/system_error_monitor/config/diagnostic_aggregator/localization.param.yaml @@ -29,3 +29,13 @@ path: localization_accuracy contains: ["localization: localization_error_monitor"] timeout: 1.0 + + # This diagnostic should ideally be avoided in terms of Fault Tree Analysis (FTA) compatibility. + # However, we may need this since the localization accuracy is still not reliable enough and may produce + # false positives. Thus, NOTE that this diagnostic should be removed in the future when the localization accuracy + # is reliable enough. + sensor_fusion_status: + type: diagnostic_aggregator/GenericAnalyzer + path: sensor_fusion_status + contains: ["localization: ekf_localizer"] + timeout: 1.0 From f662ac7da76c0b042944df903696ae761ffa5c92 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Tue, 7 Nov 2023 12:21:15 +0900 Subject: [PATCH 131/202] chore(planning modules): remove maintainer... (#5458) remove shimizu-san from maintainer and add maintainer for stop line and turn signal decider Signed-off-by: kyoichi-sugahara --- common/interpolation/package.xml | 1 - common/motion_utils/package.xml | 2 -- common/tier4_autoware_utils/package.xml | 1 - common/tier4_planning_rviz_plugin/package.xml | 1 - control/autonomous_emergency_braking/package.xml | 1 - launch/tier4_planning_launch/package.xml | 7 +++++-- perception/map_based_prediction/package.xml | 1 - planning/behavior_path_planner/package.xml | 5 ++++- planning/behavior_velocity_planner/package.xml | 1 - planning/behavior_velocity_stop_line_module/package.xml | 3 ++- planning/costmap_generator/package.xml | 1 - planning/freespace_planner/package.xml | 1 - planning/freespace_planning_algorithms/package.xml | 1 - planning/mission_planner/package.xml | 1 - planning/motion_velocity_smoother/package.xml | 1 - planning/obstacle_cruise_planner/package.xml | 1 - planning/route_handler/package.xml | 1 - 17 files changed, 11 insertions(+), 19 deletions(-) diff --git a/common/interpolation/package.xml b/common/interpolation/package.xml index e5d2c7af8d06e..6be04482da3ee 100644 --- a/common/interpolation/package.xml +++ b/common/interpolation/package.xml @@ -6,7 +6,6 @@ The spline interpolation package Fumiya Watanabe Takayuki Murooka - Yutaka Shimizu Apache License 2.0 ament_cmake_auto diff --git a/common/motion_utils/package.xml b/common/motion_utils/package.xml index 334b023f7f29a..5f630572c061c 100644 --- a/common/motion_utils/package.xml +++ b/common/motion_utils/package.xml @@ -4,7 +4,6 @@ motion_utils 0.1.0 The motion_utils package - Yutaka Shimizu Satoshi Ota Takayuki Murooka @@ -16,7 +15,6 @@ Mamoru Sobue Apache License 2.0 - Yutaka Shimizu Takayuki Murooka Satoshi Ota diff --git a/common/tier4_autoware_utils/package.xml b/common/tier4_autoware_utils/package.xml index 701907929ecc0..e37cd0cc33975 100644 --- a/common/tier4_autoware_utils/package.xml +++ b/common/tier4_autoware_utils/package.xml @@ -6,7 +6,6 @@ The tier4_autoware_utils package Takamasa Horibe Takayuki Murooka - Yutaka Shimizu Mamoru Sobue Apache License 2.0 diff --git a/common/tier4_planning_rviz_plugin/package.xml b/common/tier4_planning_rviz_plugin/package.xml index 5dfa3605cfcad..4af4a371ef651 100644 --- a/common/tier4_planning_rviz_plugin/package.xml +++ b/common/tier4_planning_rviz_plugin/package.xml @@ -5,7 +5,6 @@ 0.1.0 The tier4_planning_rviz_plugin package Yukihiro Saito - Yutaka Shimizu Takayuki Murooka Apache License 2.0 diff --git a/control/autonomous_emergency_braking/package.xml b/control/autonomous_emergency_braking/package.xml index 5dc65cb243bfc..d45078064da3c 100644 --- a/control/autonomous_emergency_braking/package.xml +++ b/control/autonomous_emergency_braking/package.xml @@ -4,7 +4,6 @@ autonomous_emergency_braking 0.1.0 Autonomous Emergency Braking package as a ROS 2 node - Yutaka Shimizu Takamasa Horibe Tomoya Kimura diff --git a/launch/tier4_planning_launch/package.xml b/launch/tier4_planning_launch/package.xml index 8f9d8f5ea079d..950ef67865a85 100644 --- a/launch/tier4_planning_launch/package.xml +++ b/launch/tier4_planning_launch/package.xml @@ -17,7 +17,9 @@ Takamasa Horibe Satoshi Ota - Yutaka Shimizu + Zulfaqar Azmi + Satoshi Ota + Mamoru Sobue Takayuki Murooka @@ -37,7 +39,8 @@ Mamoru Sobue - Yutaka Shimizu + Fumiya Watanabe + Zhe Shen Kosuke Takeuchi diff --git a/perception/map_based_prediction/package.xml b/perception/map_based_prediction/package.xml index d7ff85adc9193..6a1354b37928f 100644 --- a/perception/map_based_prediction/package.xml +++ b/perception/map_based_prediction/package.xml @@ -4,7 +4,6 @@ map_based_prediction 0.1.0 This package implements a map_based_prediction - Yutaka Shimizu Tomoya Kimura Shunsuke Miura Yoshi Ri diff --git a/planning/behavior_path_planner/package.xml b/planning/behavior_path_planner/package.xml index 95ad5f1efb9ac..1f1eed3f95ec2 100644 --- a/planning/behavior_path_planner/package.xml +++ b/planning/behavior_path_planner/package.xml @@ -18,7 +18,10 @@ Takamasa Horibe Satoshi Ota - Yutaka Shimizu + Zulfaqar Azmi + Satoshi Ota + Mamoru Sobue + Takayuki Murooka diff --git a/planning/behavior_velocity_planner/package.xml b/planning/behavior_velocity_planner/package.xml index d83f74a71b66f..1357b555f0ba4 100644 --- a/planning/behavior_velocity_planner/package.xml +++ b/planning/behavior_velocity_planner/package.xml @@ -11,7 +11,6 @@ Kyoichi Sugahara Taiki Tanaka Kosuke Takeuchi - Yutaka Shimizu Tomohito Ando Makoto Kurihara Maxime Clement diff --git a/planning/behavior_velocity_stop_line_module/package.xml b/planning/behavior_velocity_stop_line_module/package.xml index 8610b7b428bec..ee79d64312161 100644 --- a/planning/behavior_velocity_stop_line_module/package.xml +++ b/planning/behavior_velocity_stop_line_module/package.xml @@ -5,7 +5,8 @@ 0.1.0 The behavior_velocity_stop_line_module package - Yutaka Shimizu + Fumiya Watanabe + Zhe Shen Tomoya Kimura Shumpei Wakabayashi diff --git a/planning/costmap_generator/package.xml b/planning/costmap_generator/package.xml index feed19fdcc235..ae124a1774881 100644 --- a/planning/costmap_generator/package.xml +++ b/planning/costmap_generator/package.xml @@ -7,7 +7,6 @@ Kosuke Takeuchi Takamasa Horibe Takayuki Murooka - Yutaka Shimizu Apache License 2.0 diff --git a/planning/freespace_planner/package.xml b/planning/freespace_planner/package.xml index f92c0a449970d..22557f8a0bbb3 100644 --- a/planning/freespace_planner/package.xml +++ b/planning/freespace_planner/package.xml @@ -7,7 +7,6 @@ Kosuke Takeuchi Takamasa Horibe Takayuki Murooka - Yutaka Shimizu Apache License 2.0 Akihito OHSATO diff --git a/planning/freespace_planning_algorithms/package.xml b/planning/freespace_planning_algorithms/package.xml index 372e623e101de..2b20a935c4ae1 100644 --- a/planning/freespace_planning_algorithms/package.xml +++ b/planning/freespace_planning_algorithms/package.xml @@ -7,7 +7,6 @@ Kosuke Takeuchi Takamasa Horibe Takayuki Murooka - Yutaka Shimizu Apache License 2.0 Akihito Ohsato diff --git a/planning/mission_planner/package.xml b/planning/mission_planner/package.xml index 49e1d0de8be93..4fcf2661ad20e 100644 --- a/planning/mission_planner/package.xml +++ b/planning/mission_planner/package.xml @@ -9,7 +9,6 @@ Ryohsuke Mitsudome Takamasa Horibe Takayuki Murooka - Yutaka Shimizu Apache License 2.0 Ryohsuke Mitsudome diff --git a/planning/motion_velocity_smoother/package.xml b/planning/motion_velocity_smoother/package.xml index f19ead1874f21..54c60c938970a 100644 --- a/planning/motion_velocity_smoother/package.xml +++ b/planning/motion_velocity_smoother/package.xml @@ -7,7 +7,6 @@ Fumiya Watanabe Takamasa Horibe - Yutaka Shimizu Makoto Kurihara Apache License 2.0 diff --git a/planning/obstacle_cruise_planner/package.xml b/planning/obstacle_cruise_planner/package.xml index f482be8ebafe7..e724ddb3e6bd7 100644 --- a/planning/obstacle_cruise_planner/package.xml +++ b/planning/obstacle_cruise_planner/package.xml @@ -5,7 +5,6 @@ The obstacle_cruise_planner package Takayuki Murooka - Yutaka Shimizu Kosuke Takeuchi Satoshi Ota diff --git a/planning/route_handler/package.xml b/planning/route_handler/package.xml index 29f0411a5aa80..60adfb1531104 100644 --- a/planning/route_handler/package.xml +++ b/planning/route_handler/package.xml @@ -6,7 +6,6 @@ The route_handling package Fumiya Watanabe Zulfaqar Azmi - Yutaka Shimizu Kosuke Takeuchi Takayuki Murooka Mamoru Sobue From c9e0b91f2bc6db03fcb29614c4db225d527b1b43 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Tue, 7 Nov 2023 12:51:00 +0900 Subject: [PATCH 132/202] refactor(behavior_path_planner): traffic light utils (#5503) * refactor(behavior_path_planner): traffic light utils Signed-off-by: Muhammad Zulfaqar Azmi * Update planning/behavior_path_planner/src/utils/traffic_light_utils.cpp Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> * Update planning/behavior_path_planner/include/behavior_path_planner/utils/traffic_light_utils.hpp Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> --------- Signed-off-by: Muhammad Zulfaqar Azmi Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> --- planning/behavior_path_planner/CMakeLists.txt | 1 + .../utils/traffic_light_utils.hpp | 112 +++++++++++++ .../behavior_path_planner/utils/utils.hpp | 3 - .../src/utils/avoidance/utils.cpp | 84 +--------- .../src/utils/traffic_light_utils.cpp | 157 ++++++++++++++++++ .../behavior_path_planner/src/utils/utils.cpp | 56 ------- 6 files changed, 274 insertions(+), 139 deletions(-) create mode 100644 planning/behavior_path_planner/include/behavior_path_planner/utils/traffic_light_utils.hpp create mode 100644 planning/behavior_path_planner/src/utils/traffic_light_utils.cpp diff --git a/planning/behavior_path_planner/CMakeLists.txt b/planning/behavior_path_planner/CMakeLists.txt index ee6e50f5a9553..e71d1dd9d86b4 100644 --- a/planning/behavior_path_planner/CMakeLists.txt +++ b/planning/behavior_path_planner/CMakeLists.txt @@ -30,6 +30,7 @@ ament_auto_add_library(behavior_path_planner_node SHARED src/turn_signal_decider.cpp src/utils/utils.cpp src/utils/path_utils.cpp + src/utils/traffic_light_utils.cpp src/utils/path_safety_checker/safety_check.cpp src/utils/path_safety_checker/objects_filtering.cpp src/utils/start_goal_planner_common/utils.cpp diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/traffic_light_utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/traffic_light_utils.hpp new file mode 100644 index 0000000000000..aa3e7f4833134 --- /dev/null +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/traffic_light_utils.hpp @@ -0,0 +1,112 @@ +// 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. +#ifndef BEHAVIOR_PATH_PLANNER__UTILS__TRAFFIC_LIGHT_UTILS_HPP_ +#define BEHAVIOR_PATH_PLANNER__UTILS__TRAFFIC_LIGHT_UTILS_HPP_ + +#include +#include +#include +#include + +#include +#include +#include + +#include +#include +#include + +#include + +namespace behavior_path_planner::utils::traffic_light +{ + +using autoware_perception_msgs::msg::TrafficSignal; +using autoware_perception_msgs::msg::TrafficSignalElement; +using geometry_msgs::msg::Pose; + +/** + * @brief Checks if a traffic light state includes a circle-shaped light with the specified color. + * + * Iterates through the traffic light elements to find a circle-shaped light that matches the given + * color. + * + * @param tl_state The traffic light state to check. + * @param lamp_color The color to look for in the traffic light's circle-shaped lamps. + * @return True if a circle-shaped light with the specified color is found, false otherwise. + */ +bool hasTrafficLightCircleColor(const TrafficSignal & tl_state, const uint8_t & lamp_color); + +/** + * @brief Checks if a traffic light state includes a light with the specified shape. + * + * Searches through the traffic light elements to find a light that matches the given shape. + * + * @param tl_state The traffic light state to check. + * @param shape The shape to look for in the traffic light's lights. + * @return True if a light with the specified shape is found, false otherwise. + */ +bool hasTrafficLightShape(const TrafficSignal & tl_state, const uint8_t & lamp_shape); + +/** + * @brief Determines if a traffic signal indicates a stop for the given lanelet. + * + * Evaluates the current state of the traffic light, considering if it's green or unknown, + * which would not necessitate a stop. Then, it checks the turn direction attribute of the lanelet + * against the traffic light's arrow shapes to determine whether a vehicle must stop or if it can + * proceed based on allowed turn directions. + * + * @param lanelet The lanelet to check for a stop signal at its traffic light. + * @param tl_state The current state of the traffic light associated with the lanelet. + * @return True if the traffic signal indicates a stop is required, false otherwise. + */ +bool isTrafficSignalStop(const lanelet::ConstLanelet & lanelet, const TrafficSignal & tl_state); + +/** + * @brief Computes the distance from the current position to the next traffic light along a set of + * lanelets. + * + * This function finds the closest lanelet to the current position and then searches for the + * next traffic light within the lanelet sequence. If a traffic light is found, it calculates + * the distance to the stop line of that traffic light from the current position. + * + * @param current_pose The current position of ego vehicle. + * @param lanelets A collection of lanelets representing the road ahead. + * @return The distance to the next traffic light's stop line or infinity if no traffic light is + * found ahead. + */ +double getDistanceToNextTrafficLight( + const Pose & current_pose, const lanelet::ConstLanelets & lanelets); + +/** + * @brief Calculates the signed distance from the ego vehicle to the stop line of the nearest red + * traffic light. + * + * Iterates over lanelets to find traffic lights. If a red traffic light is found, + * computes the distance to its stop line from the ego vehicle's position along a specified path. + * + * @param lanelets Collection of lanelets to inspect for traffic light regulatory elements. + * @param path The path along which the distance from ego current position to the stop line is + * measured. + * @param planner_data Shared pointer to planner data with vehicle odometry and traffic signal + * information. + * @return Optional double value with the signed distance to the stop line, or std::nullopt if no + * red traffic light is detected. + */ +std::optional calcDistanceToRedTrafficLight( + const lanelet::ConstLanelets & lanelets, const PathWithLaneId & path, + const std::shared_ptr & planner_data); +} // namespace behavior_path_planner::utils::traffic_light + +#endif // BEHAVIOR_PATH_PLANNER__UTILS__TRAFFIC_LIGHT_UTILS_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp index bfa83c43b061c..3f9591f6c2143 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp @@ -130,9 +130,6 @@ double l2Norm(const Vector3 vector); double getDistanceToEndOfLane(const Pose & current_pose, const lanelet::ConstLanelets & lanelets); -double getDistanceToNextTrafficLight( - const Pose & current_pose, const lanelet::ConstLanelets & lanelets); - double getDistanceToNextIntersection( const Pose & current_pose, const lanelet::ConstLanelets & lanelets); diff --git a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp index f1bbb3bc28a36..ce4c9ad7ac72d 100644 --- a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp +++ b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp @@ -18,6 +18,7 @@ #include "behavior_path_planner/utils/avoidance/utils.hpp" #include "behavior_path_planner/utils/path_safety_checker/objects_filtering.hpp" #include "behavior_path_planner/utils/path_utils.hpp" +#include "behavior_path_planner/utils/traffic_light_utils.hpp" #include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp" #include @@ -49,6 +50,8 @@ namespace behavior_path_planner::utils::avoidance { using autoware_perception_msgs::msg::TrafficSignalElement; +using behavior_path_planner::utils::traffic_light::calcDistanceToRedTrafficLight; +using behavior_path_planner::utils::traffic_light::getDistanceToNextTrafficLight; using motion_utils::calcLongitudinalOffsetPoint; using motion_utils::calcSignedArcLength; using motion_utils::findNearestIndex; @@ -227,85 +230,6 @@ void pushUniqueVector(T & base_vector, const T & additional_vector) base_vector.insert(base_vector.end(), additional_vector.begin(), additional_vector.end()); } -bool hasTrafficLightCircleColor(const TrafficSignal & tl_state, const uint8_t & lamp_color) -{ - const auto it_lamp = - std::find_if(tl_state.elements.begin(), tl_state.elements.end(), [&lamp_color](const auto & x) { - return x.shape == TrafficSignalElement::CIRCLE && x.color == lamp_color; - }); - - return it_lamp != tl_state.elements.end(); -} - -bool hasTrafficLightShape(const TrafficSignal & tl_state, const uint8_t & lamp_shape) -{ - const auto it_lamp = std::find_if( - tl_state.elements.begin(), tl_state.elements.end(), - [&lamp_shape](const auto & x) { return x.shape == lamp_shape; }); - - return it_lamp != tl_state.elements.end(); -} - -bool isTrafficSignalStop(const lanelet::ConstLanelet & lanelet, const TrafficSignal & tl_state) -{ - if (hasTrafficLightCircleColor(tl_state, TrafficSignalElement::GREEN)) { - return false; - } - - if (hasTrafficLightCircleColor(tl_state, TrafficSignalElement::UNKNOWN)) { - return false; - } - - const std::string turn_direction = lanelet.attributeOr("turn_direction", "else"); - - if (turn_direction == "else") { - return true; - } - if ( - turn_direction == "right" && - hasTrafficLightShape(tl_state, TrafficSignalElement::RIGHT_ARROW)) { - return false; - } - if ( - turn_direction == "left" && hasTrafficLightShape(tl_state, TrafficSignalElement::LEFT_ARROW)) { - return false; - } - if ( - turn_direction == "straight" && - hasTrafficLightShape(tl_state, TrafficSignalElement::UP_ARROW)) { - return false; - } - - return true; -} - -std::optional calcDistanceToRedTrafficLight( - const lanelet::ConstLanelets & lanelets, const PathWithLaneId & path, - const std::shared_ptr & planner_data) -{ - for (const auto & lanelet : lanelets) { - for (const auto & element : lanelet.regulatoryElementsAs()) { - const auto traffic_signal_stamped = planner_data->getTrafficSignal(element->id()); - if (!traffic_signal_stamped.has_value()) { - continue; - } - - if (!isTrafficSignalStop(lanelet, traffic_signal_stamped.value().signal)) { - continue; - } - - const auto & ego_pos = planner_data->self_odometry->pose.pose.position; - lanelet::ConstLineString3d stop_line = *(element->stopLine()); - const auto x = 0.5 * (stop_line.front().x() + stop_line.back().x()); - const auto y = 0.5 * (stop_line.front().y() + stop_line.back().y()); - const auto z = 0.5 * (stop_line.front().z() + stop_line.back().z()); - - return calcSignedArcLength(path.points, ego_pos, tier4_autoware_utils::createPoint(x, y, z)); - } - } - - return std::nullopt; -} } // namespace bool isOnRight(const ObjectData & obj) @@ -426,7 +350,7 @@ bool isForceAvoidanceTarget( bool not_parked_object = true; // check traffic light - const auto to_traffic_light = utils::getDistanceToNextTrafficLight(object_pose, extend_lanelets); + const auto to_traffic_light = getDistanceToNextTrafficLight(object_pose, extend_lanelets); { not_parked_object = to_traffic_light < parameters->object_ignore_section_traffic_light_in_front_distance; diff --git a/planning/behavior_path_planner/src/utils/traffic_light_utils.cpp b/planning/behavior_path_planner/src/utils/traffic_light_utils.cpp new file mode 100644 index 0000000000000..9ec8531818d83 --- /dev/null +++ b/planning/behavior_path_planner/src/utils/traffic_light_utils.cpp @@ -0,0 +1,157 @@ +// 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. + +#include +#include + +namespace behavior_path_planner::utils::traffic_light +{ +using motion_utils::calcSignedArcLength; + +bool hasTrafficLightCircleColor(const TrafficSignal & tl_state, const uint8_t & lamp_color) +{ + const auto it_lamp = + std::find_if(tl_state.elements.begin(), tl_state.elements.end(), [&lamp_color](const auto & x) { + return x.shape == TrafficSignalElement::CIRCLE && x.color == lamp_color; + }); + + return it_lamp != tl_state.elements.end(); +} + +bool hasTrafficLightShape(const TrafficSignal & tl_state, const uint8_t & lamp_shape) +{ + const auto it_lamp = std::find_if( + tl_state.elements.begin(), tl_state.elements.end(), + [&lamp_shape](const auto & x) { return x.shape == lamp_shape; }); + + return it_lamp != tl_state.elements.end(); +} + +bool isTrafficSignalStop(const lanelet::ConstLanelet & lanelet, const TrafficSignal & tl_state) +{ + if (hasTrafficLightCircleColor(tl_state, TrafficSignalElement::GREEN)) { + return false; + } + + if (hasTrafficLightCircleColor(tl_state, TrafficSignalElement::UNKNOWN)) { + return false; + } + + const std::string turn_direction = lanelet.attributeOr("turn_direction", "else"); + + if (turn_direction == "else") { + return true; + } + if ( + turn_direction == "right" && + hasTrafficLightShape(tl_state, TrafficSignalElement::RIGHT_ARROW)) { + return false; + } + if ( + turn_direction == "left" && hasTrafficLightShape(tl_state, TrafficSignalElement::LEFT_ARROW)) { + return false; + } + if ( + turn_direction == "straight" && + hasTrafficLightShape(tl_state, TrafficSignalElement::UP_ARROW)) { + return false; + } + + return true; +} + +double getDistanceToNextTrafficLight( + const Pose & current_pose, const lanelet::ConstLanelets & lanelets) +{ + lanelet::ConstLanelet current_lanelet; + if (!lanelet::utils::query::getClosestLanelet(lanelets, current_pose, ¤t_lanelet)) { + return std::numeric_limits::infinity(); + } + + const auto lanelet_point = lanelet::utils::conversion::toLaneletPoint(current_pose.position); + const auto to_object = lanelet::geometry::toArcCoordinates( + lanelet::utils::to2D(current_lanelet.centerline()), + lanelet::utils::to2D(lanelet_point).basicPoint()); + + for (const auto & element : current_lanelet.regulatoryElementsAs()) { + lanelet::ConstLineString3d lanelet_stop_lines = element->stopLine().get(); + + const auto to_stop_line = lanelet::geometry::toArcCoordinates( + lanelet::utils::to2D(current_lanelet.centerline()), + lanelet::utils::to2D(lanelet_stop_lines).front().basicPoint()); + + const auto distance_object_to_stop_line = to_stop_line.length - to_object.length; + + if (distance_object_to_stop_line > 0.0) { + return distance_object_to_stop_line; + } + } + + double distance = lanelet::utils::getLaneletLength3d(current_lanelet); + + bool found_current_lane = false; + for (const auto & llt : lanelets) { + if (llt.id() == current_lanelet.id()) { + found_current_lane = true; + continue; + } + + if (!found_current_lane) { + continue; + } + + for (const auto & element : llt.regulatoryElementsAs()) { + lanelet::ConstLineString3d lanelet_stop_lines = element->stopLine().get(); + + const auto to_stop_line = lanelet::geometry::toArcCoordinates( + lanelet::utils::to2D(llt.centerline()), + lanelet::utils::to2D(lanelet_stop_lines).front().basicPoint()); + + return distance + to_stop_line.length - to_object.length; + } + + distance += lanelet::utils::getLaneletLength3d(llt); + } + + return std::numeric_limits::infinity(); +} + +std::optional calcDistanceToRedTrafficLight( + const lanelet::ConstLanelets & lanelets, const PathWithLaneId & path, + const std::shared_ptr & planner_data) +{ + for (const auto & lanelet : lanelets) { + for (const auto & element : lanelet.regulatoryElementsAs()) { + const auto traffic_signal_stamped = planner_data->getTrafficSignal(element->id()); + if (!traffic_signal_stamped.has_value()) { + continue; + } + + if (!isTrafficSignalStop(lanelet, traffic_signal_stamped.value().signal)) { + continue; + } + + const auto & ego_pos = planner_data->self_odometry->pose.pose.position; + lanelet::ConstLineString3d stop_line = *(element->stopLine()); + const auto x = 0.5 * (stop_line.front().x() + stop_line.back().x()); + const auto y = 0.5 * (stop_line.front().y() + stop_line.back().y()); + const auto z = 0.5 * (stop_line.front().z() + stop_line.back().z()); + + return calcSignedArcLength(path.points, ego_pos, tier4_autoware_utils::createPoint(x, y, z)); + } + } + + return std::nullopt; +} +} // namespace behavior_path_planner::utils::traffic_light diff --git a/planning/behavior_path_planner/src/utils/utils.cpp b/planning/behavior_path_planner/src/utils/utils.cpp index 37a628f54607e..93f74e670ecdd 100644 --- a/planning/behavior_path_planner/src/utils/utils.cpp +++ b/planning/behavior_path_planner/src/utils/utils.cpp @@ -2289,62 +2289,6 @@ double getDistanceToEndOfLane(const Pose & current_pose, const lanelet::ConstLan return lanelet_length - arc_coordinates.length; } -double getDistanceToNextTrafficLight( - const Pose & current_pose, const lanelet::ConstLanelets & lanelets) -{ - lanelet::ConstLanelet current_lanelet; - if (!lanelet::utils::query::getClosestLanelet(lanelets, current_pose, ¤t_lanelet)) { - return std::numeric_limits::infinity(); - } - - const auto lanelet_point = lanelet::utils::conversion::toLaneletPoint(current_pose.position); - const auto to_object = lanelet::geometry::toArcCoordinates( - lanelet::utils::to2D(current_lanelet.centerline()), - lanelet::utils::to2D(lanelet_point).basicPoint()); - - for (const auto & element : current_lanelet.regulatoryElementsAs()) { - lanelet::ConstLineString3d lanelet_stop_lines = element->stopLine().get(); - - const auto to_stop_line = lanelet::geometry::toArcCoordinates( - lanelet::utils::to2D(current_lanelet.centerline()), - lanelet::utils::to2D(lanelet_stop_lines).front().basicPoint()); - - const auto distance_object_to_stop_line = to_stop_line.length - to_object.length; - - if (distance_object_to_stop_line > 0.0) { - return distance_object_to_stop_line; - } - } - - double distance = lanelet::utils::getLaneletLength3d(current_lanelet); - - bool found_current_lane = false; - for (const auto & llt : lanelets) { - if (llt.id() == current_lanelet.id()) { - found_current_lane = true; - continue; - } - - if (!found_current_lane) { - continue; - } - - for (const auto & element : llt.regulatoryElementsAs()) { - lanelet::ConstLineString3d lanelet_stop_lines = element->stopLine().get(); - - const auto to_stop_line = lanelet::geometry::toArcCoordinates( - lanelet::utils::to2D(llt.centerline()), - lanelet::utils::to2D(lanelet_stop_lines).front().basicPoint()); - - return distance + to_stop_line.length - to_object.length; - } - - distance += lanelet::utils::getLaneletLength3d(llt); - } - - return std::numeric_limits::infinity(); -} - double getDistanceToNextIntersection( const Pose & current_pose, const lanelet::ConstLanelets & lanelets) { From a29c7da82355f265505b30d48a297dd798e2e3b5 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 7 Nov 2023 12:57:26 +0900 Subject: [PATCH 133/202] refactor(behavior_path_planner): add const to interface methods (#5497) rafactor(behavior_path_planner): add const to interface methods Signed-off-by: kosuke55 --- .../scene_module/scene_module_interface.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp index 7f24683e5680c..534594d93445c 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp @@ -289,7 +289,7 @@ class SceneModuleInterface return calcOffsetPose(dead_pose_.get(), base_link2front, 0.0, 0.0); } - void resetWallPoses() + void resetWallPoses() const { stop_pose_ = boost::none; slow_pose_ = boost::none; @@ -477,7 +477,7 @@ class SceneModuleInterface * @brief Return true if the activation command is received from the RTC interface. * If no RTC interface is registered, return true. */ - bool isActivated() + bool isActivated() const { if (rtc_interface_ptr_map_.empty()) { return true; From 3a70c88115eddde2455d01d971dadd499c8b273f Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Tue, 7 Nov 2023 16:35:38 +0900 Subject: [PATCH 134/202] fix(intersection): reduce path lanelet points (#5507) Signed-off-by: Mamoru Sobue --- .../src/util.cpp | 49 ++++++++++++++++--- .../src/util.hpp | 4 ++ .../utilization/util.hpp | 2 - .../src/utilization/util.cpp | 26 ---------- 4 files changed, 46 insertions(+), 35 deletions(-) diff --git a/planning/behavior_velocity_intersection_module/src/util.cpp b/planning/behavior_velocity_intersection_module/src/util.cpp index c27a2ad218ffb..7f76d538f0846 100644 --- a/planning/behavior_velocity_intersection_module/src/util.cpp +++ b/planning/behavior_velocity_intersection_module/src/util.cpp @@ -1463,6 +1463,37 @@ static lanelet::ConstLanelets getPrevLanelets( return previous_lanelets; } +// end inclusive +lanelet::ConstLanelet generatePathLanelet( + const PathWithLaneId & path, const size_t start_idx, const size_t end_idx, const double width, + const double interval) +{ + lanelet::Points3d lefts; + lanelet::Points3d rights; + for (size_t i = start_idx; i <= end_idx; ++i) { + const auto & p = path.points.at(i).point.pose; + if (start_idx < i && i != end_idx) { + const auto & p_prev = path.points.at(i - 1).point.pose; + if (tier4_autoware_utils::calcDistance2d(p_prev, p) < interval) { + continue; + } + } + const double yaw = tf2::getYaw(p.orientation); + const double x = p.position.x; + const double y = p.position.y; + const double left_x = x + width / 2 * std::sin(yaw); + const double left_y = y - width / 2 * std::cos(yaw); + const double right_x = x - width / 2 * std::sin(yaw); + const double right_y = y + width / 2 * std::cos(yaw); + lefts.emplace_back(lanelet::InvalId, left_x, left_y, p.position.z); + rights.emplace_back(lanelet::InvalId, right_x, right_y, p.position.z); + } + lanelet::LineString3d left = lanelet::LineString3d(lanelet::InvalId, lefts); + lanelet::LineString3d right = lanelet::LineString3d(lanelet::InvalId, rights); + + return lanelet::Lanelet(lanelet::InvalId, left, right); +} + std::optional generatePathLanelets( const lanelet::ConstLanelets & lanelets_on_path, const util::InterpolatedPathInfo & interpolated_path_info, const std::set & associative_ids, @@ -1472,6 +1503,8 @@ std::optional generatePathLanelets( const std::vector & attention_areas, const size_t closest_idx, const double width) { + static constexpr double path_lanelet_interval = 1.5; + const auto & assigned_lane_interval_opt = interpolated_path_info.lane_id_interval; if (!assigned_lane_interval_opt) { return std::nullopt; @@ -1488,13 +1521,13 @@ std::optional generatePathLanelets( const auto [assigned_lane_start, assigned_lane_end] = assigned_lane_interval; if (closest_idx > assigned_lane_start) { path_lanelets.all.push_back( - planning_utils::generatePathLanelet(path, assigned_lane_start, closest_idx, width)); + generatePathLanelet(path, assigned_lane_start, closest_idx, width, path_lanelet_interval)); } // ego_or_entry2exit const auto ego_or_entry_start = std::max(closest_idx, assigned_lane_start); path_lanelets.ego_or_entry2exit = - planning_utils::generatePathLanelet(path, ego_or_entry_start, assigned_lane_end, width); + generatePathLanelet(path, ego_or_entry_start, assigned_lane_end, width, path_lanelet_interval); path_lanelets.all.push_back(path_lanelets.ego_or_entry2exit); // next @@ -1503,7 +1536,8 @@ std::optional generatePathLanelets( const auto next_lane_interval_opt = findLaneIdsInterval(path, {next_id}); if (next_lane_interval_opt) { const auto [next_start, next_end] = next_lane_interval_opt.value(); - path_lanelets.next = planning_utils::generatePathLanelet(path, next_start, next_end, width); + path_lanelets.next = + generatePathLanelet(path, next_start, next_end, width, path_lanelet_interval); path_lanelets.all.push_back(path_lanelets.next.value()); } } @@ -1519,12 +1553,13 @@ std::optional generatePathLanelets( if (first_inside_conflicting_idx_opt && last_inside_conflicting_idx_opt) { const auto first_inside_conflicting_idx = first_inside_conflicting_idx_opt.value(); const auto last_inside_conflicting_idx = last_inside_conflicting_idx_opt.value().first; - lanelet::ConstLanelet conflicting_interval = planning_utils::generatePathLanelet( - path, first_inside_conflicting_idx, last_inside_conflicting_idx, width); + lanelet::ConstLanelet conflicting_interval = generatePathLanelet( + path, first_inside_conflicting_idx, last_inside_conflicting_idx, width, + path_lanelet_interval); path_lanelets.conflicting_interval_and_remaining.push_back(std::move(conflicting_interval)); if (last_inside_conflicting_idx < assigned_lane_end) { - lanelet::ConstLanelet remaining_interval = planning_utils::generatePathLanelet( - path, last_inside_conflicting_idx, assigned_lane_end, width); + lanelet::ConstLanelet remaining_interval = generatePathLanelet( + path, last_inside_conflicting_idx, assigned_lane_end, width, path_lanelet_interval); path_lanelets.conflicting_interval_and_remaining.push_back(std::move(remaining_interval)); } } diff --git a/planning/behavior_velocity_intersection_module/src/util.hpp b/planning/behavior_velocity_intersection_module/src/util.hpp index 11aab06ff1d94..2f204f06aac7c 100644 --- a/planning/behavior_velocity_intersection_module/src/util.hpp +++ b/planning/behavior_velocity_intersection_module/src/util.hpp @@ -159,6 +159,10 @@ double calcDistanceUntilIntersectionLanelet( const lanelet::ConstLanelet & assigned_lanelet, const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const size_t closest_idx); +lanelet::ConstLanelet generatePathLanelet( + const PathWithLaneId & path, const size_t start_idx, const size_t end_idx, const double width, + const double interval); + std::optional generatePathLanelets( const lanelet::ConstLanelets & lanelets_on_path, const util::InterpolatedPathInfo & interpolated_path_info, const std::set & associative_ids, diff --git a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/utilization/util.hpp b/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/utilization/util.hpp index ceba86c27f864..86273b1e35e1d 100644 --- a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/utilization/util.hpp +++ b/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/utilization/util.hpp @@ -100,8 +100,6 @@ geometry_msgs::msg::Pose getAheadPose( const autoware_auto_planning_msgs::msg::PathWithLaneId & path); Polygon2d generatePathPolygon( const PathWithLaneId & path, const size_t start_idx, const size_t end_idx, const double width); -lanelet::ConstLanelet generatePathLanelet( - const PathWithLaneId & path, const size_t start_idx, const size_t end_idx, const double width); double calcJudgeLineDistWithAccLimit( const double velocity, const double max_stop_acceleration, const double delay_response_time); diff --git a/planning/behavior_velocity_planner_common/src/utilization/util.cpp b/planning/behavior_velocity_planner_common/src/utilization/util.cpp index a3a5a8a169759..85ceea0d391cc 100644 --- a/planning/behavior_velocity_planner_common/src/utilization/util.cpp +++ b/planning/behavior_velocity_planner_common/src/utilization/util.cpp @@ -356,32 +356,6 @@ Polygon2d generatePathPolygon( return ego_area; } -lanelet::ConstLanelet generatePathLanelet( - const PathWithLaneId & path, const size_t start_idx, const size_t end_idx, const double width) -{ - lanelet::Points3d lefts; - for (size_t i = start_idx; i <= end_idx; ++i) { - const double yaw = tf2::getYaw(path.points.at(i).point.pose.orientation); - const double x = path.points.at(i).point.pose.position.x + width / 2 * std::sin(yaw); - const double y = path.points.at(i).point.pose.position.y - width / 2 * std::cos(yaw); - const lanelet::Point3d p(lanelet::InvalId, x, y, path.points.at(i).point.pose.position.z); - lefts.emplace_back(p); - } - lanelet::LineString3d left = lanelet::LineString3d(lanelet::InvalId, lefts); - - lanelet::Points3d rights; - for (size_t i = start_idx; i <= end_idx; ++i) { - const double yaw = tf2::getYaw(path.points.at(i).point.pose.orientation); - const double x = path.points.at(i).point.pose.position.x - width / 2 * std::sin(yaw); - const double y = path.points.at(i).point.pose.position.y + width / 2 * std::cos(yaw); - const lanelet::Point3d p(lanelet::InvalId, x, y, path.points.at(i).point.pose.position.z); - rights.emplace_back(p); - } - lanelet::LineString3d right = lanelet::LineString3d(lanelet::InvalId, rights); - - return lanelet::Lanelet(lanelet::InvalId, left, right); -} - double calcJudgeLineDistWithAccLimit( const double velocity, const double max_stop_acceleration, const double delay_response_time) { From 55c615c410b22ce2276f2603a2b2c1c493cdc860 Mon Sep 17 00:00:00 2001 From: KokiAoki <81670028+KOKIAOKI@users.noreply.github.com> Date: Tue, 7 Nov 2023 16:43:15 +0900 Subject: [PATCH 135/202] feat(ndt_scan_matcher): estimate NDT covariance in real-time with limited initial positions (#5338) * add covariance estiamtion * fix: msg * fix: typo * fix: yaml * fix * Update localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp Initialize Eigen::Vector2d Co-authored-by: Kento Yabuuchi * fix: vector initilization, add: explanation in README Signed-off-by: Koki Aoki * fix: initialization and some build errors * refactor: variable and function names, changed covariance calculation process Signed-off-by: Koki Aoki * fix: README explanation Signed-off-by: Koki Aoki * fix: functionalization of eigenvector calculation, README empty line Signed-off-by: Koki Aoki * add warning outputs, rename function, move two functions in util.cpp to ndt_scan_matcher.cpp, fix README line Signed-off-by: Koki Aoki * fix: format of markdown * fix: add space in readme --------- Signed-off-by: Koki Aoki Co-authored-by: Kento Yabuuchi --- localization/ndt_scan_matcher/README.md | 25 +++ .../config/ndt_scan_matcher.param.yaml | 8 + .../ndt_scan_matcher_core.hpp | 11 +- .../src/ndt_scan_matcher_core.cpp | 143 +++++++++++++++++- 4 files changed, 178 insertions(+), 9 deletions(-) diff --git a/localization/ndt_scan_matcher/README.md b/localization/ndt_scan_matcher/README.md index e210d3a28796f..d7a7b1c5c37f3 100644 --- a/localization/ndt_scan_matcher/README.md +++ b/localization/ndt_scan_matcher/README.md @@ -34,6 +34,8 @@ One optional function is regularization. Please see the regularization chapter i | `points_aligned` | `sensor_msgs::msg::PointCloud2` | [debug topic] pointcloud aligned by scan matching | | `points_aligned_no_ground` | `sensor_msgs::msg::PointCloud2` | [debug topic] de-grounded pointcloud aligned by scan matching | | `initial_pose_with_covariance` | `geometry_msgs::msg::PoseWithCovarianceStamped` | [debug topic] initial pose used in scan matching | +| `multi_ndt_pose` | `geometry_msgs::msg::PoseArray` | [debug topic] estimated poses from multiple initial poses in real-time covariance estimation | +| `multi_initial_pose` | `geometry_msgs::msg::PoseArray` | [debug topic] initial poses for real-time covariance estimation | | `exe_time_ms` | `tier4_debug_msgs::msg::Float32Stamped` | [debug topic] execution time for scan matching [ms] | | `transform_probability` | `tier4_debug_msgs::msg::Float32Stamped` | [debug topic] score of scan matching | | `no_ground_transform_probability` | `tier4_debug_msgs::msg::Float32Stamped` | [debug topic] score of scan matching based on de-grounded LiDAR scan | @@ -257,3 +259,26 @@ This is a function that uses de-grounded LiDAR scan to estimate the scan matchin | ------------------------------------- | ------ | ------------------------------------------------------------------------------------- | | `estimate_scores_for_degrounded_scan` | bool | Flag for using scan matching score based on de-grounded LiDAR scan (FALSE by default) | | `z_margin_for_ground_removal` | double | Z-value margin for removal ground points | + +## 2D real-time covariance estimation + +### Abstract + +Calculate 2D covariance (xx, xy, yx, yy) in real time using the NDT convergence from multiple initial poses. +The arrangement of multiple initial poses is efficiently limited by the Hessian matrix of the NDT score function. +In this implementation, the number of initial positions is fixed to simplify the code. +The covariance can be seen as error ellipse from ndt_pose_with_covariance setting on rviz2. +[original paper](https://www.fujipress.jp/jrm/rb/robot003500020435/). + +Note that this function may spoil healthy system behavior if it consumes much calculation resources. + +### Parameters + +initial_pose_offset_model is rotated around (x,y) = (0,0) in the direction of the first principal component of the Hessian matrix. +initial_pose_offset_model_x & initial_pose_offset_model_y must have the same number of elements. + +| Name | Type | Description | +| ----------------------------- | ------------------- | ----------------------------------------------------------------- | +| `use_covariance_estimation` | bool | Flag for using real-time covariance estimation (FALSE by default) | +| `initial_pose_offset_model_x` | std::vector | X-axis offset [m] | +| `initial_pose_offset_model_y` | std::vector | Y-axis offset [m] | diff --git a/localization/ndt_scan_matcher/config/ndt_scan_matcher.param.yaml b/localization/ndt_scan_matcher/config/ndt_scan_matcher.param.yaml index 0ba1b1a2e15f4..1a6c26cd9c351 100644 --- a/localization/ndt_scan_matcher/config/ndt_scan_matcher.param.yaml +++ b/localization/ndt_scan_matcher/config/ndt_scan_matcher.param.yaml @@ -72,6 +72,14 @@ 0.0, 0.0, 0.0, 0.0, 0.0, 0.000625, ] + # 2D Real-time covariance estimation with multiple searches (output_pose_covariance is the minimum value) + use_covariance_estimation: false + + # Offset arrangement in covariance estimation [m] + # initial_pose_offset_model_x & initial_pose_offset_model_y must have the same number of elements. + initial_pose_offset_model_x: [0.0, 0.0, 0.5, -0.5, 1.0, -1.0] + initial_pose_offset_model_y: [0.5, -0.5, 0.0, 0.0, 0.0, 0.0] + # Regularization switch regularization_enabled: false diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp index 09fc08a97a3ac..9eb62230dad9e 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp @@ -25,6 +25,7 @@ #include #include +#include #include #include #include @@ -105,7 +106,7 @@ class NDTScanMatcher : public rclcpp::Node const rclcpp::Time & sensor_ros_time, const geometry_msgs::msg::Pose & result_pose_msg); void publish_pose( const rclcpp::Time & sensor_ros_time, const geometry_msgs::msg::Pose & result_pose_msg, - const bool is_converged); + const std::array & ndt_covariance, const bool is_converged); void publish_point_cloud( const rclcpp::Time & sensor_ros_time, const std::string & frame_id, const pcl::shared_ptr> & sensor_points_in_map_ptr); @@ -123,6 +124,10 @@ class NDTScanMatcher : public rclcpp::Node bool validate_converged_param( const double & transform_probability, const double & nearest_voxel_transformation_likelihood); + std::array estimate_covariance( + const pclomp::NdtResult & ndt_result, const Eigen::Matrix4f & initial_pose_matrix, + const rclcpp::Time & sensor_ros_time); + std::optional interpolate_regularization_pose( const rclcpp::Time & sensor_ros_time); void add_regularization_pose(const rclcpp::Time & sensor_ros_time); @@ -141,6 +146,8 @@ class NDTScanMatcher : public rclcpp::Node ndt_pose_with_covariance_pub_; rclcpp::Publisher::SharedPtr initial_pose_with_covariance_pub_; + rclcpp::Publisher::SharedPtr multi_ndt_pose_pub_; + rclcpp::Publisher::SharedPtr multi_initial_pose_pub_; rclcpp::Publisher::SharedPtr exe_time_pub_; rclcpp::Publisher::SharedPtr transform_probability_pub_; rclcpp::Publisher::SharedPtr @@ -187,6 +194,8 @@ class NDTScanMatcher : public rclcpp::Node double initial_pose_distance_tolerance_m_; float inversion_vector_threshold_; float oscillation_threshold_; + bool use_cov_estimation_; + std::vector initial_pose_offset_model_; std::array output_pose_covariance_; std::deque diff --git a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp index ac30b09df1c8e..cb66998147220 100644 --- a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp +++ b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp @@ -53,6 +53,32 @@ tier4_debug_msgs::msg::Int32Stamped make_int32_stamped( return tier4_debug_msgs::build().stamp(stamp).data(data); } +std::vector create_initial_pose_offset_model( + const std::vector & x, const std::vector & y) +{ + int size = x.size(); + std::vector initial_pose_offset_model(size); + for (int i = 0; i < size; i++) { + initial_pose_offset_model[i].x() = x[i]; + initial_pose_offset_model[i].y() = y[i]; + } + + return initial_pose_offset_model; +} + +Eigen::Matrix2d find_rotation_matrix_aligning_covariance_to_principal_axes( + const Eigen::Matrix2d & matrix) +{ + const Eigen::SelfAdjointEigenSolver eigensolver(matrix); + if (eigensolver.info() == Eigen::Success) { + const Eigen::Vector2d eigen_vec = eigensolver.eigenvectors().col(0); + const double th = std::atan2(eigen_vec.y(), eigen_vec.x()); + return Eigen::Rotation2Dd(th).toRotationMatrix(); + } else { + throw std::runtime_error("Eigen solver failed. Return output_pose_covariance value."); + } +} + bool validate_local_optimal_solution_oscillation( const std::vector & result_pose_msg_array, const float oscillation_threshold, const float inversion_vector_threshold) @@ -141,6 +167,24 @@ NDTScanMatcher::NDTScanMatcher() initial_pose_distance_tolerance_m_ = this->declare_parameter("initial_pose_distance_tolerance_m"); + use_cov_estimation_ = this->declare_parameter("use_covariance_estimation"); + if (use_cov_estimation_) { + std::vector initial_pose_offset_model_x = + this->declare_parameter>("initial_pose_offset_model_x"); + std::vector initial_pose_offset_model_y = + this->declare_parameter>("initial_pose_offset_model_y"); + + if (initial_pose_offset_model_x.size() == initial_pose_offset_model_y.size()) { + initial_pose_offset_model_ = + create_initial_pose_offset_model(initial_pose_offset_model_x, initial_pose_offset_model_y); + } else { + RCLCPP_WARN( + get_logger(), + "Invalid initial pose offset model parameters. Disable covariance estimation."); + use_cov_estimation_ = false; + } + } + std::vector output_pose_covariance = this->declare_parameter>("output_pose_covariance"); for (std::size_t i = 0; i < output_pose_covariance.size(); ++i) { @@ -191,6 +235,9 @@ NDTScanMatcher::NDTScanMatcher() initial_pose_with_covariance_pub_ = this->create_publisher( "initial_pose_with_covariance", 10); + multi_ndt_pose_pub_ = this->create_publisher("multi_ndt_pose", 10); + multi_initial_pose_pub_ = + this->create_publisher("multi_initial_pose", 10); exe_time_pub_ = this->create_publisher("exe_time_ms", 10); transform_probability_pub_ = this->create_publisher("transform_probability", 10); @@ -437,11 +484,6 @@ void NDTScanMatcher::callback_sensor_points( const pclomp::NdtResult ndt_result = ndt_ptr_->getResult(); (*state_ptr_)["state"] = "Sleeping"; - const auto exe_end_time = std::chrono::system_clock::now(); - const auto duration_micro_sec = - std::chrono::duration_cast(exe_end_time - exe_start_time).count(); - const auto exe_time = static_cast(duration_micro_sec) / 1000.0f; - const geometry_msgs::msg::Pose result_pose_msg = matrix4f_to_pose(ndt_result.pose); std::vector transformation_msg_array; for (const auto & pose_matrix : ndt_result.transformation_array) { @@ -468,6 +510,19 @@ void NDTScanMatcher::callback_sensor_points( RCLCPP_WARN(get_logger(), "Not Converged"); } + // covariance estimation + std::array ndt_covariance = output_pose_covariance_; + if (is_converged && use_cov_estimation_) { + const auto estimated_covariance = + estimate_covariance(ndt_result, initial_pose_matrix, sensor_ros_time); + ndt_covariance = estimated_covariance; + } + + const auto exe_end_time = std::chrono::system_clock::now(); + const auto duration_micro_sec = + std::chrono::duration_cast(exe_end_time - exe_start_time).count(); + const auto exe_time = static_cast(duration_micro_sec) / 1000.0f; + // publish initial_pose_with_covariance_pub_->publish(interpolator.get_current_pose()); exe_time_pub_->publish(make_float32_stamped(sensor_ros_time, exe_time)); @@ -477,7 +532,7 @@ void NDTScanMatcher::callback_sensor_points( make_float32_stamped(sensor_ros_time, ndt_result.nearest_voxel_transformation_likelihood)); iteration_num_pub_->publish(make_int32_stamped(sensor_ros_time, ndt_result.iteration_num)); publish_tf(sensor_ros_time, result_pose_msg); - publish_pose(sensor_ros_time, result_pose_msg, is_converged); + publish_pose(sensor_ros_time, result_pose_msg, ndt_covariance, is_converged); publish_marker(sensor_ros_time, transformation_msg_array); publish_initial_to_result( sensor_ros_time, result_pose_msg, interpolator.get_current_pose(), interpolator.get_old_pose(), @@ -560,7 +615,7 @@ void NDTScanMatcher::publish_tf( void NDTScanMatcher::publish_pose( const rclcpp::Time & sensor_ros_time, const geometry_msgs::msg::Pose & result_pose_msg, - const bool is_converged) + const std::array & ndt_covariance, const bool is_converged) { geometry_msgs::msg::PoseStamped result_pose_stamped_msg; result_pose_stamped_msg.header.stamp = sensor_ros_time; @@ -571,7 +626,7 @@ void NDTScanMatcher::publish_pose( result_pose_with_cov_msg.header.stamp = sensor_ros_time; result_pose_with_cov_msg.header.frame_id = map_frame_; result_pose_with_cov_msg.pose.pose = result_pose_msg; - result_pose_with_cov_msg.pose.covariance = output_pose_covariance_; + result_pose_with_cov_msg.pose.covariance = ndt_covariance; if (is_converged) { ndt_pose_pub_->publish(result_pose_stamped_msg); @@ -694,6 +749,78 @@ bool NDTScanMatcher::validate_converged_param( return is_ok_converged_param; } +std::array NDTScanMatcher::estimate_covariance( + const pclomp::NdtResult & ndt_result, const Eigen::Matrix4f & initial_pose_matrix, + const rclcpp::Time & sensor_ros_time) +{ + Eigen::Matrix2d rot = Eigen::Matrix2d::Identity(); + try { + rot = find_rotation_matrix_aligning_covariance_to_principal_axes( + ndt_result.hessian.inverse().block(0, 0, 2, 2)); + } catch (const std::exception & e) { + RCLCPP_WARN(get_logger(), e.what()); + return output_pose_covariance_; + } + + // first result is added to mean + const int n = initial_pose_offset_model_.size() + 1; + const Eigen::Vector2d ndt_pose_2d(ndt_result.pose(0, 3), ndt_result.pose(1, 3)); + Eigen::Vector2d mean = ndt_pose_2d; + std::vector ndt_pose_2d_vec; + ndt_pose_2d_vec.reserve(n); + ndt_pose_2d_vec.emplace_back(ndt_pose_2d); + + geometry_msgs::msg::PoseArray multi_ndt_result_msg; + geometry_msgs::msg::PoseArray multi_initial_pose_msg; + multi_ndt_result_msg.header.stamp = sensor_ros_time; + multi_ndt_result_msg.header.frame_id = map_frame_; + multi_initial_pose_msg.header.stamp = sensor_ros_time; + multi_initial_pose_msg.header.frame_id = map_frame_; + multi_ndt_result_msg.poses.push_back(matrix4f_to_pose(ndt_result.pose)); + multi_initial_pose_msg.poses.push_back(matrix4f_to_pose(initial_pose_matrix)); + + // multiple searches + for (const auto & pose_offset : initial_pose_offset_model_) { + const Eigen::Vector2d rotated_pose_offset_2d = rot * pose_offset; + + Eigen::Matrix4f sub_initial_pose_matrix(Eigen::Matrix4f::Identity()); + sub_initial_pose_matrix = ndt_result.pose; + sub_initial_pose_matrix(0, 3) += static_cast(rotated_pose_offset_2d.x()); + sub_initial_pose_matrix(1, 3) += static_cast(rotated_pose_offset_2d.y()); + + auto sub_output_cloud = std::make_shared>(); + ndt_ptr_->align(*sub_output_cloud, sub_initial_pose_matrix); + const Eigen::Matrix4f sub_ndt_result = ndt_ptr_->getResult().pose; + + const Eigen::Vector2d sub_ndt_pose_2d = sub_ndt_result.topRightCorner<2, 1>().cast(); + mean += sub_ndt_pose_2d; + ndt_pose_2d_vec.emplace_back(sub_ndt_pose_2d); + + multi_ndt_result_msg.poses.push_back(matrix4f_to_pose(sub_ndt_result)); + multi_initial_pose_msg.poses.push_back(matrix4f_to_pose(sub_initial_pose_matrix)); + } + + // calculate the covariance matrix + mean /= n; + Eigen::Matrix2d pca_covariance = Eigen::Matrix2d::Zero(); + for (const auto & temp_ndt_pose_2d : ndt_pose_2d_vec) { + const Eigen::Vector2d diff_2d = temp_ndt_pose_2d - mean; + pca_covariance += diff_2d * diff_2d.transpose(); + } + pca_covariance /= (n - 1); // unbiased covariance + + std::array ndt_covariance = output_pose_covariance_; + ndt_covariance[0 + 6 * 0] += pca_covariance(0, 0); + ndt_covariance[1 + 6 * 0] += pca_covariance(1, 0); + ndt_covariance[0 + 6 * 1] += pca_covariance(0, 1); + ndt_covariance[1 + 6 * 1] += pca_covariance(1, 1); + + multi_ndt_pose_pub_->publish(multi_ndt_result_msg); + multi_initial_pose_pub_->publish(multi_initial_pose_msg); + + return ndt_covariance; +} + std::optional NDTScanMatcher::interpolate_regularization_pose( const rclcpp::Time & sensor_ros_time) { From f357bd31ab78d213fc11c0fadac28cf7ff599746 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 7 Nov 2023 17:29:56 +0900 Subject: [PATCH 136/202] refactor(tier4_planning_launch): use xml style launch (#5502) * refactor(tier4_planning_launch): use xml style launch Signed-off-by: satoshi-ota * refactor(tier4_planning_launch): remove python style launch Signed-off-by: satoshi-ota * fix(tier4_planning_launch): enable console output Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../behavior_planning.launch.xml | 2 +- .../motion_planning.launch.xml | 2 +- .../scenario_planning/parking.launch.py | 160 ------------------ .../scenario_planning/parking.launch.xml | 58 ++++--- .../scenario_planning.launch.xml | 4 +- 5 files changed, 36 insertions(+), 190 deletions(-) delete mode 100644 launch/tier4_planning_launch/launch/scenario_planning/parking.launch.py diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml index 4df5152e2ebce..085dc92982663 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml @@ -5,7 +5,7 @@ - + diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml index 45fa85f0d77fb..577b0e00d133c 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml @@ -2,7 +2,7 @@ - + diff --git a/launch/tier4_planning_launch/launch/scenario_planning/parking.launch.py b/launch/tier4_planning_launch/launch/scenario_planning/parking.launch.py deleted file mode 100644 index 7dfcbb0307bf0..0000000000000 --- a/launch/tier4_planning_launch/launch/scenario_planning/parking.launch.py +++ /dev/null @@ -1,160 +0,0 @@ -# Copyright 2021 Tier IV, Inc. All rights reserved. -# -# 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 launch -from launch.actions import DeclareLaunchArgument -from launch.actions import GroupAction -from launch.actions import OpaqueFunction -from launch.actions import SetLaunchConfiguration -from launch.conditions import IfCondition -from launch.conditions import UnlessCondition -from launch.substitutions import LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer -from launch_ros.actions import PushRosNamespace -from launch_ros.descriptions import ComposableNode -from launch_ros.substitutions import FindPackageShare -import yaml - - -def launch_setup(context, *args, **kwargs): - vehicle_info_param_path = LaunchConfiguration("vehicle_param_file").perform(context) - with open(vehicle_info_param_path, "r") as f: - vehicle_info_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - with open(LaunchConfiguration("freespace_planner_param_path").perform(context), "r") as f: - freespace_planner_param = yaml.safe_load(f)["/**"]["ros__parameters"] - - container = ComposableNodeContainer( - name="parking_container", - namespace="", - package="rclcpp_components", - executable=LaunchConfiguration("container_executable"), - composable_node_descriptions=[ - ComposableNode( - package="costmap_generator", - plugin="CostmapGenerator", - name="costmap_generator", - remappings=[ - ("~/input/objects", "/perception/object_recognition/objects"), - ( - "~/input/points_no_ground", - "/perception/obstacle_segmentation/pointcloud", - ), - ("~/input/vector_map", "/map/vector_map"), - ("~/input/scenario", "/planning/scenario_planning/scenario"), - ("~/output/grid_map", "costmap_generator/grid_map"), - ("~/output/occupancy_grid", "costmap_generator/occupancy_grid"), - ], - parameters=[ - { - "costmap_frame": "map", - "vehicle_frame": "base_link", - "map_frame": "map", - "update_rate": 10.0, - "activate_by_scenario": False, - "grid_min_value": 0.0, - "grid_max_value": 1.0, - "grid_resolution": 0.2, - "grid_length_x": 70.0, - "grid_length_y": 70.0, - "grid_position_x": 0.0, - "grid_position_y": 0.0, - "maximum_lidar_height_thres": 0.3, - "minimum_lidar_height_thres": -2.2, - "use_wayarea": True, - "use_parkinglot": True, - "use_objects": True, - "use_points": True, - "expand_polygon_size": 1.0, - "size_of_expansion_kernel": 9, - }, - vehicle_info_param, - ], - extra_arguments=[ - {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} - ], - ), - ComposableNode( - package="freespace_planner", - plugin="freespace_planner::FreespacePlannerNode", - name="freespace_planner", - remappings=[ - ("~/input/route", "/planning/mission_planning/route"), - ("~/input/occupancy_grid", "costmap_generator/occupancy_grid"), - ("~/input/scenario", "/planning/scenario_planning/scenario"), - ("~/input/odometry", "/localization/kinematic_state"), - ("~/output/trajectory", "/planning/scenario_planning/parking/trajectory"), - ("is_completed", "/planning/scenario_planning/parking/is_completed"), - ], - parameters=[ - freespace_planner_param, - vehicle_info_param, - ], - extra_arguments=[ - {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} - ], - ), - ], - ) - - group = GroupAction( - [ - PushRosNamespace("parking"), - container, - ] - ) - - return [group] - - -def generate_launch_description(): - launch_arguments = [] - - def add_launch_arg(name: str, default_value=None, description=None): - launch_arguments.append( - DeclareLaunchArgument(name, default_value=default_value, description=description) - ) - - add_launch_arg( - "vehicle_param_file", - [ - FindPackageShare("vehicle_info_util"), - "/config/vehicle_info.param.yaml", - ], - "path to the parameter file of vehicle information", - ) - - # component - add_launch_arg("use_intra_process", "false", "use ROS 2 component container communication") - add_launch_arg("use_multithread", "false", "use multithread") - - set_container_executable = SetLaunchConfiguration( - "container_executable", - "component_container", - condition=UnlessCondition(LaunchConfiguration("use_multithread")), - ) - set_container_mt_executable = SetLaunchConfiguration( - "container_executable", - "component_container_mt", - condition=IfCondition(LaunchConfiguration("use_multithread")), - ) - - return launch.LaunchDescription( - launch_arguments - + [ - set_container_executable, - set_container_mt_executable, - ] - + [OpaqueFunction(function=launch_setup)] - ) diff --git a/launch/tier4_planning_launch/launch/scenario_planning/parking.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/parking.launch.xml index 741df95937c42..98315919b540a 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/parking.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/parking.launch.xml @@ -1,32 +1,38 @@ - - - + - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 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 8c015892d06b5..66c90ef2ff833 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 @@ -54,8 +54,8 @@ - - + + From 338e1e45afe904ed3e23d545089d3fe91f7cb66a Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 7 Nov 2023 18:04:27 +0900 Subject: [PATCH 137/202] fix(avoidance): fix avoidance return dead point calculation logic for high curverture path (#5489) Signed-off-by: satoshi-ota --- .../src/scene_module/avoidance/avoidance_module.cpp | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) 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 9e4a3a928c4ca..99093b465d154 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 @@ -2902,8 +2902,15 @@ void AvoidanceModule::insertReturnDeadLine( return; } + // Consider the difference in path length between the shifted path and original path (the path + // that is shifted inward has a shorter distance to the end of the path than the other one.) + const auto & to_reference_path_end = data.arclength_from_ego.back(); + const auto to_shifted_path_end = calcSignedArcLength( + shifted_path.path.points, getEgoPosition(), shifted_path.path.points.size() - 1); + const auto buffer = std::max(0.0, to_shifted_path_end - to_reference_path_end); + const auto min_return_distance = helper_.getMinAvoidanceDistance(shift_length); - const auto to_stop_line = data.to_return_point - min_return_distance; + const auto to_stop_line = data.to_return_point - min_return_distance - buffer; // If we don't need to consider deceleration constraints, insert a deceleration point // and return immediately From 60a5d558218560cfa29de27fad2b0dbbfeda4c9c Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Tue, 7 Nov 2023 18:06:36 +0900 Subject: [PATCH 138/202] feat(eagleye): split fix2pose (#5506) * fix(eagleye): split fix2pose Signed-off-by: kminoda * style(pre-commit): autofix * fix name: fuser -> fusion Signed-off-by: kminoda * update package.xml Signed-off-by: kminoda * style(pre-commit): autofix * fix typo Signed-off-by: kminoda --------- Signed-off-by: kminoda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../eagleye/eagleye_rt.launch.xml | 3 ++- ...launch.xml => geo_pose_converter.launch.xml} | 17 +++++------------ launch/tier4_localization_launch/package.xml | 3 ++- 3 files changed, 9 insertions(+), 14 deletions(-) rename launch/tier4_localization_launch/launch/pose_twist_estimator/eagleye/{fix2pose.launch.xml => geo_pose_converter.launch.xml} (55%) diff --git a/launch/tier4_localization_launch/launch/pose_twist_estimator/eagleye/eagleye_rt.launch.xml b/launch/tier4_localization_launch/launch/pose_twist_estimator/eagleye/eagleye_rt.launch.xml index b04124d7e981e..12d84f374f7c7 100644 --- a/launch/tier4_localization_launch/launch/pose_twist_estimator/eagleye/eagleye_rt.launch.xml +++ b/launch/tier4_localization_launch/launch/pose_twist_estimator/eagleye/eagleye_rt.launch.xml @@ -145,7 +145,8 @@ - + + diff --git a/launch/tier4_localization_launch/launch/pose_twist_estimator/eagleye/fix2pose.launch.xml b/launch/tier4_localization_launch/launch/pose_twist_estimator/eagleye/geo_pose_converter.launch.xml similarity index 55% rename from launch/tier4_localization_launch/launch/pose_twist_estimator/eagleye/fix2pose.launch.xml rename to launch/tier4_localization_launch/launch/pose_twist_estimator/eagleye/geo_pose_converter.launch.xml index ac92fce40cd6a..d4f82e72a297b 100644 --- a/launch/tier4_localization_launch/launch/pose_twist_estimator/eagleye/fix2pose.launch.xml +++ b/launch/tier4_localization_launch/launch/pose_twist_estimator/eagleye/geo_pose_converter.launch.xml @@ -1,30 +1,23 @@ - - - + + + - + + - - - - - - - - diff --git a/launch/tier4_localization_launch/package.xml b/launch/tier4_localization_launch/package.xml index f00752d1c14fc..9a137032e1277 100644 --- a/launch/tier4_localization_launch/package.xml +++ b/launch/tier4_localization_launch/package.xml @@ -16,7 +16,8 @@ ar_tag_based_localizer automatic_pose_initializer - eagleye_fix2pose + eagleye_geo_pose_converter + eagleye_geo_pose_fusion eagleye_gnss_converter eagleye_rt ekf_localizer From 0d929d408eb3459962c9cd228421a826669705dc Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 7 Nov 2023 18:35:23 +0900 Subject: [PATCH 139/202] fix(avoidance): fix oncoming vehicle check logic (#5492) Signed-off-by: satoshi-ota --- .../path_safety_checker/path_safety_checker_parameters.hpp | 1 + .../src/scene_module/avoidance/avoidance_module.cpp | 7 +++++++ .../src/utils/path_safety_checker/objects_filtering.cpp | 1 + 3 files changed, 9 insertions(+) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp index dc113b0b0be18..3634586c40540 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp @@ -75,6 +75,7 @@ struct ExtendedPredictedObject geometry_msgs::msg::TwistWithCovariance initial_twist; geometry_msgs::msg::AccelWithCovariance initial_acceleration; autoware_auto_perception_msgs::msg::Shape shape; + std::vector classification; std::vector predicted_paths; }; using ExtendedPredictedObjects = std::vector; 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 99093b465d154..2ad0928696a5c 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 @@ -1967,7 +1967,14 @@ bool AvoidanceModule::isSafePath( const auto is_object_front = utils::path_safety_checker::isTargetObjectFront(getEgoPose(), obj_polygon, p.vehicle_info); + const auto & object_twist = object.initial_twist.twist; + const auto v_norm = std::hypot(object_twist.linear.x, object_twist.linear.y); + const auto object_type = utils::getHighestProbLabel(object.classification); + const auto object_parameter = parameters_->object_parameters.at(object_type); + const auto is_object_moving = v_norm > object_parameter.moving_speed_threshold; + const auto is_object_oncoming = + is_object_moving && utils::path_safety_checker::isTargetObjectOncoming(getEgoPose(), object.initial_pose.pose); const auto obj_predicted_paths = utils::path_safety_checker::getPredictedPathFromObj( 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 a7c604985de3a..f6644a4f91e8f 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 @@ -285,6 +285,7 @@ ExtendedPredictedObject transform( extended_object.initial_twist = object.kinematics.initial_twist_with_covariance; extended_object.initial_acceleration = object.kinematics.initial_acceleration_with_covariance; extended_object.shape = object.shape; + extended_object.classification = object.classification; const auto obj_velocity = extended_object.initial_twist.twist.linear.x; From eb08ad1841b9604a4907faa2e6c940bad74a533c Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Tue, 7 Nov 2023 20:07:57 +0900 Subject: [PATCH 140/202] refactor(lane_change): update state log (#5514) Signed-off-by: Muhammad Zulfaqar Azmi --- .../scene_module/lane_change/interface.cpp | 68 ++++++++----------- 1 file changed, 28 insertions(+), 40 deletions(-) diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp index be3b78803c4c6..7534c2c1fe45f 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp @@ -76,25 +76,35 @@ bool LaneChangeInterface::isExecutionReady() const ModuleStatus LaneChangeInterface::updateState() { + auto log_warn_throttled = [&](const std::string & message) -> void { + RCLCPP_WARN_STREAM_THROTTLE( + getLogger().get_child(module_type_->getModuleTypeStr()), *clock_, 5000, message); + }; + if (module_type_->specialExpiredCheck()) { + log_warn_throttled("expired check."); if (isWaitingApproval()) { return ModuleStatus::SUCCESS; } } if (!isActivated() || isWaitingApproval()) { + log_warn_throttled("Is idling."); return ModuleStatus::IDLE; } if (!module_type_->isValidPath()) { + log_warn_throttled("Is invalid path."); return ModuleStatus::SUCCESS; } if (module_type_->isAbortState()) { + log_warn_throttled("Ego is in the process of aborting lane change."); return module_type_->hasFinishedAbort() ? ModuleStatus::SUCCESS : ModuleStatus::RUNNING; } if (module_type_->hasFinishedLaneChange()) { + log_warn_throttled("Completed lane change."); return ModuleStatus::SUCCESS; } @@ -102,31 +112,29 @@ ModuleStatus LaneChangeInterface::updateState() setObjectDebugVisualization(); if (is_safe) { + log_warn_throttled("Lane change path is safe."); module_type_->toNormalState(); return ModuleStatus::RUNNING; } - if (!module_type_->isCancelEnabled()) { - RCLCPP_WARN_STREAM_THROTTLE( - getLogger().get_child(module_type_->getModuleTypeStr()), *clock_, 5000, - "Lane change path is unsafe but cancel was not enabled. Continue lane change."); + const auto change_state_if_stop_required = [&]() -> void { if (module_type_->isRequiredStop(is_object_coming_from_rear)) { module_type_->toStopState(); } else { module_type_->toNormalState(); } + }; + + if (!module_type_->isCancelEnabled()) { + log_warn_throttled( + "Lane change path is unsafe but cancel was not enabled. Continue lane change."); + change_state_if_stop_required(); return ModuleStatus::RUNNING; } if (!module_type_->isAbleToReturnCurrentLane()) { - RCLCPP_WARN_STREAM_THROTTLE( - getLogger().get_child(module_type_->getModuleTypeStr()), *clock_, 5000, - "Lane change path is unsafe but cannot return. Continue lane change."); - if (module_type_->isRequiredStop(is_object_coming_from_rear)) { - module_type_->toStopState(); - } else { - module_type_->toNormalState(); - } + log_warn_throttled("Lane change path is unsafe but cannot return. Continue lane change."); + change_state_if_stop_required(); return ModuleStatus::RUNNING; } @@ -134,53 +142,33 @@ ModuleStatus LaneChangeInterface::updateState() const auto threshold = common_parameters.backward_length_buffer_for_end_of_lane; const auto status = module_type_->getLaneChangeStatus(); if (module_type_->isNearEndOfCurrentLanes(status.current_lanes, status.target_lanes, threshold)) { - RCLCPP_WARN_STREAM_THROTTLE( - getLogger().get_child(module_type_->getModuleTypeStr()), *clock_, 5000, - "Lane change path is unsafe but near end of lane. Continue lane change."); - if (module_type_->isRequiredStop(is_object_coming_from_rear)) { - module_type_->toStopState(); - } else { - module_type_->toNormalState(); - } + log_warn_throttled("Lane change path is unsafe but near end of lane. Continue lane change."); + change_state_if_stop_required(); return ModuleStatus::RUNNING; } if (module_type_->isEgoOnPreparePhase() && module_type_->isAbleToReturnCurrentLane()) { - RCLCPP_WARN_STREAM_THROTTLE( - getLogger().get_child(module_type_->getModuleTypeStr()), *clock_, 5000, - "Lane change path is unsafe. Cancel lane change."); + log_warn_throttled("Lane change path is unsafe. Cancel lane change."); module_type_->toCancelState(); return isWaitingApproval() ? ModuleStatus::RUNNING : ModuleStatus::SUCCESS; } if (!module_type_->isAbortEnabled()) { - RCLCPP_WARN_STREAM_THROTTLE( - getLogger().get_child(module_type_->getModuleTypeStr()), *clock_, 5000, + log_warn_throttled( "Lane change path is unsafe but abort was not enabled. Continue lane change."); - if (module_type_->isRequiredStop(is_object_coming_from_rear)) { - module_type_->toStopState(); - } else { - module_type_->toNormalState(); - } + change_state_if_stop_required(); return ModuleStatus::RUNNING; } const auto found_abort_path = module_type_->getAbortPath(); if (!found_abort_path) { - RCLCPP_WARN_STREAM_THROTTLE( - getLogger().get_child(module_type_->getModuleTypeStr()), *clock_, 5000, + log_warn_throttled( "Lane change path is unsafe but not found abort path. Continue lane change."); - if (module_type_->isRequiredStop(is_object_coming_from_rear)) { - module_type_->toStopState(); - } else { - module_type_->toNormalState(); - } + change_state_if_stop_required(); return ModuleStatus::RUNNING; } - RCLCPP_WARN_STREAM_THROTTLE( - getLogger().get_child(module_type_->getModuleTypeStr()), *clock_, 5000, - "Lane change path is unsafe. Abort lane change."); + log_warn_throttled("Lane change path is unsafe. Abort lane change."); module_type_->toAbortState(); return ModuleStatus::RUNNING; } From 05396eae10b862f96b5c5924ba85e9be8f2aee49 Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Tue, 7 Nov 2023 22:09:37 +0900 Subject: [PATCH 141/202] fix(lane_change): do not cut abort path (#5509) * fix(lane_change): do not cut abort path Signed-off-by: Fumiya Watanabe * refactor(lane_change): move insert stop point Signed-off-by: Fumiya Watanabe --------- Signed-off-by: Fumiya Watanabe --- .../scene_module/lane_change/base_class.hpp | 2 +- .../scene_module/lane_change/normal.hpp | 2 +- .../scene_module/lane_change/interface.cpp | 3 +- .../src/scene_module/lane_change/normal.cpp | 80 ++++++++++--------- 4 files changed, 46 insertions(+), 41 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/base_class.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/base_class.hpp index 472564a061f04..daad5b1a40610 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/base_class.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/base_class.hpp @@ -107,7 +107,7 @@ class LaneChangeBase const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes, const double threshold) const = 0; - virtual bool getAbortPath() = 0; + virtual bool calcAbortPath() = 0; virtual bool specialRequiredCheck() const { return false; } diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp index dc9f44fbd53da..503542be7cda6 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp @@ -72,7 +72,7 @@ class NormalLaneChange : public LaneChangeBase TurnSignalInfo updateOutputTurnSignal() override; - bool getAbortPath() override; + bool calcAbortPath() override; PathSafetyStatus isApprovedPathSafe() const override; diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp index 7534c2c1fe45f..05b7c5d7dec92 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp @@ -160,7 +160,7 @@ ModuleStatus LaneChangeInterface::updateState() return ModuleStatus::RUNNING; } - const auto found_abort_path = module_type_->getAbortPath(); + const auto found_abort_path = module_type_->calcAbortPath(); if (!found_abort_path) { log_warn_throttled( "Lane change path is unsafe but not found abort path. Continue lane change."); @@ -195,7 +195,6 @@ BehaviorModuleOutput LaneChangeInterface::plan() auto output = module_type_->generateOutput(); path_reference_ = output.reference_path; *prev_approved_path_ = *getPreviousModuleOutput().path; - module_type_->insertStopPoint(module_type_->getLaneChangeStatus().target_lanes, *output.path); stop_pose_ = module_type_->getStopPose(); 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 f2c6782b3ef6e..5bffef1a4b421 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 @@ -127,38 +127,43 @@ bool NormalLaneChange::isLaneChangeRequired() const LaneChangePath NormalLaneChange::getLaneChangePath() const { - return isAbortState() ? *abort_path_ : status_.lane_change_path; + return status_.lane_change_path; } BehaviorModuleOutput NormalLaneChange::generateOutput() { BehaviorModuleOutput output; - output.path = std::make_shared(getLaneChangePath().path); - const auto found_extended_path = extendPath(); - if (found_extended_path) { - *output.path = utils::combinePath(*output.path, *found_extended_path); - } - extendOutputDrivableArea(output); - output.reference_path = std::make_shared(getReferencePath()); - output.turn_signal_info = updateOutputTurnSignal(); - - if (isAbortState()) { + if (isAbortState() && abort_path_) { + output.path = std::make_shared(abort_path_->path); output.reference_path = std::make_shared(prev_module_reference_path_); output.turn_signal_info = prev_turn_signal_info_; - return output; - } + insertStopPoint(status_.current_lanes, *output.path); + } else { + output.path = std::make_shared(getLaneChangePath().path); - if (isStopState()) { - const auto current_velocity = getEgoVelocity(); - const auto current_dist = calcSignedArcLength( - output.path->points, output.path->points.front().point.pose.position, getEgoPosition()); - const auto stop_dist = - -(current_velocity * current_velocity / (2.0 * planner_data_->parameters.min_acc)); - const auto stop_point = utils::insertStopPoint(stop_dist + current_dist, *output.path); - setStopPose(stop_point.point.pose); + const auto found_extended_path = extendPath(); + if (found_extended_path) { + *output.path = utils::combinePath(*output.path, *found_extended_path); + } + output.reference_path = std::make_shared(getReferencePath()); + output.turn_signal_info = updateOutputTurnSignal(); + + if (isStopState()) { + const auto current_velocity = getEgoVelocity(); + const auto current_dist = calcSignedArcLength( + output.path->points, output.path->points.front().point.pose.position, getEgoPosition()); + const auto stop_dist = + -(current_velocity * current_velocity / (2.0 * planner_data_->parameters.min_acc)); + const auto stop_point = utils::insertStopPoint(stop_dist + current_dist, *output.path); + setStopPose(stop_point.point.pose); + } else { + insertStopPoint(status_.target_lanes, *output.path); + } } + extendOutputDrivableArea(output); + const auto current_seg_idx = planner_data_->findEgoSegmentIndex(output.path->points); output.turn_signal_info = planner_data_->turn_signal_decider.use_prior_turn_signal( *output.path, getEgoPose(), current_seg_idx, prev_turn_signal_info_, output.turn_signal_info, @@ -1500,7 +1505,7 @@ bool NormalLaneChange::isRequiredStop(const bool is_object_coming_from_rear) con isAbleToStopSafely() && is_object_coming_from_rear; } -bool NormalLaneChange::getAbortPath() +bool NormalLaneChange::calcAbortPath() { const auto & route_handler = getRouteHandler(); const auto & common_param = getCommonParam(); @@ -1608,14 +1613,12 @@ bool NormalLaneChange::getAbortPath() reference_lanelets, shifted_path.path.points.at(abort_return_idx).point.pose); const PathWithLaneId reference_lane_segment = std::invoke([&]() { const double s_start = arc_position.length; - double s_end = std::max( - lanelet::utils::getLaneletLength2d(reference_lanelets) - minimum_lane_change_length, s_start); + double s_end = std::max(lanelet::utils::getLaneletLength2d(reference_lanelets), s_start); if (route_handler->isInGoalRouteSection(selected_path.info.target_lanes.back())) { const auto goal_arc_coordinates = lanelet::utils::getArcCoordinates(reference_lanelets, route_handler->getGoalPose()); - const double forward_length = - std::max(goal_arc_coordinates.length - minimum_lane_change_length, s_start); + const double forward_length = std::max(goal_arc_coordinates.length, s_start); s_end = std::min(s_end, forward_length); } PathWithLaneId ref = route_handler->getCenterLinePath(reference_lanelets, s_start, s_end, true); @@ -1625,20 +1628,23 @@ bool NormalLaneChange::getAbortPath() return ref; }); - PathWithLaneId start_to_abort_return_pose; - start_to_abort_return_pose.points.insert( - start_to_abort_return_pose.points.end(), shifted_path.path.points.begin(), - shifted_path.path.points.begin() + abort_return_idx); - if (reference_lane_segment.points.size() > 1) { - start_to_abort_return_pose.points.insert( - start_to_abort_return_pose.points.end(), (reference_lane_segment.points.begin() + 1), - reference_lane_segment.points.end()); - } - auto abort_path = selected_path; abort_path.shifted_path = shifted_path; - abort_path.path = start_to_abort_return_pose; abort_path.info.shift_line = shift_line; + + { + PathWithLaneId aborting_path; + aborting_path.points.insert( + aborting_path.points.begin(), shifted_path.path.points.begin(), + shifted_path.path.points.begin() + abort_return_idx); + + if (!reference_lane_segment.points.empty()) { + abort_path.path = utils::combinePath(aborting_path, reference_lane_segment); + } else { + abort_path.path = aborting_path; + } + } + abort_path_ = std::make_shared(abort_path); return true; } From df0b85734f4f1284cddc500f9f92dc7e228bb44a Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Wed, 8 Nov 2023 01:32:45 +0900 Subject: [PATCH 142/202] feat(behavior_path_planner): change execution requested condition (#5504) * refactor(start-planner-module): Improve code readability - Create separate methods to check if the module is running, if the start pose is on the middle of the road, if the vehicle has arrived at the start position, if the vehicle has arrived at the goal position, and if the vehicle is still moving. - Add a warning message if the goal is behind the ego vehicle within the same route segment. Signed-off-by: kyoichi-sugahara --------- Signed-off-by: kyoichi-sugahara --- .../start_planner/start_planner_module.hpp | 6 ++ .../goal_planner/goal_planner_module.cpp | 2 + .../start_planner/start_planner_module.cpp | 92 ++++++++++--------- .../behavior_path_planner/src/utils/utils.cpp | 3 + 4 files changed, 60 insertions(+), 43 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp index 206ca5ea080c3..8ea963fec0b8d 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp @@ -132,6 +132,12 @@ class StartPlannerModule : public SceneModuleInterface void initializeSafetyCheckParameters(); + bool isModuleRunning() const; + bool isCurrentPoseOnMiddleOfTheRoad() const; + bool isCloseToOriginalStartPose() const; + bool hasArrivedAtGoal() const; + bool isMoving() const; + PriorityOrder determinePriorityOrder( const std::string & search_priority, const size_t candidates_size); bool findPullOutPath( diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index 3c470cef2c935..6d34ce4ecde38 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -300,6 +300,8 @@ bool GoalPlannerModule::isExecutionRequested() const return true; } + // TODO(someone): if goal is behind of ego, do not execute goal_planner + const auto & route_handler = planner_data_->route_handler; const Pose & current_pose = planner_data_->self_odometry->pose.pose; const Pose goal_pose = route_handler->getOriginalGoalPose(); diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp index 622cc9e3b87ae..e3670710b64f0 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp @@ -145,41 +145,66 @@ void StartPlannerModule::updateData() bool StartPlannerModule::isExecutionRequested() const { - const Pose & current_pose = planner_data_->self_odometry->pose.pose; - const lanelet::ConstLanelets current_lanes = utils::getCurrentLanes(planner_data_); - const double lateral_distance_to_center_lane = - lanelet::utils::getArcCoordinates(current_lanes, current_pose).distance; - - if (std::abs(lateral_distance_to_center_lane) < parameters_->th_distance_to_middle_of_the_road) { - return false; + if (isModuleRunning()) { + return true; } - const Pose start_pose = planner_data_->route_handler->getOriginalStartPose(); + // Return false and do not request execution if any of the following conditions are true: + // - The start pose is on the middle of the road. + // - The vehicle has already arrived at the start position planner. + // - The vehicle has reached the goal position. + // - The vehicle is still moving. if ( - tier4_autoware_utils::calcDistance2d(start_pose.position, current_pose.position) > - parameters_->th_arrived_distance) { + isCurrentPoseOnMiddleOfTheRoad() || isCloseToOriginalStartPose() || hasArrivedAtGoal() || + isMoving()) { return false; } - // Check if ego arrives at goal - const Pose goal_pose = planner_data_->route_handler->getGoalPose(); - if ( - tier4_autoware_utils::calcDistance2d(goal_pose.position, current_pose.position) < - parameters_->th_arrived_distance) { + // Check if the goal is behind the ego vehicle within the same route segment. + if (IsGoalBehindOfEgoInSameRouteSegment()) { + RCLCPP_WARN_THROTTLE( + getLogger(), *clock_, 5000, "Start plan for a backward goal is not supported now"); return false; } - if (current_state_ == ModuleStatus::RUNNING) { - return true; - } + return true; +} - const bool is_stopped = utils::l2Norm(planner_data_->self_odometry->twist.twist.linear) < - parameters_->th_stopped_velocity; - if (!is_stopped) { - return false; - } +bool StartPlannerModule::isModuleRunning() const +{ + return current_state_ == ModuleStatus::RUNNING; +} - return true; +bool StartPlannerModule::isCurrentPoseOnMiddleOfTheRoad() const +{ + const Pose & current_pose = planner_data_->self_odometry->pose.pose; + const lanelet::ConstLanelets current_lanes = utils::getCurrentLanes(planner_data_); + const double lateral_distance_to_center_lane = + lanelet::utils::getArcCoordinates(current_lanes, current_pose).distance; + + return std::abs(lateral_distance_to_center_lane) < parameters_->th_distance_to_middle_of_the_road; +} + +bool StartPlannerModule::isCloseToOriginalStartPose() const +{ + const Pose start_pose = planner_data_->route_handler->getOriginalStartPose(); + return tier4_autoware_utils::calcDistance2d( + start_pose.position, planner_data_->self_odometry->pose.pose.position) > + parameters_->th_arrived_distance; +} + +bool StartPlannerModule::hasArrivedAtGoal() const +{ + const Pose goal_pose = planner_data_->route_handler->getGoalPose(); + return tier4_autoware_utils::calcDistance2d( + goal_pose.position, planner_data_->self_odometry->pose.pose.position) < + parameters_->th_arrived_distance; +} + +bool StartPlannerModule::isMoving() const +{ + return utils::l2Norm(planner_data_->self_odometry->twist.twist.linear) >= + parameters_->th_stopped_velocity; } bool StartPlannerModule::isExecutionReady() const @@ -234,15 +259,6 @@ void StartPlannerModule::updateCurrentState() BehaviorModuleOutput StartPlannerModule::plan() { - if (IsGoalBehindOfEgoInSameRouteSegment()) { - RCLCPP_WARN_THROTTLE( - getLogger(), *clock_, 5000, "Start plan for a backward goal is not supported now"); - const auto output = generateStopOutput(); - setDebugData(); // use status updated in generateStopOutput() - updateRTCStatus(0, 0); - return output; - } - if (isWaitingApproval()) { clearWaitingApproval(); resetPathCandidate(); @@ -385,16 +401,6 @@ BehaviorModuleOutput StartPlannerModule::planWaitingApproval() { updatePullOutStatus(); - if (IsGoalBehindOfEgoInSameRouteSegment()) { - RCLCPP_WARN_THROTTLE( - getLogger(), *clock_, 5000, "Start plan for a backward goal is not supported now"); - clearWaitingApproval(); - const auto output = generateStopOutput(); - setDebugData(); // use status updated in generateStopOutput() - updateRTCStatus(0, 0); - return output; - } - BehaviorModuleOutput output; if (!status_.found_pull_out_path) { RCLCPP_WARN_THROTTLE( diff --git a/planning/behavior_path_planner/src/utils/utils.cpp b/planning/behavior_path_planner/src/utils/utils.cpp index 93f74e670ecdd..62a48da85ba2c 100644 --- a/planning/behavior_path_planner/src/utils/utils.cpp +++ b/planning/behavior_path_planner/src/utils/utils.cpp @@ -974,6 +974,9 @@ BehaviorModuleOutput createGoalAroundPath(const std::shared_ptr(reference_path); output.reference_path = std::make_shared(reference_path); output.drivable_area_info.drivable_lanes = drivable_lanes; From e02ec1b818b7fb8b0955ddbaab43e156428114a7 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Wed, 8 Nov 2023 10:14:36 +0900 Subject: [PATCH 143/202] fix(intersection): replace with findFirstNearestIndexWithSoftConstraints (#5508) --- .../src/util.cpp | 53 ++++++++----------- 1 file changed, 21 insertions(+), 32 deletions(-) diff --git a/planning/behavior_velocity_intersection_module/src/util.cpp b/planning/behavior_velocity_intersection_module/src/util.cpp index 7f76d538f0846..94bc75b805934 100644 --- a/planning/behavior_velocity_intersection_module/src/util.cpp +++ b/planning/behavior_velocity_intersection_module/src/util.cpp @@ -84,21 +84,16 @@ static std::optional getDuplicatedPointIdx( static std::optional insertPointIndex( const geometry_msgs::msg::Pose & in_pose, - autoware_auto_planning_msgs::msg::PathWithLaneId * inout_path) + autoware_auto_planning_msgs::msg::PathWithLaneId * inout_path, + const double ego_nearest_dist_threshold, const double ego_nearest_yaw_threshold) { const auto duplicate_idx_opt = getDuplicatedPointIdx(*inout_path, in_pose.position); if (duplicate_idx_opt) { return duplicate_idx_opt.value(); } - static constexpr double dist_thr = 10.0; - static constexpr double angle_thr = M_PI / 1.5; - const auto closest_idx_opt = - motion_utils::findNearestIndex(inout_path->points, in_pose, dist_thr, angle_thr); - if (!closest_idx_opt) { - return std::nullopt; - } - const size_t closest_idx = closest_idx_opt.get(); + const size_t closest_idx = motion_utils::findFirstNearestIndexWithSoftConstraints( + inout_path->points, in_pose, ego_nearest_dist_threshold, ego_nearest_yaw_threshold); // vector.insert(i) inserts element on the left side of v[i] // the velocity need to be zero order hold(from prior point) int insert_idx = closest_idx; @@ -165,7 +160,7 @@ std::optional> findLaneIdsInterval( */ static std::optional getStopLineIndexFromMap( const InterpolatedPathInfo & interpolated_path_info, - const std::shared_ptr & planner_data, const double dist_thr) + const std::shared_ptr & planner_data) { const auto & path = interpolated_path_info.path; const auto & lane_interval = interpolated_path_info.lane_id_interval.value(); @@ -212,12 +207,9 @@ static std::optional getStopLineIndexFromMap( stop_point_from_map.position.y = 0.5 * (p_start.y() + p_end.y()); stop_point_from_map.position.z = 0.5 * (p_start.z() + p_end.z()); - const auto stop_idx_ip_opt = - motion_utils::findNearestIndex(path.points, stop_point_from_map, static_cast(dist_thr)); - if (!stop_idx_ip_opt) { - return std::nullopt; - } - return stop_idx_ip_opt.get(); + return motion_utils::findFirstNearestIndexWithSoftConstraints( + path.points, stop_point_from_map, planner_data->ego_nearest_dist_threshold, + planner_data->ego_nearest_yaw_threshold); } static std::optional getFirstPointInsidePolygonByFootprint( @@ -304,8 +296,7 @@ std::optional generateIntersectionStopLines( // (1) default stop line position on interpolated path bool default_stop_line_valid = true; int stop_idx_ip_int = -1; - if (const auto map_stop_idx_ip = - getStopLineIndexFromMap(interpolated_path_info, planner_data, 10.0); + if (const auto map_stop_idx_ip = getStopLineIndexFromMap(interpolated_path_info, planner_data); map_stop_idx_ip) { stop_idx_ip_int = static_cast(map_stop_idx_ip.value()) - base2front_idx_dist; } @@ -319,12 +310,9 @@ std::optional generateIntersectionStopLines( // (2) ego front stop line position on interpolated path const geometry_msgs::msg::Pose & current_pose = planner_data->current_odometry->pose; - const auto closest_idx_ip_opt = - motion_utils::findNearestIndex(path_ip.points, current_pose, 3.0, M_PI_4); - if (!closest_idx_ip_opt) { - return std::nullopt; - } - const auto closest_idx_ip = closest_idx_ip_opt.value(); + const auto closest_idx_ip = motion_utils::findFirstNearestIndexWithSoftConstraints( + path_ip.points, current_pose, planner_data->ego_nearest_dist_threshold, + planner_data->ego_nearest_yaw_threshold); // (3) occlusion peeking stop line position on interpolated path int occlusion_peeking_line_ip_int = static_cast(default_stop_line_ip); @@ -404,7 +392,9 @@ std::optional generateIntersectionStopLines( [](const auto & it1, const auto & it2) { return *(std::get<0>(it1)) < *(std::get<0>(it2)); }); for (const auto & [stop_idx_ip, stop_idx] : stop_lines) { const auto & insert_point = path_ip.points.at(*stop_idx_ip).point.pose; - const auto insert_idx = insertPointIndex(insert_point, original_path); + const auto insert_idx = insertPointIndex( + insert_point, original_path, planner_data->ego_nearest_dist_threshold, + planner_data->ego_nearest_yaw_threshold); if (!insert_idx) { return std::nullopt; } @@ -555,7 +545,9 @@ std::optional generateStuckStopLine( static_cast(stuck_stop_line_idx_ip) - 1 - stop_line_margin_idx_dist - base2front_idx_dist, 0)); const auto & insert_point = path_ip.points.at(insert_idx_ip).point.pose; - return insertPointIndex(insert_point, original_path); + return insertPointIndex( + insert_point, original_path, planner_data->ego_nearest_dist_threshold, + planner_data->ego_nearest_yaw_threshold); } static std::vector getPolygon3dFromLanelets( @@ -1348,13 +1340,10 @@ TimeDistanceArray calcIntersectionPassingTime( // `last_intersection_stop_line_candidate_idx` makes no sense const auto last_intersection_stop_line_candidate_point_orig = path.points.at(last_intersection_stop_line_candidate_idx).point.pose; - const auto last_intersection_stop_line_candidate_nearest_ind_opt = motion_utils::findNearestIndex( - smoothed_reference_path.points, last_intersection_stop_line_candidate_point_orig, 3.0, M_PI_4); - if (!last_intersection_stop_line_candidate_nearest_ind_opt) { - return time_distance_array; - } const auto last_intersection_stop_line_candidate_nearest_ind = - last_intersection_stop_line_candidate_nearest_ind_opt.value(); + motion_utils::findFirstNearestIndexWithSoftConstraints( + smoothed_reference_path.points, last_intersection_stop_line_candidate_point_orig, + planner_data->ego_nearest_dist_threshold, planner_data->ego_nearest_yaw_threshold); for (size_t i = 1; i < smoothed_reference_path.points.size(); ++i) { const auto & p1 = smoothed_reference_path.points.at(i - 1); From 0df1d8fb42ca778f76fc4c97e44f9df04b136181 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Wed, 8 Nov 2023 14:28:19 +0900 Subject: [PATCH 144/202] fix(intersection): fix wrong resample process (#5516) Signed-off-by: Mamoru Sobue --- .../behavior_velocity_intersection_module/src/util.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/planning/behavior_velocity_intersection_module/src/util.cpp b/planning/behavior_velocity_intersection_module/src/util.cpp index 94bc75b805934..a9d0f56266181 100644 --- a/planning/behavior_velocity_intersection_module/src/util.cpp +++ b/planning/behavior_velocity_intersection_module/src/util.cpp @@ -1459,14 +1459,14 @@ lanelet::ConstLanelet generatePathLanelet( { lanelet::Points3d lefts; lanelet::Points3d rights; + size_t prev_idx = start_idx; for (size_t i = start_idx; i <= end_idx; ++i) { const auto & p = path.points.at(i).point.pose; - if (start_idx < i && i != end_idx) { - const auto & p_prev = path.points.at(i - 1).point.pose; - if (tier4_autoware_utils::calcDistance2d(p_prev, p) < interval) { - continue; - } + const auto & p_prev = path.points.at(prev_idx).point.pose; + if (i != start_idx && tier4_autoware_utils::calcDistance2d(p_prev, p) < interval) { + continue; } + prev_idx = i; const double yaw = tf2::getYaw(p.orientation); const double x = p.position.x; const double y = p.position.y; From fe35797558186a2f34c91eae469ec0e6e3b94c32 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Wed, 8 Nov 2023 18:17:55 +0900 Subject: [PATCH 145/202] feat(intersection): rectify initial accel/velocity profile in ego velocity profile (#5496) Signed-off-by: Mamoru Sobue --- .../README.md | 8 ++ .../config/intersection.param.yaml | 14 +-- .../docs/ttc.gif | Bin 0 -> 2467326 bytes .../scripts/ttc.py | 13 ++- .../src/util.cpp | 86 +++++++++++++----- .../src/utilization/trajectory_utils.cpp | 13 ++- 6 files changed, 94 insertions(+), 40 deletions(-) create mode 100644 planning/behavior_velocity_intersection_module/docs/ttc.gif diff --git a/planning/behavior_velocity_intersection_module/README.md b/planning/behavior_velocity_intersection_module/README.md index 16459bb64074b..cb65e2a3cc23c 100644 --- a/planning/behavior_velocity_intersection_module/README.md +++ b/planning/behavior_velocity_intersection_module/README.md @@ -86,6 +86,14 @@ The parameters `collision_detection.collision_start_margin_time` and `collision_ If collision is detected, the state transits to "STOP" immediately. On the other hand, the state does not transit to "GO" unless safe judgement continues for a certain period `collision_detection.state_transit_margin` to prevent the chattering of decisions. +Currently, the intersection module uses `motion_velocity_smoother` feature to precisely calculate ego vehicle velocity profile along the intersection lane under longitudinal/lateral constraints. If the flag `collision_detection.use_upstream_velocity` is true, the target velocity profile of the original path is used. Otherwise the target velocity is set to `common.intersection_velocity`. In the trajectory smoothing process the target velocity at/before ego trajectory points are set to ego current velocity. The smoothed trajectory is then converted to an array of (time, distance) which indicates the arrival time to each trajectory point on the path from current ego position. You can visualize this array by adding the lane id to `debug.ttc` and running + +```bash +ros2 run behavior_velocity_intersection_module ttc.py --lane_id +``` + +![ego ttc profile](./docs/ttc.gif) + #### Stop Line Automatic Generation If a stopline is associated with the intersection lane on the map, that line is used as the stopline for collision detection. Otherwise the path is interpolated at a certain intervals (=`common.path_interpolation_ds`), and the point which is `stop_line_margin` meters behind the attention area is defined as the position of the stop line for the vehicle front. diff --git a/planning/behavior_velocity_intersection_module/config/intersection.param.yaml b/planning/behavior_velocity_intersection_module/config/intersection.param.yaml index adbc7b3e087d6..22f68733a3bc2 100644 --- a/planning/behavior_velocity_intersection_module/config/intersection.param.yaml +++ b/planning/behavior_velocity_intersection_module/config/intersection.param.yaml @@ -35,24 +35,24 @@ distance_thr: 1.0 # [m] collision_detection: - state_transit_margin_time: 1.0 + state_transit_margin_time: 0.5 min_predicted_path_confidence: 0.05 minimum_ego_predicted_velocity: 1.388 # [m/s] fully_prioritized: collision_start_margin_time: 2.0 collision_end_margin_time: 0.0 partially_prioritized: - collision_start_margin_time: 2.0 + collision_start_margin_time: 3.0 collision_end_margin_time: 2.0 not_prioritized: - collision_start_margin_time: 4.0 # [s] this + state_transit_margin_time should be higher to account for collision with fast/accelerating object - collision_end_margin_time: 6.0 # [s] this + state_transit_margin_time should be higher to account for collision with slow/decelerating object + collision_start_margin_time: 3.0 # [s] this + state_transit_margin_time should be higher to account for collision with fast/accelerating object + collision_end_margin_time: 2.0 # [s] this + state_transit_margin_time should be higher to account for collision with slow/decelerating object keep_detection_vel_thr: 0.833 # == 3.0km/h. keep detection if ego is ego.vel < keep_detection_vel_thr use_upstream_velocity: true # flag to use the planned velocity profile from the upstream module minimum_upstream_velocity: 0.01 # [m/s] minimum velocity to avoid null division for the stop line from the upstream velocity yield_on_green_traffic_light: - distance_to_assigned_lanelet_start: 5.0 - duration: 2.0 + distance_to_assigned_lanelet_start: 10.0 + duration: 3.0 object_dist_to_stopline: 10.0 # [m] ignore_on_amber_traffic_light: object_expected_deceleration: 2.0 # [m/ss] @@ -81,7 +81,7 @@ maximum_peeking_distance: 6.0 # [m] attention_lane_crop_curvature_threshold: 0.25 attention_lane_curvature_calculation_ds: 0.5 - static_occlusion_with_traffic_light_timeout: 3.5 + static_occlusion_with_traffic_light_timeout: 0.5 debug: ttc: [0] diff --git a/planning/behavior_velocity_intersection_module/docs/ttc.gif b/planning/behavior_velocity_intersection_module/docs/ttc.gif new file mode 100644 index 0000000000000000000000000000000000000000..bb797f7df59a1ee9800ebae6f978bf1efc555ac1 GIT binary patch literal 2467326 zcmWifWmMEp7sr1a>@Kjt(jl>QrwB;M(nv{{bV-RQAt>O|OM`@9(A^*+h;&M~ARW@N z2m&Iw&;R+JId{&yn=^Orees>oXxvwqxob~DWDbr70K$Lz_mA-J=HGwu=7w)+`q z;rAxtbouP;?DX{X*RNmyPF7D&PHv8m2>4k%9)Em%OgK0o98O;x{QS4Ib-cMjI2a`C z^$@n2kB*KG4i5JA_I7r5wzs#pwzf7mH#asm2&=2x>+5T4Ybz@&gq6~Nvr~j0S%mM& zgz4zz<>jTNrNza?g@uJ5KYq;5&(F=xegFP_c6N4VW@dVNdTMHFa&nR|o;p9#H#Rml zIy(AqaFEbfL-_iY@bM$zn=7H)jL@M=_^L!`mL)Wb5gG&tbzH;4!$U(ugM)(u0|R}1 zeZ9TCU0q!r9UblM?X9h?EiEn0&CN|sO`kq}YG`PvudgT6D%9525-KYRu6lPy;BLf2iJv}`g z9UUz#Ee#C~6%`dFB_#@lqM)E4CnrZDk)))gBqSun#KZ^$0uG16U@#&gA}ACJfk41u zFbD)90Du+nf3g380(}3?LjPaI(Xk&?>Ra_v;J4rSch-TYal98hRt{^>Qah{RD0RNI2pUt@wMYh+(zPgN|DCmHbQIq@jw{1; zJ%+EibUjw6ac4bFtdDOaUUJrTBSB`XbR$vzd}kvG1LNOJR;6>>Owr^i+kCAfwY!ZH8u04LZmx(hz%QgPV0=)ZsXc{NJ#sA)69!`LF4{W%U-NlILPAJ z$yn>g7K_4)pBI{+8LcR=Yq@tp|XN_-bm`T*aJ(hw5ww!%nt_b@!FJn3V8esI!{ z-j-9zkh<>f{n)bHF+j#gUm-ChO#S!SaQCRr$6BeCYmZUczk@zw{598=tx_1CF2&m& z6=#z=(uZeL`WnK&r+?T8DQD0p1sOs-B*mz|+q_!(G-p2qm716Q@c4X=#hGj#P6$fo zUVP@bdp_&gUwHn*xtq}Nc{%VeOVes_``Ksp=W^;7i%%UBB(}jcl6M(mzW! zZ)JUKXjY4nZj{L=uw|6JpHq?cW$!~x!wapNjo{{=uAgr%9g7}jy-Y8Gbz2nOk-`zGgW3Ztuo0I1YXq2$&lyGrkZ4I3QmllOO-07M=i=J!84v~i+NYo zNF*W(5(vnNQD*82e9O4Mw~1Eb(2BsVv2h~4@szSBo8!T09~*&kA25Nv0mT?(^@T1~32MHB;*?UR+!6xdE~MG2kI+78$NGeYQDD9ZU+MAlGR zF-P8Ag0B0OPt?^9sB%ahX=lW#Cj8E%3~}H(<95LWHsZH^{6fPH57pl8iQ3|mrQ^yBB2zKx-h}h@b;R#IEeeY=bNww_H zbnLx!8%cl|S7EiS_5I6_JJlf9GDP-TtlVH4>Jm_=?&wIgo$f-oHNn}S>m-k`Yw)yM z4HU8q{!+{Vk&T5LeP9X?(piVy$3o#U`f)aMCm^B;clD+(l(UVq71lo=DR#@MMG_b= z%()CY%5e=3IfNxaeu!%CXzj&yCg~<(SAKw%1ZxYsU95;g2yS(PLNCK;fm)C>oC^7X zVUy9E1|cc+Qb+i@z?G(GTgf<%@_RL1V;!yFrPE&%tliJ7h|H{wBw5>pY2WaAX&zseVpYpL`O#>LYbgbIhQrYOOW)m>h)A zhk=m*%9$SM=tk3t128<1p1BH(f?d7Zb4FW6kFJ*|hmXQo9gkG0Hxu)}jz6yu*d-d}zru0U?s6xyI~BbA0$ z#=;c-QBH01SfI6So@u?^9bc0HGHJ(L1%&{qKBvhr@?Bpu23|B16c-0=)TxipFpBD;OW=C`Qv^B?Y+g~YQ+nFWq7=Sr# zf`ZqHne&$DaR18&AJ)kCMcX0wzfnK?6c=DU7@6>D#~JT$Fpvlzm>%^?4`dS&MLgIqQ5)$P~uFy ze`)fKdduX@XfpqF=Q{RMu5{yiBvtBOkugn++EpUe;4Rf(RP2A}M%n^9b3Win43t+x%W=}#17XdP`+iAS^k{k!kztz``05_xMO*R@ z6|RfM@OpuTv7SbaBd9bM*oEy0r4o-C*&)4j4+3G!?b%R7iwLM_{Ch% zYnRBAGsDYCuiGX@(&Ou*g@&+faS}CRffcMnZ)%{ zfHN0Z9{>l@Ld278h3tShl({7ub^st7vCx>G@Z~vkdlWR~4spO<152b3E%ib$ArMVY3H#@E7hVqlj4 zH7zl)5Eg7~k!~88Zl0BH{0(d{pKfy(Jla8GkOkYm15U+aWC1>%)0-?Cm0o}*3;6Q}JD)C+OXS*-78RI@%gT&x&WxYWO#G9X%$W81ZdRH_ zRz_e}W>!{Q7TjAO{=60zi1EoO%PMrsiXTsvrB7omdCS9L$VCKX%AnrKB+LXPpqdkw zTmgm-x3BZ>+Wx%j`1Xz=IeEiXZ+XuBxCwEJPar=}s7oe=VKV5W>>KR>`dJc~KJgDR zhgCH3ispOL`-xb)dAx~u7i7Yu?B29hFqX98!z+B9fv?dMeJ&k4F*ZUx~#z)n#C$CHm^yr)o z)t&WSoNsqfSmKGU?3_O#aH`Maa^A$vUwFHif_?Pif@oCCI7Ja&#~l|G?~{A`*~8{L zs7f@s{v~n@6PeA20%1UUSB3gaMTW9PdT-5MzInv7=T%eea7N=A-iYc#lT?h8Lha*n z=CD))sx6w~(gVeBr~wmwxUm?@D>|yTDIf(=sQo&E<+bhKbd!p4@>49S5iAcZ9!{BO zRh{czNodRiP*3WlJU;n*z$Xw}wdAk#i-q={8$SNq=dH ze}8$v=fVem%bKQ01`@aqmM{(ieK$}E8kyz?|Btd z9=0x4Q^fMsz}w1;x7A>!0x4M(4aO&%uByL3Kygo|_J`m8=c*L{7ZO)h%LV@40wvJA zoPHE=B~WE+PfYOE6Urr7)Th|UB{AbfIpL8fSn@oqsY5R5wiv~9av7u!zFV}6nj+1>x zqjbC}-U3kjT(W#LDs!CJ77t0SrEo)|__T=C#)&VnQ0e_@x%`i}yFN0q*C4cOdS!9s ze{27clv8$8LhD>^P((U$byl6AB@Ap>4b>|poQ)=fq`-cUgJ7McHE7f)zzqP%=F(BV zf}DA`IQ`=&11g@AybS!!6#D9AiOOH^^FRQ)2E9o}(s(yPhG^@=NQQn!LnaXWXjHyf zBv*?!(Hhd86xis90e2G5pgzyIhfKtUjL@r}GEtKRsK1Ph3%(VQGg!b+&@YhILXEv3 zp`L3npMZZ)R!L%-RB|#oOetaRnfR1k z4DrE3Y=eq|Z)@J>M!B5*o@2nCiog>`*=bonUm!x^%9QIAnLc;_xqMVw}`j zg&3bpahh8fcL(JtM!|O84nhKu__V9~j&D2N_oVLAMJS=qDgkn4Llr~P5_1EE3#pomWW>((SflN9TCmYf}`+Z-t_+hsKY z()9kOi6*NDKC=O2-F6`2PT~!3RR=UhvOema9BK^Tj1d1Kwmv92Dc7FbGeWJ<5H!@| zIKgXw^=;*J^#3q!pUJr#r=O0CbkXKBhu$a*?04XV$4Fu8Ddu{Ii>|S%sS~ zO2WNH!DGUp)F)`fM@PhsUE70%HdfbB)2=C3l9>nBQ*LC#A`{_$xsWW!DE5OH>b&pE z5#N)|zPpZ0z9O3w4yFR3hfVN6x?_3q_T1&yYNyt>Ib_dVTEBaY%qFwUzi*{77J{>* z?vBNhyw?4uqdS?m#2GvCIZ1dXm1UtMfr=3iyMhBLr=2@{-vt&77fldV;= z0tWMb-b6;vWw?@iB|8@S6&Aj=_Dc~GCW{Ui$6FW55~vn<$GQ|`QskF8MwU$Sr-Yv^ zEWTSfs9M-uT4bdJbu3jj%gQX9E%sSY4csitJm&m$lfM>Rcag9Hj-!f-CaPap2@VGV z4_ClP%Y!A0#gA7?M^?%HEppa@Pu_!}C(@p^kLfCw=(9`Wb-CeQHN^kcn90{cB2=L* z6GSJ{-O*3!jxYtSbGnC1KNU7qtJf85HrP)l?`BKW=#Q!Wn_00o{4~OeAK?%k{UUz! zg|ux=;~yo59$df<_0ngZ_U~rQ%|@p2>fMShxwx&<)}QN-H=o_xWPiHB+`8#}J4oAO zi|Xmm7Y08C!8-!$+p+`ScNf=K32g&B_5m9&Q0`NkH~rg`N;?7UJNyp2e9F6C?h^td zKdrNOXrC_IAMJRmZ1MlwO+DHQ4&CML+T+RJB{v9vH@X{~u<4t<^5^-s!>E*8;tmS5 z@3*$c&2hj5K0vbX*DV)+YbzdN?e(dq1mRaH_4aHayXQi??bUlhN(Y=>ha3(Eq@f37 z>_;2b2mM}0+oK0RM-R4j*NLA>6(8+WfR3K69kM$dqm_@36OTxgj&}9-KauZIo-A}O z9Xn3#|2jflk<(xPV<$UiCw*`TyxNiU+6NO*le$Z5%XenUw@GRaU!LGuIDRoxowQUR z5$>I=e)##pi?YHRyvuq_Ojtqjtk7|_vrE^o-?3f4Zae17`6aaSi{yxsX*}z?^+Yo8 z=^5EiNcNg?$O(<@i9Xx!QawsAs-(y2hzsNMUF3He>rb~kKYfO_{78SbmHZMsK9R8b zO>Gcb@b(}jXwN3+(2ioWp=#}^*NIWixqHnHivjqV*qo<(HE{1#s~jaEMtY!6@x7MF ze`RSqX#d6WZfefOYg%&I*U>in>4=Dqxv|nvONJx5a%?ghOy=lJ)vi+-)bWP5_uC5#I^?a_b1|?ZY zR$xcECr0-4`VzW)#Y1>}9!Y)$dhjQ`{hZc*n<{T+uy($6Wt-rwJNH@_YEN;#O02tz z`0d>tl5)zJPhhA&g{&O|Aj~QzjBHjCovFX397V=LE{Vghsm9WBn)YNqT~kY75r1|z zAO@t%nxlMGrzuP{Gsu-1b!0YHhO^#Lt-qAgru6^#do(;C?&9}y*1u7EY|%H z#cX-DYg}$pWz+lCxKGIcclBdR8SGT^i_S3lw7cPZLzUq9Mk2ga#bPsjjjrLAu?EXs zep#5-mkU;#>&v3tLSAO?#McOco4^7ZaEip4{|o)<>1wZZhV;Vz|WlWbbOmSBwz zPD|+X=4*+U2PcKZ8heaTtmwZOd-Owh15I%6J-+pvTTHnh_2iCwZa+{sY_KCEJ%>u_ zD_tC%jwul+)Y9}7sht}ply61SOlWWx85^hw7Woj#?sc#mVy?ttN!sGvpF;0zSDi*( zerZVNGqsKMlNWX@`ea(*JsDGSdy2+YH&QCkjYoYJ-DvKZq$XwI{KmP_;!#edl%-oq zQKO|tO|R6$$Db3VDCG9^H-2;&t~FZuBsn{oJS_3`vwptv!P7KgyXZN4KRQ*YmzK!A zZbW+HJ@t&z1KLc(Fw(>`y9h>;fHl=y{sF6M;=$NLAr72mbVx>?{W^~E+}zH@zVd=U zP+R@3bLkJ0X6F|L??g(@W+AJP3!4VvZ_J`bVrALETXp3*@E;!J?aErj>3Ip3FY>sp z)%ToA2_?l}Trw*9zG%bQ(~^||fv3C)T+dR-w*Q2UW<6>cn+@FlmLbBPxNa`6ni(?Z z%2fK*(NNkWxA0ufI{-xg6_0-#B%uZLDEDXEMPMq9Z)Ot>4jY48n0>bR9w9(Nd%4O$ zM*a?*5q^G7{5v#TYLT<+Vf2Tg?~Wy{TC;BqS&A3^w!fAwJ-kvV%quGGPC!^nh@~{W zI8F+T^{NTZpD!r6*S%ZOZzI1GIx2rS((-8G*Re%cUZSk2>n_y!>ZwB@UQpWo@4?5f zFGBuGfBhG7qmoJ}T~)YZ13r|b0se(p#$5~8vOb)@qY!n2j(P|iXe~H94*9cS3wy{- zOCa;Fm7_xrf)pi`NZJx2G%54cV47IKdJPa}$JoI(+D>{OJY#KOfSQ;ljaj=#_#-t}+JDHQMOl!5SKK&ii{#e~G zT8Jx`Hwufku?y_e1E-`FLwRm|8FU;3V&b8`Mflfc!`4#uS))B0s{S2s3O*4w0snVv zEc0_iZ2#&rJI=PGweJs@-23=`eZfUCB_f5U#{hoMUS*d#SKE(iD)nJyj?C}7gF#1A zIVDyOvP80+KG{CGme78c>9~R_hrwet$Kjaj}M^_Jj(+B-&MxWOfn@HDx9PzhVRJtCHR1p!(Hv_4VD}Q{~-F`iC(?oz6VZb7Z@Bo8pXg3f8)uvc>9T8+VSyG zipKn|fo;t<&JV{01i94_n|pVee&V}AZq{4o370eb4}P~so9#bj@*gy_spt{?R~6me zQ4rMD5HqHr6R}di0$H)1`P^1jT=Q+Hh4N3g?dPAA-jTBAd4NW#e6^O z`5Ifrp~vkjuNJ~dJ3W@4MpQGqy|6L7?YBqFm3HgJyY`)wcBm6AL|zuZe@`zKQ!B_s ziy@I!{wnwP-U}wFzHoV1&ld`)61zvc@(;|>JB*E1r@A5NZsxlJeg4LU+h8YRh)@<0 zvyxC}CvyW8JV@@doD$8j;z-~v1${n&xlg$Wz<3A#@vYL_U*cPpZ&)^!`1861u2F1A zWhP4{YNTRi0B|R_XyY!)qydZxUC(}oAn+Hy5$sXER_c&GyCr;}EGl{L<{gqPCY%Zr z3r05tyi}f#>!PY;l}=MZiub5+QOJH(;V@P?ZYI?wt}48wak~73Y4}RMs6c7lGkd>B z4@sdOq{@9u&Dfok2>fO!A7~MmgjA@6+I0v1QPn?4v?x>)O@W7fKk9m4UB~0n1_&dF0spgJ!7JqwED*_r61gTOK_D^4wNb-}r$O|w zl>@{2-_pOv$Mv+w>l7q7k^B>6l`#IGx)bf#f!)hj-wx3H;dcK`{F`7dE%VU(VQKe^ z3ceKqcmM7a^EMSeIr|n`*_n%!E|AwUWgM*Xj4Sl*De950FeWJpmt~J2hNC5UE44zW z6IL;VUI{Lo70x%X*{Zp#TdNioXt8`e1VK%U7x|#=~Vz+M1HX zYCn{dgGf3#zuI^bmsQqwUEhx$?nim*ys;l1_l)i5>K*WuCILVK;Qp_^xRHJNVI(mU zfix=B7$VWAjQB9YHBz)XLRi)znUd@s^+dq2VahT@j^;Tbn&gf$k;>j-r$&nFXT(3c zLpMod4ClUSPY+pFe%6JKLeBc}i{y5B#Gdc4CU)?^rbv2o)RNHs=`>7|cbH+W*jCTj zbblbCgDp^cTEIk2V4P#;JAzy!7+21bTUU4$9sc$bjXdcVf4>% z5G>fpT+i5Clh9D8mr;9P`ce_xi$J0!9c21EB=5)Djr&U<;_0|3OE~r2Kbi8OnHryH?h|Dh5YwPEBeV^pRC7V>**Pxl+*=S+o6xPm75b^z?@4py-V9+n)X zZ;m)EjIqD_#x;G`t;p1+8PXDpR%)VCk}+@`pLHiP^Jxy3aSwObjZC;3;cfEW?@oqq zr{Tq|G22g6is|E&ShzaI)Y;ioorvLKQL5!{Go#KKY%eu77^`faE8l4DA# zv1I0in5s0SOcxwM6Wf{^ARrkrVXk#Er!rxJPy23}XGWYJ^+0A?)!G;p`5+4UOFilsl%b58`%NySVbvoT4tgFt9lC(yv3b6Bnq3|yYCT9xwS?pquQa7=Lw3o zkw5m6fArBriZz9b0#Sb6Ai$33>FW5S(!}oR0lAr`Mi3}k3s$a5B4y5I41~7!7!)M; zU~YB90HGaxQQ2w3ElV@4k?CzFI+kM5FZtk>=4628n13eR3LARS^RUQzs?P*Lph8PJ z;l~QGU=DtmQs(fgQZHx*6Q2u2%fem@TK6k7PpMf~PcQ8K%qi~e$&6P(T`o!LlJMq= zSv($0M)b)xg{98fM0x|V$}s%M7g*Y7vJ?rrE>} zsPolpM4t`*euPVs)41T^RPi^$ zcGb=Zl27_bVbxo0_JafV*Gu-rJ)GPwkSf{G6{7XpgP24b6j;fD5UIazx@cFU@a>bk z;dte`K=b<5hy%Ts2454`9TzdGY>5{*scYp7A!1gF(W+atpev-ZNXi{!PRN;(*AAv8yAFsx?#3bg;;FJ}h;f zZvFYEp*l?y2JUMIFmsb2sLqysCVr@)dn6(^RCkm|<=p99JHFQ&m-b=H{a>=j@`7jM z!g1%uNRT}*S`tCB@vQh=XLndv#UNjo^-RQ*KC_C%#kxS}*Ziv>Msx4%8hQ*?O z1ly=0lV-$Ur%^`?k&$LZqyPSAe-G8<{bs3%FCq~weI6Jrm=_(IM>($C1z-@aj;=fQ z#qQ3-OYhFze~s_HCh}NnjidH9SMk<>|5w!rj@Dk6a+CntDu!2XxP$j$|CE+Ciwt ztz?1^KgSD^t>8;1PFTM8kiI#t6hk?Vhf}R+A_qXc*f2gj2*&#vW{ySG{)rO`m(#r@mgKa74Tz;#90eC)WF+Rhy62zZ3JUvbSH#-v1~IT@8EV6Ky+34~Rir zanXKFk+&ES;+at|@i1j-JI(8 zkuaI(bY}WdYvgbC`gFHFMZTh)eO4uGBrp%g3hTe&x`d+vKw$t5LE$7<;SmTTPX@$) zPmx~7=i`_D#AFw@i(?6aszgz;7r$t6r@AYCqHAW45X7UgCjz2@Y=|=|+<&{#4ZxD1 zi5@eQvo^ui^#RISBD?YWP;+Pi<}xB@z@-1r9U-5lPxwL{ud{1QOin#ycHPR%H)r*- zVpWXdKaL4eM@fy~!bb(qML*^<4n>6fjz_-=fT&??Sr-Dw%`f4P zFO{lEkhQl4>3rr!FQa7E3Zm^$yb6Uq^;z2zqSQDNT$K50m`D?mr_4)+ohW@*uoy#> z9Rs$O?PVz6-;cZq#@Rog#&C_iW1k2Pe?Z5 zdOvNKE9|3>(->;ca`K(bo9>y%1M=1N2;1c>am%kQiP5L_Or}ssE7xnD3WntKlb``;Y@A@ubDqb?0_;F}Pk5FY$@nrdj z$&clu8@WroP)nTXlYc>f4x&?4s@p#4D>^YG+ddgv4hasUT%69L!dwL>HGj4VF)J&X zgzYG(XNQr=Uap22E6K1&(nk5&nL{#))=YT0rYO)@q5=A7#zajFt)E>A)~`POawd-Z zgKxTg4c6Y?0=eGAnWUh_otLCU!pIe6*E=_p!k<3*KpcuQN5^og6LVAebx-hcKV zl5J|mWbC9Fuo?D1Is>><H$Bw?z_oO#7AB=mM2c=!*-y3(4?L2XC3LiX;q0XjNNn_6%ohiRRV5j94dOaovHdAKy!+Q%>Kjw6MuI#|c zRXJpHTf1BQ{BkNuoF{y#cqLk}tzcQOifnQN-1!_y2d|G02uw;|x%X0XYChUBZY*m7Otkwh3Z77KlvFVEim z)%MqDrthKHgY@cC?6aHchKv8b-gvO~nbe}?@@E{c!u_6ya(+0>@H zo8R`q`hJk)5{d3Ri2pN^*E$lFLbkkSD;vZJ8EE_cD@%9%Xlobk<$)dKa~({R?ZQV;fZ%M^m$wL{==Pr z22qyz(HV<0Y`+m4&;ZXKDnbA;z*9@&Kd?b3nmi%0`+XP{!cF;~>C7W-(c2#Zko)O( z%O|<&L=yRW-o%wKw$7KaT^F#d_@>gcUFlk_I^Bdrq z{mQIf_6lAqk(RdQ)4p*HRg)Pflh9O$UXF)jaQGx94z7e}2mA!3R)+`1c;B37p*U6f zTBFSKx;L*>`R=~}5r@g=(|>>eLHb`EX-P;)Swz)a9xCW-^LQ}unz36^h6nXj2ORg> zm&0;OW7zgrS=Er0_Be@Azo)b5$D-dtyLhJ8{xqRzRl9y$`U~73a<%q{c;#a=Q&8Ky z9o0gmCR?>QsK0HK;sTA6RJKPE2jw=aUG|ePp_g_IKYy8R74a|g2)$#DZdtw&3HaEu zbQJaZ>(nP+aaKE<-NfguN5M~Ct_ZFilw-)Bd0>LJD{K$8p11#-5qVA!v^$3dbWF8& zI?G8UaiO?~&u~@iLi&vLTXfP*Rkdx{69f>CX4x$5k2)n}ki)3yfj+hBXQcJSL&i~* z9s%OzG`0Fwb3mL%!j!fg4m!t|izXe`Q%mrg&(=_aU$uhMORW}szC%BzTy=X_6 z3Tw9MC)v9yQ+Jobx!$R5$=u{gNb{e1nv!`qO?1P6+Q?}a{Az?RK-~6!qcjv+^B=LR z!cgI?6#RM0-7As#K!e%rYW|}!KRNdf>Brr@SwfGwM1oGPnpELQEP7FU_VEjhbBLVB zT;|KA{Q4*^7l1+(z>w~^-q-9^ntUV=DZ1~t^)k)%$KxDlBHz+*;yPXLEztY4PoC26 z3Qs6Jn%*thR0sSy!zKj}kOFV;`|4b&qb3cGtWDU^_8}Luic9hUNRGd`1X|FN(y8G= zc?I8bEG^LvJ9XATcSVcUbZ>B;1Vc2kC#j8}L9!D7?}oYgW=(qLm|+`GQ?`4+#+{E}r>8AM+F864@V zm3GD6bL9QI#^QV)ca~4D{8&je0Cdr-L|A95Ym$3-kQm6mmM_3?BQK&}bRZmQeQX9& zRZLt1a(J=@2Pz>G$o7kZPxrViti+Tu(MjI~y};>f3tMCPe^xJcXjuTjB$Yri@u2mb zo){xOUTjqUZdu4X^_JU*nqTi7x#JEm!Afnb`g!l30O=OclgL*mXJ+!pI@2L)2d|MR z9kzc$Wo|6xwW{;*?1kx9?cEk?LUt&MzvN8UQaoC$I9Kh7qJ6YT3BgqvV z#>fv8GCDz21oU{WRqo-PiYqzIvQr*7tZVY9!dT%7cZ$@I%iXRE=6&m;i5ptE5Ne>q z7>uPju+e>+bbp8a!O^CfmzMc5v*i}{6HT6G7^ilG=|LU01G$qU-KI$oq&*8e38mo7ki%y1p`)i zvCG7vNF`)T>9Xia<9*jXwcTJx4Le8Pye&2F#BHpeNAc!E0bbrg7iF}P>{*w>T$ogD z_ky*{pRX9_0Vi)dsCOc-69d{3$vZcnZ@$HudQc$MRjh;ne(_PPHuG?*Z&O=FBJ9G1 z&%$`$$2`wSx_hl6lF8c^z!L`hhPDbW+;Y&pii4Rfoi9Wv=C_Am0zH z_wyt5UK{W%sAW>iaz~)Nm8CZ!Vwz>;o&0l}bBaQRfj@RXgb+#Dft8%P?wFVHxa6~+ zK^~^C=21Pm9c;M9FOYn-n=k9G7C@ulqpD@3L}hk`r66!NRY_BnwZ7jN7IB{jlr!={Nz62cy{FK0PZSA; ze|4)>ANLH_iT$$Q@&%bd5-~zsu9jA0)Wu_H37Tbb>HOl1+hUJ<9Hs>Q?j5tJgjbQ& z2{Saw>oX+__}4uG<1O{7G{rOK_;o-qf(3o-WHeg?%L0gM?m-f_Ds{nKw5JdM0cN-Z zM;tNC)RPiBJf@6OxK`nE^6Uj4CU$JzE3Env3*nXdVCGw?yu+tqqe}J3{ZoFC19^G7 z*Y0x2H|Nf*_q&h}yDH-fh(a(xS_+n)?v^Q4CIbWXh;F&2ZqeZ)3=-h>C3GufLdr;> z?u+5l7)Rxx!*EGEndGYZ{BP)F6<$qy-uQ4%yD&LlFSCxr{w@IxnT}(`)TDY9rVtxk zR~%LBnOwe!V^yuWv8-hWMegirqdSEQJ1OFoq<47!^L*sKcA=O%g>%EzOS_~Bl_*?0 zp9n|t(I|0YdXv(s{$NZ?=mh^3i$o$+)XAZ22nc}ek_w7E96Wqr(=);xZg?)JFR{Ii z5}KxZQeI!E=2;bvt$;u}SQopCJV9l{Xj(d@d&p3w2(T0qD(pSIv*kH+xva>SG4{Il zI!r^s_c2P|oZ`Up(6F?TN6dmLdRqPPglp{A&SA%u_vegsR&_#cn3yM2x=R+J3a{+8?Q`uAu8c9JzJuAIB=-{IL!u1bmv=S4!P0#tr@g;#+9!8wQ| z7UaGv3ix(&BYPOHRfNcTV(aD@R}wiRD6jMDk_tN&jKc++z<1_Un1BvW$=L<)ujn6m zrH<&O^J?&zeb>n$1x1ap+)%5HYWO|Z2uuB0Itd+B6;W4JB2^V3ZzcLguoPG1dy-I$ zYp0^O7>|bpFMS04D}aIRHS}7AIf-}ot;GE^fKQ(=&1)AmvG+`j8X6TL4AvoL(&UWfb{2=MMQB~c}EHDZ5q za>Z(hH14bTVJchkk%;KbXY>?ftSzy+qp<%-Z8JZ%7NK~0qFqyI;$)CU1x-Iv|8@1_ zR~J+g3BiM~T<^P;MX>VMARw(%(U+I{8X^_lRYszUcy-3eh;h!%Vtgl=gzXfP4@Yi3 zDgSmN202yyY~Lw_j|!p6SUl4@zis(ZmF_3M5)_o<746j1qcaUfE~@Gss6M!c{`WyZ z5~)I+X525VW+bm>9PiDyLe3DG`6Q#k%$5+rIvy@K7p|iY9vI=%l3vjKUaEox#J-U~ zq(4w}@z53YcCV1U?=(@G;cl}3TU#F%r)1{hss1S01i7dzpW7{nm~krXbN6*|S|FFa zR_QlsB(e4P(g}~4b*5f?nA0Y8ufT?9zT6|jsbj0wBV5`Oa%Lf?S})?kBf0;P+?B|! zOR)(et0?We0#mS4x4y#Iyu0%`ajT<{?0Kr&H*#-}q~{^)lGf4wt>5+~#|3)@s2Fnj z9$B6T@%Bh3gRBQP(M|Jyai349iY3la{@rIvr9WR$Hx2grU9evcX*Px7FwUsw5knUd zLw(#%D)b!?hU-vSO=WqCrW2kNw?4^pMCu5 zIQDumf53XP=DzOpIzLlZ4cF1c{eVfJ=qW^EzK`benktAHbZykcB9w^N{|BQszR=UN z@6TBcbfv<6rJ;J2HY&L=jAy^amFX(^?GS`SidePk(@%l$h9(u)>vRYJb(;iH-^5FJ zrE{MuS2-M&^c)TTJXVWgH|mwJIM2Dd8N2vp?R{LpKB6xooQVZRzpP7_@hVzvYBff= z$M3)2{q;bW9Njt2)_ztRbUPY;yQI+_W?^1gDh$x)hvi&X_H{f{=}>MuHR`LwrXI`A zRhYS#(fQjk42X=QoIX7H+kn+iA&-{NB-EDrH!;;ix(vxh-pNJrwu81=(h}V(`gePa zD`xAJc|}@rL#j7}8oYz4qmsBy*#gd5$<5Zu%|6zUz1K1JYH;pVd*62vN6|pO?mm*7 zfXB-;k@h6HZ4tplfD_}e9ZCLSvZ)?Vv?t8F!yHAVlSj0%74Pu?blTRxDl(9%K$ay1 zLl0oufMi4vDy7d4RbFe}()tiW#`@fvjSNO5#OBeuI3?Elqf~kC`ZzDVCJU8BIKlNH zPZ~CDzwBB0J^N&S-q4--X|(V*vlglw#iu9Jer>_v^Zo8CUIh4}M~nnyp+p4iFXspm zyV+;ByOV9cPA!1%a%XjK>ZEQ8i2G|~pee!&q>#Sb2EKVlWV=zRyNg%NaM%uD^|LsZh0ID`+rxNs@k1%BR7yZRz8Q_^%^fR!*f~XkSjhkWg(T zP;U2}GJQFJCh=RqFHS4HgD%+ZwIJ}Sb?y5kTea_}R^K>L0A}68R22lD{w%rVyK%L= zVeqhJ{<%Po8sYhHTj>|T_i697?>(LP{&!^20dnu{ihqQ-BmfhPH<1d09DD;{Q)mG7 zC9eEO!2~n8C}J+{yVGAX@^REsp@c#WKfd_UYm~fdPqZA1CKu`WD3tW(d8UB#?gdHJ zLYf~PYGkIY^WYa!VGytG9Ka%1tcta}Uy6;CohwqQR`$U(LCF>tY`|Y5`?{gqfHINu zBu(3LrjYqdg5Hu-Jb$ytYnT4ctEv`1_G?t4HNst!zA!iwE*o|Vx{ntW_hvDqOrywd z%1nO#*DLLDi`+L(FBL|=O_{zZ9PAKiR%~T?W_bk08>ePGjMEuiQ>knQ(;#>IFQ^F4vxZa0_edYw9} zl-utTA)F&yL$$_CJ9;sHUq}MlH$zz<`26!)D5>3aPqZ<{9+i7w0_l z_s{JyRdJ@0UVqW+m92bSL21rsveU-FNcg~w8O4bBM=H(&EL^H4mToFBMdklXNLuMRRT{Y4nav~)~{v*NwVi>AK(2) zMiFP_sD2CPeb-uWRoNEiMMl$ECC#}QSnD~=gMHGVO+5+vl@$wE2sqx6B>lhEwa%3N-KjxpO8*N)M zFHyXT(_TNV`C1^8v5{*RPgS>5lK(D#|Kl468+P#0{dpDTp-GEvYU+sZX=^>-JR?NU&igblrcH#LzCFc4C|Ndr|xSO zE_Q7~*WCx~hd%9tR1c-DxEI#fy$3w;My@*Q zX*JT-n_Do$gm=|V^Ug+6KX2~rr6L{vVqt!GLVidg1y6%Poswdp9^(AIW!3Y zE5iITGBh2pyOBUgvsz0D5!?R2_qd@H1m}qnY1CoT{IBu_I%v2 z6glRG$Du7-LGS1po)!fc`)m3wQifT%D0Vpg3l>=k_4?wHsyy7+EMrf$T4gkBxSSnt za!7F)WBiuDF-?(5G)TA*0iSko47#B*S3jLXwxO!J$G9og&62c|OMTc!h()*j8J-S3 zH&ZVC4k_^gp(v{pj;091(WQa;dHLs%6 z$K#4zXj?@$$<|4RbXR2MoUIc$bVkNhOB|zQjx4qVg=%Q;wunZHlmsXAB;VLFWU9)_ zNnqALPcJfg9J_-=Jkoo8TI#b^*O;ElU5=gP|28nZ4&$9=AqZrg_dbda=SgNpx4Z~K zJ-5SvN(-ROiZ$il-IXdJD*7L9c#?4`7o}^TMEG?DKOV-m#ctO{*{>LWztV}4jV6Vnvnv|whOz2uC!0`KTHRx=OdDU)#@}n1a}7lJ z74_BANZG$Ndb2WnGN4-wus$zR9N<%a*IIB=;pnHLA2r;fQ``KJ?O_vV$+y34Oe@W9 zKsjOKOsS0|-<(qWba@pwB{SoqMACiHQ0dPP>S-qjW8C+~meQ%M1kPq!6>k%;yYdr1 zeRB{vTQ%xM1`2rmu>Z*M0K)uZ-2VkaMC={l9WQ`S*F*7*0c8Ci=pI~rPZ(<~iJ@yE zboPT-hX=W;>y?PIpaFFT1!%A=0LHUV2fwdLy}sH`ZQY)@B*{__~d zZ9TSB-csUI4Jol-O7nlc1is|-nV5cS+2T)^1&i|QhgYl0Q&*xqCbQ+eMOG8hE!+wT zT9`kDvulwEV2r*^I#0(o!GF-dnb6CbPnmMTtPB)tV_UYNYyd$1HOrwkB}eHp(uPJ0 z=}ONyMztz3qkh*+YG*q^?#keP8Po>E+8&c*v?})D4Nk|nfc+uIo&&I0CoH$_Qqb&vNFV4F z<%40n=Z8+bLc{bXU&VZltC3dl!nk2Cv^&8rJ>!dHHFl|1r^QO7a)^ zbeQUAJpkBk$|zlqQIt91dA`kb+b6UK<^(>_T=&q|I*3lkO#@3A#qYgkkC+KOCqRDsBQsZ zJs<0jDRr9@9LT#w1z(}Y`P+5V19WHMr{1u-$8ArHLiLV!j9B;prruBVQuW{CCFq{N zAQi_5!aTg6J?LabkoY`;1W7Ur(4ja$7MlMKRT_WN^f_Px+TO$i^3X-$1REd>pzjyz z4^rq0+Q=y>&Q0p`{H@1~I@|(gMZ2xm4ck(w+y>@JoX?T`Z!i*OZp@02{(XotK97fgawjmA3$1<5=u%*(vy0 zAk#D>3BfkrJUw+7jL~Wbzlervo`zUd6~P%yxxGnboX7pxG1MS^lQzW|ph>$vQHniF zinoUt!aZRPuELV;V(1e9i}lAqdP-67OCoelDXJikhZ43Yv#f-t=NZq~ z@ytH#`&XJ_b9|U!_ZzfRixJ9#2(v@qt>N30;reg8JiQ-4d7#mufN%r;=#1vH7Ksdr zFvPQ?0MF`PM3Q^n8E5TODm|?yi&*{iF*Pm*D(m;D=AW5 zX%=2-rY31FLdj>mGD3tB0!=bfO(3K=uPpfnY8rt}|8EIh|ApQpk)fpLx-=B)v|@{m zViM0(cce+!Q046oYu5-1d+}yD6nNDP_AU{K|{{xuI0vq+ETW zT+gf0?55J*r1Hs4fpk;$YDn(IF3|&sBKn!!>kCHh0E#9BL@W=p-3v4(E^#G7DTNC) z&_~7-o)>>UO5b0Iivi{jO)v18)OmQ-;e3w)2MxXpbxJL1nm=mK-Pni~o+rrIJoLb4 zKdLUyE25e_8K*%oCvf{QAN?}M-}lqhlkiM`H#FL2*p=5 z;}1iBDY3wyy-C@NpfCl_N(zOMHFP2=bDHD?ESLn^LG}Za-287BxOB8QJlt6d2Z4)C zYW*G{#9dbpOot4Bm2u1P7s=$fbGrA!1Pg~QK^EIf68ovdm$5p8hqZo=0{H5`GC_0{AGY^oFpP06Q@P0*kC zIR$?Hy1rQ$PGBtJD8kiZ{q&q#-`^a$U`{Nrb@PPfA;FkKnKYftOecjc>~f$fY02!; zvRmpSxZd1Zn?v#)y*2j$f34#Kqe%5j>&8oc4*o6&Z9_={7dw8N+)MoeetP|8YU2f~ zcC5m8_-_q}9Gn*{uZ~uc!zmW50M+CEXz+~97(e?Y5&e0nEgQP!h^A#LKX(+rerL;< z&)Np@N5p?GosrsV;48ZAWaTCPFQOdQj?Mh8$z}$})}6^Nkw2(+-R#%|THM~5xk{T- z#>Z8)AP$J!-ll?OQr(`VxO4?nzpA%k@o-<=cHxn>P~v}QK4PzchELqePN2j8cj4`? zuO{*MT1*~ZAy=B=#B@s=C7&IVumzYa@jP4w91_ahUko~;4AX}Ouq+68JDYhwGqX+b zh!Xbj8PRdD*YOL%e?x3VVmCHlw&cp^n`JpC5OnY-6-5ph!ys}qczCIzgvk#bP5&0-k*Dza5KoT<%ihSBl?L@?+YI-={* zp2ApwP?}m2g_`mrv}3n)qxJ-&{-y>NzFByXA~F6L_qQ#!IfYR@_V1R*_9)!tJ-ILBg3<%YI64vQ&Gqa=w<&32PO02w4T924a8S&}YI#hkgUzUg0REvH*mLnG1<;?JT&}8{n`O9QKdMq*Dq(N@B9ol1ko60BJ(&1#!nT zx&Ekl?OGW}-rkv6_C=)inYSUoWW2hLr=vlKrE)9v9D}uesILeUvrSDvMjL}j*V)Qv zl%(1rOVn+UPJ_Uw1#+Ow0HMwE*|DG=^nChIBs|98i;h9__v9~Mim`8}us3wN7dpE^ z8$w9<8e>tooZCtdX?ughaymz5ub(9#eL(#)pN3ns1I>pMGYfjV=~>^&7?@d2V_2({ zl@j2S{`I!V;!aS|pIo(o{4&v>&#(il%gWVrL^X2_3Xpq65+v%^8lN1N3jPc@KIFex;XqP08|FkEnd zOA9jD$CM_WtX?ZR=$a%K^P9Xgc<4e5cl$knE^a+%(K0*GTFtDaf#^M)q8Ay>qGQyb zNcFtGP`=j|-ypqpY~=YgJa%VJm))sF8|Kl%m=eOZEI9e%ZZRNxrpL>}$`W?#NQR7W zOym=*E+>D7VZ^BRbcASianENasi%MytR(#?-)|V4~c=QSx@)8~=-j(dJ_2 z*j5n=b4Im`Wl7(M5-E`+0ii{M-sy#)p2ct93^F%SGQNdXet)6z{j3+@&PNWK)Ui<& zz7-B|yjj)?1m4Nd+fZ#PP;Jv0?qRHLe~_ySku2W?3C`W_Alpl_(LcCQF%&7{dfsnQ zukGRdts!2YY`#||@+Z7?Bs9L+*YN#5QcyCdxA8LYEp6Sw`}Lv4^?4<#inHh6k=GO7 z0ksYE$qks=CLoFJwn?!YKxTNhN$c=~_33eA0miQBlqp4P!so2F8F>@y+g*X93%-Zn zKkt?Mw$_WQnK|qNdAklz_ukd)`99qb#RWL?2|jP2F`80e^B<(t9PDZk<9uPMxT5Bj z8W-z4OTWny>7W)DK9`g3EJl}7H+$2j3zZ6xQk3Ct7MQo`3-2cgOjQa~Skl0uX zVW)ur$5Bl^r&I-#_3M3l|5~uegm`?D`qTu0>Q6A4PZbFIS{n8#M1menTDqD^&uhY4 z27CsA{ksF8Sh#j|B>_Dl*yO@K;p&@x5rk~uaBHr@!5|C)ucq*`!r@RFc?*9BvhA*H|o7%#mo{-KA6pjFjHg&ZbT$s z<=1M%PWk)Osq)2oi?Ix`DE^afo}BZ$KAyVSPCg~K51AXV;?V{MJ;pT;APJtUt&W*EK|Vhz;o(zLl8Oh| z4i%9G$GbH)ms;PNMcPg``+E)0PW>*a|pnBpkY#N43x@Q_r8{3xe3S6J!5kO89;)AIP&!%v2#ud$D_}9bDWBK&! zLQ#Yt(#&!1*=4}-!sq*i36kQRa+FR*dE0S{@=BJ;0%|svDOzUbmZ_ST`<7`6fh=#* zd0lLFqXkS93Y0wW3SVR)PYdI~fZM4mrzb|gqA)7@MYrfz48l;+SeWcb4MjevStbFz z_k~us(}s0%O2xu{afZWaxe}xA*$ZsQvSyTho7TWESw+pLZDq}8%(qnylcTn*_k=QU zYdU%(!^qsnorh|AaaHW<2dSd$8b+Uv*)>iIkD+H~BQ@ti_+M#hV%QadQxI>Tu4Fv@ z9yVece11n0PjW7)sm{@jae>W7ttnV7nfT>DuXlpmai>ters$gM+gnoFo>PRGL)m?GdAz_SA0NfUnhj65W!G z*|JNG%5a6@^Vl*>FKHfZcJvE5@sF^24DnTNhO(&S%4h?=HT+{tiP^ zl@!AusMPwQMy9mwLVR@aL;|1oKFwwQ45u8XK&c7s?)-a_|7`h}`oWhk_vTw)61PpK z*cPzh_}d!E9_Xh2*ss(;H-XllcjNH+6SZLs1Q**K zq`z8KS^!7(3=SnNXSHn=@&MnP>-96zQlAhX=HN2-a=|TSNT1ap;FpMpS)^ zZ8DCFE_U}7Qql^j!@JG#dE!HaP4eUNDYj`6u7`fNpC-E%SuPb>!d}CEpsQ|#2=Z@? z1a>6|TAfZvbQ6tRL|UYc+A)?&>d6^k76HSOnJnf)@xAjjSi9v6{Fc_kjvZnPM8H{kG=9te?_@jS-Y&waF}&?2I6zMz#g~M`}$?a@>C>0 zTL9m_;*yg>|5Mre7i3HpW9izBpNU$MK17nB)nU3qO>^@ps~rtySHEKl@FX)FDaz|9 zFAxPcN4r;>|Mt+Xme=V(Hs0I3>Tiqm2&S<{w|(OjhP58;Bha;7yl?1gs{(#SfH`l8 z?kc9cIwXF@CAxr4G9cLI2m6t&#Zl|m$i0rl)I}6O*;asNV52oHB7TL`+L^O`zgf5M zfIj{C3L?6JG!yLG;c%jn(?m}zXhy)xY~EUuzTVgN=x3?H4(YQtEq6%k+sx*Q2|L>S zC7Du5Yj`Tj9X~C=OFV#=;)E4*H$c3%l*Iq}%rWzLd*~xb$AmxdD$%M+$+$i) z3VWBc(zBWi)!wf#dRMXJ{X{r>qkx>*keMzqpuV;%9ml@Q)w(obto>A_q)Lgo@unh> z>f#kBJ7JM#v4bHTNlVlbv4{RkXg0CNO$CNCB2B(BPWO#BlgkMHxxAJ7SnddO!-+&& zt!=6#+bxx*%4#%6XVB`>ErZYgt#4okt&dDypk5?IXg(ja!k91d^@**;o{+!8QScYIzk{7Q=--XWUaoKUn7OA(OPSl-I7NA{`7r*j5)wO+k`VbeTE#DGJYrrZ+O2a= z(A^O8!H)KO=B%FsztZA_Lx-}+2KZg8%*C4>0#OFgD<|@`#Ohy8sUqKTTdKd@U^oS$ zd2NvWIvv={N)VJl8UE4>syg^<22t_(@t5&u`_1TC?4sZ<_t4o;y8AV@9=xZ<{ob6_ z@qMHY#j%Wl@VP_Hd{5j%Z^!o!$|_TEH%ui`l50iaUAzeU2Jf|R?WYsIFYlM9(5~)I zntmm$|2;|~yslNS3fDMGK3sTO?~U)}%$KKsK4pG5`OW`u{)Op^CTP;r z(E>%|V;}Cm4ic7xhF?c)3)S`C^YB1V^FK&c`?aWXq2qUI^#Sf_jhp69=nQ@wfRH)^ zE~UzbC7!6mZ)vX`FiE_R(A4x>;a38Z1quOqTY=B61+JI`Xj9=V@#^O?a@aKfXv6-4 z#ev6H9;t5vzybl>%$^G2!5!Mc`&Mw6IXaOuAQ~^?SO;cU^11u!E0q>F)f)JGNr|g1 zSc@*ye4m?_M20XA`#v7>Bmo>cV?Qt$L?0f)T;^-&8D?AtXAc*%v~AVQ9n=uGWDN-3U6*h_veLHYCvF{TP}K}8d@lpF8rT< z!&4*-*FBlcGRGQioOqx`n?$Sxy^Y_F(w`wO*r%J%NrQHJKPOI{d>| z&lo4d@L!%R%Ytw}I0}KUn9A%Ii5l<4IC>Rgbi>2JwIb)7XE{MlkX1v&k zL7lK4ixN=+0FjMIojmYs1@DHX1mGran)qFDni9@IJe^r06Dcih8TOeUMtl&d=MT9Y zOfcAwKHT@AW=W*$30q7`WL>6_!1zesn~2@x35J72HzFPKAX}aR0vH+xB+299NaHMp z#PpIV85S|=^5k)ikB_Z)1S5~-2q=HkP@ZGBsN2LQDMp~(ywS8VK3Pg$5KK+KNJgPi zAC*LL+u+yrPhlfWlx~X+QcBYoOq?OH|EZhGk(L~FBjh0jBLldGI6c_n!~G9Znov?5 z+tU+JJY5db^2^flg~U8CK*H)Ttz^(N>wMno#j9Usyd6quAkC!F&1^|e$C^p{+Lv5J zO7ZC+(*T6AX@WP?E!Y~I_8Jv{)`4HbB#7tmMyF*3)00AM(iS7K5$~h&NVBA%S>H&X zRM(@+Z(#o101qo!(Byq|C{z~pw{I#-3e?N~t&~eOVmG4qVdEe>raYG(ABj_mfT5b; zrugSv5rE1@avTvTEHHqun^H_Zd$~OcpEZ|oB}6tn7k?=?XDFBakOnUg&xr$GY3RBdFwK}twpR?BoqP^?Z($X&;jmPv>E(@_O3yUm^s3?mXEsLpO zn@P;a6U=Zvpr4#{$Nmr&z`iKxqT}QW7^=66Rfp zbLoVWQuroSSS+QY`UxDT0+zQUnTHKZzqH8~QciwZo{}|EnA?Z4p^n270Bwy&mEc7E z=7a_A0Ue)W$~Zw={c$nRK>M6n3e#v8PRzh#SFGeeHKNK%)!+1m*I4WEdeAO8(dDKw zf1ZLF^$Y*l)DU^)^LrIik0t3S(Nav~Saj1SxZ+9Fqu3=vkpL7pML#(Oz#z<31neg_ zY#Q-Qm8bj(R*{o(Q!gCjhZEjlL_8yT1MS-=;YehSx2ooN)Fp-zPP-<|;YS`CrP>X8SuH?%;Bh|+O3Z%%u zretOLWMB|>H7877T?5!afThSwTv%nuTQk6|$w%;=j@EZr%^ICG#~H0Sf~_eo)Heyu zj62i-EdpwWKu>IoT5XHN0uols?W5ZDT-#ekJ`^4WA5_$2t+s2CrqOxl`u%2fF2Hlu zWb#O4@>*b$AY}eZ(_---TJ9U#fS5@E{BKa>m+xN&mZ;^LpT?;I@a4a`) zd^_jZQWtdmP{z=r4XRn&P?%<$*#XMzxSEp=cnWSTt1&`Y#i(} z`m?2bwG2&h>>@w24ZJdFWiRG$^)$xgM z#}g|)kZ32!ch$)qyUFhqlUqKMN8^+G?2{+hQ)gL|XR1@jqEmmOr+!vV-i%MJ`b^zp zPb0CXm&Q?$b!2`FV3q_Cioy3 z+0QG)%qvyTt4z$xJs)J4K$2i}qwsT1A7RtUsW067Ea+7)JQ-NH=~{RlGxb`8p}xewi+R`QyY=)9&(%v!%@HPrY2reaJTa-m+BKmi>c`kq$Lpyxz^ebQx{6OWx%t@apYMe8+XT1Xfj@{8W-u!BUcPP0zaa%Prif{FK z`}tGY3#y%$;xLDt9fPN^p^U1r(LN8{e#ZPgoAtf7xcg8p;M4Rbe>c`e9&Q0_5rFNQ z8}CNvYtI7U$Lgj(Gcd6}!FXl*$gVhZw$|}~i^HTKkf?4vaTD@k zHJ(v5r?hTdYbS^o3@_0{YP}alW*YMgJuDVL705&B;Ka?LgSAT@yv7B@IPnV9p$U0- zZ|d+dr%rM4&LD_0LdP?}|BP(vEJp@o_Y_Sc9{N~K4Kb)g%dDg8Imbbs!X>Z?UY~Uv z|0e&AJOk=#?{8~CV;s=8b?BYvSdJIZsDG=xfF(H{g7bkz09(}w^@y{L-tnBd_MB1U z;%VH4vczvN=#sGky$FUXeu{Ph!vN=BGUc8(tV<$E^B^lve}Mr>1ES+?wVnrD%X*CY z4cKkw^_>V&(FRT$FD&@<+QM0QhKsWDB`g>Z01MZ=nAwDCOrt%AC47G(Al`y2bz4IH zq+9~lj==u)^oFk$tCkbi%83OapvY6Q;#%Ao6By552;>aCPrZef8gq#g)|9u!IP>=l z^2n!JD#9w>{>wb3EPo4MeHEa|Q;OZpiF=*VWMK;R+ zgdaX;9cu4?;lW}6Yzs}?K?zaF)Uh|$DZC2}kTxYp_fM&fB;|8hYdg{!FlYqOZ#*pW zK<;1+GTCA04ChSIJL(eOQ z%QI#(B_C*(6%}&@T{<4`L)&a}+8rD1?6UO#uEF5;cKv1xfe9ZF9kW5I$j5oKOD3G-JV_ejewcSMr72+6L%Z~e*4uncdP9aa)27?9n_TE$hT!v z6KVcXk601Cv;&$Q@y0)Odi3KS^NW>9DzAe3HqauOB+PYYLJlu1hjdYU#X_m5m!;~2MDt!EQ%b7~SePh{x3maTH_)#$$J zS|rCb>*?ozYJQ@Fx-yn*AaJ)A{YnRABU<~D<-4y|_LSj6R*e9Q zjrO6srI*xa^6s{&#op4I?}RR_S(9tIH0YTYM6H+Mx!fw6!QP>gDq`6_%nYR(dzC8& zBf8^nrZucd_vih-JxOCON`A9q1LUP-*jA$T>L1zQ4s25+{XkBp)I7k_yFBwG%8KLS zOkd%{^2*P`N7bM*M22qL{tqHM!*Aqm4oEd&r>2FcYlpmDn~3iL)78U)?yES0#$yvi zqV~PZsCmDq;PdDa?%d_*CfaEHULNb-SN9$b{NAh;(JN%b6${!lrD)l9XBm7p;t7!z zTi-P&LOR(d2E{M(<31?H5WvXb0Hf?jB#M*2&f^FANqC{$U69Jb zBdKu#0Uk_X{t!3}(^$m5ENGPk<*nc}u2L6QERaU`mfsooZp|X@18@3ER3}_z>}|;9biVwo zXCnWPan1JbP>}2Skfg099nXdW8NbU2-6I zaOnQy&fpz@(TAN+j7<{xb{tA4n_tY~Tn;xnZ=n4QWmI~H3J@LR198?05Y!(SteC~= zkao+b&E;@guq6H-Nw*{sB5uZME)zfkRvLpC{w~rlGdW3iIgvCNyBz&VvHoFD`o!^o z>EQHc`aK>V{O7=FV=mHy3W$x5RkwzwkAAdN5WCfgCqoelVwPrGn~B#|!~^aMpm6>G zyqdf>Pky08u|Y<;fG8w)H$Frf?y>S))udN~u_w6sRWGII=zst&3Sj!!y-&w+pcL1zP~*FR%0-7pV22s>y~rIQ z!*Qq~W<%KK^`wddCP(Zb8EWI!muIbY2F{+wGZ-+_LNe_$7({YFQDBl6?A;Brkxd>pn~ zWBQA@{b=>s_V!{UBhL_~#LK58=+p2hx>HlCbAq4ND&8vr6s^s*Mm2UeZw&xg4^<^| zFWllRmQ9bib7kkJdgx!Ht(tdT6w6WInlmiMG$~4BXt#s+-_?zk#m)hoTHmD3gii=5 z%7(T|CY)n~jX>=_^4&TGI+|E-*+Q(LbT!*{XFR()Ha?_@b5sCE{y{Xje}7{jNL>cY zb*+%1Nq34y;l8qE$M*dkpddD?GtCgH{dsO9xh^>A_nz4Z~1K7##p;+RPW z*iq!X=>ujY!^s55j4ev@VP@kuT;7>f zDV{hHpZyFsf5IPSLjs~_L2_4j%L$QZW}=qjU>JD-IvWaYg^>c7$XZvPplPH zGG%X7IGQj5hazUY{Rw7ZoEd^-sE*hBiuI*hX| zi^}jQV=?N|y&~kEJcfP{^;6!Euxx@N5Kc2+m~&a~SFNUnN8YQp9Gupt0e6ndm=7=U z_;m8Y(Pz)#``^a~g!_9(e>B4l2$N?Ij;~WNli?|cHA4?5)*sR`<89lh94H@q8l)j&^_jS$MGu#u|dq4Hz z!8H%fXkUiOYbNIB*%hVHfr^#aT=s)op}m>ZlYkzxd|&q}E2ATWJ+Bu<>+W@7M#tt% zA|p6X7*6wrWL{;8d&e}y#uS?TH3>2KZe=u%LmFfs!QAQjbHctRw&9C3N+=(8&GZy{OM=dEsBJ zKR-ZnUx@SsaH6f|OEDNqGulZf{SGd<0dd4bOAkOk=qNNB5SQyPN%Bv#I)+GS6V{#QAc|XKyH4Awt5Hq39@w@ zWi|;N7aKT*`E7Itqc`%(KB1!smq2fRM-nR9E%W@J9m0O!KB&v7tOkXgCi_5W5cKJ3 zfRra1m`6^>M@~0-K!zN}wJywI80wTHXS60~d@T3+PR;~d-jqV#j9uPbRNg{W-qKM1 zpPfM;dFyC-n=E=ZnF z6g;C9-e)OzRVjFPDfo;ld{|TPJy!6$Q}D-D44_a9WLFFlRSZ^D3^7y;wNni9Q4Eh( zjL1@qtWu2XQj8u~j9F8RJywjnQ;e5w^8YXXsVkrW96@eCVgDNu_%HJA>c5G=_y2&v zk0S6n^6KA3;71SmUqoQ!#Rc;B@7u@UKRd|Z-~IyyMxJdwqQJ;s>;EnS?;}qpko)_{ z?JeZtz{CERhwYX}4*2Nk=zqxpZ~q4eywQnVFG4OZAXn0m3z7dX958aG2087uI6FQw zGc!Fs{fGi1hliIYMjk$OAe)2MYZ1<;(vn0;{N~{D%nqpB%8DAd;08iJ(Rj5h3C5e>h+a3?vH5 zKO!&@fg2y+e-nYZxw-!*DDeMW1a<@ddH#R?FQ#F4acK1a#s7us1&x72{=@&}#~Fr! z3jX*0FJA>ZDXNpL-0)8B|Hc2E+-Ye3SO528e(Qhwzq+J>&0nvFEG^~9W9)PpBOW!2 z_-u(NYz{K|gITH{!pjsB#5#L>o7-;ttZrrYDXrx zh-q}|mbp;-eZ1xq6YiEPL=?+Gt(lFbikT zzxls`2U28I!T;j_F7KpS7L<2;DzOUD`@7B(m%4bYw9qGO=#Tv4|6=CkZk-4M*s}Eh z?*GbJYxEcXi~k!XFMLqUiH+EfVEw9uC=-v&$SXfSVPTF5t~orctm{CcQGXDj9hFA0 z-Nh_H;n2-{^nZOvDr>E@yTNcyA2QP%uY!zR(k4_>Qnrw4<46Cu{!Qh#AWT?K zuRCgV{FC6F9IUx|M_P>Ph_TODrCp+$BDShuUA%K!Z!eE(lkU{6HlVVvBx~B?C2TKI zWK~V*KaB>WpY>g?N0|*kcK+7-fE*wF-=)b>nk1-*Xm;;DEyc?b!l9_MK!VP{=Z!pl zSV@D3xJBnl(W|cY$yS`T)1Jd0Vce?hW5?&S_=|R~WjtHQzuhEX*#B8b&@#%LW)$&g zk}|*J33SPNMW@c*j(y=St@L8Z&fam3$iu=FOIyIC!t7i2SFbDN$(5>)!XV!a3WiLi zBwp9XfxRUbeeV*OGKOE;e(d0)D|K<~V&M7K(U0$wD7d%#MNw2s8%&j=@tfcH9OAca zs9y=?aCI7W?qte*yP3#MGR{2sjONF8>X-ks`4H#_YtxuP)Q3fE-DIXXh+wp_B1KJX z0nEGO1QR6aMu}>VjeTbC&g+i?o{Jp=eIO>2fEUxpt>0prN0m_^}VIM{1CfDpj;-2MS)6Erx+ zHj{1Rn@xyde}ZqB5`@ppP4lA4Li#DogspN!2EP;n+B!0UqI{Y(%(k^T+4k71*YCa$ z0jMu%f~nhnqdfzlSPJ1WRScNdixiJdL&)m6%(4Bgw-q23nYnM!gDw5{DoLSfX;ECOPHwjPcmh7 z;d}(?Jv#LH{bFZCZ&86bj%|o6Q*7O-Gq}nmOw?f$9EMqxmY|o(R%8kxiqFs56Q!24 zfyauT=3%8NLa>i|!Vzx0p}kN^V(ys`hSNzu~f%k4- zft#Z4rS;{jGBgmY8Sz`{nPwn}^bYM>UkaD|pT;;RR^XH@tr-PGc5#jNTR3AOfUp6S zjgBTh84$%lK~HcLuD~vxuR@EwmZrSi52c6B2EOi>X^@LPkR%r3_yXR??cX0_$vNon z<9>&T{7~cOM>JC%|AQO?1BqWC;%V;su)65dog5qa|9%w6Q=+fQzF-x&lxKuEn#fB4 zJ!=<&Ivq3FHNMRHo%Fi9PEL}LK%O5(73UI*;LDC^z8M~o^j7{9`5~q z7{;MN^u-(3v>Y?z~;7 zi*2sbun!X^ETpbTYpyZ<7B2FPf65#8-D`iHpbvFY2r!jmfZnkgiAee&KYv5h2kdPd zgTE^x@(l^8YZgMT>67cY9?7-rKV1ZXwcS{rjyd~XLTfnby+62f;kg6HDrw?hl$N?H zj>>zx5Q4qO>cOTlBLID~6V3O~(|*q6hL@rTOQFPzga7OgA%NwsD>>r6YxEQ`5 z@I`@&V2;#;A`gjBWE(VHwi15p`$Oo_D3OZGf|3hb9Q^XkAm=FUXbbbt9?>PyLwFQ zMGIE&i44+k{9e=b_x%6I(|y0Q`9ALBzY{_1*qhiCwfBm>x7MspQ7vlJZbIx)tEHs` zwOX6nH1;mFSB=`Gt(KOe^3C)0{v6+bAV1v4apkyk z*lV3*JkH#Rym0b8zsa7oa(4erPPmwVFzal-5_L4t6&4{N5r7DQgWH$p6qv>K# z^A~*+xqgI3H{F!%P*gC}wzmCTyLTF<9rcwK7kmlbBn`%Z0VC9d&#RNRTIWJX_F~72 zj{8O$Uh``n0WL# zt;}9U=XsILxaICA*c*=R07H< z(aHP*jTWT+DB#E+2x4wYOkGM$$6X|*go50x6SQ2KwE5!0I=}p!OOR_y>QZ+X)+S7gnJcH;-|3& zBN>v#phx8d1OcS~GN6Zvv~AG1o4s_lzm_LV(w2FO?$USeJolZlwDTqe9Cq(G^W7!d z`k(RYpHW%q|2Z_05*L=zQkkvLPS5xfhG%2%!U3>4NPZWhmc)KkdH>r|CQDo9F?CE1 zqe&6H-Px0@aWA`uSi84_cC{Y=fv@hN$*Uv5l7q>nr5UZo;9zm$kGwE*=WtL)&U!-* z_dY#*%(EquN1` zj&i{~{!eU$`@8*5Y@HX+#*3|M&Qwb@h{Jr$s5qQqT>u%_g{*5@_p!9`50av<0!8Ol^uhNdp4yfW zzbbmwRP^*`M6eklVE}sk4n`#@b8K0xQJnP4S=N7aYldwBi38yl`8o-(}zeGha@M&0Bt9KO1a()qGI;uB{#SFhh3mXxl&1e^mLQ+u9V!*xN?F?PO zndoYhm=s3PcS03y2J`dyPi_sn1vfLeK@3Mz{y zEwb_vKl6sm42vhNWQcUA`7kqqU^$w$u>DYYeh0fkhv@&5)|&s6))Rh?6LRc{b3&hZ zjsy&Esy;)&^z96cNK4|v-*pNW;R70-KGIJ|Z=;sW`p5FePz1qnVpeAu-Am|Lc&9Z^(m4>P^bd7-x@V_F#i#) zHJ2nA^hN+cq$mw3z!rXQZ(w6B;xb^3j}gqvdY{29WVia>aaHhDjL_@8#&?2MKMh#5 zmI4Sr5j{?7a;#{o?NfB2Wsrr#djBW3*1lAB;UceErZ~@_hk= z`hY*>i2u^N#on%EZ0k`FCV@yjG8qB$FyNS6LEo`&<9X6{KjPNS+nkD&j$XSCq)T2f zoRD}6IN5^~bXLE$4{jHHUosx~MyWkUp)QlGD>Izc0x0OyhXr_(L(Dp>uJVe66FWLP z(-%9R-Ri0qMlVEkM|~>7CBafg%_ea9P0aG<^+Me}n%(`+yXWx>N$nldD1b>Ik~jds z!@q=|+QkFPryumhCHBDh+YiTkmV~kPKlA;}(uuiH!w8$LtCsC|xy9ojjF@{XPO*rC zk{;nYh*913VG)oFL)<4NLVX}D{=lizOH-ZM?AnV>?maSWXJzY(0e$Grg$*oIJrwV2 zvCjqaJB5tie-aiKxlZ`biWQF>_`u5iUm8cmW@riPL()ohr$=o~?#9q%@~F$!w_ItW zU)y)!X>YeY1|}U29L~!6?T_14 zs{4E=Iv*V~TCDW}*B`#(uKM)JnGCC8;J4&V&O`SK3Q!ZFamphPa!2h0MzlnRliB+F zg~ueghQ!T>a;}H}<`0DqjlMGKsZG`QKhA#cJBnc&3qEd)LJiAQ54XPPuM+7&RSwlD zcQ-`R7P1W|r4Bl!j;F0LKC6b&_^JM0w`Ym)6&oSO`wb<<5dRUVOZ9|L9xgsi zU8GlDjCwu(ZG7?NDf zUQb+Yr@*Qt)JYe&-!`6xf=D$k=Nr2}38yZ5)GQNBtWADfCT##w>(es%=k!ucX>HQd zn88-XNn3Fk$~jnVcGTJv{Z-AVh5T=G=f`Vs6LNew$pE6xpJs{0uek@`II2XOjN&hdPii zGEXWkf2LhEhFzRI2CI|$%Mb3UY`&oDt?FK>c^LcR1mDtvbO4l}y;cotRyz*2)oxdP zU+9(&0LLeUE=H|z$Wr3d4;jvs;O}3q-q8;{gc0~tipco?nI={)TkEV@AAh(tMX^Lg z-PB-18$V6e?>ycY1$%F{R*L*m|8UvD1W_{kd4qi&{D}ZJ4S6RO^=Efiess?1`(j|h zED_GU8aoQeW;!VT-b#srIb=}1JRx{0PF1O}A57U1+P(4b-v)@12#1Vsfg2KTy@8*& zO33=zwmho7?OA*Cb>psI<0H=o$0IkLqc#rDRt}HuG_VIhYRnnzyl~XX;W4xhoR`CV zkQ8{w@XO?vpq|4%9z_9F*sY%CQdL-)YGr)OgH4X_UsS*EIDX%Y{(eySy()zGu^DmV zrq5f<-dEKhRSOSdICkfHMnfn6ivdM`-v{@WgHd1KMjxBLI3{}L*->~B*m6Ry<^i2L zp)NXs7J*Lw0Uj?v3G9Sj-%qHhJVtwtX_deIbyTFj-fKI1Y+bkuuiw4LvE}-)*Bz(2 zm#7N+KtjyoNb74)UiNzD^XS7$Z<6mABEt+a#hYJ}PN(8(r)}V>x`2($De9951gs6n?YtyTUJwlES!FO)xbQ{X?3DQ@72wZ zQ2ZJC_sN{|+?iwV;g3K4%sIVDv44wf(BKoYmm*o8p<&VRR$)pJX~_$E>$ zyHN+HGNhB` z3XSXCIpa50<`wCrX#y{Pk7qvFa~e&hE?Tc-`t7q&bFbejZ9WKRIqD|*p*t-?`f$x5 z>=6<_+cu>2&%&enbK5y~x$ZS*>OY6eps!PE^;WCXF38H#bnxw52FvdQb6qu2>IEConz8x2Kc-Wq(&;49 zdF-Po=;v>==j2Jl3Oj!AKS+ z5x+KLVDcile=Iai6Z2MvTSK;uIz`x|JKY|}0+|^x1-nG_Ye_AGN8|3!ciW}t=?VDS=`;~rtYF`2Dg-ZC4dC`>1?LpoWYpX`K zI`{?ESTvdV}ssFjt zAnaGFNea~Sig+L1;p$o?okS-*J?KxxZ6>JF0RWXU0n;y@5y06D#C;u0HXv1q$f!`> zQ=kebL}4H@!&({~<4KID5=$(T&MjGsxO@8d*t47&Y|Bba#RGXYXbxGZ*m|>dGloQZ zh`?UZelW=)L}6j6?Pa9KW1xQUHqkHg3BH|-xB-voN4A;9idxBDM6`K&|Kmj=8?}_8FBz4+i zxj(e#Z<|^u3EDPDrkuS{X`lgajqrgVqMq~p8<>blmN4&NC7{XlB0xd5*?%L6Ms9^j z1bX?xBMydC8oA8vDQOBhMYEMTe;LJJTLkq&w#4%rV--h0gb;~O<~a>UF{HG&&LCAv zfgQ8rNpoDhcw>us*{FoUN?0gQlRd}`MnH(btj`KW`HxvEMy9}>obO(5ZTPb8Y$+}tdd*|zEWBTz9M-k0?*O5FU;=Ut3^475 z*`$5ov`%W>IWymYQ}nKuVtmjs@KvVn#h`%$TM!IycQM<$J}@u)+B2;4r=fyA$y-KY z+4kODi>TMMch_5((a-~+w&~L!tp~7LN3+^W!rGGPE6#{&>9D zLs?bl+AuErt4FqHcRmStYnC8#EycAhL@9B3=X1TIT-)DnKeUS6TH#qpcWup`$A2%K zGU}};`Ji8$Ju#_|dKW7xiEg9$x?GtpYy=qgs^cq0TyTXK{9+b9`T_2_Rt56|3&zk? z-Evoky1Wq$9o&)QeP1_z0%m?zOxE+D>*`Y>9%%uKU;5^$cHE2#eY%By#;@0$S?4_w6-nR%Vp{mR5AN_I{5CIF@_Pu8pgO})ep|L;u&;Z4htsUib8}&lO#sMz_7Jib?$?@s{aIOxVRa$?$;kSo;6tkCtL=}1>(%=(^2oL| zQWD@6?ouL^P&eZ9qla>L-?96}P1*C#u9u{u!u%p5I=NpaeX^!4sdIO*{hXrK_)HI(J+&9p3ia>?UA(6^KrQaJv@w1 zfkyL5#(D(222RY}3{Y%-4mu#`51a-?o}`K+1kYz4tFNq4SzRz4*mBm4m_7<>(Ih?u zHnn6(xxtYK>Tu1A1jcGd-<|mIWl{wM<%)Bn7Vj4r5()O|AOD?ll8vSn(-Y!-bJ1iN zKK>y(V%1bs(qv+rZ4;wS0U*1m$=%r|JFh1`JqnARz{08!I%@7}SIdn3bPwxS8LdC# zV1`rbDH)v5&zIDMYDbq}l|?)DHiRUlk6lRahYrarpCm-Uv{;Je_2BAex~$UJs}16( z7lUfizfv~9zV(Q|^B<^IDsG5?;K}Kq*~^b(3R^Ex?YekYsOoQ zp#GMsooQkT-LaQ$*q??dn^hF?wJI@0P2iwe3xlQb1;}==RMiMV2Q}8p*4=UC-KM4~ zW>BaXp(BtTrYlYm*cFL6VeB#>*M0p;24P2u74SAL*!}$ zQ6C{-Un9^mBlOJcc7dU}2l_gt$27pSI$R=>1WKaSHEO*2up zquHy`$l(nT&Pb`u5xjw}^gKOKg%zk#o%K^e1`ux$WI(diRsIFNV@`1AOw4gM2j1 z<}d(mVeruhLcU~b_;!$js-?p+umQc zMrtPNv7}SRfN92SdZbj}vyR9^TE^VE8$*%W7pX2MBhS1D9!U@hT(57w*1~~wk+`t4L}q_>cerYJPFwvu=x{!nUN5l79KRMZ z)=1t?r_@{4RadU1n_Q4gu$k>4jxNCyz4g2vBYMWCogbQ@R1sAO&|p-6ZmC0e6R(W5 zmEi-o@g%FEa(STBEM8k)ig=T@>#VG1tvwm>mMxZ1d6U+CTEBI!wOP|}z-VI9&~UnV z$X#UOEplAMn_wbx(qm-2w$CV{3)(0toEZw-8Og#`(;4T^i9J^~F10sOAsBrQ1x797 z1uKW~T^=$+6X4>VB2*+>P}(%#WXGucfz;#|qu#l$!ug%Cp{^v2(#gcrPJ)asj|=J5 zHNzTT#z`NYjOpCPatX?}$IA5s6*bOi1&k6XiiHS{V5&?LFoUj?e?ueFIU2n(aYv07ZEZ*!TU2SYE zNtv0qy-1mxV#QS@#qPBB>9hdYd~MC-nK&q4A&y?f90f&wIl$l28|L|#_c$b;8i-}K znQDh3g`Q94XeG9l-s1dcu1RX4#bUuoZ;s252MoF6T^wdMc_dsDb=+5^K&t~8aKN!W z1qik5KC>YEtvpTJ%^^A~K{2bbTP9UzaY~nTzhG9C9xCYd%v~H!e`iYNRQ%}`lysA} zsC1V5pF|ZmSS1G;BATMcIj(exq^U>agofg1KprzxZV zFtts)+r5dq(=QE;)zXXGk@04?Qg4c%Q z)`n!_T?7d=kzgA6yJ)10?JAVqi@@@rISK?Ze7=O$t|lE+F8;ha^VL4-&64yyG)kSw ztA9Bx0Lg}okpx z^?;K5$H?lTEd_~AgV)^UiQMJm33Qy@#N*xch&;@Q+>y@idhtXd&K@@LWa$no!bIBs zG0!JAeiKe7duUrfymwK?@%Nsx&OEe&MSdpD{$CCBh618(B{&*qk!n4Q5%g`kA9ZI{&u%vFk^m?R#RbSR*xSidkByL+Q z!i{=QsgI7N6E2Uv<4Sv~c&6u6;cm;uzSR}Ap{~=T;aFp^E~`?Wcxp@37W_r$yA5z+ z(1CEj{M_;9w~0~uf}!K{50h?OwNTP}=7;RNYVmdJSKU^H?#WsPF4UIR3^WQ0-2$?S zUj*ZuCLJu+Ip{JFimL8v>pR^1p6YiQZ9jULKEi|F4F_wUcAoiAOx7*E?N2$LLFM)u z%y}^id1%|bcxvcvf59ggg#1j2QposFn*@7jK@<~#Pg{bYAS5hy_knD0>`h|S?o6o+ z3BzqAoXlO1?ppxX00{8hNFqWy-zF;pu>dfZ5($^u6 z3eDrYNZ|Z`8Y@(0Ga(lm=gX96cM@0l$NOB=&ZMQa%p~#8TWap$J=xyj;zB1U21Tv* z*MFB^uj79zZ=#7S0gEM~t!< zRq#pUNKrC--EQLQO!;*d$@w>___DnSB_HFrln}KUuTBU^=n+R=b?_$O;5131eUsfW$G6-*< z#MqAzZAF9ppmF?A0v8}2wE1v@0lLZXC}vu9O!oU-BAeUr8;#aEb7UU-Dn=RboLA5u9%_x~MsaCkVPb9D7cK2GQ5tgOTI&5p>+ zSs&4pbZ4QBZ2R)Nk1B3wn_RvzV=1#xEJNj?1O5E~8zAh00D$2QRw&a2u{hpf#l|

7HchEOpfh&ikPWAyA@j+C)_hQJ5L=J*F5G^dJJi2YVBU5O7hqHvZ=*smTbX*<>gf zeSEZ@oZMmp_43kjJToc$)z0F1r&u_p9I%-*O{q%bVHix2ZnbGm*M9-sfhCg?; zzTZO!?|ClT4IfoGPa8%Bc|SYj+67{Ae)$N{xh4d;nL;}+e*AL`d6xKQKRo33x8K1| z_fs>7Z4i&km7fGrRXybl+&T_Pz-D>q1+@1(NvXFG2F7sV8w-pdj=J`s$|Ho4C-H`f zrwt?_$W}^JMQCtKaEf5HAxrYy5==&ZD!2s~R>&4@cxfd3Den1| z?Hevil{87dfC~OwFLt5z7-YBWeahc-P;-(k0uM>`c z;vMMFCa2J5s<5toZZ;?qi6P6EHv{XWP>V_$@CG$3NeNr%CJPdA$g zR|{_tNYvQQok@t^dwl!x{ME`-^yWr5h7%fn5)B|x;lTgz|MsCt86|xW>f!jjC5J_| z*H3Pp6oKTw_KS5(NvYhrSt8!Qc*jzy1+u!%p5)X*2=e10SKAdeV35H%l(hj50Ulk~}^a0ExXEgV02~?)W$N7d$ z8b76G%Pn|zycpy(mm#ObkuTvOAHCz8aP;RL+5Q>@!O{1$fYJ|7&k>imA6?5kC-EqS z3iFVc|DTGnuU)(}uNC!9RS#_YK~}kQme1+2F1rFB!>ioYn{N?yZ=15oTfhqVBYt`+ z5c-x=3U@s_CG?Lu6n?kMg?C&KP$mYLajD|d@;OYrASg4<&u0`Ap%+|m>N!)hW zctXCnZQLm$g?X+iT(=%C6G*HqVN>M3wrwXU{Aw#D4Vo*CO%c2abx%>{Zr@2Xko?P= zu2bvP?*_H|n-OEpqT7cP5?DJmmE!eM;D1T?lVJ!95rqwDL^(^LV#WUjP^r(LU10*? zugg%@sLQ_s7!;|ZU~wEvxL`@rty_AM|3pdz-((sn3Y9(o6Q;`+T#ZU7dmVm>_kWXp zym{`pN|O=;sg1YZy?dc={i5!V&Y0TIk#ON!@Xr=gGDt%`Rmh=a6X~0U_v_27XqKsvkcqXUa@t;pL)nHc4L;S*>z*Pt9CB z?&n>&B`7b2f(x-!q|niyLXUpPNyB{m`w19j@LX}9rqi=UnfsolXTLr$CHZe4 zgpVr%^`&ON%`@YWfpQxKgM?%v*K=Tbky_`zK20hP*>u+_<=IyuL+=wnpJUypee zS!tB(o4xt7@(M@Tq3@eJXUGdtpE2CvUH+_S3GP$9a_D-PbxS9CeD0%iTNe-(R#L>@ zrT&82a(*|9R?NaG*b1dQmgm$Rxw9tf*P!{T#U$PeM#x2f~xzkzLWIA^IV<3U8c(u)_os;`V4@$7>?@3gnL{JlNGKIaK zT5OKEV>KKq%#z(3hxSWkNE%Vga~|MRM9UqEg8?=dyp8I@>UhXS`9zTUml>An@2nGL zFcTg9go~aniQ6yA#GxkdOt?)ol<6y1s5S}KbHWkm=(&Y7K)fFu(NMsmmi zNKsi3z$~AEwu*3JO<>fIVfw-&LRZQn5QeW`6;oPb^(gWib!0uWxcsX1Xnl&)ys=3!P-lDJX@32BZNTW{q{2D!m-1u(OfVifJV5&sPuR8a(pyXEO(etWMB__A5?1z+7nx?s=rZ9+ew_4QlZ0yw>nVmvX0Mlm)4!>hmJq=K$tf>#ovu)S zDJ1l>3MPoZA#?rZwFkV-pcyHqEPNnjd)7fr#Jm2nJk?}>MgmxwweL8S#3Hm*rF;1&=R^+Y2sJ!oFk+zT!M%ZSLg6d zNP2oL-neg1BBBfceE|#%K@^29RGk@YXKu_=OYiRK|5E#up;K?a``{n!Xg;~wt$+Ze zsl@SMInD?X()q8@JS@iQK@S60`9XrvjqO@0FPF+ugNv60$!haGu?D)A+Oi$uNKhz< zwPE_3AFb=Nrx>oTCbCBc@vI#OeW!3K8y&T?n3cXPUcF!}>hAMbEC23JbWky)ZeIjE zi#XR zF`O9;k*VAw-qEVlY=>hg<@5Z6i?{g^AS$owugoWacHHv_*BG-}H#Ux6Ql$!$*Cx3g zjQqDxeAWh<48nlxi(#HOMsn+2eYB86^nG>(`@>(Y@aMck3+T0-go9HGP8+|3*Qq-( zZzSeBoT5ef%+$fXbQ@0)^5B-aCwdfq4U8>N*B$2AL(~XfV%Y6*RH_ z>x4xFTsnrAH|C_k;cXyAXME3%3u=)V1PSYD(AJ~73?L^*%6_CM_F)gnurjPDAFz4; zu!_0ye!|yn&SY{~Y-nIoc*Ym1r_O`Qw?BQ&`p8_DtatWK^ouoapRi@drHZc{5eviuoe37g>xSf(l|9ne80Jr{o|(Q_0Tu`$}_sTe6XcJSOWkwfPT|;{B`u_ z4GA?gVejU!YIwb^IlOI-{Y11YQ06#m?&Sb+LX*0II=rW?xro905nEyBk-y)kMKMBI zea|g2<^jzw_osCR4gaM*P2}2UA(pwP_~;8)Hpbix-ahW+NPYFCwVU*5IJVP{CP=Vh z4>&-%&A$#1Yg^rKTanjCe_!Ex2bGkjKjLaTho|GoZ9qzVTj2?SuTH2-agddKv`HlLs9$k%TmU>fp9_BVX% z2zex^xHTw-&v^3`1dLTVkU!ocTCmH>)Pe=Y$nErt)jO|?a$&wXgsB&!PIP45!RlUM zS%>27fO+xM9CFn{(nRCg_E$G|oVb$nuRuscCL+yHkPI;X<1ZW4b-(<`78_00e`qN@ z=RdUcz-84V|3e&_Nn>S2AH;m)eCvA=Vq(sjj!5(W#L_wN1tIH@EqAnFBExi_v=M=* zwE7i@YbVJ8b-ndU0$>nd=cDG9{IW?=lJ`_1AyB+Ty}*T~mMiVEYgHVcDv!CnM@(Xe z#wP*^Uo8u>V!s_X)o?5UvShZ~4ju_PgA}i7Z=6xPNwaV(#m5ywp#n_kd~DJeHZ;^{lpBmC zt=Ev7Bf#%=qDUZ&kpFq3f|&?%1Yang8;xZr9bhu+SBcboD>NX#KEnvTqrowZJ&v_h z-BnH16mX`q%-P6TmkaVaYaS%ZyRZ5Ou@UKXuH zQDvayd^vz1KnWWIW5Qdb1m+oFxk~)k7U&xPhvP)7APmKO(9g`|q3-h%3>{$*+5HHc zf#<{u)aMCg;QD#oW0bCU%#AsY=o!3)VoCfxgh;g@K{P~`#A?Gn%MAGYHRJ#+Ltg)r$ATlaR9|J>l49)P>x>b#`+3P_ zFxi1*7WB{G3FMV!DPIkw&%owZ2(gk7g)0DV+{(FN;8<6saK>cc7qu!4b`L- ziC1Li2UDu^itqJiZBShkNJ}3(3FBM z1IT%b82aMc-#2j#lA29->l`w?jxI6RD|OPh{nAvbMM(P9p#2vMlw2+`vOyqaWG`oB zKd;Tv*e;P{RiA>+LqGH(d|m9u?%`EP&5<}SRGwFkdzJq>RtZw?a54nA{~uTyn=9d; za5+eV&4p{#A07^^)PN`!>j@LMzWJQ!A=s=G%d9MLe7C=eVxHG*WQjYNEfdhGGy0Zl zAo}pCXZm2V(KOnaJm)69;!)+axY6;QJ%4SHb^1*dljbH<`S&(TG_j+n=i6S-kiGjo zG`JoMGQlz$zrn&P`~{*qEE24Wpmr4`a`XDR^GI7yh?dFln7N5rIUdU`^_a2n>+kT* zU>bDDS{(52 zmpC7ftG<=sl51uBFLMF18EHg~;141pVf26OC!IRlC=p>bqRw;}A2iaDk=WsInwWZD z_Ca8FMvB}!yfCev(`+a|tS46_mH4Jf(G5o?-x`<{blRDt^&iV?C-ma+V@X5X!s;W5 z(t&zWl=4BpQci9IIr=ply7>EOrF63X)b{;AnhDJ$LJM8V$*_V4A!nfc;Wl&o;cT>cBLxyk2ePdgC`4&6En#Vp zU^T3%uy{Iyd^*>=pAHk2626ljIbMzn%e-=Z7-hu zNtlLr?r$U30pY}cl}Z9}y1nmbCN#B=?Z*e7X3#lIN#cDu{JP?A}XKeLy#M{AAX2qc*P#GEn{Hjf8XpPMW8L_eu&^N zN&UPZ@$c%Qb6;i5j3#z|OsK#yMs56d5-AF;lTW)pAaqwgl@%T5)aJh*EIcCzVigAq zpQPv7-M*2(fG8Mf`JU+!kYqR41glZ+9cakJD+4Xo#(5C=IhGG-ya~UI3aBn zx1rj25%`xn?5{rZZ|eD=7G-QfQ>cChIa?QVzHWQY56SkiJ$>n)v>%u-`HKqI1awz_ zi%iesN#zYT=kHPuWDj3BpsNgI6ib{=eiw!YlsYG!X3FRZR6J>~AY05x_~|rIf6X4A zWsN36+Ei)$eM>7>x!CrG*13BB)9vfn#|z;VhVhurzXfDke9RqnMeW)cIjO$ZQn8S4 zF`ZOY8;w%byx0B8h=^t!Zm>C`)9I|ZG&8)wl!&RcAeQ#3&gntVhm*Dh$96Gubn5#K zp3@q#_5i~Z#|eb@YtI(HhdSb)F-pqs60V+n=xB5b5B)7lP1RNJ61lY75jm^Pch9%q ztzPd;cGdi<)%v;(>@b&%qvq5c5QA&4vY_yoN20MxQ@1V=wWnY6S_uIu2?j~Kj1!p5HnZ0)^t&f znr_4^9RD00I;(y}Xc)ERg?BHgg^wR~x?U;G*)ND(6EIf(n-z}2w03v?AaopzSg?%L zuJ&X%17$u?YSay1vd2Zv*tau$otl+ipT?137q5H6-oH~ct$q=%+w+O@-)HNt z{rh26=4N>hdpLfp=ydfQPH7kK-z-`}?#-G_U0r|uu@%XA?f1N!+L&Seld8z)uAc&& z_YxISLfMY=B2uRduvI} zTt+XA$U4xsV7NOUw7AMlqAIh>(-j{ZV0PX<-?C{Woh*#YyCZ7XLjJntxsqJ5MaPpL ze_+YEej6G@UI-F-{Cn*Dd?Z(Vl;-i*W1D3g(cPvOqppQMw)IX^+MuTl#yN3j zgr(*cp3HU+?^nKh*m9^Vf^_{*FTg)yQDN|~!SBZx&s%Il0i^|QZ}0YG{eHX;=Yz8U zEC>%qO^$YOP_9*0MJKbdh~08@0d6tz)bpAK{hRuux^b#?GZ!8exAbkFQ7|Vi8dvx; z-=OnL8_!py+hqWE7kD+93aHydxbPGEl}z)KJ?Qh-AR=Zt`LGYZ&gck_r}?DSuHin` zzb$`Ek{q3?fOGC0JV~xY%X63N_fvRRHw=zPvmFo9n`(&;a$ByFjq<%z{3Xb}Og6)> zeJSK2EacSR$VF7YX$-KxU#lJ7?Bn&HXy0>ttROIdW;iOlwUabif(fcK$^i?O7s=Kt zTh^YJS8k`BVb4ydlx(G&)wN2ktT2k(1rI*z?b8@Q4J15FD%#=SymjLr9|*i8yX;Cc zNBLLArqkV4o;T4&p=G43RoErljsCr&vu;F_x-L4&&CFMr?3T`#YF#RLl$buveqT)C zZ&ae;mJ%Ey<7+muvYrt*(dsuYp@ zX3va!o=Admxe!q?k)DD>&V!h?I~n?tZ;D(jXlzxqENe95?7TTl_g}|8nzOR;2nplQ zd#+lQD3?F<{P1NK$KOh;O9kHjlC91_0{O2Q3cCqMiOpWy;eX?*fY<)3*_l{Ulj6d1;q? zNo{FcOPhE4nES8ad^Btfb{>6LQt%s%yr{@s+zN`~9jB6eoAX0nPUUyVoyz|ErRTTr zoivc?;uHf`tPOMj=5zer&)$F8%+9-JdX6{fE>R`t+dS)fv2tHCG`vpw01xnc>SM~++*F9K!+s_ZUciqwyORSf*HSUayotS3-MxSo6|D` zlXTKb{qNs*!4ZqQK=ytn?;ICpi6I7HOzb0S`4Mvx=t!n3S^Jb66ptH)Ys*4u=DLL) z;Z~g57KjAJO}P6(J~M%JWgmLyBuvhV&FIEufaUFAQevPJb(#jgK)Vg$P=8GsE8U}L z)N7=toI_W$$HNeQM1zA90(Y^=kLF_8-oSbhZLriQZQG1SdLvX{ep1F9qgel7iCAzP z7K1IXw>YozN}kd!=j^&P2qN<)b$b#=IjJ#78w8wBvvNQxxluFw4IN{jOPUAcAuZP7@KSHGsN+VdhVQ&yv%rgU6FYSeVj3zhpd+Y0Mwr6vul8k*?Vy`|b zS-<3G`SvG+J!2Y;xpooktLK+a^2 z;-gDJW zI?ujg*VI|$^?;1%5^m%Kls0r!-l@5Gr|Rqm<}%(#*odbelI%b?mWEZ^%n4BSNIW5k zH6o0mQX}W3IW&U`ptBZ>Xo9(DVFuQJNx6}p#8ss{q>V-i7d$q&eFIU!}usOjT8VFF)*kD2yWf6BEzNh?a-M(3C47- z$=XhT>`0QbOnZZ7`Ujw0wcCyBq56$i4{j5`8(RzbLP~|39uCI!QbiRE5ljI@&YXaI7vVH>c+X?0Reo%XA5KpD*4|Hs_lJUmBDS@MZ~eMnew-g)4=5lATPbx zgT&wM)3jlQnnfJ0Q+TP^P<{X9jnhf~mp6vI98j<$LK2Q_Qvq;|I4RIGo@#heC)0@3 zwZ790Q3yz6_D3}8h}!7?e3UYX2rWa#KBXN8b@N$J zIQ0{Yo&55ScYbyk)(dS4)oq7@?ZtOWX*4&{61bP!YdzmMxq1S8%=S_=m{25LOv8P^ zH0k3Eb+T!HqO7{>Y)hN6(J$2_+L9Kw0<(PCR5fokYItTOc4X>gVTsHIKhr}X{bZyl zQQ*&XT7)}6W#w0in)E-D)+?Ce$WWYFHD)2S@TYF{$uqaCEzVi$5qV#hW8QQ3D&zM-D9-HCv5VSI z6D@LO>?1H43<#=z0Z~mAAM`CcdW}2qZ`GBOAvpOm4P5lAK)KV*4st5s@IE!)X&}w7 zV4M9MKV|Se;J@txF1f#>GT+s6o<{EQIsF}XdGzZ=pfb3#s*k|6FfeDzVPEB$!c-K; zSvJAF18qiy(X_&#bXxWu*+g+*gG*7dl9+E@H) z`BP!Y`?}ZP9^#%{t!_B3X=7i14{p8sypc|3QywXuD7U*EZgD{mKRo6mx!sdCa?@4_6^A{}X9W(*Y7{1*!+`*4> zJ?ve7c!M+0Z=(S-IrRQ=G!`6r2Y`41#+X@j2`na+e#M2ue~VDi-#(Pv^pcBoX)1I= z(+s*xz@7@(H-<2h_8DcsW4IWsPKKC9*&I%!%70uN#0h9qNisc9c(_rv=xO$Q_-XZ_s}Koa$=uq*o&rS7&V<<<%F`)04zd*H6v-&bQ6!4rKrl7k>p;?N-~A&P*^9^d!f z`|Q2fI{Tb;zMTJH)|wA9&vW1R?_zY=zl8PDCHk-GBx~4tWnAfUykR&+pW!vHe?ae= z!YnZWeAn>JY@&VYZFME%P8CIybfQ=pzsE3^y4idV)&wnt{X3g+#UciIJ$yOYlQV0dqiKr!%@k*? zo?t3m;BKZM*CtQEx?*77ZnUxD|fT=-%#FVK79hqR0#g&Jml27~T zqIsk)(@DRUbmlw~xDR%x?veV~`?tc8k4{R2ZTfNq-Gc2=#`R|XvS9|hBQeJ;fzwy~ zxHvG9R|0lTq-@N{cUsysOCn6_N=&B6@5}&tb&d-M&a1o%=Jyn8ontjrUod?c7iU-xm21`P>~*~C|5!TY znp#wr631it%KZ#hb-_V5^_(N6aT+b61TBAJk|{I2FjBOKR#Up!OA{fX7Imn}C0TZ| z!e!qxq1<9mnf+kqF{=R&4z{PAp_yFeq4Q%}__nmJNVeLW$5;HMomc_piyn?g+3FfC zmyk31X+xP_&e|!FS-SughDxL9vBd8zgQwY?afgNsLrlh%hLc$)Pc5`#via)Z9IcMg zhQngKEjkX@4NMO&`Qg<{vmG=w1TmniYxGk0Gx_2XrsX{T!ilD%Ez$;$JC-Gl3OCh` zcxj^}8R?&xe~h_WoyB)b&a%{SJz>>-WQavfruITwXX3)U0WIJ zaUaVST9cS&OD=s-bR-AP=$7eoGlSk+WECp=&ajpo!8TW<)qrX1^v%oHZQHXj1Q{p! z97X&w*V~9&^G{rtj(r1XsLVAV|HNOi2(P$)-EQ)_S4ul+vO5n}}8a~+f|6_|IpDje<^w8^lxE$eEUhGXvp^xo;s z1}!|Y9?G%J`DOQUM(Il&O*EJjoqL}<-n`hC$GMCv8wBC`B>?94Ntd?lYjtgIGaqfW zE+war?q#3-=oawA;pNu-AX+}+iJ4SL1#6hI$6ZFVvyUE5mbxE*J)y_U`piBf_}*&D zwG+~$JIK9c21qWaJ-pB836k^5X>&$xI_p5#qBR+PWW1{@Zc6y^B5{mKDK4&>$$^y* z{vLZ={{1kY(SD~bVZF@+hI>pbr`2x1KiPYa01vR{FGd%;r`{5|9uAgXWV|1FBWcC~Bp-hEJDS*TaIHD| zua;X(BwBaQkm+VD$13=SKR>3-2pKOs@F`M)+4t}7V1whxnfA-KGz53c$$j(U^l~ED zdda)V!)`_bS1N37v_{JOig9@2EOTO8k|+AWL@*S@{X#zUg{(@UyebD+oGdHJ+%Y

SK_mNi+ z!*U4ARC9z3S5sDHWQzI663D^ipro8bRa6)0`OV$^-cmH`TJXQdK|q_K>>ZaTZPx1!lVj{CiAl)ti?AMLNx;=E35?DfM@Tg$^(3=g*v!9 zW->W6$)a5zz00lSX09t;2rlltys(|J>XN!Em~rHicB+pVRA-uS;H)d}hef7S3!O4n zRGU^%?P&{blU!n zYCimU0^K2j>+lvvbcJKi9_|BTug~{QQ4C;-1Ul{~5j(m2hbe(e&)ICS4;Pvstgl)t ziY9hmOcWF^!AsT+xcxzlP|ea4xB?sNHO25qlB1q#+!j|L;AMk>5!n5i0Bsy6KB>g+ z5BF7>8%nRaaV%83QgxoJ)uX>Vsm=quH!8c_sthTCtHRGL>z>i~vS@2yR*f)TBOiGN zXb*+WiStS~DSvi@)Wr(yG0I7?C}nOWxAkEmH?k~z83;bJsdHbzU9+ujO?<&vgz2r* z8r`k`V90$!-~?Z3JEQ`3cYmtms#mp9z21JNr+qsG{MzT9c+paUS8c*qjuXY!BY&)U zG>@_oM&-VPCU}u%>SOP1$21;{&!2Cn{usBL7~cq9+wPk9w6qgjs3@J(?0c@L>E2@a zwZ&o-L>5WC>41i5wn2H`4_t-aw2`*LupN#-s+K6Vl-nDEF&^BbaL2vFx;^@bGsgtd z-pmY{Dbo(_hgtW>+kZbgsLVQr%(`;yGe4Xxt$aNz@}_OHr<b>UD=B zqNws`0Mplc-p2D;42H`hMlb>2K4>hJ>lF2yu)iVeZ4*VV?Ji9upf;rA#y>5Ip!ddq zuul%DEIBoP{@gvjqO!bFwERV7qVRjA%H3Y!yzfH;DFd%-F*p zfjX2f2FV;NY=SXnfF62r?b+hj^0Rdoww^GZ>3irk)yp%wh&e|MSjTGx{D z)whGwlS!P@G``dF2+H5A9D5+<;Agw$oIsl|OPB0dPMm7x8lK-B3HWE!(YJRGmE_;hk{TSlK!jj`dEkT)`usqzZ;h_1D|X%+-iDBcypWF&X!wr zSA{8-O(~Sx+QH$qeS7a^mkK*Iy8BzObc_3`iEo}75E*O>9_)6!=qtHkm4CHYk#(Q$ z9{n*F|6*6rS>vrmPp5_k&@pfBu~RtTlU)LSaY4qeZ|d^9*wEWgens?!1*I`Bwbj)8 z84gxUQ&s8Tw|V1Nl8V3nPW%0R$(NOt51*_qTL1QYV;8c&^Sd-?msmSg;$csa8ikUp zQmh2Pot?^Vyr8i+Rx_jM(0Z&?_N&w5TWK~MnB*e~>E%RE3GGjHVd(R*oPxKEil{u&063hqZzP|S?$;mK`;hBncja*5TGxVt?U(U)J{Dx<>C>etc2a=cuf39`@@%OmUJYbwP=UK~tHA2Ysz@|eXx=@O%M&aq8F8RC7IfwuJ zUy2putO=PM-CS$qkj)hv9l8+d)cchouRaKf6fCM0VP+ELMcpsYfAs&6BJ)Wi05S9A z($8k<`}z!JjOn4zR3z6@+D*#VJl=(TS2IxyL5pnc<9-JQ68(^h1Ej#WzwuMD50m1? z+~FVCCojKkS*Gc?81eR^@#oa^LzD;qO#FIJCuoxq!jm?)7WNM*uW5;I}67~p~RoMmXn`* zp#vN_n#n($SJ=ux8`o7ciqiPK5;WBkY3fQnFjP#@>tIi7;w2bfBjvEp}SZso$3LZ$P-A;}q7*-}=n;px$dNErQx9**6~KyGci5eu1KA}=Lhf}?1q%`kHY{~c{n1yWg4 z5SIm<*HFU!^%OlO`L7eK0 z6~7-$+wl8TQYhcLI`z(bvkPc;&Kd6qs3xPHXs=c@V`qy$Z zvMctSjQ!^gRA~E2?ClWT%K}U}xDtRJ<1Ih+H?q|{@-2rx7kimN<8E=357sE&b&HIW z$L~kd=2!8%3yry2r1_GW^Deg}jQgLaTEqvlYnWvy7oZ8MmhtNPV+rrA3$A2s`E1tC z7@+;!5G98mE*i`WYPSU*Ve)qMkdD10db-5JQt01XdMd(ZYa!XWF#g#QZMb=yqVzMK z>>3raM5 z1EN|V6Eba}oQdMePTDheQAu%`sk|dqYj=zR*u$xRHEBZxYatA~C({jw=8eFitLe)T zbMe>o^#b%S?AG}8SF&@We7(ygWD{u^=6>ct21Mw-ji?VhwpIx|*<&@mHU9SENwdLJ z{f+EIoi|v-eMX4+^|;&3zLjlml_B}R33rqbmPuFl^w==8AYtiCRAc?T zp;50Fek{xN-ii4RA3d|9SG}pt9(7lfvJ4_0txM^}U+*+3G~eYcV})||7FS7Fq0aK^ z3-l1vr_BV5N^iA@6^q9teZBh^)>#ZuwNG~PP-m^I!I7&D!xkvXIq20rFFkN}zrEcxxMfT@ToVs(tnN%$pM763liL;a#AGQW{!;y7kM7g21tfy|sp z{(hT=mmB%d;W*ov%;Qam(oCbt!SXGI8XRu2VYfbMhqh#N+q%uyrK5h^Ytz`Sq%y|0 z5398_!K(0Eq6GVqCk?OouAN)C+u1A{ZTPx$r=Vm0D89!be>vY^Mp#nx1DhTFuZBL; zDJxGQEQ*DZXd6!r)5hsrV4m|n7{Z0LMv6Sj8x7tRHwCemSS1T(hi@wX z=$v$Y0Ft#LY-x)HP7J9< z{LYIvVkw4ouAnoSqUit+DBCjfcgJYRcb}JUmX0vw&Oh(c`2KkFg@`0AK85Z_i*>D_ z(oXtCLJyK3cCB%t0^Z1h_txmn=8|sxilaX#fDJm{n>Rkneb~J%h|@w!ik~+4sT`Zy zseH}s7<=3mU*LZieCktyA+wDL8d|J8vXUy(S$+o2&F!$}j6?cWTcIVKefZN_$ zqXDu{PsoJ;EZEYgl5-ssLjmiJvG3~Rct_fC%l*fV^wC1+A#!^W2x;a1!@l-;>^BVx z9!#Oc$jiM%u?u4GRGfQ>KzIdA$QF&9^$OARqH-fZ?hz2}1o}OIO4I(I&&dt~Z>v-3 z;>myRQ-DFRQ!}_W0e%8V!8O8;^`vz8;A>u}7qf1EbzS~Ef9UMw9l>}%n~9f$fN;W4 zf4ccE5lKagE~D9u_EBm8kd8-ofdSIZ|G!YAI2wWDT{jXeospb)4Eh~`5@HU`g#af6A~}QxzGIKR zv?Wbn?hWI{(^_BouUt zV#gjJO{b3Vscnme8ItivjLNI753@QvC{mqQFR6GW-r+Oofo=lGso{NDixXI*8;h1j{~wjCtl+1At0OonW22=)&v5Vof@XoQriV>b!GT-%h#nAr+HX zu62_0AGrbr>#BsPbcK9RmO{Gs1=>{wH41mz4U}8+J>A~tdHl&!uZ>^T&p*^RmT$RP@KUI#U9dPipkTJs;xQ%1SB9a@&1W1+yWK8I9mpr5a_GhH#aZVU>{bUFW~(&;wq_7%$_imUXslaJd|izMi2$aoOrxw76|T)ntjKYz zHLM&Ng6U&Pxw$UbzuT5N3uee2C z@fyA2cYk#$>6OrnS0baYE`NR19qm>(=tjE8-S^A0^cH>pN|fB3!uu}Ds>io;DpTtu z^nmnU2T&iBL#q_BsV&kwV5zqDiKrrS0D}MLdE#(N~o6vG^!_l{un$-^4uG>7#DQokdZVP<|l%PowL}Y<_CO`l;dHo|j zZK!}o0Qryf6o-=afH(J1yyED)>WJU_2yirAgi=RLP)EX>jua(yx=3fX5jw^T@v97J zm=wCplqb#oI@-Mh?C?7IYe$_@XO0MZMJ{w>>uF0NUAxii*DpG{Y|s!qm6r%w=08kv;$-QV>0V))}PbF&OJHqKoFWioBE;c_ZV> z*AG{ISP;=M0Lt)vm}L)qzARhR9{tlj($SUSa#^<1KI$(19dT3zluYlk4-Wvk0ekol z9L%VUieQ!oJ$O5m>!IV&!#o!7kN3nt@1POWUTBCdPS?Aag`KLqEc-esjK%&=Ah?I6 zK3fb&agK+$8R3@h;)-(Md+9LQGV%j)_>Hd_wisw5;R^VG!oePL3rn>Qq(L&MCSP;{ zILHx(QX2z5^@7Pa^_!gcn=1p?YzIh_F6*v=+vfv0_Q)^-#Hb8*w?BfDB2s2*@GA9y zg(&rPkAZXdA=|wH01u*fiD0gYh&Ye1F`$b%AB?Xb_7O#A?{^hd19JeiNjMSq6`OF+ zW6-63&||DWmU`$>*D#b+#vP@o!oXDa$$w(tVDrKIMT743GCOS#zFDGg_{T`)Ga!z{ z|DGZ5^uRxsp@&7$Rvipg`-r$VEt6dgcqL#9*A8I7zwl{f8e>EE$MiCKpb?ddhUlqa z2HCMVO7Dr`IQp;DgFWcJ4<2{A_9-FWR4t_6xqXx__Q5WJ0#+WaN=ja0s6*uk%hM4M zb1EMjx(jMN*aQy?38rYk6LEMEb(E7m`YJ_?h5r;$6b(|rlZD{nx6xD~(FPsSLIEGb z7HOHgKd^rLz=4bWDKrPZiiQF>=uUX1te{(F5FdrX!C{Jh++f}KLL&me zB7j#Wi*4f~!S<*qEMn81O8X!Uyb`BKP4}-SN{SJxpodM+ts#pC`f>21)A z6}IISu2dR46^yvQ+GbBhwnA_vUn%=M2Z)2FF?blwD({`uON|rP7s=hQP=74q!~Otd zYR%^FnhwoEE*{BkjMlrlDllOU11QhaQRm@sO(|p>7L2lo6Zfg=1yMvCf*JwP+9L$t zFM?MP_phK`_EF1PbR@agId#)*V)FrV>(SM%r{Sn2FW4P`dI={oEr_nxheoJwI!$aL z(l_0gHy^65c&ly|Z4(p9YAUmlK<*v7$i|(R?>q4q9m0t2Mqu~gFY2&;3$n5m&Pi8) zbsNC##9r)xS14a`uHSZr1x{=M*sloAN2t`*7xF7}@eEIzZzA>)C0GVt0F{FN_Nj*9 z9gt;}{q0~ZK(1s>=_>k0qpy)F?HhGO-urLM-@n5&=J>k5PkvuZ_Czn0wZJ8Q6n!M$ zz>^z^Q|zfzfXm4~mZiSMQ+11@c>t)H5&|hn*@}Ie|6=d;#g>f3K3Uj490gE)*++4a z_GqaXP(c1Z>OB&;j77O8@78hBaXs9pc)3sg5=BCR!Q2P*KQN0yxt;%KYMy<2uN z#R#B8Zgw~6)6H^)A_z@;_<;>KqRb5KtMc2@9CD`q1r_mo^9nlJb8cYxOM*$O7iwKG zgK8E_s_*_j4@G|sf1mtr?pPJ=u#eg#r^$I|y@7^9%Hf_O;1S=6A{EpNE5sQ#^{gzl zxQqbqAxM)T;Iz{^;*Zn0)4!hucF>X2Da#-hx=t~4wJEw51-wv0pLHbu9)58)m)2jp z++lb6{@vO5%Li42)V&T=uh*xOameYnMci$=VH7aJbizXlknG$ex13=AZg(ql4!$H*cPRRJ)NXm|sNUJHwUgS3cmX_8ef>Z>Pj^(<~ z0}Y)7dc8*J6VxOQv?YvyI=r0hajA!~iu)yO=s$(Bt&hyEIu53&iNRC^qe@we6hZqx zYiD?_MK(R>_~`QS>rJe~K%^6S0!H8=dBmR7V>58KCJ@YCKDzydsj?hPQ@>&4G2iTp zX!La7_gumdN2qOk7=bEZ1T1uwk#S$W#f^h4mdgG^CkVnce0C&%xIU6Q?#O7HE*{S0 zvvX0{4*?27bV16Imq6in-iF>FpIwq|^H^vDF&i+AVD=+IhOSoM`Ap)vf}-O)9&Lef zqGphu^%v67bZ>cQY1#rWZ4R7KLV8e3_nyb)-a1aKQ4=&wMu>-757qnum|u1seOQ~s zKnCGyW#F%G#NPd7+$&2ExG1kmUfb~;t*N6j1YK7_lA`qM{w z{y$>KjkRe2B0z7}zH?_Ly$`8<&>JiH{9sTHxN0o%=G*HRSBIHh3+~HA7Ofw=1ITUn zjl}y}gc%=yz;dTODT3IiNd($!71_XcL3EehfV)h-;p{HSVY@ETMqEjM+H$Y!Ua@)R|Ttsl%F z%rxLK*NwgU$ka2vzb8CTiil2#DN}jfd5P4D`+NUR;2K!{bA+xC6UUtbpgs5TcZq67 zt`E1{ulubaJ|%}m3R2hsKfB}X!rrZCEr-o=l+pR@fd*G1`d6YckH&S{UnlLP48W4N zIC$4HK!BBfWP?$_vX$_O4o7gm_cI+pTcC64vFC$71ifvV9!$9t(w`7HkQ3-8u7YtY z3dH^4)0-UWxzBFe5nKM$XJ06eksG->J*iULNzNYB_lnh>*w9(h?~WZ1SoCOtgI5^* z=6ZBsk-1)joR39m+`reib8dfs*~jU!_iFNL5Jsvfpt{(;OYnTZf5@@x`_Msd*TPd+ zT{%YhD><3yc8*DR8*%AV}9zXr9lSrps4J-LdNN`0_d zG%ue6+{9n=nO6lXSpX=@>_n4!&@5IexQx=(UyFUyj2Nd>Ujh=RNe#5pLP5>@muPC0t=59#Eku+1YOogh9vk3P<&cqnSzUsw9ML`weLAWNVb zMNm8lP{zdxM&rpJ3z}1%;kD6}Q~8l3q;ozT1=O9S$$)+br`>RnizVWp%nlGe@U|Ne^_OL!eeBSj#`oIuV^4UeQLwv=|)wXY@wKV zfs!c$d)T$SKKe463vSfC5eU~5pnk<(Lz~~?E*;bXqDpU%wnDC_+cHzIT$Hovwm<;( z6LOVI*EApWwc@Y$?ki1yiV2HfAwOC^2dxyrP1Fps3TFE^DewNF&As8_2@&d70tk^| z=Mg1pW~oXXr)KfGGXb2~Aq*0n=#K8EtF_%w*UU(Xy0@CW0NqxD)@cLuKA25>wD#>& zi@ZU4+tQ9IREs#AlzXSwAZRIEG_|Pw%0P#U4s)$fK^adr(=Ry{8iEKEfyO)(M)pv8 zr@$Na&Np6=vjF@Z5vV68Jk$`ORT}PtG+I!2f?czl2A>y|-+5Fbzmu>ALNQ&fqk*G$ zxX<$M=}p`N8M+M$4+lh$RsSnKTHEa&%yM~szpmvgergJU`wtWlBtd_oz9jN;7jpW4 zOJ1H5&(4Tvzy2rn^5^O4>BWDkmq-6Yy}UR+{=d}AU)!h0dlyFs#N)O96~0{l2Vd?J z{yTiRNBlNH+}a?imqe0!xzRyVFZcHL{%81dV`F1&ZH@Tl%i4ceFE1AHL_*!g%nb2! zDRDlV_%Y%C4Sf0G!w2HzAaT-vc538*z?a1S2I8AH#O7w=`}@QJTVjtnv0I1OsYGm( z{7?9DVq#)!Y;1INbYx^?czF0f;mh9MUfll)zSRB)U)I$T8###$jKsSC9lkuPVePGt zBf*yq4GkpqvbMIirlzL4y88L^=d0zp6%`d_Wo4zMrNo>ZVp8H_W+pK-l=#@|Taar> zNl8&rQDI?Wetv##Zf;IaPF7Y{Mn*+HIWidg#A-5r#U%PR8;;q_45B;@-qLQc=^AOmo$92F1u1`ciwX1O1^$c>hi%HZzAHfqd0wz z#`<&Q=u}OWhU}G{^(-^hdA~5_ zTml~qz8>y7!B|H+XN}z|m4GGg*44MM=GDzL5UpIO7>itAJZ0+g>S^fuwcynFCeT%b zN_QAn8~qHHD{4P_@v+{n`n4f<{Rd0;Z>>;sw&GYS=BZv^Sa$l2=#|t$bd$&CiEG%` z55MbuzQN{%YJ?@@8=@ALU;KC*u$fd8OV8{8>R2_jx?;@8tkIKtz&a-$i4tMilZ-W5ZtAG)3zecIwH<@QX*Fw7o%^=dbzJ zoXdILfPMI$7|WV^!(MwdbX?b6GFa!(`Zyp!p*o&nT`I$ zoP7I!_9MjlJJaSvCT0BQazZM8Cy;CXcY55*?}1;NuBkCw6=K$tuHZiL1^*_fUHrA| zm-AExu;DtxO91*1$@Uq4ca$tDer-Z<=PEi;;YgqEr$(;6p0e#h!khA!0l_$3l{p$} zv-jGYzHKANJWMYA^h)CmoeTL{euxB^B5p6U;BHggS#7ZWe0AGyn*jo3#3*D*^ z0U1tRg&{W>)&yICWRbAO(C**0E+k-$pBzAzQYcwOqrpq>~#9l*c!Pj z=e)9GMjX>K{u+S|Q;`q)?N{e~(U9adx zNPp+VPr-mcUC}BO2lV3--0OKWclX$otl^V+t%oXbvq8xUOnRX6mLu>iLH+T_HI{Gm z0vk!lnP3`2r`MdqZ*#QmiZleu7?y0dgoREFb6-#A{4Cd0%jJ$J zc%Jd1x!=n4NkVz+>l=1X)67=#x)C=>dF{4v4dciW_L^2lRynT-(n9-8M9pKymANPs z&MQHNxgT|G)sL3<)~N*p)Oq`nh;uL0kfS5JwpUNr#L4sKil!GXp00tC;>n>DQ6RyizxWL&4nflKfr ztg*M7^=gPWrTXK*^sCaEVlxhD53G1Z#P)TR!<`4$N`5_)()t#(p+$E0XC)e&^U`Cw zz((M6+dJTU);>-ape011z(T!hINPdLD zpsYmVQ`<`70@QC1+^<3*i7;co2UeBnReL}PzY;~DU=k0{8!{%5mw(1wWN~0aY`FBB zKg4mb)T4sMy-g~15cKv$bII?qE!DGtNhZ=m+=cPBCfg}Kg7arN)3}S)rPu$+OH#gn z$M8sj+z+FxW+>sRVRJg2`pf6(L-o}Q;r#bCoCR6#uT&!R^G7UYhao+^6moNch}-@e zaNqH-cg{{f;Ye?<;!O4&+0N#=Lp7LY?Y}xJoz3G@+ghqkzPXXe%ejfRw)XLF4}#7X z3D4U&_r1u^gn5>>FJyTQix;m|pMJh)b8M_Gs0pRDc?tWHepz)jb1nC~?_^h4 zP+SQM-SSsjm`V%{mtRMc+upPL!JZW9F-m3{Zi?zcqPyIqTc zX9|e6R@u2Q&FwzxS`(3L0eJGsvqlcntxHiTBVS(@D?z@Tq;; zE891mZoPQW-~B`^bJ8pMq?VIJW~^Dk zwRq)zWAKVGp3h{)$7HU`WC;r7U=chF$PD`gM?tj1)4)P2`TPE%J3|n#1Nfy2xNs#r$Y+e_$1tEBC`)VBDf^Gj%5vfBXKyhh8MF~*#Az}%~!G=qel;>{iM zByZ`&O3J6GwsVl>k&$8056yfiKyhDIQa(Ati8uvO?0<-n;*>+&==%WTARJj{rstGS zwIz=F2v9(K{zHr`gZafJuGS>3%g2&%$O!)|dE)!Hs2Y9kjnrs{+p*8&j6Pl$2T_;f zD7(;4#%mrAJoSfm`cG{$rQVN%nEzun5eA8$T@p_Z$w-=HQ5Lif2UE9)E!$IpSD?Sk z;2P?%MKmQi0$z-Psf)wUa4>LBT8=%mI2>glo+{3g{fqK_Wu*^Nc&gz~#1M0}*;;*|}uEjMMG8XSZSI;9u$S zd2qT(!LU-Hbmw9AVnK2zel(U?P0e6mkTWFKgrQ8D34=~ikm$*B0yX47Ns1Q{=zHp(J`zkP=8wN5UeUR3w;*@G=RZvRH#MBUgX&*OhSA zoTb`?F$Xd?JpdX(`CYF3RziWT>t&gA(h@P6O&I(EN5!WJ-!DTQVKS}@qMgN2PvO87 zMYM#lyMuS7JZq}r>-@O+N?1Yuw~gn|YRbfh%UYVierDvC)X}K2aBk<4)}aTD75_F7 z;!po=B6yG<&hYzGHadcEDHezZ?2teKEiXM+s8n^RbU&^2bSn}*s`O#4DozO2bfZH6 zd(c1UIm~?1I0dyKe6($6pLQ^xPql?s$I~K4*Y%|TP>W@Qts_#Zw%4!d5&i{F??ZKCpNtH;u8Q>p@ZyLzzxHp z`QfNQ;Q0{&{%r&t(5a(?g@^8xP9;{ByEUvwHc%}T`zK=4y}?hs$VKeY<@$}yyP~bP zE)Vm{Ie0_BAnG4xs3}6GKOJL_I64^rkDA0#72#R2nl+UWEv#vCHvC%MRk!LqVjec! z9B8;y0CfO!#e!*rN`AJ#5*3N)pTGPC+*~PK4UM=mpC}_+c&quKxYPdD|<3vuJa1Z+k5%&}Siv%}Q9HY!9LF@v~2XIpkQev_!cDv~IN8 zotZiq3Fb(4WIhs#4(f=1BN$sKMDS~-G^%>^f&pY-WrYD?G{68Jl~vvT@LteurG~Jt zJ`N)2o0)BGnF7xXU*C&-?H*aTc-khv$dso`9^!_^wo`As?*wgks%*5Ej~Z15Ri{z4 z)(Ur}pE1#*$r}>UF?bYhLFz09GP(`UdraN?9F+&9RvHldwBu*DM3M)7_4nG3 z4&3e<0NF~~k3BXN?K9cS=P*VK;YmwBv>R_)9|T{!b#8e@c?d_O>szoH931UGpn5Ou z4csb=70(F&8#F-g(Vv(clFU9RMco@@+?NqN=!Yg>$w$)|4;NBLKUsQj{Oi5{-msDJ zyK>PH>4PD^bclp^F9T)2^_ZO&)#&R>ql2G@%9KYsMBht*26EZyRL)0Zj6>prgB}@= zd7qCMJ{}q>8cGQs#l9GWtu)jYp|5vQvth;?_6FvZaSPNeY_`?I%A*92!C((Mg*~if z(;!M=T-9p4^lakW*hKNr_*H|^K--afwv*r~z}%QjN@94otDRXC4>1|iGaeb+>!&Ej zv!$TPD9Bye>6o$9`AdUemHQb(re?c7^xegikKtRp@T)|RNwV^4KWv|*1leCRYTEku z^eSVbpM3^{@si)B+H9wn3ehyUI2Vc!n>Z zG98&0b%Dsoi{#l}YMfQ^BOQ)uLzQXvkQseXbe<*o9}zk;JZd-`aO0Tq_&mG+YnFX) z{Cz$Cal;r(Sr`W%TFMqmIOp>n2{L;zRjOeD$KNSbf z13AN4DVjMdbO#=F`Jcy|E-#jo`Xx4W*T<+WmnJh(h8wyU2wHQ89&-gLbH&|59O~px z-05fx$Gbm&z@@nLA{Ko@=59Ak*_xoq@qst@rzMC}p_}dtZ;}?m&lactD!K7OnsLbE zaKs%98iM<`2=XpH27a(0qcqvlJ^!S5j;!2!{63xPB1)RD6n?wsX2`Pdby-mi@+FB+ z4u{=#f&U=DuBKBF@YyGxjppv3=l`xqo1lfwqPjfjZn_Uoa^NYi%*Y(T53SK8xiUvw z@z*}Nr0((`lch7yr8&|`+0=|hFrCMiFD!IHpZc>%DnYIZQDINDOPZ8Y0&4pxQ+(?0 zlr{FoFS_Gj>~D`as(g?+0EY1>v+z~&iT4KIN8}t(zX)(!0>!a71%QDO@$s!?CS)3w zJY`O{jE~A0y+a?kGBIsaUvi7S;~GT_-A>NkPE2))eS3d2?o;OA^dJC=zt~QByB&M= z5kv8&%T>CQ^e12m${hVI-_$Lrgu9)&`_Akx$-BgIekFzFTkd>qyW<&v@$n>hev6}Q zzxX=a_CT+3wd5*ZN&@*>2%Tn+w79xqc@<3>6X#FdPgeaFX8CRQ>bJa-Z_%;emXMFW zTxR#&4zmF1kwc+Q#XG)y!vp@taM?M!{5s8(Cyu? zA(N`M+iz}7#jY*Xdmuv5*_v)z}Zkx!sidV1(oY$NeB z;UW6U)x9-T*G3we?J9ACcmjab3F?vmL0)3ZAaY20)o5l3Zml@l%Xf2jhKZ|qt5xME@BC_P;LNKfU{*?DtqP?nD z(Tj+*F;c13%+LRDW4yFoK~?z2$~2tKlv3^OSu_%yXPG<8QWkv^lyLk$CWgs=s* z)g}zR3;ro-EHT6fAFF88Hhd3=RMLvdd~$29g=Y3u0O&I%ScDK+)x-$n`>Jtcb#i`s zGYw*#rc|GN*jn>jokjPVDg8ISX}o~C^fNAt)S{nFyBDI_7^4doGJw(YA3dqd?NBCF zmO##7#>_nYU-ab3KYDUzuD04Nj(^t7feF&up_lWm#c*!9AAT!Y+g1aEl+b_9B`6>A z>sn3xUmkXMLz7-c*>LebHXG=pRZf#g%-uq>ey#hAd>3WaMiM`3`{S?f8)(+vP2%sc zhocyT%`2-~6IQa=L;dHe_&MvM6r|bW`{YiA1b_$gKaUp8)b=-%?F}!-rvx`Z-YWSs#uUm~&G8*u zd8?gIjbwpFvq%Q6zeBdh`V^t#_ad~@W1s#NjL<6$&^?9#b57NteV0J^&t)c8r4T18 zL~??8;_s}rhT$Ms|DAN?TsKr08=m_ZogcqF2w1ey2$XyJg$y63Mn3{Pu~0`uj>YTUTL7!j zMqFN6p#+Ol#QNaVobt-z4c6^z)YG9?1RPjjQRGon&?HmwMboVda*qqICKQ3n7+;fw zmC#%?H+U-5kKU9}qp3ZnB5q>1Gz}xGWdK>NAidJn4J1G1U&DB%SFPCA3=0gp1KhBu zqTGORIh5}nm@5!X0mpMw@trtuo{o_7Ct~5@2Z*$n(N5U&_7eSzskDN=RbFzae$r0@ z(nmhxCNeI3OM5Hv%@|M5uqEswe-j1<4Jz%@AnZR9cP%&ZAJs`GYC-oZ3w&noiVm=h zDy~MSag91DeoQcKs3}AG5qh+daxtOo5cQ$G=}m3fiLC6bQle;{n&+blbsmXQn2O7F zd32o8^`5)EKY4{uGva@IrVV@#tP_41v>>|$Pi*XzRnjjg+mYV!Z%#=ng*Mt9ff?(Wgu9nvM8 z3R2q`-6bfXfQTrdw19x4yG1||2?YeC6{Pmt=X?MDxzD-(-Pzf>{w29u*zo2T%pEr#o_@i7k;O;7wPc?g-QDZ7SD7R}C`#60 zkMj1NxD0b4(kDdV5NAB8HUW&Fbz`#eftz+l$*hiNlS%1;qh-dI;Z5r125UV431JF} zm9{&tU2?l9({eK|xO;*B);0b*cR?ettsZ|bCEMR=nRl=_LJxV$ZIc>Lu~qpnu0b`? zFn1$p>4Vj;AdU14%C6?tPE}U_M=6^oQIAMt=mue;iwe$m$rm3k@QvK^G+cf?qwiTU ze*5aikb+m?QxE;G97$Q&_oh?&oWDcC=tPj)tJwCI9P2|w^c%OauqZ!4o}*@yN&&~y zzr8e%L(+p$?kIWr79LW;WGSOUfYklVVvs}j#N%>0AcCHL-WzS4#G!NY{HYl@= z$dz$xusG5T7{-H2{XLa3U^V0$l4ay6Izc52e=C&f!?Mn8UDR_@D5;eyKqXXq`N8op ztc3uv?s>jiQIlEed4UT_{KlKEP8-qr75Uj>KC`jLzNd*5N097_ z8?Joy`rGp%>od_JQ~4{1EN*j&%6dzFov1QMg2*)_=ws&^5kaRGq~qg4YaXc1HAOi9 zh?mO1RCUYtzWO$h+Ku}9BfbE@?$5UquLR{EYHD@5vUypC!x(&!8@|HiY?80?i=Sj- zwUZvAp(-!XJt|Qh>aq_qKZZH25feOGme~tO1>j~hg_%)3;(%qQ#bd8F z<0K9-l|<|h*x(fj&|#ErPizGJ@FT(0@un$XqGa;{^v*%H~>IM zd7LAe;+Tqj6{De5*8WBa7uiCs3-GF*DkH@;rHwRQuLp2rTzcq_{F7;R-E1Y--4@(h zskI9G_Co-e+O*`5M)+XDQ*DP>El25B9!7G`t3&48Ln(U5hy9A|`#D~4q@?D1>4Bkj zeI2hKuVT*>eT8-J|G?edG$C6b(w^#gkZ89M>4wtqg>kdoQ`Y@ZDvvH<5-~&A;{m46 zx+m(of^SNrt4FTfhfBpr4G9PFhzEQ>>7t+rY-Rd;f)1Fmq3$!yjwB;J&X$oVsgW3# zL0j%r7jAt(g{X&J<3lS=9~M6J&8QNQK0<56y;Zr4JJqi{(SKEz8j;@^rf-KHdvref z#Hi`1a8v%|NZG*<%5EfZpTvE(ATD++sJJ9;-hG1~fprXul~Gz&G9Fl*B2 z-B+W^Uq&-v-Pr)4VYJ=|%~)Tofocm1+g(~R%@1i?H*O!CvVCg&<-GLmYQuc%SQ?EX z5;mbUi-M$PDvyeI2%1bOPZP8l|E!jq^Ovsw)V;K7yjv)n5s*RHQK2(G6_sI}sBd!o zWAdmFI@dihylT?Jt?gF#?Bgt(=koAHS=%KE|8=!#w3eA!tif5V2|>BcCoAKRv&dB{ zgHiO%Vf7fk@ocI4w6)gETLeOrA8Y}~cVkF)gC|+=gZXR6A*@p0!6t9uh+bw$Y3MX) zaTc~UOGc}FB29ENI8u!OSwv;W!{@oJEj-1O1TeyB+^>JtPk*eC^aP-9CZ}|`P04?o zvx}(1R0>#0TUcn*0VSwj&3UYsUXm6+TCM~ozz^1fQh(OT9STSjQe&s&9PQ$*6x>KQ)=6N7U3-7x?Q zYi@N?tKURDR>rO5#?9}z=X2%rfRUqveE=;pNNdNePh6&oYwh=H3qh2C2fmhPoP-9x zk~gW0l}M`1&}eXfEdEa3B4OW!f4RwzguJr}j65pa3g-r-0eV7D&ggHI(67V1jpA!ypgcGD31G@nr zQ78nb3bL1^n2DqGW>cg?URFl7SFt+YWtvnk15Pa=zlCk{XOX$$kV#?FkGZq5P)8&j zQ7-_=zIDh@S;-S%JXjWtP95o1a*iFLFu2yq9 zVIyS524sk+cRzS6(|u4Tr0J;e$aU)U&mci0Dm8*sI-CIFd7gG_(`~kvJcW&f<;@Dr z)b1(92mmodQeXuwdk2Az9e}D9--QC|Ls71cAXqyoU;FkAdw)5b)UX1ByWBMi9>R^^ z1RfP%9x#&#EF$u0p?jQmGjU5VxrN+MSY|2jAz`cwl&Rd8$#KgBL3YYWSYpI%N&*5h zf(HohKqJi(6B-dHSm%P>;N?SZE!s|XGb;y?x!Y+0q`70lj*X7!2ope zx`<_(b@JvnH@0mCzeT0KjxT=qpYe>+SwuPDXM02){BHqHu#(!K66uPLK->c$5dSHI zyWnDl=J$!;k-0A4w70ypA9KImBIt$wc7qISJCwqaI3X%~sJSn9*58SZCMx@_h_!8z z7&igCr~f`ja% z2pCnLZ66uQrjX8a(%OGl&RZA+D{7YYvHkAJ2@?XgtMR%Nru9T-G0e)w(f zJc4$orWSB|=9cpJ2kxyB&Cpe)q{wDp<9(GC8Tmhte7y{)C7&9eNL_Lia2n^?!pZDv{CKJ%t#bxvyN5`jxVR--mNN#}aS=lZ4=Ui=VRFG~Tq zKROq&GZhG&A!Nn1%iR6GeRgK=JxO1I_8(2Tw~XgNSOKR$uj1I-Q9a&egI1g?XRb5O*Afi(_%c|9ZmzdYL7Ax&HNXP4;*!_LJ%zj zm=GX&W3Ux}^0@xI7Xt)q5rvB~%y~N!6`(aiA5(E#a#|fQJ0<+vdSAs4e{@knA&mYMbE%2H`ECB!F-ajOmNyDwE#nvY4iMs&+pjbVlCn^8z-bI?Q zg_V!25_1lhJr7NT0+^x_wJ4HxbN=>T#C)`cSn;Dn6Rx||>`KrnHmQ}UMu4&2b(^hO z8-c)6zLj6J_X{iDdZeCktNlsE5y>SWHyDJLHQAj%*-iKFC%Fe6YRR6kze{q-%f+`V za<^Y>%`JTAu>S9YI}%zK{2m?^-fT!9Ejw74-excrrrbj2za`mgKofPp8VGyEmow`!wrhb~7> z#x4(INAd2vZPo1!vFV?!iy0TSSG#gBq!FX8xo{Prkp#VW za-^{0#!OQ=P*F%``qU`Sbb&W|IDHc3+b?m;u*sPvJRilC&GoqCMLLC3C;fORV9z!yms%6tavlPy1^XRFs`_7aNP|zBfjRh(o{5o4#LX9=Izar=)HG6 zvyC`2>YL^E8jaK}g(uuv7I^Ig3(USXCFU(VC~@b17yQ-GA*aFkMjHc%l6?5xtmN-# z)33Cuf_0S?>$QD5IMaYfii0j6;h@Vt9CSIuNUkH#5xLv^)7goFe$Yh_Sj~On$RPCz z=~LlVec}KM=Lxep{;9-+t>aUZ9alT8y=jhXI}9V9>O?POXu!Ce!l@QU^R>cbpjzk% zBI^sbn0BP_kh$WqRZOPziZhGFDWSi8Chy);rb=$!5*(~!d?2Kol z)4wN1+sNt>%4~4otJ7k9OO;}osm%kduHA?eimE+ktSGQ$Eh?7~1J6Eu(26)AlfU-! zrZYX_k7oF+jQup&Gak}j4J)NwE9~8G-Gh(o()1mflbVEJbC62^1;uXx3ZC9Pbv!Ql z{G!WEN&vsQ;G+k>iZd~oS=9K@>CCRH0d;yIkj#2$+!U(l%K@`?CpKDpev^sJ@Ki5#dWYQ9n=L{~T6ZI3cMG5NLXI2tB<=5M zdE(h801lq}+sD7A%Vp8@-Ko~ZQBA}p`R>`{+_tlN} zu-YI%r+f$ocPQauIyXM-tXho#hoUAt?H3yq2Z?(({PAox-uIEo)@N(^XfZ5y)` zrDMR`EY>U)zW1hGidu9lfB^sm013csw!Dmk^4x8tZ@C|}a_a}GlnSgQRaCKOcpdn$ zo|+4`hIg$biRf3>4Xv0rqIsD`M6wj_%=6#k9CzY28~)wlNkkvZVy^QU+rK5&1z zs7{j#Hy-H80XzhYqxu{z)>O5i0j`=9^}n3zG%#|0xks@)r-V^j16H$$5x!&WSN&VM z>aL~RcPK_Ggy1T&;or^Sv0k0S$@s&5o48>$4AQNmVUV^Q2IYHPr#IOv--o{utfw07 zh(2B?!)2zr#ZC&prc3$=)oCAFzOvq9d zQU_Sy%zndr)v+Lvy0Q zKK|UHLrP{yg_gDh0EkG>UlVddzPAdj9ETaQKby;bp!|Y-uci5!J_!QbEXg&-l`RFZ zi6u~Ijr<%%b|yKH5t!5pV7OTxAqT9dn>8-20K@^RW%QGLVHNdbYCPy_7B`$VaXG z1^mSKaeB7Uxc9{%ZU zQ~9YKhj!G_qoh^SRsiM`Z8a$E@HgN~T`cP=@xu(%caQVu?#8CZ;9M>Umyl|ca3o_!H0*&qb-7~!cI4RFg> z9IuqB+-TOTRK(Y#RkW6$tPJ3PVMNfvbpz(0-nKu+`hMWM;mG%AUE1F@Nq~G&nyQ!m z;8T_j1xMi@45Xhcv^)oTNVIre2gvB2p#Drtl;u(iE|aYySwFE|M!OJReIaB5Gngg5 zO=TPDv|zvIHmNtrwyP-yuoC-`I9qGaY~u`oYO29BAlaV?ec3M>HYgue5K_5nAo}>r z29#&}iTho@uDiu`Xwy&j8%%-d;omQ^D$IrPh`6iF^Z_iZNLncTXH(@wXC*fsm|Bs8 zCLV+602?)81S2$6atHY9i{Y_A@$N*WOVm4Dah4TIZZ%QCvmagvlvy2+6MkB2T-nmu zuO<)T%YGtDv?*-EmSC4G$ZHL}8Ku+0%=eUW=~PikV!>*91Kg`%Bp?~L>`S!_Vg?`? zqcpz*F$9eRLKHyUCyEq9{2_SEmvH)Oa=;}<8I7XULaE|5cfuG)n)=js*X8I^wCqy# z(s6nqhCb}etD@DhBDYM&85WqS(y*s6XqlN4hJ>YrkwDas`&3HOTow^<{ysIW63QQV z!nEN3#K>8c4bVdV8B_92qJF$*(7}YN6OYZ|fP4r@3x9~YMpyT><$U>z!?H>%Wp@G2 z4Zk>^BJR{u2Ce^~NCZGB00g$f@CPJ5!9kH`I4CkvXfR!B_XlS+qdH9n^aon!uoQSX z>}~E9SdWGkYVs-D@#Q9R;jGI5EQe{Mm+hbvZ;!Lu;F^)3F*&2lLuZd@Gpk|68IXbQL=s6q*{@nD5ueM#a2@7)cF0)~9I``O7Svp}Po zSDod)!jEe9R#K*qGiSKfU9>dC3uoY3{R;dvc%yi@gpKJ&b624+0R-TW!am^gd9)C1jE~(04QK&7&%Q{aW_xCggSB^Eh!mM*dg9%5~+c zI5ZMZ+z3km7)AW2Mt1ivn{BBe@MPD9!=5q8+-MTR_MQ3HHCy>KBX<iV?nh4ivO> zMu>J*wi5Ssrrt_0l@`ADW^ZV}n%)b{c9LUepD-K`Oo(C~Vt?8GEGU)te*CUut@RJs zfwflsopF76&ju+Knj)&2MwEA?52L0xH?lcoZ~#>4K&cEma_3qW)g0XXghZvka!`dx z&LJho4zyiG?81Z|^i-D_YivJll^|92bNK0pAPL4O?%&AQI2K#$}_ZSg;S-%3&hN%cm-vVZ2e@AWNFYpgQLIMo}mf*fv z5$pB9+UegGe;VMi?)=$R%U?=^G5(ujLk5TeMgU-%5H(vB@MCz$6zTUlOjL81iH@NN z?tAF-fV~pIVyX zC3*;Xw`L-uTs5Va|HF#v5bv&E?Pluq&08%JIPWN)+Oej}&9eTN$AR#CarDtPkywEO zW1)I7_U`CXqw0P3;0Ldt)> zh@1YPVXj3|kRbWi@u+Es-MEtpm43H>9;OKyfvg_)g-HOU%WK9O>BR;~E(RHdv=|>Y z9gY!15}_kOfCpru;1nj}%V9jOP=ibdC2@^#WdeW}!5$mBFaLy*Su2u9gXx6?{k{V- zPltm`i&H3!?CUZ2)-jn68od{gLs3)tN~HMwvi zEtgn014`;!NH%&ZJQCLNBP<0D$QV<{eM$7JS^P*+;=`yodrJy;i=?GthgKRbvsM8W zxX?hL=qitI;*<2vKv1%zLD^%f(L~kmfh7D1T`4RSCTtWF=>ugHQ_ zAOlx5Y2-jjB6l(IGCWJe92bXN84>_`_}BYLsJqMsYQrzA&4d~~nlH@q zyq<+ibYut-Y=p5Zh%`^=XIMp0#e&qT$%T%M=`W3G{jqJdy`uNCL9*Ou%GKleNed!A7ZVLQ$$b7Q+Iv~fyUya_;@zeth@B+A5?Z{{gZ~7oE zd<|XhYko1=cwxc>RuK>CRyd6O%51aI{~%n>Z6YYVCCS_@D75swW@D95e-$J1Md(PI zla$=cCp0F*KI)C4kprOzWU_3{xIg*bc%MPrYguoCB*mT;#JdX(3WQ?wi%0Jtmh^gn z_|T39^6K(p=LTYb*50?2*O@((*NK(aAZhm9$Kpe{2Yjg-QA(1vT|bI(IpD{J64m#( z(+GF^LH}MJjZv}NFJgCh=O<}0IkxB=;?svx3NGg+5&;g}nv!dN6IQ$8$d>mL>5DPn z#&~H4W9|%M*})M1Ms(!+lIVZMV!6*Vz`0@_DCW%@hJU4egSyd~rKKHyO;Kh)wF(_a z3&{u5=_dOIZSN=jlbst-TlT0Rew3hjnBap?%AzeOs94R62BlImR)*Bs`jvfus!;xG zy83=hbe9Z|7(v!m2}zd@P1jRqIqod4G{dg+COa0r>0`kU&W`)xBQG-X=-!!HF1c|w z62!cY`B`Gx<~-P-FLzl_KG>)Ixn=3fMhPqDqNLS!w%9f@|M>D(yRH6vQ@_;bXmjqw z$Gji9)CR}rY<4u13=CpEB;M<8p~A7cpBI%V2(L%tuEX|+Qn~(B9kJIWNrcG#`=k1= z5AR<8D=OWq+5xqjo>$-|$5>}8fFzAVCv~^_Y$SC1_mGd{)P&P`%il4+QWw_Hu`S9$ z53Ol>EvAcXi3nKTK&*O)r*H7hR9*di%+f61`SkOrB$tp^SmjyU9uxi8+yVRq&o|?` zJ@CfP!Tg@7;_Dk@6{@5gb_tA|e~)FDieGe3a zuQKhO9}s4dzh3cC9SZ7oXjajbh>ziU_bcsgcOU938)OCrrj8r-B7|KvCXe0?w1JB_O(zh7c@B`|j?%tW|Gv$ld-7PjdCAH55Qua!1_{=ObKrfHCbO|z_ z3t(R^jS*9DoPmXBD~#^OhA{Z{T;hV~wF~d~L77blDuhdK4jUAHbde8`sIiC)&g&?X z3LG$;PxsM`U2n15*kxiV-_brn&2~|_fJC1Vi3*b`va?$BWzSpJjfM#l#WZJE7QEu-=Yf))J&!vU64sYIAfG7&1f!X~+dszN@)n5W?~YK$KWEc@I4 z5j-~4CmmbBl~9|Sr&sUpln_wySZUdlx^HGHC?1C`s@o6H@VX%9X@)F-N=3`>X8-9H zcs$7(T`sfulWSAb&yCONnj#pQ#1S46ZfpHYCUiddrApI^J5Z&#?a|$a=C_B`kLYTA z%ZcT<|2IDCKbC|&;~*NN%0YiV* z3n>rnEgqMzo^RKL#Vb}5bMvb2dB0fm-7zZ4PVJAUz-PRlY}2uo9hBp(_^WLMGV!a9 zH94k^i<=D|nfRma1KqraHlz4^kXR^=ZIN0z04LwlvFRneC*OyC` zB-Zu0w@1JhJ&!m7kzx&bv2u z=fzHE=usPAYRvDxe>+K+O=aIXF0=g9I9g^oDVOcFL|DaHsJ$1v*#$!MjT2X237_Pc z0}%LiyE-bP5=3>BKZr3=DN3;$=tM9F+mSewy~B+>pteuoS3kQE2~2{r*G%WiABu%u zDx)Y8qke=tsgvQ7EZ0f^q0@Iz&NAi~7MMj>8s8}-ELl^-WVl*M$ z16GP9`qjykzlXObuPM$OMWMQ?neBY3OA4(*Cx9zq6}k8vqfmsyK^1HcF{iOA|3Ul4 zgFU=@YvACromXN=xVA!%J^0C!vu|$radU21GJ#iGpc&*ydJ?W?M;|Ti&I$$sm1KcH z;!JnuFff7jCmi0m!%Ik+R7^E4#vz<x2W;^J>xuFc6rUdCr?9HaNQS$?8=akC{$C~W8qGxEuNd}q(f3d&Q#Lx)EWZK z=y?rsGZBP6#{JTseL9p{TnzN$dfd})asY8S8@miD7za;sH^K|MYR3h{Kn@F{)wI}< zp$B+qhs0W&5Df{S)RlVTQtu)E)ekf-erHRj#E`sdvh))t!`;|oKC(SJ!onmQ|q%_EZ$DjR<%F?LHozp(vfcI1c-0%HcxsDzU zM^QhJAS0(h)BX_Gq^~;36jlqF(1?ahUIFpNTLK6k)+Q2d6I;>hb_ELeeoYE)2c$Jw zO}`&ww3jge#dZ(_v@dnD>D})?&V6e=EPnDRs~{!r?>cs}wV};f;I_lW7BiCkJFX zsR9T{jbZR)s-WOg&~`;9tYUzF+An%e%7f#M9KZipCUD6bg4C>#w4{i_+>#zAij{2; zryyvDCy~jfWt;y@qJ|`#PcnSUwurw+ji~n?<)oDT_F{B%&kZ=DLz9h0H7cLj`GnCYc1z|icr@h(_n>n*Ho^9#<)c5~;#l-+;8{Je zzMn-_D7E$iPQh9BbmfWIlIdRbj4xgd&=JfrwBKaWlL)O0wXWn#pqvTyxBPpYH_YVM1nKgf|lG2 z5dXxtlH$!_ybApdk4}WJFRDVwe1y|Ny+reGa?ORN$oK+N$hmp{Z03t^=YvH!X(cIW zUT#JhY8h7UR4DP<1s`yhStq})A-k+o>`1U+3k&iDY^ zG#*qsPYU$Mq($N)9#&W?nH{np14Zks#C=<1rXvJIKs#zugCj55HO>B6 za=xXsaB(m8&M?KcT2Dwz(dSwTq?maO0CzXoKdECitgSrKv`!*8ePQ z#W|{28IaEZiYzCM-RqIUe`K6_+yBJ28S+)BIuh`vCu{F4SWC=%y2)5Fx&!al*|Op8 za-GQ+4VoTFUoLmg zXqyO$wg{;UTFXP~;dMyiI`t)xl(RSt0g%HYVQz8{URRm(^kV_J;R5cyDs-VmmNC&U z=Pjmb2RGP0ZP4e+MIUWb8jMpudnmpCnY&t!v+H1@-j*|+R{7S(e&+K-UHT}W;^e(Z zAp-L5jTgp^4Z;sUP@Y&MW5^>ymqHC@FP`T<|8jb(f2oiM$wF%fWb_e zP&qG0`2>+=_78MHz8wM(T%Q*&O_^9q<%RO&OCHT(2`}G^338dh&U`%k24YTmR?hv{uT;o_RZ+p%>V$X71c=) zu2g@Kq~p7p^P_#L6P5Ubc&n%40$o*x_SL|O^|ck41?ISRonz-o>Coq*eTC#4+}X?h zN+S1s!C(23_X{Z8>3aZ@9JR38^*hXlR9QW7|LK3a)>FI-8`P z*pUfVa+boF-rQO^RPm=Hh^xpC-JILf7c_{Dv@m6QFY%Xu3c@Q|jZ3+9pZ=#?3L;^8 z7&hLzcZOY_wEZ;Q^>4^4c-Pn8)^rxrf9*wnZPHJw%`~Vh@Ourddi_lBP0cuL(v_|3 zVOOVL^$+se7A}aBy88i;qUZX99A`Iho!|~hNVwU7U3}Bde!>BDMef_DzNdV>&pZ^T z)R9tZbvND&scR$?YT~bN`YhT!&kPuavwbQq?H+4sX@m9db=A>{Ll9I3$j6rWgCKGQ)9{}%d1ELz7c+W(Kd?8!bjP=+51F`Z}p zyCKGaGchCw7!~Bdbg@3V`o1qxADGHzuymNmJ;W^nw+*GSZ8Bv8wCUqJ#?$+OQ%6%0 zq#RSXLHHy&g!MfW-;`IsmaXEGeH~-{HgNA-1M8W0xw4bdT@5wBcXBu+6XvRZhjOcn zBN=64GK>YVaYNXu>Q|nyblb*s7n1_C06hwy3%5?PUCzNIBShnWdaae4>{&i83}@yf zJto&^coFrRMD?8P6z`dAxGT^DOZl8#(^u|o{IA5^zKvXz4l%woZ7Di%{U|%4({cqoTE{Uu)%DU=SdU%mV%QM?u+c( zFE7L746X=|^uG1PUSG-R%LzNZ^Pr`Y|7=P$PZNG~eQo zFD34q#MbB~DX!SIx9Fp-%gQ3tk{v(J#-hTpGhGC|e-XrctrQT_-xEh)Tt+9m|C8?C zJ76+!wE7_8^&YBY9@?5UVlnf{7nv@bj6}S?|l83qZWDl zVmZ%SXEBFEClWBi>VVY~&yT?fbhvtsDwMFH_w|?A3~ztF{}Rs-H0qY3d*AL;lFq%q z2+7-BGa3SXzdWQB36<_fj6~R9&dh`-#jLSr(X~ve%6CxDT;_lBg{j*2c(v7r8Kh|l z99NsPGeoEPowAzjquGkA{qDbTDgVu1?V^>e@BKtAyR#rq>)vBMwHk__+=VRM=q>Ze zFKJ%cPR^Y^kLC7!yiay4`ulq4dC8T}ua{3b zt7|LuI0XG(*AS&s+gBc1F%sRLd!Wpyd~wsStR0KL@;djrUcYia?BZ?A06h}4ucpfg zXf|dQT6m*q{Z~hA01GVwHndAd@V$F}_hmn|pQxyzoj{@Pz-aPuMo^bzc^y@!w6)Em zwc-%tNW*gcwQ%ph2SPzE8;}VxOvUi4AoByd%#eOs)`0vEQpOML+|LaBj(UKJb-~71 zvKWbB)|RIy9|i@xsRy{98#Rw{DhMxlnw=M921-*xy@u$*KQw&gQ0oq#P#HPr8LxaP z7%`{wRjbuj7%yw>!M7==b-Kd0=eXI|sy;6)_=3}wt&EJiG2U@r>3onq9O1;c=q=WVbKGcu$3Hra9Fv+LYdu}XnAfqX(S}QeX0K>QTpF%ScbCFOxty=(gGb7$(451 z1zC68M;EQG?UB5BaskPo6^pc_0W=?eJ1`f=d|Ui}t9ZagkRxrmnh?BuOh?N;ZwI7V zn4yt45jUeH2%%9qTu_rwKtDPoQ`OwunZf#8TWYEP*7la2z`zYa7_<@v8o-+N{BTc> z18TDy@4Dxrap%)VGK`-{M(B!{(Nb;I%B_GP-Y{XemO(s^#w4xVl7{OX~vbB(Oojgv>2hg517ST|i z4M4+oZX$MGCNJKj)rFBuUi3y=BE>4eBYD}EMz||mWR6ou-^8p!zN{k2kj9mY`FuoV zEF>K#%W*8>k5Igxvn3GFR-@v`Uu5+4Gir5Wzl|Cu^p;G%k9LO;M~|941{a#xSHHK@ z0C?!ta{+hNStF={`+*i|$b&%c9n9VQ*G_I4zA{5=i;@aSPZ} z3je;0>ocR`?)q)b+7&9xzr>Wc^4hxcxIp+5l7N43jVF3^GQy$xaqJ^b+NS$cQO>i) z+VeFSvU&ctKrQ_Bv_vA`3nRz3QWd{5YgEn%OryuCOXsVh22P9QG)~n;?Lh*o^NCo%Ox0gDafF65=}oC>=hzSBF0;57<=ybSG=*2Yi=tawS1--mdjlA zc%e2%+s~uu%C6>$)(t^=VBd4`G#@uPS?8n&&W=tIUY>mG9_f9*GTOn>q}{csEkJbc zDeu(bK2B+SqG4lJp(wr)msxh-bKvT0(-*7uKK}-PANghBwqM3Xc>v${xu|T&QY&^r zJ22AP&}p6VqT@Nb!Nev*h=5|ioRAPshVdW}R5tDE4HR?vw!i!YC3o-Z&me4mDHkXR zz`Y#SW8JMCU>vKNF8pABLnCj$Hfs<}&+~JH) z>F{!p$c=@t|G(k>Z{q(SW%n7>RR1>mex;B?2w4;<3K&2{MG>T`l+b&#Ql+W%CI~1k zp$0*UsB{R3f;1^A9YU`ny$C1>($z>45y;7X|Igmfv-g}c`y5_m1~S7dLRQxGyS|@* zsz5V|wTpeXWYO@g9AtQ#5Vtcc205U`a{1a^u6#fJ-V1)KCBCTp?LDi%vLJG@y!*l| zC`g1f=LHBG`4fs>O@bLdUcFZIaJ1NcyD)WpK{kUr`nL34iAxYf&T@9F{>Qr#?*1P zVXXGM>#{PF%^ZEh}>0 zzGbhtR`ve6RN5%O&|iIaVf;y%v=-K=!9()xKyR|-RExYnhmf2S>>xr}K`7zCiTC_8(CBKyK9z+e4x zEtF{FIgfug!K9ko{HRs?|H^yp zpJ@y2PXuGyg8Z*(OI|XQIA|9cQU(AEDR5PJTkOowTOUsdbSfGb+liznW#0Kt%S@!x z{ri&LmCMoCX6CPDcYA*!CkT)UNLf#?aex`+1*hA<0V0k_1Q`iO z44ZTAB72Z*2qx0nzdc04|7OFTz}|fOeo^OvDzM0yRf#CbC^w#2B66R=)>GKH@Yr%1 zlZ_2#(gp%h|3S)xv_p}$p%{`otSj_fm(_XgFkm;NhnwhqGE(4`0j!L95f49>`%kUW z<6k$DffF%ejaYv$Hi5MO0)P^@5CB+=3SR9D{^1AGqC!=wLM>5uZ~5yoHu>-HMBdYk zgic&7rm@}zVd=Z!zadZ^;E|35w!+3=2*fsfLeOk<^pXUCYz8(6p{4n3SrP$&F{YLX z4kQGy+B(I`8_aTXJbjLT@JyqPN58{AHi0Mlsl3xCX`-?UivLN_D}OAZELsxa*Ra7A z+rYK)n4fqUK!7geG1{}p%~?N2fb0(e&4@Qfh=w#eTE|VC_dOYQI3BX&A0PBGWH&MB z4lVYjFTMCN zoe)1br72|^FC!nxSHt+Y`^1*xiO_3tE**28Kjc%XPi*9)FFhwtb0l3r+nq>dZ&@br zynNE0pY+H7>Ckp!`$iJM%t>`p;=CDMN&H%@{DZ{3l*F@>v5J4}El|&xHIl6FBwaim zt(*GvFWDjd#4}qbHT!N;bEoJ0W)B=*KYyleK2vNW8v z1gxk#tz;$b4LZFXoi0a3$>GzhqSI?$r@wVduU$!RicYUbXSC{Ml$_3JkIra%kkQ?p zQB}jxDl<#}WDM$L_Wog_Q%G0Uq379rW>zx4ptI&qXU*$mF?7qN=&Y63S!>-{-&eAJ zqO*UU&fa`Yrc2zj^~!|2&i>n-eXv5$W;944XDBdT3X?Mh`G|rpr2H3oS(t52&=42= zm%J>@Io6ZIznUZPFh#lIJZh`U5r9s*Yp&t!Ea9rlX%zkHkK`-6udiIL=Z|{j6BF}ayv-M4 z%YQhT?{KtW@j?Mv{Z+xe0wuEozF#k6KIuiT9`V-APdIucwBcv>CBfn z%Fvf4xG84}15^q_yy%6&iG?qYGQ7*e!o5Pv>cS$)qC%6R*Iq?05{vS>iyBsonwX25 z&lI=n7PmVWcRniaE-dctDgLlp{E@k2@Jz`$Q#;Y;2|04!GRd5i@7-oPz;FrTP6DUd zF2_4^iL_{B`AcbxB06Co6rxo3T)k;mNv9!?<*TqmM!^Nxs?s8%jQRH7s+WdbUH zJY*n~bk^_80OrrV3np(x(<_jPZ_gjAG;pbu4**5{?wzi>ch2vfxcC+jBKt_b&*!pysa5| z8x8Rf)$&hs;AGeG;)?QORzcA`AGbzvrYB&>m!TN1nlNO%_AltTKZ0(IporC`YuBpf zAhODk-Y);6r$~%K3)X1(-oBJrS2yK-f`$nqz-{o@VJi44ruK4Ty*CC^@A-JG3T)S_ z=_;!84tOkChT5mWO#N%qQ)q5?BXF zU^Tu<5d$bm;Bsu>i4>d@$npJeI4qmb?bjex(D$aiF+^+= z4engV%HdB%*Hf{9Eo{XtoP90a8K6dAd5i?}Z5k|;fJ^iQQN{nZA5)3e_3tI(W5lbJrJzs=6XTHo{0g&jXO=6%Na?@<6?0;0GTYMdkH!Qkbu*P@Vl>AAD4lKG#r5l#)B*? z4pd447NvsWDq??O*^{5qQ&ikhvfoqA0-Pn_9Lm5_WIzQsM`IxPDz>Mvucx#aEIZr# zD(WFXd05=phn(wc(C-;!=^Ih#8)E^CY*;0!<<4ceyuT>gz>(_W-uevo0Ty70uWvLK zTay=f@XfFRJj!6V3lR@-%Z_I~o;4$bx#Ra_@T%ryNlyFS^{l}av z9)Mz0h5?$l>R`86I_`P_9aKCR{uPe?DgnQq&U&KYVMQSL4Z!3HGS315TAr-3KmuZ& z1y_xt(Wo~bkD9ynSsjd`=ODH-M}ll{p$v4=7&CR2j7$ukc424Sc{5BHo#q<{W=Cz# zjRCVkv!cNZ+~gD%fK?!a{e%O>V;E=FPQb}U#fM2b4V))!-fc@!EaL-@?@?^4uWxg=mcQr z0cbOJ^d`@dAPSBp9qewH{%|lY*j#SM&>*ca?s)%>~1&0VemWVn;9>EO1(%$S=2f`;B_xRajfE0V15s8EpN)o2{L zLBmZ`M>%Y;p=DJH0pMrjIb;qaG#Y&pGRJN>#}zks^bp7A9wET`6={p!rDB}`L=zQj z#TJ45MG{P5Kd&@*`Uk+B^)HUuIC;dM#9K|`*Iu~lzrdEYaN+ZUOfXm?(a$%kZuDaWk#_N0422SZUbI*&`wV zE|#`*Lwnj_4pV)KE5f~7(c$xQ$!E0WEZk~VGAmvL9A_LNQ~WBS&&Jiu%DdYAbSZQ!^g4XOPFL+H4xu2H)@<$V4{;O&Yi_wj{+PW z{3DRUY8VK<4*KH|av`m+<1KOppu}jCBAp%CFjVX~_mSfRtefdzRZ5JfW$hBB3Tykf z`s0wIL)TM^_oI5S_~RBU5i@CA!vS>93+8m>~cyKn?;sCFhh(b_b z__D$uemyzxRU?*HvLfL2uP0Tpsz>jhaFk$JlTh9+*p|fCwns~mD)w)`USi$%=O>nrJM$j<5Ij-3Z?{OoGOyQ<)=NNEH6v#Ld(6PujX5^Dq($7^%R zkZFeV0d1jMS=Y!FC|iho%x*b*3I*rV!CO>$ek<*t*t_p~ zjP>3#Z&i5&{Bt8jzcjGslovg=!?yPjWbS(`HBv9aH1OANs>-X}!LK1m7GT@FbW2(} zv*J$Q+V;<-FUn`mdXH7x#@}y*65}rfd#dqS!1v~!h`WMn+`gri1+gKzU{}-w!f7ab z&=8fC06|NGDongSpep)wJ!`USn>GV2Iw1t%H%p+|3utMwcv7KEs$R{E4Hk(Ov>2R% z3NV#~qRl=hLWsw_r^~gzYQs0$;L#(?#}(n`z%lC#Z8d%)*>zeg7<5*$3s!ecQdojX zSC!u^qb^Pjr@}d?On@1PG33ca1PdvY)Gnm-k31;@Z(lyHD<*>iG?>_58vFRpsSd?B zUR)CJc7zBG(lsJ{IIkE>s?KK%iuZ654Sud{T~(1R-pbZM&cgWvf}^kFy=2SD#%gTe zjmC9tYiw`o_TtA(0d;-`g18UqsK0|tP2RcDr}dpyYRbHMKdzu7SE zVE?b%rIr7Kyd3vPau$C?Qds&AdHIF^;rIWLm$+%7Ud!vwqe^G(=8pvsc~7X3b_Ny& zyiRqK6Rfa>o0CczuN~3^18t9P%tk~UEyo6U!q~ss|A)N1b%J9`yA_AB#a#fX$Xyf@ z+o28X?tRwl!%uwZ9DQ7po*qkVB7uB!p#MVkiF2N7*n0V2L02j+=mDC+7^zTW79rKF;SO( zW%AfXou8c{Ps%go$sqs`x6D!6HBsZ>@`5RG5!uc%w?$ZkWZpxsObv!SDZr2?zdFYI zl$kt9%DXLc92pssAc#t53GG=YYhhOssEIVcL+(O`h!X9!~v83tyswA?uR zK+kgVO0o}(qzF$;G_q_J$|Qf~WP(0&y$$Cu;yiJNo}&vW=;KQ{$rmq_>$%>&nm*$5L>KKeLUkl!l%tq*%M~nMwKf>gk{&1s_9e7NMIuS_;*O-V; zhlx0GF`{p(D$C5%3Di)0ToZuE@qfs4lR!g zdv)!ln2h7eo@NGldF_>y2IfQ~4W?2rY#{y3$tbAyib+PRz~?UY(cp*I@}TGO{~e=L z2i9N*|F0P3|0YpxGbGA`-Cc%7dH8#qzPrA=yZih1Z~FftQ7-Lm|2W*-q;D@UB+AXr z&5ex>`mZ?#LwWdf=06PO;r9jldhg-lB7K=kUwF$fDE~V^xwyEvu(0rtK{+?~^?w?a zvkml_9Qybuee&7=M}U$(m^D7sKR7t}@#9B&PtRdXBZHniWYCj6&h&OGdh-=}qt?Il zq$K_A8G8AN|4vVKcXxMocDA>-|DWi|%m2`m#l`gEOaIc7ApJFlo{ylvg3(_>=r4h- z0+G6s6b3z6TwKhcC;z8AnU|MG&&r~wq|g%|zoukUC=_~lI6W|s?&m}I@|q0@V0e`O z(I?Z=(*8R=85b898ym}TC!?aG{zFfOhK3UVS9;Rl-~WHtCtY0Vx9#YbW^@x1y1IIw z?JZYV*Z-qFdHwqJt5>g@n3xzD85tTH>g((4=;&x`Yins~X=-X}XlSUZsi~@}5(ork zWo7!Mi}Z71bYWq-06+aGFZ~E79R%qt7&-#MU``HsxL=Bk|ASCozI^fGMR|F7Sy@?W zY3cvJ45cs}&d<-!$H#Z<*fCySULGDEZfT027cg4%z|H3Hcy;rBZH)kJl5nA{E4pkNmzR*rOW7YHa z^>DuN3*F4s*HgsTrj^b!J@3TYn9S}{dGy{FPgXh(7h3hcFPW8*NWT`N^_)@GNOdE$*MmI^|0%jY{2g!QuYYbw6=rbxMb?yIR>`bbfW5iqFrv1gND z>FQIhc(*oQX3xMV>)wB#s`g&{FO1T#zWUdk4WAytQ7aqMCS%K&ZP-w|y*5$l^5xdC z$Ua_r#XdbqZytR7E1)-9EBmJ6-<`!TU+$m(B7U&v^K;&)xAwkBctkzJk*12s{hK0;k5GW{fFh?+1>r!HF)0bhngDg0#D)<{tEcRbj`FWsu-$fC`G zq7(7+kL4Hr*&fSw_~huH&Nay}) zW?n#vg4X6IqoRL(#QA6CIWREF!jZglzjP9y96qZn`IN{rs|6hX#*xUpSA`6W(%1P+ zVa^%4#Hm~vUfraUs-d)^TyZC7C%u%zGwWqCOm$D*z^d_W6@9X6>y-nVb?e|w7QyfD zChit}e>QI|_eZGU)C&9_$zj6*BDy+7(`y5{!j@Y6-AOeKqAg-l|ml%GvN zRL`3x$_+{=_%XueYYPj9({SxC-v#$J&YSv!ZKs?HiQt*C+f-EHk!`Oo1pisF+W9Bx z7ka+FFV0Qp@(B0plOA^+=tD%0r0H;^w8SY?lu;92aiB~{o%mxi7gUd+BuOo-TIXbv z#ERhMAGklpY>!!TgnO$fGs$oQ`LVE$BOj%uq+e(-h_N9d(IDd~EkZMjS|j{<8rneF~Jji;B2J3*aJzF$rilGn*%bvSrLN$#pd&@0Nw( zSp=bsFc7(`FPsQoBv) z=r6Liz8!nI7qiHvU(q@v;W8BY(3{gj(To*(-oUPQ@rS=+Y*=3KbZU28Nc$D*sQ=>V zcvpvP?XSn4u`l>~{mEQC11{!uF9gcr4czT0px|mI!8Ezy`+Xc~?wIu>P7ACXW%zDe8 z%3dP*@(;5=;mC6^qLF10C333IP8MLi-wR$ya%#DAAu051_@qG9(@rPztC|BbLrEHGuaMA||fgLtylIkOdAWI zlezhbbFo>+5Oz^RzJHO$q1Yg!Opn0l+cTWCx0O$rae_{tuG>Y2`)=(caqxSO9{3RO zHS$cr-PsHh4a$M=iqwH`u#j~}nCU5`%S_~iFX%UUE=N!6INW=uSorj%=Qs2wAJc2n zRx$r(iU!8rc{~HL{f78$#TY4c@dXrk4V-FIK-i&OS;CK00tDVe!T6pY;p1fh@y^TD zIAxYRj$1RCP=83gDPD+)ao5&tiEF5`bTsezW)~!u07TRI&fEL?xX8@+Ocm6>6MF1@ z?Bcl2^w)}{f)i3_?J&RMNYn0k_J%Me;y~Eyj?J4fD+q9jp(irm1}w|eWkzyfqhqY9^BFxlg!_&U*y(TBol22{i{z6MRh`y%>wD>5p(!_xl|d z;$tgl&aZvbyQ9~_(szEhpY`%m zhw@#1k|T6f+E@k8F=a_oNN!;ms&cCo*g5rF7DSDjBFitBo&sl=c>%7(H*l z?QZ>H-R@kvNTsGuiQk3qjlL7_+F;%(DlHH>_>1E&Qo0H*RxI*#)J`rRPFKcn*ShHa z9lP}UJwf)nlcaV3=VK&QzD6v{i~dmfo9|rBumLTC#ZqukDZ1XP!t>$grHM1Ve!3@= zeuaoFz`clSl6&Rw5H(9-h~MXCjNwLTET15nj_hvn7@}E@TTI>WeXqq#h>$1bOt8{+ z3+EngJV~x!Lg@U_x{<}>|8eRYu2YWuEI85jO%87M6{=l|ePao;y3OO&%aaQ6Y^GejKd+CMH=1bmhX#v==AH~?x?Fz`aC0qMDFQNK5KIpo0y zW%Rnt6;mVB0^}UPz337WU?XL9=Swn~J}e9ntFkAzE<3C&WPh0&ud<**CC|3j#QRLs zZ!xa&4^{>nLjX?-)(r_jBv=lp@UG+#&N=_w%HZ{US4Akta59@`C38uR!`3yOlS5W?mCh{!;K|FUzTCFC0Jh?3qsit{UC0+41INj>76I*rUdpO z0raI{cWkh?Z9Exw^00JN_}EE?c?EfD8vWcqIwd9g>4ahU^=o5(rbyq2+w<3qMXq0a zCINU}M@V9m@L&p!1zR3EA?yFvG=_r&TnCY@q9DcQt}~g~6Lsa%6Q(Z&?AT3sg$+Uh zKuqH?P!jw%0j)U8G)YB61<}b=CIu?$uMGofWZIiWsd}P!Jsr`_#JH3zj|=YpL;~Cc zI2up~DiLs(gM1WHn_1?8z#6(U@9MP`7A5&eq#2Y;kR8l3`dByd^Z(y3^mWimMqlG1rGrQ0kd zQ1r5Iqytx%{S)+U0CWty;kalD3ftiFmNS>HKl_~gEc0R(w%pe%0mdZAaxeh@j*fLj zWm~EIbH+gSUlFq6E2N)_`SJX$0fzu=j%kC4f+r@&wkOLtWneyqVbA3D{>i-9oNC7% zJm(aHGx5J_48Yl*+efE)Yl#RL!*83z2M3s=5YUe_3|9j9T!K|}lWBwC1cxNS=2)cv zsLD>}DOcqK<8eMW0?z(UxOp`3g_%q`;W>Q?B^Zj7vdqiEAP;;Lv&MC&`UUzEP683WI z3fW#f2WqNgRwr@mD@CuPMKm=om#V;^gBS)4`LT>#Gk>&6;>naJZk$k}w^taqn@1bx zxVCpM>-96!9`J}6QieAm%eV&4k4S1-<*+v}kDV@{oX5k za6n(&34hrBos+k9t-d4Iru1`#Gf?s?0z z7K&v9OhBXwHJVBAVO~|G;8f*C;X^|DyP(>tE|^qz#ko+ib0c==!WbCk+S!P;bDyf- zI|Y=w_JZ=BSt}2~c5ZiHmv@^zRXeLy)e%=RF1#<4i>|KV7l!abtQE#oDSXR;6doMf_lnBDhyslZiV+k;*t*etBuDj(} zDe@0eS&g>MayPC)3O?*i@J^*q)vqqs4D`AVxjX~bstsZqN@BocRNpgcpm9{qoE}H@ zn%qZ=#v|U1!nzIDb#v)!scm9R??md}TGTP7qe_4MPZc$-j#DqDRMDBKko~$Nt_{eX zhPx>s(uSp=qv*Yu3#Oh3u2biW>y_%?Lns~=wIFE#mrG@n7HeUz4_hc|J>Sv9#@)iF)7*HhjVcCy>Mg)P7;i>M zUH$gC1){N~=M{zK!+>_v>DKR;!Ba<@m~$ZA12{>r1Krnl+p=TDw?i_Z^Lj?d@LCI@ zuhhe$4I^mXLVWg>9`H`2xN~u=OY&2jXn9+RYqRTgi|M7BI}>2`04|%-wR5>8C#flp zMLvP=&FbIQlrn}(qD-N=3?cCRsXb}UKNP|y< zx6FGL*6VAEd#n3;*H3ltCpVfY^pz@fwMJ&K{wnv4ZS6yT=nrhM68f;a)Vb`?PO9(V z?tA71*0JVP_9*l};Olqq=uA4>aSz$GT=ek(10c)Fz1G0)BL813q{i5$5BeX?j}@Jt zWnMSNjS-o?-1$dOtS3aEy_zt+AFsOh|2f-Lc-hsJ2*F9Vb}X_zRp{_R_A?)RU{8e3 zQkcytFgtqLHGqctNknKHV?N_^k6KkyGx}H0jzsE~8LxpvV%xX%4~El25}KFNz+@&# zU}+Ww6@=~(ktn}`WBen3`v!y7FI0Dxv)S4Om5s#I*BH)N=Otk?LCh*1tH}&prr~rb z@!8s7Fd8~NulO-srEP2c^n!lq2bFNE32vVWGIrwV+X=k7>X8}*4^@TN(^-zH|LFU~ zp!7$V4;Fd$xE&(;1`)MAYi3Eq74TqEuY;F4b-cGemGMtiC{De#ntC5JRehl0U3S%* zq8UDb>meX(6sK*jX)WwmW`3~F3&Y8ZfG>fV{LD{9CF79`<8hgU)Swxbr!${Q2-EbL znbwhs*$)%*nG@_=5En`eex#d1)BkdABE4a#dnP#eD69BsFxrOI$8FrdVYJg~V0^j< z+TT*S0eI*!@$jadUCnjm@1ZyJZhoH(-ebOk1u|`}UUM4_PaQqX>=C&20WR=$A-CI- zh0W*h%Ttd(@_rb_d>CR=>IqI``h!O+CLlKlGUI1i?;6A34h-|Neih?eC_MYM>H^Yg zrJqf*>G%4e*x{_ikFV#m>dKuFV>Y-+iE(Bp^s)`E-uR}$;oRx7ePar)=Bl&XK*V8h^pDkIrFC(YuXUPL%;{_I_t#L0%k=^c z=*OLH0*er(#W8UXL7+G1)q?H8QsLpcLBr~Z;iBr{s=6Wv%Glck59GXGoGD$yt*_5E zHVyXQ91iYY_`JIJgZ)8p&Y4$`pu-=%ajTpC)D3~=#o!-*vS?&Ojzu(56mUHA9C47) zmDSky)sl81fQHsySz;N39$)|4$j%2e!3Lc?EZ?UG8sPl{8 zSlK808se-KrW^mH;f60549jNzNjd*b^LRJQ@ju?@cd~!7i5i#562YI}+HKDMU4LF> z@_n)7=U&>EKliNv?kfG|g{UzTl^_*RE2CE_>Pd(p7d_T?v`IKw$3D&bWZM{OGf3r3EJO74W?!h)``So9n62J~f z<5P@t3W7=hVwAZm;S7wj4Fz;43*r@YwaFhRsaHN;$Wl+e@=fE`YyDQK2QVV_dwr-E)i+*k^w@oZmXYSlP{h;>xDj}Dx z_2to&u4&Wv_N4a_$8P?xtiA8o=w|W0#I%knamS!*yws*P{DGY*$5OXOD|~qC7#Dus zy5`~WMmyQEVQp&W^{?A}=39dAWxxNBcdp@fdbCgAtYU~{6njiT6=$8)c<@5UFNnQR#Di7AH z_lQr=r0}}zR0tM|vkfU50au=WdX?p+%VtZF$cRQ}8gTKT(0A7bm)Jtr2RZ~?y2_So z_hlE#TCpQ^aFG6 zd|B^@S97uK-gaj=jzeE&8{MdrdKdEO=w>c!HF`ezkj`E)FMyDYzKfSy{RI%!KRqDe z4c@Y$xGWG47dg+{GD}}G(K=G7pWSa+{;~FJTl8qUWeIvLoVnVKdB*PAeG2T+N)%dY zE(|kjY_r*5S|3Ha19C=Z(Ay)vK3{6Buc$!g|kc_2Qr$P5fR`?yM z@tWH&qi0g5uj^W+XOP3NTkG(h9FaZAMWVIWe$q6FR(2O^kK@;l@RVTFjt$x{o@Kgw z*bO6E8S^@#;s9#C9f?y%OAxI9wH5Yc(!6-*-Uoj1*@lH6?Bc}j;EP|H9o^9p@?Qyp zB4bJ`$fuK@?!3nL?r0;?q_`l~qn7Wz;Q~SQ#mS$nF_K)`_JZ;|JV3&c!iD4I?Mh~M zDnD{1eajrUpR{~TBTVjA`px^7MOY`uFATFsMTjZEX*>_zUr!*C;zG7m_Kyc|nE(JT zW3JsM6yccz6+G-#HFsvJ;IeS5*_O>oRJ_3JHf;3M*ew$kRq6iA^1KPH#YQV>Ck9Lr zVm-Y-W8n)togF7pA+irGagPX%WJmKA_Hc*ba=egUhg0CtBZ+2CzyNu#W0-tROEK_Q zH(cg?a#YmR&b1&9g9D$*(+3fm$A<%LksW{0Xes#NH#zKB41TdSh!-;IN9C8vc)qKiGjD7lQ;@QTaC zFF;gdPlnN*&b^k24ow(o>ns1ZKO*wz7UiC{Bi?tSL$Oq_?dP*MVMgIX7E1m}U?X$H z>3X}hS-Hw{LlUAQi~|ez@N&`Xy*w?Oc4e+S?RD~rk3GU)+@F@OmT}GxH{-PB9-iR7 zsX<}(B8CE8JZu!STZs2-J3dJU>TMjc@0@~Jh zR7`y1XQHg_!s+Y0?bn7*B$l_lI3nrPsW)~(^qZ3!`t!>(C%0bk)K3Xp+^W$HefuP( zlOQJLQ_Ez4k;jY4M){iq5{ z(*jZ~$G%A^&A^w{{=q0ionD+4T*l;F9C8YE2!|vbKNy-6{esF3V!1D(d3ld7q<`cU z^zSKM)mp=pCuMmjzn|s`sBPiu*$_NRV>Y$p8hO6H_4Hzc)3tQiXsrA@zY|ucZjj75 zBpyk|<0jRV!v#}crd=r%f4yQhn)d!}n$D}W;nf=W?`G}NaA(qGs!ghqW#p~y2fm-$U zRm(iCm-;@#^%u23d&3H@h?;QB0iv8t6z$Bx@pIaiX!`r3WC1pm8L*|Vwq4< zxV?pt@Z>kg0l<9x(^yr<{nGm-E*MHPv<~507NO{B&dBMsY5G=#xw+nvo0@!gcc=2D z!MY>P0$TN274hovx}&lU&%lgtwVRcjmvTBn2jN(t(J+7dNi(Z9PncB897$n13_m#0 zrq=SRRgKd8g^uv2(wUSzL%FACky`#OM;bjN<)-IwQT}ZrN?wm%s9?Q3TlvoX@KoKJ z=ea-O-=!h&OO5h3d-YZo`SC@lKVRi<-p6!iUBB+3prt$leX=XmDfWm4t(e3e|V z$kl~#Zbxc_Rk1x2Ag>`mu+Gw-;QMoH{jVV8=L&g%S&n;*6%sy(Q!+Jwe6{NJ6o1py z>Bbhm-={jo{PA>9u*zPb(h-t=V7Mo8*{qU_XKAHoO+ z*~;Scmm7C`^TNS;LK^RW&bj@~GQQ1=|w1cmZrD zC1;W2B%pqBGKNr?PE9KyL{t-o*$L(LR1$?dzzKVW$Z~9$x-Zs*)Nek%-?Y?P#=EY> zUVkA}TU;JcuJ$L6t`)K52@5Wq;@oeZHg8UOqADWQB7CBSpA)s06ceO^V8>J6NjBT( zww&oJpyT zz-zB}T({Fy@##1w);U3e{V8v*^#q#c!ngxF&EVx8#ah*B+RqZSLh)UQ7?mJ+{6#X1 ze&a1hX&GtfNsLmL^uI=q5@)P8S|S84089q5)BjIrzybFew(lR zzL?I_=}y_V>U9a4r>J7JD6u;fVoI#Ga$jq@LQ{s1RO;ETr+rdX0&yxKjAc0nW~!JX zty^$gMeA*6#5LX9fr?qv?N=AtYY49&ro!^Ck;~3R=1%uy=DqP;5KUy!leg6zVxiY$a-{-k9M2BdLZ+_ zC%BQ@w84I#(I#i(s)Al+_(1+HvCZZK^jQorA!brW{b||%$<=TKZNPNj@Uyg9?Lu8w zU;AEP^j!Us$=ki1gvh>oDy%ccI1Qs_J7czzUcPMw4kkrTH_bKuM{g}*20nw;6rzVW z`RKOM-w|c@QIk*eCT}(efrXDNoL63W8l8;5*z!eUmIqFr8?2m+KirK6coXPQHu71T zpx*$~OE$8k|3Av2*{mRG7wS|U<$fxhC3WbOMyvAU&SUL_S)T#a_3k1nNy05gece!# zX=qe%WO0`5I0V46u?tDE1IvJ~F%upSH6tLy2Ot4dxIkH`bpnDkKzc9>7c_+j@xZXq z5ev?d_>7VK*pW;L2&2zMK*0&iVJB%}x-~;jQ;geFJ__H#K!M0$FyhXgF)OAVOOeMa zr#Ztf3TZ%qv%5%MkSw$tB>)gF{p%}A%_74m!d-aCH@le3OGep-jn4I5c|jzeL`8V4 zMFnq<2cJWjOu!_ro21zc!uT<<3JBhaYif$zF8o-#i#+t(CS0AiQMwGMj27-{1M*i# zsTl)o6EFMCNO{9?_DmL-K1_)b_$#@rT3`W>!*99v^ z8kwrA&!B}4fKRt$cxcQe>ZVcmuiO*l3A0TLH%lR%3U!}|3L1#K#(_GojSSjFI@rhn zvys|7s0+JM%-ZCjW9i9mlkoeEvrn~ONsx@Hi(~oVCyn1wDPbb0@X@uX+o*`#gAaM9 z;&ZQ>fg_4L{J zr|Vr)-+NNrD(oA`JpNtekt9!2$Sf3?fV=pQ`@0G4J^OO{_9Rp5=hYzNOl{a3d4v*inwRN0 zpbcwMK`0SyGC3cG-Ji{qCpz#m%{{Yy(QxbUH<11S0kBtgprHZsOoI5(8~#XcW0_zI z{CHWYC4hYIHfn%^(lruBcin717v3aH&&0|Dwh9W7=j=iUi1XNp5Berq_@TYQ>n{?{ z*;DLiB0fnf9^)GlEU&pL=@{wf7~h>kU? z8lqA1pH;f%L|BPR)n{!aNNNotTn|4g??fNduA9iav$oyG6PybkEON5gLmLzx3a2So(EVKKa# zklDp?$N!sumcBCExAwp}x2(<}!@j`h?MMN#*Un3b;m0Tm(x}A} zzC9XFfzCJ$(o@%?JGBw4l@5z{9^n-EtrwS!(Ra%N?8y|OgA5`}$uazvqHV#FLq{|~ z4E^)V-ihlGj}1;N$%%AV`_>P9+>d3+Kg%5accbNj$WtqS8_3~G^^I;lS=!TPjZRsf zM2DbhBCFF`__wT5ogS-?ttIGv6@>Sz)tG9?EyfFx>u!c;qP+j-vN1G;ZNaG6*<)-a z_{ZJi!=76A!kYI3$d0aH|7$NgP$D#DW0YM&N3@@~t7?CA83U_Ra60+!*Ty3M8T zq)y0t17h%cz};vO?K;t?lQE8=z0mK6edwr2$4hl+kzLo(EL(*<^aJe(aZj_}{?(d@ zJF%K*I)`!OzK&~jKezAx|D<7!H_a*>Z6Z%hC6p5Eec==+n4KO zKfKu6FMMkd6sr(kGpW^}#ekajlv@k^C@2k!kaJ7dUVG>3mWm>xJZK-rzIVl;st%&o zn^BtoDvNs6vza?T=^d}dibvEWrKGP)H4Lxk@BARyg!b;O{m?|C{KxDjJOz@`5AKD2 zDV~*-YLt^{cm)$6K#dw) zzjq$Fc;xAX{p2N*r_8gL7YnA|UxGp2lOq##djL9;RUZ3BqOx598; zHF;uHC$;NT9JlRzeR90F&A-UJ{!6=ZS>{ay%AXL?r$c6@z%|~uYX1B=mH8<;sD?zX zIzC^On6%@R?;E;SeH$O{oGpLZRPlC~uUm3;axm;M%#SP_{uYL~bn5qghu@FIYT|au z;hu8-Nmbe;GN;FhEX|#j6roh3$tf2V&zU5fbf zjz#`6!Jn9x6k=vXO{*eTv*_hr6u!@EOX_MwFzckT8e)G?5pl<+#;;oHiKXv_) zkOVThI0h9=e!%z-_mJ{Oqv{VKRS2yqz$~y?C${-zXw3=hEK*&(`PuvV1nkYJNNI_C z%XiS1sx}L)qouX$OvoP8?4MCbRBPc4jh=%!#%Z5Bmt0pa_mEe^R$P(_)oP(a?0s2KQCTUd0^x6kr{%MQ$i^N!&o^VM=YtR6m5rOM9~XP88>Xik$TTL`*WcryWS-WxKWn0A z5yWt2?hCHVG{H79yXci-$6rDnu}9@D!GGc4oe6-=ewg4BdzduVup%(!-klDf&b{wW zD_35Ah>%m?UgIsssm7j{%O!FkwfZB}q+|uhaAqI!n3Hwy=)7~*cyhA*-uKmKIa&$U zolib2FMVkW*6pcqTiZF;US`F0)^gxm(T(bxbE?x8iJ}rvs{{I{dNyV=qp)1~_FSbX zcA?8D&A3#*0G-sQ|NK<6ii!|Y)+@tPgiliQRJM!W{DRn^^i)0H<@>(CCcbOl0*m^$}Vr(jGq2IV_M<1(2D|gEAU~BTXy{S8dc;s}>=|LHB5!jRiHE>hsjY7j!*+U&k5mX!zL2nu9>bn3-2iX~ogk0(~5 z8Fg_%f}H8scPccGO@q(H2DAwVRT3gkEo@8mIDbZ`WYA+Rd6xxK8iF`arlJ$^y1b6j zs;a4OwXfN{tNJcDocpq1Cv@NBUd=c4fGzJ>wB*Kv3~Pv^r`qFeKq~2B?$#hY@OtVi z5_=H2W%-!_oNy!A?Y{YFGGBB;i|T3e_M$0!?*GNsUB5N`{_o>|jE#nEbi+oD?ygbN zDcv9nN_VQGTe?9~xUL#^i zs7YR|*!H&|V#EF&BFd8#f1)aq$jSPu04}faQHt!Z9TA-FUPhHZajBf-JOQcA4h?H< z!Tncvpjg6wCVHOd&+qyU(1eicsE(pdggRfnX0&BB76T=rhMkMqr;w?ojN;X2m2o&{ zl;sS|pp1B_siL|NEkuz>|Ge!j)+IWhK>nYBi#45f<}5{elIdp9VCz6h8t+W*txXq~~*hr}vAy#OitoOnr+C$9>c=?}C2+a)7?*9Vuffayqs5 z?}fM4Wu3qkgpkd6FvGG)@_$0o&SG_sRfs3QXk~yPL{Am#r6>Ls`-~BwHB@=sJDUIf zb;%C>U$ZyrwPJU|bRLgx6jbAsjQZYN*pk}JBfhy@_kV=jpfW~V5lL$ zkogUZ>c`CI(7hg0J=oHBeB@>{Ayvyxmpt|3*_LrM^Iah(PBhC(d#YVrtmZiN0IhYYk z-`tTB{Y1BtRc%ZavTqjjVo@0SmQ=HYfQ6W(3AQx0t4_k-*BhQ2{wr$QkV7KI_UH@y zpA}+ZJiF%ij+V=#Qr|+5F<&Pjuj%j##m^*R>S}OM)#Rpw6RguV&m=M{U+qqY%{V8p zUu0L>SR@JE94Geci3t^9CMEG`c9`3C)2(1Zjj%PC%6d-An^NBC6f$h}nt4rBy1t>P zJ{1+dO}$vl$=b|6Io_JH@LN#DJ<#nHwwah%nTJfj($J z4;inM=)#w39pAp(8$;WOtY%sMQ1z~F%OS}@^dE6I#pV!(oSb{#luUWIlJ*p%8Nn4{ zK7P44cxK@FwI*_9?S!WRzBkM$0AOx>KD>e*1Ge3`&8_mk6VSIF+KR<4#E1L^L#~I! zHXR?7rf!7|NpJ8ykgSSvJi5c72%rVz=C-J0xmj?TL|K9PpZiv=25E_a*t>Rp)JeAz zWF6a5y#=!^cL<1%FOC`8#do*`YoHz-Tt%Q4Zu!F{=Xd| ztDe_%YQ%o8C@^eMl21H`JPBvb)}^NRXF2bm>IMk#gV+#HDf7kS*b#}9`@IWM3FI{l z)EOjX%;eG^g{$f2lO7LnE~UTo^15nXkbSS9_f{%F>lp=-{LUthaFdT&7ur4 zr(Sxef}$)P6tF1k7Mj2H`bCoin<_ilr_TsFv50Vy!`TkW`6QEYQ>EHDj}Vr}NmoCd zq71KoBm1~LLHWRxQn`KQxmAd%z;k842Ky{1SNYj%Q=dD|(=2N?bl~@>N9`GMuIwe5 zKX|{*B|$!1#_L_&=?MpahV8J_X~{;sIWId)UuOY6)sI#EAUl>41%z?A@4O40 zu+N*lZ(Lr}@Dn|hz5h&R-pa>MII)ImZc|%|agLzjw)E1+i^;O~r{@_fv8@wy_X3nf z0)TaA#ZUZ-PKeZy5}~KZ+M!qT((`9=S2!&7`qZRIkI!yHT{smk>B+_@ZN8_DD>A2@ zXeDpx)uPw#LTj@3mrtzWQ%#>XIwz*+Ye1KzYTF!70W_IjM|wnBHLaPU4t>NiG<27s zhm;A!)#DEf%vC`;WlkvfnK~x*C^ZTD-Ps+c%~#mvVsM+$QrXSCOjH@-5lxOh8M~(6 zb*#J2dV#xk|Mlp~{p)YKxfnjY*4Vuk=Qb>BGWv@yTBr~N!+`KB4+sJj>j~iSXrT(Q zL2ispVKmf!cn-ioXTW?U!<@ULjGCH%?$W7TfjQ&K6E7y{depglW9WidwY3Tn_PWCz zgu8yW*LzMkOYF5BY})1Zn2+y?*6-_ zDaD2l#&We|65G}JlwC9sBMRJc#O)e9N@&6`b(z_5F0WXwD6m}3h_E=AmH>l9Ffau; z7E5DQ*JGIjbgVIe;EO8aX5-CI6)(=C)oRjy^u`0ocr&2t*3lLRfeV~{U00JWaWh)l z002Mrf-qghCJ4ttx;b?h%bKL^1dK?M zG`SRS-I22&p%RbCq1CO2RpC(C2rfAZO`Zxuo#H!&N9~Q2CTZP@jeVAc|;(= zJBF+Q7b|0xHbH=Oj608J6;ae!ooq;;HV_9qqG`6#h6ir6hKb*n$g= zf9GGiU08zCwP3BoL~;<5A*3nUxU-|CGyOA%i4ea;sc!WR3|8`LWEKVCDg`GB zW0ZDq_+BXcex#Zf0hYJIQ9TJsmhDNp+>nb*J&-X6r#2nFx)y5cJ4BGL{UT3D_Xq=BZM~;>qmq^*z-@ZvRJg zfGwj(gvg|J;jprahCt1T)JiN9facuI_kP2Pe{{0lbvJXKq49e6xT;=@q~3)9=Ye6~ zQ#aTczq>x6%$l5Cw0WhmQM2oNkpT4=DRm==o8Xk;(S{PmWgzsfh z?`w)Zs9t7>(HmP9j{Cr0GGI8WdPMN_B*8Z*T2OA39Kf(=8e1JT6eHlO5ChA0o;EP^KtWj6J-MAZ_#J&it@|3hMCIh-l6e- zVk z*~?p+6z`lVT^k1~38gKYe@5XEP!K?}#zA4M)jf(#0#p{&)FH#F)*hM%o->^X>V<$S z3N)i4fM9=+6NPRR5GpJ3E~zbgYDuTuj+pDyveqP!@c=0WMYGp~x#FnU*GJ))VO4G& z^|;Ye2~C?A4EzdADTUb<5&0t1`b9-#N4=G>BAQUM^{b=EH%FYv7@z?*@cDXAWH&)% zH==bnU*yZ>J<24Jy<(9c#Xt97h#Wi-`8pwT==$@=vdF>YAgxa%0*GyU2>@KaWH&651}Fi2luQ`}t)RKZ?z6q!`r}eajyg`&uDZvgQCez2Ogu zfqp}>5c6AYqFJx*`ENAyeCC`kgGBc6MZKw`A@;F*WEW?xVc%xQMJK7l#m)4{o6q7yA2|^5G~^Y#w?)VTg~B8fQJ43e4o9Z1ddw~ zb!gZb&z)`tur^~xhkSv!76L;%2BPD}sFIz&u$8iLZprC$MkPvFu8RxD2HK$lQ~_$H z+frI`YOI<8y3ue+A)DfzjtQDF!Ls$upnL6I4Z)o_-wV7>Kn3 zE%wbzizcwyJ6L@Y)F~hchzTAkd<0j-(>Vqk9i7R3zGsspDIY6ss;x=d9H>|>eY?EH zjN`k8jz-_jO5eNZU0+94OA(GA;~brEEo#JFp4?}*D1%+CG$HFYv?Lhe$1+aurOfWi zC_5iy+!u1|x3#TOziSs_DQkYu_{1l!12Gk-1pciH2Xf5SAc)TURuT^~SoB%F=WkZ# zhe8_Pj;NZCdi^u>{xI!bckHuUZ&DZJtOz;lj<(H{v6Y<*^OV+~68^L%yrCdlJ-n!7 zAWLlVa@zinWhd_-2;{&)1H zl+(m*^NSFS=$H!ipLk;{|Ajh3lXk*|GUh&PvO?Iwlx$AN^Lwx2Ls&-%j{-uci61)8 zIZVhU`i7;vWKH>J)mwZK`|Cn?1=r2>itt;e!=uFWCB%cMXAX%ue_ZN>i`2r@UV|ep zFK+4dYLLh)_m30Kj8S*{=ZMCMg1h$Pdof%awm;<5a+oCJYV+J7`Lc2OvQkbL$znQZ zkGSLk`zDcm`6mlsFdw8ImftRg<-lJ5E`iMz+r3Qr^4l&>yaN-Cxr3(s(wm_A_r7TG z1KB=xx;|07oxSK^Wem?$U8^WK#4ivDFIm-ub5Qr0K8<~ar$RAJPgi&!U(1?e+NIWJ zg!)WxP1pECU-??mI8(0Y%^xoP`Mi|1!y6JA%=W=;IhR%MW$QkK+QET%nt#o*W7d<= zHeiJ=TzDtfpB7ccQ1KpGW1QkWi^wPL5fd}BKrG?lT4&=BGCjN_5*w1R0m{T1zG%y#78yHDBWTpsRU$|a}Dd+O7 zj@!-4U&SWvU2lAen*NB3>n0mA%jj)pAKJDWS{8h9Px=vS^mUou4Numf7SR9xaeQOf z3&`)|b^L2N;>`>BmPOKMZ+)aR2pi`>vKM^E007i<`aEhuuZj zi-B5ONR8HDoa1GuU_7oUNPUKO$T*V%nx#G`IJtSxsjcK(?Aw|>G&&7Ky_oX7Y%+e`2ut+md)uWlPCE+gOS@xSuIDcX z_Ff3=gWUg?n^TbKB)dfxv|XslZB$n29U z)k24RBIC8^e*3T?bf2M-Gi(X}6;1k53$Z(O{yeH(E`KvUnWbjHi{fIVjxKyInBEVN zrX}?dP|f(D8wPTWUsRCv2)3>0RPRHoGXs28hW48pH5yb58ir$bFSN^Pa9i3Ogw!)$ z!}KoexbGZ{_gN3Mw%m$6NAqkIiDFJd3=Y&NmXp4ajz~pi4k130W%2VFGiM=SDfONB z$wdCDTQ7aq&H71`ZqHAPkM2vL_|@E~d5)*RW;5fZoLCtFYIuMYDt1JYPgzYp2MN3u znw~+IRY&)LNDR9h)$X61>Pj1O{x?HeNM^R-cDpSdE;n#CAgf5YWb}enn8ZYjA)egg z@P(Y;l9iL|;t;Fq-3Q5!()_VzrX}VF5V`Gkkdg5#t{2vhIbKcX)`S*$tKau8_{!ZI zgmstm@;@!CJo#_jGyNj!K8iElp4!GhaQ%0apYod*whgTh3!2St+6U==WpL^|E4$#oe^WHRozBuIrv8Qza{pFU=Mz3N`7A7Hg!$g}_3E@wdt`NTPz%l2c@ zzq^e4w>*E#^HsE{B=-p7Q>{NT;vDzx#z0ZE9K00)5%1+!l152C*Ye8w^e&XyJ!_wg z+u?{eL)|TjnBf1a5E~Ib$>wmyRi7BPft-SRA9N(79hM#{2yN$gMQyizY`JXcAm;pw z={|gOJZ%h`H<0#7iJNaniq#_PLsnbh_0kJGLkbMlB1qPu`ALQnVLloOF zGbE8eWTo1sj_M9d3VbWeyvY&L{(0c!r&57DN~XlDgqLsI`Oe**XRRNvlR6?S1zYhA zflngo0U-6U8@xX0afDc=VRse$Ef^5;63=um-9~=+!LBuPlwq!P+qy#lyZt>@sc5)(BnvSTX-$w($u$H z)d+@j#8l?FNeb2XcPqw~Oi#F7n>k6}&QAfyeExL=ASrxGlnfn9XR{I`)M^R>X4Gj2 zhPi;VDQ#7H&7>@(D`#NmtH+D*!ZurOElqh{Lj`WeFw=YPvy%yMzs{V++%oC5UW4MW zdF1OEqhzC+3|f4VD7zn#s01-aqh=H!2*)ZN;Y%#zZr{3;g8*T>8VK88k>g6q{5NyZ z$0PfN-Q=I?pZ8|6oPn8`!|vVlYL}wLtE*gYpZ@8EnMjzv*0Y|cCV6^HP7aTw`i`ar z=n)ypWW##d7;P#uKP-f7jEQ3BJA(K@c32vBT~nhqcNG;57CcKp0xrVvuOMMI?apb; z519>txeU`NsuGqhG|M^>kka?MN~lS|f@ZDv!h&29(Lw~X&9tN^9A>YB6HwV6Lm6my z^6jS*xnfL6_ods*l@E2ul19O=1R7m?Q4p$3zf?bb=)aDUn6dRJ?VeO{Gm>0T4KtUa zj0qOcPm84`t5|ANIjeGTV7&SnUnC02mXm@fF%};`2|05mC-3C}4%*Wr?e7Fcjqf?j z2PDygWKFH@hE)$x1W}7>2(=4s@BY0-?*Iv+Yn=pAxoL*878fwVsz5w?Z)tkOYk(nF z#D9F=>ddHy30JrmF&Oup{YpdM`C^iUi24aT?u1%Z{eqa18SV^%6=Dfxj-p{+ASr8L zm@>o7MPj&aF!BQ$Fp6dr&D@naEt)I6C*4-`*4wDd&vX4w46RfarYx)UVcM6ZQUX?M zWM@{^%;%{K2CM|sKh23X*6oaoNbpv7rDQ2cU<^qHV?3%xwzwL&M~szx>rPU>zE3M^ zy~tcE{?zx%&Rled;l539s^2}bfL&)C;`ewP`s^Rv_YpNuWTv0YDm8|0%!QH>H5JMi zbC86JT&)&%3NH)WIG+zsp1e*Zb1bV!p~TXDI|8ZYPTK>(R&QT^2m?QV$|Hba#WQ)A z#R$vjetOxx)e?$&Z)pF3g{orVjZBO{NJ?lJvPC$P2QZ?7PAQBs-(au!}AU$;b%d_XQQ+d)S!}$Y|9th|iDgdKKJK`2G3T7L0po;^tnNo+~X&yphDU;0VqA|7-$2!dZBT%!B7=={>8aL z0r_D=8h4}7?h7;7CJzW3DX-C1eG_RR!k(D+@8Qv=^1s3HlC$0~OedBfwFX&5&wIXW zo;;P+<&La6ZwGFPDZvzPX*gY&-VHhn5E*=*bbD}7(Bs_v$2ITh+RWQGH-ZkYC|Bf- ze|N?{z0}e6UVQ8;sd-hsHTuEmH)!_KO}nG-Lrd)$X%+i#DVFQA7dLYnJeMzHKf4O8 zbo_bcbY;VaYv9`&ZF~PqP-F-7pz3s@?K=?3ic#rug}UstgSmLpM|`62&U8$k1b zc3C*~n=nDjj*b}oPowA!F6h1Zd}|&1kz*!C?!bef1AHZtd2O^!kXgy$g8|PO8^LRh z)Y~D!qd+A523rT(5+wY}!-gju?K3X~;Mz$hUNd}@muie&z6Ukxx8=S9T7IBFV-mw7 z(z$7pCM{Ufmyh{=3eHE6mRW9eB}XTexP03Rtwa70?m8f5)9U+m?8rt4Be(vOV$KBD zu0bjd?W(oxPnu5ym^g5p)hJLsza>FXNZ5h?baS34lfbocg_5g-=G~t2#p@=>ZKA%Np%nDvGV;X=i8B7Uh?MM*r2c+dAx#rbl#gYo4Nk_p0;dY^;zE+F=e z!*Y}Jy*QWZEoQnoF6glrI)H~$0NS0!Z8{I->0ti~`{$9JDHJUiq0dXWgNnVy!w|r! z>CbnY6Vm>MDms8Y)(jOtcT^#fWu0v>f|27*;;)?J|FDS!>iJWrmOzFQeSKKn^tm4FZ8Ia{6r-|gs-)OR#FEaJ zTs^iJ2t8&0y>8A;Dv0R0l=3-REl*oZnu(>`me!d*iHj8~VsUpt^B1pyS{9cN&0m}h zfru(O-2#n@jkJn?-g%}4N94K9EevbYC_Q_gb?TCqa4Of+92>zH@&0N1reJ$jI_dHA zC7tJzK?shdJFl?PW=IJu2G>{tEeAgJ>ut(PzivJ6b4%SIm9BFO`wF>=ACAY;=5-d8 zjQa!-`rFcZKM#(@v}jGq^OflGV(2$vNgB+q^DY*7#-A)WZ;Umr>F{q|P%y+{uhxO` zw}X|iz28W^O##6IXJJ`IyFYrd^o5Hr1SrttDPWo*>7Wi7C#z5- z)LGZ~CDOxKB=S#yV!kiAv|n}poz@EWq&o~j1*GC1Jh-Z)Q;>QbA3|Y7vN|urKp!Gs z704Hay7F$)rBokReV}J}iT~vOT?L3Z;fI~@sQ%D^oPtL!(jmiUf#eX1u{{oKbi@1~ z!oLi>t$AGhBSEn*5x;*@D$zb({ov(L5Zp!Y@>s@1p<*csOhr^kP$%n)V^P=j_VZ#O zAWU;T9r^Gmqad#AxAi&0F&U$xZG~JjvR1)5;)7K@+ek#mpNAj>WG%t+HeMb^iWJ5vCS-dHw{aGPoaM44GZKY%P_ zbmb!a<)&Gv8!HP$bx2u-$JqQ$|MB5YIbpnWc)aayysJk-(tSj6G!2Ba9I~Al^}~h; z?VB`87nWA|x{yo2=07!&RSltuW#8uSQ?j|kv~8I(Y*1pZtUyuvF)TM@C0+2sVg?mY zqMp8j3SB38a1L~FnJK5_Qsxp-j+2e4?cL<~riX9^(Ps-~=FhwZ zSSZ_t+MiR*Y@;bj6!AZF9ZdZlZ2vltku#eIHdsZS^V!KM`Hq?}iF(2PlmaH# z5ZP^zd8J(3=JV&2!uQu|{h6y3JvP^HaSC^VrT zC0mtVc%Q#Gl$;f?Onq)o4mj(-@X$wCMn8Wv{3s~(WglZ~V5J-*QcRgOd$0$bjUc_L zq{>D=VIO9jsUYz{78@$LYA^}0qbav5D0^%slEbjm>oX44ex5a&Nq1PVfv-VNczp-t zEI~jmJ=;Mv!z1js6b6DQ79rNl=-2jDxRMBBeElBlEvZVmPR4ht11;pIW3jWylYfE{ z0k`=sXKweFB+9*=lvQ)XgJHv9R<>ITx3Q$##;-==zHCxR(2qMsO~@;k5}VHVYY(!- z5SpEF{N8%2uRMe-lL?d-f5sV1$d!Ye3RyONxbUjCYKv~P$Q59%l$*Kyz;PXWCl86* zd|w^|PGBLxm>AeGV&{}5?Bu;Gl~Eo5=`$Yk=D}M=4$DOq97$@gZpZwtMSuv}igP}d zl$5QO%_6BQnKwb~PhI#6L_Rr<0AiJLMq5jtAM$KFED)+M6>)+@8pzVTKl^6f<9A#w zU~^>|p_sxFKLTiu)M|8%wk%wMs^P#`#P&m^7wXaR}+7!uQ+gG-BwpGRMTHjUNr)ew}_nhJonbY@8>y9rm+JeazzZ z0<4|sPai(|(aRq9&}lh1m@}gC-R;j8w_$%NuMdMo_)HKprC5VQ_RHY%<=CN1&re8+ zN^*}15{YPzv5Jdc)j6%9fY5CZ%WX(I85s}*V4@+!GU$bhivMAhQ7cEz>PdKv(jIkO zHIYt56>vo&!8Mh|fYZuWBE={68KJkM`|F+*Fy=~mt|^gjb0n20MP6Q!O4Z{rO5bnm zHs+Oj`MTuA_9V@p*~@uW#*zcDTMM;xF9YIt&pjuTUHKD)Q|GwWqV+%Y1xKE>toH`} zSSw?(^0Mo2m*)QAUd5Lv?O%fk3$yguewq3~CZzed2xd~_kKT}%r0BP|rHYY5%|%Uj zTir{}Xm|^ca!H)IK0mXk|82F}P|ePjHRX8%m{~ql}@PeWQpFlUK${^5)4J z@xh**ZQdWo)7KRo4ptiqlvS=mkB@eyOa3T5MTJ$l$DZp4295>_F!nttpC0tMsr>i% zv(;6(zhD`$eFOx@p5z>(%Y<5txCxidB)taiy_i z=BV)Vb7q#GN$MC%eLe$K z!`a+Bte#AVGC*XVoQ|H2*b9ZESBchLTrm^p-t~r6A$u~MY@LO65oaJc}bMCEC zeDk`ZUT3#N7Ys7rniyXOaDE=I0NCJ|6VG&{Q2K z>CU3`!P(~lL-FK87pv8iH>PwAGPiUgY)2Acx%V^oPWrNmBsdlM|BSD&Ub9tVDzmF2#^ z{298eqPa+{m+y2v=4T2r@+;Q>3afl2fSX@YTTM>@Rf$*0y{sa{>6 za8q>gsY#~O6Pf;?lv1p~W^olA}=?z3F&@DCOGEw;EIV>7V^x{f*UBJ>7G!7Eh==_GbGiZj?JaOD&-0Z)egQ;Tx)m z?3xfR?ViOyz)F6Jh_Q#F4cX|x?)y+=e*_vKo1v5xHtS#^5vqI3{Qa}Uo zxtsD{*vjp=-YN5qgp?(&TC()y8NW{BB1+eL00^V_Nqj7jfxzNj_o|N9&3wTfDZT?N z|GTJL>7}}z?sL@J><4rZknyG?EkUSZSiad)2>71ZhnUy*w{DmJ&2`gc;-oSp#ML5L z>$g|}5I`4yP$Adbd%A??>NG~VRa@Qlsu?eu9O)p0mNuiLDVoOdW!;tX4)^p}dd%|K z7oMqFeBvdI!5HhQdFbD%H=Wen3%VPkr0~EG`xSm1p;Dt-A z&o?shL6I1hT{PTsk+b)1IKVIUJ%KgKxNq5EH>e|TmGSwq_u3~BlUPqGhO1a|$SOpN zmJ_A#zs~rxJyE&Y1^PH_jN8&L zNk46ys$6bd=-p9*9mN;2Hn|D@+To}MOQ(OWbg$^7xKSJC_R9gX#{2lC7QzTpN` zzhXiW+l1{HHMBE$0sq2V)bBD)ye(BlrGy`50)sXtl7>Dq>mikIBa zj+F@k)~+{>FCsrqZ(t%9bene}0Q(UB;^of&E?#i|yLpM-ZmA$t!yaYO0?w@Ih$No+ z$^iY&s2|Yqrni9`UhSz551x;ULfRZyOH4F z1i(=iaSV!+jhwU{V^I~{D){I_vUY=wzvJ)r_g&wP%J!d;a>oYMM;y|{5{dAdfjrtd z$?Y=7rSSvF1HT4;J%(MOiC$$Q8N$D&!dgBE;x=NqlqxgJl{DRdGT|?iImU3rs%Mn| z5Qb$MF!_guWfuKbUJ)2nCi z-ZQ~yU2e3JZV7&)jB&pjAs}=alP40x!O0P@=QC-=<9%+(O z=q{J=m@yo~nDnwLA^Wy(L_In@O!|mVt)DN!ZSuDNN+Ne$VtQiI@A1TH^TcB7I3O{B zK_@9MEcthSGKM?3bT=`!9+z_0BLsUlxf*5rZ1>g^RASjha1&$lE32fez@&CY(au7R z7h$Q*sH8FLwEL)(q53=66@xmDloGkrcZ}(Mg=uek9I~arxJ*JZZ2G6&^v@(uwop&D zb-;;e@Ry_~d-YF#Or?JfdvZXMaa{Q1Co1FIBjb}!#-I9(gTjn|yBWJH88}qtXU0sh zO@_@8EYwPqvzi zp7Kv5GYM&}G>HH(r%5*NYG!Cd0lb$sa<2foTJZR9K{S71gl=KHO%^8ro+suz|5})G zA(FXDlkqntU@o-~Rix=(v}09NkyWJ8QADa<^nAX^@3^SQzqsC}STMJExd&dtRNS#z zoYhq4xdRaDBnYJ6s{{Jyb-SYGM<$sdP|Nal7+=|9or;J;ZBR#v9 z<8`S>=isn?G&vdzj~9#ljiu|OmZOwc>N~jc{}tu970w}@bw7Bg@!vJDF4h-#+%US_SG0()|e_h zv(STEH$Jm}Q@P{}+i$M~un$^8;-xBU4fbomTeap7o&ktDyR~Ov(+73=56q|PWRB~+ z1nSN7>hXqR4^RUZ2fswa_OYY^q=4IlT95rYJ+gXlJzRsIExe$(LFb5U#{{;DB_TvM zx|2yi3$|@|Zc8}l^NZg1G@rKDghUeqc?pNIwZr297;=T+W|=n6k8-AwfPAj$s5aKH zgJ6c42%pp-t8AXxZ&p_$Dnvx_T>gK>ikne{(M|QwY*ocuzbe2v+sQ)!h#f#VhlS4y zw4lY?ipYQ_4Ec;eF!^z7U&PaFEc7lK91MqbDFE-W6gB{)-me)PP2zwCTbhu6$&7-i zk-vo3f-AwNSW@+Nl1ninso{1gc?Y$A2YqVC6dAzsv4ex9^NBMw91GTQCgOAR*{$`F zKJJ9Ebnq&4F_d)3PIs`AcLK9G@6Yr;Ux24WCcsjZ>uohTu zC)Y(2{QyD%zfS)CPT}e2l&Rek)=V`zyyyM z8re=5ok?Z`&;LkE&`)Oc2j2Xn@B4l71~j~LlMFZlrz2g@PxVd|LoB?>)^1psE#hdlkfg6^FoT(54DF+brou=8%RTR5CMeewxC|o#be<^Zvku zceDRn^2q>uc#zj5;7oj(Px%#2ev$eR3<@TWr1of@(7{glcufKDNqi3=!YW9+AV@zH z_ppx~$YY%<8h9OV057Ki=rbuj@H)x^(gM#;oHHRXI|(_SY*Lyky?T=*G~LbG57{F7 zI5GW*VoL1Go$GTa!v8^|PA1H+H>pYKH$=fU7?jN+_I1(zNGBER1XY1S8}g+Uh24ly`W!!s4d7CQoFJ(-E~;9 zDqfy6i2W-@1HeB>IxM^!aGGs?*Gdeu|Dme`paV<5CqL4=;si&2B#DM^?^crYCNgGv zzYk1!e>wA>&~#4i#q8~M;5mZwnfz*=!x}}_*f+to`0MxIlZkgQ#99@^2S>zUf5HW^ zs9rzv9yFYD6YPLld+>p@O$;tdxgtRc1g29zfB3O?@FOt$@fF+psKfdsC6Ijtdpt<+ zZ?@Bsa(T}CV^7P+fy0lN!1{Y znUV%CLpc4>@>}5#u@9-|(>InLemW@oL}0Xe+aB^mj1)q(^8W26jmE^ifzfqhU}KW5 z77bM}q3Wnuze`0~Q~_5~+E!Vom28J~Q&0(Ptb((~^p)U-25=7car=Q`N;LT*Vgf$5 ztv>t#+yPA%oA_)o@?94iqX^HLt>$dEZT>NK3J+UohmF02jk=RgA56cEqP}eew{(PC zLjl{HFZNI%0VBBA?vqpcW-XE0!||)t)34!|-=c{hrs+OhcK_a3`rRA~JWyGG2nC+{ zMUB6Ny%O8*Ie5`$@C|%Co%r-y)W)~5ue)P)cnWbZvH%D5R)i0x?cFmHA0qN<(+?=7 z1SnQ$!OmpgOzL5kz}jY@>m2A%tcftIxATTB&ktI$2JapEp{?ZpEV9q4q>p@fzlFt1 z&#_AL5oJFa6<(YKeGod3Ds`WkAa0?)!yl5c_k9ep4~g3d6tO6bP{?+BYL zs;LZUz8b-ITYnxnh8;m)wU-gxIAXy580pGi-=F>@>-c$S1poD<_U2Cwfez--8FQmZ zO$r09-W}a+5S-Qdr(w3q2AYxp*i85@q|h*T?QvtP=n+ zBAMg+Z`t?5_w9!dW94^8H2v}aTnT3$EVPK>&T>CNPazTD+qog^v%nLz}*y z9o&nR3u`fS0k$eg36IYK;M~mk+)|X5Efb=91WV6^g#IDbj zq45*_6Ql~RGlc43oA*Bc0Y{(PzCT}4x$sy06Z{!e+D<41Cz{7nzF)lnj{d0mKE<2u zP<`SbnWt%2go+rV&59XCIH{Ew*xrQv0P(ldw$n!uRsx5lIQO8`E^9L`!7jv2pD)`u z{&hM1>(?XyfF;y&CSS>f3tz;D%e~^Fx{~s{Y;d}2{&lJF^s3wUAApYGO^OkiiV-1+ zm9VB+eRVzNd-eGhyeQ&DgACFBEbay0^uHm|mwa0{qj-$+AZj(5s8k3br6ah|=5wJ6 zZm~76&oY@DFjS-6W9gdxqMeDcPi?)`bh_?z|&0zw$hb_k5%a>4CKxn=c+A@AML%q{SDCHJvg2( zhTHSR3)&6Q3TAt)T1dS)x!R@|!QjEl<>&pO7K9G_N6{MN>RTUsgdC`A?N?9k&J-$# zky*WGsU;?5${J<(Y32cl_&gicen*#?;iiqc;yir%vOG>U^d>DLXm5ekqAP?_5t(HE zbLDMzC7e_;@+-T=#vxO;2X4OB6y|$vTUmJT*V_5oHfvwdere0UckEYpG~y+F=Ikc# zgYa7jztyjFHn|5Go8XGWRawLZDb(uRERo%&ai;cxOTku-f!W+8;vuLpc2Qs! z#9@TNRIi9?Y7-ZrZfn}0=)p0zzV4pk>QhBC9BT-@HZ?#p} zm%LC%G*4k7dAwOTAz;{SN|JNWVO6Wru>J3pNxZ@J_sqDX3*xjm#2jy>&xwf#wfpW; z*qtYeH`z&#cc^UGqbfj{d~=kyC9@u_I+%k{NnH*Z-=%{uRCSfEVFMH{5}#%r>Q3IN zN|m|v;Cg;BnaW=Lvr<0S;%Pb_sLT(4AJ>1)mmKG&U!NHYIB#(%m;O{EuK6EEX?KQY zS5}#?VQz~TAr0G%lj;4&rF-?385ry#!g>N&qp4EeHOv1n$`5dw(D3${tk8^4JH(1p zf3+b%Gv;@qYW+0|7M^V~Y#dL>x9$hPD-*LgQpC8;C;tzlWX4c=ADQwMh)_44&1>Ei zAu5gZt3Pp(y7_-EH+yb5xH>Xwgo1rs`#WB_{y&UTIs5;ycAs5My=|MoH%UlB4@C$_ z?@b8OJ0bKYMUgH|iqb^{MCrXFO{DiKK|w(2y@?`72k9WvyMSi$zwi5*XV%QTm>07@ zz<#mUUh7)xI*;@Cg=HTMOX31fY79AJnNECRuTEAo0{>pfiu5zPaW~@&^{z5RS^wKG zd;+KdhySNxc#ZpW_2pe;bCl-Cf+y%-{8Oykv;`*^OIo z#50CFJ3HIk+gn>(o12^eSH=+cqYF1Pg}mKNN{AY7XUu0eZ{{Jv}@;+}+)Aj~sDkX1F`LI1IYn=E47J7~0v{ z+1S`Tc<{i|($d1h!ra{4)YR12*cfjZ8X6k@zZ!zhA1{r z*nb&@^*_hUjjF6Ze{A?~!*Gn<7TIxOox=&({EbH~|awNLy|RM8)ANq3H8&6 zKDa~LxL&@RAa}O4ny3WjD|Xt74oVjK054_<{7bJA?G;(fww`*|*!dsBuwp&k!sq9D zhIItrMy7qb^TunZ(u$2Nmk-h#Y?9x6Y5p-0H*Xw6tqJ z%$Pl<`M@Sk;&P`e;qhLxSh{R7-d9xq%C{U894(4W-)MvpJrI7lvOnYxU8?zOP&eNNCq^yXQYR z_7~0}H>z17FKr{q?#@K#Ei{cfE0Q#-d);ySy-t76Dy5ScUI)^G#$o3S3KE5qmTwEc zy|@!swb%43DY8mp1L>@Hwc8|Yf29Gv!>U4e!!3o=hPz^d@8( zc8f|0%nb?V)?vfyHzoh}OAPM1>g9nP0dxUmoK!SXaQIU^<^+VE%;o*Y{gv!t_b(3P z7lf0%8t9R|W#CUt%1-)>1M_MviA@2rLL$GV$dPg@Oz!8BYSOd{AXgXXBsfgpkLs!sQ2KRt@&sD{(OY3dWpIuat*IoP0DnW1tcb{oup?Sp-P5haY6?jl&1&5=mY&k46sbK?^I0jAc#VJLWwA5 zO9^HjOhVTZM3|MzP8YqU=@Vl3qKr|4e^v8K@yHW)AsP+PS_kgS%gf_DfQ(m>+G7|w ziU24WM;ZNClZ*z6z@WiiK0qn-iZqNa6BQ-uz@FsjG#+w4$pHP1x9z&()vG;~Ii7pO z9W$?wa!=!a>RU4;2Y{^eK%Xo0U}pOK%wh#?sr^d)!STUZTUr3st+>)T;kyK;1)R23 z=Efp}eOHPAeL#4Tl0>CED1>&x_V?^h)pWfzC>Jsssk!w{?AzT^53c)TKDOh=-;Un; z);zpJpsyPCZHx)rT*z_DiG}rK2`k@$v^52QO0yeP01}|%H;DJ%vc@V3^6Ba^sG(K_ zQu9=QsDu?zC`Z}XRHjht4UiXuR02^zFlRBskcI9*kJV+E0v@Zf5@|uto z0$xbi4Na;l#Ng2UGeZdB;B+K|-Y?UbxRhw@(;A;ZiK+B~51c(1Rk26d5UWX%MzCM8 zK${Ida>PdEkjagw1Vgp#pEUhL2|9Veo+l9iDR@fIBxp3+(}$=0p(eiCz!DnzffZuX zt#E=S*j6xMpVGDUX&kmma%sY^GUpz=Jc#qVwo4!;tX6_t4M6X%+{9Nd3#NJ?G|R!v zRnrjT@T6Gp3A>xI2snukL1Li&w+^?Rop7UfOKD=JTz6=nzxQs6YtyXDxR=ZmZm`Rz^MlJ^KBZkamw;3N+pH{hPbD zvofk2B9LhE-Xyo|Wz9RXtG~x6JnPXHf>eqWy(7N_A7|x|BvT(4(O)HX7B;}_Zar8sA-ciOqy^*swJ^LoLd$h4fp7F3b-1oz> zwqwfR!a<736(@_NW{5TdCS9xqy~63Mg{vCD?Wp7rlqICt5Sk_-ByvtFiYp|5(Ap}cGPXxP zB|qtfV(akL-ZS-U(z`(qUaXo5i*>$!k>uEJ0|r=o-V84u#ufb0V_J$pUOw`EZVja# zLq^eWEfa*!E8hSGtER}vjNLu|dD!toW35cVA@AGQh?O?E%|-=}4FOKju26_lNP$zt zxy+sF1IPmkErd!rhBe2!52sXUs}Uj=x(^`KIU>x+LV*F%t=}&WHrFd&`pkUB-7zi{5xw0nx)aP|{?BOT^-qI%oEeEjzWKB!A5)R0Jvr?eSbif4A zBmH|U$PkXLmwA+dd>0Y?$fulaevHA|AA7XDAv#?uI(=a}_5(Vj5Z!Mo2vCH>w zLCb`PNpMKP%bh7-FL>k!C$)wFr%P%)JQ&+{5!-=`>za-=kV5o~-&bnTCp*=r6gRjL zE(HV`K+$B%Z~*TgQli83(xc(i0qVX8qe&gUi|EZ*9w6qHbE0XR@33jdO+H4 zO+aKow2~zA06~FPLwuA(jDCIInG)NW86x0hxcG$NDk+J$If-;8iTrgE9rpf!hPpBr zLgnFIjgq^%>;Jfmc$jJiVfq7`NKp{4-xqIq5%|Ldaq|G`6$A!T0>qKgB{18v3?6)k zS>pE&@SSB)#W7qf2=dB<;wdY_A&N-;_r35bU9=KWta>buRFWYdg0R^X_B+Ysbs8~! zGNEUjVz{|Lsky>klc+Qk0Bdr+L2=*OH?Aa#;XG<+BficDafcO#*NDKuUi|8>w#s?# zohS_%fI-V7drA~v4j#}HGq$4;&#+`?9%S0EG$ZNPN1REw`a>4GW4oJPXKThizh~Z< zX1gVB(Xwt%vP_cWLEOYj$sO&cCY6zu0rEn?oW&8g>OKLlgW?@tr~dZ7NAHxzEw`d- zwNYXVblB2DfM4IO_EmiegW>D>r#N<=^c0`V_b3+v?}u z;-}Ix<;Y=d%L7gC=Sv^_X^Y~v6LUat=u?bj#>Y0LO#0b5K7!6Vh&3{WxGoy1l1ox)v-w)-JksyCqhjD$ z`k(&1Kd=2jl+mx85PBx0+ZzQoYT=xf`5an-WHE(8<%P!mg$X9bY9CXU%L$-tt_2=N z;=c=I%pAF9i!LQfZl&gS@)c8R6$|+nQ_s4vEv2BG5eHDX-fV`sL&@DsCq*;GZjJ)a zij)U3_-rixzb5SEML;}AuTT)j$~SF&MUO9iUHNUzVq847^E9N&hH>kDj2;L{EX5!y zi0QIeIwl{lW4^_bpIDQbSR;bysgZWl>@ww`iTn<`a`#7yec)mq=L%Lzugxt*hOf}Q z2t*K;qG%~A$PB>`kXPmt%AlYT8VHILu)JTnvQcH}w!*y`>Aa#!dUZtkap4@isxGF8 zZA|znA0Z?NQGlf=JuO@DLu9eOBsTD?@2>tFBY%$wc=|*#=vXpDwDwG^Heg&N{E5_! z?Gn#z&3E)Lo+O0Z2ah$GaODGfDt*Mv5>Z_e`FIc{p|O8@u~(>?Z+m=p6~czI+=(;MX0*pfR}fSFq** z(H{iVL!kWa^G8_ois|Ua`ni&73{1NTfjJ2C!^u>&Jw`ZKlbt4!QE8)New;%{a`H}f@j zHVn68>Kf@kA_%NWudK1bj|*Xf?VO~3#{O@iBEW_M~fH%~zK_TJUakXM}I>dUU&G=xBcQ#Ntb;*C!<63mKwfD2d==p7(l(|Giw# zyiTjJ)<@%e!dfFetV=!m0i8yIV*_=pZ$ku|pz_~*Kd7ufZ~J-E6hE)Q2NbBl z<5D`~vyaF0N3md+3$Nzt;z~>1^j~+ z49CxzlP!E|oj!G#F8ec`@?vU2mnyOkx@t0Cb=-KDbgEf* z(UWVzuw`-Q^N-e6Dw#M$&1!T0&Bf%o`Laig7fkI%@rxDlcp-6?l6;w=b2edt>MN{+ zs8fo*qX0UpM$Y_=xNWJLWY+A(+?3^y4yI3rmKjz8OEIfqJ^Bli;Y;jpE1Y}t9B%$B zZ&w5sfBbc&bd<;5d@FUby9#4o$;(--{j@4Ev#Rg5prNQjxVITCH0%9v^`^~oiSF_Zq2&Vd zZTjV(qy+@Kv>mUQB^u(tCt4Y0@2yAW{v>|CMJJSzp0Hy6lG13Q0ltK=<9I))yLCbH zD>7lVK3D$zOGK{x_O|6%E%Q99=cIG%wk*fAH#3B+kdwaAkyGJhv$VT@k ztM(s~&D@{_EJ%J(+K9T;P`I`JiX+=&)ZT~H3VitcbIoe+o8AFQ@Yo9yN{P^2&M!NC zFXbOB9$FtB{=|JgAfwnN#vzOo#;I|_vaZMB2|rP_s{^C+4DOUG3d?MHzdpXCoOx09 zgP&3YL;4~9aFgr=9k@!gza^Qtfo}V8^Kg@f66ODzK;glT>X&-Pz*8^w<5j(5jytC$ z6jWavylzmUnrFuzepxrJJ?qas)owo>UpV#qOUY73+0^!M z`aro+{dLEiC1lfJ}xl8 z4ff1S{n>2bGhnP+TS5=OTe_RXnz??_q+WyP8c`+BHA$^{d=FTn;+W)LLg)?GG*Y;9 z|6>^5vTO^Zr{;=^zkR>&g09U= zSkzpQ9xJhy^x)}Bq`mzhGvEC_U;1O!&w}v-&fPW@cS3c~DCe?Y*Bka%biO-+$dmMQIsdPMqQ~>06yq-cFw<)prGdvF%3#@ znG^s*YgaK8)@yHwj=HN)$v?UrALP}I#gl}RapK#Vn#jwR0A@EAv4G# z$l)i=+GR)NcRu6=82xxy{8)d(5(!AewmKkmEd!kiyuZta_yt--v~M-8d2x|bzpq2l zkli%WVR$3(3M(e6tVAqb$lKAIXFsjZLghe{QkAV7(wX*js}4$%*p}3n>xTQA^fn>z z$mWD4@aW$T-$R8ssPDfVzAninQmO>0)g&XKA~=uzTkU)IA2tjNQ<4~c79Gp}-XPxj z@y3*yk*zYhgv9hE zKQOqI-9w#|9!~FG*9cBkLzt1)DLov*yx){( z91(WM)yWSM#RhK`>%MJ|=Xda$i&5csMPadJ18k%y{CMc&{%Na|+;nmYQE zS$Qj*qy-Pxn;r8y3#YL5gd8Rng^4m|Hc^KG6=9NVydk^=I5^57kDGavf5t^Fnk&Z{ zaTxXb5klU6PBm>z=TU- zY^guR*i5D`^d2K8v@~gz2vmIL9Q7he8hAX3NX4h0Z&#Kv>%7$nV^)+|;ZBJix+nv6 znS%m+=G=K&&N?F|pE{epXcRx{3BKd{8SsCI0T;huuxByIf8HX3-?`!}dY;`}p6Y1w zY=L$9VSnpEPB%~c_4B86ap$##l8F~PVK~I!iv<=wnDmNLr&C_Yj3dR?x+0NY7~p5b>Gwrs*+*seiX)8qPf;InBtw1-q`a{&87L3sjW~tyBL>X zs9y?A91NyH-J_5&CQV0s_^R1{P^duqvyK+dh`ZG#nxEwShJp!nJD*k*t|saq^>*hcs93Y(3?Wm8-<+%foJ%lof&DWXXF$4>jGQaOMGSS z{%>EOa}FK`5LS0)TC)g-mGe+Apr5);6e;VJYtzoQMcgLKr{IeIb8tVCKYfCmL)B43 zQD!`MuwEWS=%B{*(I_{hIE+Uuj`vJNBj<>!OiVmVH~HhlJ-&Nfs2pPX&8=@Mnos>$ zCV-o39btS_eFOu(4-Fpp-z}C&t8o0BB3@x%;-lL^^D8P+&HX7dFeUaz* zi=OK4#{x(sL9c=u+ibLZ6}o=hT^$&2&pE{PDL|ABauA zm<|wAm#B_YXz;`*tFsSN zt^48b_~O=JF%zY>^IrFt$J!6Bwx`;03+^una(N+VB(GE7bPN%nar zJZ-VV_nP-BLcNm0x_}T$0ji z`W0G(@Y@?aJbp^zR>nE2^FK}Nn$?wGdKQ0S-1<==V^3&rw*o);HiGh#iob(ygb}_W~2U{}UnluzG>jlrtGfms;PM(FSc7G(4;7Z| zhh6)``mDKs47aCa6|@-?ejneyoNFPl=(wsPZQtgAYmjXj#h+3)pH(SRgepSTl;W{( zyLdZNP_3_!=vTbx6sgYSi#P-AcyM{viBbCpYQFQLQt(d4#9T++P{*d3!p4)1ekG&~ zwj=qX9iZvh$5b;_H!`-Mca1t;(s#AIQ8@dB?z*U8&s0va&fHp!6D*d=3cbbcqP+54 zSwE$7)J~~;pb|Ia2MCiA)sj>R#VJpNF>2J^A}uYqPdZstFq{FTWq=@Dqche+dT}@k zO+z#h`&PCG(>{(dsO;j%!cci*QZC{oq;9D|fFju*EfodQo=ysv9+3bQO}TC;=iATN zyfEpmXzhp>z$d+I6)i}wDow9JOQ+#{y_gur3PM7IVxx)a9P((k*{UR#Q(YoawXj#C zfJigkRd^7lq9_+f_Lcu_3T6bsANdomn;kb8+UM}8*CAEW@~+e)Z&`0nQiv}xAEMeN zm6QrgT)m}sr?^)}PT(e|`m$XQ{oSryZB>OZ<&mWFuSvZ_ydP}qNS}+LJ+AxT{px>V z-x}3Yfs5p93F;Zht0GO~PYg{Z{Ywy*c%YW-J@7D9!?0N6A>)9?ylU_WF-;UWzp~%7 z1^(F}Le^9xi>5QBzW0^NpeH02p@NQ>*UVwmD$-FYgaD7{EA3SJ`jrwl*))rFhRp06 zQcnieMb+I3hmw$k+4h5(13cv#K^52C>nW7)NwrfDS`y#-tHU(%=cQv$6f$;HpWY>o zzD#qU7{omR+I0HLi2E)4wVN!;YO>4TLPi=U1bXx~VgL}}W@jdZgH-;YymNbLg{bS(IFK4)`}UJLf^jKo1=J-XC}iU)0}p=H^F zxDK6Y`{=qrC%U)`a6?7pP`B1}vCvGt;+&Y=m-^_sd7fc=jlV=;l@PsDgx&!0>%pNY zMc>GQtSVi9-3{;0>uaNv*UGcmx2sur18%O-@K@VQ(c}fS)1MPrQ{+ zC%$}v=w4*^bz)hhf^>dm_fGKhTw3Uwf|!W-@?$%Mc30jeT!aR|BR$IrIrT?JXud{s z8kC6Y$7k!m6^ygy(1oeSkpKcnLETTJqdzN{<5)$gF?CHHQMb0h0tX;-U)aZIo_MJ#sTIfoDtu(Kv1-(xc4+^~>i&aa#gE4kJ?aXdAj z!JmoY`PsZEWu!dmj@;07@mJF9`lP7v`%MT=5t19c;jZ~GPhLXGrYONJ!e>q}%W29` z)=eth1MN>OSl0M+N z1tA#>aW99y*8t)7W|-k%wmTY6knMnhQE<_N$h@Y^xSs`nd`8ae{nX#f)9#L+L%!ou;U8>1^>+;f z(f^r@TKHD9A{hvlVm2iVJqYu_Mm}i@7r-K>^C@PrWSXWhEj)F25$2*#!i0_d4|Rx& zg5HjTX^GzTG>Opd2!E)3ma5!)_w!v>&BCNlXPj}iH=%;6-=kZNx}p<*ZzabzC0?VV zIJY8RZoyo)ghCHM-UE?=9#HMaIaAR&e6Mp0#mx{!lfLi9pR`P71U22%}&GKOs&{QFIqDAs~oxwjeA=aiV6i8?xkKWY)1heP_Wu-J^|!Gwx6DdP;y*8ai%Yv`t>t8c#F@-vKzPk{H?OVbxM7fqWJ;g?htNk6Ixt}f3=**`$Ldv z_0hs&Mv&6j>Tc zpN}?u_qt!IEu}VfiE$BU;E%Bl$2g&%)*DWrS}}e(@n&;17H@3u#9Y+whIjyo!1`wn z96-O{iuG~2_jxVLZB*8NW~N;1kiB*+ElFIo{%ZDpH56O3@d$UcUE5cSZ4)N-jp6G6 zlsJAto=DrHf+6OQ>k?|4)KIE7mc)4eipcr79*y3?(;(__5T zE3wn=503IvbA`c(YHc_Qo7!Obut;-!b)4%W^-@_VCjTD)7>0W-&f z8#*@P)A!8Zl^(CBpM3vmzWQ@_amVS*&0%se$$Ds>b3X$f_JSAcq_9fx!y(Qj%>N+L zyBuH0|2TSpdFF%L)rU9<)ze9t2QJj_YdEe8RZG(!%L!?m~moPDx(L_*{Z?GTkaV8P)T2bm z!?G=yTOTa$6mk=5ChMb_$+*uI7!7zdvT&~}M6S!jh)DDHWc!bq8c$Bsy|vSwlbV9j z$ng6u8OnuA7r6!=^>`UT#Iv<>2-A;z$_%A=<*{iznoan zWj}a!sMik{N7T#E6DlD=Rq{b>(_jO{Q(OH|W1LnZDba5o{S2i<8xIdt3ZJ6Nr*U}v zZwscW;j88W!I@=3y&B!0+~M$cJm!@oD45MgH+@NB4MvwUd@oe@z1!b!v6Y4diDx)H z%{Z#Qh;ToEdHVi#pN3j`tjLx5w!QJ~l)JdAU@h*!^^g^kNlQeG47;xrp_P6X@&!Jo zb5dqW1mg8k=kawrU&-x5d6Bw{w`fMZ#<-3QP1bxXJ&J#LH9RM15!kmPo!N{;1 zpa@y#=PCQ}N1J7@)QPA)N_Kkes#s*J_aQBNVdLt5#xpM7Q}Nq6fvigXgEx}Q8!0UB z1myp9z)>yb6(>e>dz9ED1rM|IB^*4PzfTlF1RZGiO`meuI}1NJ3g623yY=8jX$pbu zQe=P>*{51(^4~sj7r{S!`$hAfCZPzB(h={UMYEZ_wQUL>67!Bj`SqT|GmN08wf@%_ zgDka5?##$Q0RB=JKnOY=uy*}#hG8;WR3IxblJ$MxxZkv)ZT%xsq^}*xeIMkMR7xeDTKbp!)MaTVU5A3nW);vBJT8wcbC^uZEFn(~aoE=xAKP+DRy(o(9 zQBEeC$!N|!UBs}n?O}HxM7ln?n-g#d$>Ir_m5d9S8Y`fz-0<_gC8P?aUNDRIt=*kB zQ6-4~q?5Y0)DIr|o~V z1y|f~-?Z{+HuX^^g_=$+Rv%tnGNmB6IOY}Sldvqogq0612x$>27!JE?LKds_8g3iq z5-y`0Qw;0-JG}XnQzn4UKxZGc*&q`^WEgBa86DeTLK$W?SQLiV8nLrB_`Tf3f%d;% zO(c*bmgZFL+f9K39QmT;@)}t;iY$dUxVV6z{IWhXGMd5>oIx_w<#f@}LOgEdV3ZcH_9QQ|6yezmgV50c?%nqKbh=}& zKVTaG6iU^1RaG##yOR+i)SSf-klcJ`3#}a}=)H%=4f4%7WHX(gyeB~?FHvEOSa{|R zm5r^O_;p5Ol!F@B5=;s`49VY7G^EYSp+?`beM$%UXs~NC5tnBp2Jf$)4k$J_{W-P# z-Rz;71UOMbK1=?3wn8?z1BMsJkS%}6cqoD3X0-R8uUFRH3gzq8zQcE+!gf5-Epep5 z5id7;07#%sF>S^OPkEH|hKc6irSZ^X*TPPil0?i0M!Nd`w1=gv>SeAkUnadTIB1br zrlJ=bztt2**g@Ph0sX!4+O8x>5x2x9cXYczd{~W5T2XseXZ)`WI+#`W{``V&>~fg5 zcc0309vQ*7tY9M+vkF9smZpWL^Q*5+vlDi@IC`?rPWm?vb(jN=RA-LvNMG_O#pbKt zU|!O;rb5bp(fz{aI@iyPG(o@s4xVWeGU$eW-NB1E#MSi7&fcrG$m)FtAt@Uh@~-dz zIc0cylR6c$i(Cj9MzS;gpa$BME|jeksSp6i?+P}HxVY zcCx6i*7+cdGls3SQ-e@8ELQcO5{d}y3WFK41E{x-zqf?CrPvcgaCu0f(o&aTGQ4c- z)|h+zedlSumRiF*U&PQ326;zChq9+wlHAbU&B$~mBc{BKjUkNch&NKwf}lDys)&-X zLPZ>jxBV`Wy0*Rk{b&{86X&k!qAy0RG%WSk(pz!jvc zA3Mh2?+=6t5e{lZq>Uw@Od~Mx=Y+OCUKSA)IMv(p1;> zNN`B;udwO1Kz&;_4&Qz@^4p_cxkl-G#hV!D*MvZ8f)YhBJ$^x(B&~Axe6={v9}yiT z1~&CPifFacX%In-stt%zJV#kbzta|JlrMFoP`qw1$qATX&AGPcrR@4rR3mS9LfP~GlPbcbPu=$w70@%{?czU2BHR7wD?tmPwSnAWD;+KOwB?W z@hRP9K4U7PNb06CEN=+uZRAI@Pw_r%*$2vGO<0nrSOBOl=chYZj$+jZMeNJ{bhz;? zKG1{x^8%=N;$?c1mElB{>N2^f}dv zxqedBqJ_||<9k-D52b+Xka$RQx5SQT{H1g;%wA~*K*213G565mnqc8`(dxib0sW4( zx@ZE9Zn0hA23x*zpDNKXi@t|5OObx4kMD}UG?Gmu;(Vup*F|!R*}xqXj$gay zJBSbGe|D81$ksg|D5UM^8<$gJZK8?86rT6#-J(l-(-mXU12C&|gC$Z)*P~iiS&}SI zz8A+;D!q~_g4J1x*jBGZ4Ok=6&=lpETiXV&803efpeQARDDKRT+T)r*1pfe=?zvx! z5&66OqXvWkk^zwY%5oq<`ZLmFrK>xk9-D^wc|TDSESs>@BuEu>69CZ^A)q2r25~r7 zx^Cp6M4w1PaGWOx2mOX##O>6>hlbQ(WDrvMXSFIw*@KAwdDMC7Ei(HL9YvO{eIYMG zcKhrk?V+B*1fAO4&SlG&rI&AWoeP`Szq5`L>FRg0s))or-S0*g06k;}ySy?%U9MkT z9@W=a+>n2_MteIvlAIJlV#+JCOp@HMSo!GK_m%~>U~Np*)I<(xfIvBQzYfv7l3j-c z8%+^P+Fy>`EBXC8fI&j^zEYD;9~rL)x%u8p2_mJKW)-pS!uqrq)K=lpVA z#3t7_b%|suM!f57G_JRzf`J=rK)B5N4KBP&#+u8#Z3p3?37rmQ7zzN>_u!h3+}c{+ zOjY}d7tM^&)t>Q6*grB53*LT-I~>Z;rJ>Ydr)_NNA>nK}YofCUvPxQOj>ch+CyJQA zZ-F;EgscRpnPT&g-|L+4!}#?@*y5!FRtl`Pe;T!47OO?@0&FzqZ)ktNqIuc%ylqYG z4shPwU&OIi7cH6{Onv0h6ZP74y@;r2zpP!G{fClyczpy2)8We-rHn#^HWiqcZ(%-` z%r)O)Z5Fp~3ZH9yVg4yPB$KSOZ)t(qlcl>(RZ<^hW&`EC?&bl4h*P^HzJ^MrhVWCW z(4K_I)`tr1FrZ0;I6Ok-Q$smvdgwGl<-NNd#ltQhW^!I*bYDNnN8R>#5y2Gbv@U3yhdp2nnkiZ2(3*&YEfh&s zpaiQ99+t{DLAkdB@@I%)Vo; zT?<~0v3#`{vE*F%_ORfb>;X-L?Y6v)!L<^X2UuYzglbY1<`Ig#?t(M-Fim%ZE`}9H z05or>BK8$x35;OHvx=C&G>956`(BNb#ZCgpVzj3PhMYEx(*(n{vA~lxO2hDgZc-Hj zSzHo_Ky7;^K{>RBcJ9mJv^p5Yc|rkSP;hS{nl(fQfeV9GgSqguVt}&5#LEAq757k~ zvJ72jHtaR5ExOst%uE6Gf27@;ODp(PBHjvaKC_Rni((Kf3dv?{X+=6B}`x>`xfS{coWmOQ~II(2jBDE|X226T#<&;od4kw%67 z8a%`p2C<-q=l7t6>?FL&FjSf^t%C&w69g>K2kUc-G!Jetv-}+l{`(NB8M0~`V<)b> z%=<2!udq<)q*Jc0moz_=bf`FA2`n_BLZ}25un(pk=n~H-<-f-7CHLI8?iOa?GUVq{ z#(q&#E#Z*qQUuKJoyCawa49e2Qcn*Sx+@6DvE%`-*YQ}D=AN!}Ww@dehNE7|YNAtd zE!5?&hJr~vObRTV%7SJD$)tV;4`7%9C9Wk5`XD+KZjVOTD~qj*qt_p@J6NbpKUsQa0aimhg2=pM}a^1qb z8fd`~X^l-#4_G?BQ<2o<29g_a2@#{}5kS~^+H>z}Dp@S8cr!$K(!AC)c2W$(aHZ;+ zyE(iu(G+2vaP;q$AZA`p=BA5z=XcNC*D=_r2CLDU@d9fJNxR%AsBG+}oBkrlgc zSa*tc=&%lfc_6r8c1Bxvtx}H3Zbe4ZFxn{3lTIm<5E;`DDb5hi`fgFTEwz^#On0I4 z`MLMK*N%eiRif+-^7#zPosCn=(9=x$18a0HcP%CWbR1f=2`qaOLQB&_G60gx4&~=9 z(w_~Lyv|3fmCxN;dqstRc}Nr`g!u#noOE9K+GIS^V)JIKake#G`|&rY;?3KiNRar%zdT4z zdgV+s{Y3|bb(cKN5MLAq2{?;NskCqWsxVdsl%V%6Ds|$vsO?u&Sbu3XRcm(asPa~A zANK5>F76Lnb!6r3{sG^ot*&>=BzIC)w-3otgUB+5z~{k5#(H_TRR;Ec4M_C*af0*0 zdGF8!sb}%24pgi9y0+@o_?4EL7XP?x_;K}}5wnub2DpC31AM$n%+p{h)C!zNMXG~k zVp6b@9A**inw9?OZ(7I5_OD?Ew-I)?Wsnam7Xr)vrk zWwl@#Aja^b<<>%FClZ;bL(zDCP_WF1xKnXL3EcB`XH;l+^6l=T(4IsPVR10w+S~oV zLI;<7h%jQ76So6q;Um!g9)tT4NEo}KbUeCuq$Yf7xPM|Se8#+g>L7f+v3KUv0 zc&Eb25JsV2*dgy+M?ktk3>zN7@K1Cn-|E`Oi<~C_t$m0LYv<3>y=?{V9A;$(QWOCl zmVgBX;=zK1QD8|dSkZ$)Lmj1rBD{|!d~g67Ctw`tq_)Pw0#WctEIbiKlz}BG>tu`D z*ODqitE{dGanN65WIniWtc-~P4{9w5t`s1``5_A{HH)_&{%XSsU6={)(~3|@1`##s zQZsr|@f@Cq)IuSP)N)E^YKPQMglQc`&fG-kZi*Z`)Lp!F(vh=Q(d$w%w!c*4CF>zv z{f4z#8k3uLuH6ML6~ct8yT0A#M_hN03x%z6@7=8J83Ve(yn9on4+)geueElg&6Yn^ zI$2tm82{a2xKl=8Le97u;prQSJeW;B?JN{j;r2$8@uImeLPN8a@ggRzRH$fBHF4su zhrZHSufKWhM*a>GSe>)w{nVjsVm}$ z{zP7xlHR#Mf%4Wd*0%R-``?3(aD2 z`P;1?DmI_xUHUe{J9|ef_K~yD(GeP`V6JCXJo;0yX{J<()_GK7#s7{>eDCy7(aA|a zQuofQnzwKJ4*0=moZ^1z8$#ztQrb^zR8O=ZN0^by-?RL0D@W9frr)=@nQZo2v7}2W zHh82)?DWvx6&BLQ9-9w8wGj2z`PzWduWGOrpmoCiGVb1%zwV~L7Po@WpbH_Au$mzpvr35|TFp+#jBXzx*UrumG; zv_Hqk-I(PXylpFKUVnZr^2{nIM#L%0_jwU#@S`7XXDW_Ga{Gu)f1$0)9QW}>5~Zqu z=Y%g_A)dunyD^@kcN%%jAa;4r9^Yy3$4Qt^6I>7B`xf@)IXFWleecON34$BF=K4$} z)53*&ic*7G-kt?MyNFPfaIxzp3%w0&c|;52Rvol?Vq`B&p8NW5hTG6t+43C4$2&vg2^GuR06!Y*&&Ipf*6pei^;b7kp;b9qfoVS!z;rGTtheRsKsKLzl zU1ID}`psprYp`%Yb23j;S}41N$snr7JWDoj=|a*R>YFAYqpjhC5jz%DKNkDZ{QD^g zIBecvl-A9_e|$%@wPJS&R~|ge8}fx3Fa& z9~WH)RXwWjXSyx3@&34{27FY>;`XWt7d3ZcQt;pthWEi6uuRbt-zP@in6P|V+8!2{ z38weon#Ya4XxTRRt90;$6@i~Skv0yrJ}=KpbP4Bg&AV*9DcdI8Lto0KeBCMAv(?=9 zt+U<8;zYaiW&R z;OgKYi)`6cuODmZr;l=tBv)hO0gd-tD%Eem?WvWk?PT2o6vDctCX@>@?~d(T2wjJg zlDBGJT)!!OepeWpm7S4Q`>9K~M?YLWy04{i_`2}UjM~!)bc?;th8*C6W-$q-o9>cb z^RHHSs;j7*c>tM}d^;;3VVeYGoZyhQPYR9>?-^*nn85t8xc|z?>;-ya-4gWD_Zhf) zZfteVpzf#Es_e_@D~mPR-?k=qPzRFpRiZys0_ryZEa3k3vOrvh92CBme&Z9ca-Ka+Wpe_%25P<`=$ z!|#nM847qtX~GiAp(xDurm67hQ?Hjp*N5J{u&LJn`o=>u+@&&u#0vJ@e!|4LRlXH+uQ9B0W zHRSn2(2VaJS#Y*hP_t3YCO++v7D!l|A)b%4j8Lq> z6J%(#gZD%@i&nkM>2(( z{GY~8KV|h$Yw=s$b;Bdcla%UxE_@YMCW#2Sx@G)*|CF`yUnfUv>9EI4HV)EF`Y~W< zt7E%HlQ_*3j-lW{-GTz6!0Sa89|G3D2Ap&?Yn=z`x}+GMZ#%j4u{o8P>Ns=?P;#m~ zyjpA;!|YxqYJ0L#ka3QG2QLo?k z=T-+N+aZ^^RGMth_g?LKyuIW4qw(aEOWdQ3QM;cn`^MCf3LC_~8gJC*Z|paP-zeNA z7{9E09LAu(^lm7VzVOzRu7*MF`1QoVuOn(-UOfC@4?VxLq8Rkif5G+}siq)IP*2rz z-TdMw(a+RA%ejLl8A<}Q3u%$@u$ub{A$#%i2EmWPl1qP5OmA~n&r*7+nQfS6+!FXP zw@{tynO&3@>K2j{@h|gVXF_vo2+1B`$Me|q0icQPj@Pt2BEqgbX zQnUL~9l4Jc$(L-OM^()L;@_A)+J8SVq~m>pnq-iTu)+2$mMX+s^tt#KTX9Oz4G1lK3isGK-{WCSvAW&y&YJIFD$CUxK&JBmzFUN>MXTtq!z;L~^ zSBfle@h%_1Y2XzNRW2T=;YU8il86nT^=e9(2{=zLXg!rzQKdQ!$9mcsE{^*5lALwVA^HM9xDtWY-~{gxm4x>2 zR3W_VKcP659#BLGQi~&*MNgp49*w}`s}UF>4fTtp`Y;=Y8c(G=55`=3_e{;~7uF4H zbez!_51a33`EPaWU8q&DDi7pk9HHtDj}PZBWk1`9z2vfM;q36aW$OdRhB7)Ccaz zg2STHbh&`#l%22T+@Iv2fLqYpLK0O{$8%>rw}tPYPie%M!*Cjmo|qIQe4Swx4q+;u zruiZ$7p{XCQUyS^^;{M5FYV*}*%Ox5w2q!HT4cd8(pLGk${All`(#4xK@np89D5KV zcolP7T>F1j#*Z2@6r99v=4#7MDEn6f<_9`>6#V`-xIr!?d2>WyqTcv}Q|M#83~)T5nM6spGwLvdW0Fe(@Z061KX1ah z{7SfaS7dFDrzQ4M192*=x|H$4L#2`73T!jrblLVmr5|qWg`Zcx26Yq(QiU`B{r*Yf zP2h;}VH@e@4|meh!^Neh`<=r}pM04W`bCqc%BjV#Y(T}=+0TyyGDTRa_kke1&LE*_;j8WH}u5-s1o+zu#cD-iJ% zcNHA_19Jqg2v*aK>#ItDaxsj&c&zz-uKK)hA=9GAe^Qs2xGKV46K@pdtHGl>x6_8j zxIP_wok?vIk`lizw+O7TzdRmfu8jAu4@sF@eAZ>)8aXMJ8B=IfsU zf=uV?bR@Kw;%q8NP0UA%){TEkcsoXi1rHfVL0r8k-@-@9F=3`3-1i!w)@#sjsCds+ z^4}neWR0jn$w9yb^5)*@j1kc%?PkCV_q#qAz0^6A6#RPS{myM%Qp*K1+?^Ob$~X5B za$_V5lh%i=;2JtfpR9IS$%9hZW{x8^DBag&(T znIC$yX0|fBM%3b^FI>W1)1xRCnPzd`Ln)iEwxUbVv4UV4wrDN3fpj+82q+D8Ye!2Q z5}R4qKmJ_0`=|F{dyUb;1`mx!8hmvA^$?TotCgvAt=YX}uy?pyM51TEd3!Bw=O|Yq zhFjE(Ti2V<2$4;*niJugo8XG2&xpCT!u?={yim;{L+7<4}#wxg~-$Omg!mc)Z;WVa^IUE` zR?6@RTr_3^xXw#CkkfJ`@Wu3Wfh{QO?)oK64fGRk!Y@<))m!k3J|htsiuN-8OuqXyzb`gq3dG;l_Ka0_jR2`k{_4+E2{xC6$zD>^ zDB|tUIoW;#Hs+@{59Rv8%~h&;`?vZtGf@lhufKN$!FbyUlpysiJ4v2iGy5WX4k1pd zF&|)zHGQiw|4r;_hKAgl>KE+*F0Z5Gw*s;k97KE}f0|YHE^5u)5iY7$Ox0q{GSc}G zp|jK`ui)}SYvU+!T=*(3Fz-V&xsm0vgki@S=S7fmCvHs_ zd%gnh-WG~?K-+z{t#DR9=x=_nw&*ey*cxOx*0t2+rK`51bDuM>pR@ez$H~lS1NzEr zR$koWZ*>NysQ+%a|HM|8msfN7u;!^w>YnY&HTq4)+b%qEbrQENvaO7VtZHQiWZV07 zc;yj?2AUSQ$~hI`OA#z{N|rcIGffAc2WCv~E)2@G;vAf@XghWA1ku+~JzMMYrMnj% zTq_WwT-f2}!aBcXbXM*2MFEO zaL^UFV|2g6Snbd-n7L&SS~rgI1LbVV(o`)gmnCA3J(qy6*qLZLQs{ z>(zAG6KPI)hpu-X^9%xlZ||`7TbIh+Q$8}0%kd&N`M+F9I1gvGsq-^tzHfRY!O9Di zIa%93!%_iwDBS+;kvX;eEye@i`MVS$JaQBGhkFcu!WM1qHoedA&A6*Y-1;4#97>pidtQ2cY}V-&A-xU*3!|6hDp zTI2gX(=M0md5-IsVnt3lH)uI|)g?vmDCL(+D!E+d*2l3P z&Sqea1=`Y(@wxs3)D@lVzqYFd@&%p~na0Q-tsRy`NuZku=L+cCZGTe*!kH^X-;&jh z8)7bk6|`hO_i%LPGk49tv6=1Q`q*vrae@Y&7@3(QU`|SdKt#UiTJ@rl2J6UXvo-XB z64E@AMxwO)>kTZK@tYw~x%II-D7KvZ0l#_>@GKHJQ7(dF&kA0AmUqGz^<477jHqv8 z(I?^JubbSv*;r3?Mrhe(&~izrxTVT+4D)EDVRxggMiYetFkwHVMc`UaoJk4r$tVq8 za}ap})1X=m|NOq(RVml@OSy)dEC^p=L{)h$q4L2)Z2rp5uBajiC-&;S#WgIOSvi+r zP`5j;M-Mxo@rH`Bzth?9LrwC}smY&B9uy?GkVPrt+X?`pTKJ=9T{tw8pG}qxfVL5K+95&q8~!WEWD1mv3-5UCRg}4 zXxE9f_kNB~{+*asnVbumeBU#9KV^gPL003p z7-i-Y6+NKe$q5`P$p6}0M8n*ja;RiuW<+$^^UW%XjEBvGdPK(0-!n9?Yf*K zpWlpmz5*he-fZ-A^mylHjJ4!B3FXm#*f>A-eCo8H>f|SPXkWFds(>|k)0|Iy>x5&A z%tR6n*N?z;oB2&(aFqs?!|pfIlgk?gK^u2Zs!ntDxNuPO$j0aAe{iQ?yNh_1fBAc? zR*t^2UH{av`KjgU<&``ZZ|$fzW|16r%R3Os-O1p1&z3#*W?dz+#g@x^M-`+hCSw}elf-6lvoPR){x0>}nC^}qX`+Ox3OZFl^t#B5v&>l3*Rq2(=y}SUFU40owLW30Iq)Pua4B^scgYjg;uqRHs zd?=ZNIpP>r#y8ADB00p(E?|uzafHKgrS~Qfc107Um{Av9)s-lPhd;MB%`Z$5F2vIP zaGAZJpGiBJwYLX(dzqh#)Z-ie^wo5u4QD9L`)rp)59p2sJn>TFho|=zdH-%Pt;}=+ z84?^FS0_y=&DM?LiBl3wL=l)K!#xF_)j=4u%!7~KOz+F%1@eBJpohuw9^Zcl zeO+N#p!$Px-EP#Ab9|vX6*>*Ry56!fg>JK7@(VnYNc!;5W`#wc3KVXmp-BodgeeDV>wa0WULZi)A1o@Jq{_=5q}F`H#`D(?|fEv@_K?Oz?!4eEG8GX)Q8Yy^zg$3>9B1mg># zloT5^RmBM+x|J~kLP_c1Hk6cV(Q*uj5p;Q@vU~I7X62<{AHMtNam~63+RhTR1kaN| zfM_0v>?n&e$!3r0vUb(;>AD5aagS$!%eY0oz4)C~tg^S%Tl!01wnSYA680r}h)DVS z?gzJK>qM3pGLe!K;N8S(Ab>9A^0$vZ(a+vn)_M&f%c*`^uFfp{RKNM4)*O0mgogr3 z|0;3zg_Y$*)d(N8`$cVfwH}K>v6nQz{Uzw1{<4f?%%`D{l14{!T)T(EjBp^5&Bh|x zeu#|bzPRZ-p)|SeH)}>3-3=_5F}&DNPK?5Ncx0JirnN<4Bke(kf8gXW~nl$I;w!pNbp(4cW&i0 zUtZY2)8FpdRTY;g-KLKG60$#|sinL)nQGPgj`s`tYi=JO_qOX0tnu%Unzs|j`%D(i zp{LSMUZ(%h$QB+`{ptf1EO#s+i5^@1{;U>X`Q}kmJsSuGS3Y*t3YBW52BowrCJPxL zb%@z3WAbXG_qybuDWO|RuK~m>B{#)hieRrMCP}pjS&wmEe3zZhKUq1tvVs2c?m+4gIyBu{+HFK?sk6Itt1buXKH*3f>i~OJ)ZA znQh%p0=MHiAu&Q35x*_4hdfkCghWR!b^(#h>M_-Gx?FG%7ndz!+-Zg)PpPbO(oHtu z5n-B_V`1U;MTH4c-bMUkdx4Dch>>%`6O}d_YEelmVHiJO+U!RbMp?UF&&Oi9u9@Fd z67wd!QhZD9i&o!w{pUrLtUdQo%d%G8rVQcL@AUnUJDQyN#vWyFav#oKP?OwJ2%{uz z6;x@$c@8lN30Oa>U7K5cmB&*l7iG&14K}wF5^#wQepS5bt{Om{0v&}TcQ9c@Lceat zylJ-BP`Osn_Bp!H;B}R($5yOt0#hXyiidw{Sk=gDDi4sW`N*(k@^WjApvUNAkk z2eGj1o2_6o8&HjrPQQ9mSz&XAHDhLb*YtI+fPuo%`VEy8UDKULYL8JvULSDd%+n^- z9??tjY`QHX(Jenu-R&fmyW1Z)Hz>@arGG^%Xc*YHCcUV3`Y|?xe4XC*C@}4 z4WL5JraF|^h=?27AgKeDM%PEDi!ZjcI(&S8xI@@)zB{1>bMX-nCT z+|(b-ZplYIIxF)|4Su)&Am@3IFC2O2I7-t@zPr{)996GO_l45*$#Ub)l|l9f2yV)d zwy&=&7yZhtUp{2pV+YSHbbIsBe6Q@Q9g@Om8gQI~fOa~B#|PTQQ(aG7%jSQ?O0)Wn zwqxKal!)~jMS}xUOeq<6qY*v!Kb}8KLNu+#Y9_56ECrPHfyqa$t!OAw*GRmmHPMm7 zn*XL`iSp~#%-Z?&(Ts&si=|i^25@+BA1FZkb&K0=8pjs~d7}a$ZFwa(zFJ?&^Aho{ zmttrO7ar-O6@tsS^)=W_f6g0jvDwW#<#6sj9Mclg&~xzk{Y+)Y`c1MN=~wzN&4w%~ zaK_~EzM6Z(D9k10B|r?PuOyf#%d@?)6+Fm!m9S|^nLl&&LCXu95oJW|CgSa@mRj)! zr|(KZ*|jM}CDyjn7QV;w7hYGU4LC(nu^+!n`uNi)Z|Po$4%@;kQ$uzTrwTVj19CYr z@+f1%g*Euk?20PFd+qSMTkygRr!`bz3q&ifvi?zGHPRwSD)Um*m5)2j}hKMU}pC+`d%D$7ODx$kC${f>YhXlc7q7FW!HMN+ec`f&A|`*4U3a z-^MEMR&IrSYnEH3K5wOn@&dC_r30x^yQyrlcH2&p-S6L|9Jbe=L4Bndkh936&hbY- zou1*?#BfJF--~`e7(V?(LLNW=e0evD6#SVwHJ}%zx|ekQbcH?jkWK5d4^MTFbM@=A z`nzY?o7dq2(EU`+3j6&E$rqbfQ%`2=i%~vPu~OGirwikuhwbDo{QIe=AHRnl{YN)k zrVcx~Tiui?8r&D}3q5Yi$ZL_0PK~sLj zQp2V}-w9MWJhaUVDGCCATc*-WgZ)l}!}=)x?7}td5JzcHRBi}n;~M-rDijN)t!8Ai zig+>?zOjE_;4mC}>^Ja^oCT!a*+ss=QPPy+X*Tfl)1Z%7%9m1MRNk;d@~k+Xf+Pij zl|o5V5Fib{y$irf5g)wJEq2uKJ(_Al6#YmPkDyMXiPYYu`xYY-)-}<5R&I~=JR{yQ zT*WY&m!dVTqI7ek=KH9M0jc}B=r{ri30nbu$01NApprCN-w~>IJlbv-B?17eQ*gK` zVy*=}4FmI+#wCu}H9d}(osZ_MPMTz~;f7(dO3_g+adB~M

cAN(@yixz37!r$d*f zP-g^MSub=q?gA_vO2R?`FH{g7O|HRG?*)R*l7_5qj~w4Jn!m{-8YmS#0m#h zUt%vjshXU5#p0_Kl&A32il(3`B9%3PqRor;Zg>j3HRZ=~%AP{1?J(b9TxwWVs?A2y z-><1Mury)ewBd9P3Lh+@4b2^h{uRgePr;R#`A@->+_PK;y(UtZd!u9VNJ=j>3X2My z66**+ch)4r0!iqXxp4x4cP_Ac-0aNG?M%HDpK*g93;o5XevyCPfo$z%RZ4rxTx=YGONOn`yjwt{ z7C!2FSMHUn>{O<-OyNAk;neH^-$Gs~xM?onmAlrOd>aU|e~5ORqWMWgzQEpxspAiD zNO;_Ts;aKJxrWCDs|NijA)q z@+uS#As*Z271EYU{#})XVWd_Ri@)UIHvW{nec-VZd;J&d;|X{P2U|%#+=t;tX*L7l ztfmxxg8-r26 ztr}?)NURAY)u1-pt@bfnZDvqy!B}msNNo{SU1@$zo=9CKRb7P}sjhabHovZ}@k33` zR$XE~1<5X@g&!=?$JbR?-#u3UVypfoRYRXh!+=4goe?&hVik6$*qPrC-wZT zVSdu}Z(SSb6B^&wH7<@dE^Re_rfOOdX<9RA`r_8~Eum?%uIc+&(+{`CWso6gwduD( z^MPCQQ9|>dy5>`=phq7t)M;ecslJrzfreBIEVzauu?1G&LjApt_IpbsRV${Tj^41f z(ybL{2(gxmZE*smvEZq?dPANzfyH`$_cq~zdNLmKbvoT z=D+yNZP7nmnJesOXOt*cOhIRyXlL^G&Q$8IbkVL%!>(-iuAIcKy!x(!@vfrpT_x1d zOGTe&fA`$&DDvvW(=ITjqiJ{3knI4JW)B87LwT5{LZx$S5@S3;NWxv8DfMnwGMqWZ ziF=5Km>|C5P(8~KTGQugos49(Fu4`+4vYFiq-xSn1!r_?@w_0}^#CnY;0)^5r=C;w zo>X>-&p6a4DMT;=5O1OSB8BRj>Vbt*eIk>VCM4>s8E8=)+2jPn_sB0aQA@ipsnXu< z@4dUCFZbPF!qZ=#F20;HCHGO0FR6j0K)g~b@yBT|Y>#*l{1TAr`}_SRFcn5(#zU;| zoFR1FABnswFZmnL5IpsAB3jmq`ga<#aHXbQz%#~C4&ooL4vY=>}g-Cxz^Udq#-f(!xKVD`40KM^FUZy9_u+84c z6|vqkS;bYjmd$_pgKcRNZsJJ>D}4oLkEm^lPXhY$NuJjEi_P}$LT+fg_Xke}f|ztO}{ z(!^-e*y_iLFEo=IA?UO1!I<5Du*^qNs6_O{fX&3P5l-NtkFb1lbO1V5k6G*=EORJF zojD6fi<&MJGG;EBqTNkIhb_-|t_(u#kSXZVgXJtLo*4k|!#cuPT!?;hqaFczdvAp_ zS`TC+O=opIygCR}a31O=08raSy|D*2?a)-F6l5(EPS!HfltdbUtYuDE_wt6%-I$ys z^MDR7(9VzEiAeoJWj;EN1<-L)((|y^Ioq?j3$gP~9`F2IVgqVoLpEaZ3oqDB7XYt? z2aOAkw16cJDX~20G=(zHh41XfdeY8E70t!i&c}PqCN8}%X`F@IQ}ueGYc9umH>#>K z_i8-LgX=SsnapxH=Zre%d<6Ns@Pce)8YiQ#AplEOW>gE=$Q&B7|iEVm`=Hl6-J*!NgRzXOB9r=%r=?VZ>Y!K3%6QndL z@*@s|e61Y1!g{_6<5}0b^$A#}lHOQGORW4T54qEq+CFeZAL&V=?6 zcJSULZCxnZc^7qe8dDj%RolDOc)r!D`u!=_a+(+F1CH_r8OGd=Wv@-y4xk%M+3NiS zH2mCZk@zmJ|GfiA_MB6my8QsA(s@gN4BcY>RJ^^CLRIU9zLG?>!nIB^iFuKNCQ57% zcy29*Zhvmt7Bt$?{3< zKW2Kv^xSS{zi-ctXCo>F9h0(wY2H{b+NCw2o*~3>p?)R3Mt}Slr zDk-EA7W3dD%XC^v9qOZ}I^+zuj^;TPdAYQ7wp7!ZRh{}-=?#6m3GF^Drd{$kZ7K3V zsTaJvUfP_WegUboQz#Wh^dA$%%}?vLpD=T&=!FvW2Nduz6>Wq_ zjhVW%VTXPiM_Mf_Jb%}GNX8A>XwU#uHLV&(#%r& zkbZ$SMhw8oP%LM@3=t+BoKg_zp2jJi+k%MO=31IN7k{p^dOHrMVl-38W2er&+2Rzu z>an9`#)V43S1NDJZCNx}*J_9gOaY2|%=YgSHny`Y+nHgxBHzmEz#c_2uU{;LbMm!1 zQRG)H=45nHn6HfeC^)#y84j6Hq=T2;8c4Kx5g~4K;5A6u-V|Tq#(e)vZI1NN?nBCQ zC*bx##GR!N2kr|j^8yJh@$5R>XG3;bQadPsOFxSJA>p|ZmJcMRE_wc(eFU*`^28G<_Gp4&C|ro|hp(kKvyjASua$Fq zEf_Ge5&J~zQ#t^wXE`EYew$kSp$1U!qk$@gt{V05$B92Q(VP9{TxwCc$|5F?F)ggb zt~Wp2;HN(CVA2)uVQOZd1{~JX5^9$r{h)J|F({3I;k(jP6P{>0i>cLRvW+qw;*+_E z5L*+z>I>GBw*+4ouml5+0? z53QFI#wAv-g%F;2zJ+*u-yT*&S z*#f#6Jae2P!487`XoT534mA%@*@rZVRD~wGXdg7cN z_j6&W*nMpGm^;_;oED!+@k?vn*Ryof+-j^fmcuGQiq-krbJ3U?E!10VA~lo z?0D@b6u8%_Ey(KHPkl5Sd9}ZExWJH-0-x^v6ERFTe7lpPD0s-50-ofv#5nJ|y?5v9 z82Wml_b^XRp-;Hju#N9)cJs<2|2ug+Wg@w?v4y%fWFGAeQJ6jYH75Bc$d?VnAVRee^4b&RlVo_V^QSHKWkzZt`;9LKY*cRBf{g{;{N<9gwb{06>1 zBZdC`Js%c!etJX-11L@K5PmxlZ2%4`XcA8CWC!6q#=&(=BIqmZD8vKQY3`Urvaj30 zE+4C-V@#s>`0WwK0U8WdCefl!_SCk=8Z1L5F)|hQv>pMP9A8aHvC8ZAs7J?|SW444 zO@0SVa)1`UplQ6JlLI|Mi0y)oX@Yr$17o8eqXChhSE6Q?@x`&WRE%lTrHNIR$p9VM zD%0e@GC2NT^;EY79^ShfI+sIMV77=s987{P zI_}=ACVPUFqkwpzzEPDa-Fxf+^4tU^$-m822xxGPr0a_9JJP8g4+M#sfv(tS>H^qx zH3i|QyIKRxHk}&suff3OtO2A_%Yf3~G<_#Q^Sp8XGU$41bX>(MBQT}q1NDhldG5fB zS%F@XG8>AU{e=dPLLNZD@dUpCEI2(%Cil;kfFbi@QIb}_+N$@PfR7M1fDkS6HCNZw zh?m#3GZriXz7jrrks6!_zf04H1pJn{e-rOso|3+rbmv+*dp3dTd?lJIsvY+1`!}_R zj8oxE`-B@tLJqTcC~Ur9fG{!^b7L2EIj$YXyy|lG(TO?X(;LXa21G~JG&#t1{Ni@~#Yw3lOD62P)u6P$SE}(}0JU};3kSR?EY69j zruI0lRr_d0v6{zH6!>pY9}58Mz(sDc(9!G-Hw#*}COY49U@J`yuHa*~MZ-CN^d zAb{X34hL~wkahbScckB@+VR$W-n(nqAULP2a%k&|p&`qTCkJ)>L+Up_ezkno-I&1J z)Nw@pW&FR%m2k` zuKYKrxk>u*n)K}p>HF~cW#`iL|gl zS}Y*FOZ-1rnsak=|N5Dv>GrvqssBMTNu#5rzP`DM2~v0Wd3!tQwLfX}4r$PeL^LM# zsFR+_k=jMcsOH4P#Q6C5zntd(+0txpZ*OaBBelr=$I`4f{*R?uL;YWnCWKT8B3qg# zHA?-BF=R`#v9YnPuCBJWwz|5ys;Y`ql3Q0^URGB2A4@YMgA^0Fn3O~c2_gA;tp<4i zkENNHm-qPbRpc(}W}ySTXAxpRjsYTDV^kwwj0w{HC_YFb%Y{VQsko16cSsA*_u zsIRZDr>Cc@tE;1aI4H2)*i<5;2old8!A1>dcIAx$~vd$rQ#|A92e+H2od zo0Jr+n4cNvM4>#_2hqnG)tcq+KPKoZq2tiju#tucl=l+-0f-DYc{m1yM%s! zOlzaCSKAlMotht_=)3m1Hp zb}`^R&KQz=u=Dm=Y6&UyOybKtH(ngEk>UP4@a|(cDUPrliPjNX!OmNu{FpFHfVX6Qq{u|P)%EK0d`t!YpgfHZK z^a@vld5vAyGJ|#UGK$T9vDTDa$XgIFyvzf`@LDM6?-f=+~E#7(^QyncM`*FDNE_Z|Z5Ps@G2gOSw`rPPjG{ za`X`US|=_QY`1w^PW7WN*4z+nY|fXh@0j-~@X%k(aB^wpJ2Uv%weftxE?ZheN{d>U z)kMQVa@0^#^X=-UX(#`la>mQR2h>f(Gdi)E&dnev&wd*Dq?vv`b%Q=M1=BY;?AIaT|C=eUfGQg@n@oQYleZ6gr1u5%2EaYsn^NMz9dv6pA5%)>C zb_wydQTnE=FB#IDoSNa*pJ;t`)KMX$sk$S&|3(~LG}!3R`h^6{#eXs_wwHEKu#4mFr2 zqW6GW3%mpni{v#zeW9K2Zo{}b>Z8;WWY?$_U!Qzme_o7PS9~MdrJu*V-t`F<-8;Pz zcHcN?tBr~~WbIP|a_4X97*Tfd(!46p@fVY#OxU1SzwmW} zkCp|lopD8_;hv8?Py$Jdy>!s>I}!F+VMtZI_bq%^>#hozcPC(Q;N3#;w@QEM-SA{z zyHtm)rvU$Q1j_`0Qhub5nsOQY%K;>7iHT&1;|azSVgbcTdE9D zU&cpW4z){DS%6^FN1!UCuSbfk>yC6PQeZyS-EiyevM7|09w2j(_?dAk0VZn)e(@9s zXW|dKMN^(Yw8DH4utT~Sm9x!{3|%Ud24UNm)>mWt!}f95y4+zHw4d4nAW)vvJjR8l zBO-BpjF5Or%t1#~7=NkTfy@Ylw3#;O)^vvT;3^aB@#uSDRD=^lxezzQSbXkua*dHQ z+e#dhB9)e>A7oI4(kK2N%{pTTKx94VNxe13$NdDrOP*~Y)o9k~6QOu;C@A%YPy|K5 zS`mNsrJlEp&6(GFoG!@(M!`+Y3T95%A%==$J`#EndUbg?k%hho&*>w%?^S|4b%(8b z9kE^IC7*r~NU7N4u?PUsll^7t;|>bHHPJaG-&g8RK8T zBtAB3oYBC0Z)5mkk1HlM=C_wUgRp)z6@MmIas-|6W{;&bEqmv3)ZyT_zgQ}~6@Cq= zyd1&*dTJnu0}Rh$agYTOqxGZuC<8imSpg}8H?)s}Gv7(KPtodL=-ZZPxh?fe*w|2p zwH8~3%4@X-)_F$nc!b2`U*OTSL4P5^_R*VG-{nfSj4hD`ynxg^~U_C zgZ$15ubtukx*DH9STx>0T&fD~8(Jz;*Mj*5XsTsk-c-?bB(2&^GZDR$M_EgmTsFd4 zo|{sK3$1Wv@AfgbPb0#O!1T5o;e3bTl;M8r+-WRe!QIvmls7g8T__C_nA;rE+jB`l zl2_vF9wk{Ry|L>4Ec+kqn?L%}L(wCpSdN=Y7KfnKC0 zQ1P>c%KGNZ|HzaRt(fEqd}6s)xa9UOz-w?)QmaY|CYn^n9R+U>Ox#bn3M`W~uR$f~ zD&j7U6U_^`5t%v~ythKc<9R7K^uubtjPJ>N3;#p?IRsuYjJ$v#;QweP`17@$`9)dJ zII6GcSbBzXZj&^*@c0VYJwKXxz$;vV3ISZ)c0^I7h0B~z+efUgaA~9AswcF7PQ?KB z%r~jMbka*KyOWo{Tyvozljt$!J(At8-?6t2$I zDWF#g11B4;z1Vno^^xwc(6kr9P|uc%e9bh8^rXeWwdkEr4J!`{5U@Pg8hYXvIZ?J~ zd(L)Q$ew1O0>Q@+PIufAiSsE&e9@!_Y)4@HQFe%nZ#fU@P--L{tNZBr3rpER&Brgx zDyJ+ct0R*)Pi7e}dMXy;utT_qYsS5mi=#iJS?OqYOi4C5FT!l&LvK)l1* zc_iPxWg&bqTl#%@MMm`tANpIS>UT$U9+npBO`DCq`s1754s+P9e3-En+G6;cRV+>4 zQ~wN#P>I}VT2N%8w;!jFw*Xdy-$_HLLPKm_LyBKh{;sA%g{F!YTH8(+jEPmnM{(3d zaS4UhLc{f3S#M>x0^74aStFvka%} zZ>AgStC&f_uHylybo8@;IESoMaeWKPKR4S(9#Rr5Zc$iDJk9jAu)LdX>F$q?w?lq! z@nv%LW_h30k(=?|DhEgdyHtQF)Z;8zlj3r-@qc8+HZd1#Fa>kgC6$?FuQGegZ&YXB zaJEDX*r9^7vcjHuY`Ek^%I6#$d;4N3C|436)n@c7e zfYIMV9z>ZQc2z3>urnh*AU`}Wf372+B_L1YK}y$fN`Y{}D`zx2K7i6b;|!nSSF3ci zp<=aJQ2D-qIFrh*aC=Z#yFW0?fTW1g(=T4L4*n)w%t;4aYe~!#LSLOiU8^aW9W7W0 zECGWGbzE~lE4mH6kG+~(7$igh(jYr5sgykMGn2S|SJAmHmHGIRjmjb#9!M(@d4Q+A zffmjoBXqme zSEi_JS|Col@#(urw=`(yE^V7a8H;II>4UPm_t`$Rg>^cWp9Rr9*8zCAO_y~!S~uj~ zXt|Qx!;~ioa)=V*g-jzT9ui>cp&;R(U`d~?B0nYcpNujwHbO~)8;>H)G!4BM zNHeTo6Xsfj-&8oXL*=zV6HHKH_(vqH9)P3nyM`VgV$$42sZ9a>9{?E~RAL##k=8Kw zykX))!|RiVu`Q4!zG3P{O8KiHao-DuiTYCa5VJ_u?)`Ox&|B+Cj7+NvW|v@~z$H$#J4R@@+icS~97N-6ik zl6g#MGs_zi${i9=Q&MQca)PZ_J*2cAe#8<-pyW4fb7-NkPHPkCZWCK#K!+Ap$1jk*fwE zZU7wA{VZhhS?K9AeD^akFG?|VXH0Ns-1ldZH#=ibK@9kozX?rg%3ZW}Em?*wkAu5T z^1Jfgn|IhiR=auMPk_}qXpv|`Ves=GbuFSURn(YZDf5my-3lpu)OV?XlC)OW=T!g} z>~T^h4X)!=Ae7eSz4|UIAs;6h&hi%5Yh#?evAq+W*DXTSi6oK47~u!vI6i(9O`@-7|EDgn)o_NrQlt zLl52YQ$SKdky1(!hVD)glm=-~LImdJf7W`>S?he+pZABop0)P<-1l|KxuHldOGwiA z((+NHm#0JsjLV!x*C*btCb!D<9oC?=rzRL^BsJkJzfih80d7@|@n@f`+V&@=FUlp3H1b#HI>`T#9L^b-HZ$gM~ybd;$u z_OT1}u#S=Q!tt-$q4*`lz~(-D3a92UJ-QFj&J10O*S(gW4o?pI?Z^6`uJoFXkaNi3 zKag={rpQKo0Umnd{5+l6SVZRzKlIfpA!r@qv4*1oAp8f%lR5nQe8o4Iu`4{h((bUA z;}ACd508Ed8a_q#)~Kf<5lUg*O>;;{aGm-iL%AD@x7t1|v^30@G+4$s5^+1sY~K}N zgwM`SSU)iGJ~TJ5X7u0E*g9p$g9);eacuT>l=p1V1R=7kVVgiq4#(A*Ivlf-oj`Dn z&l8XI+>VbN4)bJoc$EM_?EZHM|3ke3JHpZ(y$SaI(ZTPd$AuF|#8Vu|F=?ofsqB=L z$D3Q?&VQadEaBq|0#jFvU%`Up%fx_nw)*{*k+GU#l2n)bm42Yj42}K_HwpQv=j(O0 zatW(xM%aWr;S4L*YmiJ3*3CA}q(4o4H>pHI&W9M_heOw+iSMQ=Mebz&dNxSd%=U-O z!ZK$S6sx%IX2WV`>AC@>M6c9V1;8xJ*o(XM~Hv*82YIP9P2sMd{-%bBWF?gy}j{!+1>Zq@#Xic%M8;{YPdE9lrQC!eRI0)PmPf3g$J+G#EDkotOY^Ag{WE zE>QniYrR{OTAeednEq;$-p#Z@{9}VW6L7DNd&2uYR%~$qzQ!%|W9REnj$;W}GV`r^nZbER|mAO4qsElV~$2V4cD!?MvzHUO_o5Ys8@ZOA22I9yi!W9% zN|Tw4_@$op%Ohg{RpfTz#0IG!=&F64xPh;X;6SHn-~H2mjS@%g@%P5#U!NdjUd2!= zk|FWhtw@JCE&YS*!vh%OUU#ubFZ0%G??aZqy>HTBnxusgicQ)j~i-FifsWYwUtmH&m;Mr(_`(qS}82)Sx3(?+Te_a<^1T!DZcSYnfFOJ z)&V$b^j!dJ`pf&=*zBB|_Vl>(oEp22WH}*e067Vu_bl1Z5{bu^PG!b-H;Z=U>h=|$ zRx6#Hs|X)a)m^+Rh>r{Xh&(*#xWKPFB5Bw&8rISFftD~q zoa<81hOc0>zyWKvLa4SQ-SsP-E1C4#hrAId`QKvw1M=Ckv->2g(R#M|ezzz2$J zyArAc4Jp22d&#M4?ga34(r$Lr#{(ErJDX^DvY|*DjKHA?va}m#dnuR9VFfdmzt+*` zKZ`d6)6eo>e&h2!@JwGB5&6}_GHX-^k9BeL`+!Qs10*lFr9V8UNR7dO*VuZJ92a*0 z${jlNfIer>VY$pxyxsqKfhP(qmB-Z={>}7gpU>w~?a{Lq>W8xZvyPy4%tO`r>_PPv zZGYbY5Sf4>0r|C}u|r0E$}pIqZC`=$rbgQTPo!BnoJjRJt?+DeU^J6tPNKx}w~Ilh zl;1h{7lqqYk*Xpg6CG-VQGnQh%~|XH8+bW&srfi<0G@d*!-ZWr06|-Y7V2|m({lOA zj4M`n_Z(8NhqLK2q z-lextdcOc?7d-L-n04Ve)3)dEF}-0zD?fG(Yk_8~IJzNNgDFJ(X1g0@&lf_rhg^sq zKAWCV-Welkk7u^I3EZFOd=$?3w_&$-r7d)ju=9OL`4($2N?cQOKyQ%(K*YMmuEWc9 z2mbnG21SlIF+{rz$FaJZPVcEQw`?`)3OCGTDgDAJ|mrvKEGXqo*T@5k) z;*k>xF&1xs*?i;Av7FNJHh~uJjtroMP2q_q4?l#X!GX5CZ0Rp3S*w!6;jkX^aP%0@ zn36KCq^a?jLz~MDE4QIf{=M14-cfID%?pv@oFg|{obp>(J9W*H4+7X)|mOl~uaKWw-LT6R}#=&Bq z;^#{nq7cV)Wjwm_v^IJRvqk#ihP6O5+x+cQQga;x>c>QtZ;V8w%r-M%3@=>YyxeKt zeXlb>H=j)-1#_p&H9xbPQhO%X;()!eEZ+-@+G#VbY1xr`Qku%PY#W^(M7Q2ZrS#f9 z$PDe6#+Y|M92y@%py`Q06~ zYS&wCu=1xtdypqd_6O}p-{`lsa+f}56HJw>5G&h}r2 z5zOvCaX3TTubmx@M16rsQ&Cc^s1qyw=G6UO!gbFGmpBg&ZE4U zY(^s-e7!au^XBuM>Of}!=fB#f@BQ;yoSX&y+D0GkXXST+D}|9SqNT@J2{9?of>dZd zTf*%BT0aA+*n6UVKVzebjI`_6XgA zGPD#gbYZsms?SyFqRlY!a`p`t?1sRVGm563E5TQHQ=uA}l$S^&4YH_07*3~~sLhqp z;PS9l5M=7hIIiFKsi*DXbBLG4bjZpi1MqpJ{PM_2GkPN6~ zsA9@1CXwz|ZSfOipUYti9XQBnsG5YwNg8(`yY0z)wRnYbbG&StoAc$|0^(6}*h9b} z)&N$Y+a$wM|BC0Jb%=jyYFEf*_RIyj&}k6fjc0S(FDF(-=oiaMG=104k|@U}1zyCtLQsJ!|^dB>43A zK^IQVDIo#Eq_(8~=c1=+1vBRmcL)*8z)rP-AGeg0_xF+9utk0)mfE+4!J#qGU!I%CFY8h*T{zLk9vX zF5Yg+)=5oWk^~)C ziqp@=#CbVLt;Neubr13TA<9fPk7TiO$;$&l9jsdJ^|_X_S4!foU0$?!)=_amGA%mT zS0elPdhOHmZ(BO3(%NEi;=T_}1a_V_IEggF{?w8*kY{`j5 z%2^`n|C;#Lk{2n{?5p^RR}qkf z4ub>++TBG!cZX70uZ+BAnfY`1yQo*l{V8+dtCM3#m4(@WWPqJ1)a=q*71<~rn337L@| zysa93GFnF{n(9t<6a!w4!bECqU^CZ(Uta%A54&cic#&s#yO-V4@g7yc#{;;0t(0Dm za^AydEa*yi!=zPp@y#gTeiyxCQ0^UV$9`y9!XX4%5DEY!aZHJM_VAq`DEz|*GBW#d zHs)VBqUICg{OOK-YA6QY>Y0 zHCE$&q|l|PpsuagpMhxP=~H_=1|gR~THdNB{8Rh);L95hBt+8^+arGV(ouxD$F5LI8*~4upVJC zPL>Wpp9JogGaY0|(KhWEOo3?p4bX}&kW~^HE+kgVBxa?a z)ASG2rmYy7`P56#IP|jACrEmTrjt)A5#sv{oTsV^8*)F3nQU>m-1uM}>^jGE# zdq^Y}{1c*u0jecZ=vnb{{%8xV=rnm~*A;4&)wEPtt5nWuai?e`BLG+jrou6u=qa`L zm=RS|jnWR?_S??nj^3dy-QktdwCj2^3~uab&+TxV-iI%NdIZs9!xG~ojH8_$ zXv<6-&e5?#35}tK!LADV#Lw#WjQWK9`g3DiBYOJSpJNazw9d~_ZR7g?q$NgY9LK)* zjjp7$tlo~#rWpKK(Msom4`%8&ZzbW#q}u$_>%V3E?xejEIB^|4@gv9JPlZ9(A2i04 z2_UbV5FQ<=g@^e!@t`UV54&M3@a`QV(Q`83gqWZXafo z?Zu0hq@pn~VHNWO68IM#L>U}I!LmTGvpJ3C|U&M zvy>3AgeSs=7S_U#xW;!2sUCV&Gm-@P>z*d2z99d>6o_lUpl=u%2T6X0lTk5HYNzVy zys+FiD-=cY&0>DJHT6vuz&#`mE4UVIHH0^s6y?1a%Xtd2zkYC00z#-B-W=`lH6u*0 zE!@jos?uEYqJOf4iV9=;3O+n3U}mLY#@tPIXSaBNoerRb#v@__EldF+s22|lKTNE< zk@got^G2}`2FB(&5!xn+#`OJGFF#I8G@+^7Ubp=BEx&-iSi-_Jt|NAvoCQeE%1X|T zBuBf&1^_Gp7JwIMBEt;4_>8ERdmw;Yy;iPOSmiQd;j$OSXwCL=gueAJ4td_wIT>8S z)lcPc+(~)d|CAHs5p5+{C@9P*j+F;w5rR(#VUMheWw8L+Lhwh+L>U-nF-$9QCg1AK ztaU%yL~x=b9a(9tEU~YqByB%^^CZ#ze3WgM_|Aki#x*1%2!O}R22m`*dtroc4Fw5q zHmX=nFPXJ|i!jfNusmT}N(L;A_pW9`Q195jH{w1mTCTrleonW?tLA}MBVt*iAGHG@J@R{ zj*WfM4fY?e=x0o@N}NOw+VF=V-!4^8@4N%w4=dUGuH_F7>3hag$(r!WHHuM4=pFt| z6a+y_9fm0q<#H^kE;aSC$mc5;XIuF1Cc&WWy&34e4r!(CfRmNjdwpt7{mZT5=uXBZ zC!_nyzozlT8GMGvl?E=(hDltSpTI=)ImAg21S)}O`HiZ_y4sI6>YasnFYfqOju861 z7d=%@<~z_eS;_4 zbD{ju)l{LO!iH7K| zu?edzA{X$nesFwio@iBOSO1;utfg;vdt{pNyjqc)Ja0E;gnr7JOOf45+{~kska!^i z_N+pRy-8?|&qcJL^ zcmPUYIY!8EE1q4c6K`q>t|k1Sai`%EGylK;YWE!uuth(=M|g0`^iY!Dz0uGn=Yo|F3kRRZ(f`{8z9M<7 zCF0kLA2=1qxdb7z;NPJ3<~VjXkvtx7v6~4xsm%2F^c8I+sExn1NoLMclaXM43aUYF z{XV84A^kbu`E#T;Q4Y;+&*6(NlNuWC)ju&QatV=d#SPz!*MhGW{q+G%(f|{z|1$f2 zp(d#6(}1Ky@|q{{@%=6(iD^P&pA98gx5gmu3P^TOz0Q0Yq|V5=Pc!Wpn_}JFK6y}` zoUQApXw>6J8YSpzk(U^pFc{hw#CoyO`1LrYM9+2Xr$Mgjb@-)E6|+y%Q9!M!cL zW(YZ^ z%h4v6`(<%J4&0B)%}9|YF{#?n;HjTESzx-GKUU+yRQbY;Wkbf$yNdK|mo)Kn1qfJm z;hiGKx|pbt5H$5bmIwi&-J&8O|7p-%8b2H0-i~XkO{+-0vx}#w}K3DM8!f8mkc!`=kml zj5{cNvLT6E-0|t*WzfZpEy2RvbX1o-F?28D>dH4ZI2C~JyO!W*@xpg4-qv^1zUA7f z|GIwen#4TF?<6oCYH)!Gq^MJJ^mSKO{=0OXWQTy*b^U#{%MkG|I-_IA>gGm7ihBfJGra}!>PydzF5E{aL z4A=g3?uI4N{F`-zcrFHcKMsq1aB}X376U?{2b;EYYD<1${Vj*35Iix$__4*?G5p(2 zG2o+C9ZGoIFD_TXb^Iq>5IB0dqa$qJ`>u~A$#U3uq-gm0NpRoOeQX`s@#m~0N4se2 zYM;^|;wSZS5mUGuEw~Q`V~AtK%GJ~NPs3k@m|Q5T%M;uWC)|(J5t3VkM%zWz4?=xt zs3?bW+hpTE2s|5fi!)!tx3s{TTi|LVBGktII%!^N`-COe-wf&p@2CQC!4NJ09{Gbv za}9&%K@a!bJ7raiCZyA-af7X=yc8GmS8Gi+?pFUImnGnSUWR_jX3*&Q>)ctF=ikN! z1>`r^M4?>p`Bs7dHb#dzRBp^I#;re5D_h8#-ne=;!RQ5Bz1W}*D8ZzhZDqN^sLNjH ztG}RDvj8fEp{SYRkr71xvp?B=;j^n+B<1-1-9a!h?hi~fK6bZ8z8;hiCCQlS=OJ-w z`8jjcV8^P>8O0m0?3uAldG4A;n{yE(CiQ1^RCivZ$hD#b78=_|U+ndoyE^jv{_lb2 zzSQYj4{+|X34%xr+}dZ-yrHezubj>_;I=BNNR#z5M|4cg$|I3?NiZ3GnB0C_O%a~1 znMm%Zb%kf6bw8)U)wWt8sxfB_7^;hzc&ar?BatXUdt>+x$Gx7dKvyh4RB zVDB_1*55b;DRy^ymK7(H3z-eoeQumCo@=_Hr)Ud?P(+9?hhz|i-}$nqE9RLpC`tkl zx}5IAJJvBJNVmmA5lL-_1R<}f0Y(!rW<85SgCG+dGRO#U&SUnbGfUFtW!06M{oGid z&NaXEHudneoAyOoIHXe2qVH zz0mxH&Ld3bsZ;P;&L&$KQzeo7?K!L31d;tNY+rrLPJqFsxIC$k5u-Z^CO*mW)^4iJ zSdZV6vu5q>`~eo#W(<%JHvDqf(}NH^6wAVPfbz5t)_#eWm{rKFIW=OuxJcIlk)8RkncGmARZ%J`s@(>kH5iZ%seEi*` z=I9~yoMxBu8OYpnokx>-kV)90|MvaoNj-|uyf@(I(-U)x9)cDUSUqu>jW~kH#Q^zT zo68yQ)nyF`(+4lMIvIi4Ns4DrJI{87B|pycfAbZ^0Icmcb=DA^-jA8Xz5dA^aT}*r z^jMX7+3aDIydSmgT6KmQ&Zo|#^Qy!cg!hgeNQ4@2uJueRUL6Jy5qw-!dW;*M+Msx? zRBcMqx&7LZ>FamFZH^`xujKe1^tanESkUHcT2OjNN! zBnnUBy2PV}h{d4hjLZ{JA5Hc*F`2KFAVjT~q8NpzAd#sgO6QAGd$4xuHMB+6XT%NC z_ESLMEu~FPINk*@lsSu;bXFV>d7rwn#+k_dbP}2iS%UlWb1MfqE=jm0HAT4vgSlN9 zJm0M!LSojleHKelVW&ZqYoB6Ii9;uNh%W~AOAy=`=OAcRDL3d*wNZB>xwF8tBWzXr z3~%6MzGa6iR(<6m-v)-a;jsQ^!4OjK4p&BLQnUAK{9Nw?4?33ef}(Jk9M%X*;rhy1 z4e^RrPX4*s<*+MF2?EA)mRPJCGjH3BW*)dauerln1n)nsVoGmhdySpf6c8N^U}MVs ztjEWmHzJAhr<6gV!Pj;gKgY=YF|%o>MzY%f6x9@lFaUvGe8$kX_9SQm;e;bhnDiN-D3O+qM{o zPEXbnG(pbPSpeT(!6C=BOxP@4J#hwPck0NZaQ%uqPn2*-Ef)yQ$@)muAOV`cu?mbM5StW3lf`X?BRWLmA%BfpBJ*z0YoE zk9bu7YyS~d09Px}e_|7rMAOl%Mq`#TNJ@+#l6!I0v3;b)e&3yrFMVBW?R@CX?hk-- z;k1s#8Ub#xZ7E#vfMCVk=v~n5dOX@eK~j=0J~Py&jFy$Dy%k^Za};TfA165$fD5q5 zAoQMdWGor_foKM#1h{_Hxc@|U_>z`;<@4Ph&s9KtWkX!rCJ0gCYTx@XejE~-8W^d?$^y!5|| zD6Dr1k`^HaVLomE0Nm_-G_Eyq5;D@^jIk6bCbU4v`o2{Fm>!#f_qE#WwdPn11<_%j z0<+(w^V5HD8TdH=l|n|$6+0z3UCTfJ!{EbO zpoKslc9Zy~0Lo=rX^vJPfp2UK6$cJVypsf_ikM-o=lsNSZ=4>k{6T7MPZD_#NQ=Uk zTO$2W>ikcKLoC96N&h7z@&=a6o7p%b?F92 zM%t0RbyPTn0Evp^pFubHdV8NF3?;rBecq_D2N2V@O%(5(_q+l_^7k~9!lMFrE7%Ee zSY?rF@KhV43eZeQKXt27vZq@h6&BEg$U7wqq9}$Z7%CtIy7P~ei_h_@2bDXp)yq!3 zBj8dnuHWw84^Jux>=+N8kocqQ|HRNfS`=1c0}S%5DBpjfG7Mx|ym8lgq>f8t+N&fJ z$8?yWv=s-gtXx;dh$w*=!A7&oo|L?UwdztO2ke0R~q0$_4Ei<~4&zu>Q? zZ4G^aJcYdvwmlOR3g%P_)58(yh=-`fi0F+XBzk0hDFFf~g+m}9qg&Z7m0W=Z;Hz>2 zM0AXQCt{2JpEhfSwQx$4x)0RZ*F%224B)a?L-kAlH>J7+6AvU!p;Dt9i}HVNJK1Wh zoYQ02!15-yf1oJ#Xx&!$x*LBCcQ|5Q@(+TzVxtifrC8Mir34Ce^p?>9Bq6=zPDqKW zr0Q{1Zbx78dL%J8_&|2t3XuGesvriTwv`v^T!0km{-@5M z_PL;6aRae}Vcg1R4W$AseCw56uSeJ$oW@AVfFyrlafhS2FTLKxWOR#nsLBIyXrQsg zb1DiYs{AXA06=k`pQT99PoibOQw5ahrIwdSv04%U^3b#`iK4p&K%GEJlxV(`7}~WB zaZ|@vHk(|`v7AYHY)Y}Xw5oGOKaidnhBYI(;}ogLRZ@q|64}^Gub)zIFtcZjqFoFf zqHmBjPbBHh)?IJ5VnynlhRJG?>2ZvVbjByK$nf-Vw8s3E#Kwa5x)q^Ow704R&{!Erp+z2t<$Ft2I|Q2c zv6V_6Ju36r17pwuNIp}Ur-1Ng#F43ftG!_kba^AG&?m43LaIFoBOg6V`uU(H6jE|Q z&EbjEP$IX0A^;T2Er$wil)_%GJmog?iYihMha28Ukc4^A?2$Z?1WDt}Sn#OLd;N zd+ufT4lyV{zPdoEnyIjdiLU2C0l<{v$W&4Nx|6ri_7~i9g14{w|A8X&7P9py6Gy43 zppZF0W)37BB1R@eAGsDoPYPzIHE|GnclEq`YuznkPD9#L1?dTr&Uh`W)+bz};+D39 z$a(uh=OMee`|>_g1>r4#Ls_x^z8IsY6IHX%{Q$FwoI#*7 zdT<~IC_MhgnRkss&%(u=6s@9Fa{vnPXe19GQo=*M@IM^n`zw9EN~`39l5Rz79RB)f z$)$(cFosR-;S<8f@OyHS;sGsG`YZ@b}HZR?E>Hd=r? zI#r+j3NFyQH)6~sa(xnLX!4gm1cpa#?N#mBs~2(nt?|!%rv^zqqsQHP>ZoG5LZV1$ zqqt609jl^cVv*Dc9El94kpbH!V5UwFho%gMlS&0U{lL0??RD>B$%wJcEk2B5=f>Mb zh9l%9qLGx`NQA1t9JuQ*13jS7{cVav);B4=H$&#{TiC$-vAv2_y}~)m;?2DZODfAn zE)zS>mP*}B7azK8)c|PCyI)5uB5E9+-2~SzreH*}U@yGJc1`N&H$o5)*h8~~pt*1PXc;b7BPSQbp<~5Nkl`6;&z9ZB=Vq zq?_$8r3&ubnDV#BLqZcwQ#kxfy(Xfd5vbkj2GJ0b&t}I=P%;!cKr95JHMULJ4{h4l(T0l+lYJ^kfW zw*;lPZK|>)LPE81=-1DJw*i+EVG*iqp>6P*8;}m4^!OVk+$PK@F9?kgfpn<>M1ZUX zD(J#YcJ3J73=nThG*3Z~XonGxlRp;?h&xz}6$)ZO04YikT>B=L3P?0Z3_A!w5~cyW z%3ye`#+_!ml=a_(@Ud+FtXm+BqkvQ)q?@@4XI{?lR^<$#B`S9#U;suDlmJLYkQ6mh z@C*>Oe52%3aVh>@5j2R!GppwejAvmk8e+l!OkH3$^SOGznwYKnGFFtuzgKxBT4++k zix|T(grj__s%Q$^&1Ih{o+tAcF}4FxoB~fqJ=%&(w|j>#kiAIc%e9AsA)RR z7y=w2xvN+(ScN@7g>ZI~-{%h=1zdhZ&D4O?%&M|`?mS^z~ek7TiG|+?WciWSsh`Wj?OUn?9@FChaoJ zPRBRa^8U4AM2#JQlH(7%k2otBbgO`*7`yaT?uHKqQ7A-tpEP@`M)_bbed?lo$*$_tkm`~S9}JetkLJq!L-DD}R-?btW&f=Q@?D-~5XGwZt#9yXe{g=EYp;(% z+QSq<+W5~2wy}|c;txGkg(oAL7pf{si<1y=Eecmn2nZ2Pkx5LK5iOKSdUGvOBa@u1 z!UO4{U&Bl>gB@pE9ork@w6AnCKD3p6_|o{H-4+{!+WjtVVHOp3mGM(8nn0X;$7RT$tr_@7f+OE#3Wi?v-i8Zz9>%qQOti$ z;g5UpMJQ-M2+DB7q~mc73oU(8P+;Qc0z>KE)8y=eL!bUlmA``X2WUUDCjHs>_wC6| zvyVl<4N(u^sh&WUJZ{NLz1P3n0Omzvx002+;Mni2d5gZEHm^UlI7iB><9=8$v9Fi^ zDf)Eltd3~tRq{kVxBL>&m{spaSL+28B~^tcR^I5feD&1}Q;vqFPYWfxq5I9f$^up` zVePdgHCq!`lo$a zUH|-=mY&f3)>jC1(t)`0V~cM(`|Eq*hMpbjf#JQnS=srGtu1|x z!U|vHlluf=}p-t17=?7pNVIK{n;Q%XJUu=>|A_+$XSGL3P)*9O!rG~6Hj zd$V=bxis8){PI8GX;AjSR_qX0zIgfUjSg0S zEYjFQd2KSzZSnz$2mZ-YbLG>u_UwM9j(t}en}61;JVpI~MVk09F4NWwd({LoR*f8) zhSG<8l*dIvX7de6DhsZZ(JX*N3wejmz2(WO&;fv|#=6DUS#|U2ynYlGn7FDHD?UpD z6J~Cvlxk*j;o8BK_{Az)|gw3^z} zxw1GrT7xfi&$jQKGM~m*tLmDUx)y_ZA0J7Y4;0C|3eKOH>aKJudxwZ?CaKM+rsL@U z2xyzw5z?Q`ORK*OJfO6>3kWOO=whdN&-N*ddGWJ;xss48Z~Cz^E$c+F5h2<9IaxGS&v_n@ zMlg+Tr*Qu-Pwv|^M)=#3#CYlDw>(lKGlmh`TLTggeMGU|YQ3F>z}oTG1*WqDbVR-6 zBgu!9B6%;XhGz}meO5~vC2OO9%YxisJl6+E`NqhklCQcO=d!J4G-@OL&kbupt8*e& z_tOKj#?SXZf5v+`N|+E?fGnLE-!Vl;@vq4P9_c0bT?|=-ZAnVlyspVMH8^7olCr)} z99VJ|7o(~|s*dsHL~0QbS;+Dd0#r$YzRoRjblIF+srN>hTe!UOr(XR4!Esp)=I09% zeQ0tlvJ&L{+9h~4YKE=Vhp$5$pWy#<{$wXj7C-v~EfLqk{hTQ%X+(#u_FDeMr|6)* zSjii5I?(k+P#M*RmiXf|UK?8TOahG$_Q|@@v^%BNF4A@wSmH zhnTwMuB*sZl^D9b`0?JmlXthurg4XbyecSUKT9Hh-z?7Di^}aClL{tD_5m#A{1)G! zX}jgk#B$}w?S;MKm+-1En=i`yUsNh#N%c8VowjmpygP1=IQfLZRcG)T!wqj zUs*O7exvXI4x-2N=M|Rf_MQKg;`m#~_+nTeizUczSRn0Z8{*mn8@=Rd{-D)w5lShN*l zisBpM0O7SWmmVi{x59i`@ebcSWE^Cq%fm6G+CS@xTQahV%i$;TXxF9l_!bM1nCbWH z1J(mwF!GAnweQ(7K_QjQVq39m(K>)M`#fr;41bOLB0!cxwD>r^G;>O08QQN`T$}-D*DreFKU7SWmO% zDTOPc2jwBr59&c22A93HEAVjJ%dJQ1v1(|#%4^E-i*kaL4hNNEauhFzfogY0#Z7Ty z52MPs!4trsq?~)KRY@tn!=8p9_#7DYnGK>|g)0|6i*nxs<$-=hE5SvXA9pTqzB+B2Gn4(tA~QhXCrR*+g^N} zb+7T(1LHFW-jQeH!GUD76dg~;bHtd1*Jw*;JiHuomjI|kn ztzQ!FR{GgqkUY`Eqq~4F^u0v_fa$bjEp-Y1A?32*8I@R4HSo-mx-K6)^|5CZQPYqH zF2F8XAL7&us58b$C2ONTDIuWn!qj@%1uA#r5U+>^d+F!76(xPRU?Hy*co4NHK_z5EQ zHYi(d%#-A2s30^o0(NrJ2LUFdri`+xqFpZ^5UJi!Ilq24kpDG_jnhgJz`@Jdsnwh+vf}gBx+e)>K7kPWj zKUqEElKQe*E2cezObgOY{s$aT^JGa@1jUH>7>VZVF{ZLUc(sW8P0$Bciud1S;f`d> z|0~jz?o#a}o(?D_E83H3=?$y5ODGdA`lTOyGh531yxOp6-z;5@E#x1Wt{bfD=E#re zYZSqP02Q&NCKX-rSy~XFypINp6=iPqOZQwl-{c71y*{jkXG?QXZ7p>p`lfcI2Q7QL zNTt4Rk9+sA|I-~FLN!r!h4_^-_<2F1w#pTK#&nolm&{x`Q8)yXxe7e)*)L$ecGK3q?| zmv=q-0LJ<2(DS0SuHV2;W{2k=@zf2e(Nxk1>*WEJ1QN~{MI2&B;8ebXIsEJ?soEc&VSiO{ z7~>kaV6V)l8{mGx3j&JuN{HMbxjak&&zQv0nA-?tW`v>a266H1k*a6X(j^Qqy1@vd z8v$C>*q?DCW9!toXB39&*nK1R&qTCsWhGyX$e)T59r;dyhv}x{aOHN1D`2Aj)AW8u z?B<68pJDu=9;Ew-2mK}kZv$1F4&y&GA9^J}M1hF5xW_ODGd#v0+nrAIDv{@tyFL`|G2J1_~SY z+c{^d7?Ly()CBk3hAR!8nFbO=97mt?1el$@^ z*m%Byz_mK$FV$4%tmHp25f1pJQm2Nx@5Yt-jFA8AqeQ8q3{v`-r53gUW}L=l4^-yP z(Ilg!?Eftj5E!5UZw*}6@XJvUO%y@quxa=^XY?rUpd!(KkSAi=y*bLff7q%66D-tD zD{@pPB}hI}YKxc2!Ay_|Do^6ibo(jAx=js#f95WjR(WmegV1VSpp?VOWn0eXq!3g3 zMactji9gNJTmPdqnDc17Qe{+A<0%*-r%6jVZ}i<%`{(CJoNT&Hlsr3U?~3a2D6c`QQ;_2A%Gfd4@|JbB8O3CHk6lS&0G6l0Le=ZVp4%N3;f4|{KCkGt6YxwLEmh(-2^A*gs#kUPJolh#qCyqTl~#=Ed1OO*WC!#{S<3v zLuC%fJD_=a!KG5-mc(w~-DH;CWN{#AE=mLIZsb~At8F^sLRIB(Bwh0@WfEk32V6R)XweP7NfBX z1P?Vk*avYw_O&=LXWu%1vTbf$XU;?On7viXXFSM8Mj%%2$meO$ONZts;?aK#PuzJO zMA@r-Bbr^KE?x8U6yv0xCQ3ciDG6BV_7S}D58w{aUu0#(U|SnG_|l(1g9ASa88?`-7niVPbt{EEW(%DS(9I7teC!t`?UuM0oFXmt zPzaRUJt)YxFu$^$mI`5Tuu_TQ;bxO(nfB^x3DPtV;SBr=Zw{x1i(|WKW`cEqmk;tx zfWOmIe`)sC9KsrD?}%V;hTte}T4R%zXNxqhBc%Zr_9%iS2P_FKpsMi&j|JOdAeWAe zUwOVaYe?90uJB;jaKm2w;~f^t?ighmUmPi<2`yV|LxPP(w5kQ#%tF(iHqhx>#O)8u z7eGP)Z9rlstpzcffz6CA82z;cy)7NxwiC@N9rJUWNb10{$RfxwH>mC53M!NCeQpv> znPXy%@6qGrRhgGZGRl7+TSp{-BuWE>qJ~G7Qg|s+U(&F-NpaRLv68}F=eaW5LgM%> z!rB*A(?bHXT7@G~%yRD%asDQ{UXi}0&SC-iRY)bXe9Mek$}#yb>)&G^YUC$OT{iBE zf6I>pSRD$Mo72cP62mESxxeLKENaEbT3?Z;Xvcx8N&~PP4_%FK*^@H3tPe+WNE!{B zJdsiE%NNOy=?YF-WuE-!af$d8vi|-Roo^|v%sS2M|HIr}Mm7ETkKcbY1{(~v(G4S% zloAEWQIaBH0RmD|B7%T44(XDR?(Qy;9Nj4>-CZIg62h*1zTaQ`&+mWLxo%zD*bUCv z;hf#rd7l@r*Ykn+pz*RY>Y;v0jef$PXNcc=_CueY#xhf1e|3LQ82^)w9h51MiB5y9 z`ZGO_-I=zeGKdM%SL0`J5}e_)Mb~^F_^g-U>11z!IN7T)joX$XAnbDH znMcq1W)`)qN8@r);C`Y0VAk8WG11hLcqGf|*!NSUN5*Xf6>-K~@@%?GdGnNH6z!wu zuidkXl5#ini!UGL;l{fGVfh+80-LtvptCRRnF%R~)hHDY6bKVraJRTZTlJT2ORDD{T8F zDB@+xkt|jp`Lmc&!2|;N)Uxu zt8^$&%lAUBZ^<=fu&);-<+(BRhj1b_PQs8~x0aBaNuZ-;R zjaD#ExcYgsgOH4u?FSF7Qw}ZTvIKxq1 z5gp-|!i>HpAzrgAEnJ1ouu5-KZOa5X;_Hj61v8cz3A$g)2SsellMjqGRMIyd$*eP( zY^WJ+DyD5d99?W3`yD*grItV)_T0Rbh+0C=D-q{V&UPa4inaJgB5ms3rnNF z|4*D0WboECS&0#f!+QePlF`gu2?65~j%%$zL0N#u z2g1&+{qC$lj9ou*M?au5(7+6|qFL=5N_-YaAge3x>4+fAa7_ZLrE6sUn@=J6cCAMp4;eKO%gZ?n zMsLnEy~8#@ou8a$RQkF#EDTy&va5Z1aY;%2DJBlo<_}|%4R>2x>;kOQl~ZZ5NGz|k z1!x-EhnaZ^$W#RXCOKHQLP>nXhww2yGc)&=kRU|S=kKHG;^P)J#(GGdc` zx>GkNF)y`fz(Ia5T(oFB9`E!NfIc5yzWBZ{FLQdBPN7g1OWmF#7rE%7*3(7>VVkOm za+G?qX_5pmcwVP{KX3ZJ#EeNNQJuEk!LcNcxk7KQ6UkEai()@eYN?tklhS@$^dTd{ zXv#gLSLtPblX{f#p7FGo(ItU`hcV2XL67|d-P3IXVcuJmrs0x@5-Z_8FX=Nwpetje zqLdPGoy<=27_(0|^0%{Xbh7W}+0OnAw0Ym65nGyHdo~7a7*KJvU!}+B%El(IIK){Op@kR*r4cmq$mV<0?;_sQgl@D z3+}~buz!J3Hna8bQM54MNh$O2x+MW{@g79K!GeC(8=EbFno3buQ6FNdIr2?}R4CSR z?bB&~xI1Prgo!!cKZAQs)mM^dYABsr5WF4WW8xCkh442;@m_&Jv2bvN`^AbDd)+%T(~bW32hi_czQtXrdjy-(if>btP6 zmGgkH;}_gjZbmWl3!?&~!&z7e^t&Ynsz0XBTiklXE39px6dop}3dF3if21CjJu}_l zSNS5YH$agTU6Lp0Nb*3Q=%;eF(zJYVZaAk+uHlve8&Raqu!X2o(u!R^cLu|-^GDlc z%i^0uWYzh1ZMXoqpCT!0TK$jjue7RWGdYO0icI#SG_W_VRMLi42}>?@%xv)RDwfOZ z@KM&P0QbFfcY3x^oI@tjL1C-)7SDTl?$gf`sxYU_(NHtz_yLO@3Hi8wnYWWUV&pUO zOm*T8H#(i^zW6e)uB*rCo@5Bo6loMOj7g2u=4<9Lb9d5B#DmbLWSxDa%UwOOlvCL% zMnyVpq}o=CwM7=)!@8ei#zykgEXA6F8MlOqK&qk{XH>-o+#b)GjFofPrC;geE?NrU z!o@-@=x_Cw(Nxy?&QV?bN6b?9Tkd~LO*`Q?5qd>2Nb8>vv6iv~d`Bu4$3#2F6QbK1=gwQc}wui0Z<;(wi@s=GG~}UqCDS zYf#;ApVBN29EC6|t%7jM((=tBjuor<>t_5nd?^-0dkbf zvs$!3cJQe0@b5rR(umejyCa8#S8|k}Mc$jG9R$1}`%LPj(b>JBElkrfEH0+)ck@~> z^w#v+rCD^F(TPxaO0wzi<4>xCl^6x6Z~##`&?nbp67|UICEr86B2n4u1cn$3?(RqI zC#j0e`K24sxu!XOCh#C

3?$lBc|l zo)I8LeIq%j!N{Xv-yfzJ_mNkumEJ?0GH`kSCk<;vIa_C5k|&S&&))qeFObdu>g`?m zWQZYn^mqTvmho{6`8*0&5cpCJ*MhIh*yAIN58KQnf^aViBaNj|0WA4PMh~jZCVPqPLoQQznnj7@* zIHFpizeb<`gKhtZ&;aryKnKvw!M_Fv;Kj>-3W%8jFQ9=B`T~sU17Ds6m|F+h1P53b z2EOJAG};byEcCbI39?rWa!CxldxW_9^Pc!8AR9%LTnQ&SlU~G-kOlkQ+t!hq_LHOc z2b+>O`a*5dA#v6r3Be&rg&`@bA$BJG-q?^Vp3ofC&^+tVg5c1iLR@G`UufBODE_v% ziYKf_A~YE54fzQx$wbzoV8J{Np^1j>T)xyiNLn6$C2N1x;2_&+0v9ZJa5~Tx8ez&4 z@zpKR!8+olUc^j8;B;Tach$h9hJZz$k2-}xccDOgB_%-vdAbQ}^bx|W9aMxR$BU(z zXb@o)5%vgvI0jP}{*MS&6dLJPNq&kU7d*4Up1t(;_t||0KL~pI!}a||kXzLs5B7%l zbo~aOp?LX<=&lJk8H=z0fQn2KkPe9jmQVu)`;88suOeD@AU87w*I|fdP{a$`Fwjqe z{V`H`ZTxTGQtY5@BuqIIa*_!JjT2n}B#Iau$(ae5bQ}Ypk?FQVycY%!K)h)5UrOJN z=Zt^(^l3cVT?>+S(iI29?h%ZK1n8*zn1O=-!N41}S?7NeEC>^unj+mC5D#;R>de8o zWkR45dJx46RFcf0kTp>-LJIO?Ok7A|+zwbh+#w;W0GZ2e!>al^+vYVYIGX96`F0^^ z#Sw`UFD+3tbPt6@Vd3#d01ZGodn8ujfPXtN4hsT=;U9&O2@d4MBL3GZRBee#T|r5# zYhIj*?`Kp#6cj~&--#9^j4{oIOq<-os38SW@FZd6{blmYO2nKtA!r5G$b(d>3<59+ zfD;)W1t+EmdD)&itpD_B5H5N0UfKljha8(^VAm;IlyD~s3?fJev4bWmVSjZ9CXPs- zV~Ogb$Y}uJ;2!em9{5--12D0?^nI>>CF%82=|xNQ5xLBPyna7um*;+Nqz~I}^oy@q%|YJMTOj#F+C zJ_H2159Hq$Ca-je<3N&kUs&ii6Q}F?jgral63g;Hk9-DFEaE7 zvVDrP4fqNxMRUwSiIyJZGRvMK!t@Fzh+<)|G64I5A_UN&?ITiUJZyUu3ycw+10;CZ z_NjZ)SBY`_hrtri%78MHJz^XowA+TNd4DQt?_q z@vKdBKyhiMWC@{d9>HvBxK(NQKtUIydjCM_=x(W@N8b2Fak=e{;&V)|df9Gm@v>y$ zc4MAieEf_{JnOgt5F58)Ail*|vg1*)mu#8aUpCh0xXM@YO}!#TrJO0KY`3u#no@Sv zShj!hN|dw`ce{cRcIR}rth%^NzqpbqrGlg+jbcv@Piyjg-{k zoiyt3kf!si&#th~?j@gJH4)(|)6rq~!t{+@tOi>ap4TtIT21*|*DmWe zUbX5yCwzV+mTrOX(t=Vw8w}aoewQ@hjm+~`4QC~|wu`~GtCThz3>&Tix{c0Fs;MPk zc>%+tm-ASYQ*7sM?dRL=B2U}@@>aXhwxgrl1!~&G$J<}{8k2do)1S6KckW;`>{yKM zU~TSTq39T(>2#ayxcRrkTclIWt5Z_6<4&`oY-wj0s0+_l)pyZz4b^%i-%u{4xM$Y| zTkX;zAczMrAtK#R?7ANhF+OYVHV_auPVLqUr#JlDZI;>vmhXYa^w^U1K&pG}=X>Y!+YIJdp(DGz4v?HllA!u^!aJ_1=#he*%6ik@ZZbi31f-gEAE-x9s%qm zUy+Di2blaAEp0>_TKw7gK!s*F zIhJHv7_oUonovyhg=~;Gixh`WHLw{dEFAz55SE+3Pq47h&7_Okh&>EUK^u8X8;;Wk z5fTtjIv^GSsCd;-`1}xXG&C+fOsF&bJ#`pN0R3))*p2c5u}6VzqBgw-wo^Ix1coQ= zhNnx1K~<4gXOS(%qkr*S57{t*5t6VH)-8a%lLa3^6g+L2t|!QApw}y)9fr{ct7pPimkGjkK8d^2 z3n1ZTSRyGjv5W(b{u35%WkTqNL_{ppy^JDpMUMkWk{_AGY8coOko!1m%J4xr*D}l< z2{uHLe_f`rT9^VkLcW>6Z;^-VKA3tMF-3?ZAE_jguOwBvg$xyr(ZImggy{(#VK;sa z1C@lomPr(`&vr|qJc^u>JWOt zBZP4jj^6t`Ax)D$Wtprj8dfTdtV6;A<;U?g=}S$}DJJ)Y$oC6qgSW_cQEj*~67E(O zOlZ6efrCd%e0HOt#L-|JFa@fDb^!E|!z44p$Z9N%qkRQrx(pnxz^nldt$%iX1<(ky zF}HADWTZRQZ8&hpXN_HUl}Kk*+bD6)F)`#zVuac{yXm?reD$Pk4U`4mKoU|L5nm$X z!vI9m#HtYMnyA*Y*x`zP`kDqDFuLBT(nJ;^$v}>qAcD2;F(eLGG@W|Bbcyt`M~G)3 z^rbt=L0RM(XxOecd8ZNmCnQ`n3%rBO_K_c#K0*Nfnb+Pl6oN=|EJCUjhctQ(w4+lQ z(vxDecH-eckozithVMxrS&vAT#uAkr;CC>Tkq2aHUeF^HWhv`cIed>$WRJ*nuK^CY zn;?8L$v4ojx%QM+lGIMwoo={ruOPBt3ptq1TWgcjP?Vx(d(f^nKV!TzH?p?S`jI)4 z+!g?+y-B_aBk|}d_0K&*iv6mx!=A;%>g&UwvOk<U%VJS}~Z?!PPC4)ny8B!8n2e^Des^5a?jL--M0Kc$qKKe=<c|F>TVxh#acUVn4FU2%J0BRRt_IN=PVxYSsDmk5!Mf@v=t2klMkuw5Zf&p*rwYI- zAIcTdGZ*BG+b1)edc_{}9@3;{V7OSCa)S>P0_cx1uPX3fY!vNe|X2;#846dtfcP2lG8$~5u4K+h+^ zQ7_cRRyI|*jMBt846}2RIoj%b^i@dg7!a=b0uTV*p9fAUh%p+a`qn}3UN#lxbsfnQndJv%@%{7*xTY)Lb!l=c*mGG^Pw3CZJAtNjNm6e@#9T z5o`h9&SpEM;NgI76M!+Ssm>K)bigt=CBR}uxn34>p_`3{1Qd=b`ktwT`|2U7G0L+x zCYdv_!X0#JAy)}V*G5s&_M_WsC?{!ew3B(f`=&4QX`*Qm0hW-AbrM<-@9P%D6~@?z4M?-31FdCH z63?2ZYx$cfW%y~=xUU34X1{D@_^~!_=cKgUND&P0yOHup4ZRh|ahzx+J5%1H{|cAx zP3%!u5pkapVBgny8O&kgu0jkPg_@6YVj z)z0;j!C4K$_SWpn?d-f1R%p2Gd?!xQM zToRqE3XC5K<`U3n{gFQKp`~j89ca~@!-DN&A->ZmKjVh1ouG|d!qawkfximfTd2@^K~=2|9~{jxy%{<1JZnD zVa~L0c3+}L=c7}uIm>~Yiu9&Vr02Rh+try0npii=kIRCc++9`arfzhYg#{c-}9z2x0dV0x6V8&_iSl3&e+1aXUtc>L|lTd&T5Ia32jsi>UI+9BZbn%=*d)N~1MoC$$v91U|QZnh4su9TZba%Kf zlTYA(OH+}x$&Cu2%p&)+^ONhau##Fh*Ltd@!1NNgOn}<|88EbxLnS|^crQIEz*`#x z#YE94@r{Mp)rQ@)+F6tiLPpqtb6^@rfqcZ(5T|)li0culw9JK0R3LQ>GEs$&wu4k3 zFroUoJ9XQ9B`g5-n4{Scs)+Lq4)wA{MVovSFMgCR5c0TC@rJF=4?X|)eTqfL*dQ^$ zA?zv7ucXPsE`>=9g7ubvz8MJpr+zH+ee(|T0Kh=5DA}iFycyP?3r5eDRclb!DX6+GE_{(nMt{{2t2^8$Byin~1d z`}gnVUCZp?Bl)8>#a@PZZ~eb4Y%?6fA=~!H#gVU*YRZMF&^yv7uk8eT#cLg zhMP;qO@G3D`}lvOcH+jzaifK}Q8!$_%?#e}oSgjn^((Hk6W7>?>o&xF3C6Xm;2LFd z4R>*Mg1G9N6B85vC42rC+1cOU-`m@ZS35g9JKNja+uGV%T3VW#ni?7!>gww7UT0NR z6|PeFKfKOTMO-Njt{90cBEuDu{I6u^d7)r?X~=((orQ&k|3!AzXJ`F4*%=py3k_V4 ziN^W(;GFDNJv{!4>`X{Vh>MH+^y$;T$r_%w`fsdL@*eK?Z5%%zj*AP2LgAPgaWphIN(vk~ISvBB z5fWarFca-}nv zir;vM{zo|0;MLz>*_65DN_Y9*H>c`5sf?t{nZt)E#C9U`ADU~H&2sF;7`;OOLv}7v z;4B|63^#rLv4r)*mu9?nmMQA3;PuglC4OS?d(# z+0U_lYzZ$$SuKO#v(FA@JZx*dx;%rmMhd-mzy5VXAd!JNrkGCmh1dtNeb^Imd*pGh zoH*}8`P6zPfZlSNHQ?&1bN&PA;#Q^`r_VDESMF^3Y;RtJ?`E1vTb?yd<`L_)2#L)^ z(}?|Zh?xsVx!zLPFhx>ovZBoSwb%OLtkyT7bwTkasf? zPj*@+u_gX&PqM4u$xpH=*WU!~v+Jj%)vhEJd?Eq$b7Va4PRt8@4!7OT3f|S*b~OSC zqsf$%_;zytgY5L($xnUPSd^dGBaC+UP0tgZJMo6ZlLnFQ(qSxau(w^xT5m9koN~QVkQR zk*4xZKQ_7FD9|G12|~^r6RVtYpk~KtHtzn{FF>3_X&pBUN=37IzV}piBS&8?bwTfV z{cMq2m3o^Y`A744KmSAMi!mj-TdxM?JSC!rMKqWlhlSUe*GEe6Jp1UQCbGQoVfNwQ z-%ZxG?pO#d%`bMD{#E?o9IwZz&0o)~^h;h-o9ipw!RzU$2=cRKe=BYY zlb53qGCqBIptEqe?$#Le71Me-zvEYyx=;_N5!a=AL9$F^0ZYzqJB0=Ihhr>0Q1rsV zEy3G!_HEAYo5bzqZ~E$8_L+aQ5Vl!uHBkvs?Gz6>dmImmM~)qH@!yI%+^7T5qHO;m zJ1rd)5x406MRrb0{fq2;@NcrS#7nQGC_OPqxOK87h4 zH3n#)RO|PCxR-ing1Pmmwu#g|D#8o^YHT~)8#>8l}7uM-f= z!~`N_ArHPi&xru(ci(PZ_EVWAgcA4r$>5Oe{+d{GAIC6xS!Po|J^>E!?Zf~<6Mzs( z4aT6%Gy7!4Z`~pu4RcjkMl)L%{_BuOububb=;A#P!@tqR1~6dS(0y;yG(rXmM$A=0 z?hY)cLv@d$g2jS~>S81S9us&}crF*WTEDu2E`d-q3#QjeZIf_%ghG$NYkbrOy+NX&+h z+SDTZXbyEk*f8=;X~;e<;T0k_F*7zxWH8+c0SSi*h)u(-pM$D@B)g32DShc2=Pk8S z4`b0!;dAS=fCw(q*N}sW&{6poU=sMgZ!PnVN`>$A$fM_Ft`!f2sSr{elwR;d6?kvwG;+}EvxflxmS2R#nA z1DP;?JleWLChD6`7AU7OZ1*dsIMvPmqfCo-z+-*Z9+m z%71u*1H0rn4l^31w9tqX)cP!jp$r^rj@U;A5=n&ifiP+b9(n^@c1~5C2I4pNE z*A;fi->mxRR{MdfnyW)_(iCAY++ifNtt@?AHNE3qpVQndtg6_!87+y%fnKBWb@?&V zYHtahcV|Jer+*PX+kRSXnEOH!7lol$enKDuKWS=tWS{!eG|A1X+=$IJVvxS9Q_9R& zhgaf@yWcvz6*`#X$0MmG8Dw1VPeS6cyEin~Xm-ft#W0S({)T4Er=)(;^g75)IG9l} zVA+lP!G7kGiyINrbNP2=SNz}vWkE;GN~py1?yWW-tGHyrN|_eKg6b$EedE|+CsSFSaO9S zk|&(>>4&Ec;FS7GuWh;?g(_mu^ZH7_9Obs$BU9b(n0?=4i3i91tc~LM$8WM`8;66F zA}g(5pea+hJ&%%{0)^va&&xvohhN4xsh$05o27+%PpT`&Xy{i`{?iSV{;n&y@#ycI>dgkl(oq+c2xh*oB z2O2Jx=qI-oEKMIWrs_Nzj9jfGCCq|u0>D;+4;SqtfdcovEVZ8-lKa6Z`CAA2-XlUo`jgW#-pp zmN{kD&1JW9WMAI=Pw^C>O6T_K=k^eN=Cq^(kZplA;)(xZ>M+2sK9}KXt;pa=QC>Uo zDxz~?5;=DI65UA{}zV2}~&*Agj8KkG|RpalZYvrvqQ!S2YcI|eH6GSq0ri@Obk zf5Or+q>U&l7MqV*1!>U6%x}@aV_}FY8VMhRlsp5`c*xTwt1=X4jrV1JzQ?w|VSMD0 z4LBI6TfR8Ud-3rF67-GOQE)LNa&ejNY3D7RSK24?{C`vXcfru0s z-gDLZn)K~lXPP0uK%I&IjF{O32^Y??1xl8zi>Sc`^^%?qwuOz7ADbnMzZaE$4=uZs zMev~kUl}79Kt|3QApO3V)?SouGnTc?GIwpg4QMPUIVrKeS>e;3_9*iiadZs-y>hTl zIn{dUwyoQ)ZP~kF0~m`T zq@|fjuI;4slvrXX2QW!ia&~2QIz0xie_6Hg(S_G&^EhECz@vk0_^H z$>g4+2ZE$OL#V>kB%=Ahe5$Vp{k-7}`|McV)XH?TMT+~$+-EPT>i4D|A1^3{dC1CO znp}72mBy&3w2{l)KI^VX8!GtL7)-#UUi4Md4lbn0ld17W$!AjAW^ehJ;(=mfc2be) z=DZX!6FjU*;jgIYucC)kzyqDjM5R#(J>=awSnF1Q{QNl2wr62y3U<@8wWf;DTt8lz z{U6r!XpUv{5-~nV^;H8I=N6KpmQjJiE@@!xd0XN8aU1;AYZ|R}?F4UxA@`6}P-MBc zL;G@cyO4gw_rwUHaT4~SJA`%}$pIaFn$3bkSb_Nt@vPPoMk?MUvUiwHQ3~OT{z!_K zAwuIY!i^SU&8|_~uHewFM=2fVnmytK?e>)fqK@(H!pS)$og}88B#J&w<&kib0Ux7? z^Jg1!Dgq{=caarNmuZf4mL4U*$(yG zHpNq;;Hv%RSh5;=rhz(vf`Pv%djFpA)Pc~_frfp$kJ6pD*&A+X5B=OT?F+9RZXS|x z8+_^2r9L#c6+Ys_4wMeHl8l3|@Q;!yoxRQRtEE-zrPv9tfz8yx-FZ4&!%{JJXvw|N zCjz~-UZXpVBX@kU*F%+K&0Sac!*IvpyCS4(He({D-Ant@ilt*BQhnRULpx;SH(nQW zM@&4|0Ve2(KqgdFvtULURw&NMn2mg5Szuy#Wo)u^bV_<0%`$n1V(e}-fxP5bq4x39 z@UH|PW*RKMTmqVjs zzQCi(R&fHq+~q0%rc#Xu-yChfQKo&vqoO`n-$fi7Deb5Z2TfI9vzi)pX+?b3Xqw*M zkfgX8wT<|Oc`zg53o39We2ynuqe_D!km_k;;bmDKw`ROszQw1_7DpgSD|2oZ(a@l6 z^G|0W6ti~^rgLPzG%O^zq?JXJzs_drHRiG{Y@#XAP^f)f8gk&$lr|UhbQUW!#kcU) zs%4gVJku$&?m2PrOI)qf(EZj&rL_Fl|STbycHB>7qC zhynTNbgmXJUp>&Qw#~gbSe7dM3Nv5aFI(g@UJ+Pa1u6+X6juA_fM?=$S&gSq@Wq!h zt6cDuoAyl7X{&;Q%WQ`wZ37bvAr;<^&ybMx7Z1Mv)?Ad49gx;4=kb~S7O`0PdW9Me zC|%J>_Bv@T&fTY5ePgik$frooKE$zbhyYjqs)!=%k zE3FZeRUvS1b7^5Y@z4(`yP&|jYnZ-Kd0qK7a{(h#C0o38B0cEcx~o>agX`bPkX@&^ z-cA2FJD*%#L$UcqYbSVk%Zz-#wOq2yek!=NCNO=wYj9-2eb?7)mn2ivA|gh1XEohjGM&@X|GsV4eS5G9fKqX`P$4uW8Zkkv z10;A?-S4sLw*6t((*wZgK$mW7K{{9Os;|a$cO`wd;jLyr7#N(?9Ho8$2tSx|e(;e7 zv<<-2@ymNSthK7D)~55Dn{+=Zar0Q#bv@QSG-9{+N=FVSz1yk6i`WGE3(fss0*dGpaS_0tpN0Yus2#c5{gFT;Yvp7PVk(bF`+nOgh3 z8q;vKAN!fFcLH?{djtLqbQ_Kk8BHh~0Z0SFpFTMY8vtT3}?r^R3hbW~P=es{(M>F2LNd9kTLhmk$qb?YSF7BQh1!kCs3tbMS zT|LCDp1pp!Uw(a6DO(4{I_PAs*T}E+o2)qr{k^c~cdxg)7_)j$4EWx){z69>*hBZ8 z%^Zh116H6|tj2d@RwXE^s|`uQBI{4Dv#JzI^FPVX05UbRf27X-kMIczlm77=Ly3%5 z-)he(t$I?VL{635EVNR{Mb1z7H;{!7Lp2ohQ`;Z!b|N%N1(Qx~LprRnf=bO|_5^_P zfwkrAU2WQOzcF1k!)b?I!$y~b#qN{@8^dPaXS*`nVihLM{y!M&!z8M-{P{MAzUbV3 z+@_$;KuC-qN1Bdm=mCjv;8S$r3h6rJ@dFmanj0!E$g0QU6ie56zA`V zSq;w|R=X*#d#rbsj^Eo5XiIc!v6j(MUxB_$i(gJ2=r-NHf?taQ-;A8IFr7eq|?t_0kzq;xq`|UltY95Z~X{UL$@JGz`L#q zr6?bzWBD6vxiwl+d#O$w8k-_pOnSBeI{dw=getQyjyV|xRt`CXKq0IFV!CSFd9}J4 zH(F2;Fu{%5M-MrNoxeU*xk2;zfrhfnr1qniabKT24~Uz1_9zN(S(?pt}EjXgIGaw6`1YoJ@uyr7Yf%4d@OUvjV8|W ziRXdav>D3?%q%nLX5)5{f4nv01Mm%Jlwuj44`szYbgro^Ml^X;6&1Zh2i;p1ZZ9B> z-`VmH>Hw1*_%4fi@a4`0N*%sj^6B$?$LN0i(bqqda<^@9uu-s1hOs#hyTdo{K)sx( z2+2>}-b%bP1NPdBoQ`MWZoIwK{0k)x$)pmtJIYRQxvQj{ipcV{>}n&>@XDEXs%GAs zt%HyFN);w{hV;8m#8C%ZZtXZk2>(gt8vA6`dTzvFjjzoBzC~hLY+b>9P=3({$ZVASTSqhMJbHQN z5#=C8L)5BlV)m`_!Z4wM?8ji>Hs3sZI0w6u-2Lb-p=$pS;nY>~EP55mZ{zH@_xotP z8#>!-bu@g|DN%}|Sn))36z%yl)U@0EAIy~O4{FWTHtE&WwJ0K)$IaOoc+(%e9gDWP zTvv&ukETvMdYTok3Pg<~ZVFTfz4>5%BjB;J{|O z{EJ-zUqokJ9$-8CVO1Z?C6?!|VW5t?@u_t`@1QzFs=3ShJ_*mJ(7o(HAFv`vPHG=h zhK+`y*4MNlTdVu!MZ=c1Z&UEwf~tKM`3~wYMdM6wvWYZ|81(!~gVcSJXDQV1{6>`m z&nqxuCQQQ8e`UWbRiJF+N~t=llLaLzik4+$3zU7FNwIN5$-A21S7t%>`H(7+Lv9Wx z-2 znksavx3v)T+pS7q`{`Dro;2?}Zk$nff$7rsZ&8^wl};k8IYNt{dwFW&7@al$zp+v7-{P`ol&6NVl=Xi3vL|60U z=NJ&NL*Prj#Y7~1J@F>T2XS@NXtJ-aFiR3p%y=Y+rdw^$tpoZ0oX5GT{#%6Y@S*?a z5G4e%KsZr$8B^mNbt1zl@Bj?f` zg>{uq_YsvA7nE}9%&>vK+Yov=->Jp$@83>Jl7FyOU!s4oRXE;Sh3f{s*TcG7$N$c@ zxoVWHp=(`ucU!|=Dro+~Acq?tc@jnKs|lTa4JEy!a5UcNiw9Q6;!n|quMaj&rRHoG zPb+cVT{ccssS84j!7f!L3w|~JsU18GST-9|AlRG+qT_#$IeXWy_F@W0{AG^uK@5lI z#B$<0p$2wu%JYfOUpdk>c{mmiuXLqpeOddswdfp%bK=3RT+lf8?8ocxt`-EjPm|2iM-f*BX{`&@%dax;m_ig);X7azNqcv>*Zd=)zc?!zdf5z*JRJ0 z-#f3Vi&Vu7?@135R^&|IzV2-OSC!TCyFmiDP2(Yv{srxdu`! zjH{6>yzTl^6D5ACCecc*Eg8=fXu>HEj^z$rYoUJJ9%bH6=qx`lD8uy&`lF=OL_yr8 zNs8s9jr63Q?eAyQJeu1}o}a5DVj1{VDK$%49&{;9A09m6!~u)#h{{%2VN$^5@^{eB z2NSJJkCw>CAc+Q`iUQ%XJcdoTsj*`IQqud_yUfL27uX`wa#OuXDMQ7DuZptHN^;E| z%3=!gU3Vf9<&C6BoG;66#wvxN6q!U7RlK-WhZNAMN+P97;b;X-E|Ry$g377r30ozd zSOr}R#m5%PhGJdeCPfz-%F#UjK2i7doaIPU^R;u8ZK}J`lij{0(kmTM2|MfyGLoXT zF1^x5^Y9J}>gt!$%8#5oEj2qH@O8;^g^-OkUG8;>thevXDcWmFy&+R^5K~bfQVwnC zatD)eDsZ@T^{_~{uX?Ds8MeP3x?z9WD`%);tJz09M_@@7atV_2g(Meh@6(m-^` zeqWtU@5w8*grU2M&AkEA>d6A#K|CtKf1#Xa#FvBexut#jT~z0ZbhU;LPApMMiD^-5kcwh5)_%k^S+yv((12v&VAop+rFecBxEMAe%nD|6$;j-YAbVf8 zHsa%D(#P&X-HOhkWlHVW*BWW4ktTxrtmi_Rrn;Qp!T#;|lU86G83-#P*0(qwa|DDq z;^Ekgz&0pY{u0RT6eIxP--o{!VHAIRnliC4-tpnXJ2l<9>oG+0SVh0KV|TjO&M8 zX9!|YHx;gN%{~d>p$!WWmX}aK#xPDR?jhYRuL;vd14ICxkCh=yJ50?AO`d;SU4y5( zNLuP*Z{M73$B#F}O}I0ychJe*>xno(w{guNwLzo%D+;YfcefXxuz1p39!rBr)RVz- z9VJB0CHer_7$7!yGBFyRP?^-~Rnr=`MYDl5rvD_uKy3v3G__Mcfy1=xvaP{?&A)%! zJayEpg)G1XH^gA7jN;Sr?TQJA((x_lVuXt0y&I(Hwh|0_!6HC{JskkdnMCfI#Q9Gl z(8i+7?})(T=CP#P#i=jFrtyc2ji_tB6pp1JUqw;P$l!gDeSwg_ghirfqL*NibWh08 z3HBmiFt^HOl_7xsKguQi^BrSj;HZ6**i`qfFhTOC?`sG$5IOnrV5_dt^S>rvW@Zy}CWQb}kulTep*eYse(tZVlq6C%!p_ddXnvE@8p|y6A_Yo7-%j znbL`b;bd4QF9^-|nj++S9NA@&P^X=h+$B%+373LWyO1$8k2E?~%lu6-|1e+(if4> z8(0^VzQ`_9w=o?nsA!>bq({mcfnE(!mAX;uD}bzwZK@Y-%#P_3U#I=$ZSA4^9~<*1 zJ`NA~9~(2#mM&({wv%OA?|DwkI-3bcU0Sj%+$R7lY?tcCmfy#<&@Z_#puRB3l_w`s zB4>1OP%g;M~s)&I6ohsjr(?+`TQ&~#9 zkQuKld3J7pT~KnW_hRO|ES9%pYS3!G<)_BH@x8CqL3gGDW~`>C7p~oSSQS3+eJ?tA zZL#S#4NkRBTt^PSh)o<+-{7dd8nOyZVY`lZ9I1H%gy@{lXp>wJko!X%)P}%T6&5y* ze{xJ~^p-^<9S^U*p2a(XhKY7wfbrUIQ>pliAC@V6m&C4@Sq}Q#y7(R}E^V$mvbPe& z^Jgs_mq}0*F+6k%Y5w&*#Tmy(qa!u2l$2vH=)0PK#2{M*nf2CB717>&up)}T#4~a4 zj)qG*yD7!&YB`g0E^i50x59W0_G|fT1tC|;wPhuPE^)Xt{I+99IdrH@3H<}#?1CJT0(AL<<`xp*NyDgcdEt3AGxV_ z|5Ph<;}Ke=tX#7_aFNvbr8}`?Mw-NwA1h;o!NA=OXR%!O+MIu`|7me^%bjrb{prrF z;mJMLVO2<`Si>bxh_|s}|8v!)l3NMi!}Eh1o786h_)5A+N~93qyLhMi}>6UN_t;*X9FXAKoXg4DMCGN-qg24`>cUt zB#?MZ+dq)w=XWad1}Hs`OWXH{ zy+0?wi#oSDTYYdn_%amigu)O-D*O7Yu%IOd+{O~@HIRcfFn?Z zWBxJsp}eSHwyB@8hF>BIpqF(9<^2SJ);(rVmm<)e#Y`)L81Sb)eZHC|OujgR2C^*d= ztT^D9Rx^{X-lrnB3;XOL#3qM~c5rV>Ntf?9aGhXUZ^uTr-H| z=bp){K(=@+(O5c(_J3q8@oUng%XsQJe<8B-ulVPmZ-PF!2TNJ{d385G7h0k~KG!(d zv&=i}@yWyjaiNHFN8I_}Bq9;iKE@FcS-SI{JH(VV)UzH=>BuzU?CBXgMB{rJ9oB}x zw#Ck6DPB<~0?4Ji*D_LZXd17Q+}jmZ;iK5wL7#i*#4msFRIcLl60h>4FJpP?5lb)| zRxHwSYJ?&*lcez>>Yc5YNy;HG`D5kpdb{H=CMzH}aI1@cZyXYUDz zClN(q@hlJ#=IPMF5rRbN5Hs4dMi}4?oc0GrQ~_HS^mQ=Nj`MAu82Z27G2NO2PPtzabHAVkUYZEr@QrQV_AA* ztZw<*bZm&oO)MQagf8-ngD#QdHwJ&GIMMG0zkjA45sO7|f?mNVX^|WDUfkU`^A1%# zSu8t^EDApHg_MbpQHl3@W0LX{@1U@EiW4`;UQ;0P-pYbZtWIt5u?U>XnF$oFCKq^4 z4EDSwI|s28ToacbF6_fk8KmX3RvkG;(;4KWsJu=%flOY@7_+f2sBBp?&f5S>6ZZsG zS~Piw_70C`8Y;1pN~hUrh+b3jM(+G5`)!3u1tGEM`JLHXcI|VH;W#TL6PuAt!3P)K z1J!%kfL8E6z~bY|Z?E{M>yW1Ht#j^+lgT~zezp~E04IdXTzwbuE4h9$S; z--@EQIyr?ie@~?SWYpnF`PUGS`iSF$H>x^* zpC_3V=&k8>6D zhjC>uGy+%|<2lZ3M8M3r5-yIKE7v-KiUCJ##WabaRjnGGPuI=Sc1-WCAjkk2jjB;T zBbMUjQTuck#`!{UBgr(w=3nn8g|9~9pQRK%`MzW&##n**c(T9g5hUx}@hbJ0YPr3l zc#-5%nOS!==@_rw!uN`vi+ABwn9hucMaNc?imJd?=ErgdbDNs@_G=f?H(e^$=7N2M zjC=W)5AV2E6FJ}iLNd%IeZT30ftj*cYDswQv$>+dI~J#A$CK12mv^S>R;xGFb7=D4 zAB3AXo(Odw(#UT%xoUiLs0Ikbs9z_pS7|7XBm8~3Gy@)+%b&=esmt%lnY|gPCo!sE zCAVE*7<93_U*8H1y4Ro~J{!i-%=}n@9A_C1gw|uY6N8V;>RqRY07x)KpP$AfLewkw z+J*hI@@Y$u1tTL-ljpyUGh2}F#Mh<=*qmZLCH309CJUWk7ilJL8U92{zZc%7336;H zq)%>}7fAhZH@|&$|Ig1QK3>lF z6FZ_^wPkg{H!4!QB|GU~6UqU{2voUC)P;EQZt6x4R$^bj8hj5(m?BdoZio`N6*=4D zTIq`7X>phMBtiMP7`0NC;-gqr1JN|Cut`&-#PmNMNfqqTC%=D`%c}X4WNxm-@wyR4 zzb8&0VpR_S+K(?tgTxZj8M6 zq|=#J9Gl2?`wvoAq2OP~U5*IYbSP>E9x4V?*-`v^sCKQa=4!me%94TK;7mN89LV&6 z7Za1p4*)s97N-3}zq}FPi1%tqKR#?~aJ+3^xM08jv^WK}Sh~h0t$lwJfHE;~V{$Vp+H#k`q11f3ejB^Fi zs|;W7fdwa)AfmysG$hA>ycHXiYZA=Nb!#<8D(L1Fy_x6HFJkvv~c> ze<(eCJsBfao>a`lM*1eN>-+hsKblEb2un-G!sJN9!u$mGP88qKh>|_59R>l4;{`01 zSyMPvaEfsVa)a6?w#K=5{m^IA(P74Ka;9IgzX6eb$|+%^lEIT-Q+`70z4q#c=?)Ls zE<&E0$~A6FlTYNknc`h@eqF6Zp#xDOpW*={mw+K2pmzq#>C8-W1;`74KtyO2MyGhF zGz%!zzZPr(_-j~#{NY#1u3)xHA9dgRmc@H3tXMjsHC{9E^uiKi6kLV-sE@|%sVcEG zc37P7<7Zo&z@`*D09Kp`9aA9(4R0kfj1qm-4yhC1$R894%t)e3S0|e*MtcVRNTZK;Fg!9}%pk-I`IhRNpp*os*6(m(DD#kDWn!bF1kc57J zpuFTsrWK0e&72CYX9mf`*DI{bo^YC*l3AE$Sbx_)A9&1PC()hY@l?i9j*Y&gp@+^a zslXWc%%6-MyUfbzkCpk!ME>h07mfpBAYj2QWy*Jx35pV>1d$ktd&sHOD2Z}d*OrFn zyDz!95@o`5+d78xAcQ|9BdTHBm|t$XT(PA@o_Q;_^x4;H--k60BoAP7s8Orq1g@W! zH1gM~tlc*-rL(?rGE^Dur4O9_i?IfLT$K!HS5sti#zZ$$wUK`Jx%X*26Gv^9^n5f(|MVQgPr7}Te|zS?lAK7{jZxF>0XG?5r(pJ z313O3|FA1Twzq_oAX;XSL+D8H%!NKOU1nJPO#qgof7UW!P~uWFMWYujz-k5lkSCI2 zDF6c4u=pZEM+l9=vNy!(BP_Rt!sxJz2+Iwq6w}G9cQhlH`H9{Xvjz2I3DT&GNjNkr z9Z$bD7QP=9+WDK?8aEcI-QdzSC9alP{0wR;R&XjLs5Hzm71yUU}GODLnJ)&Zb)7N4AY*d zTVM^u=!p)EG$I_DxY~2LR#Eoup@1%&`jff%t^~YU+RZ5Cmdb@1GmAC!R5AFH*%DTdDaPz$VA(%C}Ib= zvZu_)^I1=p=}+)rTR$0~)JBD*JLSscW=y1=NYkrqFlipgeMW(62%dgvsaZU0I)qz* zl>2EcyIzcZu|3ZhdtO3TvC??3ULTVdhB<%b%UWj7S)5fnyD^{hmrtbyUHwXN5TT6~ z)MX5#tQyND7`Vh-ImPpEuZTviSV7U0lel8ImWzbS>X$RnOfii8r#+c_8F|#I>Kdp4 zRGw?5es_xj0F-@?P`*`VqTC$vDz4Uhz(5Ibr)W^!nbQ((MBB|SMe{-`wczDH2oHs8 zmYKS=cfabb#fYV@mvJT1;pF{LZUK}c!NW9}>I7!G;Sbj&FF0%jz7@FTYs;Z>sPeUo z)=-7FnBu^l+8D{XSb6}>&Pk!SQGVvQZv1rRKvGR3dC)R>(1j!xbg-&tGRtlskIl$W zqGmIG=Bju-V8&fxVuMHKtJs{K8=n$ED?payctEck|D3mdn_y6>j;ZdJn-MZN@(Is)5t+*-XHB=e3=^Dg)M zxpe`AxE|W#hUB;)zWuIRhdR2c=+w~k}4=vgcqmPZHaZZyZCx(uDZ3q>d}x7$@}`}QdX zr~8v`q831RYh&)xQE*Hq4=a>=%2jFXK$p#hoyR0z4SGR}Ri<_*5}5q!2a{ z3_ZA)ph}rnLZi0|rwq9AgzG>p+50l))e;RnGZWPC3N4WeURqU~T6FG@XXE}fvU0UM z{IlM$edhY8p(=iGSY5`HY?LP@W+P>uSB(l}1w~LwyjC*P65`HfNCAHFjC*SW)`c8@mlO9qsJ`zuyS<4jdm!hMi` zyqL(IHWkWHAof!?x3xdOIF6x2)@B*(l_qPjoyCd}>%F76Gc|wbF?iQ_&sn&rPZ)ny zBv~Nx*&1yv?}vB8qtBp0I{a$*C_`S=qh%;)ZEwQe6)aL#ELVpm9U?H&KN9pA7#7Sx z2^wQvP|rBzocHr7T#3w*I79XyMAT`;)eU!VyKD;>m+w<;uZD8JuJuJtxeHjF;nYMV zUN4dg{xpgENjjw5zjTxDyzv&K57ToM(?$;F`_`e{#w=Mi2OoYfr z7$vC&_^XRL?wW{zj>O!zInh+(eN@EN5Zf{{Dl{Q8JDySl-X^z}$)Pj@u0kGr1SdK+ zw-E7_id*6xsBs^1VN*?fYOpR!&quOu88QEdirzv_He4)d=gkHx2; z<$wtb5f`CaMklP0C=n_0g+na1}avyCM@< zu59#7Z=kUk{Rzbf^%{sExUH8^E%2sU>>;VY=k!UnU4Bj4q99kI(ebmPCsJ8#W1jSs zph|4~!*`p?T^^J#tdsPhd#hr2QM#Z%|UBPxF~IgA`4w-h8@~s?Qj{ zJR25Mwn(D;dg8Ef0_yXwvN0x*NML%d4)hxEq0kZ^L`Z%#X#3*={^a6WW~+$44>|}x z{)i4R@T}&4S@ufoq@sU72~{IiBZ{L*k$xh`eLg7Sd1CD!sAT44)acIWj|!7J)sPqw zQxLtw8pPGMYsLG3R;1=FVYAY6KIvo6t&Kut2oPLV>4@9`fnp|# zWdY;eeto=~XS~uu*1)8wS%!5`^PRVT*0tUrN!J^T`jxUFW}4>=r|Zh^16lz+u_YlJ zPVxPXID8R*(ZBbt4<)R7j~(kv8%v5OrIk%$n7IECvP`V(iKT#XEz0&?)ZCceqIo_h?OfLkjcv z5<;MK(c(%^qg&a&-zgSKG2W;4txVkz+UwdZ`tgF|y`-9ziWHKCxEZAucI!!l$!|UB z<^=(2Y39;ne}~k^htmO}AdmsI4c6rXF;wPYC z6(i{yC$JQws-}A9@*=`viJspng7UY?+vA5>q?Q5_QEH-&eo(^RKBlKF4`JsTXHd}y z;f1D4g2$oppJHVrAOgq=)u*a%_WhDpVTpz~XJRvLJ0BT~>kCzXDc7{&g^SQwBfvtn zO`A$elvd2v;p|*Xi0@;2&Hy_(y1++KjeZG3oeq+~s{T=cDz4pA6#z$7lVz%AqQVL? zSg+z?){(*;o=>^Fg+CuEHf!Zek-Q4Y;}6rPYcND!Bxap+O1|WBgc9@)1iY4g4naSM zTr~=za?(RzB#yptF)sQXGIX-m1Wbw*)@kU4KKy*yyfMhdA^6mKI|zryLIEz-=8xeu z(Lr^TEwE1nOUrfx815 zD?O9b9MU%ac;Fv5MabSMIZfoe)*d8UqY$v*iOr=|8l#jM_ajpLNO8J}fO!8oRaKf_ zebnhUNC4E&I7VxTUwVB>2+(@;+|btpcyT(+n26A2#%{q`>j zCQo=@FmQgY$5AO)8B^M;hq>lAML8s85UOh#S-*9IRG2ej4Q<=*FAb+W(9)-TAM(Vk z*T(3978uh>F#vjdXkSA@!Y{BF==O0ijg=!_p`b|%smSj!+j-^rX+%#_SjYxstt6R< zF`_wR+~`e(!B=;)gYfEdy1 z2q#XUb3&;3=ev6IYfwq*AaxXC4d8ACQJDmBKmm8QQP&5#Y`ENkR`%$73gfTasnG}8 zQ$w`+ayWASBh)pb28i3%M09%>){5X&<#P~1vcFWvv0oz8^ND(FH0V_FCv{&Dkb62) zack4>RU+b7#CU~S8OSwg-I%8J(uJ-PUxc*}ntRM$M0Lij* z>BX{&B>lxnDhVY%1x{)NXpzi`qZ)PNXtMR=$>mS9DyaKXPR&>723j!{43qQ*ysM zR|zH*JSY&wr*~<;J8bKhK|o87@1?3il^Oz; z&v4XYq3U<~_zfOWojb^xrw>TlC#v(JDZe7)sGM{@ep-1Vs8LC!@(kt3i_Ut`u9cx2 zWBF_B@-F?5&rJtvJ&)s5Ks1^aLSK&hL$6^1ct>sDA)WX46AtBmR`+~PC3Vfd> zu@}3Sl2yH~WJs*3*YI_XeZbvORivNrs6KmW_Dxar2LoHarr1*1#v(4l+wQl<$^5`q zs(fcsJ_Yyu-M0O1`K}%%5{1%+8L8y`K}lOS`C+z~1{;SrUiS_Axfu7i-AJG zEVf_t_ha#PQVT7m8{1P@c+g! z)z}8ry$^Q6oJgiRYFpj}?ruida}L_2tg+ty%9g2ocj#f+&dZE*iGix zqq$)g?+;ks-#>oqP_o>B;Fj2Wn|v7Yr!S zwL8enYwtuc2uQA9sDF(xn@)*BB6H6+qdyD}7_uv`%oCTiuFaxTejZR2MqId8Hn z1RrkePCH`d&q0-vE!+Cj4G9i2pjUU#w+%52II|McoGNw69b?O6c*wBs?O`IIfcIKG zz_k>qdo-+g(U`)3h{Ic5Dn${*q}`=*CEvdE)QbEvnZ&?Nf}0z$k(SjliyIJSkkrzo zB>adN&CK28^pN}aPIqIUq5;#jA#AOowA77giF=LlLX+%_GyqCaN*U1rM%B7X*6^QyFly&^r^OWy`_|!6%_eEMmC* z9^w5qUYTj@;B%R5_@t9xWSMz_A$$d~8W1ONuewID0ZJ|G#8B_=3@-%{=TXOzZ_)wE zbjY+u3a6ng^azE8$e0cVlp%kxl$%H|dxYzI2t;j2z88S-y{7@H5F?NhPzph&3~%3L zhGzK_O3v{T62{SkL_^vQ!Pf<<-a=ZTy3~er4g)Zg1m#DGj$~#CWrF%JO=40pTj8}; za@7Vk%6}hS%LbQN*No2g@v#;!ff!`}gAs-Mpjg3|*1YPsAy5OroqU(GQF`fwUe<2K ztOq*bo9scy`DsB^VHL-`e}qR55!42jFpR%PHEt;WZI$G&vZf$H_B04?2R1)_Lhz|6 zX@SUR;^XcHSq)TKw%_k{dTjUUqM*(8-Nt-ji;>m?Zq)FU*>1j$M=7j1 z7@o{3F|8B-?kr_q%0dR+xVHUjejn@11qQl1yyssBj*cYoGjAV_f`M3grr%zO2}TMaGF{C*^q5=iu~B!A{5 zM4nUiJ|dp{i+kn=ZPWNuI|2H39~@Cy%q?PXc4Q}nm zMr62-BO;{)`bhs1nd7;TjOYk32}YDox6vV?@t?o*nGPBKlhXOrC3?vWd>>&J|J0+d18H^=D2Hm0{zy9fj!z*WD(3!i|WB_wg22Gy`vnlw7P=LkG1BfWa zJ0K^2AHZuM$`-KleUJ>9#2!577)&Tes2<4qH=R@ZnAvoKjm_gf#4^f>ollIl!;ck% z;DPtj>8W1C^>3mLNJ%J|qBB{49CP1xnawf-ZhCpJ0Qd2+xaSFlpGpu5iYK%m`V+lp zBg*^0gbfqOt69Mizt1}}ykMWo_dL+OsENi6eElquBNVK)(REIF}+X(f%}jp0S2oqY~(=#?^s>e4`rCQ}9Ax-Cls&52zx}l$|@3t~*FV zADp`8xh)`}>eZ~lEP;9%E4!JhiP;4zw^$QUTGU@v^+g4ZkGcI*5rt=5#E#D@(G(n1 zs;0a;{Gy68V#4y-r}!w^2$k;6Y`MnlMT2YweP=@JW_5KH*dmhVbFzYsg1ead-@;u!$Nenjk zGBo9Q%lW~~%oOYyH@vpgOizDq_Bz;r=dD561YQI??GdTP_c$$F>^U2h+EP~qDKFp} z{*ZzCp)vDq7|ukq&e%fwHO~!(VnNs1g<7vG!{XmGXR3s@F(v2lQI8+OsWovI-f2=kcT@A#Z6GmS3OOs4pj8e0d*n-t9*;4Ca>upgp7S4&^ViC{LDQ&$Ds>f=GN zSvy=t;L)fOAx#lkQPeTo1V@SFZ4V6FEKKt*crBXkl_}w+6r;tk1|-dn6JK8b*x+wg zChue?E7pHBPr3RH(v>ALezSeaes(eaWI)EQr#+FVL+7JaI=X}!zVbg{G#hOLIxve^ ze7muI?=saxERFm-yF{ivN52vIdDe*4Q^W7+mZ4VXIZ0PA+K7I7ASg?=HCa#sNY(!7 zYsF?(EU70LKvs}WN$+85onaSJN(z8+kt>m&^q8qow}2%BtZ*!uisimhnt5A3K}b$V z!D8oc9Xr{;ge6TJh_SrA;6aDq-Dx^uI=1p0zgFw#7}C~Z?5X<4@Wo!y`NXubof(due$Q_8_m6)jhV z*IZHW30>;r=~kY0|06K-U5=65Dq6}j@m=-mRk{A7ilFRLzY&PgHy)bW*Dfao^$!Vq z3_OQ&MeE*`#D~{yc08x0c*$t;5;vkorjlGe_>5|R9%#**Q%pkQ{|}lO&Q^Q)y^?>9 zefHce?NB1=PxTLmCf4V5pR#H=67ibZ%1@B>GwG;X3e#e(9t2SQWFx6vqUmztZ#jE>G`UJOZF$z)7xSD71Pz~;$>Gk>J!Qkw zw3bjCc0{p6^QqJOw@)7#ig0Ip0Ttkv!w;Cp*5{~S>0eN4~xth$xiWb<38D z7=9Ho!4o$?Iv7c<~9oW0NmRNxlq`NZB z1Yw;9;p^;6WMO`>WwlMXQum5~Kpw4oTXgi(4D}!Mh8K~?R zKb~nX$u?2QOM^y7g1;?XcRrHn`u4tyKe8oOq7$!|^My#-toqSR(qFrS8s{{~H7$yI{x;0(R&#+y0pJ z7d?ZdXZS_?9W6fZi{Jij<(GG;`qouJSP$y0ZqTVgu#+8>ggkhH{ID~us`JAM3U*{G z=T)w3>}pr;hrC%LJXj}eC8StbCa&(KF|l0`ZInTT^B~a!iegbSw*YA5x9^dq+e2?r zx<7x#HR}M@Crs3$*m><=uIw1kk+$)(^_~6!w2F7-lCwWI!01_eyAE zmVV!eLplw3%X#oN@}6y9RR%1+x0bV4vFg0UbdD2s0a;zc)ZK-Q#B0jr#4+DV2ut+t zd7mK5sX)uPSo>v{{Ng%Awp26TgtvQ@iZRPJYll&bhmYD!U9sl1*k7E(#N@zz;=@3J z!GT+Fa~a9|8ksCGXHZFe07~Ax+3Ek=p+70@XT+1AO?t2WkWz9{m8GpQs>VTMq7*Z6 z%bK4({d`S4Iq1kD);AI2H%YiZ`QhGIB~~%5CHe>z){y$s_@dfdu(KhI2Z7Q*EcUi0 zJIB$jmA&6NO*#+1M7+Mj? zV?PCzkoe~vnb*kL3i|(%ohXbt^wK-I-!!PFZ=ZMcN-sBZa?fn+y zYz76N`#-|g;!h1SZiUyco`Ao%c>j18DNj>7(Pm3RxH|%?Op*>t1*-m1`&;x`5YYN+ z(Kgx+(7*4F6c86$%Xnol`$J6j?Z&4!$IBB#W~mFQfYHY0zSc$#L=RV<$ydcJ5)v zivy{Nk8Xb&q(|;rG-$*UX|9`45mdXHer_b{PYO*kRJr^JgZAZ|M1mNzYC|UWqAGC zD=2iHXAstM@Zo`LTh#h?+?!lShWq?%qKS-f2F?u=_mi)+>QgwKzk9wjU)HKDyXM2E zTYpB`^1l+n`&+GY|4f`%SA8r1qB5;==4rYsQgtZlpyWH+aY_zB0D`fQ`)ARz%A-3wiwFG#*dP@3F zn?a00GUTX18sV^@SXs@{fDst3aASn)J?F`!25X(!lt9HoS)9ySnI0ZH7jlTnlsCPx zdTPIuVp!_8x8U4dpdg}7>p}V1_xtsNCiC~GYg=yhQ`2NEkc=pdk!h5_wJU(}PyRQ{ zj7W}U_qTQ#Kd{0RVVXQjFzHGBoG)oe_I(jeCca+X%hX6**6)t)7msh+N`;w!wy!Q$ zPK58$^081%UyA)fiwPzK$1(+NEq&cm`g6l|cP{?sBXWK%Q_q!Oj}^kZ+GYv3bKZ~uCF@GD9uh_PosQiuTCRq_%>5cp=t zvmEt|kp=$IZGch3*a}X?P9BdPy1pmMqak6ZtiguFrSy7|iUqDvl~@gkSL>y`Jt+aV zNF+0;bTzg5u6@W94KM%J@;*N47;mJ;?L?I}jM6|~nq{!N@sd9NFwUZLmO|z8+F16~BsQr@;v+9eO=c3` zaEGdjq2j(dEyGu=O=Fej{vFp$hPG`eggrV_1$>*moUAafv+An0U>-BC|Bxf-n8QQ| zD@PFDhebT7n=`n&m~Q=}UuA2zc#rJwOnV4nWhavs=)Z9T-ZeSVLN*(`kF#0eGi;%q zwvJt!$zXD8Wb%2wNuzd!E7H+zG-hBU_4l`0r`9mcjJFE`k>x;YNZX2l51HX^UokNk z8=hR1!(T$%HSW;Xks(3R$d5m^C`jJnE?jG+KnUVa&T`)O9|g4KZ9gB{Q+BdndGD(5 z+fB{3Byd?J5RnDO%6N{wUz2j;}~Q+K89a@4H*|%+HuwVEGk6Xgx+(rc}C7t~ccO7gNLM1ZYB-9hiE9 zs8t{1_5NTqLTqYi%Fi}OHMgj0#UVT&gYl;zQeR7VW0qXVAl7PfG5UMKFwL*LEeFFC zG=!LjAX0xLOqr&@Hp}MUpMOY~t#6!?EGq{H!35IE!*&NjSpt(g?ryL7p&f)5r{dO|JG|S^PW*?F_D$K#bkhqUN-eKYByq& z{#PiY;WdT}9!W4AHuMrFz37EOLB0w}ON}!MomLXi0#b=q6QV5Jsiz9Nmbeb}{(pq} z@Ij)hut9{tvPZB|uZ^~Qd87B_zO@NGNcojNPkrUxj+siv{O>t(-ps^B zi)NQ@q{t`AtyIU_O}pK@zpoa#qRCI2QkRoP*dg@fq>r^?iSETcb|l6Kjqbh}t6>!g z%BykoJ)s@-J-oiRo|pKTDF$BcKT^TIaxlN(MhDxF-xXAP^ueL~Bul7v|D}+USD^|L zCZfqnkvUaR_>Of*x_h^xD`I0ca&^B_Lh%9a`pr8s@SlbO)V%XSPXp?hS3uv zjUxVsxV>$~aA?JF-4ao^lc$a`{G&0n*qA$WF`}L^!o0DPGBFaKv9kFXnX1^kTY$n= ztSmfE(Gvm+i!#te^KU4^^3mW%G@cUy?t%=Pj&JT6Z}~rDr|oFGr4>xf9d5^);G&h_ z=9%DuP4KEpcrcpavz6cnPYmEq4AM$;#=6TPPA2ZjTujOqmLHy!VHK05mBe|gcD7?~)lT{Rm{hB{jl4vy_CzY0$Y~e=Gs2O6 zgGE%fML+%)en$PI2^+B{eYZ59)jY(F-=A>7h-?)gl1^`}p7pe6pFGKN5|jO}%;*y##;KBE=Kz?g2DFoBi<>Zvjmd5qKH2 z*Gs5U3~fe}l9KozY$+L7pTO;rlf3h!=copBG*G|JD%rj{CQa7#a z!@^i|6TF^rhyCsafMPsWQ#{AUd_r0*89et1pR4Pmf)Jj9j;myb*Uz)~9v8f3V%H4(;~2;b16To) zu3{Q62EL782Y}ld85kgvWBw?|`uhXh?}3tD&+jBW@BaS$*Jfn1XTeHG7Fo%okL1Cs zmch|9;3(4_Un&_^O<5CXu}Bg8W__@`GfF1~ne zEVtoR?$%gw^TP~iW6?#)11DsBhB*G`BhvjPB62>&M^Cc#qo*;NVF|wxg|uZU;$2y!zB!YfXA3ZHURn7)%SuP(FIDcc;Yu&b_E->#V8sU)&4u9VC$Z7B=BU+J+^ zOtkZ`qDPMsM1q85wCJKmC!-U+MG1)>Bt(lI zz1LA9f+UDe1Q9_n?|iT8ey-p1p(+dj|ue#I1LvL{0#3(7Y-rUdo0_~PpX-qZ<>)(P*{5r9r{ z!FrZ>Mm26q$@qHtH}wjm^-8<-DkKd&3U9e;!T18AW8!yVaScBz8}wdO8|*f$6XV|- zGglMT&SmHKW^bx2-n^e5dB1lLa$hV>%?FSa1JnL}XBF1ya=*rzKz5SU{6lvB&AhzX zb2GkU`%TC0XvdG;j-Mo*hk~8I^g4gPpp~g1UN)lm>VZcJpV1Or z%Mxw6G%>Qn0`f*QQF39t8waGOi~Kj1>|PBW2^M+2OO}D=y9Uhz6a!C$$nwT-=T~6#=6;DQEYYj7_Dx)gl_O5xQf79){yWDp(>Zje%FvU zi4j4&!RrSU++rweRkA82e*8cM@zshA0KrC0P<%F?5+pNH(cJ$ z?y(6W6c>&p08L~?z%4PfpDl+V|H3V0h3xuV$A&J3|BYMTC?IYWLOlauGFWJn7`cEf zsxgJcKnSHMM)6XWD4~F0F;njaj}4Oo2SSs_u9MetCjTx?{u{Sc#y}m=C<5yVswfia z#_eC=4izVV2anQJOCV;gu=161M@f%Gb7lp zQ5K+zgC*jKFR6Hb;Blz@Y3j=vHDOc?K#ajbLRBde#Bk6M95PXW09-!g2$^*Vai0R? z0hrrLDvX|vfLkVqk-QN@H2@@b#zO?$GP!2_#3=u+@dQ!WyYuU`5yFu50-}|I3BkLc z{PI7kVH##%lgD9DcMm9ff+xE$nTDi5UJ4n6lB5lwP8LS_lL2W}L>X?Mp<$nU+QG*K zRM6VAtG{WbZl7MWeooJSmKpLn#~_V2F74WIn#kEJ5$gp2yHGj40P%#b1CS_7*k4@Y zHG=GgTqrVF5KUbg9bbemFM40K*KF30Q9wH9AK(#R&PrwgIUX9I% z%Pd1fm)CsLa>;--lt0l5=+yz)l^)Ti5kz(8^F)DD3_w9*unbFD22iUIwN8lkv@+ENXciyB`;g$@8vkYUWeABqK&n;_gq2J}n*Lgxg3n?(b zXebLq2I+?2u}}c`4&nGNwZD$OTH_Mguyfy7S3=c@CA+hImwdpd0#Ja+Y4yvoq(gLY zEXgE}&ch0Ciu`DLx!d-2x07v;Gc+rp zB@1l4Ulp(~O8KMlivHvN{(LoYi`7si_6Ohr!sF~mlu_eXd&0FpXZC-7QtksM@7Qh5 z5>M_;gtEWrs`VlLN49KnqmAB=jP0N+N0FL&J-MQyUGHbL#chzlyB^MXk#oYZR`wCAWFQIc{UTrBPtzsxHfCwXY?7V`k zMWaMSPz)3RDW1w8`PX$(l(EY1J5PUGbpHMaw_KhTuAv|f`FW7~Q^fk@)~gefcNC_N ze=qKx%oflUTjajZ$$jIrzx996sB{2*dVuWQvwe3M`1qFt#qUsx zQ$Y3X`MXWM8uAP=l+CS^lPRz|@VA!Y?-euT%K>qy0`1{tjH@T{S{KAkEsw{~>xz_a z6@By!L++wR{y-R&;jvV8)lIs;Ec|qS{RhzKK_=Aoi+vBlXXf=6MQ+`A0a>{q5(f(d zfP)okM%R6=hJw3^g3AvXO1_ERr~3X4e=+&=YWwj3r27g0P%&5IfRUILC-BadmI%G^ zjX0V>c9smKuy93ZG-|R;5wOeK)Eort5-@IsK(%*tn`;WxV`=Rt+Os{mdXw1I!&hHV zZgz%r0hV zB|I1Y-qYR&>QP|H-4eh@E@w|3`=E`bK^Y=9+8^CYNzA+Ht5WewJkpDV9u+6X?OrjvB24v{GrjE;t zFueZdX2MO_liaA-z;Ou_9b5K$@GkhI?t>TfVz`mtPNu5VKa?2TFvyc z0hT|SJ5E`fhrma-KIQpJh2?2 z15LEd;11b@6oU!5qU#jCXZF)<|KOd>9B_6|u?o3p%jxbI7IWux{%Ktj;^N$(cE)V! z9G=8X3+C0nX3=qX$$eD*cp_l)&Bz!w{t(fy!U0CxRQfDaBe#iq?3C0-p`y@F!av*DzYW2^j=-X?NaNxVDAZq zKNsFOb@~vWX+7CXpV`}HAy4M+`&~Ynx6KOiU2ti-^j-4)6yoUcEz@0ZuSAl!=pF)H7+x}by9rV&a4L%x`#RnhHm^}?SS@gq) zoIddr4n5y(!iQe`dOeg@#1Ia;aS1iTLbx%YH-jn=UZXG)I}AkH575OHvwiADCdg#hHD6HPXfH+*VQe!OwzF~xqQCKSk z@fDIu90RBmpttFO&_Tad$igz#qs&i9q}s>FNw=jTW4=~QeFcfth#im$J%kGRLujF& zBjoqHA{1)AQz-q5>>M~Wz_2~Q3|+GUVGVR*Rahc5MHx)`-b55F7w<8M?fc^@?(qGt8 z^j&~rg3k;*qHpKH|6-Lc#8M3`BRH~`i`hxQI&u0pk|$phsY<=JkaD5xW65A}P`Nz2 zgT9W_vu z9tcX9X{n&SfF2wd>$a@U+Q!cbh-9m2UPR~v2j~eCrc@-ZhZQeosQr_1+9i$B=?5^t zdhgt{Ti{K5bI{olyS69QRzd3s79EAgj?_&>Y4X z`1tt$AS-`pX>#r6*;lI4X z&!_%RWF-!VpL&j;@FS3w3;!W2ySwpCP58ch_;z>v2Mv6S9R9uV|6i}NrMbDWvGKo= zl{fw&D=RDURdV<$I(#MN|C_A*Th7z-_St{P%8H7L|E*RQ7UFYr@#*RKl#r^z{6fNO zbo4)DrN2Ag%WEY#xS*im)vH(ku`6?Oa-Khb{@?k^q@<+y`1sh^*y!l!$jHdBu&}33 zpN58p1_uWR1qB5J1o-*+`TF{LdwY9&dU|+x;N9Ht4i0!58@!bj-pmYdY=FOc6R)mv zXm(}wZLU=ANJQE|HnhH-!iig4QVDJeeor;RefA=b7Wo2b#WTd2|#Kpx$MMXtK zM1+Kd1O){J1O)i__;`7Fd3boZxVShtIM8S`J3BiY8yhPtD+>z?Gcz+26B8pNBRxGm z9UUDlEiDZV4HXp?B_$;ag`%LKASWj$B_$;xAz_0+h>3}jNF)M*fWzT17z_%95)lzW zAP_JZ3<81h08j_~^AIW%KnNC{nu6{K1U0c;LH|HP42tV!o=$C1e>{Vv^U_dl@nAAq z{TYjHUCD4d|Lsa5Cv_4?l$h;Eo^E~F_zN)E7z1U||2J9r-uWY?BUlc zfzktWY#$b4_1hYM+;b#@RF|3TQ0gX>DmDKXS^0}TQnXXq`*Q0eJvsz3VO9_XZ_FwPUs`V} zxUs`Slw@Ab5E&zLVtG3{^z3kOB?cYMzZ%Or;PCA!xlHW0i0`$Cm+@b^%kvW?EB)CM zi8N!4NW_l$2UIXLvr)0jTuj!sepHla;N!=OdnkeXPbX zM&9S(G~M(hvD)cz0QzNmRCTJIbNz|wgwtle|AxF({=S7g4opLIZL1)XjzCt%gklEZ zu`)Yb#j)2$_zOuG9Lq}Qta7#!vuubluf-{~B5zTniNdaDF>ohwL!4|9U%o%YBX{36 z%sIbNt*hJI1jJD*yYISSf_pW6bb3T|1H5nc>Uud9TuEK)_;}rBwC+}6KG~2|HZ0!Y zzsrkQFT6zxTj?ECO)l`>eb`dHyWe);HNWp4dNL9YP1$%O3Z-xM=Wb3fXca58B8B=e2FQSE+KmE_X> zy04|X4|~`Y7D%VbXQp6`s3bn3sp&XXt2Omuf}d6Kitd{^?;&}}SnuONv<|}tM{Jlm6_72Y!`nBlYjp2dE>Gp7S65SccPCPn>JfUJ z7z9?MxtDaY04^eeMR+t6)5^a9_(#MkoHVA;nW}I_n-x5g3EUM8?(UV|sZGN8U~(}n zuVq*GYS|a23Mr!2y)JYF|Cxj_ToNW>#uXHbTnwZHbz|TpxdX9Aa_C5;_7(vM(P^YB zt#HdY+?+X!m5{I|#e#iDW?r5jzgGR?1W-wYJM`T^h@TphQioAsELTW&fC1rHOmq-8 zHBjpjO&_d^3TzFF*9nYHDt*lJrj-ST`55O`&^L zdl=~+aTBESjCUb1`fI6SzAwHIb&)?|n&nlnD6iuA?lSB&5ms{aN_O^NCa4JE#tk^A zBV1&zgkhSaWoattEi=j4BK`3#?Xg-uY8q<3E>QqCaJ+y; zXY7HZ1?_m3uaT^c0AxKX?Lhi6!JcH~9Rd%DBi~+yXWo1+$^L6cz~qHCba+df`c#p6 zuQ~Wb2{>xR+J9`X#RMbZhqZ7G(it#EO81;!P!kCX#%dcSX)(ci;0B*{7)3P#*}OE{$r zg{#5}klwRg3=ebr(d(7f<_J=!fNK2kg<8HP5rVzG5+?3w1K zi%)?OIl|1B!Q3fW;$|%A{Qn{=<-%yp!$`Kk<`@`Ja~R8f7~4N&WjLqYKV&7Ze>i`3 z__gM6q4{tjN4Sp|+$F_1Y&l%UKZ3Ivv8QcE;31XE`DCLgCdE)y0NMHAQ^?`df=|>% z+JR*;fi3h=Ce4BMW{x3?a_3(YDPYyPNJ2a}g@@G2ULcS5PF76~uZ7}-ud+}kvTT9$DzEVwUjA^a zXMQS{4r~Z9D8aRJ#!>X5QDSiF>H+VAjhK>C`C@+R#${gsO{|Xa^P+e0aquJ2ypH)5 z`@7gHl-_@#C|>lBpWF9%aW!w(f`9bClI6IrQyJ052=#%O($fSkuiN)hD6$S9!D1Ad zw~;?QV5T)BxA@}CwBx00ueO`+b>;{n72$%pdptQPTDho1qxoSj=<)N1-p4oW3O- zIPZT^p3IrUcj_p$WSSH-=(uLbPReauS*v64*b7+A=;5MRM}UGw{jB|LC@T zSm?3tW4PU5_~Y2{Q0mt25+g8SS3ngtheb+Er5Rc{h<$$ksW$0{9I6CI5$Tb2T<#r+ z%y`<8YfP0LFY7@e&#L*vR9Dm9;J2x<^qo6T?pVCPV@2x$DI}`nLG_$La&(g-88fK` z(({mPw2V-&7^)W?TJ|{y4zm5dp8K{XA6uA@l-C9kD!lOWFV`$yZUnqsl{W==?Gt74 z0HgZ^g{lP#w0(TqVUPNV%>i)8DKY9?UG1@!C+_mBQcmd*N?-^_p=p%w8jwHc`0(p+ zK2;z!K`;55h7oBbAgq1r=X_dI>Sz($@S9f$f8|= zqBurZh3EG7H|!tMJ+hK{B-uq_whTQNdo-ByyjItWjL98R$>Jf91^E|xM^u}+X`TF& zE<Bc4v0HcsbzL@Yy^O8%fzeZ&RZ$Qa-Y-Q!Ws=XUkn6*l0c~)4AM{G-Z;!Yf; ztS7DCKbU5teZ|mOrEF^juCn-(ae=G_3iFAmxV5-5JNLox>$!z@soj;Hze@C-uJ5*1 z`OTGC#MH-Pi1?;ei6ZzzPgHG>eK6FYoz9C6=fv+X zcRLeEx^kmCwgd&xiaimWJsA=W`>lE8uGGv2FzpwpnF<)4P+Mtk_p{M%IYks(d(Zx2 z*R_k@oO60>g+}}PC?Z19fmm;cVEw|P#p@Tn1lUM5uSdW-b&jP z4@iJ&sqT+TwKsMw_5GR~ZQIK#Zy)Kg9PT9@o71P3l84U|mtBW8?qEvS>IZBvY!EM$=_W*L{Snpqm2 zseU^y^x?VQmuacmDQ_%9#`;6RwdtlMTnp*PM=Vp@E0rRwI5W48PKh5SJmb94Gcwkl z58Y-q^lxwJ&&gWyI2wGsVfC?ZVa`>FTElHtQarcRV&<&WlBim&QUtg1EnGC^ncxg>Gwc@+wYjq`G&)_z;?^26Nv((LBNeBot8 zaaBv&kEX0IGi6ruax4AnmGgBWGln6HeJ+co z+?L*7&JN*~GFqzU+LQ>zsBQTz3!dY&v16Getll=`Szj-|a4~*$w_2DK{-Rbjt-%Vi zTp8XYnEFMdk50}Pgvf;mGHmrp+|uL&=b zK0y82E4C~glREh3Yq02FwM2L24O9NiRJ}N!zpQ5E@7ndvl5#>*v9(`mW!`i}@aq?b zi6v2yui_mmPcJ{Y^1}rV=ub$W{rIu=QwjCk_wm^ylq8G})2OU`^_`}A^_}hnd-bxm z`-0d5RNjj?tT-`&jWr5gMRNFPIQZyjqeN+lmZ8pf>(?zq4TRY?&O*M~yMIF}_nBbF zo)!{c;&E`dtIx10Uoj30dQ}$7B^PNc7YhNN^~xnlqV6n{o`{iWs-m)rIm8M#gUD}& zd|mnO_H|v@zYNyw(KT#I2@C>@ye~g6P=lEyQR!v@S$-%{BJvFsY05M9p<+d#OK}3C zGz|e}ZI$NLH90)U-xm-CsZwOiauedZx?ai;LU)2#?=gyOX&G*4D6jn{1DLy#UXd_7 zxB%iizFUJth{T`%_Ir9}hPr`6nB$;zDTEK6D(YD8xvkpY95ryQ8tWQj&&Ui|MlPUk zJeIKJmg4zFzHj@3{X5&2u!+M>!~HNrz!;NCgkqTg@zpnfx9x$hIzLJiK|O9na*8+B z(3VmoD%8*~d1gdo;{*db<{k*Gn-GC+bD(cCJgujH7t1WVvGH7^#`JMtd;y{Ht(3O_4ujCcb1MnZ}xW}pc&8n@AoM~Pn=J;Ci7tC!3yfKy02|cgF+GI)BYgwzm&!xUw_cjJxa>;s56}Hx5o*`Z ztG}JMAvQuNmcmm(lnS+t6i2bIP*;c)usn(KbDuA&Mm;Fl9|F4>W&W(+9Pk8nsfH6t z$K40IC>7uk1t(_zc=~RKcf=2fP=uo=bZTXjS-rk7|X zNf=L@`t|ba!JU})O+WwQGs?ITS0)vBY-du+lLIyqcSs`6(LZNoK5MAZsp9pVm}i>f zlDx}UZ1D@E?sfynDCh5voSf*Q+;kL}l6*JSC3413HXQjFsgr9%#;%oTerPk0Kq5O( zQSaGZoggUM@m9`zbv!obCPoq-H?DGNV*gt{$IChM;T?7!5?~CkvhbdV#M?}iDJT3+ z-e)ee3iM02KQ)=iv(w*R8{_#ZF)xF^kLbV0s}ZWOKDPR|JcvygYyY)!7(E)V#4d9= zR{|;+OHJ$Itq6@aqPX+ns%UrX(!ubLs457~UDK7Cp)Nq}IvZXX750FVk5s6@6V{&B zXZu6?GGpPOoILIvRbJwo4I!uYWh!Hr-tR?qrk_fts1n(h)M_z5rg70qm#Ek%`Y)bx zg|p<~If>_MZnt|TWxTe5RJ_IdSlc94Urrz=)C)s7O#1j7F2wS8##3K%QbW=pVT4;C zJz(sxjE)&Vd}pUZ5IdwL@gfRuabAIXKx%NF1|xMmg{G9Tx~R@~uqJzy)btI;C#EKP zqWKNR`m!G~Obk_`W^Ws5D`iY0O0pru2puJ61Bw$B5hG8}qa8%^p6D zN-|3w>MDLF{t~$fQQjAD%)NEJa-vmpx}fo%%e#J=`)*C^jrSjSLjMo4@}s70lFYt2 z{i6E00PlmKpFez4EyLXO%|r1}x#i*up14RqI*Z274&tjbw^W^?=I_R;W%}C~3N|v_ zPLOQ$u}!i!fWRv}PUk^4&IL40lJ)NTtZRGH-d^rSJa2jQ;_>rp-mJ3ik_iR)$jlJQ z2cOzn{)g8WN=xqF%YCi7ko`Tj7;mz@Ns*TOKtO}R^X{`p)txW}%scfXY`#utyDgd{ zmgb%WS!W*UZo#rluKVcT15)tyW%Xr#+jHwx=XPo4rJn5GuTHLg^bW!L{i5LYc;;4w z7AyQAQoG0DWi9T<1@RwJpCb*~WS?VwiugWR8M$i_q36S@2Sq<$=9g44Ki&3R^4rYU z2X5E(=LHSb_Q!-Z*gCLTVYb>eH{(LDek@QIPv0zkdu>2q_VZ$BXGqXvUB81tzNg}c z_Sa3$w^UxetlyUpW-mvSW!sV=GMGx(O&cDo9ABxmTAk^8DTC;6*tox6Y^Dc0e)kK9 zq5}(JIT_LcIcxIU&AoVYuV?sB((tEb$0L8pPucSmagltk#31WBRk-tkkBI3cQ4Y5{ z-xQALI-wiH2-BO4DrPr0MIYbex$zO2FFLpwHQ3Am#ZeH03ySX4aB9KQj1ygM zF0(`B2|AdBxO*QdT~3+KOEC$Tq`Vh2ZZ>K%g#T1ip>e0v`JPN7qeNG3JAOv^2uEO2 zy4T)!mfJZDECU=+NTH3uxf&wfsFqN*Y{#T4aPxteTNXxQoq8o(M>i0Wc1LJKPi8r~ zoHFv6vgH(S)b^m!6}~R(6HT_XI>VS;sbRpMMN;vUOGsRigmq4pZbFRyzp6RbA1T~&nmm{P2=Yaj-|jXpLU$QevfoRw2aa)tbkWK z<%So{Z+QU&GQN?l#@TWS32qyd#qGlLcNN9GPP)XXD0z)SfFbq%vmyb5&<_66SNc1~ z{m%78fp!)9@jJ9Ll~U;v#}yJtM`rVwJKAij`IcUSTI%LnnbA+)K82cFD0tm{z4QJJ z^T#b?#haN)nDIOKAu)#se{ybhgujo(_Pb&(uhI3~_+2G>;Y#|6IL%&WhRb|cT_yT( z0%t>1q)X%a$o@_Cd|>hmNogT>zR}q#Zfu^JQWY23RI+i6OcPgtFqMnK{f%h*7NTv} zZLP(jZRNVwRM#Ij`E_y07z5hNtq4y)g;{6!#+J>}DQ`HH6^@O*>T}e$CnVD&X5l4H z7CYLMeS){wLhod4Xgfpl50K!W*;G0{8VWn!+61^4X2{Xbmg^I>HbzgrEP3$P^>#q;p57Kmi?(9)Fi z+*bUul2+8Oe1+HXir2v~$)2goC=(~Wp1)ho+1x`6BaU0ff_0t`5UDN9N>^tCG zc{%ICxMU}+dPwMV6YNqHI`7P|U z(3!h`l$FyFRod{NyF^v$($`z*L6h=P3y#%QX%I)<&c#q~-He2u#}PpTt0I452CIGs z#}k1}6K{OO&*i5L8U`*$84S1IGJhQ8!tiYq_PfJd=rE=4Ni|$W*V&Bh@vVrsF-im9 zUQLm-n5Kn#8d0ecr5g`-N7i1SbXSi&yzrclCPW>6>I}yu+Q+_FT;r->%eN&@r*V4m zUGdMg@k|%*JlPQR^-Y(d?E9h(7G-;*y`d$ns z|Mr)1KzO#&k1&<9Pq(Y7lJC8!aw?@5i+S)ToPQ~j^!0_gaI(*sw&ky}ySh#vFVC`7 zB@f@dI{R|F6aQCo|3jQhQs9OzMbMHUaOdt5U(=bEiA4&PKm8ja$0P!0HOC=?Q)M5< z-X&9^DQG?!YnI=5@zcLe{o#4r!w<{%J5QF|zH)O<7gjw?8`iw~Fw%F@_;V7!c}()^ z;)P$w4@o3VECl{nIa@5sqEdxb@`Lnr=cPjZm3Jqes{>G!5}3x~Jfw_+;%rU}p|c$@ zMf7Y$S74gziMqm^iwezg?9&JeXmeMV2dfxZZAq}Ernm_%q{gJ6R#~jt+1tTHgG8qb zg6!gW3$pg=)hMOVR7>3tcDm#0yBTJcudyIc--rs@#ih$bc}P`xh0uJ#H@?`C?#}eE zOWlxC?8PVRgn?;VrS*}OwM-lu>S8o#ahBeT;*KgYb@IF$Dh;Zt7qO(S4cdCW8O@Si zhdtLL+jAFt6*J!R=SlpHkdmg+82crBnvzUx8ixqNYFc)7JNK0aY3R&K=@O~xWpt`o zY9?s`r~)s9ii-PD4gE|Nkx%*KX&s~7%Hf`lQIu$ea95%)024&VipRqIjbbc4 zn8gaBgSMhIhH~uNTdatBuC@0)U>OL7$7~4S|J(2p^6$&4Ffc$ zonc}fl~m1GMdTZlicy2^)`Aw~5O7CD%r_$xo8d43D|8ye#DKVV8p93%ibHS+L#*U- zO!O&{D;jbC6q?J*V*gf-@z~*S7Ekt00cCcxpQZtNrNNqpiBCw8dyjym9*eUoQ*U>-v z)e1}x9V>APCuxq2MuPJAM@N=wMlS}(hz#~D+nnAEgi9eQh&ZS1G$ihWJW`^Bm&3%x zUdHPTXSxn&xh62F#$01Sd>BJG9YnpV0h|h;!pmUGF4$%y$o(`@@D%(A5e)*cYnBrm z?Xiv(iQ6THp!$isru~p(Z4y=;ZZQoymN;tv{CUdB@%HZIgGgdf+&j|IT36D4iH}qN zh>tq46#mheg7GkOA|Kq%f5gXm2rwV%gdX7x&<{`1kKRt-(ilZ5RTB3b-A$NQb?wh5 zm7^6xa*w@Sd!xx|K8PnPBnfiU_@TV9fm1Ax#|%$)^gV_I6c+Xfg$TzI zc^eUE7Oej=1OT8;XaWKmBLZM=HAmBy>hmRPT<&TO&64jQBsCh3PPG|{WEMB|nWV`v z-p)4BYDm&=Mg*aT1sx*;2^;trTo}f1(=uru5mv7g{~o|{)Wn#f!93+qzgW=q6}UbS zE_e#{@R-QBh~)4m%Ca=oQquh9G87Y>g2+M97)UJ782)T;FI>|X{yS#C8YlYKl&T*o z`h!|b7!kaj7v>0cG`h2HcLyHwu`Zizmw`##1LlW;Tl1%d%|o1HV|xr2t;Y3 zQ+HNV)M9hyVoT{_>zC&W^UT+4AZ?k8ceda*%Zpw8^dTIQ!b357ry%9*7!@eiumGBo z7h`L1_tcU_k!DfB?)q8Dt!&N3Fr&rXCk%P{3mQ%frNUo|l&lI3zPz%}Aor(`0m7!N zGAc7^rW&$8u3IeeWW2dV;3b=3K||4!P^<+eI;?6i+>K@QgXIwinm%f3HP2W)#iF3l zqP}h}vH!udk7I2Diqy!iPGp|P$2ltL&UK~H8YosKWJb;k++h47_Wjqms`A3m_*D(zz#Us*V&aMOFmsDUufI!O zk1ScwRor;qRp_knS|GYH-CWVmeLaeX+nViBp1>o=r4`kyb;YloFT+bE8{hrW?V4KK z;PsWZZ{IMNv5PZUQEs#s|4OW5m^no3;Gkuz3%=#_U~QUfRkm#9$;q<1iJktyTqw-G zh#zZ0UH520o**$;#bP;Kt-yu`g(KMc0dqUb zpNZv{Cr-s+XFb;MNy?5nmHH12Kb~tAv_+^`$o7{!zuXcp4Hg8P0e9*G%@ZIjZ zyW9EF^?AW|uzM9+WP7B{@rkc%1)Iy$q`mn34F%qvv~o6&q+Q$yR+PB7Px+CsOdL7- z4erXdPuwNp`yM_!$srl7@iu59c*bO=+NG#{H$4_^aRAP#-B{euT#DXgdAUCQ{92`i z^fk8jm21#d*xrOYvBEqwcscs!*2kw#?wfb1x6162*mhQVOLq6mHp(2s zbZer6x1tn0MuO_xj!#Mf(VD3Zw{4k6J8VdnG{`{D{_kGkiOuWtuWoI3Np))Ap*nDb z=G#{Ck3lNbzm@I(e03esLdx$NjYn(_4<7KsCDck)|B*nC&r$ z#*t6*%D?jdRsE}@`ats2FYV4A7B3Hprf(~B$MX;NG6;Gm|37+WX!nuEt#_KT9{cV- z^H)dl=q?%xuf19KX=S(1BFNC?W3?){k+zR9{9wSHOH2Eg-mTv!B1o>+J14(5ioJcz zRh)`qBX#Cu^c+ugvWcwZbTP;$R-0lbPaSUZ9V)_+^fbQ;CdTH<)G*1v^=0E8pTa^> z@F)0aHy}FX%M;g_o!%O6(LwJwcTZB$J*P?TV=s0?RGu7tA+|OTW1oBycP)^!PR$=^Wf^GpRqWb(YrT zQHp>rkVoY=kcw_&w~6;gXvGg;8-$T7uTO(ggeSlGG}3f{wb(v z1ywFJSNFP0W}hSBwJ`E<0M0<~C% z-)|1Kz(Vy70z1E*P^tvp~^34V4B3igxiLa#y z{wR9bXLeTf$0+vd+n1+*v%eAhqQk=(!k=V^EIf4uYOo6LLAnK&xX1pzKYc^kW5bqI zV}CwMU1(nA3kiSxETAAfyZ{{N7`oZ184kd-0f0(1#c9dJiz1mE- zTp@Ipx5(EYFGMRt`?G0wV|HYZ)<(!q8tEzq+C+ewyf+uOw%6wk-;1t?nzj+kd;2aQ zS4;jve}6c>X_xHt{pge?X!M;*x|aCUt4Mg`Pkg80hkq!_E*iTy(K%~4v-4-^p=FoY z{zf%sZ#1Q90L9I6jvKwl-vG;tXY;`gJ9sL#;bU7-;x0pd4Aw+|*2zQ&5sNP>c(Zp0n}&E72Wz zb&;Qeb&sl^wG-q_`(q9V&U`AhA-)?bbeUV@0RHa8 zpp5TSFc3s~e=1Q!r^I`r_*uu*R5;wkLz#;(>mU>^`{RlT!=zwV@ozZ|2V^c?kC82M5fnXLWR^62klmChR0cNQ+p>gqK@LJugN_bAz_1md z!Q98<(Xnzh;d(2BDiV(U!ki_tndRDoL>#eq$BL;~S=jd!8G1-HbpQ*-MdZg=RIDy( zVx!=zjdm#*34j6Q4*}V}F49vDB8op4!bFZEBn$t=p$^ zVr?k$oSN_L@mG=i^VOfXr+q872GKj8o70ZdcpFapNteaP#2NZ|gPLK`G~`5h1DYj9 zaEPk4HaWzxR~+zEogob)0=-Sw4B!%MIdgK5w*Qfg&}pKYmG|dtclt0JcEC98DlT zriJJcyCkV#Pf8M<2)cXAV7y38x3>8O7XsSSqr!VOm6AlmkyB3j;12OjvBrT&(36+? z6kgF100$z!3vTp)BS{PcV&YC6QYgGRI~*tqzU`5Qd{sHA&InO|U$RH?E1TMXYoOA? zJjP(}fFh*kg#7}i9j|STwe^T+v>@rDc?Sxi0N7?&}L75Nk&> zT%^vE9JZ;E!x0-T9SlUsH#s6s{GpT?MkIcH001k{lB~u?IWiysgNr^C8;7RBPG+xk zT(`>3isR(R3R{N48;Zv(NfH2-;*Z=AA#s?}w)&erUI$WnyK3i7ee1{SQ0cd}!n+nT zt#geX($(HoyLUdRDL$E(u89zKwS*V34>$MLq*v|Pe+#6vB}kqwC5e#*)bCERhY%uR zB>0COMgI?JcNrCR`}U1~f*5KTy1P?KI%epS1`!qM5_OP}5E!~srIii=>CPbpL_oSk z8l)RZnLXG4+Rwf2{j6u-`^7%jyqOojwdTdF^E~I6_sJVn5wvTDRW~w3-%De7G!I$yPw?btjmz@n_=$m=$ zt7F<1>_v1K2PrF?lJCX4aXia`YN&PhiND-PT&nzWxOiMm#{ zBO+<6%H+q;Obn&Z#o`;)GZK%|a|iO%OPmEo(F96cPTDHg>L{XMn?qrz?A>d`DXt>++m6qgPSIkUtxzwM;pJx@riF$8W@JzOFlu|CEks^QSegIsi5M^_N zhlSs2>tqRE&4~}jNR?t(yL)(0FtO!aLR)Wj=?c$8VMsUOv*oXH!r6(ePQeUU0QE(+ zbFX=t0xAqE{@=e-46d}Jtf{j{%Do`z1r=GG9&#W`uewKm3$#o1X>AI6wt@>C>SCPi zqW{o`9|Z#}7%Lh+^Y(f8*&d{lh?WynR`USwSmDqZgvg41za3+tD=@xm{xz@=qOKBYr1FN10G z>NQs=ew7NRNH54qg;y2lrkUl|2VK|3x~~Q!i?ybaw6M6eVo|hYkPTZEwao5S<>^*6 z&LLqD%iR#g;XSjY!3mMog$c=1a>pV_p9Bd_s&Ix7~q$C-!4!nVM*ELUQiWR_pS@n9^DD9{v z8rD+5+tgP=&4RD4Pn#U7Md3PhcyCpe|WY&9?95!~XHXcal zTg-CtS`AH@F%#gnDYQ(mZP z^IL43^YI9dHa`yXld5+{D40?CV9(xB7^?hiEvn)%2=T8; z^};J~V=vUjYJPvX9gJ*)?l$>**Iy`eD_1${F8@O8G0|;0DlY^P8}Xt>BWNbO#Rsrs zY{AdAdu?AAKi=HbMHfEd?)6UTjrLW=H5oCbF7^#5GG16j0D=yN9o^$Mz5c2MS(o^q z^)ZdA2+m@9L=eisXUm3OzhjGj>lkpGGddx)x3$)}d}Ti$+QmN@$H6f5Vjl1&QsdxE zMn;4?`=8<6KZ-GZityxh4$N?RcKust&q1|r%h=$v*8AXKVcw|gLgQIhs7)~RBq#oa zJ?x<8JbgPoo>+l5%=8={FT0tX!W$AiYV_9e<0@Z_i;G6Ano@5`too*#dKg{aimYB< z9(^d*uA?pBuaAwD5==5BP)0;;6})uJ>i(<)aWX~je5_d4Wh4|cLA{#gQ%8O?6PpR> zeoB9Evvw(w3QA@~fpOE0u$))a_fQH*jTn zbty4xT1*^i8QX-nDqobbO^ZW-C(80iV5LbF!WO>lP5wqNRl)Wy@o<4=tW?>dif0m! zOTF98@7l_}tGi&UxWl0Y&ClH|CP#5~9N@*m0c5T~j*68`YF8$xp!O(VPtBg;SrBp- z(X(hj?BMYA<+iR>f%+$)hA*e)Yr(p1cpTh%AbKyJ(6z(?dsV_7fL)c{<$4PgY`TJ9 zwO?ST9CUBj5s-}tYI_B4A!~JmZKi#D!RJneuGxd1OGa=inaidec7{Lo67Z^!_kCHg z5jt{up_{l7_sQNO{6+t!qq9Tm+@~+I+NJa4d-FS`8Zh+gS1#k_7w<>DXlZ6Qbzod4 z=tEmOdab!PZ5$A`;e_+hk21GC0*u0|(1Qlaia~a}2aK-W>ie71p@e@Co0c#3Qy@#- zy)F%#&-*rAr;CWrqQ&wZgKG5=#@r^x>y$c;7{p!G7pp2 zfsR43r|?Vb8ex~?UvFJ0(W66%nHA#^|o6xi9 zVv2_jRQGU5X1|at+B5X*GwvQxv8d&{9E%`!+W1}Kny6?~tFGqxuO#_U^e0-Qhm5nY zC}u=2{;2t`k5jH4oyPAN^_DURZnY;@5ct{0l{{vpaO0WjB@;NN;}KPXBhQU$bYO6| zv#uvth8KK<*VZVM;0xH?GK9gpXf;Q}nF_nKJWe&lY0_hA9gHb_w}O!2urTc&75 z@~LVXnnAEexwuvM^*Z<#H~fCmL}T%zP$#I zhn74_v>e9JDh_rOlCPZ9(V)3DQqd8>)Bdii+kY=*{A>-|{`lL&pg(kI{764RLhL!8 z3ck2?fS?EW`2))HMYB3%mKt4g914nBJ-^V10+JxYGq_HzRs{JYj45qRo%vet)6R%T zD(A*;1n7-fUm1B?wc`BIvovcwH%mP;s5E}o^B&2xWSMYo)Q?d$21{CG*Q+{7XgoY| z=m~B9)cxf7{gKz_qiTP&_q&t|p4z*Q*!QS95P3OGc&W~wF)m9u$%*KW!i_&j+GaP{ zzVRH8eQehLM_2WaYcbOF=O1O-Q=(c=_ePw{&@&tTi$Ulcm;MG$y>6vRqSp^e-n90< zc9ilu{G(i6@5Ay(OMb6-vC0`=!Ug=%rILdCRz*DQ&Fh3Wo457u&+4RkLZPq*htmd~ z0(?=yb&Buj!4v1Una2K^@BRjb1ROR#%tj)=H?H|ea)?X$9eU`8Fd?%Wm7YuapJH|M zwEHIB+c}qCFB>Do?Qkg(6qg7V2?Uh4$>Sc*OO>Gb$~P~vF}) zypMX6Sl_+t#ChLynHKRBj~MjG>Pi%*!e0UsHG!tkgs^yDWt7#+{CF9ZaH=z~C#tKP z@$NEyhSP0LK;l-VZCFNo(&sJ9HKL^J6AhS+GRTpt7c3IQwkIRXSQjpU1IJwGW`?G( zO$e4<@n?Exwo3nv>rq;dD|*#Zaq3vSyJDO#92#zb?;1vICq3^^CP>p4SVPw>@Q1IpChNVj7lA3z3v^FD( zFxMxE^rpG?suADs7r~5@2f7J-6ZTWpC%;jc3Zc&s^2l2iaE91`h1gukDZ8$k*m}@q zt1>ILFzK{d8(({|yj24s;%=R~{8XDmKjzyl?y6Zwl7NLb5$Z zd)E9DjK|7u$M9o53f$&V0w0xtsyliKDEmd^#ffQfiY)!Vui@aGow1BoC*k`*AGVYc zVr6HOxpy~nt*_?aw1(m+>yw6Hf89b8)%aC0HyvO=`%>HcMpa)*aO*3D0Z`A&`!98yqy%sL$7kBPo=4xH6K+Qn z{w|XOwn#CTq{_Dd`6e&Ka**U~&wV6)zRxjr$=yy!?e23$QxvIKujqsIT>S~*_Xl?$ z`*AKgFDKpo2mIPg24EyW6v;{=bSjk;m;@s;#NNl@m#^_rRy6+aBVD^2L#jgR?yHn z-nOp1E)0=?Mi!Y&RAy%skdU0Kq~v4r4GW|M8~eAL8cCHo$L7RVwGp$DOZ@?(_K1Jaznf2DclO4gfDBMvK6sK`aPwlTV}W$DpdnyfBXAh}Lx3L8)WpP^>TJr~dBfez=+z~Uu!Kx0@FPFux*``=aI7XpRFJDi zB#i9p0|7jaLs|KORpdHCEZzD_QQrHKU&z#5x_-KSQ_vcIN4&LhA8^^!pX;nRSMxoI zTB~Q#?|As(lK<5{W@af62%TMm4_K%zhurMHNS6bt+r~@pz|B{q_$p>sWA+t#$KWCd zvug>6J8!b5-`fY`1JAUsSOU%-VQUhf2-G!$sS*8HC@#$rTeQ-8l$*9&2QfcLgW= zvCiTn8(hH4mBL&{ygG<;kKrq)jKEJ?zs_IkUkrS3^LE-AmL|xk?Vc4GGOXohEF|np zN%5u3Czq6Q!;++#*c{fW4lb21t&Ri%ZS0KYKI*%aP4Y0KaM)iFJUsTM zuLYw3y1!d0YM^BtJzP*&rlGaPqEk`{Yz@G5tIyaRtU=9PEvB=+mTq&L;CY*rn0dUW zhOxR#P=%@T?4?BrTLCh0_3#t;>2!=sIQj~R^H|362cVmP2udd-@ejJud<@CpnzXO+ z7Ou8@TFtFkpHn!Zz&;2|*J&>#r@B_#TL`WXj!68LNq<|Y1BJ&1ykBMGkL>wru$}DG zV3$FutEOF~HEeG7DwBH7_Fndh4w4x^5J~@A<}tfo1x{^9R+6Do^m3xBODKWvXEH?M z!z{p%G1qOcgOoT(el52*8zavxMY{7KIafUE+_ofW;3&aK{(T;|;cw&FZ}1U=BT7=f zEwv044FD@^h#?&C8X%jRpm(p3+Q%x2*tb8WMlFHp3naCrATD|t!SJUE560(<8H?8I zW5&Q{43bL8up{>Q@3XeGcRmxB4xD~wYa3<-ph9Kptijg0Tj!-2{Z*0$F@1@ax?yu8 z@7~t3rK9mE6Lw%Btg39pK3hib2B}2txGVj?KrA1Rn=rj_FfB+MHh(aVuc5GF%`f6$ zaX*9H)TSmoQlZekkj|`uoReY-4Y6f3mh}KlR|;+SDU}#nOp%Ay36Pb$nzPS@Z53{>IqJA z1-2Hx_@Zs;r#wvAz>fX`p_Ai8Eh40L6ZLE?Ta!xkZUxbo{!+`pE1ebl93&0 z!{vURMiV~vtL&WK{p^spTwvRnT(W>8b#9U5s|D%Ll9mF8$#Qg1(b_idg8{P5qi{oM z{!fiil70;@ln&hEH658PPTpVAd(kUae`4$+tJ6}&K~75WYfIH{M6&XV4R3%; zkXK<+Yw2RxK=DjNx2rT})<@c18iWwb(Y4Ve9i??XFUcm9A9OjzOr(DC%ndAeia@Or zNo^^MOtJ}Eyq)tudYAq5`IAlE#$G&*tA(0xS?igqJXRv zsl(O7bCM6@f~l19?)Wr(-I0l+r?3!d4jiWuxRRciem>{+bBtw6I?sx0N!h}(ApXhh zoHDBIFWaao{=eF-)n7J=tvE4aH#2E`Iu4+DjhK9_Qz!n#Ru$b<%~HS`G`5$@y|{Jq zu;a20KuQ-aG_%}yF7Hj2Cov!PXHM5} zIyeP>kVC6m5AO#;l7Ed(DHS6~d`{WfUc*s|a@jf6@^JU-u8Rft&YSgq>7V|jM{BlH z4>8`p$8nt}gSt$)uXDR%i{_E1YjpVBui?0OE0Sp-y6_cBy)H^^HlR)rC2bW@V+F`I z3gbkA_!40dYZ!LZjYgj-#vb#sgQZpJMk0$a9+mvsNDlJh(`o&BtgUtz#Kez(hjzxL zDxK(!5z1T5C`!0J`6hjvz{(6KF$xk)%Y(!nL6SrWJ|yx*1F0ZE1ZYU%5Gkis0px_6 zuJ>TDD3MSfi9dFDA{K}D*M(R;7-A=KxAXE&IpI%79_S?pk^VhC82sF<7w647AUcQi zZkZG>m-O!_2q+2@N(2#*fpplYA`yTX13D9HSoE?A`~V0E5{zd1sfi@wOSq8C+aJ;; zzR_mEStlNYow*`!W|gaBt^Z^s2-KC5aE?G_)^O66N%gE%qmgu)xdigiLwa^V20Z;5 zNF|NDU3fr|B>Y!X?@o1$O=N`yvtUo>_l<%j_>PyO!7L0GAj0Qi1zks1d+AF$Et7^< zL6TM|uX7q+CbB}|B)&Z{lc=Le(W{+%GbRRfxnsoYd7L>(sReFf(;`gS?D(6mTV_eT z+WV7YhH}!&Fzqht->$U82ofhaRT-HOe+~gQ$oL)G@skQ#1=wOD+3B7kb!3vvAM| zX|EHSR5OS+5=pRsB8)k%fyCufPFm3fj&S%Kcc2ZnO~~&;4_V4t1+S__g0@*6BnhOj zQ%$|*Y7m7Q<$O>i2S8DH8E8_xE|@0vGa)6kY9$`5NEnLWCo=#(5(jEoQ{Ckd=mD5N zkJCP<;H*07>pRIhu;LU%h|-9Y@Z}2zeqX6LW-#r>Sw=OAh>OgP%48d#;nXsR8RLam zaZck(e@zzc43@r^B!FW?2N@@N$PO~XA)G9eDHNBTt5skzZpNF~ZxY{#CS*n%$q_h9 zwTm;qW5<7S!pZuQkR9-Anu3*R68_7bLPd=DH^s6y(0&j{iAYO{>Ga+^kdUJggE8p+ zG8(6}oc}SoDn?~e(mqPIXB;4G&G|%Kxv^IEw~bQ$5g+?Ic0*XT0cy8~n1bgNF7#gY zH<{uC4;Fkhow_of`B@5Y9i`tSmo!dMA_XTW>k-~P4YfLHPZJe!cdcUg1FzadJXTtD z<-T|iWd;d8E0c1U1Dqr5`Rm%VX+=m0Un@P6^FPzbt-V;SrT9KMgtX=qw$@GZ(0{tB z%T>84?M%Bk&Y8GJB5$I%>!Dg}qC;^;dnzG-d)`I6#{vf$fTz?R)+kdPY=GeDntMue z%D4*-0!}aVu1@uqCQSM6YuY0L(0A0*^~PFBruS?b!mHJP5gon9pJ6|j^f56aqvRAY zmAXgOipe-;aa}QUGnItg-!~7YyzZi$bmuU7b*`svj!hQkxo_f01$ceh)j}Bsx8{t* zvG_J=JZEDOH8Q}T6MGQ#00H{e6m1bh^(3MGSsazVz2|`$N)wZdKYQOo0c_cB%9WBw z>oRVs5R4)8e8Tg`knQ}j&U>BI`bu9`mh}Ux#}W^PBst>6A16de!;GHweAua&dS2A!2Yl46OC!@{`x0Wt`1L&$<$Yw zr|}(C%q$Qeo;?VDXA%S#RW6%drV{Wnf0Sa=Lv4F6*tzw)Gf6+d&YE+?8eP)hLh;9? z--`AeFiCMmKoRkHs55UU$ZC!M^3HB-n-LyA#pF9gzj0* zxK^rz-e^C3>6!BK`2`1*Rp?P8%~Xld2TA9@DPB?!eZJKoH%^hK(LgV2&X(La#zwv~ z1m2laT&Ul)PLwt;4y<1b``o{<0XO;?HnNXWw@x-Zamis)XQ!=_^3#{{zqd*`9jARy zStfnr?aYke;}rRiQeNAJw)LrbcyRI-yZ#+1M;Tj3ru(4--Q?%g08Uo5A`_H-s^bqD ze@wcRU(Q2)inLrSE8V+X=I~|g5Vp$)N@qjm>gXWJkQ7!ND`OlJ|6>{ymaJ6qrq`G? z(z(nk&Cx+3hRtU^o~F4z#4WqLc&Gf?5Hahu`zJ)E3H9?${o;kLYz~dOG81;g`r!TY z8SQf!#UT@0OCKNEo5M~-j05X>{ zj|h}@U!sjynBmx&ZB>?v3I{N&=P}|nC6IC^k5$HQTykhmg%IQcB-IF4>)x%=Ch60C zV4!>CM)R3*S>*n?gNP5_{i}Xy8E+|N)_1uNDL$~~=wIvld#U~(q#EWib(?G3d>eFd@ z(#2eE%$3(oa~@-{&J(Mgd?;53il${8N^b*@=wjSqqs8Nm$&%tXOLcrqmc}KU7eZHL zdtG>S<;joT%x!QjtQmF?j26~7^vXn`T}<;pT5<{i8lC?;m%f)0;5}G;JM7VS<(%fg zX@khekZ=v4D10dj2=d4m*horIG;P)nE{UcqGAHXE48PF~JibNsG8G&2shH=oo^{I% zQlEo3667`2vQlQ|Wt|y~2^N9(@qc`;-_I;YNxI)XfWSS?#dF4YdFQWGBXk2;c5 z&2z2DK$p(@yZUeWSHqqp)Kovx6oKX&E8c^qZ~QR(^0z zemumDp_@+9(}~f0sKBC`o8h~7(UbnZz>~Pt^pIGf#(Os{= zloz0kMI_SPy^q?yKE3^FE#GJVw$JvhU2^?nl&WTEAzSSFcK}=~tyhZ|3p64KN>z19 zb)PqU?fT#Vc%P%=0F2^Us5S2H7HwmbeA{}+sedGAxGHC0p1Clx3EDw1nC5)nXBfuc z_}-c|eEf5G=}G6*0&tnp;F7`fEw1@pW_|RAd9wYZ47F$oJMkt0MxTcUuzq6#6}J_n z23RqvcQe@e4Ax%Pw$HaD&;x213LSr1M8)#nHtst7Y_PYe*Lj+~d+n^(=V(@BZ^`X2 z)Z$<#Dv+GWBT` za>{5wv<9}x?d=f0|73*1W-dj})?Bnu0Do&2fiuV{S4R-|@wk2b!D`s1+LG!u;~pDr zFyKnPL54VnSGo=={0PHp`AOsBq;p1IV}BUAR=CqZIMRvQDw6Kcmxut~Na3FvjBrNv zZbmWrO}^U%rOUb94_vd}_$^he36>390jodnlGp@yF$BG!QeT$WOnavvzj2j+toG+X zX^1`UPGn=c61psX2yUfqV}(~FZi!SjUUlN&`2sFmt6jLX7;Fs8%%9dpI+`Nja;+y3`$G+5SHn1<{Q7Ii;!%8{Uv|s_oVF00^5l(nJn~qf!WAcZO#)*Vj08Dho`syoviE*BW4gLKE4;) z6Ge%O9lg)bQ;&v@OCvSW=AGOO7!vg~F?_cuG>$k5(Gs5#k>np_)tnI1oq<~w^6k<0%cj3P2@%`3II>Z%!jE9L8z+5)n*qui zvgQcNc~s-xHNEef`rNXe`CH2VDCF7r4QG-rn zsW(GGwt1|Z<@wbq9lqDjE>kF`N@ia3n!V)rj`{^BFL#=N4SqLwB#hQCs!~{Np$6sI z^cj4sLt}=u=PNT>pE>FSDE+*)L%;Mxp#jTBM_@M1kJsM-SLb^_Y2r1Tnw}p(V$O8J zt&8v^-4k&l560gD^)#}d&10@SSc7rL>#bCl_)NYjmD9c-u))l(SsJY+_2ViUr`wuf z$x6*Ub%vK*EJ0vyRZXRmp-?!byJiylnE*6}RZnKIj^lyC^(?C;LimhT+2XD3a40U< z36xl`!(dg9Czxm0` zjaPn9wyavQK|cS+FC{i^)fisDtyZq$N^DOIdECphtuHMHgJt32X5nM@*3fZ%evw>2 zKcfb(iHq9sYY!LCF^r{@P<^hL_m>b1j7+(ag0`;zK4lx>7W^s1<||EGTdhka;l|F( zwv&;Y(MmftewPMt+;+dt&G1SnV91PNvX+8w57te>*Cx_MxT8}LhOsj;AlWiugO!VV z))KUL&+WPmu*VQr8eiJ9!btw|x+`np4)BJ7h(zUUd*sICMS35vWYt#5@_3LnE>hd| zD_t}GB~`i>OoRzH#OfM+Gthrn-3`VT>aw_QK%V+>JpvV z{=oDyKk|-0vWr-DJy>dG>0^y2%JwXTfF78c0iA|Zs*kz~s6Hl|@@l4}H*lw%Wc}+J z*~2&z8X|Gbx?U5OV#}Dr{>eEDJjKJxS;`xJ&*Sl}OG!^*fpD}*xedZwnu5hhm@R)x zgO5L04)aU2Dk|BSJ#AoCPNHZmRy8P(3W)kDHAseZD_Aj4_J*zVMzAw1CtS_*sGM~r z#9i62voWzNF;2V1$1={bOXaD3XX;hFOve^^;pi16qvtM@>#S1F()11AqZ3>U_%=)j zqg89XA#5qtjN>VdPRnm{VxJ0i&S>eck|n?7+@RDa7}_hWiF@;86%js`5FoP-$wqY1 zD>dubsvBoan%LhflOD2id1o-EYFCw`l}J%uZcoxR={^V<5nrqc4A*sJ(1;p-_R{^6 z$!<|Y^k==0%iQNs(JqGf8@-+Z202Quza^HwY5I-3=f)=&r*`-l09f_hh_6z$K|3SL z4j4*%oL@Fp6#AHCdWTQua_(`YnfJJkfmtH7HpttTW;P7=hycOUqOGv?cyId4=I;?J)_?yS-> z=!tEk7DVhtql0sB=|~MAgm+P)5!Lr=LhXM$u<>e_PA60s#3kEWb4ELfM4O|2LB@b7cuyH(0=Bit${qFC!CM%t*_vR?=! zD}JYKA-%(_0;GEp#uB5t78idCZ=ycY8l#KL}WFmP+=^>QzPi%UIA5&D|4O z+~5N^CC(`40;o3KqCUR0p-`FW-XS?jtX!A{+LCn8`vb((&0z#Ns)V91PU3&;+4AYr z4f?z;gFcGgpr)Bid$1KDY9o*ctg%iZQ?GTOyM1>5f-cuIzBaek)t=HVJ>L=+vkQmh znA}3Ie*`SPDir$Y5XWj3f>e|U`dvN(3x323l%`-DXxY@!ryYG)&KHd|TYRsC?-MV!K- zrO~pXacOG*U}GNX!$klvN-VceqWQ`(;uSsTKf}^5KDJcRh}+ZN>DK?U=DBDP1Ax2A zlgQ%d47FDmZor;755v-*hBvjRg>)n4l)%{r$s*D_yElyt(=;!e`UOsqcnCPB3+yy@ z&=qNm&#)rk*!;D=5UD11yY?O0Jk3o6qT9b(m4A5kUEuEYJqz`mSh3VFCPDa9`h~&L z(rz9f`g=IVHRIZ3k#Ff^OV3w*^3~cJEx9k^Q{^J#78AJy0X+Mt;8!29s)GOWmmz5*5r95jsju2KYgc31!V@&2EN-GGaN z8QBHn!*e5LIExo8M97=%rXR4XIMLz1<*sxci`~EoFbYQrmV>mn`9$EWPzge@pqF7N zY_NMUcqHNOtSs>F-mA`=smc)hGZm`C%Fe%sm3Kr1E1=86PRvXtCh+zm5Ih?Q)I{Ms z1>!}bhz0@(2T-Ju0Z>Q~F>es&4OlgmjZBP9V3hEu0qN@KKZ2tLEAhc76m5kIHpCsV zB3*;|frIeptw?7K@T5HayZXJsx&8}0u*HYi6l_s!Xew4LRdWi}hz!*#2~{`8XZL{U zK*9`p!;Ce<{ySOubSvx`B;1-eT&D>_JIkz*%!%b5o3Y#@3~vGT5BIpsN`&Pen~+cz zGSF`WBJC>tvr!0W4EGvNpjt(6iIO4+@|B|1?bdkP7x5N{EZ~=Nz@}6XX&NYK6qtI6 zq8f+-Z$)Kq1?KWbUur}brlD>kFwywl(Pdi!U(5q(O1yWwcmj-sK|%NzXaFD)7h?bh zA^synE<^UPGUN)uJS(hmln6{lQVDpe-XD2CH3ZB?@@3g~{V4cFxKAFBe~yO#M5Eg( z?JJWat}n{McwLYkRv1eTG#vn>Mib6e#ne?{AIHN~fdH(~WD!_~70H-%-0Z_RP%i!- z6y)6u)F99FZK~(!j34YOZc#dkd@iw;mU%@?7#lAp1cPRCz;s4QZmLMM!dN*Hjv=x@<2Ip4r~v@J=H#CsfH1*3v8xbr_jl4)p195r;NSeHno~&UQdA$k zZ<6w$rDIfcm$*)p&;bKjj)=QNghADitsG_mR*$U02UsOsmL%M6C4hj5Sdv%LIfWVD zYwUMQ3PEa`^Lv%%bob9(uT`YHLZsLLBtu9b4v=6I#YGGwz4s_qc#L2W0>J*m4>%$o zEs1oJNslp2C%a1d_&NPGT~_yYCYeg=E>M6CMl!t&)&qgD{ZD_6{vjmmm;XaZBB6CT zIKCpJK@h;xMAG*nIO(WJP;=(_bf&9J)=H%J-lMGjsP`THyj37P^3w-4%h-V*X!kPa z9jH3^Pfi?85dKdj>8wG>R{E#KhEJ(<*+&GqQ2JbQ?c5h$Sr@gDM6$1rR}#~&a;ONi zSax#R>GKetxqsf}((_x{JBu+{*OextD)fav8*ExW7hp46BnAt`cM2uv3!h!T{q)G` zk+0KZ{v!Bbx>ZJzszrgzwU@n1kz06?t4p!%PJt1s^vj&1~%!m+O`6>QCt0ae zozX%ea73z|^JQi*`QGy{ShaFoyY~KWxl~N;U}>$~^Kz_O`IWE^aZ{$kP%fE++bXSr zCj#a`S8iEQ>I-1%cj)VlpVzNjV9CmQELmyxz5eO<3amvLqGgxu`>O1ka zM;HA(Bv_!?PwwG|=gs!JO)^o<(p^nPbYESB5<~!PQ43=c6PU$XF}uH{Qi>LaYfU0HoVhM9MHa`Yl>91EO66(wRiu z&}u;DQTs0xhQPd=YR3kOF?frGC^M{}=P+V;6%{}b4O#(YBmaRY>rfvpy3k-LEbpu$t zIbFNKN!`~_jy?g$L{T|7W}`$aqrilq@J0x=003H3g)1+DrwFG_&A~t& zkYH~BX%c|i4o&a|)dw&jIKWEEXrjfVRP&X=DtR;qj2Np>KEW!KRaC8v-$8EpQwGrB zJ)5G~!P22YFo0w@2Ui(DlqLv^JHnMh;O-te+K!3G*%(Ev9NsPT3y0!2%CKskXG5c` zLgS!Z$d@Br1y;xzfB;lIzTGx*qD-&|pf3OITXjJzbVT}WnYMlalN7K*Fao1%hY^93 zi0VaXo#X+VZ~~Ah=npdOiQ5pz<(H>!Lt=2KHUK)bU}F|HWx<3awClT#hTs|EV&H?I z706Ix!ul=2tO%^(h)4rC14^0#h|DyA0C-k2-d|<_RiHCgJUqkLwai$A+bke)HskN4aFZ>D1P+{Xtqaerq)*0}2cu#+y{4LULY2-;6O8}f8E!+$DL zXr^+1HiraI`}8NRF06tT+fY9XLd>3Y6Z8&I^+a^_U(hNYkw$6KZqZKJC6VNzh_>M* zbo(@^04M^vuyvFi5Y&ftDEW9{!>BmBFAHEcEJcZF;UfEv$4Y!RJ8d4mxbp&c@5OwQ z5NvH(9%l@gw@k98gR^M`zR(&O2Jl8>+2O3k-M`6QO*4R;W!$l4(*IbL!HFd6D5AoT zX`rNpnl5nD#5b2X3+>u7#zJj~B0)eg)1pw!;Mi;6t!{9#_ zr4<#mB8;|T1?S~5vm#9L)4Gl&HYS0{4FWKUpP)MsRyu-iex#C{^42`G=yk__YPLCP1SZfC2V_ z%v&J`=oQpI6eSsmScDEkipe4IQvgo0LXd(zpe~Y7VVM09sl_%$hVWL^0pJsKCr@vu zsAJ{>igaEC?+J`}9vS*m4M>h|~{^KPvr`zMhqbF4)< zO42n<<+>R1QjfM00OfC`&`lT3TA;c-A_k8Uj>2jEM4*0f+~6vx|G^^o?N(IB);nRE zHaN-6@Dex{_qRb;nxY-!;W6vI6LSL+^;4pbWg@UB2%aN6DI%PEBvGz6at8$*GgC@n zj@j;EVA7SR@`tDJ%9FL%Sc`HTYfOE2yJ*18AryR7nVy zS~YKVym+htJBvGkmJ>~*L3TlX$vG05wWP~P`&uPfgFcKShgb6{EbJ9T#Z>`7u zWFP{1)sjSOb@nY;Pb^t!tC=O^d9XewUO@b^f%=kj-q@ln5^unif8OLb;Nb>Jy0G-L zhrC>;Xv)H9>bb__5wU3BKT~_M8gxQ#;=AYBA0xp-hS9X$i=P_QmK;2Ch%(V_4=zAf zNuF9V`pTet4hyqxrgbiJzBo0nhWZK4$bm;mremGL!hp9eDPz->eMuY@f6cFI`iC+@ zZYe0-!t4R@voevh+v_${0CVF$lE>lz%}qR2J6MAL!LRl}uzsuWYYof{z>4;cCJG-Q zcB2Y*I(yl@HBP2qTp@hx+qd_#)(ZoL6SU|vYh|kcoeeamYavj_qb0m0{fUK(k%6VyBke;l%f#1n2mubIcpeh+*jN&hwR6gEn4-J3?$}b(s1zZ6+ z$zCHlHZ-qzdCAo2oa?%PmVMQE%8-Cqw?29WkOnzT{`=S306kr|uhhqY{0Is3H?BNp z!LIIbVedzdZL#Rf2%M_W|FiQ(E^eKwa4Ud) z(W2wnIXdQrP~(w4)^-Y%JRh!e71#LZLS^)8fAJBS&%Gi^fq5TNv^Be%HRy%2;xsLs zr6#61NIK&NVxRAQ!!v!MWW|-`+p@x`#W%I?MGe3kU1#(QCg@i4Dg3yB_c9+hzc(Pi zurZ(KtEsnj>7@P4Q*RDB{A{FTkQCmt(Jsd<3(8Z?2a+71kPN?;;}p?|pZ-$pQG5;3 z?6LPZXKew>k%b>UJwCJL^Ji5%e(p00PuqwR=#XBElN-?_c3iO5NOR@bxpFKDwtTn| z853}2+QeSdMdLdO3=5LblAIIGeTbK1pC7R=`wrE`*Sd~*N7r!kvh8%*?^VampPN@` zFwI+JH<8pWvX|oFTem)jH@9vB9I0<#4+=Eiz8(^v`Tt8+UO0*T{=dme<^o;TK}h&% z#lK|bvp;+N|B{uMmteuGBIf5u16#2#_sH;)?sK$oWcs0VzjHWw5&`^x=FC}!3C=hO zqKU|edjK#%-L8ju-n;i&&>KPQF#0xippVu!5#sk2h)pvIgZ+WW-&$L+F--?SNVpB7bnI-7xJ43#?Kr6$04N@8 zfVJLwB{h0rfT!j->BPP_JSK90`Hn0+(qvWY7b_V+*f52=&oJJ-U~T*TQG)ln=zkbW z54M=AjRg9%0W3o)`aV9??J*LVM$Jwh9tcn;+XKMy?+~O4^I#^=bvqt~t8e{oD=g10 z5qyDFwMux&4?+aj*%a~yfMO>sX0S(hfJDd}z%njoIfO6JfW-jMIIV|svs=-M6!Er~ zVtQbJyKdlXBzEYZrMZ{NmH>bnBL}d?K!iDrpvu(7S! zK?xqW%AtUq?7xi1q%1(IK*}2ySL9fHpsPbpJ#o5Jh^CmA#2S>M(D}g&ml2)VwIaC< zXMO*ccN$K)_`yhgo&aBy0&dT|Jdp^6rXYeEKGRZTAxrrGhEv}DA8^XQcUYV9@6BH< zPI>*WOnHlab93|e`Vxy%USPkySGPBpH`mzL#SIp!yt_R8SEU3)wT;cSjkUG4v7J$@SGlybge5As=6`R^?rhF( z{aRS~J-xFzwY@pHy*jn{^XJd``T4oIx!Kv->FMdt)sCsj$%%=HwXuzrq4lNFxrLEm z3nMe*N2TkzZbxol}xs)S22` zmGQYPuBsIDu=U|n};;h1~tgP(xPao5=aubWv($e04c%Ph{9G{R7ADxIL zDx*S@f`fyxM5T3%uN10QDxeAD?sRDVtn*FMkn^iB&jkOsVI?lr@s24zK7n3uyxcuP zux_Or^7X$s<(;YFfu`oShc7>x72ioqZAwX>3JG3tbG$dsPSeXz)ys>~_~7^|>|emr z+S>ZrvuFCAMe@G2k1Z`NEG!;Ae24`s|4Xmb*4D<-m8$BRSh^AphyUwSD#|L#$jC@b zOaF^giirK6aY{~3P7EUh1_r|rKrmo17Lq(=V7P#h-9R9JK_J2ZC072+RsNS%`Cm}w zze**RsQjOON&pamUH=I3=D(=7U|<%iz-Eqjfj(#w+TjH= z7{g^-=%57ngY^%5Jhq7#cn_<1qC{KW<&PMHhV9KvWFMbnyriO*ZSoso0bCxXr?46iFO>!_C|T036Gs3FY`?)X&GWf4Bg6T3N(xeBDL&qx zm*L2T)cEFbz?G zzW~BOJ--SJi7S(`@)xju0~2iPjk=0U5D)E8A&{^Fg&<8bxLP95KJ?Vq20>oXv&cZz z4uq{in}7wX!YHS#^2*e$spFvo4RFH}G}mnN%{b?*^UY0M(ZtR`2Q9SFJ^!5Z4Flx) zZ=eVJ>t@08LH%CBDXa0%K3MB&zN+%ePmVD2e>(rX^X8_^sKnO@VZ-*QV?sp}n&hK~Kpms9y$!wtu!TOBD4`;Y zvb%iy{PfpkHOrZ*GfAhOJuQt8}=- z1~w0YKK$VW|6#Vm`LwWzNK9f1k0_uQ;_yE+Y*Q2qazi2RiH8ER+-$VCMJ&#WdPG#B zY?vs{DTDc*+exsXbgl*kswu!9^`_k$6R?)V1LXH=FaGsG!pWV zh$NLE?XyN05l>hYutC!1Bgcrr@gN2ehU;tyLn{I-kOt!;1A$1&A?_-XSy?11SIJ5r zsq#IIM9?Fx^q)$?B$JyoNFEEg$5LKVl%wpWDO-7yR}%A>$jpy1%@a!*lAwcLVZ<8& zz=(L1VH@=z1_u~%4tTTzbrw*Ca->nIgJ7Z^^XLUC<_G{^)DZw|xQ0F6v5XFs%q!&_ z$S#BV|4Uzf5|}vzXb%qp!DJd_nFdX$LbZZW*)%c$35cjfCrZ(ZS~Q{oz$6Jw0K4sh zVVaD{hcc|dg?A)l7)>YxJ~jpbUOVK&u|0?neW3c64LG_07yux{Kjy*OdFW#p0BCKR;PEj? z{|WY7%a8{#CgD58a`K5%jVd68J6y)j2Lvjp2^VEE$jV~Yvd}%|bNlkpi(2=(63wVV zW=TGf#)DJrY-b(Yun#31;k-w%0RYgeUfK>s6}JVz0JgA+YqY}$zSZSYc?s3WQjR~L z2!|{N1j?vQHH^;XYIGOO;OX+EnF1o7GFs7Hw|-Y3wiGV_lJE~Mz~rw3iAH<}q5ySR z!T`Q7({DY=G~x=fz?XwDOe#=|aJYiNE)FF@5iD5;Gx*15^l?@o48`E_Vj4X#!AC6& zUemr)80TPv543=Z5)Pyd_Gm;BHnCGW0)Wa5!4eq^unBZ1!30ZF>_Gc#-2d9={{`L% zM+|W6UjR_`vI+*Wp0O(A^LTZ?&NM(0qEU~3NR!DJ4sTBZ;DAk>BOmK1hQkbk33trH z7wh!$5|Yu5du*c;05HH2mN5@XDHXV1Y_ppoJD(EZ;Tz#_0i9KSXNC58&$zbVtpoFC zRNLo{MFO@!)Erz@PtVwofq@>v5e^K@n#~2NbwYQY>uT4I+A|?Ce}sJ_ZWBAz&~9vt z?W2OQhNBzGm9cr6+v7Z2``xI-woJ60A8y;o+kjqdxLM8b*&tvBdI<0<(w$=igYlFJ zJ|Vmp9%OgxuGee?U=8)_>lYV1#uvvpvi6-7 zLkZs%*YUo`J#)ZlfChSCfh)qn2a(g7$68f6%7;EGp(ljp^Rai0V9w%I_uJ{o)`JWL zP-9s?TigO6c`}Vo^sd8+>pR}nw_DyuCNZ6+Vb(C$o@`xtfy-QjxAeBJm?5Tw6H z=`=b!e+|EO((|R`G|&J5Vj$rDWPIHRMtHjwuKC)ljPnKZyDVMa)@}=a*n}^3%}bwl zzT8|7FAxYH!T}1`j~wV(#l7vPZy)K~S@(g4q$GV`_QA*8;2VG3|M0b0+Mx@b{MWJ+B__zWnz97`w&8-*n>prR{o<0s|ona^`$LCwrGid-1n`MfZLO zLVxA~JkZn?hel1-giYGSP2L1f;zSSRWDuwz4Fq8gnh+DB$4|wFc&29)0CgK;u{*cV|N)loLEWYi>5BxO=4rBW>AQZOY`G(`|i@DFeW08e-X zCWwFfCvz((epyHpsHb`YQ3Bxr4hTSl>}P{jWqmrBhBU#0Vz*QQfB|qAhjKWFbXbRQ zD0u{7f4%osaWz+Ubys;c5PW42)lh-}5P~vsg8H_FXh(B?|8acDHxR5>3pYV|fMI#j zhl6Uki8sQA-X{g9`x6@1{vh@+Q+Gy#ADNDu+0e(MK~W{79k zSd9XSBbum2e)ooUn2-v2hiWxp6=s3ss9_xDVKBiAs;~>mFcXScc=o7;9T^k<#&`xn zfOGbYj@WtsXln&IkStk!E6GSbSY!rpWJxB3)fAD7{|04JMrBqu5Rb49?$8{GXod1v zT;u0J^q3H+R{;jm4Y5{<#aMZ8AE^-K zCjbWF0_O%GQF)0|8C`tYmpb^DS6F}ecW*=)n6QVJk_noj$$tsK0(yW4b7v5&H(+=9 zd#kX8qge#PmUROy_||2dv56Px(~fr2TWgh`$Ch@IB?mNVgM zIhPPMR+1*EcG1{Ml}VnqSDT*s7=tMzg*lIj*`Du-5G^Q@2myC;_nikAp61D)5{eMD z**|}$mYk`U1GJk+*_#A96J3}Pj~96kT7$1C5H}zU?_dwtuond}L0|EXNwl96s&{|M zJL$7~7@C`Ec|05np9fl31I@~&^N-a1YtQsqOSZ zxX2Cj#0>c~qgPwCRtd8lS+RLbvwM551(BdKfQJe}l06Hu^Z~R9XSY?0x4x;jjmx)> z>$e0EqB0SK;V^?A3!ao&w~9NEjQgSZ`n6rlwHONkC4h6n>967N4P%(O54yQj+qstc zxmxR?pewmHi?IQ)cvD9ctVaunYq*6Qb`UDN^GdsIxwWHPx}uA*s5h=M!L!5ry2%;4 z#@mv}i-opZyP-?EGb<28|5_8Ez;nT?xz&5UrJB9qN1DvLyzR@ayDN18I}?OEy(U_` z=&PmbD~!VHy2|^#xC^9_3cWHB0C9%7{#&Q`o4*sP^-5Dh4+5c%0f{adyH?7aZo zr~v?{HZh4mo5KQ&k|%nGoSVWq=)mC>G5Np-0-*%|pamtz zoX36q$Af&xh)l?S|D4E-%*ch@$dG)bld}0 ze0NDa#_`usWWWYgFb2?o4j-Th_&^ZT&{re_7LQ;Cy1dK0+{?cF%fKAW!aU5xT+GIN z%*dR~%Dl|X+|17W%+MUo!>k5(pa*xL2F$Fhq9D!O+|9xK2&L?P){Dw%_*^6)504f%h3ZBzcSFeS>c$JSkfk}GPQ9Vxv?9)@gl)79K|sZRNxHvkPevO z9MB;h<(bmU*-)zB1wF6@%is<*006sy4qk8t&``q|tkK-t!5`hXG|fvLC#ih##b9iy zbE6;(0ssyIAre9%0AL{)q9K?P0_-3RP0$AQz^NvJBJcAlR{gS9I}Gc959%-sQFsBn z01xzF!7*{edHKH`UDIqWIj4(!enFf-eZMOsB~(I7Ae1GC$Rz^dC164c@Q_r87{LHg zCT9{m6ne^yoq7AKaqRoq9&FQjLIJ!xzgbbgC5+lCqbR|`+5+JykW#WARVl&nPHyBo zY=dEL|3eUP69RJc+jr~R4;IeC?b*f++L1dX&+8Wke7Q+#(hB1%zydJ>K`h1s0LY>& z%;GEnpbWhIgi8PbA#*L+QVBh$`tW8Mz#r!qcd=pEt1z1|hx-Zf$Y)f~8gA;j|? z)Zt<^ShEjW!!-clHDFT^V^cPJk=0MIFnJ>x71;W#YeIL+fXO(T@+7jiw< zy?WztqB)%7IiMptq=OKq(=W6wAEgVK^F84+K32sJ!BE)rfY|KgJ}Z*td|r)Q-q{;`#gMzvGJ*h$ zcL%op7tGD*bWJxBL_rpWK^jC5O??mQ5Y-?gLL^kxp)TrvZWEj>l|+1>6RzVs{$?I` z1{r6$2n_3I4(MAq?7?1bqi*b89_H+g>M#O;EFfe5%G1(rw$yIQ4SwxIm+hmOE0W%6OLJu|w|MC#~*RY3(#o?Cq}J@80ccJtN+l0G3ncW^V2atnZh}@7adtq>jY{ z|K(tQAf_3Bj3#4b+u^Z(z6@W^4nJ=YukG$$@ykB(2ok=Q^Xld9xBiYud;aka|CjEW zHS+&n>g$X1{A(kC+qzPN05VAO_@1~jzr-QG**1UgI-lMWALuah-ai6k|Ek;x@A651 zNHJgZEKBo#@$wum=*k}NCT|~yP7qRK?@HhC`L6XUee^R;@!l@*rhe*xq3TkHhf*V_ z5kKt<&-T;D?r9J90e|vNFCb$c^%uACU$5|D?Dy~o_=}(HVL$nlFB{-)5K>d0d(ZeD z@A!Z3_BMR=Ef4o75AT%^81v4tW?x_oO2DJ9tzJ(^S?~Ev1o~$!`GZgRIluHZ@x$85 zokmh%BPzJB52Ufbr?yY~C71lfOZtWH{JY=uTJhHTi1`JE_JPm&Yp?v8{|EWSFZXi~ z{n5`KqmAfIQeev$a+`1U=Pu6N|KQB8m!_ZlYd!Y$-xqe@y9fa_iXZuIdi($ZK;S@v z1q~iVm{8$Dh7A#h_!q+AM2ZzHUc{JD<3^4hJ$?ikQshC15=Tzd@lVIei4M#-V42Y+ z%$OHv*0gvNXGNVmVd$BmL19mf-NLy5NpxpJr2sGEEOKyF- zwJF!JVqbP8SXQgrkSz4*VX=@cLk!`XL zRI@Nc4L3xszo`DJ>_Fz$YmCJ0MC=a5k1Ci!4;TV)&_sm@_$HhdCIqZP4zKcXM<0I# zGNvAP0x_xtKRVK*Bsp4=Nf|ZzX@&|~dJ>@)!ue)611X%(v>=xn@=GztB$J^qYbuho zDnsN_#S-0olO?zCNP(i=VhBeT0@pOMOXtcQ=}bTeB@{?O|5-}YHa^valeR^1dlb?} zGb$mo&FqX+pyNQqZ?ZQAyim^{*y3Y7zn9WFUa2OaXAky-r&# zNL5oELiJZ+hlLJ9*}RN1$6Lo+R={SR_0*!DXb{TQXb-9-!d;a`(N|&<3iexZ$IU8S zki2E~+CJ4~lv`duatkh-GOg>bZCwSG+=|TAw_kq)HTEiWPkL3Of@OLZM||03sL}@K zWmurkLc3SKZjt?WA$~LFxMPbp?r30W-$gLtE#3V{*5I_vDbqcW8yV$ZG4|LXkZZ;{ zXM%3tNaTu3j<}|SAtrev^Qc8Q==MH|dEtY6CYNWO|EKO)>WrX1*=d=9E;^%l<4PJM z2qpY^#Ebu=+G?uT)>rL|utw74tS#P}>y9vU5!Ofp@W#fb={5-NZ{23Q@L>tBNbrt^ zCc5qvyS7MW;q;EUgmA!Nd2YLBMtf?+4F^5c&rzcJ)1Y}fJzd8i=jiD4D8C3#J^$XE zAjJ<4ICR}}9^IkaVPE~b;MaOqg}1;4zM|ujquuPMOV_#g-KRG+_o;q2Snjw}Cs_N% zz5kwjykSr>(p=wbo^{R*m!5j}H*9|)?86>DS-`c%=(m;2k2qVh%T}N5pvODwQD*}0 zL!gif_@M!=3v$Hc9sq@x5!Y?cBK4}41R?mm|IS5kfv;IXDN2z*5{l}BL~3BW>gT8k zD(rq1Nx|_n*N};+Zgul3Rs5DRf?M3;1SJHbS5Al%95xPrFLd4t6QY3@k#B|!S)L7# zIFKTWZiuZZ#Vx)NL@s7ThY6{owH|1{+Lh5El1qRK9Rdnnb+3hLbV>?6_QjoG;TEMB zKo|8$5jt{kf>TT)5(7z*3c`^gW0RsF0T4z)^>HH%5P?E65Q|%^V2_tH(-mXFNGiSY ziGMU>03GtR^eF@ZHM)@-yT(aCIWi+mctaW%Vu)K90+Y9-ib)nD$5koObiM@8q8#Q# z4O%H2-l&x-Z^%oIxe_BafWsR$pb#kB{~{I(z-2ZE;!G+s6Ln)`Au!oA5y@rllL?XC zH<#H#0_yTK18@Tzn4k~?P!bB-)FwCM$W8}}v!99tB}1l_!D1d{Y3c;zBE9)9eOd$! zaX`Z?Yl+WnHk6g>@uUU)si=(dZz7~jWJ3@c(m{5UpEYYJLHaO?F(_mMkzB|MteF9d z-qNBARc1m1D$0^3#9@~r>5Tf8%A6|lqGU?xKr-QpQE+4cS;Rt3F?rLIaul2=+Nf0- zl7JS`N@#q#QkD>ERGjuJsRHSOCxG$8g@_=J3HiburFu!K?v$r@-JlW!5G8^Zl_BXI zYbcL8rn3UT0Kf3WArvxzHNfGd|0n3-2yQJy0S-HmWDhO*+!FE(6aQd^ zKrXP0cg&+0Hjtli4XN4N=GM9c*(*?{v|WaPz%Cd7?mF2=T&dt-wQ!K7LTDLV_9pOV zSvZF^;tPOXqyr3Bhz2zBTUF{-SGoZ0??5)p!9giqtMPp7Try1St80AR`cDzEA}KkPHAY{DTAo zL5C%xJY$Vs_P;5%>-b zHz7=5LXRap(LTFxV{N#`1q2;mMc{)V(?EqmED!=>FX10Oa6qz^y=-PT+u6^CcCtBO z1`b5q+SkVRv!`9{Yy$VEPKl9$}%Cr5e8RlahTx7_6~hk49pK69Ga+~y{?gC6oAh@1CZ<$fqfIC$=J zq8FX!kNC$Dh#dk86eJs}AVxc?F^PjXW5WPwgggpP7&R8L9((Bc^#Lc; z-U-tPh7**`|6~9-8OmT}v`43VY21SHr;j#Bn29fAr4zg91j&bp1=5OW7zFg9Cp}l* z8($N&VjK2IM=Nxhg=NG89?7Vt9zTR#6fF%!cofxs>q(5?tn2upiFyDAcN=!Joxgmo|o zs~d={;|dJZFaU6ZVkiS400V9y27&N^cjyHrXaZtj2bl1I%o74Da0Y4+2vH+7Q$w{} zDvU!o1hz_u#&WHMfUN-}K>Irg1Dr2-pojY!G5$inEu28D5dh$j5=b)$|M4tLO9)}` zH-S(E{{|cgRJewL5C($NiXuC*s~ZS5zy}5ZfGqe29uNpB_=h6^05;GE0}zNZ=m(ep zIDwNxBb*KDkLrx2n;Gi!D^r^&<9L70!5$) zMGy#72!hH0_^ZqPg~Xoh9TBZdS3huk>I!$h3GfrOg^9g8MeLx>-HtB-6aun4}< z8cDx`!0iBmSurOJLFDAhb;gAH-y7ROpVAyi&guD|GGqo zNn{9GvZcqwnUD;}%1lm2qYXfK3l>Akfv6X}@JtSzOu`tnnY;!euz~JeE+x2!U08x9 z2!?pL0Yd8sO+W%GNQQHmCQ+kBTP(ueJd6=YxGvy`YPu%lM5(0=nd{uLtt_RIl#1N~ zs_2v$&}cDJbimgbG%rxfV^cq8Fu!H^JpgC}YM6(1I0hw{$9hxB+ zpM;ps1x?2-#g8KuPK1anL?~2$X;MmE)H!WbocJkD?4*S_$1khYOFY!QhywgfhzGDn zg@CMEkgQIP8aBO}KE()AJyjY#C#m47;2;2B#V9a?8Bn#(L|xNX?TSNSwFleCgLpz* zr7>N_2saf7V?9=2ZM3Wiu%G|{Zj}oYxl$};RFksQ(=Y;0@B|}(N=c+d=d#wp!Pd9o zRXiP4WhGFSSg~z|)Lu0aJ>65Y%-5|$4a7psgeZU=IDm!7fF44D|9Z7oXWgWO?L_9x zQZ3wxE(0oZ9SRaLFni%wgJss?vRJNw*5Bla38PqI`BYU6RVR(on2@wLz0)dF2t0u? znq5_HyjPYuf%{~L0(jVjpvspOmY6Nr9_83{l?pV9(VWfLgV@m+`%H{Ay_Dq&I#Vr$ zU;;P5GlYl$N-6@S{S~Ig+NXtDwmpeyc^#aspL0c5QB_w~Wewj1&VxV$I9P)uMO!}& z+QiY?U)9*QEytK3N4dQ$zBvlJ{aKJ4+>@|?K3F}45CQ)4zl3-KhYQ>|n_SX4*&6Lv znN8f2I6i{_*(qC(uxbFv&DznuR<2zQK}`s-6T8pdTC9}a|8Lz_(=FYOsK5&>h}GT1 z^#ClNjoo!^4Fk}_SBu1|JczhbQr&H((Dj|djS;G?+TUGUmiR&eJ6`TJT!T0$*j-lU zU5!Kd1;vWhSxpF;x`i~gUc$oOhS1h=4OoFC-}0?lkT@FXRNej6S%erV1c*uiDS}`7D-gR3iR^vkch{6+K)~(_kMhJoh;=@)%yg2v^LerJmqRMTiZ^)Ys$Go7N9^VpQhl=P=@p z0Ki-50IJRps~%8u_Tw*evx4!C(@YqN# zBMbnCa9C$uzU!Sx>p-3k6mUw+eFGkw*T1fhz$RUlcI;_xh@0i#x&damhTZU*hhE@< zAF<;%!g`%}Th3erShHNX@EN>XT4_r&I`UK8OjR zBp{e?>t68nF>Uj$Y-U=i51z?D5 zBaKABt#H`5Z~HR@CrfgJZ~tYN!Oa0{|h&hxN7&{F~_g zE7OEf<{WR0`X+Mk-R{9|i0}==|1S?9IL7MY-f4N@1vM*(4Y0fyuaBj|NF%KQ`6dW( zz6Czx^40M28SUxt9&v#PVC)7ZN4D$J-suEq?Hvz^Dp0G5-H3kf^A2%zEzNKs5Awop zi2V+3^%>bJ4RDzaFMhx;edGrXY3+$9YmMmK{j7Av_;VlsWI@+-0Kj2Gw=ABmbv5tt zhUkY=7l<3M2UWjxkoaPSsDU(S!h=ZB6^(VnnDr08?_1||g^=R?*=@@Ntu)8lqpE~T z;0H_y_e!t?W2gpWhjFg>0e6MhgxE2uJP1mU_QIIx>XQz1-?nvu;ANiI^<)|D&sN@xQiZfug|7$uuUB{dn1WIG+Jvz9gdhUX zHTt8+5K|`z6G(NZ|8;!#_D#=ug3zBCu;#oUC-5HhBsXJbI5cK3{KGf=vCofH1BU13 zTfZGt6>WRB*QI{gT!Bb}z`WSH@A#YpZ4%;|E1%|;^zPMolXWy zAc#po2F1^h)WheCuxaiG2mk^H5-e!&Ai{(ILi`Ica8n0`5+^3q@lOZEj2a6%Fymk& z$dCg&eiUgkBgvC06{eh+V1^zU1XfaPN%N+_l&-?@!AaAm&z~L-TErMMA-p97mApIZ z^dv)vPp48e@XOO7i4U06Q26DRA*y1>k}YfYEYyYrH*gTx!_t_tMbRDvN;je1yLE@^ z#miS=02q2^|7a+ix9>=g0lI~Aftcgp$B;`FoLiP26@paiNv0aLvr|c)bV*DD2aQ4? zw_-s6?fNzB*dRX(R5l3!iFWDiQ6g&@@nOlq9}n+aT;K~mcv6@>ewSp6aNioZcK$r_ zz~5t;wIaC7nQWZ2!=H@uE0Y0*JK(%gkZ?e(TTjT-uW$eE_;*bJJhEnhO*Xz=Bpi02 zSx47_XC0RU9(uf>V1WcW5JNb!yp|w@lo6zzSX8l@-E0dK&u zgF=RYl_HHb+8EM!_3!`yF`EFu17~A#c%6pTMJQox#c4o;9xw!uVUiw!!qbIE5*Oi+ zR9PWR|2EU~g2as)p%|u0rlp|}6t|Qz0GVyNS>t%uRKkNiTL5qcI|3R7oRxeQX<(mv z4TpdXF(rT&hK6~>SPWJE+1X)PzS-HBlMZx2A4aIh-UA6i5Z?-xiaIK2x^7wq!RJjK{Bk)%*Y`6!aG4JQ~4B_J5+btr@b4hD|O7U_UyDZqv% znyBF(sRUIj>L{LMqEG>Dz`;a}w|tQ;y6KjMq77E8sD%;=l|cp)Nt}|;e!HXt#ud>( z!)vsDK8q}ozaqqf9(u4)u&`!OXrZ$P8`SGjM{Gk6HPq0fjS%W?YiS>z{DLh)Xq=`H z{}yVhyE4l`eH;=zkA#p98v-fuj}{V9tSGQo_AGG2kCwpXgA7+W09S|GS$YzeM_&@$WPMOBPL#mGIk+!QI$20l%I z@ec_Dp<{{80UJl~u|E%PxX}Yu0Fw*?2ue7Fj4Ca0WrB-^nP&4?EmgYRjzUu@=AyMz zEiTj&jw@}e4qH^cd;mZ%vCAI2L{!YPPdv0Lf)7E{pmLA}Aqc<3KRq~bJo3pazdZBJ zJAXU}W^nL4_0?P7eDu>_zdiTZOW!^C;AgKq1%(n8KKja!pFaD}b0EmFAhbWf|N7t4 ze?Rp0E8m0VRKa8CK(+vn&8-X!o&ZJ$Ceo>de5Dj!yWRlhd8u@a>C%l zAri5OH55fSXko-9GO>v_d_@1I5)5o;VE_Zr!ZmzBKy@+TDt%DM0oL#a5hP>;VvERG z1o01ZGzNoiM2rSEvJ77At#1PP8}Nh|0^%7Df8kr7ALj?iK(cR;g#4ra9Dpzf9ddhy zY$W$MFpF?}0+Q%^q$RJ1N&f9=EF?HaKk$JMei(yu*^1+vGT|+WtYKUV{|Oxy&Qbz# zoRESRd?PN+5|wIXte3u|hDMm-i<#9705{8-LYg*~MDc8Clp9);g7q2-j3XS4njAJa z6h*2ap$ug>f>7=r74r`Fp3B@Rb5Wv6< zVhF?o@92dRnm`P8l%y5fD1#5K5ElUWfF7z?LM8UGRfGhzWg>_J{~W${kQJb&3bL0fuIfvmk812Lk|*g@5b_095z~IG3Q0cohT{*ciw#T9uHp zz6p&9X(eh9G5}bj1seaThFz2El<~*|OanoJJoGf##$Gn207#A=m;))uEtE=(rS8Nu zixXy$x4h`si|1+pV8=fP|H6oNNY`i8wQkTDw zLKJ#=PceL!Rv&NC>2njFN0X8otPa7Knk3DD&bU zNf3w?{t+)G59G;FCJ2H3FT?#U5ly8ZGZ+m-~o*` z$feMA#&a_TO&m3t?@)d23?Gsx)0s}&S28Y(36{|h|9*6=7wh$j8ve15asQ(q`*6<( zps@@x^QRpvq5wUJy$OA+QFoDZ=lk$eAj3 zo-?wKU2Vevu~?Xu%uZl2@nl~d01aPBFp{Bzd30rT=7R8XIFu1^J;MH9PTTo4X#r~&N|xBb=$&1I*|159wwLR08YPA^dTghJlAGv2uj zWCGv@#h3>>{;SVw^fSa&U$D9|pfxaT>J1A#h``U{ffG_d^yXipa0eC-Ym%Q(LDHo0T2UIr3?Czi6ltE4=BU{hzq$O#1pK>0+4<(6SPAz-~%ya z13UN}x@e%fn9Ld^gaO3Ie3*qj{Dbvj|6syZiWQv&2l|8ub|4Evp$pzbax6y_I^h+n z1O|XZIJ7_(-oz7PVgKn8CJ+NMoWkI3QF7G)9K-<`Aw>9@1vUJ`F(4t;p~xa!!#&)? zH7r80?Ot8Xoo{DMSW z2$pOR7XmP6V_pfgaHx zL689(P{9~L13J78L2SVySb-NDgFJvFL1;lW@Pk6KjS+Z)CoJGeL;$Fm#WnncT}~xc zdKeq*Lo!rLGU$UEsN>;y|7APUh3gSST1rG{7Q{~U#Ay13SSn&nQkh;I1PRE)BjCj} zQiK+;!aC5yFbpQ!T-ii;O+v`Xxs=5z$|7WL7>ZnhFl3A{Siv81rE}imT`W#aI8In{ zrdg0(8=WRXXy;xK8e0mFTOx$-CSbWAVkVIP+1_s zKPXvoYT{9vMH8xKYJ%Ze4(gaDXN1x$u@mWAwj15RLgfCs=sB_xCb zXv4Q5L_bIaLb8o}+6W2&!!L|L_eCT@gw5ELg%kXPVD2Y>a*iJ9(Fc^@Rzl}U#u!>8 z2MuT!Xcp)^3h6}L|6fiJX+9$9KE~wkse%{uz!ofnJ9I@bkdP*ffe={1FxZ1n9z->Y zXn(2;4opM?x)MT!PH>JzMg9Yh%4l7U$F}{Lobm%YY(gm>#eWKDfI^}zQUzE>sFI>& zpdy3{?!l4nDNG_NS~6)u48uC$gE|a@&ozS<0e~u?13s_=GB9UyjcB^~AOookSyW(` zx@j(r$0DS|CV0~(q{Ad&0z6zLp3O_FR1ev6-s%5c? zCZn3Fr``w(ASObH035)<8ybWe-GXn41wQ;kBbe%&de|}$+d#CzG629LRN_?RDW9_A zW}Zb&#RN`u|L1~^1%=Q;b@u7HUYnaPYmG<(Ff83~oy?iuLM)L*HvB^Ya_gyjm_2+c z5^#nO1PQ~@Dhk@GOP$4IMHXttt61zr(j2PBQX33bCcEM`DW)RA z;?j6@3kHtAh$GA+~! zEp`DZyi%-KV5ehvtko(Oh0?_mvJA{P=&lmP%xLWicG#5zR=m;n?7uHX(X;TEpp9xmc0E))Q+;x?}1J}%)hF62&b;l@CN zyk4&Y|7%E`W`n+~S!!;Qg6@)zVOiwi9`<2-hH27y!sna>t#zJQ9Dz8#Ee4^851@kF zpu+LxC}J2b6c7RM2CwiAFYy+y@gDE-K7koL0rEDl^FFWfDlhXwFZC906fllkvBa@z zujn3xk=CoaR&3XnMJuAhE5@R3s!kUiPy&%D94gdU%r5P&PS}D(&Z>mbKEVp?FaP$h z|Nbuk2e1GOa1fY55DYK^C$ItsZ~-6i0zdHo{($*J!P;`~$3BG$UX#{_FH8x<{Z52A zHe)&(pz5lN0(en;y1@e)#3?>3bnpC@N|kYeFhIlLEkcR#ZeQdt1phD)^KSzO z|1l9i@DLaA0uzf1KtTm(?AAWTN`^zAZSanE<@l1tMiK-Pc%)Hc-|DDR>m~%K9>h1^ zLa23Jk%i?U` z9)%tM@gDoJE8j6J$MOoa0F%JL3J`J=XYK_bMQKhb2XigHj>TkFrY2lwW|FWMbC?5G zn5c@yB8ZzPt4@vx8Qcj07ptqBL5A_dIG#*!>3-E77t8*|r1=0ZONIP{EKk~lS zXb9XWC9e)|f+E05B>Ymv2{E5d-!uRW04B^sKlFn=wB|z7^HT`5Q714`&vhOX5UVyGORyfu!8!AFI{S4ziv=)( zLe>6tAd>D_d@DhSE4iBMsQfmKbhSyKDH{I+cr14pONLd41awn(b>lUE-*qe#OAGw( zYmfJLPelOOqk%sgkIpj@GOWWwtf;tmia>TIqruq%z*iu`Sj;qg+jo0Awl+(~e*gD$ z^Y@8EFm|y302erI$M#J`$2T;~i<5UqI(S*gEJ2_`&1S*Pk_v^J|44~?0>BAZGaE$O zKAl(#B!~mKh@Y!-<3x$0xOM+`|EBl?yFi2Ba*KC2Y}+_Zd~b~(xcCmUSja8i_JZBw zt==~FGGovv=)x69#26O@e8@-qx^0t(_?tI3Tsy^-Q#Y2Q_MjuM5ipJbyEr^EI9X)y zmy>x1uic-Y#O>zp?%sD@kxVAH;j|LOL_P&W`~$n~`I`heOOg2UTDfWax2j)xl?Sm! zC%Ts}c!QJ0PEGNm*SZy(d2yQhsDz?H)TdZPC8=AAuUABr-$bBCccI&Lvj?zJ53r&W zHjJ-Cw7r6NGrA)u`$pI>4wLH+W4c`#0ry3AHyT6-oRL_Z|Ion|d#OKp#7=rcn*kO` zfxX{5zURBX?>oQud%sVC8BBq{4?MvaJii0Hz#DwO2eN}8@U%0swo`?pKYGM>rU!F- zMzFyf-$NYFvA9dr`U1nK8-$jn)j`DcROrJ$B(uA>$+06ueuKmbm_a1eyv^S{&gZ<& z?>x`*o5y&3d9 z;0M0o`~BeaJt5qI{6&HkI6Tzn`mUG7wNtg!m$^1!|2;_5gEe;yHZwN{fw4r0K!yW= zuu}y${DUyKz01Qp-&+1n%)KMf0qn=V?9V>!*S_uFKJJ?V?(aVD_kQmCzU}`35aod& zC_dxwGOa&;qrX_yE5EMC{6QG>)^|)obN&T|{5I;hx=#f&{DaYl&`maCwt3Ue#f^q~xAsGMDBY)Ie{ZmkV^FOD>OS)NL0zhQbB9Durc9j4mRJf2~ zLx&F`MwB=)VTgYrC}z~Skz>b(27Y-uG;u%;hox>|@tASfKW8gp#*{geW=)$nD_+Fe zQO7?WJ2~bs`Gk9QHtk!OZSAha+py=)ya@+jn%A$Ny-j}+KeUK3apRbhJpGa=!p)lp z4GrBg^!CWVV~#0xiq*>F}Kh^er|4aL;%8xtr$it7Kxbo_^u!3VQzUkI#A)IeOa1cHSRfF)p`8bTI zz79d_V}yy&fMbn@I=JPQ4&M659uQ%S|1q%-N83=e{Qk=ksQ`7%kw>ZQ&;t)aj7o4p z2FtS0I}CUFBpg>JVv;l|N7K+J8L`})b<+Y^^Q+`KQuRNo9yq$KC`j&N}_OlhxN;RZ0-7wCdBhKgUW^(B>Lt^eq>{@uq=A zd5zA|&>$@pzEhQ5sf%B9k%$R6+(>V|wXz7c*=^NiHnCJ4TlH1iVjWkia*y&Ow>u8B zRlz?4h3Ht&=9LMQa6X}^-p2M#|14QYQURtT+mnL;#mIcUy4Pu7-xt=l0@1a z3J^0Th_&6>=;(B|3**Ez?wCKP$*n3+JOWY5P@Xg3^ zpeEnxX1wiU`)&__@dONy)MIZaFN((8^t?0&itoJq792p=T|*bQta!8f){})xnQWTP zwh07q!f8SB-lrtKO0=&$|GhoEm47G`Pezfb1~fQbXap5A*vX22?rGk8oKoLu0M$S$ zzjeD>hkZx$pN48c-P*PNU93^o+W1H3mnkk;G^!jY{cpPb`c>#{A!`U zkQXTl&V+(T%S0a-5Rn3y2R#eP%oldjgMUC{hDGE^4Qpb-wO}xV8+2W)@}!5Vf$(d&JiL=q=^}K!bJ2r zQE;v*T&<}1zQm2NA^fw6A^#h4FHmd*ku+)KO#DYjjo9&fUV6g@7J`CX!~z01amGKE zAxTjxgpxABBTn>aK0f~KPP5xhR6-~g#TD{}hm}D>ILae3&xkn4 zMD!xU!-WhW7PlY*PR{X53#ABmK?^ldshx z0K8163E%0MNK&(o#4KXLJTZlcu#q7@#ECrqfe?Dmv4)tK#yr|#3?(S!0=sy}Jc?lh ziD1(v+I%860k@POQEe*Y1j{Uq^Gmzj5&*IY2Ol^>(z}SXalstuM65|MT|h4)B6tHD zf~Jr!+yW6e>Bm1l_y5u})-V~2XaW_Gfesb{U>E5C!xf@I#E4L|CKl}@MyZmNK0*W4`5>0AWu8K%k3EYBhVY<3hYeZ5CJkT{2mWITZZ%>lYw!;) zXel3TNQe^tp@pd?4?jb}>gyh>6duhEkW%p|pa>b#vf6U35P=+&QrcO|iFSW3^{Yc- zIx&!V!e<*XKr>fh6B~re0;io}DLdl?0GNpc3PFb@8e)ME40j3t=z#-}n_T5Cm$}V# z?sJjL1II@8eAKP3QP#&U*AxO0QwYL$!5iKnJOK(FfUW~LUe32Vp{QvHkzxw6xf8FcfSf{0rHu_jz7oq@kc zNdq9`B>+$aJ{B?!R5WB0p)&C!%#dOgub9OxcJYg09Ag>Jn8r1>@r`j@V>NhC5IOeo zkAWOyA=4NZ;i!cghMZ(2FPX_RegtDNoRc)p(E=eE2}IJcsfFy6ZZt8IJfi$RO77wu ze)({SN6Zl664$r@cC&J&+ZyX?aL$7}%G9Q~-R_E)&*U{PbOrooLBm(QgI=x$5VeQ? z7TVB_4s@g6{AlD7ILrs0@*E{GiYP>6T5cGCLY}b6Pt!yZ|2Rygn`g&Xq{9aa;jM3h z3lXZ)#Q&U&+*nvVMpdw7o zBpHH5b*d3ekpZ+~9Y~;0VGoy}_jky}`A|76_!Pha#RCIXZ3eb?Mtf71(htC;Z zq5lvE#mVssQOtc7L|yh&1E~b!v8D6jgx80pE~Q0L+ahCI}S= zvVOW6n%KmQNJvBBL63+|H0=$SGuxvg3gBV9eMRvDEbLB>Q1s|28x1FH{(kJhCmSb_ zTV&$7PpC2$zf!(X1pp@BkVm*9As=|hCMd80R%9cGyFEt;M6Zx^#2Nsbu!e^M&WJ{V zrXJz|>h0bV;*Dlv46rWu+D6`Zg8af|?W`+SiYy#v;SiVt5t5@EL}5;%sH^<$tN%nu z`xHXuo^9k>0CA!b#?0rSx#L{;;&hkKxvY2in2hZje5tAsO6a z1Ej$hvOo)n0UI!>7}5+00YC|v&eRyUZpLsU z$}lF*&}r^O6v{y^rs565LHhh7yPA*KNKlpl?*v&6lB5j;bV*VC5C-$mA^&2rIMm=D z_F)?Tp&#}kZax4Smca%S;t|>*uK<7o=%Eb&AReZ1ANWBU8vy|JPa*v835QDx=}E4D z;b1btpJJi|LL~`W5pP~mBc5?3X0c=FBoXXx7TS<0{s0ceK?7;y4|wc9?r>L_(SE`~ z7TReUUvML1Py*BB1DqfvonRV*LAOF68kzz36rvK=VbmC49uxrpmOvyiK^~mI1W4~Q z5&{}h4~^()wMLOVbn04Sf(%0C6#MaL{xKs0(jx|PV}8UBREQRSF)9w>?GTbS@GM6r zQg=ylu;v>q!`)4@k%BALO>d>K?uIi2I58u?qL^}pb3H@9{+BDAuw?Z^uZF8 zpy{5@C+TSn2=N4gS=zS1KIK!s4sHQQ5*oN+tdYAH`=>LP5yU}CSX6FXJIGJ~Q!BP&4s04w+7 z50YaRT*DVv$$fCe*if@<{*c+6EhbPfv|_U++Um6M({y0(0RIwVr%HjsI>N%5;Xl>p zLy3a)JU=*Ma zexZOG;yLXN09K%x@X8|qN(fX`DJk<}l9Y7_^s)Nm5bRDo_hU1~p(>Rk1nG<`P4lCM zF(EQEtz_bBD5T{!6i?ezK)q*4xdkX6LO&fwMPiF1k|0!Ya!Yr{PalF$H3Boor9aR# zAz|YXCJq*&f(`+RM@!~SG0Ozy)GRTyvrdjfMU^a%v?E>AL%URs`k*iyB18cIB~-*j zHDVb40n8M2QCn4MzLb2z6sv6GM#EwHbVLowp+=QLUH^0g*f`Z)A~fWPF;9(=@eB{~ z^wdaGb2d?pQMUz98=?T#01Yl9GgPF@GQt2tg%Wm^SF^J+fAxZb6{Bne4jHsZ{^0Fi zK_Nxv`ku8&JXJy|Qd>L1`(zVH#i%}4)vvsDTV53ypcEq1Lq%c%DJQ~A{vqtzbz&M; zRaFC0Uqv>E)jW@N7nSwSge1?}R3ZabT0@mui*zL0YjJ8xB zmaYnE2Y!N9`7mRm&XelOaQ6pZLXkNMLDgTJoSnC8?PnNRU@Lv(6W#d#jPSpiH zq6B~^W@@%9VRlq;Hq795RFpHQ8lps~&RjhuBPKx_-S%yJ^(~N=B9u1R=wLJN)oJzh zD88xhVnaOv7gPmzaZ!~coCJTk)@JDwNf-7$JNKnRbf+lRVj&__25WN%25vuhB0^X1 z$h26^MGeQHeRNc^Sl4QW(RJq(j8>uql2H)57M;GfTX&a^nsXrv-~dlRMO0)wCc^gi zfp|GKe8op@fg*XSugJuKQgg%)CN4C$%5WfyWvTZx2Uc-cVs2XQL z03-nzT#q59j+xMxOd`Sn-~p)Iw|LpQTkT`ey zW{J@!Iri0Q;E)!;DWlvJi$4`>Z+9bRcr0s|fNeH}{gI3XFfzbVA+ih&?h1YP%^^zd zA0%pykJyouD2cNPk6|Yi;t&y_hLpiUin?ifU091@mvA-0i@#WrX?Yl7YU)P2g;*cBfmAQCN zL79$pxKy6!7m64F4qyk;;0@3=h!?`z{vlD3Sy`0%G)A}=P1tGH=i;2$&H}lW2|0{k zNS0?=fhqKRb2gV}2nB!v7|>Xf;ozYy0ewZMAvPdXf+3ze`CYx#j=>a0AIo|1S57?W zo>{nR{ds^1IwDqZm$n(3ii&Jo{ws!Gcnyd`kaS?ikY}ykDklr3T4s79q9U@e+ zV5pm=s7Iro^#h8-;rhl!Q~&8;WT)ArrP`HU+VEPirNKC1aTjd6T7sSjtUY1V03gdA z+7!^2ovke!)OxK48zye~A>5iaP}qu@BD-oQsqcC}d{nHkSxCd-`>^`2y*9AHSEi|H zmkk@4bQ%s&L82L=3__*;BAZm$TJ4USo8C?oG+U$oxF|?DSxXwUTlb#F1q1D13bDHxxn88 zB1-S{da_T|`+vGSp8(*178`vj3}ctj!_&LN*Mhwp!o6?pw|8`0d@(63H9S?EnpqsB zX;+LF(KYjyOms+6#BIRfC1`FwrSe~LItvs zJjny}o2!bMJEpibki?53B9+2^DbW1Kn4S%poPVtLJ!pRwGE zTKtB`C@#Lix&H?*t6^yT#C*8O+#yIn9v(r|j~oC>9nQ1v1SFiMgxtc>7h|(q)+GhR zRpr*lfR6k-^35&(G8)Z?6*w4Kfsd$un;7gChrM}^#9G_rDC*Lx&-p#n{-65c!Bnqhcs zAR;cjp|4Ng zUg-UU=&M2v%K>izf{qzF1PdBGi11*cNK#ffdSiFc4fCDoQGJ5<7GNj0m z8~;0EB;YEXw-zH?y8Kx3rOcTmInum|Gp0u!|8(H|2{fospdtQ+7>YEh(xm_-d3x&U zl)rz|Zdr}BfT`B4T)TSx+Op_Tup)W-BpWh^8Al1*x_t|m;GuHi5*ZvAH*O$3dI04` z_-9r)afb@x{rh%d!-x?lRurid?aRmj0(=Sw&V}TRls7}R>A7WRi)KTc_AK_a>d+p3 zJq5<^AGSDFtpZt%JGbuDsaKa?t(Gm~;fO^IK6se8K|y)+*il~a(714~3`0+-m~mr@ zBS+_^%qLv97^=PFHow~Y@7?T$_HGX!sne&*xWR#As`i)o{QLWV`QB;kofh162LB=? zSao+DNXH*{=y8W12ZkbECgfk05lK#bzzLpLgQ z>M5q7X1i0Gw(f@Ox2LhPYC7{h^#&Za=qGNw?g9`lSh}Lc>#>MADvGezIjBb-hW47s zbmAzwkAp&F~tDP`z~1VX8e@_$gJuN0~fgV6el^>W(dbB z@42y87=u->y>ZPIPGQJh*W{Bj(-Cku<%se}!3<^T5W+A?92x;JxIz~=d^7;6#oT&n z@yjb~)$-L#T|mvMzTgSKAy9Qfr=4JHjkb$fb7i$xG4Je_apEL2EL@2$3ilxmizCXv z${D=fV*oTzf(tS1!AIhJz`{oiF|<$u)RF}NLJKkQ;fgon0Sj@|+W$&D@kec^J=EHy z2bIjKr(k3O$)3a!t5qnRPCI<2Yc)DoZ^NBXf^;iatQ|q~t_CdRh*yp{w9LYM^Rv(b zee}{#FH7~-S5LhxwP?P1_ug;*jW^wlPk#C4dxL)Z>Zkur`|iIF&iCGY;sVm9DI6O9 zo}qbG?OfgNzn2)`9jju4N5ob#b+Ide3_J}0my)}!?2dN^@x$>5cBsGb%U=`}2(n-? zo$rZogd{AXc)-yOS-1iep!ftRUf~K^(4rghGocM{D8E{`f)6f0fJW?>KOhDXbSkQv zw;H&V2O{w!ida=U4Db;Okc@1pK-m(nNERg~C4yR+U(glPpq#gx{$V4gu1;1dMJ7+lC!^qoi%jui2c;CO-y!C1enDfe z00$AH`O%V+(O)lli56e}(un;-jYn7k%Vkl8>b++$U!a7iDYLN-q1 zrw{fl=smNk8dfgFmApfQ&upfzylha6yi4bB)>*W6CjV@nV2Ni(IrQcMXRHu@ZrZq(rCs{UbvpLo@!I?6b$9Jw7zdS3^JQQYFe7B1+GM^fXTaF{`af~YtV@>z45_{9IM zYo%7K)ELWC%Ojofw7gs7@Xpqli@5C~mI4M({Gx28aBrBcsYNavV;%oc!$k(LiFMdx z8Aw2~V2RXC6aOlfZ*5C+pKIdi#s$Eq760&Rxg63L!`RED`SWj&yeAXfwi+a0N_r)H z3tUwA&BoLs8BU>wI$s16@h}4wj&Y6)l*Q7US@MDK1(#v%cgka|a*D6qXckj?YMy(v z=x8ljOt;Ad(^%Cz#=4a>yEH#UCiN-tscHZWU>%nT?>*WuYXk!-&~l|2B66LO5gUuw zR2JH=pM_<-N?Iw}O-jA(J#T!&*22p6(EuiK+kSQ>y=&IdDMVoHYmXTx*%rb-tZ)%$ zw8A462!X|y@Q)riVB;L`xW_*Z@{o&s<2)cYQRNmFEBWC;Qf9Y*3kHcP1YzbhuXzxj z0EG^W+yNXg0|#~v^q>p9<30cR(EpE)bfWt_=}bp@(VGtSpg;ZNJwWzg`#qx@aAQ^Z z-~w2>(1|#(mk9~aB)07gfGzxks}>=~Fg&t}+pg*nW~jT}?~eDp>wWKh@4Mgs{&&HE z0`Pfn?imP=_{1xI@r-Z0;~x+C$V-0ml&?JGA7S;$F5G_uz{G8hVF9%K0-EcpL)mS- zd75Nf?Q92t+bM4G5MW&6QLnuNN-i9tYL>H4rb8L^z+aau8ZL#1xy_G{bDfWT>b7q_ z$C>YZ+e1J4wVyuqp>BN#R9)P$#kz}%v8sAdVKZQlgN{;m`X!#-A`XYRMI;_>+}IjA z6hdywmqTKgXD~xnhIg>DJpXK=V{8MM5lOZip2rFRU;?eM4fc=@tuPh?rGLHVZbV~R9s+5RmV|n>giJVW2ACUJa1PdxfKE^hWgrA#zzxJ; z5gzaky`Th5Kn(2A5ty(ETOb6Mzz=0$5nHein6Lz!kPl8E5+(>AR4@;#!VG5<8hyYC z>oNo~*g#t30alQLmS6=u005W(4`o0F#t>^ds2cM}93BQ@Z*drhHiSgTfA4lM@m5{= zh7|WU6r@;+qIin?hW{!azztx~3<;PKY=93em<9i!hyXwZ|8N8zfegK15yOBC7a;0xNe3G8qW%a85`)iJJ9fw-nFll9$UCs~7XzVgCANv} z)`><)T^2EqKoOHU@s9M^j;(cU-KZvQa1FAij~HPB=&(8#;RM{k5B#7FJ>U^-fDcVz z5&2+x7C{N^0RMN>IFV@60mpD#l)#6p@dKP7O|#;Wv;&frrjukriHPwB;B=Bf7$Gak ziC2=2frEqrSVVStmj_lWJkSmp_>#l>ji6 zuoscW_%0ow538~bCJ-Nna0~k}mZwve7bB8ik(PhaWGAVKaLJN#>4|iCDFpasH`!gZ z$rSa3Dyg;)yZI0Oun!6V03QGi%OGnO@d!_35fnfV;KrEqFbNp3kQdRA#dwt}V*mj6 z5Bgw0{DB3xPzqfcnkzG!P)HM}nHPhG805&BaXBe-nMHh@N5Dat}0@2V69Dos(unu6u0Q2C188{D=kP*Xh3>N_n#26Bzxfx})Dx2^h zMi7?anKt8Dnr=gqJHwWFk&^4lp3uQ)b%~#%VxROzpY@rO?xK$&APv_b1UA5kr9|3D9m*&l}>WCR7GS|g(RX__T! zFNyF_<5W(`1()aO7A+c^23Blt`ld8CqCcXK(m0Ju2>@f@3>CNxT3`{$cw5bI5p1vx z_<#*0NS!J(0G4oD$xxjC(E+*;Q(fw%Qu-C-ITPjy7r#Oa61AEt`f@FaRPgyjF{*Db z3jd=|IH&Mssd~}_>aZ&JkOe)02_H(SD)XiCC#J`8qHwWmpxT=4`I_&!j-hC(qd229 zF_Scks+bx;7}^z0a9hD(kTYTg`5_6nimR>K70&t+n(7v0S`JRu7PO?M&_!3n%1*@^ zpU0Yts7h?JS)*YFty-Y~AM+3HpagAFMYaH*+G;Dgx`VmLJLm})#bQq9N>mDq5NzsB z@S2x!DzAD;uiQE#4!{eywFP=o20Q)WiJBhp6VZGWG6BVlK$*>CHp6lwO5}T?J z8?kZQw9Ky4rE2*>v;jpMBx2h$x zXL7atrnmfod8^W(wt@&TH439}0*8w#i92qKdn`tq5N_!=lUq@4t733FwK8$LE|I&s zYqz+&x$l*=IKc(0LJifqCuEQb{aU(zfV!oky0u2K2a>ji<|K%gvaBh)bWpjD2D9;6 zF{)a#G!?uzVF0LLpyDzJrJEnAFbclayn6Dy-pIOwvU_gvd$qKGDoeY-_W!bR`n{Pu zxATg%ohyhZP`XuQ3Z?6m@7pHvOE1xT9mj>H1aUVinZMY(zy8<16YIbK+r8fUkpwJ= zmoN%dgbSq$2@Kr8BCHf3+!AMN5WbUcXWD!Ei(*Y{yS+OZIxHGI+{1KhlLE}S#tX7w zpuV@jzN0_^D*Pi3jFu3r95iDWfbk&C6=J}8y)4?Y8I{98JfB|7tljIqq#3@fO2h!m z00&IEqW}g>>?2M*lJmZfUA08EG&bNP`c|GoW*~$#Yfnt9X!UJEP#Pr#)Evu0ILM*i~kD=JPJLw$ZA8# zNa4aG0mD2~rU#Ltm5jxDoXIa4w|(qlU>wGr{K}*=zL}H>rEAQiFbJ#sB8^ObSuk%)y*I#=#t-t(<;yaLlFazRK($%-j_)tXY@XAfJlIpo+`t%Ei|l zv)cU0z%0lHHOyE<0^wY`A4|^tVa~b(#l`U`$#uu~N6k0%;QQ&1jR) zSVY3%90~sn(B3Q*6a5h|Obg*4$w0*y_&d#cT+Oiguwp#3+3eD0`DPV;MP0zpqwuI2 z%^m?QK?9u^;_76zERG57YdFl%^^DCgJRy--;F7WGRI8)UsF?anDp ztVP|@NiEi6ZPpbF*8nR7k+6(z%^y15MRXlE1zivajTqUxGhe;XVO`dO-Ovs##K23{ ziVfOC@!2@x(H^0xYbnwsjW@$V*)n6cM&C-7j*f34lp^e)PG}@IV*E!|b31PGq z3>~d)FR#tNm|feO9l*`n+iMv zw}luoS4gcQZ4a#SY-v9kS>MdW*eObSK z5GKi7{gT&{UEh4|viPmv5ia4f-QTwj;1{kGjD6MCJu?^NduDVX#C<_;duYYxb5KIm^Q;|kZ}b8h5yu2wXDTsgz% zecs^RecV+}=;ICKK~Aw-uIQcq5sY5ocMcfJ^8X4T&f}9l)KvcCv+d@YE!c3LF>>zd zf(Ys}F6swi9OO{a#f|Dy?%kH|>RF!L+kEI|_vN#`%C$~kzn$mdPz&oe;=L}azrN~L z-s;2t>cx(FiH_|5t?V22+s5$?5W>|VF72)f*1(SK!oJ^_zT!jN?a2P^K(SGbrw~qUhoWj@HoL?hj2W=H@o|e?yAnc)?Vlmf9)?Lg;bdF@_?kO42>TD@y#3ZH^E_o z;SDD3+77S9@T|$|PVoZ&&{muDcT3(G!T*Y`2#XlO2=RdEIj`tDU!GWP9N}QW4Uh5< zukw7%>Mg(S!j3Wbn2%9^5sa`8=#UP_u)u?e^Hx8$Sf8mpEeO_93s8>cLXXKrugkmp z!vWuA%)JD$7kU}NlRl~TZMXv0-R>gmbkFHAKKV+H7=o}V;4sA$is?6eUr=YU_QsEF{OO+n3Z);R z0NRj{vrqktKKCI3>j0orP2w}W2md#rZ|;zl|W5ngjgA7uZcvIDOIji8RB0EmN8|{q*>GEO`JJ(?&R6C zrc0PUBVNoX6k-lDj_539+H@%(J>SB;a$42uRjf?SWaZk`Yu2q_xfY5fWyM*vX;%<| zBH<{d~>BS!$ud#} zBUPF;5T0(~YWWdc+G<$Ssa2y^-IT0ZwQAYARmj(}ZOXWFH?+Kvw?&M-gJzTfs^XSV9$NhZydxOp4&!=DC z{{4aSA-jhh{pxf*$_Yml?o9KpKm?aMur=_)Lu)qjDl%`q+bFD1LiQ{KfIs|@)2~Ai zLlkjDo<3xZL&p58%8xsu3TKu-68vgG8MmV`wFVtrYrNVt+zrDEk4rDI_JSkPI1`Ul za!DqcOj0it7gMpRKU(xgG}3D9>P9V7(QcN@T$x@jp zIp-c}v`{EYy{3GsPyg#e8I-F+S7kN9Lt{&HqDa+4Q_@L4L;3f17R&o$FmkTDB`$q7E0%xCw913i#e9b zW1)*SS~;R0y5XNK20}%ef-DGO>Lvc^!2ztZ)_QBMyY~8Pta&g45=R^%BoA=H87Gvo z+jjeHxZ{?4?*F!vqWf;V^Pbyoz3GM|5-gq&d~m{_fC7pRz;=KGGdNKEamXXrnsLV^ zxBT+S8^?U}%PHslbI3jCx`&{TPAO^AQ&$}_)Dv2|X@QsY9sxYS80f+zcLau%CxL>bHM?{`>d;e*gw>e`3?001bFR1p1GF2|VBlI`BXU zMi7D-c%10ucfqV#5QFm5;0EK@K@WZogbpCx$&`eNe{jSEt=NV=($R{b03Zv?hzC59 zL4|=(!T%ZeNXNbg!Uk>J;~HcDUku52L?r6PdCzPyd1Xb$@XRM# z_ib+{Ghc!6jgkqFI2w>m_F$Cg)cl1IDO&|t491;R{2%`yYsK+D(vW0zM zVhNkbhZ7XC#3UwCkqJShLE3N+Ml7LO&q4^hjN-+eU{WWV#0e)m3C5g(GL%@%BG9BL zA`fr_3>z^B8}PvZ8UBL@0-?e`jsO5kz=Hy@(}qBXfsBDjgBOPk-y)59%%K%CCzUWv zs7B?zpOKPc#_^<0s%cG8_Dq`56p|^K=6*qYeY1L^}*3wW(dCp8%z4O##qInGAHH4?Pn# z721<)(j=%t{plCcq|^8CpdC20Xnv%TjEZbP8otPa7Knk34FF)I12HK|RmxJA&dzqV zo2gCBdQ6lX@(ej$)aX5t~nX%OzJ8VF_K6P|JX-g|Iv?qC;$K-fW|T^Dv(FC z!vF%I06p3O0C>uip7zA2K=k?2_Q~|DoAqZ}S+Z8Sz7?*bC1_85N?M@Km9DD&tME;R>Hj@FJ8bKUh_7ImGc~{)dVsI zXVh>RqN3#vpGXikYy%(IAR<2z{9^Gb7$ppDZCfdPVY}iu#}K|Qk9%xmfza4=GKO)H zk3{65yjEg9ZZMF4b0wAB&^OCD&}M>joC!@3E*q`SduDWR7H#G- z8#+xo-Y%spJ!cGKI@3;0bkQE&Xi!%w&x`5wj_Z8IK~GxKrcSk+3sP#1eLB>$R^q6k z^ykr@dWx-{a-n@KXh{E4*0d(JP=+03T$fhTt_Jq9BmL_`_a)inJ9e?Hos(+w;2&Ag zLASmAZE%NM+~X#9w|nr29+X?%>t^@3&zbd-gSe29qj)W``Gh8M4In>;tS{b5t)9wEU*a+9RKI~**DJiyN`YCgMT>Q z|33G}FaG66g!~{{Kl{<&q4vZ7{pqKF{q28${O4c)`{#fE{r`Ue3_t-KKmsg413W+k zOh5%(Kn83;2Yf&XG#XC<6%wlqOqhmwXa{3Zg5yA;ajJ|P5QcZKhifpp%20q!I0t*+ z22J=a$>4%xSciW|9{?DDO;`teSOz433>cKb^l<=GxCVMyhhVrb#^}KrGzeb!hsxSB z6jVVLbU_>Ng>|ThWY|H0;01252X{CI4kQQ@P=|jY0ePYZeBcH~=!qv>!4?#VDXhXP z90)DsLN6o;M!1H1Xop?Mp&jZWpIE~vbVDk%LM#M;Isfd!FO(q~vLU7d03G5XDAEZ) zY(oHeLqaTw0Z4`<6bK$bhI(iRRH!=u@B%YL!#_+xHk86aj6;IR#7(4vVMqsi$c82y z#ZpYe=t`DlnIy|d21aNCDnJHw=z!rMBQxp^6F7%n&;lP23CqBQcOZivV1s$6gvlU- zQ`jpS#DsV-11dO%b2zNUz(#GPy=7Mls6{n{Mrou*YaD=R zaE2^U0$vzKftUm?=m9G@hIA0DfiMPS7(;>Z0eVn{C8&gb7z3WL$7!s_8r;Wz{6}I0 z0D&Y(gG5M6SO-NA0xBp2+RLLo>Z6{pNPNsle*g4Gfb__LEXacd063B(Ie%ZY==iMh*}Z?mTCqtU`PN! z1#B3IVMqp^xJ-cnOaRbK&NKke1kHaCO%tdGFffQ*+NIM(uAOjA0Dw)|#FyGEh|r8B z$E>AW>P=p1O}~82%-l@l{7iwc0(G!~P5&eVexRgDkcVADP1R&g=)}y}q|VN?P5{78 z?W941*ac>Yoz(Ot@;oc_8JXo0jwAR70<#QoYO2b}22~)2cBlrRqzp_rha_;sb{MY8 z*hC@t2gMKwXSf%|bkBhRgMK)^op?tBU?0SUd)9NkeK zEzuJNQhQ=iHD%Mq90*}>BRU-j9slL5*Kr!C5e@@DhP~{KiK-}8vW$DU2UM_vNw5c8 zqznTo`_al1psR8)n8?)Y^_oN;3$s*DUounuG$H7oz`7t*K5tf=-fnJ zs80^~2O?V5foRreg;q|L)?D3JYb8%!_*Yf^FRL_Ifk4>JI@H)n)ZW;IbD%oLP%5U1 z)XK;QXc&lAhz84OgLG&ED*sr7cgWPq5LHqgh*M3~g*XOk;Lr|DpDSPoBc#Y!YZw@S98_cmgU-`m0P+6fHL3)4-g1| z6Z^VD ztH7!Zbcjw|S_jKW2TB+SO#sfBO`iyz&>OYT$8=8zFa~RY(pLolO8_jt;)io!G~2~p z-3@^n003#&!-8n6mH(;+e&{QH;Hym-RDmeeop@f5h~DX~UW3410B8g}X$L=Q(yBGy zoFHES$X$YvUh1`8f>7VYa=gZREckuW@x9&hz2EcQLsn4U*5!w00Dw1*(>cXaLbcNY zhF$~CUjRs8*8K+t=BjqksDY5+@TK6hYD)t+vC0^LR#=BZw2auAt=j6($q{9fnmOE(jz@+n1_` zG!%l_V&5%zmLLSw`pk(b-qtE6h%2^Ag0KKBKF{3*029FCTrw`*CF33LVS`BHEKbAT za>3vlt~q|ro&P9f9zNrN&|@2D;(w@w)a6d^l!xpKV}THcF}7nW&SNZ20UeAZ7!|ikxRz_W1^~OpYrRgy5aIo4{C!Ko;JxP?9OiO-fr&hZtwnX@D6YB9&hq4Z}UEH^iJ>Y{!{gCZ})!hc6s1|umSUfZ~MM) z{Eid(&TsziZ~tBl14vMNum(05h{L@HW?%%g-E8qs}RfKh510P_6$vtr?pYry$0D6EO0O*Cl4CPZ`NMTS0 zr^yC`*l*1R0MfC}Hu#4(#suWzhLr*d9Hw$PpL6jxsd>2bdB_K-F$UQ!1BRrA@BbAD zGsp*o%qKYIZIK}z6P%|cZUlG$fDZVFdcgBMq;pHZ^zGJyfAE4M==39)B|bOsKM!;O z81zE7tV37aM4!{DwNXZhhf4ehMey_^=wwX4bzFz;54eX#Fo;m59WwlKr4BcumTgvzGUxf zfp~SqGRq{Of<~y!X`gp`SHJ*`|NZ>^{r&&^`TzU${QUg; z`}_X-_xk$!{Q3F$`T73%@%Z@o_xShs_xJzy_W$(s`1JPw^z8ri;P&?R_4W1i_4V`f z^YZfY{qf}S@$vBS@cr-N@bK{O@bK^N@B8iJ{O9EV>c;=%zwPer?Ck97>gwp|=;!C> z?BwR<=H}z%(^)6~+^($CP)(#_D!%+1Qm z%E-yd`^2;Vxw*#1#>=Cc?q^hH%qoJXppP!$;o{heqjI5rU{FILUl`6oS ziNlhCx|x}}lzzI9c)6OIxs`yplzzC2aJP$aw~KH8et!Rh5C4Av|8oHEd>hSrXupDF z!Fff$c0-_?p_-bSqmrkijF^>`m6DQ@jg5_%gOizchKGlTi+`DfgoJ^Cfq#F0gL|5N ze1LmNSIEe zm`$>92pmYTpuvL(6ADb=#Kwz<5F<*QNU@^Dix@L%+{m$`$B!UG ziX2I@q{)*gQ>p}M!$|^#Fk{M`NwcQSm<3*d=)kk5&!0ep3LQ$csL`WHlPX=xw5ijl zP@_tnO0{ZI5HAYc+^W#Yzpr4!iXBU~tl6_@)2dy|wyoQ@aO29IOSi7wyLj{JrR#*N z-@kwZD}1rHu;Igq6DwZKxUu83F9iR!@z2T1k~c2hxQtmd=aHE=e-;^fG-=PKKbB6d z8a3;TUTsL8O}n;25dU6S-OanV@87_K3m;CLH(?OAZ4!>0{O^J<3z`Fd9$h+D>el^Y z&%Sj#_nO|n)Bg-FKH>86=+k%j*CD<8_weJ(pHKh$`u6hA*C$ARe}DS_0SMiG1qCRd zfd>w_pMC^3NYi}|MkwKg6jo><01)PvTZ9P4*Wr5~f~cT_A*NTNi6hd-;Dr=s$l{AI z#wg>A3b_d1ivFcY;ECn&*rSd)R@b19;t?qwjx^F|W0FiZ>Ex5;E$JST2t;7zl~`t} z<(6D_Y2^l8Y~baXWR}?_m=SOYWPL_**QRxE!nx*+8$v0cly>H+=bn5XgeQ6{4$wjo zgcfS(p@=4`=%R%l(ZmsqMk?u~i#mEl3j+)}=X`NW*J*N}g1YIHb@mx0d#0wU>Z&yU zS>B3+qW^G#nY7j#0R|~xVC$~D-l{?hMYN!)ki$wCYHi0NJ8F7JvTB>F&PFTkwBkYg z9fJrIfdYL6h@e%3-4=jC5eV$KEPTn*mab&$vU~2UrBX|qwer?$@4YqAn;nA@6mbE! z-bxtm1x2J8q_OY1*KS}7Go0|X@#6cJz7kh#vAq-@S!%xq%NMS|-g0a%u_Gf)GMf*h z*YH-&Ui=`cF2^i0#xTdnZ@~b6>tMJdAFSrdCh&Q#dF7bLE_-dT&sMj4xrD`s)d27jj~Cq3(+dWBfCEo0d_Ry1 zIrLPM1wx;gBM&a8j9&U3+1P{5GZ~B$*7E?I9(J*;qb@e&@UA_3?X$P<{!Q!)c6$H^ z)NlX&_~);G{Q)Ed0yVc-!3ws(J3i#&8B4&z_IhyyFW>_Y0=We>un+`J++zp^xx+m! zK?GCC!+Kq7fj&5K10`re0~+W>GX&TG(1omX0z#j{9Oo$-ib{qk!XbBD7q|Gm?}tG2 z)6)Nr#yNu>;0#Diq7s+L#3mx~01EjW0IGJi-337)wxEXw1mX-^0Kf+P5SBomVG4s# z!;1o`1_%Mrgn!6}Af+3K_=2Xo@{P}YDv})Ld>F(&0+Ek@x!n<+NXSAyF^YJbVgczf zkWp-7AiC&U7ydDiO3p(cy#RnEy$Fvz3?vn6M8GrT(Thu54FGX;VF7wZM?2oJm41PO z18l=M<>>Kpfb^p-WtU5?%x{0d45t11mk=pZv3K!k%ZNQXtMBl);;fOV_`3d%yKb$AH3UheXqJshIi2EzZ! z^gN>$0y(DdlsS;W4dEYHfXNvLqQzJjw zY-qb%TF##MOli|lYRk3t6Fs-E#tl*+&}0h4Zw?j6F1}%h96aF@T`&k9?7@d2jN*ei zeL^T2atC~H0RW*02N6>8&28Ot^I6^Lx|hB4@ojbk2Cmc=*SP1KEKCS+g)@+$9mKd{ZP#1R z=)U*BGvh5xo?uWbR3Tr&U+gh6R;0$E|L_2&TVCQx=b_zzYh?x{(^As^>Aj7CR zyG!8;-}fL6D8m_g@QQXcqQmO_@E#33;vV0t#0X(wk05Jfm0^+P8ET6Q_caHR)@@$Yjm*<%ERq>h8 z9OyE`qy$JT0RW=Vj$kyWmNl`h(OzY1hKSrq^LK(p;pr`jxdv(tY3o&pbBT8 zffB#}xsPav==-+MLGr zrne1~Cr4Qz5@5%9Bkp0*GTY)nmk`Fm9DoTJ{pd(fy3&_!bYddJm<3ch7PZJlFM?5w z03f450xl4L`-R{+Y_X>i4gfWufd&K7K|6}!^a=Oeee4dp+_y6H>l$nV=FPj__s;je z=Y0Z*4Co>o`AC685&)C5^BnuUy`_)7+7F*Q@NcT>w$Iy==cve{wc)@U?#;SRefd0KxYiZS_|2Hc$juP!EMydc{|MWe_58 z4^;Pc5h#2!r-Plw0W!t|1wjHJB>|x4d~ip7BbbD=gM_t_an@07rj>)4mtPe)g$7Y* zRUiNbL26%Bg!p%a(5HlA$Q>nkf_z3_w`PVEScO)|TA+3YqE-;Z#$jIgf%!LvcxWF? zSZ-iuZ8{TNQh0f6D2UniYr%F9;l_L(*l2f{hmQZ)9A)@_LxzTcSb4-Zfni651#yAj zW)Kg@Ty@BZVEBln_$+%^Qg(-8nWl!BsENZjb`>CFJ#Y{Tuns#Hikkz11r~;-*o$;` zielA=QTT`36^Lu-iaSV%15s!5P{2JP^9(HMH`1B}(!izS#X+p>)*HZHbyiTD_EWyW8Jh!D${WbP+Fb9P(q z_>QDlf&dUJv(hUJi6ywAD-9WuU4j9>5-hJMf%zzWoR|<(He2gxgrZlF2I+_hDJYb3 zk|^0IkCKus*^)(IDVTDRJcxo^2lGpf?KN*zTAV4edd$u4B zTF?a5Kn+W&i&vS9b19B>8D8TBhYG=k-^GreHI`&Kl0mslf0GY)AP_|G4^psT1G#~ z)LEU@d7apqo!N;2Uw{GH`JLbyp4-nDI*`Dw@pWoS@ zAMk_V84OfLpW!K={P~{?a09J*ZX(&6`^QHjAP<*toXNSI1|gJSaS2~Ap%hx77J8u= znxPuHp&Z(w9{Qmm8loaPq9j_PCVHYMnxZONqHJ&mYcK~KY6rGR2rF8nHmaeQFrY~@ zdIs8KfTWzKIS{JJoX!cI0D7bg;GanPpGvx<^Vy_M3ZGCKrR+(bR4S!k&~0W=0^q53 z>CgaII-OG*rr#-`a!HW9*`o(3k{W;xn*aj&UshOIQ;i#$KfoeBV0%mY_GZAhcIjFk% zm#FHK2&t!-Dw}(%tlzXV(2AQn7TB^>vsd$B%B}*{6G)v8oRSA5Vd=|x!bk8TM!WX6~QaK z(kHoYJGuWGz?YjIZ)gH{^)5Kj4(YI!%gd7oaRT6g3r~;(Td;Bj@x4QUmfR>EbMO!R z@WKD!5ByLr8$b=uU^s$8FqHuShpR|eqqyKV5Wd?1z{|g-=)VI@xy_2a$?G1K8Lc4_ zsIi&125}05s}SFdn(46tNYKPcU=6y!v*#NP7?2R9AP(i?wbfw?W7`WBB@hdh5RYra zDTTw83%5ILxo2D+Plka45h9~H#2QirJ@Ehq!Lq$z4%a}l2JyY%Kn~9^e(&))=bH^d zfR=p22}=KP1fq}+bMQCipbIfe4}2^IBSZwFu(Lf&#w1C+EMvTQtGuDi!?=hZz6z{w z{4T;O$D0!tqfij{a1W-i1eahBo>UM-a0yKy1-PIOO<*^8^Sxqm0|EgJ@n8?taIpO9 zuj3G~12M4ppbg55ww}z%cV@|&EK(+1MwkU`IQZvv8frqT}uuykqYljE%aQ^eRR*| ztj!Uv!~C2bW(S1f3^{x`(ad5}yl}(-kP7UK5YO;X3|-9*?PCyKy>wa80=&l7VThcU z(W3uaZ1|ju3E>3#5DG$o2lViOVJpv$_XR?L1hmi(S}@Njozf$=(gS^~6n)eCTpJgd zdY89n-PiBs)}sv9PtDDb zO&i@-23Eb;%R*`aCe=h_r_1)&l-+8UE!Y5@!>#SwwsDiQh!7pZw4}XHe4W~eI@zQZ z*rhDdgpJvmeb~r#1q^K0%VM`Kz1L!?+xoZKzdhK)E!WX)8*{4=9m2WG4cWeZF%AFi z+&hNad}!Li4cyaR*az1fK8TYEfglDTy)m%e5JTQO%G=-#TF`CS!hPB1ecs6t0Gnq3 zFo7Umx_xh5+S7R7L6_g@-QWBz-TrOe81~uiJt{&h-(N=Gk}ci}?xXe{mzTQPB0l2f zO&ex6+XFr-|A^uH(%lyG-5tJ*L`>cK4dDlF<28ZURdC$cJu3AF(_5Y3G2Yf6ZmXJI z;xEnONG=$iP2oLmG;K!CO3qnAKIG2E;P2PcxBc2c4j3ms9-ESA>#%539yKmrF)(iB zr#<87o#k!rc2F%CI?m%MZZxE3YF*CV8ZI+wuIBa4;la4)texZ}9^p7H6IK5W9-9)! zc|PA&?&p$*<#2xFH_qi{E)!p_=th&(mk!v1j#fnu>309m>GOgHP zZZxq4ik;qsXD%^)F6y8T=mKf#4UX!)uIh!3=o5Yu0n(MPH|yj5=(x^hk`9?6Zs@?i zDu+7}3Y9~2>30%AF zdeZE(!K=iMuG69K`_8RQ0II+Wc|h;=-tBt!?f1^_&O!0l zVeuF5?+(MMr;K(Pj}Wmg?(-z^G^6Vc0t&343J#wq_TGNqYVdCU<^cb&aQ*o424U?JdshXb$myVFFg* z@d>f;m=N?&GV~k&@~htNRId=mcLoMr@j$cg(XR8&%_3Cr2;i&`n2_>d?<8W+^v_=D zIq&!6Dr0}zI6zbIFu&^vPaq}m2#x^t1;GNYzzR%|_auh(1rgcg{`Z4!_685&P$uAf zUl1X$`JSHm`w;+v@CZHt6RNNZbU^vfX8Ey3@NHBRolXQP@@Yg&$7DhD5s2W!8LC!Mm>O2>Sh8i! zc8q$q;8L{>k+wbf7Ou*ma}mm&ivGiP|DluN8#6t#NGvbCG|V%oVjjvce{kU)Tl z2vo76qgeB1&Yj0HK8skf;lg!Cn?4;=GiitiuAHGl8L0p2f+X6pn^2l|ThX3<7X%Gg z)-g;TL9tTxTlsS4%@+ngY;rSev((92zm7UFc7{~WjB()dZIpJx+H!Z=+qq)sYV%l) zsDKB7hfG+lVzFNTe*R|Lk5w-(?d(EtssarhP{7?N;^7Q4N|5QTM%sbpyade(u)nkZ zGwTFoj!{CgKprsxqRWcYFhvztBB!LX%7c!4ipaBYbc)NQy!^68AuS@HiZiM(z(?%_BW%pM zw6wA&EXRsKA`>2QL;Rf$wQA_vg>r+P!BG0^8;ZoI9j8F~h z1Suf;;Sn-?MK;;afUT+5uvirj*6d_;Gqs9bgH5(u3!1RPU3rsE*_4=d$_QkTx!|D> z9(kk!ao>fvEOK3P7C~yaly=p8^}RRNio63aOxl2Cbl>#Cjkm>+G(%vxE+Fz0q8vc! zBw>p$wrJjz>U|1YzznwcMvz0EsKE!D(kXyq+R>rleqTfwTpqIMpd->asUwa-28E6qSOv4K z&%U_pkvNvRX?|&RTP%-flc>xy(`4EpFxm-b#!IzEyCJoW8ZM8zAv%tfz!w*H@Q&Ed z8*a%bUrpK{ditqtgC=~%?>7NwTxh9khEH8G0@0QsC+-tFbk{R=oFm8u7CCN`E4Tf2 zhfJvT_Fvio!*gCie?4}YTsU`yha7O^5eOYB;KbLb|I>JlW=C{s+HtSF`-dtR1GZ=D zA|M@>g$I`@>P7FYixwiX!bvElT)%!6tDcg-ocmO}zyg)>~?0ON~^4%(3p z`e5yE>a!pI$U*}=;jJM#SOqB%U_bv3YDj_?(ciWLI6@L`M@*1<9?1aFj$atfe>e$Y z!anGd0!XHLG=PZDI=I9A%&;OcjMfVyS3(zhk0B-4Q4ih*fLFAm5k-994t?kmEXX1g zOnQVBc(}zWO>rVX{Fo58M?~~NaUs~ULh6tflVAYPjKhOq{k+H#Er5+$CBRd79#ViQ z_=$^uT-MMw@`-=Yq975l1v=)j3>82GjC2Fw8%-$2{xt+(dX!sGB(RQl#6Xg2d1T`R zshI|RNDB`cpbs$F5K^$>W`Kkxdq#;7Cwv1Nh6I2u#G!>IRD&9hBp$vfxxZnys+h(! z;z3N7!c4YAfy7XwFtZlN_09j0Bb_+LD>=fmRU{ym--OHHG|&w#M8l9E$j2QDLWF+| z%ORn(3IB*0$xoIMYDzRzP*&)RNlsIWvs8=|z_x*oP@rs60B1t|1JH`-A{78ICjhkY z4-pt79GqCl13IwLBK+e93jk?IMLJTFmeiytJt+phfB}@Y)TJ*?=}KWbQ<}zkz_|&Ki04gk;cvPl}6sS#Y>J5S!I%{sE0K=IBL>%A)Td|TA zic@GK-zM`)EL{r)^5t zY+#NMLDZ0GU29trqEU`|6sosHs!VYU)u-AQGpxWo&uK!XE*~5i2Ku(+NK>O zST0V78(o)5m73JstVV<&i>xk>UCdmFWz2?J^2(%ZbNB~8)cX&A@MEGCEyzV50?(Pq zQ-t+&AomIawI1n)Ji{O(hBCXj>^3ESPkKn=%DZ5cbZrAjfG`rQp$jCS(+=xw=X?je zMEwT%TTryy6)YI5Zh4q2^hH*IlR`m9H1L8`*dT*t{1Jv;B%-+t2QR7dOATN5!)45` ziKPjE%S9?i1nd826g#NmjI_WKM0kh+Za8Bq>-X?fWRP5fJQvv@r)%HWDC`h$2pd91A}DY8u;)AA0WbH zjDUhTSkz)fyjf*RON7w}LGecBHj+)(_n1Mf9e<6cKy{2*%%I$`XKHy%03cx*UI>B~ zy3vb*XaF6!Ai@!PQI3}6;2x$3LKCKOje_KW9;qn8Cit<1hg{ksU9d`w8*(QyMDrj8 z0L3c&SZQuE#Mx^}H3E}~-!NO~0cH}h(N@?(A&Vu`PZ?)9ae0tC;KQ3v_(x;_poD)2 z0RVT>4ZP0w2NxDmfsL%V@LP7Y9zmvlMRKsoCQnH(HT1 zC!i)ivE49Z^Ku;O+J#)=90l0`I!4ie3(#U4-pm0$E`b0L^x_!>nZ~^NAPhPk;H;d3ghJyIL?|45q_y>`z(GI`4v{ARMMJ2ok)}kA84N z-vG#hIr#ApYQVP}pD+j){*kVO(6$35F}iQ00JaQ7gafNw$OaDTbc{n?>KLJVPV5V6 ztGDF?X^7fr>cEcYem#BsS#4`?44i5-BPJK9hAx~SgGX!WsrC$*_WMkfCREqksQ>VlaUWOJF6m5aA{rQa(y! zzU|AWPYa{Us}{SsoHWpx)i8#3;HT^(8UyT%2aB)?LjnNkfNF>a3^<5QAcxxnfCQKa z_Dh9oFo+h&uv5qegW!dQa|o!bh!i-1h^T2!a)$!VMyVd$5HfI09XWhxgF}e-MQsXaZ*dhjcNvR3HLPShoM7 zs}h0eFNeScP}nvfoG~Dzz^jWsA)E{Tn!J=~0P{(+A>23%RE~(s0^frxLIZ#;n1*;j z2WW670KkK5m~MQ0b{ch00&%n zf*ja_AXtbqOtv*lmRqcdFR+THJ0ew*7*=S78X(67GskrFmsv!|vJf@8KtlhI=(^xZ z#i<~YQRK<);3Rb+Ef^f%+m;lc6B$zyy zBDg;REQoDLgvW#xQAa`f=jT6Jy?j`D+s;gJ6{3FipT=6fdI+K3U_e`6et@ekjm4d z%7|=9b#%z4V8^(4MUR*eU=T~mYfKRO2cFz0p9Fw>;4uKG1rESM#VDV47zEs$I@-J*;^Bpk zEQnONOoMPi7z|0dTuS}O!AE$&hA=2q$N}k0DC)FI>--QQ5jxw0IyC6@EP@r_M z1M!5s1H}j;aRPk^1tGu#deDP{I0aoOwqr{}e>6@&aYKnANd1H*{v<*GJyHMk2%a#5 zUo=n#rHFNNP)(ari_j7;$cB5^hN3KpT!@B3JG5(5mbtWu6o^BJ2*p6)P7+*Qj6F|CLsgxS_nE=g{XW}E{aoBtkeIT z(~A&*R&i5TL`E`RvvoQj&s)joK=~Cns3BbFpY>d0)uPSQ+NfYT0EO>rHC!C zBXwaHy=;gX;FCEl*J>iwjoH>pV%8~L*OZXSbeq;}{T~0$gD#0Z3X6TGgiV`+wToN? zh1PKh(=-uRDp(FW*XxW`NljUf&`Ms#Scdqo?p#=z_|@v+Si6W$hXAc(d5EP`g%K@T z*E!i{P1h7{*pX=8?*`I56=R{(6TnX9aUx3NU24pnWa;xwFm+I4uF-2wN;>Epp3SCQGcpj z6#)XUae?J=1V_MHhM)sd$PCJ*s;+$;%%wceCEEYO+zAI!)QCOXh1e&Wd|BZ|U6aM# zxfqWAdx#Q{#fLyX+r3@O9YoFDT)ypFl;Ddi1=Qm`2qZII#2j8<)m?aLT*oaPjv%d7 zfG_H`#pNZ5^Mxed-CMuC2=F142 zN1foH(OZVaUs&DXgJ{|BHDLfK-VzSm6Qf^jWDzb{--f`WNAO^S*a3u8h#IzG`7O^2 z?p@bZ*BqV*G80#dpjRYAT_9Oh+~yvZl&U}wBq~qU6tM89NCdK zY)}&>05lumAqJ2l9?~~nj-7=PRjA!IcH;_;+BnAHIo4q@mI#?d6B;#P5$f2Gfd$XP_*SVc|>6t-0mW?NJ~T}(EJ9{$p{SjJ1X-zQ~cj8WlGxR*NA3n=Wez2e1MfnB0QkL4@Mwc)4MPon?Sd zT%kIX!1ZCZNYLmFV=XRaa5j}&o{0a#@rdc|XY_^VA9CndhUWUM)B*ZjP6OXqUgu(N zXm^&Oi$06T^$2cifQo*Xe1l38o{niO9_NbaUMvmEvrrkYBVTb|Rx+NFLnXc}f(VLkYNwXRjpk^X zo@t5D-`Ge%vxvo=X6GtS)+*V8PUy3TxD!V>ActsQuqbQz^kx|H>4Qe=t6ta;>+7@@ z3y~gawWj5%D7-iUYLrOhN9baMu#8sV=fEx%n7%K_7HE=gWz5Okve0R{CT+qtX^EHz zT!^>>Mrq|J7M}I%DE92np6&lIE$sgN;Z*)@)mCdR4(+K(=RkaHa{lJlj)*x}hJ3iY z_bHOfmIwrpf=*b@g;I3QF4dV4K?=c>WO}GbtFo#kA zK@a+Fv&e*O!U{+5<%M7ZRiNSjX50)H)d64T0zYkv7|@Yhaj^j7tv+nJ4ht3dgl(XQ zUC;tO(1xGG@BnX)uL&DoH0XnP;#DPa0RKD{*I>~e?TAQPq<-g*sE-LeeFlE7=@f2TKE469^ZwjxpHWFUwr*;Z? zxCLrNhzk$}G6(YJsAh;D029b(03g>jm+eAFSS?3vCP#0YCg>^<0P=2%37NnwRb>aK z#i_XP5{LBVfPpg=5fXWb8sHN*b@b_ObMuvS0;lu^$8wJj7)?)#w5?Yxhw!H8hZHyn z6zGThiS@CN1zCv1hB&a1Rr6OT^d(2}aISS*mxx+jYn+$>PRdD74{lH=;#p@1e-QQ+ zv6gJK&6OTbxbg=sJHl` z!2hSf8Y7l*7d`rEpcL{j>dc3FEjE07af`-&r{nStVKzRbNY5R>J>&d75 zp&|E!7y|#I%Y350`;0em?R@t}4p27ndtbNUx(<}9I)+_l-}`83+OK_)ScYZjhh~`m zWnhMHc+Z8Xt2R5R#OZzZ0PVI#E23nQmkn4BF2mwH*)Og(P4*w9RT3M z<*!#sT(>@@i0FmOkRhh>9RXlVoR%ils7-wF@5RTU3>SP^AoM6fqDGMhRmxPT(}q3H zm@)CRV$`b+0k!ibF{{>%V8d4Q36yNXW||CYYKHc0!H^^2(uGLm7%~(QIXrswAtEVO zpz8k;E^PQPVx)2lipszd-6atD?hqvMPl`mdi6M^NY_PLu0H8y6E>Y%8kHn+3{%Qy4 zYthgSR~yz07hMs9M9|3&y0|ymJT)bfdE_G^9agFe0B`R6IdqA?0bIa9&<3Y16%pXU zcSOrS5e36>%KY;=ZPl@zr$;>2!I(2v0;pdKcY?ZhIAGgv-oCDFZ_%TKK}ysUT}IO( zNSF_g1QL-3tGKemf)!eLAzjlwvz7?vh-1%M5h*bbKk;w@Kz9aNbBaR`bns#k|J<+u zjWybMBaS)hxZ{o(e1QRvK?*r!k3SN5B$7n}nIw}<`nV*G4ODT)6%{mjWsXl`$z=Z& z?F`dEkXmjzrjlfuN#hOY!39k%2H7$Vh7&0mXIK^VRYF8l=tU==efn9^bm-J{2{r}X zv5iCx2+_nT=Nyq@K`S~m%0HD>ddU}=YPu<>oqGBysG*8FDygNKdMc`^s=6wxnznI< z8hx}nE3K;<(~dE<>bfhhsa~SyTUgjLjVPi_V-FU8HZ-TQ6gdG3Cd57RL$lRddu?1I z6;zK60Q4dX05%+0(KEMzCmuoMwfJHOG0u1jWxIofh_>cV%*Rd$H>AQL_9c1z(gQ#d@}#ahE12v zCN{`}Srg@01WhiI*-_bL=0ObHe}?r;*v~+(XTfPy$QE=*F|@Nz1rs4n*VADIm~w{N zQr(aS$Q&hy}e8)d+hR~T?~;bC$03q?`CCHYlTqlJJSp@d=w0!MxF4=n(kPzyKqh*Jv) z1vvptJn%fTL_q^^(hWZ3gi=rz*Wlv~AJV0LHUOX;)5%AeCLkMAR0giE{Jf1UX)`gr1L@!nt;6=&?6N^*aSbY z_YjR;Eem*QfJbJ~3RdJmc`ke*NPc%1{E>!!HMC#-##a;`^os`Kdy4|n(GDHV4~IGI z4Gpi-jAopGAShVkM>Nn4Ekq-947me75&!@v{G(d{P{Kci0DvOsBYF%ug*FP(3ui=x zgj8FA)MjeQ^Lpa=?mK%)pr@Et?zZ z@=kWH(`PLeS~)$_05+Uq3{CUTOFL39FsL)8+Vp8*Rw@)-XyXY37=RSAk&BMlz#Ih9 zr$IVUjb<$60@cuk6Qs}!ZA|nQ|F{?cn(&Y4ITWH2WeESJEEP<%nJgj!2!wGWf=4}` zw5}LSDO`kFn07)Xr%>}NU8bT2JK_|mLBYY&CeTwI8Wup;42uYu;SYS^qaVvi9Y^Ny z4}Ng=AO7G+=Qco%XXKM0moNv&8bA*`0ALjQD98o=p`Be8#Fq`JXa_E8SB5lbAP~U> zDHgKZ;Z{p7{W~sl`)AFak(052YiwakUUFW3kXyi#ogUuZ!@KG2uH z0H*@Jhyeg%;ES6Qx565cOR+?83VBo`6{(x`lO41>(a76h8MYt$EF2 zTa3i+_Q{k|%|;MbpySRF;U2aq!Vz>44+IzB8q-*UPTU3n4yJ+#ng}5hm6u4Nfj0FeX5(9?-iL1k!*<7b}=m)#oo!p%(N8_V- zxX*s}@KH>e1+`Y{1_ar{G~$5{Xvh-)Em(#;%7Keq0w8z0>s^##m5D>pbIWhsFXX1$m($qIBn&?G(q@a4m7Lz z*3In=zx;J9iFV4UOjnH*0FR=E3#lvhj#T@*;n~9IC+txR zJ?Nnp^mr)0(|qD~%Z6x>6ivRha%=(=qa9Je_rCv{a_;tg6O4s=k1GVIG zkdTAJ#SWDcyu)d(70km0>l(2=MsOdIsZ^yPy03g#cA9(0H*)Mxq5Ve60lUrv00^NB zJs*Q$Xo;BM5so+jL;~}3x(uOGor68OWlwgEzL^Q)c$wLklKrb{9^f{9TNW?MuR*TR<4AzCvAs7NC zAmOQ0t#Q)@CQ=4|1Oys{03`noNPWf-65$d8z>8%>5f;(>?b#@3gO060OE82lU7-p{ z1QM7-GvGrnY(qKZ*Z%e3*@S>BAVUZwSYJ3^Z=}LMc)Q57EfnP2%4##HQD zLqy>v1))QbKs&Sp2|!^Jc7z~0#0O$SMDRg8Tm%S&LNB184!+1M9%REk+(S0#L0zU#yrVS_1!zqAQ zD$qlDWL(rq9Us<(#~J_4Z0KUv$s$8Mp(5Jj1Ja{K_=H-G0z+`Y9Vo#TP(wIKlR-$q z9xOo?FoQf89sqd5D8SmrOe4ks0baO(M+8POy+sgspEz3BbbP}e7{nfY!_)O);;AHB zAP$v$T`uZlU&$l@Q~;grM?QAo3@g4<2$Y-UFaJ7JVYZ#M0N$+u-zU%=H!e)q>6~x zL-YbKOvDh3LO1BcGnAwz^3kTrfTyHcQG^s+LqE)1Q=ZMV z9fJ`>gaJ6hBY37m%oSaP!$0VPV-DAJ*a1H{L$Nr6K6oNoFrfVX;^D#LX++Xzq9!9| zpakTHxVdFJ-p`(;LKfVB6gLf>W$uLx)cY@{R z?O89713rvHFXUG=EENExLO9?5_hDSnwXUMX7XdgaimtcXsGy)`px01x0#k zex3~q_#~z4-DS($Lh{Gj>0z63O_}Qt1Vy2R& z*cng(hw_J&Vg!}0DzXA2T#nnTV#@+hnH)I;8IVDq8UzA3!JeSSGyFrc=qevg2Q)Yx zLEQfVL+ODC&fcKPnTIMXTDTdNU|$5@>qg+m5M?Kw0_tXXsxxIPwhU88K1A5a6)P+% zT5Q5UFoU|TYueZYMGnD%mk2rmIj|h7&gsx@M7;TCzm}}D-kZQis}Hg)QsiMp9_ra} z;xRxhL{vby5=7pu!uOHIprvWf>TKG00X|^EE!+Y&+yfnI!fPI1z1GE9>S@S!gvVKD zs21%+0PLUEX|=9wU8LeFwjxvBVKZ5RH9|!71p>+v1O+67H=>0KRLVq+t@0>H4xIl& zAf3YWStf+ukltPd)rAvG=I!5_tS~gLFP?5t#cfBF<2iakI;g4tq#mT}^;&Q3E$<*+1@HOp>Pjy~kibozrqjM6 z_IiX?8bnvprtPj84On0476cRM-CKCWaH{Y6ri~rc!!6vy+HFGI%rEN#A^mpLX{2BD zDs4q@MKEaB!0s=24sb_Ara@390#_Ii5N|^e0B<5~K@>nIOaYvR#WMVZHBkSs@utl+ zlqB;lfy{Vr^V-@6W5fi`2etC=L!GU+%`OcJYazym;-C3GQJ9ObOwbj`b!{xGDHwSm+=%96Y~PP zE=RQKi@fO!6W11;&_)zMLI_t_2=6~2Brc=ObPPZ!%!5DpgFO%>9h?8KC)aUA#N#t7 z^Fwq=I!M4NLvyD}^F~-Ire^AaTi1unudn3Uq~4V;P4G8Hi~?7!S>cMWtMFLpyW} zU-YN0u<3Th$ZoVdLqwmN+&=PjPv`WSxU1U4>l**bDr1Zg;6)okL~l8S0KUaM`~zR! zbm1a3M~j_4bEXbgZ%8vls#@q22elS!1;!fi#&)bzQ>_bW!9+8Jg89X=tWXW01v&gf z&vJF`dbL{1t^Go)-Bzda8a4A`L~D>HNPqPplLgNj#3}r2&?5h`ToYGuz%)S^99m?< zKP&@acXh$?Gg{28Sr#^0_S)!*Q(~hsLm(DA0P zG{}QA1V^Gp5MRS+U-O5$aQ!N_sY3Si+SDu(vnju}P6tKuPDJKzZs!K}mnnfPd`#9Z zn2zoMr!qw?{6jb_clWlgbAxqu7d1!V=}yCTK^Oor5H)s}HND2Sab~vioPgG3K}2je zVjO`QyEk|@_k7d0f1{reLihb{1SK_aGD9}p0=P!B@B0Ek{4%$N4O2@y1P_qGSkpxT z{KGgf_-|Y5gV%Nw=UjY9@qG*OwDz}#M>B_G#06*Y26zAPi&t0>P@6{30VxdJQ~bjm zySSe`HAZZ=jL-NxTZ8~O=@sm;j@vdtkN`W>S#|q&WQWBOW3qlNaf5%E@DNW%$TV4` zfFwJ4pFsIVNI6iGax7*QfrpA+QVxR`G^UA(cG%dv=Cm=xee7CyuW_yEdwEm?q( z*vk2w3-~_w_>toGY5SE4OcyR@I{hj@$vJbF@A#$Dg(aK0CLel*SuNHw#BM%9o_4?r zndw!e$)r;{ozQtdnsx(HxM9~Z2NaF!LU>sR8!=$`om2VK(#0q2axedKFsJ#KDO7qF zMEH(xL3p-Sv_PEeI)?CiS@=4ibNQyPnZ8~Dzn1?yo;yTigL|ZP za3B=sacjj2d^@;Xh`3XPooBeY|GGu|G{Rdi*R2C>m-@jAdR;)YL{F_46PE^Dd#vj( z0F>`lzN6;n>wIFgaTBZvY&kDo>MRs`?62HY?%EsS^WzMfz~v^965p`Xd_%S0Kkhq zbddc+*nQU3fD9}?<2SzJKR)C~zT{7S4SfHB;!i&2XTIh`e&t{OZ5&;>i$XLezg#R)*N!4sKQJ~?cm$~*th;BY5!AH zz9AHX`@cW@$G`l~KmFIg{UgE`AcFnxKmYeX{o_ACASyJFU_m!(&ajaIfMG+24y(c(&%8ejZ-@segun>QbJ_}2kvPoF;< zf;t8&qXCCgSgiueu*g4jOQA-UI+gz_O`SZePK-G-Ysng45Qz~xmTXzGXVIor+viIk zwQu3ZMa$MLS~zLWtYNgUE6T1V{ceoXF5QHwf&XemoEYL(#*e37g*@5jkz>eQNTd;n zio*`ASj||<>7P8xr%|VlDw(ol)eXOfl{=euTDrAy=e~Vb4x2M+3@zfDb+PK=6Mwa9 zMD;l8=8s*!mR^$ebn6fE2$@LZks|^QRk5P86xTm)*U_iHULA7u*RgZQr@dQ#ecNr( zwmGB5O(EfbpQ9{5hjeIX9TJ#p$+`jma!)<=*n3byh754z5fdCDg%zTJvgV&>CJa%; zsv=~}!PMZhPsOw7ThYZ9$2$M$j5fsZZ@8)$d@M%*d}-$u92J~y$Er>oQMD3{q-+I= zsCcBahA?48m8Hb_=aeL|%+jizUi!oudCXach=wAt1)X`8Q6ZxuPfO9oH(`9UzBunn zNRAr+>nljYjh_P*l@RBT955 zXZSc`iDtsdfFWDN(V~fJs994c>)e!6#W-cv4L`EvSmQT1#Ig}ULX879q8@!APFUxT zh3-{OC-an9sAM^&lZXhgkcNgtP=%BTfcod3C!P)WP-ja@;U6pj03n|{7$V{yDKIj0 zvRG@CkJftUyLBwz_#6MrS3L#gGuei8V5c2G1HEoYs^k?HDsmmh>50p3h^WaYrOLqD z6C&<7M2I&M;vXac(BdBv8VZLKh#u&`<)&^}K<1fguG!|Ban3pC*!t+%=bwQNTIivP zE}AZ*kxp7^pxgS{jWcHa8IeV5(Any%Z^qyY46yFnYpk{A+G<$Z@#X8YZ4Mjlwb53a z?YDEjVOfu<0-5fYqMa5Z6Rfy)ssy~fTk!R`tf_!zreO#Vd>pdo%7;erR`N@}sNC|) zG0$A{%{lMf^UpyKUG&jOFa7d5@M6RC)md-db2$p?S@ICNbj z4xp#5ntQL^eqVl>-^`hpMSLF#ueuI#CZeENZvN$gjGz*Ctdi*EesgJ zgxz&pR1e=S{F$M9=%HummhSHE?k-VMI)^S9Iz>uAx}}r>De07y5|B^?1VM?}{H}Xn z*FN@rJomHLdsu(0bDiJw(?|wptQnVA)QT5~ui>`oH6(a{7FQG+$H&`yu1y_eoEu5S zW!HqGhyU59*|vkvOsH7vBkSd32^0kQPsOej_V0?FloIwuVuIo+GA-0829K(&6dgt) zW$p%G1hPjHeLw?{HN(l-&(uX82C%preT3sIKLI@DU&6$ctOMMZdnMSB*HLk?zvoRE ze(h7-Pabk}X|2Ffm;wC`Q+oDjn)rkadymm?Ov3+(eqsNKeiilbnpFf##=snBF{H|T z$}(yq8CZR9peQkbYj8P)7u|bo{?^gh`RF`m zQORB8my?sd$B}+G$GJkCE(>~SvsvoLbIQ902f7$m^W~%i~i8LgoP> zPMq}A2dc6H^(r+YPPN4^R$c!{W_-y*A7VJCFC_YL**Y4M<+?R1fQ{xl-r{S8ZElLgX9%CKj2gEbm(HC$I z7AV4qn7!*MC*81x2{|=UtW@=*2#jQ!-KbL|0Q>Jdtg;-bL(DWP0p0l4?5)B&>jCEh z{Q~b?27&w+L&%9wJi>OsRF>B|qBQb)2e>j?v7syFC~VbPWhsj@#F>UXLosxa-HyXj zO%WYaYI;yn<5B-cu+DxY{E_)=ey`qa4Vka2|{ z(ftK(r^_+?|DEC9tiX0KXs z{As5mH;en?;+=m#4(0=6%2&&<_1rdiThs!mTJ;tlJM7tiIu&A`05>X#OT5(s<93XE zZl1#k$0S+?h{)J9tIHftQ?Rr^LwYZx_#zCK7Olz{tKSgI+<_U;2eI&voVCZ>(()&y z-lJYsd6pI%ysjV%4>sRg33c|-W&1LKk8)R%jE4a$BWWi6DgA2wzF)Te-6nRj8&h-_ z07Tq5l3L2vZJG}HzulmHC(Z`z-+*Fjp@nlO*!GsHAzlVV?Fi)(Nvv0t2iY^0q|uC_ zp;He=t4hJq0EzQvw)5y-FTR|$Gly#^5s{BfES=v_JHgqSe$T9bX}ZQ!flLsD=vA{` zd-lCY#{)M=i7|uIYa|RHhncQ-j%^+94u5IRhn0SRXn5a5P75BKVy~dn6}9+)lp0)S zk2RdotoHXDU>J~stQq0&^lm8wgi=*m5Z@Rsk&h#82dxTs5%4>`@w>gs?-m~Sol|c% zes0L{0x}&lBy|7qA^w~abzaOwp%|eS&}5j5-4%pKYQ&L+_K<-Z0OayOw`W8r{Rq^= z1#ML}jxpZwdLOoXeqD@SJpB3fJJHXZ6ilo!Lf(q~+NR?RC=n(f%h(P>sXV5u9`NVs z$>2*Q=h<2*>qQ9So}GwYs_BB;0hIb&+~6zz)GS&w9LS=EQ{W2JYKDbH;Rd{A?c2w0 zZa!*9*n6Hm@dg+9>nV4tfB!JcJ$}ZvF-y#|`(w8;{+I|ogKysL$wAk)fB};2a+{%V zhX}||>i!)3N(42!g3movD_{B_p_*wxu_@r8Q%aNx6_qY zbZV!5j!7np|^`I8`Ki-=(k&Gph2iP&;$}!N7aVoY7 zxBH%JT+ELUa;KGXquXz+z<9nYEa9vJGHjfJvF{pbNr@`r;Cq{nDQQf)x|9b+x9e)WE{`xY2l!Qns0wr4?IZ0z&6Nb{I|DXHR+d3Fe|zTQknyk~v%MCF)$p!LY+I ztiePA5D456Yiec0I49xyAyAjLiz)w0gp>z;;4n6tXHH?)=|VtKq%U@Sf~J?_? z7-!*=1_)AYXMae13PjU|sC6v5PfXm$%shNuU|ySGC)87@Bnp3i~4| z)IorU7c9>yT+sq{a_cC^fD9vLl=N?^eam2H+FOicR>4>p?c`L9KqhiSDMk=c-+s4* zh`a1>1KSrIDxD^FmDXG2yqM%dM8b$#qa*ehbm$W0Ait~O;Ipj&S9eAyrr(ArVqVgK zHj>qTLNh4Vs2=WQF0(h0*BRQfJZ)c8W0DLmpbf36!`4mlRMloe?NF;MA4Q zJA*}ul2`dMzSBg_opPtqlq&2OnMvL2$oH`xGwQ`gAC9pBTKZrvd$O*vpk6% z5aMgVvLMg>#Ed+;fbM!AAP?YsxB)MXWwnEg;_^4o4hh|ETEVyOiu9de~ z!e|~|WDs|NB3Q`F*~bxqZ@|4LN0MqEvswm;2SNbii0ADNfoX;dY9TWk6Ke7nc!fx#FC*)SjlQ0T2FZLY=98!u0r)lp!xa z#yL3Gy*oT*hmsnIpXg12QovGTq|*^gF$^;M(aJWVpY`e)9?IV^p8tYF9menwou$^D z&9IWT1xX%e3_q#x+$rb2f@Bc?DH;ea1{Of(2kgXxAT}`ELjjjIMgU-dB1t|nE;ugb zjQ5pxYA_ZMUoe!RjKm5^+ZXqwdR0U_&ox+#A^ax6%MpBem9($md(WPH?}+6Oz_)=x zEG~S)f%t3U{%s(v%nG`QvahW0Os3ULW6+ylWLf6q1+UU@(#x{=4XFEuac~O@&Be-S z2y-TgWDN`;#~)w1?mN>tfXcVYBl7qpEKWUlUDQj7J@x4Tz&|<`Z?xfWm=x+}mfq0a zh^d|k@LkaLy`k{6sCG}OR`)G4%;4SYqB{%{v09Zu9WKK_a#+;%Zx_lcv@Ki{f*Jj{ z$vs;<1H_rSsN;Iu3l&dGvnEM8uU@}brWU)X4_0*_5M%MC)LAQsE$qZRb$oN7pzyV# zu@}23uZJ!cmgfkimA!8ILESW}%@PU2HS0~WF4Aw2sPkJlUJN1o;g1%?O#!uMc-Wyc zvM0C7YyFttV!PX_&DdsJ$x~w(zOzfM>Zhz`$#~jB?9dy&0E2{;5d(nuWkhP(1uEuzy>9rx1Gm_2to8jW!$|#U}y5?9EjU8&dBZS{k4Plr_ER?U!FG zSw7A;&Dnb??`5j18rL>(G}6ixrpqRU)emJ!g2^}t1d4~T;LBl^1Hd)|lo2pUtUV;L z43ZoTsp%W92!k|BO>|g6y80&GOF@uQlQBD#cJh5MQ>!>>c$m6=Y#`raj|zs_^T z8Iz|n3cNDfvGkF0@TZ+lYab;z$7`p0JhvL-2+_YUnnEp4-I_k`7VKU88MxNO?c1j= zreI>TCug^t@w1vo3mRP@pRLFM(^HGqubZ~?j&alrQ%O&ehF05K$!Q-j9NSa4^jYp_ zFVI!ZH2g`sh1U30K;N4zZKW?+hn=FJ;VXMq-ZJM5+d%Z(ZOG}JsIKwyaNM$PK|}8> zQR*qVx8qpC{VW&dJIgOiDXS}JQuA0+pCW{UYYixPrTMQm*2FQ^-=OuFIt9Ykc+E80 z4Xrn-Z%XFwH^?o&u(Yja)xw&$KR@jwuR?5|d|B`zT2wY!1ga-KRTR>K7hK< zISE>>a^FqDy1p-raj>p&K#n*rbEI-heJuskMO4A7%z@>IBlU;O zds>q%`giC96j<`7!*X9=Eu02Z{gl)@xtCalJzFhs26zlu9z>V2?1FahUwiePwN?Jm zN837yY5M`V@cM9C7qN8p;rBC!&wuEFf_5~0&NPGmjC?!a8Gz(^w)#d}ofNi>RiWe@ zLev~vtm$9Aa-)X*`hR1V;-X;WdNxcta%b0m3n{W!L@1`>buMmtTWW^J)%4Tei$BIe zf3t{wnHHYpES%7Vec|%JV6JADWh8wmvkU}9A*0dpsHGD5$_C@`X(Yn1`OAlr$hb(p zpEbn{r-2^x(E)y^0cu+mI7vK7;LUgrw`GqL$6IR&aofLrWK6D81wua0|K0_+>T17^ zqxb|q`X_N!E8=us6WUv-VXQWIb4a|m)LzzmiB9a(`<|5UoVnLf;*}=w83k z?SHaHesje;P#;2`DTE``yq$wwqayYA#ZvS*tBM~{Ov0~U;otCE+3k<-z+@qg?}y2E zZEh*Sszp^d=v%A0odU$2C~i$#lwlK3(j-Kyz`Hr<^{0 z&rRLqaE5OB2sf+SAC1Q- zxB0DXegu!OX~By&l>Ra$9EY0SBJ9Vj-e<|blB`vm%V@-l0}01<|$ zD{_}q2&kMaLFehE6Qdqiqtdn?eo57~wfJ#Rg$q-}ifN+UW=?WYUgBjelb5l8Qg7mHu^Dt3;itm$Kwlj##a!_WVAJunD~= zvCI$xyS|QKWoEXPwK3Vxi}}Kqn49!=G2Um4>UbfQbBW!w5F^*U@Qss==>F>$7{?q2 zY}|gIr9|{FMldfhUN1mMwBE4XWNyM)iS~LPZT=CyhfAc=SGM?#5>xyDg9CxN!S-$mpEAp zF!fQzXkWl5_#yNWwf$Ae8hXk9i7bF9f^ri_onS~-6JJQ1$C8r!^|I?b^d}k<-DM+< zSxwoUkf*4Ldy$Q@b>VB1H%!K&JJ?h<=ft}^gTG7+wG7l*viZtGP90k!5Q_$P3xjg+ zFCAvl=xA++WJS4=VZWwjiNY`Eb!G2u!>!W8f3JDXgkNtuGAwAVF8hbm-Z$)wULQBj zJY4P7rH?TR>*+?`&pDo9VE+C&(|><+vegg3MFgX0N`beg$jABo5Yg?z(^$+7EE0LI zW#p_?m0XgCHCGHYs1)n%pk&MqVbCCxjl2r1q|IsE|KiNSNh3_)71CTf#0|cRo6%=%2iKL~( zM5rJsM<2l0;Jd?U0%`Cb;YOFLNLMog%=;AB2~H>Z&KQGV!bU>%{Ua8NokW}j-6z?x z_$#i1)ECLh%{VbIu(G1wJ)FZy3Tx2;~S} zYE~9za(maBm_Ukls0k5p<5|~tz}oZVKsOa8Cg8TmL2VC_=v?6h1lh; zlbn<2UwZjWGoCRw;-)uDM~;6$69fP@6oz)mMuFUYHiA5rJ*6 z2P(%^!Gy=7|6$bG@jmZI<#*!5qBriBK;he0KuV>Qam|KbzncSHWx%&8=v`KD?c8S>ZYUpGYK(d*N z{`3%DNLQmG#3zT)MpRS+)R0o%>yFxFm6VeZY+)%}c7(@Mz@RirQ}DZFk&IOEd_m5I z@7q*z5mMZe^H^oc#0(>fZfq61ms$ze$}Y2I;!|RrJ_R_xD;qwG)5x1eH!Laqlb`-8 zK7}XP8m@$31cIW-E(dTJQymI@2-fgMd~ze~V3N@M%Pb80BMvSLy~14bYEd@)kCjS< zGGv1JR|OssJr+wIA`3l7pMU)JG;WT0A1&9(mljltMr{CA@d$ z>}Ni5lqFX68hs<)2{sCQU~x#iWme5moD&W7&w3L6!}D6d@7=?t3{M%oYcS^P^_av2 zSL>6#Jqe}0O|s@ucGi>aF37R+YMUEzfPVGlS@-pS}ADWc1_|k#}oz;fmf2nG4IV zB@WHs@`gpiC!(#M9YxgcwQT)fU8jHXh4TJddJzSDe@*lm5VGeQ1-^(ZTZ;56i@3Ds za#jsLXNz1)@K_#wzHZ8$f%R0(H6p+VGz+Dd_l{y>r=jaI%YNq`1(VmB&HcF z7!pKf=|&u~^1}L1-Ytk+g^9lJ4B+CH=;a&MyqhrF5q3&KdTggVmtai>@%{Bp{7N;> zG%>F5#$3cKh6dsjrADqiON7!R()Lb#YlafT86)>_Blf(3C@wL0f<5dp;{p;R#qy(r z*cnr5B+J#vE6#9S-y{#SQzFH{jb_Bn>=293gc){EDqT`uxFs1L>K3mg^&MJkjYikI zrEaN-jja%WP_s`{bjKikEA`Dcv&rY4naAXN^A z?S+kFllkOFV!%(em|tq?u2s<+kmSvpbm9WOJGGalE-&L1g501<-_?>d;!;FwQi2oH zI@r?h65x{<860BJy<#U-o zE8#C|d@`VEf{uuk1cX{3w=|BPfjBBhmcv7!sqb<(_E?)eW@De@0-#vH0y!fwazKK}L-X{*_S<5&xaHX?Fox5jfGr9{i z5ib>Iv-qoPbK<2{v#wQ|9!6Ba`=cV!qnD!YX+>rw7Gjy$A*D0}36Y{^^9taDIGgG? zs?BB#a>v&8tQ@Q?^5^s$)JGkcsr+=(LEpT&2IEsI>Menm}g zbNp<%fcA70?qpF#QiG~AKB|F=7wh6?7azZE87D6No5_GncFKko2gC1+t~|}GjsH}& z`>FDoM^O__U2AeZseIjchdLP_BcJWms*u|A>pEuf`oW%BBjTFr@;9Gq%O+~W%Kt)m z*)e<8Xx@)=EqRozCg-NsCSI-@d^v8o#%X*pkgBL*J{QuMNL`p*n9^|E`1GjOG`Rkk zM>E!F_?bu3RBeHF5XnJL6DS1XT8M}ZZV-nwCz;m=Fg0P(6kTahHe-jg!EmVA8dS%d z)Q_9$lN+eGiaqE3=}ua*aa!@mnz{H}iPi~K#_Kpv>bUB%29jFbC|X z?%D67>zF0W*-}ugBq!NqcsV?p?dEuGUlJcT8#)3Fn+sgpMYtNLLuB|Eu^mPq*DyPf z?j27g+kLp+owc;+FtyooWeamr9%Etgw!UndB|O$ECk`$5qABs?%EaqQz~SuVr|Arm zYzmR2s8(%cBStu?G8}4f9oLppt_!A4l$Q4Ty;v6t#Oo&E=yrewX{jODqF-*PcezMV zkxLdT+;%5h5)){IRBGl~hxYWJ_qNXuexHiCgP^|7z{M^^V_Z zHAxg#7ylrtFMhW#1@Aqn{CgsPB)aE&LfrmH_WoZJ)mN4;x48Tt>_5aHi%jPGZ7=$} zLy@4qfh8Iwi9S;H3Nbi=)Hp#>;0!ngc78R13;}w-t#@v@cX1rI3Qd0adD6vfH7FQ5 z_^x13RXEoH&~*asXi2F(e%kWAaHuooqgC%m-HngZ2}L<6BryP5z*Z?~FNuW(1(`oK<1YUMJ2-0lIR2-M zK4fnZYV`NhmpNf1CaK*8R$XnO9f=cTc439(QsYRjPmFWCx0XOC6h4}}{|#dl4m zeJLqclhYxOf7NOXnbAW9Qs)I0W@VUxx9fp8ctp zxJ^YZlm*T|917QR;~+B#6}1;>@7w6D7X+skr7i}(UC&~oE$KJBh^WTd_9j|7LuX7a zV38LQ7RQd8Bm4-Mp(9vO)$aALUyPvp{8MAzExg$(0qX{drRt4$W+(4%_StA^0&a(& zGekIYHWKoFil5+}9nXA#R5Q2giWGN09Saykj<7x&EOieS*2ChG!X7z`e_gd?Ik_}| zKT#Au8O_stBehcYqd{UBa0lfDmEpzZuBA&8OCm7cz&M$9_=BZB0`{vpX6xj@L9 zJCn0op$i}G*VooTs9CSawc({Gwf8wv6JIrO_W&8Qgg*(kUc2DOM`2$*+qzEM`qO~g zx}DnkZB24dunpwhzPsN7JjcFh+gw=Cz@eAJo8GR-mL-aiBjnwgN7K~V%{7Ttwir@I zJ6E#!NcL3$(5Vro3cz`EJ;1I7tg;1zWf&4_$_q$TeuEM1mR&c?_ux* z2D}91eJVxv@^HT5Fy%oi?es8-ekVglnv#(Dt$G>gn;rn5Pok`UA4iBEh`WJ6>C>=) zE2nl{AHMK>055r~Vek>MJqOpmBBT30pwTxJ*)aQxXIdwMYOLT0G-qr}ZsKTcqE&%6 z!3VZDBMKyO0`WUNJGFFaJRWvixo*Z%ZeGbaTKPb@(#QKb@cU}dhZB(>uA1e0B5{EQF1?jmss|){7@PBxuN+(rR(h7%ag6fFPKg10@CyJj1}A_ z6@bSN0uiuCyd$90(IV^n#OC*>OD1zR2eh4-`^RJ;I*Z{Y${XSe55w?(x&DYGtB9U7{vqWY&QSNl%eJS^>lX9yhV{v9*Zp6v^e_JX9UWVD(tq!C z((kmk?s0*4`Sy3)vJbnc`@P5qjI!HE-_NT}$gZZdafaJD+xrEtKl8SzKL-)%lRqB} zrcj~4M?DDuHJg2$4Z$Jjwd&fQ0L2rt=y={Bc9m1fVJ>?sb2}q1VH^=;<^qiBSsbM0 zMgNTpll%?`^3c*t+Pktj)T+6PRE)O+#6M>NH+q~gP(N)y zSE2P=^iib`y*yWi#*q1{F{TJzs4-_5`Kq%P`Cq6rzlxfz&MR%d(BN)c^ws3;y}X#9 z&q?M4vU!@FO;RS`RAURx7-da~5QPcqpnt2(l9T*-_e59v`fJ!sGQu=^nyHX2v1L z4d(9B9qktS?}bg~eeXY+o&-1>ue3z%e_C-&+J9kQfcP=K>Y8JWZ_!ZW{9DMqZYr1a zsq1m)>f?I8>4tHWu;?2vV__ca7d~{?8}0Ov{pg@?%9=JIKRZmf!lnk_ZAR>n=T}6k zbFFNL6BC-X$6y8A*e5dO200{ib>29n3Vsf9d@1?+#u1@N5$u$yDe}iD+t4J~IoC4a zk8{3bZm>(?)6PFG#qRUy#i6yq3iZ168KcF{iFzklk#77Gan`dfY&0Cb3dn4)@8>Gn zz{Wv1mG47AMJZ4NHd^8u@9lBY*pF!!ZP;3tKx=I=_NNy0w(f((Q-IM}TyaP-e^IGr zU&}XImsAn#IG+dNvQqBGfl(TnfZBDBdYt(puYNq-u(LseU8bVY$(A=zma1;mV%?y^ zyXO`G>o!7)-a36S${a6}_JUEW31sA>GP% z+k9sIYLY;JJ{XX@txOx*xjIyO2%DiI3cC^8r3f-O9H+XA?FjTM}l&S}LLN7scFr91Q$Ps1)=l(Cr%Q$p_<` zBW)SwepDhw_n|T$NlTQ9l08*kq6*x5H^@U#PQ-sS&MzMhmA5glUNGJ@ zrW~OT7#;l@iDpdihQO3|i`5)>!y7Cf8%Y}t#o$w=Cn$ehctk)86XPk!R1t=5kAM8U z<8=zv5!N6;;k=NuFfm*kSW-%Ffs#vPot*=C`#Q3HLzk0S7S|4>M=$B{1IssapaWJ& zUjxMAWTpx<{bd9T0UZYtYEPznsz?Hg)XWV}F_4(E{K=SBQ55S?G6(WoqLBmi z`rvR+5j+xee9y0VfNdKTN3%YHR?E22zvHQ+x}?cM?o~ZN?T3f42EzKXyte(lIo<;- z4qjPK?ZP1^=;=-&<@6OUPd*`iYM;zvHAo){)&%P85QX0` z)srZki=;4bM?8ZdOwqGHsg`7W*iYxxV~%<|vA%ajp2URfKZ^sMBb32d- z-t-bS{tP#s+_j9&@9^lwND00r;stCYG1SlCFQm4xs)GhwNH4tJl%}il7C^N-3w$y( z!TW{76x(1!Q%{r~AqzOR$NCeNFs?z$egFp1E;5GXGK%mt)AZSa@)JNvnN4+#KX9^3 z#dPO3OMLmybntV~W5t@tRj7gr12_Qg3`oNxArJ9c5&(2*Wht#w&7iwqRxnAs+glXQ zQsNKG(igxZ@XtrkseFk2Nsg7X*5(koLT`-I+yPdl)IHvCvXHX0$9pV5#|Pn8%2S8d zuc-kxhw+%$gYOwB(b3dQ1mNTwp33RefHwzMm2aQ@fH9!se8X0jm$-K?oNBKUrAy%% z%7|&3+?l)E9+kZtNN2ZUp;gdf7aw9I)FxvlBV5A0uGBE@wt4a1+!`s+91T}wz}Ufc z6$8j^%b*MxD}k5ntRjC0env=zkhSrsS-)uYfpc#_8L;HWhy*SiE(Qbv-qo%+tt)wK zQU`R^-BSecU#x{_MgX~<86e=Y7)c8ds1_PiRZWTfb<1#{hzYR5vs|6-*zZW|nXT6G zuR{Zz+?|RpD|-?uQz(7UXAYgJg`I;^9s7)^qIkxDy)B*qoETNOu>Zh9ZOr0-H*qp7+of(C{mdx*CLHZ*D@nWy6nw%{ac>JiuS<2WL12cdwwR z$jdI#dtB`F*ho*%7WLH~%bxs`6;h?&tLc3gc!Oa-NoDSCYyy4}W<~(&Q7%DXPvVtP z{f6eaps~lYy&Rijitqw1+iZd!7$jAiP<@@cwp=1h-N^H*%AZEMxXHnQ-b}Z{d#t^yM0=Gf7 zz5&_|d3f_6lvd#y_MiDvtZtl-{9$r}**HS&1MF6c^itTT9L!%(tDr7RW(JKx7AFN< ze+9X01x_vOQ+bfzY#imK6tj`Sm$m|JY^<=e0-K(UBYC9xG42z}BYG5t8>ZhFmd^^t z8vh_2DC&Ykxez*HW>w>4HR2LB;#RD(b_B4B!tyu6bf)H7n3F8oR&l&kadsMsBT;p) z9D%REA7|_RqvD@9j)r=VzKR-kxl;+L94a&@2@%8kW=}iH|2jHs__@+Zu&0WGQIUQZ zvA4I{5wS}8of-mPJ%d&~lUqGYNpS&Qe2p?%jdE^{3Mq|BEsZx;8ddfATOJxUsTyyKHQljg9M)<}K6-by?V03_3uU^f{ZriQ_Yj2SX7WmgV!+3*vG~ebJ+GaGLr&=46+Fw$0uu2mm`!H-gsofjgo}8GWbx5;?H{NOozulM;v%fG;)F1>M(3y+_uHzc z;5hgVJPf<5wr~9DZJ}){wbzA|j2sqVEGn`l;SB%P>76csU=|q!j~oNR#Pnc6hzl#t zOCw#lo$fU{;2>2OaHCwy$)}Z^(Dw&RT22pEDhnjgC#IV#TZsxyl#4<3?^+dq)oRQW zNYsN&A7tyU4vuu~q7h&Ke7*HZe&{pY&lU4wNa4X*SI|#eCk-KRNpM1BV#f5{q%>GN z1{o7<1}7_}{MI*1Gc~7qRteJs$<$~<=?n#U7UCdL+S~DAd|0k-Z`@DfI~QXkyP$x? z31_kecum>BPjGKW6Vx_RwqA_G#_+K-QcE*Z-^bDR2I(Xx zbQKwCe=*V-PBelhgdSq*2bJjX7#kA&H%S`vf0CqcQFqt>9h1JfdBmhqH)nsZul~P0 z=^v=eo&V-ZpI=6s5oI@9%%z z`v;VM^rUZgzW#4ddi&p=^!D~6DUDhi*Y(B|gme^lwU zwYAmN)#c@t&&$jI*wX)orRN@D>6zK-si~>)iP6!~;o)J_`-+oZ3| z_Ys!9sU-MYfxTRAGV$7b@NL}3lIZ@D7!so|Kf79rHRNE-5Z9 z4i1Mu!qTx3NofIjVPTQM!NCCmi2(rtFJ8Rx@$r2Gq#gWAo<4t}6x1LQ(eYo-w0L+Y z%E1<8Xt-c&@(4x0Hj2wMEzZ>|MJX$y`1lSbg;5N2C{mJ3D#|41^hbQ!#l^+Z(b3M% z?$MvNv9YnTvNAI>Gcq#L*Vot8)qS+3H8eET|DmN-{>zsBFIZYkOiV;XL{L!h$&)9% zyu6RFG&?){qbkkB#PokuX*xPuTH61p(&S|1kE-;e9*x4qeZa(gKm(xw03QPU$LD{- zr2l70+6aoFn)?5eq>~hr|079j$6`370tWtnCFwRpO`$G;`%zAm4yv8vmh z>Sm)C{rDq%L4?*4FZ$=IZMO=;B?C`3p9P?ZZ2hGE6wJN&E;Az|l^6+Kdz7U6KiuEm zob;!A^#@155ALz#qEN*7ucL2ZL9gMz`OR!YPH@=mwQjZDcH$r|H9PS*#w%O0)9Q!N zaHeU~@-Vi}JjPJ2l4ZtVuu42w+=0$enLTK(WlSM+q zIL9@WxgH)hXJ16w0BC*9Lv_s~D9)4m_Rk(Cby`XTLk)eukDoSlpY{yl70`E8MrCd0 z)<2v0{JGvKhjR}gSp{*@VMi<5oq9`GHU8t>c068f&G&}mT3jkf?P(A7BS+qIHWKRE zOYKxT*o;A6-D5mSHl-@4sf`zJB%#^3!Qn z!i1)H+J6E$HxHrn2-aS}4MokaVobBd&SWuu`8UgpUkZ-MFT3>e%ur)B{9g0)6K)Sw zmVI?OMj}8EHK+HH`)b1I7wTEZmKj=OM~DDxEUv^8s=di6kn=B&wYv_UKYQ7fm%jsi zzFEKi@`5Y;-A2e0&X9h1QGUl!ESHg-cq4cbp9`elGQ+N3>ToceXWDpsx_zKyeE>~4 z*Tq>Zn@^LQP!i1g5~L~}f(-4Y^^3)hJ|`kUw{Dx13ysa1c?r3lzP;Id$MN8coC(zC z29O~^EyD~%NbDh|>^r&1n9X;WbJwWH8+$GWg=sb(e(Ib*x%3w*SHbV6W9}M@mK)4c18T1=21bRGc4bBCJOcx z0QanZ`m?Yj=o`IJDOBbT?jLP$qOC40$@&(cQS2K$a{o=td(mNh1D+^G?j7uRW5eIv z^!bkP0H6`I5rM+SrOZvAuDm`2b4RCj7B>BLHFq0Ale$F2ilse}J82M%0qP-De`<05kG7Ga)pZc@idUK2hIB7-@8q+h}WS}#xEMoHlklN;esA!7Ig8FiJ z=V$)d{M{M9mDCzGw1feq6@dQd3eZj6gt7^Px+8Wx3!FQ&s*v&wZCH%_vSQ} zU{S5l0`YchH1lwo;bVsMfI@ykX?%O!s%?Gw8*d^xD3CmLk{ckmj*#AqQLSQEB{4w) z5>dMyMP$aDcJ#A}LFg5=p*;2MEgm|<)TS+|?~@!q#h^c1`O3gm?`du<2{lSpWH^i( zAtiK3elh7trEK)$kv${~i~ULpGM5)V*kM^0FfLzB{b>@#ml{L{>Y|nM^huxCN@vXz zhf^5!E{!#_+hDQr^G0__%n-=3kk*MF-gIR5S+PM=YAk;Tx6&`O2wxk1b zZ{iRxF^F-OIGsq%Or1=mG@f7UYw463E3Hg=!Y?$34}}mFcFc?P3bMTzJ2`@+#8EyW zi#-mifR@{amTd9bTEMz-i9r}xU7kvvIqX9iWe5u%$Jy2*mG55S^$7O%!$Xq6{lPFK~yX&9L z04{SgMT+BfGzHz8q9JMja#iUM;vXxgcakm-5Xt+}Uq8<`KK!CyY>o*+R)9+4`D?iP z+zf6lo>iG(*S@bf=5G5t7argAoKh#gJC>Zab4%mmkLfCs%ub|5W zJbxm6YPLLt`BV)J6GEJBr58Gd=n1Il(DwS|Lj&9VK&W}*YUlHjdSIOOS_>QbxO)Qx zz*&cS@qW1IFW>HTom{=RNGr1Z&}4T1!KDs3?aE+k!7BUMsG*mO!U~jFzDFhd0Dlsk z=b{q!W85#JX8b0wT%>094{qx6q)E}q?jD&CpdChvua`~EGGSo%ye`HsxZZ{c2fC)e z<;@^ux;b8Sa)&VVMiJiZK!bih!tq?-i1eeS!II0bRgNVmXniyu79grUdZ)g9)N(s4DzH`327y;; zPayKxD%%}M>}j$#zfh6bGWFu@Ct^+|PkjH~RrhvnUFJ83@|fhlSTNvDARho>1tfPr zQiluBFAzz9Sy@^`w)GeTWzd1Wg9{I~9CRQNi%M(8+q3QA_POtSl-#^2kfI26cc|O{ zcPjm9PN!G>MIW~`hJ$X{an|bx^g|h0VO;NK58Bf0uza>~bhqb)reM`hOb#d*?~L%A z4{hVxUA5Xx9V>zYo0(-#$!;ey&=3E+9MLS&u$tAc)G*>C5Y9g4@S{4^VaZ^@*+|gX zP&CI-5(B`$O{5QIWppE*QFW>wifflweiPl{sG&=pE{07T-D=i%D$q^BX)5!_YOygx{W^*&BZmNiKck zJm(sG_YNATDZE8(oPa*@A z8POph;j|o$4N?K5Pq^X$CY~kLJR?#?0;X4hTBSe?zO+TNw9i3lEBR@w`RLOa)~Het z#w^YcxwH|*v`Hwz0t8s+ZG8wP(2Gjrj3T-MfY!{?F%SS21Yn^Cs5J|mzDWmAAwc4Y z#~Ul)TcBep5VISBzluOlLf{@DNW?RU3J_$$84#QdlBDPEP!OOX+$kyp<820`c_w}m zLiH>*AwQ*eC6hTe5rY^r^bFk&L9jmyj6flX&|3%^9KqDs6tDO&6{s-vksucDY_)=H zjqYr%)oh(V*?Lqt2I4vDpFsLxOof6Ri|!n&)f}5YId)XJ4&u2^=D9Axxo!oy9^JXt z!C23lF?~yOf{_lv$lQS7JhxRG&VoSh$Ei7WdPZZ=k69e??ks6@@TW1-iIvnDNZRk4 ze1v=Y&HrNQJlxrO0Jfc-NQ~H<#NK<)5POvtwO6guT2)om{vrutv|_YXMNzFii>lSw zx~Z+G)uKj27pn4k-}n0mPOft$Ipnw@YJ1(U5AMRsIDb}6|VqQ{15qcVX_w~iHG+)E{eJjvec?%9tUUMlkpRr z7FmK_tl3D{eSTg4Jeq9@77mDoI3f0^!8jfAM9Q@<;It5<~$GwIuD=!k1Dh$Fh=6h}6D^T$-t(RC3?2+F$z?0hQBBP0(yvU=sS`05nu zNMF?YN3Igwq*bRPS6c*~C zSCOMyej5f@&r#ZMuDEWhoOo10GFARfRDScK{GDtm_CAa^3eChAjuY^35%LK0vZ=_^ zQ_T$%tobPSvbm}-UB2UERf#}#@4g)UTxICDa!on3QAiY=9Wa1qlfL#SdM@g&M~y{H zl~im6$Vr-TR6+SzLo1MeY4h~yT)ACX9Mf`K)U{LI6|0$aO-IVZPiZx6)lcFQ(sryL zrxer$>)qrQNPwF>F^zxX=vMa?$vK@~{mG+tq`JN$3_Y2e0`84yMO2I(Jzg(pfM?ea zBX918)ux6$y(#kq4$N8AtHGZ|GH6C}Xw-5P+gCK|H5Pqpw*5h6t*7b$=#Uu#+qw!8 zk|eHYnhrLrJF0$kEYMi>t#~WpDL@__CYOQm2e84C?l5fXg~Xt%ODx;tkWmcGdsyYa$Ix@paHfgUzl{aiPKND>8V|;2&DIlOK(WeRDJ(Pq_3G1iR4?}@I;aKcB zkUKQCUnPz2QQcnZ-M8|d>*LYJhuo)atiQ9}LEl;zUNCa=o=pdI%)waVm zj$5_1yE9Nd_6Y#!wI~&nqN%i=o{hCyH$j*DSQvgn47Q z2sUz0Y)>wvq-N5p=bPbgU-SN~Q*-iV*LoGMP*LGkQ?>m%O=u|Nc<^uTMGs5^EE=fr zHJ~Liqb>1GUcsBp`Pc8f`qPhyxZ$)eR|BB=J`QK zVd&@fTZJ6>BY1ribIpOmz!$wycfAiQnWJloA7Yq*`&~QA|L&BsExPd(W@x~<;_V6?PBCN) z4(WRPiD2%eUeWk+;<%TvNCX@nsLy%3V-m2SiJ@zPfvin*=B-hdTiYKQxKlz#i=)^eE@MxlApZou<|3BWei% zje1vso?(nKcNbwjqY#sJ^In1Duj(e>+#WCS78Q~ON$^Y%>*j8_v%aFMYydbLMiY|?bug+7t)@zR6xHBG51LXqE$ zhUx-(_jzik7MQirS`DpdNS;3LQ_up(R5S#(FQ;?_#L17~#!a^^AG zgo+3Sa2gO$Z8UJ(t)*8z{t1igOULUEd$#^tp2sSpWyMxgBep+QZ&WGq4-}xqsE9NS zNX2P0=H^cL<4x4bXPYsZ_+5o&9S{KgA_~2%PyL7Ww1c8R7F0 zXlb#~lkF|>tcG9Nz?U>s*b_8Lc?<3jyo*7x(0&?`zIU_8*C%e^m^oR>Ya!nupD-azk80z9We+0oDH`b739&?Pg%iC96>tVul2sq zL|IWNQchF~Yn-TMv6t?v#c*TaHes!V%QKl3@cM{fL|Y8UnXUBmlp~+5@GEC8ztGBp&^`E%xge9UC_={rqSeNvnlGWHUOM>357tDQOj{dushVDu3tCD%Tsu z?>zyeD8<`B(&A|WrtFpys#VDTg!gKo29L37p4^0{NX{EvF= zK(m8a4cRxoDzg-GD;^`J5LIdp#Qu*-nnGEV8{8kUy);zX#f7vh9&p|ODot%DSwfk_ z#EbpPJ;ybENVM$BDU6*>=5>lHAnhmdALOEYN(GoWch1`LXPbv^GTk-jtlI?^ zA?4eg`SBw(?vWoJUp8IpCFsfbmBfxPh!wuRJ{}J}oR;Th&T~`MZl`yTPWLZD=f`6B zS^kKtPoqsAk1dNJt z`99p^EYyJ8QeQy8Yt!2qd>{!W{|7Z$s~2KoAZF`<6pB@o`MvCrr~DPkX<_;E zUg9TBKE;Er>C>8LXF@e*2}wHVv%}wS1P_tp<-|l8wTej>YZ~s2Tr7>zx)###=kK9$ zhP21?g|cbL83QW2w?KGGiv=^3@G!74vwC4jKeGMWioimn{K*Ykle^ITU>|><+v>BB zpwZq|!^`@ScNXQNW$m-hCeqr@4f z9+Bc)ul!XHcy6DD*~G(1;Pz9Ur-%@OW1KEd4CR*zk4(*Q9B0!=f~T+QsTH)} zuWV%AKK84SbIj%Rb4>XC$!|kR9maf7MogNH#ydVq=ite9)KjoU4z}U?RL7zm$YaZ= z5;#(qathPt8nPRy|OCy1OGE`JK*es0@j%_c|8Pw%~+Ho9D za^(SA zSl6-|5lw@FVU2M)2CtCsg9!MR?I2ZBph7O`HN`O}sZfYh>DoT-;G)|7tIUL?_kOZ@ zZ=pUcVqZj~<836~!^7MuR-A!A8FyF474?4kLE``uDw7aN_$LAOl`r6p)R5Cn`M}RM zVX@+tK^4lobf2R&$jJM#k4biv5mvxg2x*O1B6Z?^%SC3v(uZgCUg;H z|BKSq+4s6_5POa<9N3klmcW!t4<^E&2Kg;z_>wVK6s|llcF}u74JLz^5BfCQbU`<_ zlQ7l?!(2nNqp@-g6|BEDEkPy8V1F*`3(D}Z-s`q3So4!KS=_UqDnkb<1MqTsuT5(@ z&ui5S57nTAQwNJSAWxi2UlQdwd33JLluNSa;yY#bK8*ZEX2#kxX=}A!l$e?sM9Ym} z7U+-KyFA&5yisj-K)=ldI4y_V8c8*2TSk)20Fe9Mea3fABa67HXOEzlL(TO)#=`uV z1u&PxTsr4I7T;@aNZtvx&zPH;YHNGedO5;3!*ijGCTTo+IrRD`_vyh^aIg7pRCcG= zhl1Y-`?`<-c09!A7zER)BDW^SyX_WOb)b5a^onuRVT(3Qt~o;Pq-pV2TmbX;;F%BX9lc^ga1K{gMHVB0vrNK)h}}*FyURW}@KW)${CoG8QCBgJsY)P)E)i zdFz<-X=#8ItYl@f;=qhI2OBiv+Nq)1`S{dOjjs*V3=dL95#L7Kd!Zdnh>0%rn%>QS zq4zsFB1vfN)9;x!oEw8AXts1gI7E*36xg0!ddYL$$1U=+@Z03(KO*=EDz>iC+}GA1 zIMH7hD;#QC@Q`*pSR?7_IViy4Y6m*TXsj@fr5a^I1Zj2++?i~`G|_AA&Jnp3I^BD- zbI^s$X64LNVSopc?}XGXA+=CNxaqSd#}*^!57+Ol7V*Xq)N8RQk==5WU_LfwW$qZ) zA1eaHV{)9McLur+HLA(ubltFCZ~+c-J>jhZ}EFDhK4F?e&nlge+*eHe;6t<1Ek-;G{`vEM6!?~Ix1{~8^30?Ga!pmG5e8bROnv(}mrc=&Uco8nBN_po>KlAlULAT2a=79wj*4Y*{Z%IL)e=gBVF zO~YOZ4iM#iKapU&LX=5|*1e2{Uc*ZA&kp0qF)f~n@=V!Gz^{@>(PV+XD0 zRYW)Ps>oN$AOa}{4R3iYJZZ%Npq1RdUJDkuxC7GO$FkzQUVRPqH@$kE;O%zw?|Z|# z;2G2hMqHl0&nB};j927l_J#Lbe_|`n;NVDt6b{d9PB+ylHbJvC;`y!p`qV!rWn-5} z+~yRJR=WumI|1ggJ%AX~=vwplC9idQS^*qY>XKV91EtUZl>-}Yd~Ue;hwFx z0}JdhiRJHmi)h$WGkre;3!_t*XJElpqHKIhq#u$Ok$Rp&ly8TH^PS4R2khntNR72B z5c7BO1Xs158DW8gvgL@WS&qD$G=fBDnXxE@eb^fN^)DyfI7M1q!j!3`u8ni3bE)VQB| zPKPK{0*moW-@lP8(fEdv$EHl9es)5DRme&iNEftvorb~{t~Xa(dO!X&Cejr_LRo-z z^I>c2Zza;_X(^O=8=_3_>G72g27ZZUDAQ6Haenade09JQIHDx=DmBGioT9V=D~L6$ zpJ#!E-cueet~Eo*G$wn50!IxL#_ViA8rY9-8=h6yJO?R^k4??GVZU7>9YskFaZ8P$ zlgUw5M8e4agV*&VogWO+dIhw1C*;0+eUQ}CquLFJ{&<*cFr09lDw*Ge&_N{9dt~V3 z8wX%=r3G=+%t0uxS&&JlQmJ|F#fTrmsnQVOEequSKxKaO-Aj-uN87=~mN)s`f>| z%FD4ecJvL=ktCBEC__2@o0BWgFaYgmuaa{WD6PYJx!F6YO zT(Cr3SJ~OTYt0VE+=2-)DYFt3x6v_Tr9GhC{+RrJ)eo4MgV4;RY?ncu2F_W1Jcs|) z>k64Pl%OoB+nVbNIJvy($R*xXfr`^f2`V-KzvN)d%LK~XS9udASaZC}8Ilap!x2i@ znlQLLo<+B@dLR?ztsSg5TFj4opUvs-^l;4i6^fG-NrOk_pCP)XgcAn71{wzPf6S!= z95g8rcI0|IB35xq^Jt=}@S~G(Ps5?a_$Vnp+Fl^&46dsnM)K_01L(0WMG^D(nqpJ@ z&bjLg<2+YO{mQs*nX)kK=^3U^&i6G9SL;vJkL31r+Ta`Ah>ip`iZ$6qJo(Fb-qjiI zCyyrmDo$pg7-tvHS8laHH!6nPmyZ{W0C63-kO=%Ps_yX%Znv$b0z6#HFS|au=^AZq zf03Kz6nx#dJq^ulEn7eaFGH1SX<=1Rc3}?=)7iU4=To}f`jZG}KM}jEm=Tm0H@{5d zf1R&+;ZB|5JrQCeHYGEdJ(~tS(seu>Jv@3Zdw>?$AVHbna*r3S9=D4o)~Lj9`veLu zNr5s(Ch$Ml{KO&f$#~~uGSqvsgyd6dK0xgptjjMrrPEKQi*Ce@9Pu-=^CdKC^Kcy_B<0gqz zMO1#j`L{Zc%Qxm_d!188$edRf|0XR4;=RxQo1dRVN@Rfb?7d#n-u|u|8)}{X8IrN|}r!V;0{MHa)=H=!7EngC!m~vaYsM1oi;SxK~YME7%5s69TJ)%5- zta)o$W-(t@YEiByojLSgo_m_Qn5#jYmm%u~aNK8ADgQDR|2QnO`8^8253Pm^lqvS3 zbLUj&QNWGBG(!Y5RKm8WS=#}Laadal@>O#{0vj{#fdQt)i0SL8D4j2Z)AZ@B@i@VFEb1SuNHW!`!^8;QDOBRN zbJE54pTmY8ggf|Ej0ZdHriW@GqJt?dd+QKvh^A^tfk{YCzE>Lc9ES@9L_c%A-j87? z70~`>-Fr9v>Siwyu|d{(Dl!w=Z56D&cyAACSxXEJyBGR>;j4qlN;ARDZ))ShJ<1(b zLRN4F)xtNyf|Z9pm>h+~>s-u+t){tZdq-?G66E7rFOsO8PwEj5-lq|ZACRP&R1T84 zohhi$C$6Y(1|ng1r$X$NR?C(`$WdX$(5`3qP?bvS%Z4GA?~y!?8W!U#qQ*Ki9}nfB0e>sD|$F)p068!kV^`T9#(vSSijeztp&2i>+| zY!v1*ly-lrzg1*|9GV;Mxt*`HGfn-LT^g2y2I~$n=}%rFFK>Sc-i#6Z#>k4AWo7*` zptAOPamP4(hkSh}dx;>=4c^$x0~^JyV-?hvB`f;YN#rIWm{1BFsO_3E%5C=(o13q`ueC zbc=!z#hqT{_SHY{c{ZPhj@CzBl42UWb$c@S+wHTL9}mp{uI&J?WgF#p$7zX&1Fc}6 zCmT+_Z#wM3pQkVKgbo0F7%5S`?B7Yc5w+BZcxqcRHOM{cEN960!B-|Pi!aMsdg2vc zCa#<)X$q3^;vsc!UaL^x<$Xa*rfw<9yEMuUWPjs#l$d3(1g`;oio!U)wb!n5c_?^) z+vi8c)BSh9=`{%O1%h!hAxr7MaO{U}ySDF5J(2SwNTA<~v8l-Ch+SshD`^Q=mea1( zIGXIZFS7lOHfZ34D}OU%*r-)dBHlAetw(&fh_%luGmoTOoI&y}ofexz2AGJ#z7(TM z=({IBZ5aE9Cs(*1MdQ|)wte>7DZ|$`zB~HvIju*nYW*swV+!*Hyq5Oe8#ru-*S&_X z%4Si{@DTO1!grJ?&MsG29_b0=+>E}H!N(hS zkr9Wq*u-Iz#M6kBc!DS)n5^RDZg~ys^hZ48&sEXi$xA;~EKv;U`!6DfV}m5G9*E=_ zjQNpht<*0-sk(Hc_JPOx6{dz=qd%*6(FKI>zgn%XeEc03F#IPs>Z@$iel8v4QsVH{ zqKfyY8@gFo)`BDP`dA$CrLCPxnP6IKr%@vI{;SD`$yzcY_~=h-W{F zf4Y;<$DNK7mMZ^_1TUSv&qzSVBqXcvq~bU9nKahgyine2*qXAQZ# z{x@Vjq5qH7_=ng+f>Wb%Mnd>;ORDHd7Q&GR|IaPeh5m|hIC|W5`JO6zZ;XwrMD$9T zXu=I+M8<3XRJIJK&>rVkyLfk{+ zma@t}N}rVYGM0^*z*YtU1&j4j!tqhR*0oQD;eRqm!52qUBLI{$lBXu=vMfv=8Oi&< zCTTMw<|K*ozb0wE+w`MfpcQyV^Cg#$q5BfA^W@GqU)tQ4e4D{3KQzI&`shx9Jb$Kt z$(4`~kL0c&ai!-}+G4{$`uU|zg!Y^65i}E#E{`W`_^y9D;Kj=m;zr69-V%_P-aZJO zR?`@&k+4167T8o5{zqxCOMdce_k(i{eYFH822#X}kM5tVHC5X*rl#ubw}*6L(bK^O zc6oIZC!-D}KYuX&OIHit>rYN~yfi5wbELUF(=48%b@=L2*Y&wRbYWDcuwkfz*wM|R z!`)Qbnwg03 zlmwx&j*gH1JhOk~WXETT=}kAX14L!&`k0m4YYi+176#3mAGlxhb7>z1hSZiO1IO(V zJp6l*)zRehcM+4<{0`McOqA#QMe!%SmDzGHDZnwdG(HX*KBiSooN9us%FdK-8h?d2 z+BR|IVAuhjqB$Zgms3+*(q``R%YLz7oD*?ix~H_KVj6JodQqrzx?>W^#`tM1la0(+ zthxli{Nv^*8f*5GhD|G>qj}m!1A2>+1(4-Me3CRvBfI#$tZ+acCo+%ChUwD-)1aes zPc!PWL3R%dS^%nhKXG60yFN`1I={rP`CjKFAH1cr?EGVmnkEv)A&`dHa|E@F^!3*d z3ZNd=qYX{ijCbf?EsdBiuOjj6gs2@3hEOly`9i{9#rEZN{rYx+%u?Ws&FapG7wgS` zmAY07G9tQuP3bpu&zAv&(TA^3SE9dDtTMrjkAfC~1@MMv{sw3Ckx2a$Yv)=c{>P{Prc30zPX0V7(ABl6fVR>7RIw;^piHcuIy@4{R za-|BsSfd9N>vpnT`Nyds2mqiqpX55MPp7CYp_Kh_dFEp7X3lt)@K3k?`fy<-d`!Q* z>$b~DP}vN8@}JX-YM-*H@RsZy6J^Xn2mSmvoMCEq zy~dShoAGB1$~jdz07KEszyjn2o7#0&B*7_zqeTMxvVuD-Q4Cw0KXf=1-)U3JCI&%( z1cWxJ*;G(gJ;Td0)Df%K#oyq%4bN)ZD z5DExU-vhG8DPXbIewH#jsbC*E2+qbtz;f)7Qk?^o8Vo{4Oml%B02p{_)PhS`RkfFZ zS~ibKlE9RTgNE=AiC(&x>fggRI~Q}Xl?N#(4!sdFpiG$QDlkLfY?idd8q;q_YuOWa z6rd8rv)rDl8=wjzTlEU;gj#Br5U9XRF`+|Tsx0~=G-3@eL?BoRvfNEm)&Ur$;rj6& z1eE6ipva=m?WB5{36O^qUT?RQX1Z9F@GYm>^(KOQnhF)!H8EIpN+Kj&B?q-S zGSq~L>AJe*rB^=5nBGacooD4Qv^W#WS%OUwi^mFmz#!l=rI`{c%lw-%HVQP=6s%b( z1z!nQxJPHYMSF(TZ7o7@WK*cMA9>1jgF21Y^2Kw(o>#$BIp-xSf_B=J{dq1{i2hq!Tb{~HxCx9#6h)ovCng(FhaiVFfY#L z)Wj}(B!h34^TZzlQ1BPEcB9DmB%wnNMzQx>y&Jx+Qq`Qxprzf)fFTtp7|uCyjbLCKiW1cL3(?$>d@k zqlUEGOEbmG$^3$YyQX?gti)J?aAgz@#__l9-kkuUH7gjZDck$G+7r$=(;6Qr6{M{Sb!xfg2~T#N?qf00U*msIumb&zNu0U;?TPfCtzu zcLD3G?_(9hQ_(n7xDFWfHi26Sq%kw#vp8Ha?U@SU;bOH0==klS#mSFF=9erCX-<&b z`DM}L_QTWZD_i(AjNsIgx`|%ton-wIkwgGM?spQE`FNFJYJtdByg@(8F3V$E<}-60 zFCbp|r}q7-b?w6Z*0hb+Hk+=>xhb(r$yPD7BBD2%@FIQL(hwf+Q6P796YGg4X|@6Y zW-nXHydm=(J6-}qx!_nF!^*+-@rj)6W0_JD3~Rw@KWP(O(j6e$4EU1{2GHnP55NHA zHyAEq`tLVBd*N$N8we)XvycA9cK;T8jL?uP>tDc=-qcE}3?v!*k>g*hhTZSP-|FUG zTjel~^;Oo}k7f;_o(R0bSSh^D&Wg1YN1`8unwH?Q?$Y=mb94)Kk+2}B=agzz4xteB2cRZtbe+10MJml zeuHw7TFKbs$q9SIfoX1}>{u3ln?bk}$cBd?6}wo#M$0bDSX*)t)D;7}H4Ahrr%yI((=;U2Vok(T{FFuTW5A$|Wi$00qW6A<~zyHjYdu1MHL}zRc+& ztK~V&GB(f)?`*2bS1M=m*yioPl~Ry=3rUOWaC-93dOhwl`3_75aEp;)HkL|AC||G{ zfAN4`ff+xyklG@{8fcfKss+)J>=TiLz@rEnzgIQBo>5!kH!bOd7|qjX%X9?9OfZC$ zP~enzj?)^s|` zO_k2B*7BR3K%jZAt12&;g9gn7&RMjX9YUTQ#;-A7@2$wbjW5KB3H5<+xxV>Yor00Mdbp1f}p^R z^hhKq6#`B%7D`dB&O?r&d3}ZhM9~8ig$cZDprnqHl;RZUgPn2PA+!8UCiCCr<{ZvU zCdups2JmULkJdu=5pLD`tq*^Rc|J3qEtb9U-xH?EA(23^ej{E>AuT}bsq5lbgP=** z*{`;Vw5!_${jw+g9#W3SYqpgH%>%sgX+1)Q^qTz(GdECM(!)$<*|d_VNO|g1h*KRQ z84UERY)FQ;NqG{@u`ypFDC1n@^uacbKU=;+fxquMm?G zOxBsJK+1upLwv+URWfRY`=rv_{PTWtddjeO}gy~wZkW#-Pnyn2Q82B1HgQpEb8J~<K8oS#U0FH9=XCdx4)c|$pvBkkLO#?q_-vkB0k-?u3=Z}2`o zkf?hR>eFW@^7BikFxH!kceZ@#$Ig!Sm!+#8gAv{L1*67VRD%ULoH#DS2Gv!Vy4xvB%8pG;9c7MjOk&wt-`CWb^4!A46YZ33hCNnb_w z>u{f?mFD1qz^6}|T&05VYslbftZ-Hfnd5#&NqEQCGcpq-`O&xX6W}L& z5-C341{afIuX}sGt(o7V>6>j-E^Z+ne6yi|<;u%T0oz6KxEm!U_;MW2+67Y$0@o7U zO(X5PO6?ALNaxtZ^te}NAUrkr(%4t?luIMRv9%IId}Nk@;3O2(?b#NKmk|Du?eVHXl{JG#%s`0O?KiKjYtJ-s`PkuQf#z zM5O#4hnZ_1_j>^&^@P2+H2U9YlK!wOCJ5~On=^OyW(Sx>j(3J<~MT#+Deg6Ew;{#1d6j;EZm8(MH4C8 zb0a3>w zy}Gp^)q0|CJW;lV^ks@H^w1r6zKLHNQh$*frQf97Y?kk=e5!=Y?^O|D+Anf6u~e8a zEuo$5k@or7Z~QhwA|(364SbnnK*X#-wDO)qVzW$VGjYLuQ1gyg0bRy;#-@;VbuCbS zTve@iU-*?;(ZH_fXgyZQG=J)UJj-gw%@XS$4E-2;>|PUSfScNXDjd`5-9FGc%>d5z zJx2Y&xWKr^vj;zfqe8E%7tQxp@T=k}fL$pw{>nbluw>ce{y)_}s_L9{T9{4RO?3bS zt`d@?%oXAAXLU`<-7uK3v8pXOZ1`6bLQn;RN^bOt4Ydbs&5v07RbU07sAIf>hlV}p z0N)x(TLP~Z3pSb`kv3R2h^#lfwtJ32hKVTHz<=T?uW4(IwyWPML$UU?;hjBOs;-H9r=f)`wNy!Y!XDTMofN&C%!L-bfzF!wUCtGQ&TeER_KnTsC-=Sc_ zuP*$Zh^s&1G~G_6)2x@logBI5uT5pXU@KdZGekuLNoO;_+nMH&4_24GOw*}g$f6y;j3*+a#cfVD zk_;ulMk?#lDvMYC?g_2_u`y`CZ9O-AON)%rjwQ`syI}T33i35adm5{T&y;ne_Zu(8 z-VnTY5(^$JtGqX>{6i|biI^M_Fy>MbEBA<8EEjNX*gMI0fX?$>Rw#1+mR6`Ffsc>0 zB1MkaQUi=6Pk)0n==~=Dune7H;2lb2*c*3lzWk}i7Jn)uzi}_>KXF}CF9P6vQkwkX zJo``Ef$zu7+L@v*p!UICHS%?3$WF;sdvd?=&&8~M$_Ej2`Uy}iHP+|5X3=_s!=(+% zl~(+SG>W(Fu4h2{=PVP!^o%27vCzKNS96VHFu3mU7CA+>a@oKuNwk*qN?6r5GT!+) zxuWn->|bpYM?$5mZe^tUz2^gHUt4zhcBeWA9rXbwL~r|wxxz8nO8;~b@BxqyGCUv| z&y#Qg2}R)vPa7bx8Ce(O7scviBpb=qvn=*;8yS*dcIsn#z9$HORU()!k|-eVX(l-W zdT(kTpAD{GPsq^)aN03?pT9ZuX1jq<*0%{vu0ObVqMvQLjFPE;?fk*H`ZSr7l+{lkadqVxy&-$t2WMHDq?60nC zkMwL?p2hb+GkEsm_2)52C6Sl5XIQK~qqgA^OL+IW>(ZJ5e*1XrLf40W$bXMja@aCI zC3&^@KBvGZMvToYq#>3!Vh8Xy?W$ze?8I`{ir=~LTne= z(gyPVn|aeYaq`!enQ_%g^y*nK?W}0xVk(c&>OOX3-zrbaIS=qw;?t6#*Lrw-*J>xn z@W7=P6@~kkDeWW={NFUr_K(j7yrzG3KEBbLjFaNSS9^7v>gYI20NzeSeY@eky!z`q zr+(K5AR$Ugq8zOS`+Lh1ACD>g(_GbgniJECt`D=HhOanSG=7 zHO43BuzCsHWvn?@i$tGBrmNp@hQD)`#X(EsE%naceFmLzb?LrcJ$%f5BWPqB)WqmT z=lw|Em%`&G+&a&m`jK2&YG_Ybt;}){fhT0! z^f+S%DWpp(5-8$n&+;x;gTlC7R&AHO1vGoxwhx{pv3c4(oe|T9td^^uA;qS_^8xAe zKiajP3*u|OcL>n95{~!Qi(TH@{jlqeYp19s(HqV0acSmHjGtl3iLKKVmuS&H$G~%! z0-D`OD2^N3mpepOk}6VL7mw{+yjT=(E5h^hi6nJ%=-q06CNUb-jFoEy?itpkSPjG_ z^v;Bf?>MTQ{groh8s~IWs@v)M`mWp;1VXCV3v|rm5Xm<9yEfoUP#V-FF}nnV9WUG#4N%jT`!Yfq7UrD0J@YQ@!w&Zt z`I-k`(CN-T`Mwd-W?2jl%^Bo5EK2}NTs*()u66fuSiEC4O7h70F{dBvv-11+-VA2isMW6~^ZKe;#mxo-9VLyb%K&Lxt(>3cq)V~C+roU-MK%Z{?{T!J z6*o=q^!oFZc`2OL{^Us}qj{1AAW=#_@=h`2H6ouySg%U5!l)?pg zc!-`W9iJ5=0=^c0N{gJ1oCg-iSL-B1O|F_FxT(00qa}v4-gUu0&25D-q@x3dfO}FL zf;iubI}9mat+KTB%&7#DnPi^IhJcgqs19eyw7hy6Ti|Tzeg2oNg|`>@uhjKb0Wd&H z#5=vG+c=lg^ot-bpdCbVOcH(U)+hIKjJ)FAkRXvwcq7+~hSM)ezd1<#E|A}Qm#+aM ze=y7qP&q9;n*49!kt?7hyD9RP0(tIvOv_{54wYLszUAu&Q(yjMum5ksk)r-q41F1M zAqhTSVwtm!LJFAiv=U6675Fm59rh%IBq;1Br8wo|#}Kfrr3^C%5S$7iPj$IX8s7z7~1>CvXvMRi)V`;FPofVlUE_`?Z)VtgZyg9!r%3yggVkDMxTQmwO z&c$!7p>{Us?j>BSIwpe_Ln1a zA1?g-s@==)5PgTU@S0!0z#J7GQ=eP3Bebrx;>3KlBe(ch%evv-#di+4AEK2qR(!wd z5S75kLc%f>BLQjZnM&}zUX3&$Yc_=oVaDBtF?ZhH%aYW~dkp250^BjV^IhV~gLeuP zzE`0Z_Vrx3@^yi>-U8P7ee8(U^i6?~gmLq4(YForh52I>7{i4y?kv1yweXjjS7+`x zZmfmn76AWl-_E*EsW_HmHrh)P!U9V~NThW9Dg>>Q=% z-xxYBc0sTj0eSg*^9<&+zBwO9(XUk`3)aev$iY`$rxa*n6;y_lZ!rM`CHl~WKB8i1 zb{>{M7SGg_hr^?oV^0ByViS0#Gknv1$CQRkY67s>waIQ+9OiUgz3JguJ+DXxZ|8HE z6k=~D1(GPPK_wxmvw#b9kU7X5XSP!Y@|-Dy8nKhssGhE@B9Dc=0VSwD*vFVmWx=oK z6fe7HERr!x%sHjAm)32lNFAsg;dX-`$`b9yh&6#bR}SexW|;dy1ms^na}LLBT4&yh z=vikIg}!LED+2)#a5hnMZtPB&!Cv~0P`C*}+F(U;t(xU0Nck3!lvILcH$fv5FC{@A zVOB-gM|MN9KC$0A0i!{OLi*o;EWCx0t@ZCNKj-O_JAV`4wejy^$o9j+o{_c%+V z_sf}Lh&6#Xd?TmPUDon~IdYYr!u1fqqRQ2aT8>Y_CDi<1{5--8Zdbj{h9VPSW+fo& z!c{>q?nPI7B~Hq7w)vImkiN;Vak_qJ>b)5WxrybQszvDNs^#ljCR_R>Iahr=z%U%=z*yETf;b%Hl%$KJL?&TkPv^dy(^<2Jv-^Q`_ z#`}r?)~1bBizi4c2iJG$Y_~3*h@LE^Ue=?sgcH0lMUHSwA;+wt)(bz5H&VYou8uqv ze3$Fok6Q+!$@un};P}Q@Mkmox^C5J)u(iR0oM;fSE9+7^!)bUi+OyX8#_LtrGw=fH zKdGq4{HNnpt@^R5BmzhnjHZA#mf-*elfO^%Ejhn&&M#XWVFoLT;R6_|sAJnDo>r!~ z)H9^*57;|dE6ou{5V4f_wU2>;u-eBxG7XywAC9!v=6gN}rZ06~5@(_>^W7sb6_g6s zCSw>Y^)yz6Uchbq{_baw6y9LHzvb_!3Tb=Ll8%D088c&t7y#kJvm=#t4&F-y*9rPL+V3ovs`h~hF zAj$yGzS{qfaJtf;8A|_ckvv!V9ZMU&v$6*jZ9JiWl;L@px#TDou zHWn_xkdA_+5I~~Mk+lZSo@NKSs|Drlg+DW-YBlFnHKmJZm|u zmZ2^np%W9qh^C|%c5EDb4|S}^uSNzrrV@h{p_m-?jPce)Zs~*x&Zcln$|GQRB#~c5 zixmZ6D zp{w>^So*lmn2G~Ume32dYp!=}c63&ob3NT-(_lneaKV-Y&h$7UCPpO(6UQNYV?T5s zd4agEEQj+ZE`xm5>sdcuyt7|_k7F~2V~$e7VTOaLV{07(kc<6Ut|($EJu8W4^!R~0>{D5&mA-$F}Y8FlVuCSlk|0YibkB~~D2Tp5dT?q$;} zD%&b5_Fd<`SXLrE!n|)u3k@=OooGZ0bCdVpB7m!iuHg2}^^}m; zGJdGVihRH!%8Ahy^f%Bov9szUp8%Prat$M|NY9V^Fou>mv`WqFf0{XIn7hQ9yXToJ z`hiwD>o?&2U zhVCvwkP>MfN?PegLAtwZ=x(HA=7W(O z3A4v2LshHtvjq+r5BA?eB-5svTy2`X7n%aXTEaS77-sljGc9RhZTUsbVgegopsJHoWAPcB=feIq1D>ork&u1lyu(RNu11LPyt9>$mMi8{tMe z!M6d+I!|kvqJ5h{d`n?B&?fOV{`}QG6nAwXujoC>)ZROLrKr)NEzFo}ud( z`15q_Ku_#0ybMkTwAZ)onwCu8U$8ww!g{@^#!Yw0WE>ubIWR6ewAH*yvBy=9S2vJ0 zr2_Mz&FT)@oy_)}Fj<{%bYK5z_mI^wTt*mjU0AkxF>@pEJqEu{H^Gp#%yi3aZXIl1 z9o$#e)N>SFvI`XJ)u*y|K^;_0Y&Pcq!s1tYdnB)HLaE$u5TCf~X?d z74z#EbU3O9#*zC1<@NCI7_dlkEQO4u%T$A5P2l%%6V=g(mBgT#~sv3No7MB z9mY&Kj)=Ct@a%I{bo?0T+JNn|^Ttx0Vym4=G&8(jKSJV)?bk9}dsdvrJ?OoPuPs9O z70@CQwE_*q_lP7&VNu}@;$|fX*e(M5SuxMjWO!RC5G_n2JB%YcNeOX@X>XEMijztI zMBXhXJ9-e*FQ>S!ta#4PVLs+b>Z-j~+_ z!Iwo63phSIF{C@hYZrKMFvWOxiR+q%bT?moPF#wirF9o#v%6}R#cPl{ASNV1X)kn2 zq~WZ)Awl0w;;S{M0{L#Hjh!%J0P{zDb>fPQ3x}lnl(YSPF9chNxdSV*0q_A7VpZ}ADA;(8R7eUhdeXL6wl=<`kKv|sFZCLhC_rH0EeSTvH`A*UmZQ947zQoG|fA`_Wy zJs6Z9ayOW*Oy4hN!32G0XMI`kddpL8$|)DgaW`ek^yj4ar)9-w7U?o>DB>|TM)*va zzZjd%q!43iSjz?$)%Y2M`i!aR*HS@jwPqD)Bk9GNfbqb_@k{W0mEOFQ5BokQzwH6B zT;hR@<@bHF=st@zTFzCeo(De}Q>B^Y%=$CCHe=pz2&F`PzPsnmwOdx3Pw3a>!|{tH z1I8#9Fc|V>|3+XH@IBMQcqLs6eS@tlK~A@&wY53U`D*6jE3KY&JGAfz5E6_%X#dG< zlKeWspME=7ihZIl@G=$i3o{?C47p5}4e#}SOWF3rnbjZQwUUl60_5@Q$Q1YfiI)iC zFF90HI}p*;&N{>LgrJ2U(p@1N9KmZwv`-0Bw`o6-&etloFNJ|${umwedZzUKJr)ka za@+Bb3V~H#e{1k7k9)%Gr!xOu~^v>ZX0J7k<79KGvZ8#o4x{z!>F?d^tc#RcTCR z!1#yq-G$U2id+!e$RIa?3;X=)11Duil@|K|}HXlB8i~NP!R%aXNkIhny!~ z42Eo-DB?yRI?oFL5G)-}VMD9rNK&T`QeizX>JG5gWLL?0Y(HvjD^&3!TikzMyXy1n z_{_4u?^$pT3+IEc0>lHql8rorsn;0x#gYS2p2}sty(3i`#Z5_~f5u~<)UCBStba{c zUgVvmLVJwY`I@Vi#s%CM8n2-Eq$M1e2C7)Eia5;ZJ|C^QF0;>$^K)ut#Gea($1r0b7NVrv&5t?3akJvgC%jP|L|Cc~g^mMuLXpNkZ>BrW{ z^c~pADQYH1)IEpMm<^vn!IUw==yw72pUdsfA;Ao>sj{7X%gS+*33-BNSHC=8G?tU) zt8H|X?tC$RjQ|r~%?H$?sVNKHmUypF?$Z-Zqcm>(qA;%?E^P6vk4N;joask@GdnQ1 zd%aSbrdwptyiIpce5?w~dK<$30XvoW`~iCc_(}HQ1Z(%(x6lL`Lh8c!9Ome}P_joc z#In;fXOZD5GR<)kbmX7M=`$T3yz#$(-2Si!vNk_)vfj7*O`T(x=yBi8-+Pnv z?3T@CUg*Pv*}GfFWtA+50M85j@Xj3L}mX zy6m-itf)A4q7823S$waPhCkDx=Yg&}*l^&Yr~RnL`P)MVro5WRGH84hEo1IO_kC$M zmj21gVRMe4vMc&k3%+7gdfH3zk8+^SZN%~~IjMIHA&ZUypCc!}w$D~}8-@>CUG01j z^CeEtdJ^R-dHQXrX)is=x9dx0{*C09+_XRm?Jhm%RE#Me&q=^$=IO7Tl_b863sw_m z0&(;P@jOt2bWaj)oYm0__4~sha7rW}UR56I>eq&)Mrb_Uk_UR`CH6Jt2d}6RQjH2l zSXPRGWrqW~5+%ll+9eBrAyuN%FN(T|upm338YV3jNEFGp@UAjt3Y6 zke^(cJl~-y1vw)zVqUz5$g)3tZ*CqiM*|Mg9}w|Uiq?=*BCg?#^nb8Vj_DHD=;xjx zj+@HsO{PR1b4v6e976k@3kT2Ovy6avcsw{}ZQ;5(>!Dd4pHpofofOU_|D0Kj#H;}=-De6iGKAfXXc&q(IJPF9r-{N`H_-k0Rb`BK6-TJZ|qQvW*J>{POA+Nhu;2cHF z#oM7hO6X216`tYFC&zk}vhi{~KZ3D~Wj!WZEy=~4c;u1d{0_G8{xj|!m^ zIXERvY9vJh=4bs$N<^$SGtNbFjIjl)^w8AfJHf2GT04Pkt`D_#o;Azq9OxCM=sNKs ztC0GhJ@??NJZ3 zjq+U7CwSZzK%R=Bju?6-1Hz;O5aAs0&v7+!OZn?F(ykwtcn}U#%6r%)B%7*pex{n- z2+~aN%TMuJIoAfhF*Ay%4n5n$LvY>>W3y#P3c`2eZNueg#~VNM&}Sj^dG>JwRU6`t zw8kH4Klb>p0)1K=5}qO1ER?e0ymW0eA*^`9qCHP2z`|L#{z!iiXX~W$IZg@bAlFd7 zK2%YBfKXeM38M*!N_-xgkOLZ^E5gR%?roZSH6MYbu>eb@Hz!cM^ZBqZac1dNo6T_3 zsZ>X<_=K-HdaO>sSLsVpT4ul@M+5F8h8_B2t{rA7c{+w8lWnNz^&FAQ9)gWDGWTgW zcIwN@Fg7wr^4y6rz?vt5+^xK&#+-GlVEd1t-&RY<^}}8q1B==-pD4mi4^s|SpOv9U zq$L<+H3n)1Y)mUy!d9svj{LH?T0Wy9f=ncQ3!jOY|9B|M<$rlxXAq`^QV8n5`s&fa zu_T@?Y-#6cuWV2qOcWxgVlTnP{!rYaAs+wNgLCI#cPGUYKgwsj!hC?o{gvqbLSJ1jy(O4FP1%xS%POk*~yy{;YWmGp-U5pZw+&(O2Zc?G}kmrlCYV#JLh3CCNg? zdu?m3*N)$ig5VK>@hmu%SM@P9e??#x=3GjL-TQpzZn@zmkIX;unNBOxN0IrqUq$M# z|GE1e7@W|NPpcVgVLbOa07QFY8YNr~q@J{WrD0x`75!;uFdfuqgXOunpTw9wy=-yr zbaZP6IzI>>&q%nExcll!>)l!C@Exr47ooqMP<9CVv*#UmX*P7*F8VqZFXpMtV}b40 zEhe8tX8XVPEdA(7KWsUum<66Tp~+>_EOK^W>g0MgW6LY++bbP9ybG9Ha zzo?NArLz`Q+y~J(J<%s~l@XSTZ11f#)@_pH*pk9zqY2HUZC66A;9Nbhh^Wr^T+(nS zVwY=9sX6y#$EIMV#RP*Q=pQ6m)2Yy9bP5M?%BN_G9YtnU8-ZC+1jH-411oO!LEN-r zoIZAvPgW9S9@Onag!48!pl|u>stupnyPdchHEGs$< zJOpf>5-m1@o+zQ;mMx^)45k?Dq%4^|mwf`mBTkq7^Y&|W>T}!VnM!wFE=6Kr@|OsI z9h^*Q&$k9CZ}pqr&g=wj4QVDm$T0U!J<*S{?n?d9nLaO?=^B#-ZcY(55S8qD?aKuV zS+XZv$;6yUwh@c6%+83QP72M+Dy-6u@+J55CHLl{8ahWnny~YC3F}4EGjLq+sB;M> zC~&wa+hdY3#)6A+a{6%Wdkx4-ZOO}5DbbZVwMRJ(N*Rdk)Xs7sIazolODq zE1=5B_3q60nT=$%Bge}zd}^iihni>vAxu^sKb4(6`O?b{DY#f1#G9&H+daZPw%IxfkyiuzX_3#oa!+aaVXk8j!cP8RT zoG|q(!m@+nLTuHpsVtDwX)K$Iyt98wzZ-@Co5?k&u%w!%xYn+AJ%=yN&#h@qre%`Jgu2LzDfw)>cDB2w zm%A>JrnbMjbSSn?t-5Z*t^otHMtdy_G0BwdTR+6FbVFTN+MT%cwH~XdbhumkyD3?P)O*mjB>H#w<#s&wZwc^k$4hU|!i&vOvCs1_oG12!2s9mXQz`Yh zCDAsgNYtg}HomQC$vp0^!|nOO(PNiY4B2TW&+SRLDK3la_J7zejMp}F+%aO*o9@@k zmD!68$~Lxdx)tu8Q)#q_>rXXmH^)s0?&<4a?R#_ChXu-3SHxF1ZriV^oHs)ERjt2U zxGAbpd0KbVFH7|Nz~yqbhM=tT>4JgzyE7)|GS=ko|w7-9g;L1gG_SY??wZK zz5_Fv_g+Cc<_b)*BWq61LxiYwN>e*TXnj1EV;lEyDfL7=1T2BWeMI zWbvcI)sL8%p0YAqYD!vJVv$&Ty*E(3uP}{0$LnzI;mt8MHRl=RzkMf&-{rQ<-5^Mk z*zUl(<5={>&SQAkOEt(xGX9fdtfS{sQXB#O&$$ZTdIvjNwGro*gV1 z#btu$&|5oG^lheu2gwpg&UP$T=K5r{%qRZ9ry>6R(MH8gt@-v^yZ-S9tU;?Yi2Wz=hGJUR#Ok3X6fB@KfBQ<94FuG zG3XxvTNQzS(nv#G-_XpB)9SCJEoeF+8V0-y?Co3ZHz6O8Y989$s*2raBP`7BAQ%Hk zFcE}h@MXR&8Slp4oJKs1QC=E`ZJWOJuO~b7{ht~Cj#wz~g&fxr4iJ@K0@Lar64`dR zIHA!9?8HXAA%4^KP)WYn&*v5UCLi_(XFjX%e7>1p^tU7fw)O7$x^PUA$O!#da*~$_ zf-4t7g9ZO|@_;1DFK>c2*v{^Kpq++B0#;(3d%N2EJ^H1zsc^y^)%!-g3>Z$`_pc3v z$4!rpTV5QeASv4tkGtxRTMKkc6JL7mA778W82o!Y{Nmehi*I9pU-;^53}_4w3LC%o zG@fWPp1CmQ0fCQD_^JcY-!87v9VVN?s0_a&Y&*Byt)s$6BxMv2Bt5mtZ;y^4FuE!gj$ksv=qMY z|1IE9_+pj#1-Yf7RrYP_74)eK2D|gmd#RbL;pfBIpS;hoc!|yh_|6}p!OZWzO*ow& zK)#7Jybzr|KifNh_URmuKW#i4)wZ(4&9pRHvJ{_3V9zykh#kM6R}7%R7*hG8xAsa^Idm|J-pY($R;J z#BcU82tCe1{PpvbtJ9l~Lby0l|3VG@UgPZVbg7%>cZ;VpH17jk#%f*g4_shS5|U;4 zmy8!$jAJy`M^(-rSwCz@x&D5a|J$$s_xz8o1-?BQk`IqCgzA|+r%hPCYcN&#tO(kzDImjCTRw_bVN@S4_}r`RE6p6$IXy-u}zp!BE)DS|7mAVj{#5 z@YNR#ASU}Yl+=&x=TW=zz_BAdbdo>DrOPQAtI{Ju)oy(B$SnZl}; ze&2&SaP-eGRVolnzV_1^Rs1lCLq|E?cCzfH#`Cv!KPwW01*(7dQsBWegU#Omgq&g; zNq8-l>j#7qeCpDmybPbZ;My9Q9@WN7Y}3bQc-io;dYtG}A-% zVN5Xx7ugATsjA$R;)nx&tw&8`1)iSAnLHJyeM%L+>^IaXku#mf7>TdsoWhbSzTkT* z>-$yJy(BGI&Kg(kI!0Hbt){qK89t-D+E_{;Ka=55rNlQ(<~|)a@a<@Vp-fI)4Rh7P zMVVznZbDV;xYb==+*amX;r@$FGR_U^(?s#$YzlsmP?!|bcuw1P+B)QQ-SU!-v&~~h z1xIc{BZ*@FmzKK1`Qvh_u=^-GnpZ=LyhGc-M5jyFEby(^BOUz3Vh!g-&*f{TJG`ji z@@O;tH*vzh^)1qLo*2-J&zTw6l)TL_u&!wPZD^SrNMYpEwb*XtQg`>n*e#R3!`LH1 zO2ot~H-DFr&d1RvycXVg`6}Ri(ff7K&Bf(w1O|nVX(-;4E7NdNT_3YZTCb~}2u~Vj ze(sUx|2IiGqb!*c$T$5*l6GJ6wJz}g{pTRn@kAveILq|%ko~X0u1)D%tDMc!%pjW0 z%8K$e+nR|w@ne^cFWu{<*~u~?*?7@rkm$QbuE^GP1|P?c&$>OY&|SwLD4lxFu|Up! zI1J2@VDJ=q#URcldGBzG3SHBXt=-1>d&~F$D{M~2@2&&u z(LWl4oDh4Ob37!;u@+OHe0x-Ki8z5RyqpYuI{C&Fh3~cT8BHrFs|wZy$++gd0T5lG zk5Oky68aWE4SY?~Rd0$>=QCHNsrs3ALXWGO4e7PqWqn7^1|5i2kX9t`^5 zNGvkiP<+=7bNcz{9eHh+#NhM+7L)DgPe(w}73l)u)(|+&^2+nL0gXhDUTmh`kR(sK zFkYt+JS_}n5bTsNf+i*z2?f&{IG6#Zc6jp|?`|Dh?-Ie=+8G=M9GA^}Ql z#;6LI5?oagd}#a!)X#?Q*omr4~u9IUA_Q6vS$N-y8~+jkz}cec=snG zq}S6ij&`X&Pb0L`Q6bNblmURHi_%~D|P7(C#UD+F1 zQx`&xyvlV9=12K}MkL^XFX ztBXeA*-%FYg`ZcRFfsekvTWUcSn8dPIQ2l|0k}q;os?pc!Zf>P0774>wzBdy-9XZ= zpe#+Hz|b@9W@;;+vbJcD0#89xqLZm-#2y?RySNjzu9>AZhRcz6DbtE zo`T~tymjdm%~dTRCrGNk`OQnjeDVyRT-1~dT^T9=R5~db!P-N7ij{t{k?hjj!)$h? zfR!qEiuSV413_P24bj${M62{Nm!Y7d1N@lwh_LWQc%*z5vb7k|yRF04HAMaWG##%8 zXZKLy*+5EIBx>V}C}r#i`7QUfcN!zDa-$RGcS$`K8!U8}J|CCq-NINm4mcG?7m`kr z18sDVX@7JE85cFF55ehJeowXPU<3Bf` z-4zC~Z5Qe(iW%40w=tDOt_X$(z@e=T_x+t#*m>_do9Nb?-it=MQ-MEphAn)C23UIYo*VDKT-jfsh}HJYk7 znphtMT-7GJApB12oDQMH-=Y>|BWNA4U#rBjgiBNNV6$7u#Jk9R0*5~W0iLGOn)cXA z4`X>D2-cB)K1f|0OcpqVcs9btRb>Hv*&>@^k-SV%2txmA@cvcy_gbjYu&_yw3@|?Q zG~hn*I>cryqeLS|%rheE@zfKWCvIGb$KeT8NQjF|BJFJ^BN7!6pvFAy1Yk~|Nz#c9U z>bS_)t2rAKqd$IpPNjUM zrV)=uVmu%S2MYzK5o{j_aNj(tstNcZ1pOVb15{%Jzm3J&C;%=YHn&jqQ#k%d{+Bk; z?*a-t$1#z{V^Mq0V@l;?f5FeSqVxu^6XS`yTCk{GKw0R8ayg?==lR9~(MYdDaF$0% z{Z0HJ20qscREr<{tP=V_Hr`S+Dqud$(*<*28+d>K3xtOHFh2;3jSSz#t4yC%M=E0_ zN4g_I^IQ4)Rwk?1_~WppK+2P44wI297!x!YZivW8Ca_jCm<|cHHHGHxvH$3<(o+nb zeuLY-04n!T1`sOtIaA%eQ@tB11V+!fZNRoykx2gN4#Viu2h+m=Q=Jy7K%+|Uf=WLG z@vlNu7{cz+u+3$Mn|||GwU)<^#gcuwk_<+ z(16BBj?Z`(WO0@Qv2jP>KfPJ1DpUKo$TOaouA;M%K!iIg%1s{=ClAXL73J;{Y4>YN z;wIMVw5;Ol<#{U~SXdq67)`0Jj^(Lttc2Byz-o2C(|Lo7N1%?+i^5PtVLGDJ1@T(d zIb)xf{ zom9(3j0J!M49qg4q6Un6b7Dh-L^0WbaOaU|d_;sZLMh37F&ZO`9fjr8h{YWZb_IB! z!J$%AV5!4*uhsNCO_p(D5PqFK7L6iQ<`Fq=ST+6;&WG5_mh)^wvFP2f;H)uCQ-0S| zUaD{MUTXRgCi**_VtzjQeyAw>I4sMng`8cihYryKs3=VcBJl0IpgSnT*Lo`m#0$6| z3qbu5`T^?D$g@C$dy;L&C-V_MI9E8-r$|3;kv0BKJMn#V68k`MUGv(xFvWeNc&7m? zzf!iNVMX9t@gWc(IvMAJ>D(BtQ@QLvqZiMQS&wM|4B!@D)bq$eA>oFtYDR5=IJ$^l zmT0g#yu;iRlWhehf23u=)dlNe4rI(K{g0>nciz-VpmvF77l8#}ev*!Wd65SCbs?w=n&Zcp~_4nCv5j-vN^|Kooj9v>7r_4^z;AbU|C<2c z+1c6swEgM7{O`L@Q|Rr=FP}EPY^`6dOy0~6pqJv&(|-SV{`Y_3-%Cr2i;Mpuz~|@Z zKcePlXJX4Ct zS>TQTSm5>L|F*y@YD%k%i;MrK1zuW^|MzVWI)!;8J?LF-Om|k+J@ws{o&DePcUO{U z&D)}T=NlcN`;QbJ44}O{)K?3}E(*=cEM>B$+1iHZNi|Bn5S z{~Zw&6Yr4`;2-jj|Ly%R|J%*Y-NnV_o&a}n_BU}yDtlEu^KH5(z{LXY{qI++Z}idH z+FM#G_XK#CnNiw*6X0?(XhHr1F`*k)=39E&TQbs6t7sb=8w(4I|EvG4_aFaTRaI3< zNl95=<{kk5U;J+#9v*IP?*AtOoR*fBii(PYf`W{U?4AIJ!C?0aI3Xb+8VBbu7Uo~@ zKM=SXF7E$d1)P{WOA{k<_=DjoHkJwE3j@|)WlKD|Sb4xv;!8+V4I zNguwN?i4Vg3b|RjvX-}0qRVm7@6YoUQku?@ii7a_c^u3$DV6-K^t%|Y7iO6%P@^@A z4(6}^x;4}DZv{N>U>nwEOE{V$DHtY*pCb|VNb21^2b<>}}DR=~r*ZH~PT`o#3-FUB2|2>^rjO@pCZnaDsqUGFUfYh;5dt+(FRwKlmK~c*&+jOHyS z|H!-f3(ZRX*Y@M@J-?dblDXE&$U>h6VtYU=o4DiHNgiz6|L-!;(1#N!v%#5bm-45O z!xsYhStHnGcn!KgU)7$C(ltmFsg*B;C5lds{C@w86<_WH=iMW`0f?eD6aOGNMPn!l zDG$DDv_#U1d(5*!s>hBL-gH`{&pGRU&0{c|BvS>75|0Y+xoj&ug;)+xN)w-kk35s- zXLj``wW;_=0q;2RTEmG?9$5EScD!82sceKm-&~?kE#l@fBU*#>~psBQ!&C$0jac)#hFfi^`(rDLnU&I^DmaLh;cJG zEEk?el5xi)Z@%|le!uxK0Oh+q9ieoV{K2g#@cd+2@ptn zwP-~;w)`ns&S|WEZxXr54kn$88O>Mh41sZtT6?A%ON{KI00+_Jkh8`oPva+GaXxZ1 zk2H)`+4LA@+7vLQ1q8Jv3&~p)$7RaLVyFKJdJe`j({XEDxM1O>?h6VJaZ;NSk34fy z2c%og@wXclgm_@lu8kNJxEOGVv1_8A#V{T=j=cDxE57am9^ejvGj_Wsd8(RYG@s-0 ztm}`l?Ve?gs+PZGPq-jAHw_(Db4)@D8<=c4ve#1Vm|vX=CMIaB%RC_H@!ABf*!{5Aei>h~Z%aJX3U z4H$vHYSISSOliK`jB4r?Frxk=B^U~r0&(NozvE{~ji8-o_$N{FtFkT)2YXDQrMV4L~d14-? zWFYl|q6TUJNN(?hO}|-?&SNjKk)ATKaa!gue>?kl>3Z!&yKFl~b_wy{Im|3NPbOt@ zY;DX`gnQ#RDirdw_QQ4Kr%x%F;mJ@*22&GyOOfzTC-tFCS*H8Rzb(rnW(ArI4;)$lIRZ%15lJsWG#iqB)3(%dw%8Gkw~go?h!FdHu+k$u9C-A1d)PD|6O zT5dtZs>&#`6yJq9Y078x+Jx4IQ2nfwL4Go~m}9?2Az!Rjm|vNyERD@!g*^^t4Lm?o zK(Jktqa>9Zk1Ppk1|taD>icr-&qV($JXW~~@|HY`w$)W6oEo4(NXC=V-|*#ItyOxf zop`DByeYH#6`)REB;JxUU!Tz`jX*^zjk8jIxJST>`&#YwZZ=!oI;4X(4^6#|7DxWJ zH!bEnh1&pxj#m+q_;b!L7=0%CB0Gj^vRphYC7RdUMZ$agzQ!J`?}7(qXq)-*eYHE5 zj?6md_xes#Wn=ar=pyftPohk*uW$EvM>}y|C}VuNPl5J+ zW)1f)N`8=`Z8VK!!b|wnLflp9y>(vw`r83mqbs0O$~A!Y?pV?JJI>kw7EF70_9bQO zhmY15?cVsu07^Vy^5)PijDACsum=uqj3~nZsDARxt`P*;hqr8=L`P9>>^~~V`r;Dh z8FjUJN$=E$0f##3%VN<0M84yur(*9|Hb`Gy`)KryOE>Hof(9-!{5O9pjP>Z?puCxY z0q9Sr=c29*Kf{RjFsJm#q`H|g!=}l2(nb~!Rc3E5d7fVU7~IpVbanBOo)35scL^XBBA5FrgTTrPn>h<$^;Dxg4TDpK%ZP@{U4`{T z!31<(<#=d`wP^t;t!L!gvO3zBO$2*Tpc+AdFbiUhc0HiKH5VhkzNmml-rWIT8KdjN$$e z#R`_=Lim+Q-{?Uo=}`po@HI^)rosakNJnguH*A_e419)r77hETt~Uuyd(`#zbTFy> zH-q~94}a7>25OmDW@-Gz($osZiXajvPm$wF+*wIcdF<|J3dSG?vVObT9NOE7V&1@U zSp>V>QZl`Bv-63Ep>29FYpBiCkxM0-OYtLh{udmo9xjh% zvCJ1rDeRii>?i{akWVOO0d-mA9(DXdSK)k0!S9{iJLZ&OuDss{jPy)UE`8YizAwgP z-c^^z{zM_kb?Ws|rc`CY&}go_67ochY0oAR65`*zjNI+=BK0e7B`HE^s0p4IW+{1y zloYX5=L;z_QrgC1f`WhQl~jrpkdxq|?|c6MyloeveE@Hq8TQ(R;1`0hcAEse16e{4 zeSzUZ=AfStM4L?Je1oYEx}$Eh03fVrGm^h*uOKic=x33uGoS%U!Q<6ON-48yF%fRK z$f|DRTku0(1B5e7F!f}jGC1VbDM39Gi~&J7)d&efn-bMmB@`hbRY)RLR2lbmSypUi zCbupT7BKUZXO*PdM22^XrMjGkV|||YtwM<#4WpMW)Yl@C_ABx!E;B7aXbRKP%OQGH zguBKMvv47zyRYJGB!s=kjRXVJ$*+|nv`yQp_FW;jnN_%BNyFq^#i?~`;#_&VTf0M~ihv&sjibG9{%<@m>f|vl#!^*@T zeuZtgOhG6DF|7t58N3INxM#A1k^w%nDFK@Q)bwK;S%)QrN(g!Tpv49Ns@z@x%# z!drDBcy)^;9`F>eRYn3PPb*>8)C%0UAgJT{!P-tKn(T7gB67>~{xIxiU|};csZzHK zWH(=?{KIEw-2B65;|_zC`3Yc9F7i|108k@_KqH{u=n~P08PdvtY`ri8#F3a-04e@M zywDq`@Z8SGnx1I9uH7P#y?QKUm&5PKwV&3L2$zX&05UxVS!=|9`xUgJPC$_iD_1AP z)v8@7!ky@@#W;I)h(7O*g5yyCA$h5e*Ny^rs5o}{_a2WG^!YcRrljxuVl2TSBG~Rn zr1z2yJ)fT3o;V+bQ{R>wQ}YhK+th59=_A&woSxUK^7xjP*})^gw25Z{MRb4DLAdoT#e8$LwUBH-!;N@}Dx}gN|_lxGh z9wVWPJtN4a5&fGHd%E{gQ}id9AkZ!c!aLH4r`=@3>2*Bp1%NAaK>~;4*da!BDn^+D z#vB61)zQZE#<@s${6|zUqL%id@rPZnraMAHaC?~2aX{d7I1W7%skQ95vekG@z@(Gv z#19F^J;lf*Ntm#8GfQu=ucVuQ04%r>uMb9Qhr|+tks|r=^x%_9R+CkdQ*tsxp2gD> zpk_W07!VoNo93{Na;olqmr*;Gg-^w`jo0G>;TPx;Y{Df_nZ~o4X0mQ`%=@6pL$6$s zjw#KMHASe~b`pSs)h+zup*1@UdUQgs)={EH;Mf-M zahDml50!>v2Bg9J`CTzzOzF#Q>M%(SeWjeYO<1al9iJ$27@}QVNqMi7Fhep!&jqi? z(HNw>CBZ!Hpfz5ya$FE{W%ry}S~*(!X3Rj-feA*yc9?5a9G8m~R)PdZ(wGXdLAaIt z)1h}7)(H;wylakq)lxGO2x@~ zinM=F#oB^KGlagYF`u3bh1U<`LGX-s2HF(mPnW1|mN}yA2pC^FjwGwmo1*Yhu3oo<=>f*$0x;f!9+44=1f-iW`-0`)=KkN%JVnBf|j|jNY`vcTB*Q-lh6I_|?aIZI^L-=G_&EI2`900coW=o-8`>i%~ygzTxi6 z59=b|KR+J)B;-m@uYhUrA|JxAr{V+)FvWcR2!?n1e=v2{Z&AHb*FO`$&_jpB4Bg#1 zz|f$8h_rM_BP}Ql0}Lr35>i8mNJ)brN{NIZ2vQ0RDJV){QJ|Z-|og6HFCF^_}ZjYk8 zkp;gm`L3>M>u2UmbE&=H%bkh+{Yi~4_du=gkp&7zTw*1Ac`Ih6t8Buk;U}kz2Ju^O z%gP&G?e|M=FE{<@{lO-o`MLAz!Z)7PxG8RZ1eMe!DH(cX`-i3P>b|1XH_Ll#OD!vk zM_l1FdykzDmXKt<1ZrM@DM4dYwgS+YKKSKfW7IE3AoJa5Q@IDtiN6CTZf$xfz ze&dfV&HKj>r2djjXin-p_gD$vUmd!a^E`exR!RePATq{SP`3e3{GLx<=l#R``tRA~ ziQLS%LjtJuZ*=ziFLAecUc8);sUXjj*`d?{!B=NepPyuu{e%RqSl|EsjGjrTpPYS( zO;MRf_x;bRkKZ^UkrT93B+y5S#W{J%E|v3{ZQNNs@ssWIvx0KC^$)g>?~Y>Me^-{i zQlSN>Km7Rmg7K+V!!S{MHT~M(K)Qbq=r1WOzuc33KXLz@h8{7XwXZKgb<^VC%Kc*U zlrx(L7md7svv`^ER@sn&F98sWfcifQIFh6+GHYQA;Un7Y43f^nBnr4e0?%bMfxQ(E zkul*Z!-tK=8|6zny~1)_-!Xfv7@+kFCg)LmzZrT}rZcOojfGx#qnjhQVyK#{Kq-6~ z{&nQ(b$Of2q9>EAVC3D=yA%UoZ#;7cnKk&>e1BKsN0GKH__ZQIFYjvio8p@X&adK- zo!ct$E?b45$|1+FWs`x58wLE!wE`2Hol*XsUSjXt?OLL3oA9bM2Rx^3-`w7SYeh9BxMs zqB*>)Ev1=}$5q8kuwVSVm{!*}c$fx)G4+0$3&L2iz@ybzxEw2ILOtG$FcE(~Y-J+W zw$*AX{15N^^?U z0aXG-6sb1$TgPpdhP-i<)7aZaZz&U^euW?qv~t_L*EBy?(^wh`c35A(rmuM8#!b(T z8#iwyDcab1Kk2Y>2zv9#M(eZBCaq&gj$xr=ilEX>^E0eM_k&+zgg$K^dwdfe&xfjf zJ4PcC1-$Eb&{D?nNeXWW@hF8C!oX~#gG~L^ZzS*=+x1RzGfDYc%=h-c&I&(27MR@| zgH~oLsx|*)jTS5FT8m?{={DAy-N=^=`iT*c!p-5gl#*2NPx8h2$W^yE1@& zq7?@A$llgN&95=;&KVL+%P-vG$DY2VQyi)FsfQGZz0}ajz=*1s0Q(q|M-v8IzIUuf z`0h2Te(iZqBUB-fk}_3DmiL;?JN9`$(-~)N_}7r+q!AC+9K}~pm$~YuiqB&4ywLf6 zLHVsy!C%GJYoiAv(lIZe(Mr`oHIk@A2;nP{DPn&LE9EmuQs~pvlcJ0QUc!s-X3;j1jieKlb8k>FQsn9;NPZ*PTf*_FC2{URlVB!?tgXKdIQR zz?>EQ3ZmIKW*T=kw`ie$BkBRd_D<-D1ShjzyicGXCauorzIs;_5O?Tad@;h&4)Y)G+IYEPa9|rB4IgX*+OnOS`sHFk*Q$|nYK&|O;SN$ z>BM4~2MMbRK93mFs#8tuHc&l3xeH5vust<)JD-l!O~ku!jTY*{`(>bs&OV7>`=5=HJDV#CQ1t2d%xKxD2dVrtuq-R= zF!>sWR*ey;RK{&eT4xWedPHdKqpeY%AXfeNIgDX7X5&m%xo{s3z5t!CtMVg5J22X+vOvOkRE_+c`#L!z~ z%6P~ls{w`P6%Ipqjw$@Mn;z4z*rVk6OxlrFaUBgV22kU2v2h4H__W4AS1sFNrxkIA zxB|E&WXAruj`(*W+$FG_s}0*AgFj3E3ExP_ileF2ZgiCkD4I;Ko2}%K{HpI*geqj0 zD>W`n`~4w2BO!Q$i=1Nzm67`H=brcN+wr4fw=Gfl{BQ^PKA8T;&Z|PnZBc=mJdO{a z>OiA}AIs(l8f~lf_1Rp@fw~&-lO3n!(QW1Alz3c8qAH=Yz%UYVR-;UA9ya4%)Qzl` z-_Enrh9{31_(7%+LszhFm=?=3%YWZcHO=%^@B#YY02XE4LX%L~LNW&OUjg+jzO;3r z@i2#tjN935kayIl4s&_S);U&5k(iXhOxM-VEc;p?-HA)WS(C{n2NE`~3@{tX)ycx8 z{q>R+w!V5eH>W#6*O3Hu=n6tNVPihhpy0P(sOBffOWj8=;Hv$s%fUB`R6e#7^&5#l zaJO=3;C+4&Q89Ud1TB`Q>o4~aL z<8|Ad#^Mf;WQF>YWlvmrh~y(ea|bDQj+XRH9DG79M98#{?((S1f*?N&F8yfq)60y0 zwqD#I*TJm2)X$x_urdD&qj!_CcW1{0G~`V?nFyc-w8BmQ(4se@Us7vqaJS}1frNB8 zxTHUr3aKmU@0uvZ7Ncn$C~J8w-NoQw;WY*2BBz`M(-AucVetx9^W;KX!y8J|62c1? zsUY+Hu{8bE+4Lzj;||RS)uyI0@rF||zd{d+F_W59kj7S`>C>guS6ZVr6HmXUtKivc zyPxTX##=B8Lm3?m!rQNB?iM%Or?#*1Hs4g;>d?YYLd#O=`!|MI*p`F_g?L+}twi)b z3i?omFl1C~2G!T9kEaE;XHPaR#TmwY2+TK>B2r;|(|wkw;O&uSXxjM{9GIE5I&wHD zH`vcFWX)|y=`};>x5$Mpw&Uio=Pmy{0-m1{q-#2zt@@3VxbhgEJdAp`q8k#c9y6o# zzAJ|o1Ar3m3QK?c_LUkEBbZ8c;9j3iQ9|09dZ8=nGXUzjsl^|$5Hr;q_t%fNx+&l)mCTka`2a6Bf6{ZI z4gTYl#g_sg)%nD2PhN(1+G^iAU&mC*=Mj^=7NC%$>=YUk?N9~Mfs%#!mXC5V;>A!t z@~8_PH0b-%O(LRW?QBQ>!JQK64$&L1c^z_k2GU0)tfd2z=nr`i+Rq2Adt#uzC`&6s zBS5o=Pf;sD%CncT36H;})=Y#U3ZZ*yIAOQ~uI&}sJ`6xVc--5!KdbV2Rx6>9ue?6> zHTBE&iCzlyt5rD7AOHvjlgqJVq=6JKIF8nq!b1fk=tCYBj6)PYMdHAI)5*(fRSNc1 zF#Db{_C$`VOv{Hg2)BN+VXetx6y>l=#UWg%)_X6n$B}tp^wvME2QYQUaqAMzZ%Wq zem2aEpt!*f6M~U&<0(Pipkot~e=x-l#TK_Ad|wQAHAL8U|3OkBjI&=~APnW+-b3Y~ z+xO{J1CxO6ZK|VMD3<+oipc9Vd|vJ8~us@m43ykZP`ByQ1@cKOcuH?m zF=kUli-4xvuMQ4P&CR~=2u={!(@WZwm%wQyHb1`6|9&jif`8*0QNtMi{n|bO0-6AW z*r{EaCtIPytb#C!mpmUQU?2qqGzK@?+f4hYd+YP~PJ4G`HJuuQyG=%>kQ55^?&_0? z2boX^t{=?zvXtwSEO)6gPoEirWkzC>nh6JSY@=eSzse>^E!)>6ps9YcPfyG%gi>9{ z?bY*(JyH_?H?zHOIiWyZ2I*@#NsDxumB}B4%QQXbF^QruQpoW{5Sh7 zSWrD`?g6zbS=>jK6+U_HPCBRb1Ppzmu1L1o#}^JCJI8N0X5R29&7fA$q=~19K9Tp- z{O}5CuJik2N7Q(_D%Lk#$*!=$?R%?xUz5l0+1ru}WAJJU8O=i`@)q@*5{;>-l~Rj0 zFdbxGN)!-f4$~hH2>C7>O55UTelx6t@)5R`FY~6_Zxn_8?3ho!Q=t_xzc$|wWGltA z$iTmtplJJe8rT6n$muB;JG8!|_yN7~F>GSK1BN}t!k~xqiOun4J&W;9OBQDq0Ig*y zw`Dy7n9^u2UYyl>ViPUdoA}?BPUR$Mbr@w$?ZHFOw*&#IrOHA;(LB~d~2E&9JNX5(-A zi8;<%T#rV>EVIeV(;PP*JHDe`>CJR1SnOM+7G)t@X$-KnkaQxpS(s5N&SCK_^WiJ2 zZyHKGud0X7O>AfEwtjwwH#GKi&R}0zXt|jQ!#M9IStMF*Xm%{b)sM5h*vssAc{si< z)>Y#(Rv_?c=_BrIK*_gBnER(B=_s7Wz9yECkotSI9K3duf6b2CB?EVbc4oO6HZdh( zpZv%;)UVs0_CfVjD-NOwM@h11K^+A>U1IUY6 zzZ*`P6H*4Bq`hb@V2M_q8iT2JiHIq?;CQ{j4YX9TzSoVT->$rIsXvoGRwFu;TXCtVg*2)&{8?y|g;haT0H${M@n4Wbi>Ti(T;s0n-hp zx#Hy(k)Gzh`T%5raN zq%8O4VX8@`hV@ibdD!r*L*2hz_E&sYykV7&b7=4;=81bT2fC}Q+NJ+kD!{uj2iz(S zUeL+%3{m>zxVo9Dlt~#yFWr4hku<;U2HQo=;>y?TSD0qG4cn>+mSHu#LA_ z_1$rLsFZ0MlgbZouglwW7Q9X0=u>>py*9$Va5v-C?8al;TUGMAcyoo^tXtM)RO0M; zOChQ3&R>h1se_z7!z0k0cpLMH;sa0!tddzkcyO`_LnfY&+?8En#YFy)2+DBXGPUl{zor@kwt>&jz;?|7{rC7n3HcH#J{tf+t;nQ|a~ zsqyt)@{b+~Yl1L$5}#G3$xt+26rq zo+pRYUnoLlQoL=!XFQ>`utDeDAZ*kJV!jlqGb5X)4Q+h!g+4iy{eEzeyk%Czp>3}2 z*M^^Q_fU>}j81$o*rzIyypF+?RYRrTI+(c-Mc)X(&?)QB_YC|w*wFoiiV8Elk9 zd!M-~f|5%y%>3H(3|92|)Wo{jo@Tyr&^#}aeLIGarNx5~m| zVu4?N)V_|@PGL5a?StRNfiBo!GU~He*9w4;+ETA>iZ9nC0A*Sh*{#HW zc6nYHw4F@<<4N0xYr=Sndp;?cuQ|Mwx#6O@{Jw?qrv**#bDvY3i!+?JEaa-SJT!tN zsEgi}JMEpbV{cbJZ}w(yyI+WPArBi(x#L1E$C>THE)hCP5r#{axO-y2fRT#l?K%(O zkBzBS_N738MJ>p}Eik0utp?)A51L1AM;GrY{!O#}n-Pw)Zb_7CO#IOGNCWZM$l~8Z z%0C-bRzvTf(&ZU6!4kxUktqA!qqjkM8jq9RfzvRCXd4f<$f9#8-}5c++->iBf+3e* z3fNuZ_3+7$@$S7aTINQ z@A2Cc4n1gU0E3nUH(3Bg}i+MNOWVRfOi% zSs7kY5^}T;@O3GCDJIry_0g!a0fnWSX?JzzHULH1hVhZJ{Kfha&*N6KpUqn$p=4Xi>=FEs2e?joA zzI|)BK76RqADmZ%fGw}~klUNf!n=PJir9zmBH&i{aZEAHkMtnd><7R}MH8D2eN!eX{#Wi!@9vNofeFJ1DsfSVo2EeaXH zq2$SL1uvU6xFS4^-9+6OmCpdNUKK=S$_im^c;4?qu8K&t!>ZE32`!&;Xgm)gL^yq^ z<%9&CwW?6j4J*n=8Hz%uOOJ~{r|!jYUm5#?V6P%8sblNG55@E&qMvg8pBz#upQDCS z!2D%z)>J5x2}If@eOm08%U}hxA117Dd}<=9T=L@^n(_!xztP zh}~RfZ6|Odwsybkd5!XC7#r}t4M6u;b?Az$&9%K_iw~1GzdvUp4u|K}t_v3SeOH$m z2-rKfdR(1rN*E+p%5WJ{?;P0ges=p;x<+#Qa9|@Vq=)rJEUN0gQfY?FG!cHbb=PtL zo*?rqk=8DLoP)BRL;;uP-nSa8Z8{IODkAhSk|BOYkT`O_%e&{f}(viiX# zpQOW5*cxj7L5@J?L@(-KKjm4RIXAUymtOt0tJ9o&&iJ7?Q15_1{QbmmgYUic%1&Rv zXD&<0>&@;pE4OHS_d|#D{$1Wx+RCX9J2BDh<%oKtO$^|9q1_I8YZFzEj+Z$uT<_Y6 zqvg4-Ee6NxYKvPmBLk9)ynfInSD&a`g!-4n1t+(cy*`Bb%G();VzM;rDXQyCx&lBNs&DUpJFf8Hz#6kL!9_z1YH)!sOfq0n$lk4#5raZsRLd`ekXw(akP`X)u@?AzOS7!wM%L z7%6siXd7vh`D6J&NDND(ihmNBEL)G6zAnH47n?(Yit!zfeK(p0M0m%^D~a)WXtU94mqUhAiiR*<1^f0C6Ex|K<*cyKZw z3uHia5}=}tY4`iVq=hsxl^>RLwpbU$b^QOSFCIVzKr-Cwq$Nb@TseiMeAh*5VeF7O zjEXqvBi)%s&Yygjr0ZlbhQ?~Rt!g@KgJ@T72Z!Y40s@+pBY&_~*>&yd=BWn4u)$Ox ze-Ek+f`NGvfkuvIotog2j8bZ*^Wbu&oJ75~b~&PzgX&PFQ|f9uCSb1~^3%{6?}i#6 zczM*&)L&waz)j;HKawX4)!06`vwu3%zRFZh_<-vCT5Ixj@=@n+jasvL5^S2wm78-3 zQ0ceGe9T%+e`=J+d}#?uP+8}Ftv9H}ZV$H!b4R=*)LOf%$yn~|=F*NO(20Fyuzt5e z*%0^K#m6eaWre_$E-P;Tvwr>`721vY?l*&`7uVK88M|elr7*!Zpm%-H9M6INP})k$ za2OWyIuu1FP+VJePnT;`CE2u*IN%7tFl8)7VgohJ)VI2s1;0YbV%_)I9-AdH0qi&?3IJx4q4q_|0N>Yz4z-A+RL=_FM4jW&jRU+v%75A)0hjLhHeClGn0m)~Yy74IHq8BE_BdsOhF5wQd&^NP~DGHSbpJ|>Y~rqBN) zy-cbEXZl*$k$Q-fel81oZJ?j|oZX1*a)yb4zIvEE^=FBtnGEx&FeP0}y3Ilqueo{e zrdlsdSd1yhkYoy@x<*x~*>~}Piy7N#Bf<7v*|Fh`7!h0(H*iw0&D-$k*X3dtF z;Sv7_ebEV)xp0Sp6LcFv{Z0p%NF+Y)Jv(6qK3f-pl>Vc#Xs7#7YqyG*OOWi=i+}Dx zLl>VVq?c!2Y33YmZQO@8)hD>;0$O>M%(2Z&#(euA|6q5Rgv!gwtay5Nge&EQPf8vY zp4Jad)S+4=h(G7x_mfTGDb%uO+~lud^6CN+{nTy(8jcN8_xghRtq-^q3<^F}gjQm8Fz55tcEgEqSltwTV4MGn?~`)y)hT_KJct@%e5G{!1vi2rdm<0(HfkgGMNZ0m?i* z1gx4-jZ(xNG8yAm!LJAg(`egC0*wLT(wuNUGXu%9x-@=_CS}UivK<)X50+T08i)`! zIFyaOpfbLk{?Wo4ZVYR+1+JTo#@Q9AT0z^&P4|cAvr4>zr7O7>+Hom|Z4eEs8He9>e+(PjQFJUJt~wU)e_1o#TkZe6Bn5y?EPxu@b>2aQIh%#6nCq-RcMh|f&`|W6i@lz?^c?A&eh%cAY?GbdyxQ>v7(k6E_esle1$OYPMl{+ zNPSU;x@402qpy8B%8?IfbZ7I&@C(G`sB{QCR@}Ohc?-9wD|z@vAH1QD*R!V7Rokyp z94t5alf*Nlqe?faw@-V?;$gu@qx;HIEkD(_&s}b3$-I)+96PAl4<;=hkucsOCmz~T zf<_+PRm;85r9;N5I@s54p;I$-l zp;5^1wyWZxkhrd}%dTa?T#emgnx~tW*N>e)3frc5h$WdY085}8^w?4umpUAXE{%_1 z9cH>1ke2g)+u^0x&Ku9Mb!;YNlIO|V{V3cE?N8X*+Y+`Hx>oauOp_};$^^uOfyKQ_ zL2z9$tffC6{SvG8)Ntcz;B67B&o!m4WMh%CXBIy7euT7kf?3Dp59K-`MFx2g$J z0_z6Do1jWE$}P<7C`u|jKFMGrQ3@NEyXziE^l{19LR|>!myD2^jm9(9dPN9(H$j=I z^%S=Bql{w;Y*h-Z-LG8`0Jct+%=ti>1)`Th5_>+&6 zwCgO0?x9OYaE!kGa@%=LXjrzcJUUU#$T(ytgAos|mVtsV7||>Ygo-2@n4ZQvJq;Kn zsBf?4Wl|pjLW;B!!E7tCKC?O_bLdEmIDUqXPmW&|t$SP>Sy@%k`972r3Ux_q>`0=Y zBY}{IenfwL>O3qw2ND0}CO$VLTqtHiE{6Y;lyaLK7eS+k@Vr}dJ8Z+z4x1?I!!5&l zonIDvwyWdd_*DZc{*=+LB_>`ak64F-VpLS>-F3zDz{&SHu=NI5@6mo^y1BTi+ZS`U zO=B@iCy7e2gU(X7mudl#s5O)aiyR{~t%Uc+mT}KUqDHr9FXxm#K`$1JVjw{J#_Rex zMIE<%7X*DfI0bdEZ>6_fP0IYY;SHwj38L{sT4s=!p_%87le#D<7(42WExc`;zu-7P;3Aw~P-9Ekt%i^CX7w#*w zV+K~C8m1biKcNml3~S?3XJZ;D4nf*xdTZuGTD4C0nbSm6$!DVd_}oOY3)XCpx442ibfMgduGaue~0lY|i2ARln3J ze>)nx&x+U$wP8DU)ZXZ$^&dYRDwDK5hJ+j9_d=&-Hol`{xgBjuSn|Q2x(E8BMgL*| zie~BB;HRC(Rc0EG>w~4gbMB%Rd1YNtr9v`YR%G2*#~OFc$W+n@oLEo^ph%0&{G(sI zw|N2P_legkCUQC~4-J!}K)-go9tDISQK%>O%S|kANGKbuZWJI@7JMQW%=Q+$ z-zh_xL?IIv(0&%guv01;HniS?vJ*vWW5JBo7%jkQ0FW(G$!EQV*4?lZ7fmLQd$m$32uht8AhYoPdf|ln)(^q=!I5%n^KdNtuLLISfMPa;f*Gp?FF}Rr zUem>vs5L8<(-ul$dDyUL?9vV-GPT*EYVWLmwvJZtkSy1b5@ComV-wb}WsqzA5p%@< zdYBS*O$E|M{Y@U?2-sdQ2-OE`3bvI<%IjsstNVcU)D-~KFFown+CL5Ng)C`DDKZ(c z)n=IQw8Kp7373^*YQsTBcc~_zAaR#GvHo_-1$oW)KhgcA0-JZPuF*sGGi4kf$j-{Z zmL&imh$0~{v|Fy&VKyFs!>(N>R} z%oAY)a*jjP0Dy@4XiE6{Mau)n- z`$NK938Hf?dhrrE84do1S#I(vB6tk%Td44bUi6>Npo2zDE{GNuEnMxCY!#WC8G)Yr zMKU-zeiGsv)ziT8$GhA6Z*$Az^{iwe$2StWIOVK5Q1W=P6RN22FTa;6iO{vP08v27sOpZs zA)N@Idq@JG`3#I_$vZ-e)7H8)xssx&NTE|I7LYJv6BLMyDA(#T*q@X^$T$$Yby~>2 z)=7QiQ_?T(N7F%*a_=B+s)kNuReoWkghIz6qB9{eCZF39cvEQJjXzXU=>eUhEtN=_ z7by1lYC80r<>;)<=(~tqlW);|2!(*y%UW+3U@w3ZyC#kbv!$et15W& zZ`|(kUiTJOM;fOBY}KJq7{)IB<|Js%wF!M1Ky*4$`(#LyuvyM~2e00n`C!C>EhYd) zsUd=?dl23ETCC`1r*r)c6-c+X`{ zjLu1`%U*NTy*VlX6gcST5xK3rPPo9U6=nU>JC#d68)4 z@X}M|Oy{LgCVkx7>(IIh#eiS^uLGa|$-Nk(*RY-rjrk-eH6b@*N*8dqjgD)OftaLr zG30t48|&1!?4#lQy61Npy6md@=pAwp09k_qv+tY6h7{+NlhoSU)Q5f!7N1Lf7TF~q zQN0+F#l?96eV+GE+sZW!8*T#&Qr?TVwC^^~ej;jyQcra~g&G$tnA9tn_O{!;)i|7v z=)Eo=h8J?s_#?-D`Tk*Cywnod;H(EFx1qBfl(xJDx9qot$xw~@U=CMC}v1c)Uf{8^ZQE*82-`XEFs%K(t)+xZR;1k zjeS?p`p6^kAhNtRImYM+oFM&(I*JO-a)<X6vch3zf{Q$Bq5DEcY+S1|N=#=CY6yNxjhfqoehO%NBu+-Uk6~|&c>ot^`_A|d zuQ%t9#m#*7c^|-iN|dj%k2Fkb4yD|TT-&^KlGsWA;ozblEmpvbxZ zxg`CHz0?cP^!fx-cjet$lc{|qf8QGTv*duc7^f6PUf~AfY0K9bDdyNCeX5PQ)2GaD zW!KKWrDtha!LdRzUZpW5t_l2IIszI&-Lsx?{MPO!roZz;a}`BqTp~0(m#)ic{H#+V za*N1jjT$lAHDwd)%kC>Mte*NMQY?O+3y;kFTbFDA$VGWRcNVwZekP!R?>pF!sosh$ ztK0oZ@f9i=2H^FLw&Xsf{yBP`^Y4j8BuC`tlwr}aezljf!wT^;AH?mmxN{djFW7-% zp#4PZzS7byGUHZmK*5w6fa^P;?@)l+cR`)>imByke0934U__#Y4gm4-o~9$E4+7 zc2h#@$wNk%9?u{`$8AuhOJU?m%J%UMW@9;h6+ZNBkP1{V>=0`|tqTfniO<<#AMF}F z61o8;a1z%)jFb=WgFZ2#_!yosa%5Yw3&KF~ z#cMCORrxQr#1|I2->}OC=47n1G~Rp#cvR5(*0KwPsOsIN)gw=C@%)SNedXRc{IFRe zU!v5Q(US#8HSwR}B^;;T@8*BJ^3qs@x1*|CaQ&`g$FO%kL7QvVN zQ1Y2K`tg!^ut7+kOEW)@r7X4oD>6>G;~kwFt=Aq+%VD;xk%ngdgFm3!^Qe*1pV1DF_Vbx8NQ#YZ;v@fAu{L zO4w$FH_tWZp-}6^G=@28ece{uRmkv~o2H9o435>nbyL#fYCE)vj@58lg2wiasEyLp zjrf~T@V$nb`8w+X=L4A`v%nbRk*~pR$QD1G?f@%*2UrQ+hN>!`_hc;Y_Ag#K&gr$5F`Dcq;pn0ZCmME0efy4liSDN>Z#PWVpq0m|{im{qks_ z36-^WIiYPUt}Ir*%6*=%_oPNBR!2=&f(h1~)S<>9Rf;fPI`sSmlD)({XtL|1jf z*1_7k30UjhD%HDR145BjfOxzM<3p6bWc8zbwhR7iFrod>xW(3xT*V%EwDGrF;$ zu>4`|Fs<^Q6F#0TMJ(`2^zU|1aC`-4K#mdb@ryX6eVZlTyLu9}@FwPu=_CRe^Tw;2Q!di;o zXP6Dg{!tl^A_H#6GMLvwkX#liqFfdr+t{iHQw%8-X*4;Z78J-Dg2BTsE(XheFw10& zo}|}0Yk-gN2Z!&+>5BWG=@u9h6lddK``dx#+rv>e4)^%hN;Xt@gNaizojJTcvLKC5 z?0lk#6fwjgHuzT+?^-uV*TN#}nE)s9>=1%h%gOrc_!hz(5?bvC)M^T}D2otGpcxAB zS6}~{<~#^e4DUy>dMZ->MdJQbXleeD6xz3Q|0%S)oJf*Fn@VDFdw03- zl33i+#a%u)m6+v)md>#QsEC@y1|xjOMDDVMu9?66Gds~T8aG>NopSrY=_L8C5sZ*% zk{wcebfQ1yJ9$j|K51%r9bkgLhXzPgsq*w2D9R*fU&ZTv1}p&0vP|so!$EGdL#13~ zD6Pa&11+(h8da^KRQt4alP8c+AU!NKJU?C=#%SrkiPOMk^6KbzNR zZ3&t5?Q-=F%jgIVWzuYc)$BX$M24I(zd0kK8^y=;Wl&2i1bQ9L{=p>$oO*8>w8cK= z(Yzo$zJ46>ZN#bR*Hb_DsWI~K)k{8V;ML)F0()o$RR&d0?(;wS2lmJBsMX#Y!5}mZ z72NX)oZzbS3>x4J;5ydnY5-rBy`#Dile_@3iJuStnMiN@JpVGdKf!mq()tiwhhUR& zuf?si*5N@r@Ba+e%@-cvJ%VudE{|$4S7_>>`s0ul-Ae&KvY~xYgc!B6WCJIH+}naD zxq>m4(D>sAa3fgZ-W1d{7_v`*TMwkxf}1aOEHVz8vV$>J*~IR{KTtx$y;Kzhz<@c} z!Gfs22T~U`Z@+A&aDPtA&_EfJz&6^%YEPg^r+YDf_~;(Id^MP2Q>KB(kM@tWl2;Ss zzGrRIG(}}LBQf|8oHGHFeZhrii$Uspt?TDk8p&)kAdi?kbSXvC)(GR5P@kS_hZfqoI@KjDumK&U!633kP2YJ zPJSHsj^05%WL8MIqwkqR&zZ+a=Zd%BgJqy;>%(wOzs&gW$R0ls1yL9!9dU~dZEHK7>jQNSgdC) zt*=?z5u?M6LH#eMzwto_xT}N6mfzkG--Tt%>kGO5Ho%bB>s+BXZrWKJhqO~0-;fHt zL;W@Q`lC9EKw>%3A~!PEs|L&jc-Od<7d1u?0AkB|A9 z)5&QQLc|L~B_sTcP59}gk654g%kY6-txx^wbbL$u8z#@FRH;Z@S9JOtURogXtK=DiSqM5{Wu0 zSp6uhaW_`8FwtBk>BdRo9>H`M&pF9TN?SQtq!IUxkPfnqskZU0M{>Y7SVob&(@4(v z(1gSfAUUM!Lkj+yU%b{67}?R_bpAMASB8d@v=){0j;Qn(-RXT%44f4-oa^ah-5Jlj z>2~n6s|ZG~czFi5$i`_JT?XSjD%b8<3ysl6P}DP!+r&s?Xfn2z@G5D)qblTVr9N~q zOuOW8yvX4`%|WW>3P$J7xWLC<;3BFI6{B+w;t?w@42y;GiFL!rU9Ja(5i`F~r5!5T zt>hN@1`LD3OJ3PO4bxKjbCgvJ!i#bxIUYuy7R&(jt9aTi0v+l_CPx(o5gXEb@i(t{ zDUaz92X#@sjH}BPBm*CY|8!l`_tgHWT@9V8R4_;3m|el$7bW2@k~Z;l(}Y4*FeD6V zvpN7jn@+Y|%BonReZs2A(LFm%NRW4>fV)v;cu@5eWuJ2-c`PW7aFlY}=e|F!Aicsj z2$F0|rHX?TC!{r@KLO=SRi$>1{;KLQosA(};8&HII6;6-zfr_Dyx(c@jCX}jRfXVL z4V!9Z$XU(-if)dbUP>)b)(s?vAXOi)>CMTz@jit!Ksd^2&i| zF%I2+=Iv}l-4E0Y9-dd+J$uT#RBDXq#ocy(rrz6f-m|ADUaBTij;M<}=dI*q8b80~ zc~*}*mz=xXr}(08Cc5EMKP{d5tEED!eKMY14)6MN<)GgCL_M{~-p8$bYD}?rc{~)E zth)N|KYi}*KEP2@Ag$VvveeAak#|~?5j$(DtdV?B^i12{-LOZuyp41+#_BV;+&Y8x z%V@pg`Zp(U#+C-gR6F)ix%>$SfjakBSYH3_9r~^ax>GEx4B}O|%UG$#Bm)BHJ4V@- zRFrd#-?tmTAN^ttl^X(*mq;JF%hjaKRjuRL#KH6(dhw1jj($G&4ZWklV1&3M*A&uj zD*Uu>4d1}6$`CeCo0>q?P<;P&$!wBR)3vL^6n?)d z+#M^Cj)O=J28?ShrlJE`Jn`-Q!odRz2J6wkIiR|MIwC`5({)WI>->+sBOeW~%)9pu zc&}7Y7LV|%GP1&Wf{`tEonGJP{+#HfKjg@&Ng&mH0T;W(Hn3E#Ia5U4$51u%v@{3l z^zi!K4sH%Mw{nfFA=!S`>U6p`o8eLc*tM!fsKPfii_>BI^j;ip6L18@2cCxxZv$7AHZe6i100_UF!~Bv+s%K zCbDPweo=FJ^jg*V+QMbS>;EC_E`!=?*mVIX0TKv-gaR#2C{mR29PSBq8?ucZBBL7VMvlI{KJ zg4+9LX1!|#^@S)X2Jo1MgBKg0Lgpj$7Z?CWDU98d4-1JPVSCjX$z?GRMK0oVd+9{~ zj{?pf{WPj!dnB2~>^7vAyL3E*N9^{G1W(yy4vX~N%_G7mQw1{bD8!<9KgefErHH#l z^|OpnTTxJVM)Ot9RvSW6$Orzi(g-+gFSA5OrgwT`wJ{k+I+uKlbJ_K%vJQ1M~DfQEveMiur{cn}ZFU7TD zSj96a!)^lK?WPH@8N2z@xSyJHuXH}Uh^JTo96|GLH? zTK^Hb2k!5OVdm(_uk*nV)D-9xpo!n80a*FOP-(jLEr{H1LMn|fQ_T-!TlayPK}wtr zP@HJrc3GZO``?SKw~3^~kK(+q%D)DYLOnL(gN1s=)zS9mmPu+_dJGEW&{H@Gfj$<# zERk0a;{!BFuSB}}dqwLE>)a^oOi^t)6Bxg2rzA|pf(h8Y5F ze~(zEQp|UW?i_L}X)?E|K)Kdpc+3Po^IE0oTEAI+u34b_JxZ=9byMeLL~eTE_g*l> z_r?f&+wi5bd(#VjwkCHKsUJ^?$4y`Jf&`QbIXxC_pEdC)lRIAGNzZHyT}m5-X@*Je5JCJ`Btq>ni4Gm{QNvm zLK6#6P$wPkwf$X;H%j)9phMEnkb$=0emt`7;OE0eD>cOh za3}-aV`-UTsYk1o08@=bE~kM$=0T;Xr$Ka@ue?io)7jQI8NwE6cob5(@{kFxwg>D%P3)`v@w*h zVjlhej#&Vn%J-9FKgS*{j`<-8OYYDNfzf>4HjkO&Ds)0-@qYv`3G%DCX`uiV$vsfx z$!!QONfc%Yw-08+i%mH=yvxCthO%bfCw3<(SAQa-5l{Aw6IYe_OScvRH*=>z{oNv0 zzm1^my+(y(@d1LTLa?e?Ch@!GAR7Ro6>TF$4ckBot8Ad4J)4w_{*io!z40!~4*;d> z;i;|Lz%W=0h1Gr&{ zEMzk(|6TJ@c7el+J#*!?HCfQAtQyUIZyW;MPkXC?*=NO!>5?IUOa*x$*(Sc| z6rQ1VFn?;0I^48~;-QnmlW8J4oaz2%<9zuiG!MRp8y1y5V&QfL19}1_EU=`1^0*$2 zw|8`@jX>G4r1L~!6jz#~B&Uj#-6g~YDMTUg2d?$x<@ zKY2tWE>>yxdie`+hT8|HWR%gAGIs7CVx2R$LqAWY70L%^Z7{K3Rk;CI`bxcG+Ro$m zzBk;|Ybt}%90zXbwxp{3xV&s>UH@OVhW7yjwSl5X=Ff%;zW+9rVl&=P^mIFT z>TXTmrQJ*U0%3GF|CRg8U(=D+>jP}HTuH21^nuvX_g$NF;WzDzTLHfom4BVf3k3(F zxd?P_0&e7i-FvmTzrQR^uK`TPdNgy-rKP$H-$mR%&UkCNFCTX;BMIaW(265+3Pi88 z_&Ik^q2)K8co_0>ouY7S3Vim{R1SxXs&)fjd{+J)A$m4MY=(*Y(!IDX3zFIJr-1|% zKXMrlV{h%z!_#x(x(=NJcFJqSr9V7yN?ZW_uCfZxLV+s+$3&G^i0( zCw|#WVIS%7WY5i|Tt9wTpIuKt0i{c%L1c`h<4LCLT4G^978%HlX%Yzv1_$GLKrGGB z4~enhE%lMO^WjiIO*I=QLb9;2M?pR2P!gh7MW3Vo@>yKsM2qrAfA-=jArm);NTT_J zaSB55cES-}?^G3{zU#!!Sw|TLM-c*zH=CkJ%uHHR4Ek+icG7uZ)E$SHx?w|a43n8Tj!A!r|(-*TEW{y+#0BJ$>?3T)m(^y&6+J?NMfqBvn1KVnYP zy&4pZ5^angMi~*6$6seu{DfDB@*bduLLk74c*LcD}yvy|z`6ww8j_$wFvt4JTA2orK=WxVt( zZz_9oRGFZ(lKaDF8Khi_P97O)UW&0~WBO??yvmT2wFbQ`!)o0W_r)&ZBK{2oIL#7g!XY*V(rnQvU8J(+^k?Zp{ z(T0-?)S~xEC}E)uwT9>U**k%-o%l+~|7IbNH1h%4I}7N;>(=v_BN&{HWbSGcI3+iO z3crJ0dofdZue7x46fV^GWyH z1iuaf!>wFCoEGtr#2W6GV5ngp&+L@449n57N35kdR#~bQ1&0aIL^6nP-X8K+CGVq3 zc-!(lD>Mx&a#m8xuG`A|qd)Nad~o$D0*p!&V)_NV{Sc+)H~eKD73h-Xj0!5955(;s zGN6_2=Vel)<*$XyE4TvCI*2NTl9RUbdGcZz+dNs;D!Ii9&g+W$iYf-)%Eq}5Cngn-y?SpQZD~_MaVSJvaFAOJEn{FUTWGIfAFYnv ztsbH%9bv5*RjRqNt|{lr$3E3KnXWV-DkH+Fb*G3pjn@3jsOEUU2V5j2fv9RV)G)dB-PYM6kg}{Hr6NdHIzr!rSsJ$ zy{`3-s%3unftAhgsfdTLEdnS~H<#%LQLb`pZ{%n5WE2sbI6!}Fz-yFdZiE0!A|Iti zwbS4zfBYjJ?PZru@UHm{ ze!87Oy2Cqgq&Gs&j@Q_rMTxEX^JuFIrN8yNV*kSyTf9~UOedD@Lr8rSuS`o=ajQi~ z>wEn6!O<2mkv5)JZSs<#N_^Fdj4csMZ6arFv4@QX1|7we8c%%NZ`0c4xcu6^NyEq5 zKC$Mhm$$%uI>{A3lyr13FLlUrd42IA&B_vpJZz(8YcLgQZ}e?Z$8TF_ZJY2-oKhx{ ze$oXgNaw=u7{D)H9P1LqZ&+&YY@_Vn^o`#ZA-U!c2y{i07B5KDX9;-Ve;Vm1S+MI| z9qT;rsJa{@z7DU^>&@E6>M;%N5<2vG2=k@L=z&sI!a9i+&uhVwIbu+eS+)*Rs!uD? zy$xl(XLjvWo!K;1#KSM^^@4EWAG*Jb^gayj!>+0jKgwaxR&K}d_kYqal%PlY&Z|JU z1ZLR>6zwRy>GoD`PHXFxT`rSXA(s7IFc3;wwTB^&2S^M*uGn>0cXlz{bTJux(#vje zP$3F^)26=PpljyF!#gNyIEZEVS=(<==cv!|_M_90`xI-renJxhrm3Gi^yG0*K=xpZ z$Y)>5;o$MISE9uJ$-}*D%<((&u_}U^Pe-&=MvIQnDZ2I}<;uhG*Tc<9B5(0~bH;1b zI{V*09kmf18D1Jn79FU}9_>6FE0`PIq3{SD8(H8UYaH+Xwbpn1+Se#B@kV-JR`l&W6|q-Ho7208hhMd$Nhc3a zhks=Eo%u|rhL0YN=lvXi!1!QFmk7^RGG)Yl>L6iiifW|QaMbE%3ZR+`%6YI4>;xy^ zwj=193oP-wCSOF}fXtuK#i%J+T6@}l9gatpIb0bheR#QAS>bbkM2OGYVJf1@tsXXu6lpkb_8Cm=~7GVQd{*>$HY>X|I*8irC#>st~=bwLS~k) zi>blOBh;+1eara`%TxZ#lk6*OSWO31*}n4WVXAaA`{TMm4p1z_IasOXfTiq`QLgo}3m_m=>%+>*;5_L*!eG$h8J|@whFb;d;)NCY()`@G735WaXO@ z;Wx3aedFpWhORoP<(DRZ(Yr7%9V>U8H%&T>O|VD;fKVhqNKw}VXFpMVHsNQs*Qy_l zZ(%02gO71WKB4>VF-g~DY>E4;4^6MC|Goln5)4fvluqCZfS3!u_k=)B@01_SKVLuW zO6nGO=vgh9T;5j`PoFy`SrIh$+ynjyGd}oi{F6^&istyM@$qK4K~M1Ea!t@`&4bR| zl0J@4pxVB6n!tfvl3QkT25WQXQgebCbNxpabYBim|HA8kMm4@a_G&V@Rcl)~{&s7B z@`>>0tln>~AS>KB66z5vT0DTcoV9hhHLSpz&Sj4ZlLsIKcnc=Fh5xwudAhv&E5ZA> zfc}|~_t_f9PI@Y1<{a_#wk$htw}!qB#TdpCz&UOj0^| z9C%I&K4DR(TlBz0Y#r8_9EG~KY`T;V9&R_$oGS>OtF)X4nw-;Sook9;qOMc2doY&{ z;k;8S0Ud5nFdT(@=KIUre=R>Oa5p_~R}uXSW=CX+1k0LYSLDM#?jVBK2`iX(hj7o6 zpXsIM6=thrN-uvlsGk?UCpyf>gVW(2qgIlBUHf4Q1C(x>2v#sq5Cnotp&p)(1u zxMT3TyS~_cbg&psU{o&^y>gy!iNz^fiD~|`Fl8;BMy=X>rrbyN(!F;>CgnLNAoT;c z9yBJNdHknPRp)P)e-v=|6OP{(-zd;kJ*KP6n6EZdqF(l1nwSuMu+a3jHX!H5^JJmg z0&cP@8gsh)Jy8AAs=w#&Upvp=KF_;J4&>vcp-fX>X`Ba?gSi04bWdpA3Zn`IlcX*o z;gyg7QNY<6Po!Wx-<+fgMb1v75z-{iG7pq_Pi076XcLtoMmNooWERQJaujxrr*c%T z-<;)Xe9unhks%~53Xk9M{>CWaye?4iM4zG}b5XL35^H7SZ>6UnsTw#NG%jD`-So+9 z(lYdsB&qNmQ+^!h-7)y6DlilJwM$^vuvSf^pb`ToWIn9~kV$DcOZ9>IzV%DNUuyTu zJaSL&lcP=f7NYRvm=l`}%6!<`BzWvrH7NR0`CFrc?ASL<|Ic67m(3DZFTbyw9;?od z+E{%T)ZK4zuP`b&X!>B10zEG`!xVJtSo)8BpR)L6%U|>Qc{PiEYGK&OqFq{;j=>wc z{_~QzM$oiZE<6;TFC585)2iJ2ZPR*jRYsI*y>?4!ji=QLQ%E`-GBd z>#;1Q&o}QMk;76~kkk%iJ?k9b_JrUXY%Ox(Y%Q=tCBDt{)swgoFegrqZz)UPQ*`5Z zYu{%&?H?dHR)&|}6?H=#OZlXUl0!6YaABrw-{R71I+Dq&*P$Vu(@c3z*qW?Pg%C*o zNk6fG&FNrSfC9qtL~|%TB)bkw>nimo+O=Wge%WbYmnO$~2%Z_7=`o)Hj-EA%^LMQm zX`wz_rlUY+Ho+_CD15)YDNzr3I%N2#$mSy3duA#8-jO+-Yd80;xVOU1I13?G#?r9D zP)g(NusnkCy_tMiYblW>9Er~&rU_dzCbQsA285ZHSM4Vc& zEUaQ(`V96U+9SCaZwfJlJ=)MqxXOyI_w}n_Cdy;3^PST_{+{ss-}4bxGm_RF#?1iQ@Wg21}4%^0hJ&mmY65$w_^`1AbFA&B0%086iA za~kXn0B2tsObg&{Q}|fzQXZS2FUr=>%mqBMB$>`dU{65|SVABDc+gEg>6}UoV6Gc_ z#M&3-PDKEyx(wH9@E*6E{gb;HiYr9V9Ck|v}NT zfkV*A{r5#pUy;AYnWfrBG@ZCf07%mP6{I=Lw(cY4&(Ph^+C=>y1yQv8F9&%jq(cKa zC7+F&jz8OPNVhJxpma!H7mVTj>IRU?@Fd1WCSN1$03V-z^}{8*<*K&(iGk)mSLjgt zAY2i9NJ_6TLF@`_w{Jc8hu9K&@W;5G3JKL3!>oW++xS+g&>9aM3EC52#=h zO@cx-65R8OQ1?o4A~xNSr{^}9^yCaH;N9D^4-JssBeceB`$8YhLqHS`3a48W4DgyJ zSrSx0+}9&NQDE0)I#im8i5P$u9=2GD4RdD#bxaB8%w?P)FDEuZJ5q4=+}m^>(DL+waS|@!HH8ceU5-L+u&u#()_d@bPb8^eX0G8#mQIE4KK z&IJJULl&GOf?T#hzjj6#!Kh>cbe|!>$&41b*bpuh^HgVg&l%t)DY)&uaztU-;lnj3 z*h-Q{QQVIQX8HB%%sDos2Sn+18X|PNjxAAD)MZ!y>-h;j;4U|;4TcKmpQbR);Juzn z$ZaHPK7|LU&{NC^D&R(=_#M(uNKJsKFoG}E05@;u!tlmo0&`pK%FORzXTB;`h3G(R zW}Lgo$BDrF?V^*+Z=b~7D|A;5bUhbCNr%I^OHIS9-HQ4r!}&FekL>_}rNt^HX~6>p zD>e)LG4jd3Srf;5#%b+~ePD@>wFwgdrzCZWAa0GjeN%>>ZC2_7#=U__>*$e`CXD$SSFfARZ?^hxo@*&`|Ktz zTe@qP;|c$FtE>1*ED7TMc(27SLey+@7r!M0Fda52tQWexh2E3r1Jo_8-Z$6I5FBZE ziC^SpQ3Jd$E{AT!x7@TJvzjFgDvZXyeF_~1AsZcblJNr1` zZ4iPw&E07eSqvD`A?Q>23+%y~Uj8L%zZ#o=NX1;A=YLG66&irOM@Li_@gv;ny2>CZ zkQE1@93kZwGL7zjJgj>!nO@uGcL>;^}+6v@ofVJuEHO z5N9V$`4~tmKA2)1WTOYcuA=IGRj4Bv{8AXoF#tr8^bJD$xt{j(sPyy6^t|2!bC`l` zPQvrhxIw(5l82yZ;m-bN-=w**0X#C&e3sGx!T)Z}{3JObsU;(PCMj~(CrSe1ijj#t zK`Kz>a^^FHprnPyiwkUIUSLaWFZV~EAcG9TAHl@+v!$a(+Q}p{u|~jb<+WrRG~^^~ zO=KaCJrQs9WSZ6idPqp2X4q5ScU{3m15T6}sP|24MZ?};kOG)0p6Jz+#@kd5zJGI&Rr)tkQV|R0>}$g&%7|J;&vOGKYLROcDoQ1WN~QKnWqwNKF-jk@l`5)~Dm#^`#+9m< zm1>TZYHyY5V9NDW$_-DIKZ+_hswg)ZDmU9JxA-Zy#wfR8Mjutm9i14)TZnf|x%)`@ z)9qLjpfki27z9-57gZThQAtCne708^@*8h^3eX~>aNG+Cu@UgYl!vUdiJye~kwq+v zP?ODM?R8OhYe~)M2 zmP3-Ceyq(Gf2mhyWm>0m5*}?jzHFZ5X36~g5^{=EZKYhTKt>f-r!h<;@xu+o$Jh;~}lckzv>%^h%|AMDAH2f4IKw_FCsxz_m!GR~B z$6lI`r{Rz=jnRbZkn(B#JCRk8(oIa;t1UK3n~13^hy+UWajOKWsurWs7t0OQPzA2e zdU%Ke&PC`{PB5-k>ldEGnc4mLQ2kuV%LlrAz@&8BwE5{G^d%k?ti zVH9YKH&{YLE%HAAYLemTy(29osaBJN2qV1{ND_B~$4Fbw;adY4O8pY-e+f4_XmJ`= zQM-f?gHV%ILn&w7)}|4GNL7xBTuCw9=ZInVIYJZG?~fPnc6ZS~dj6rPfBnMP(?>@~`}_MCc={i8 zdTZ+x<4kXCtgWr>t*)-DtSm1t-^|aT7gCm%mKGNm7Zw)g=jZ3<=4St=DE;LNdS>Qo zX6Ak-aAsx(Jw1K(&ui*xYU*qX^FD}?rmrSPugAu2M@BA3M$RTiuLlRuhK5eY#{Ml( z4-XGxu<5Ibp6lM;o9^z5?(VCxmg|wq>%sh+&+pJfX1AZ*mj*g+T3c`G>TWvhZX4g8 zH`SkZw%)f%-8D(xHHh5Ra@|!ip{pr+dwVfrb$54nXJ=cX4rd z;f`myc}FS9$5GLDK0bHO2FD(r_ZAlShU!Namj8CEb8~Ys>U3siW=cv*Vq#)!Y;0s? zWO#UZNJvOfP*7lCU_d~CpP%19(zJ(%o12@nv$NBGFw+hW4z{+o*4EY*78d{3q74iT z^!4>Gv|nDT%bzJJUCWA}OGuuH2>#*Yxo2m&XQKPT_VgY}yG=`XPeHa#Nxe-$bx%ri zPe>3UE32cU^Wwz|O-)U8b#*m0wSP&|^78T+Xvp{Ay$qN1Xp zpm_A?5eA+nB_SauCdSy)L_|dY=BHsW7>1m_$Hl$J#{L&Vos5kQg+lT0@NjW)ArJ@{ z493C1!N$hM!omW9KtLc6003aJ@IYKDg}VIS5L{xY3}?yb=>J`yuE1U}hl0ZXB~X{D z24U;OU-tYj0(Dcx_k0E&MC-`QjpV@pRiHjtG4NEH`-H;6H|}luw?JKQ(a(kraXhUZ z9ZlkR+SVGQ&+|GdLm-fe+=utgRH<)8WIw>PNnuA6@e)F#b7=YLY> zt>PZH(0Q6GDRHsG?3Wx!+#0Xjtf9) z>d-eBfjZb*B1lXsve@&jwU5E2CyVyM_FjNw1n zD~ji?2q6)c`A49Zs{mm;hbWAyB{0#`?i6N_iVXpbgH3qeL%X;uy~x$ z=%`)-xmNXO^7e;{aRe5g%I|=!%v-lW36cEmHK_nO+STNuP1 zKmE7uG!73;f1$_+YBGoEDm>9uK!yG)Y=Nb+(zhmAi}DG2j)Dwb)rH5MPNMX-h_yxHo6+J1KR5UD?1z2+ES<#2 z_keO=qY^cZ0kEDPu<%I`0@Kxs6_0ozAx+An0Hn&*#q)nk4|R|j;tmh0@xzruR-)u6 z&GYg6zV#r3dm)%-*fEx>YDhvNC^o3IkPMLD|9n+)%=5^C3{bv9Jx3Q6lpY+vYAz=d z>5NBQ?BLL-ys(p+@myh6)d)E)H3qQBWqBNzG(XPtuy&sYN9iPM-5!ZUTqwsc6-SK~ zwQ@bngd4Do0-qF1Vph=ANdTy{ZtT*63IG~vmu(>w{j`ufYeeOiTpJmg4&gBVp^|Rs zVv+l;RHmMM=AlFVyI=ZXR&4Xhy^u&-sNPg}DD1o_H>cnb>;*4Hss)w1demOZ(HKhLs7(XIFUms+ zB+U9PK=~B}crxPK0DxNP7Wj$ABYN`L={=3#OmCYM1FaD;-jP9N^WMyZ;S}GxAH>ya z9zB#>u?Vr5-=dwgIFN^Mi{PL(DX)?8Ts}?+wd{WCYK1&q*ZdgQbqmT21THjn<9*<_ zXExkTERwo*)4)A5nm+)baiETBH5xcu+e(TQz;mBTNQsfMGtyUmGrCBABw6rvypqJB zV`*7fx3Hz;)mwb|yg60o){z_*gA9ED|F$_z+_0nD*<$UU_(f-*-B0i6S1W_m>`epT zYn*iLmW{`Y5Svzn-oB;AXV-J6AMSf@fxbqUj%iI5I9j0jx(KgvY48>GvdhPZ>*!Zx z2Bd^5sHh*tAT!TqJVGwj*rf>XGxKZ>yUK7o<&Ase%g?AWPN{hj+QZ!Oo)=HRK;Qr-?u`1VoMVFw$R*Y5eAv zw0TPV#FuPHM2#nMju8m{>W-#So^A-$H?({day6OW_|XOD(14KgcwA%lG!s5fk32FX z5Ko7QK0xj+9(kIW4}L5*A$jwTOJDrQtt(1AdvoK#qN?X!KaI6Ur1$jZSA$a5w7;VJ zIwqB00LVYy-^v9C-z+}Q4#+B_%t1;VNfH3P21Ln%4uo!!zt^ap&z{iJ>PN`O3htkj z&WPF=>n=T~Iq9d71E7q?>0zHec+((-!Mep;G;=4)k^@Ys-eBnL=z9Tw)8nIK&Sy`f z#CFdrJiCq@)RC)Ld6%%q&^L$yid4IDF9Fb5b9|3 z;y9zW+RVp|KVknzTROHo!X6{E*stL)P7qx%{c* z=tysVhueGiP79g~=6G?6VhTJ6CMZjn9yX==xf84N7xr_?$V#Aa44^i-B|9WnCLg)L ziNiIi8LLbsW53Qk#9cAXTJ3uGXXeyr`q~~ipLu^)uHJQ^`WE=Yg*T5(bFzM5(ErQvSt$ze9}E3lWzg3R7OTcmQteWh~af z(K(WaR{R!4?+txYwe~zd1hL#5%uNN%H|J)T9of79o@jft^W^?6ej<9@1`2e_qdh0_ z3vGFxxXnu-Py4zKVthjN2nqj#1igD=7CS^7Cy%%W5MTvC{mKwiC(w-u`|U@;4+@z*DMM;j?CME_EYa|Tut4;@942c!u>^!$L_Am0-R-3gT*C%l8x zkG#wlL_}E0iAa|qkV(~#WU(BTOk-xaHpa0zK96I-SFqFkbrgItR%i(c<4-_^NTuowggtF2HcJr zis5@RO(DEJSY^|2Ckg7T6L_QrsJxEg0!dizLUU_RIvfNlQ;;J$-Z%Ixlg3vhQLz&uY+ zP2-og_6^v75HPHh_mk*HareEz zWdLNFA7TFYK_MprmL}w48VEq)9Z1LkIH8M3L_gpKh={;*AU0GlQE#96iK3}MbJWCK zV(>Z5O3HiC22}(nyaACa6h&8K3I&`bft>Mnk%*G%2tb|W))sUa8}OEsAAlreXGGjF zB8u{~1Az@XO`=5-jGoYEPXEIMcX&xvqJy%{W4f%tBlLB&3r#8ny|7gL`>wmOhyDz}$ z9vHJXGf6xadi{})5W@eB3aU+M)+wuvJnxrKVGcuK+Q@5c`fNln=fG9swPOBK0dR59 z0knzx#}uE#JNk)f$|ImX_#TXe!|8ToGV85Fu`mt*xdARFi46vLmw`6vUWxT}{l% zWCg0(u3)r#pvxCj!&^|p(_4duscOjwf=}Jr)~oEIGm4U`7j4UzUu8dwP8z&QnRkBg zdx8T=@Y;~ANb|1tEvdb+Ex9`=G<#L8XjwZ5ifeK2C}>7az7fxaoNQu6rq{X)FT~1%{KIbnR1g=Zkc! z8+0GAwawypUMW+XoY>v(x0n8?;WATfT&kO}`$Ql8=_ae2K(tFWv>gCw&C5h2kKkg% zh{2tm@!&3~N&w8Sy<&{_cSjB5a!q{}>NS8ExSma3g`j-eO-t24x7;zO-1i{6QwY{w zjvp$8OHA@4|5-MI%kUG=Z5^LVm%yz8{rJEt7hrD>hfC8|PHHgM;CoA}cQk|=uM9RE{?68yX5T*}*&AGmC~4NP=N@FP zYK0iK1d5I<>5aH%k0_0Qf~!!bv3=$a8np86a8}{^8^(I;x zo(dDM;W!rDj`8S>j(3brRgRIjbX>n13GE!6%SMRFbxIgIKWZ7TqUxfmdS;G45s)I= z;iW_z58Xc@96+Eb1LEPhaVBpxNmkPi<+A_Pz1+VKLv zMVovKCNhtD_|OG?4wZtI?eAvIk7u16 zzKc_V%qKvk5Rex8oa@S*#me`9obMd#)F`UN#H*pXc#XFV%f(KZ>naRSx?5WrW)pE+Ra$iE_<&NOJw@k@S=uiDUE{>ojo z8B|qk+c87K}r&rsw>bBgQXbq>{t$Fz4 z5qk26G5)sQ)1BB=9e#ge@$Mgt9Ht=w>tT+2mLj{V#=FLb`{u^`q5;H@#)sZJ9!NP3 zWKND{t8L}y?$zFJGj>lLco8p&z;#gv(KL33xvLr72cF@34K#b$!+Y(5y2PuEfbL@R}{Q3Cq5QnwP`+k3MwTjqbyxNx-Z~Fb&{jXGyedg7JOG52EUHMk9e_qYJr|T z4CVMucX_fDu*)4oBB63Ecpnlx*2zTo6RL^lY)iF(;;A)y6dD@%d?Vs$>KLC@n z2haYzG$Gco-!XCq63SJ}{QCK&B!X(!8TrHodjs@W11c1ccY9KyP4-u-R#E%Y9&ui~ z-rEZSvq2*w@E?s@E|W8UX?IR8Xal4~NHFqR{9^Crg^S%^68M#u39&B?8Sc`?=6&XS zhfo^ls{MYUfh-*;Pa3 l+RO-Yh0bltOUU-sTn!nwgdgT9A z*MIIcVz~zoiwlB|FH~f@D2JO4PaQJRwlV+u)%I&l93D-FAR~EXke+wZDIP?N)(FCK z4k8x}!y>xvH@S_@yEQ1gPN2Ojn7kG?Bqr=JZ6YMg%ihSSjZoPO)xfe*5VN6IG3cu!j@rDE$g+h2VtNE5Sr z5bwtummrnFsd;{eC$SYBT9-?}i!-raZii*Yf=}`CvFtmoYU9tDFAsHUjJm8#u2b^m z-kU!H@l|qLE`GFIV3N73 z7JuLW6k~QeGHIF{!U)v&w-+5Qaq#ZR;iYJaYE1JcAHnUsMR>AJ#%}zDl=L*+^=1F) zbC|$(oiv=MDv})lNsjvntrecBASp3tNAa8s(gTv8qF&RGGl^Eqq;uRNm%(g zOeuXiW@PN!wqdLqabRGN?v< z$=fSdj0Ne9TG4Rbl5mb_cw)bpk&@>9N1*;2rTKv>WlSs4k~&H!&i)veuj9Usn~~^8 z!Y)XogQ}@SQlD@5rDd8`>PxHLCFUV>i?A~`L$3Do!d@y<`l;0UqLKo8#=^hz)ov)OT>E5Y(o|_85R0UIOV)0hXq)K{nMm_2p0b?H%j$ss^O~`(w2;}Sa@$d;34ngPtoRw+n^Nj_PQxO zhDRqvj9`}B0;UEZr4hQMG3(j`kE>k>S3tc^xZsIA{j;}MPrC4dAynH*{>KB(*EfkP z68%8Oo?h}aHU;GGAOJum$WH7MLI6NSqWuvPNcWQn1v$*%5r)NzH$r`<-P%VYhaLDp z8ad_z5e2m3${F;f4+?tpkYCGK204eZ08S)A3^%Dj`v75aAP}1Un3BXzQv9hi-~r5n z9OMng25LlkkTHO00Y!30EmGX6r;ph~hw)hkKb6$izj5@VpxOtgv;39BlI-o9a2f3X z$XDT=M?S#E#3{oL-NxQPe3tNpm-5Wg zLUKH*Uy_-NS3K?qJH(rRdv+RVgcNEuiPNdS5A9%-4q$$aNtz&KsD>fM1u;n)5)?J* zAkxSn0`*c9WpShwWp*zN2tXr~vW_ezyU7N%bH8M*$!tk~yR0{4t<6^bZIb-uslkJlyS`Pmgb@MH@B*aPsUb14Mr^-v_6j(F3q=5L( zK~6*gYXi)3{cj3hLVsqXZ_0(GM<){o6&WzoAPq~-I4@kgTrq|ekjPgc&9`L8S1%m+ zG%3MrdlWK*S)LDwLU|%UfRgw@3GI_ORsf1cO^8m4KU1@U!>*$JXzzXxPdfeQvs5e? zw6(EWEy>s_ErV_oQfL-SR@_sK9sr7KC4^9S22-;F093adQ4|W25Ogh7;m?MNH^@q)gI}D`u`RQWAmUZTsm*WbwSs#_p#EOe7D0Ar|UmK;o z^%gODtayR!p@!SME?Ifye4(>C@tyhvdp1APjHa!Jj@E?yYodNy`>(rrU;N;ed!d$& z^E-|JR~+LQQB&)TSZLnxXA=kKN9`4f&-_To^ROd4JZTtfEa;C?Sgz#J-PC+j^H}G6#v9`LR5kH7xaOzqs@$BCU$ah*)9;CCKIas_q zWZSNqcOrndqLseaSX=1+emWGfwl7|M}Gb&vkMXmVZ} zmz?=304xOpc`z>2uEuJkK|JYH_nN`HHmjNk&1ML*Ix7Rftc)yGyyM;4*cdtRl!5JQ zYLj@{qy{vKac$0Rr$l%uwNwH3D{A#Rxog+1cDkXnYGMbv-P)E*0A(o~DLKt_q ze_Lu~JzCxW_6WQG-Mr?34?8W012Cn`tEGHDTXMQ4^Qi$o@z4mIh6U&9ySXB~snNT# z0&cj*>j`l^OPt~-=ZwYMd~ueq{3~ml_go@70AS1m3;ESILZWRdf1}*zh82;pGmi1$ zI@~8ROPot0YqMb7B;-W*$j%kj^Pg9pASy4m$cNtYu0*ZlGJh;B@0;`M^4nSHwtCt} zgLWSZz35thJJh3MvAhU|tO3}Cr^aq{7n(h~Y*%~WTY`0W%RRV!PYKd%qn45`VaB?_ zIpXn5a#IW5@?If4yy4zz$&-X8Y{(bmeWK*;l3Qnfq?Uu0@JEt)f^)s_#=i=;_V5KRwM547s6gq-ZV;&_it55wH}MUQ z{NlSDD*?Dy=n>*3(o28#jP*N$UyptEA4L0r%0L6;KY#ky-~RW%adSzyn0U`zyc%WWf5Hl0T@s+Y6}x=#($pJ;QsrCu_eAjE?oIr)+x*46uVN zAi)we!4pKm6jZ?#WI+=g!4`zU7?eR3e8CyC!5dt`8pOdJB*8MklQF2V=1Ym&fCrbl zK<*nk4dlQjbUok;HV|Zs{>uU;pu#G&!YjnWEY!j+HtB*QHH!Z0ku zG*m?Q*FvL;B#ZC;xT;#<_+{Io5Mn?R_V1&diV4E*s0#p=2k|07OJVNgi zGvE6=Ka|BKd_S|eMPk&(9~j1M?8R>M##{u)aQuNJm>Dz}f@G}2WgLmBaSv9UzWL%q zo)g4sw7hE+i)>jy%e;w8W4^OGzZkeMEyjV1pxIN@a9Pk{AHKkSBPQ%6+5C zYETGDV23lgKCs-eguw)BXoq%)hQgYFR7i(+Acn3)KPXHKvRq3|Y|G08#mv-9VdTth z?1DY`11?a+rX0WI$s-zzNy3!lcNA zse?JF0UHnneelgx5C=Grf@n~R$pj6{?94<|%eAadw7gDH)Pf&eMAH;KoS27NYRSFS zIn(-wPbdgE2!tSz184|`4k(B!kOU-X17v6iY3z@j1WuIm8g;M)63~Z05C|Oj2iMv+ z%EU%6oX$tg&Z2Bkp?uIxB!byc10v{7x;)KXN`RWXxz&8gzH?15icN$lfp)M2xafvZ z7?Q!RBbgp}2Yz6OIRF4c$OnR$hEX_(ZTf)!9QcPCP=Gdd z(>I0FIF-{mrPDf901^O0Bhb@5< zKyB1WRn#qDkT3YtC&+>fu+t5&gAK6LP*s3^c?3~4RX6oiP(9UEWz{)N)mCLy7ce^x zP=`!Nhy&1uQn=Eu%u>N483>>ODG-Ho&;c;o$RR88g7I(=1&Re<8jg$Hn1SN+tPwON*}*_)+PS%tV^ zAcuS)hhd0;Uup$`Fokf)hjK`UDELi-WkRoMhE@R3JP?Q*C{P{s3?7|MAq_~b^+&H| z#F5;Cl5|8QEr=6=5CbA9mkcfZ>_ex0+Sd~Wd+h;H@P{}6fK&*FH;@8ocuwX)(0o+T z1;xy>BwXtJOu_|QMYIAu@d8LRTcwku#c3RoV%z76NbAE=xTUs)Sp{&&hjU;Cyaj;9 zREK&fh7`c6z`e-9JzPax+;EItZ=BsBNQ0V40?5VC@5G4zM6+D-EIYTQM_%RJpA$>2 z(Av(N-ECZ6ZJb>q-GWGrT(Iki09Zwkx?B?zUWp{$;^oiH?K{@(N!NW{wlv(=ZC+xG zT}xd)OPpShgCmu6Mh`{8LCjo4VNvg;s^i^?F+qJxGHgaNpfc(vHZ9 zCBt6erM~+`Gw{`4NaJ6v@ZZZ6;BQRa9_?UHq=}Qg#P^jorrA&pL#I|$$hO;F&F$U_ z2Dl5(iVU{S4_00q{$Cuv#LygDOeA3gF|S_OloZb1>cd|O4h#`cghYU0c9G#iB;WGg zV1Cr$8b04oY+TyN#2;oFapN`!md6%8;uo%tF!%-kU1-uKF1er+-?5Bh^sQp-jN`K8 zTHD3lEmq*ORT>e9hk5V;+ACrS?kyyiiv`eyU$_D_-Ze5#iCVM@8kXZLR@^yuP)cS* z=4&^}} z<>?TBTlj@CAZFF;=Avn1{2#^D0Fn-Bx_GLm2j79i` zNEqj0rbV|C+(TSv^F3&UPG}$HVbc6WTZRb#5U7zIy60@3Jgwk>Un^(mkbz&|g*pr9 zw;kwn?%#B7W@f%&l+Iz5Zp17egHeR&hhPs}NG~GB=eE^~cVLC4%Fm64j#>BxCJyQ0 zHRh}}>6A`rZfxg_d{82|-8INvQH<$^u-*utkF6z#JWIA5zu8r)krQ})8#i?cpd)8}c#4)eP1bpy^a{vXOnvP%giAeZ`MOf@H zZfwqY>`G>7D^BX{gk}WBMa)(RiJpi5M80Z^<|wU(2o%_aY^aA6-px-);yamWVt+27Rc8Okmg;(1$dk z?hxdKUnm0U-siE_9qV3b>?TL;{>1BS=wAHpgBXAc3^J_NUae>cRhR;Upa4&RZ~PVw z)IMeVHj^i|#iL&7>yGV6#zdC}#sN17ED45d9`9Yg=&T@Z{V;8x$bvI=Ity=FzaeQ1 z)^H8xZ`sXp+SOsFzGDHeYxs2tS>TrgC+}R-ihhtxL+Xd?XmOY*fJ4p#8E=>PF3%dD z;TxCj{qAtcX6b_TgXj(MATQzniCG-w!m=YrKj3Z%e^_z=P=R}Jaw~s}QU+)$FIcrc zX0~2u{~pRNhiyybf@35`5hsYM36~*5aPxkMOvr?O-~>m{1WhOgzqF1ghlwKaXbiw} zA;IuR)^ZQ$at@EgBj^@%EOatw4F;&Wyi9Wx|81=JhHvl(ahUaQ*oI{=&{lIjX@Mi}W z_F<><2*z?K=5r}lcJ*EN0RG_69L;T%_5pYs&Qf$WpUUc}oXg3a&FP%a5s1(kozfWy z0nh|)0NPGaj@OBu+$wkfwqSu@@P*19_YNVAHXv+)K!7$_6M}BtbcbU=KX#Fi&YGf*q-kBp70R}RM3Vx zZ~-YGUCCe{_bDu?dU&<~YN4)p4j~OCCx{bh@+Z{qwr=+U4toxkxO?hHr=}Z2S5?AA2e$`5*mEu_as0 zpJ(1Zhz907eCJE8Ac5Hz2orF^KpG@q8i+%h(w=7|N4iZ_z=vpPgXL%jOwuHQ;3Q8X z2xT25L_uxU_I-^809F79R{n;uDyWLn2>=QgGHmGZA;cB`TtKX7@ghct8SFgy;qfEL zkRnHtENRlC5j#dsvTW&cWXhE2wXd%VoDM)+V@;s>pY7c&M>=GQF(jVDvCZ22WR|GMYyVHN@e_qbkpg6}h?`3~{8xi02=_ z?En1nI{=^qG-eYPS~4dY0EBvj0D#)Jkix$>0G^#ySgD;w&!Cs{x5z-(FHH0|Ab|xM zcp!rLefHi43bmk#e59F{AVjM9b|FZ!Vd$HN8`9R{7kl`zg@+&kClpZ-fe_3*Vi?#Q zg$%)X*>kAX(*r|2*n?3AJow1NG_UXgzz5Md)8Imxlp}yb2)siG0CD^igF;B$1;8lR zECh@HG79b&<8qGt;s}^!nt3LgX6m=lGF_Em&N%mU#o2^tT3BLj9pcHFo_p4$;TC`F z@r9p1oG4t14;6IV=eKfc;d-3_q3tuS#JFE zFTkh8@eDiaFhj*cDiGsNIjoqlkQ>$H;|(PjA!}@90{|EX#vOb7@vs-$(*gj)cmlxx z3Omv{t(_ck+f$z}pA@sqCCzrm9&A`)t+~lP%FrS6POfTO>d&zqlwo^2t9wbqZ0O zM+FXNQ|q$np_g90+@fRuQA|mwv4bDu!kP<2B)p@5U$P+pX7P(efU%5b?Am8o z(E$Jyq>XL-VFH6F#0L^_dqxDE5$>RqGt|t93uzAQg5^Ogf{BWXiC<>aF}8(NK^FlLBp;$^moC3eF@%HvTp1QQ;|gq0 zK>z}v!Zlj)$TNa~7r&6fC4(uxeymTI&dU0AB;~hRSm#YEeYfCPH1=n1!-aq6EZ%FN=`Tp$hY2s|W={K*0)= zf+?9rRB82CS}2_L;SMq7*-U*_6cNCqMP*9pfWSHxo=zsDW<6{FNY9DRF%h+`mAqIx zqPCD4;D>Y5!>2N#8bQ6fjc$A30$)oc(5gJbIE^Z#PTdDf&NQR3j(u!1)M~~o{Hg$M zy(}0nR*s4-gc9apYK)v}$H0P;v@c8D9>yS5*bJ5^OPI$zlyJ1fR&lXy^(g@p0H7>j zwzn?4*e33Q3Q0%;74_HzXelJxm712B&9#>Iz?X#8wx+cYpv62MaVD|yhr3ZB>t$#l z2fAF8g_f`EoP)Bz1apyrrOMQL8I%3S@rZGsh~BY*eQS~1K69y6Tn zHeb0J@KWXk%}*RKS14lz?vSt?uuoVX4zm}PMUF^WZu#}tSbFo!boL5ysaLx0BN zwg9abKy6bzO~JFJF};0KyzW`t>Gq8k!Zj`i;<_RhNM9s?&FDoFNZuKdh?hUn5IF=Q z2y%c%IM&DzeLzVenE0$kNYII4I9pZKE+Y#V2ZD+-y-ZV+#5M4N4{J!Gz8b$T$6@X9 zS#M|vXvmoFUCl4Y3{5Q`a#AQnpxyhdC2jjAtX65mK}f|eWAj~A-)HSs4vVM2V? zU~t#-ki`Qyj~vfyhWZv^FaS89j!ZNJ*$aUNvn!&BY4~FrnMgrI`Cds8_~I7_##k(> z?1c199QVV#7(O66S9|~;LBiiF*S(DK%>=lJ3%Mv?0MZ5q6+(fDfc0U<171c1mImlG z1SzzE3sk`}oC68~fGdn%73_m1;J_zv8b;UvC~(6*ECcU7ocdK#Ec}8Zc#H__f;`Ye zmA#++1=Gb~!(S{!CuqsyeOu!#-{TqoVNc+U&R9>$H3SH#%lb@UWk?}qP$5I`)G&}k zK9IvO=#Mk#l0pQ+Hsk{~m>E-0K{fQl(V5ZfeT)l79)$c_~@#v?LDB%(|Ok_Hu=LOImKFsxx2_0lhO zObzBk9PWY+(&1aJniRZ({k%dHSY79A+}6cn&1k_ttqvk0q2)>06~NXU4wUr8+b@#F zBw}A+jtL>L8zDyFV0r-f|EeaxQ zWmN*;LU#R8FmlEuD#kEYVrKaNgEVA92eRG^RuV;76voJ2D*VGa*j_bW(#6=Dy>$Qt z_@RLS;*ybL@!_INcmV}j(9AfbPh?fl0K@J1V%o9YM)t=$4qIld9@Vto00Gr62vx@f z!awLkK=NP(JB7io+?27Lz`w{HR-VztFav!pgdi{j07wFub(>k{ zBwD7FP__i1?S`PaWo737VsJ1ZJh&TDW|?RTn_H3O04)H3^rEo{z`vA0VM5Zy+=EEg zz>c_p%9Q0@O=f;^i+@QZ+id1coCpZ?jf-VaT>|5A3S(YY1Tk78Mx~d>w8KBVCTzA4 zH;e*9jKVemz!Z?fo#CXb>E!SM=Y}MrNSGK<{$|NBq9D=bXkr;@@(0GHUsPJs75qwj z77IE2!$DGK8C^^r3fW^VGNZhA;g>;WImgn6C>aD)Lb>dkUW z;D%bpM=l4{NgdUxT76cM#{2?rVN5dogB$qgf3BJfjKU6yLSzn3jcTKK0^oyUNN(&# z*u6xBn#51k;5-!nr|Wd+6e4LAD(MyOoEghA{6n(2s12E> z2;HdvZR2?E=!MkUGDHyK=^4ct#z?|H+~%te(8W|k)vZ|+n9UHv;-l*7ntC1BX^Y#$UoSY0vA&z9 zF2;wV#vSJWp(pHNADXH=$$-)siyT~KwGxoXP{f+SK&j&Dhka{WlIKTAUTf^?NLVVz zq|&i|)w+V}Vx;0KwxYA1QStm8u~31&?yCS@j5ol6nn{=>0II+;9=ICpg(PC65=z1b z>quaMy2JvX9;v2oMmuUnyAl3;}lSLKxJnaXu_!-Rwn3tX2@DVHo7ano-ipP_YQ+Ka>~IBG1JLKqtI|KlsBv zAeBXM!Zf(UIT!<9D8vM$LOQ$yG1Mb-f+voeX_;b(xU#{IQZ2U>M?4flp>3_YdTnOx zEN8&~q)f&nP1>Ze^sEc{ov{pU+X@fjK!6TVK{8r|GEl+}AVD&OLo%j z?wICiAR=y0AS|!KEJzdrQZPbmSuO;wt2;)llUl}Bc4ZxWWmt~ow%y|}wPCT4Zs~HE z^)>|x{KLMGfIb9*LI^Fw6z-xXWTW=()5b>2=85on#IPF25F9Vp;#7Q+24XVAVm9Vu zhD`Sc6Z^Se_D<*ax@`b21r7Yekifw|xTZpc1C=gBVHidZ{6h^WfCg_c2Y0Xse=rD# zum~#v32=lFoG=QfunMm*3%9Tfzwik|fgL~r4A-y?-!KcyFb(4{4Erh?@bC-kFc1&_ zF$&v4m0f`mJV6#@zzA=E9c;h|N3j%7@drCG6jL!4XE6v{u@+~s3p8(K$mXclCbjYk z=(cXsC13I%Q&~Jv0w#B|Cx0?1hq5JG0vJ=qb!O*wc4zfk zX)sArEfjE?xiR;$GDf5VI22AD-*FxjhP_>I26r(qV{r*T0TCDT5DT#}C$kMBvoae& zh}catqcAf^a|;(ok)p5?GqDJBaWHqY6mzpThw~Ocu{ewH7eD1?1n7Vk=z%8x=z;<; zEnAW&f+ny0%M{4+EH6eXj04&@Fa!gD1nXt`7KlRjneVy;^0_RBz%21*mx)ZSdsgoK za?^6e=!_1u(3gGh>R9w@{Oc(g$0YQY{fOBCS9t!%K0 z0gKQ=5j?ckMl^i(bhn}N{fV?CJ%&CCi#>z%@(8sAP+JC}8fs%E>MCDW0|eEu{L8W+wc&v29{&Sp z{jECGLouM=Rio@nw=YdR^WBu^nubB&w|fjA+oG$AjCQn-gQZ(38v(NaOuF0Fo>k*@$tnh=2Y{`ZF` zjqWlk?=B>Ig9P%mc9m}F-ZdDjrCV%wQ)=^Q)yiSJaT6ZHDB zc$|;Kiw|PDg#mU6jTi*ymMgE$`g)gRcxeWBB|+<%Kx2@zdX+Bus}o3p%NlwgcXCsC ziaEg}bX7b&f)a3M`GmS+jXFk^dJWktFJvT`z@Z%|d#i8%S+f&(tiw5Jv&4Ga`m9|6 zBdE(f;KHuggnS3Ox0iP*XQiPJQ^uMJYwm@*uQ@ihdw)FplgF>)o`j{-`%8quBd|!7 z9m3RdyTeYmzk|CwiF*zGteH%}zYIpg6N|{Z-GDdzyBj!6zpnuD6%!mnp2JoyFv7N1 zSFa2DlKT8)fO)tR`})ODDIy4oBYDc3G0~%V%kziBQ~H6!uZa2Z##;-`3_&5p0>;aO zEoi&~_WZxE9MCTWp=VapLz3u%$@kXN(yM&hv-{I8N7T>!)PIOx^(f;$d`yYKBcu;( z^}-`Ow{P@&*N(kH1w4gp!atma382C@+=Dovf;lPw#1t?CJFLSp#PUMWfIF}QLx>rf znPEk&JPl!QjF7@VOz_)VT-*cv+#^TbbBn^hY=EIDw10%Xqa$p=gDeyRpI?aK<1e7! zPKHy+6nuj1*WnVh5!VT;IF_Z)CD8Mu%1L!NnrDfWtb=o_QFmkYGWB2M03A(f~k1 zhYtZLu%iHCMT-|PX4DvQ;zo}jK{}L3F=R;qEB>u8xss(r4&2~4J5@1IJ_G=!q-@yZ z9}S12UQuG_a2PU&(Ntyp@b5!Qr%$0qbr|damm;Z975w|B<7!v0U%`eI+jVKvu^Umk zINLIVohJz4#+5twpb8BrUT4?A5aoPaDwubZ}#34+~sVIUEI7G=T z{y_8y1YUlTfj(6JX(z-LS!}T-=$e!Nj>YQUtI;6uY|IhIg2vdxk1cYfYluQ(frqhp zXgQ>aAmxg$vW{BJk3T89+Rw!m%n72Q(j59g8f8eLKpI!3pn@1|C;*_CQ5u>MfC?|n z5TZ}Cs`En^@dO}}UlyTnoPS!$Q_w;4gpoNJSEP~28h2cDyG8}#Vvjw#a1)BS0%Ep3PQU=L}sA(GV5=6gx=8-3wAJ0z0GJfx=LX zF?eJtgxqpNz39~D?qx1tr&4AAu>&3e=3$ywcmUvoXq?&Lp-jr5761g^u`q{#J86dp z696d6A!w4qsM~GnYk)*0oICCxl0Z&bWwAak?pqMUT{pYCWR9%SB-9WuiE@XeMIOf3 zyF#FO#jV$(eU(GHIHgzWH_y@zwkC!YsFoE6d{W6_hgaB90U|f6*hdo_KGCOOkDXn4 zx;-6n?vj7PQCsf0p=uepm-&mi=I&_T+uXhf>ahjSHn{Lpu_(hiin)BwL9A3{|_l;Z! z4e$H(_FJyTg)eBwE+(!2)Y2;+0p{IU+`AF*y&s3Da?P&4Ec=fx-(9NSy$@>vU4C(* zIjzD^KYZ{n`<=evi${p~_=g4@-95&zv|S_T0frGL;4;5ORS!RrThaE;fIFurnr!K^8xoM=ltlgyD%$ zW&{+80YjufvFI=(-OFG}Hu%GqI6-y`Sk5~B;R+!xFp1yWrzr=A1Jm6kyKQq@cOa^Kj1G%g|G!<-L$6H~UybP&wtEiY1pU+{u5zq!XhPytSLa?6#>;4Ojc7W1dWP88-kJ?aOeXOu!v{^R1r$>BOK#6 z#tvF}r**DG0Jiu=8Gus*t$b#qB?ZkltF+4*P4S8(yktumhX*w5felu8j~F5uk64u9 zQOzvcGoQ5o$sA6TR78~uN;db2iueaWTzW_qB!PrBAfp{5-5p9z3V=oYLYBWl#y?P# zRk5B0t4CF-6s-eO#`)BjfY`$yxKN%j#Nubk!XNhV1@15}9*m(Rqu6Sxy$aQn ze8rb*pVG!v3F}p{!U!>7vDkK2RwDwa#V^DFniOb-wY)VhOD-GRvx1AIYQOK|SEm4$ffo5!zy@|UiyS~3rO>TLkBbpS{2~^hQN}-V z6JP!RB6qiUTQ1C+>)ao7R$N5LnI4*Oogo|oaW4d8kO;h;)w)Q$m;rA~uIUgixxzpI z@I)M7AO%?5gDdOn?|vV`f?xPT1eb9E`cNEWkR+F1|IJ%~of~0G^~eu*c&T0raSO)y zZ%Itj@pUE~r3)`@$xSP-M!4jRKmouM;mAihk`aZB$`~WF_(dWvQ;mOAgUe;^4Sf9@ zMdqeez(;0MBfG#|f?z=w?|K9P9pz@jBw2DzrktNG_hib_c%Ac|#adKwEi*5=B7|m1 zW|y;B`svw5_Zx#Ei@=EM$|4NnqV!()%*oY!`QWvW<3EQ$U{9cDf2 zRGS3S%8_*ZjE$WkoMDTEn;)GS6AVTax!7_JQmBVI>Y~cqtj`|nwr?q%LyP4Z|9FSP zvb|`0oBG!8%QZ~HeVs47HLe3@Yo@Oo3&_+g;Y~vJ(U_gUjE}|H#~t`9M^vJ)SR2~` zXY|LpS8xv=yrmT{j4+8=zaJAs44Rq;E{MH1m%|0#t)+KgH?EOWgA?U~+*6;x0*e#@ z+~j30`U2GqU^eI2-Jh}o8>ai*ng2iuk1!HE*1gE8+oT7@dwUL1014{y-J(sARqorxD9 z(GR}zihmTt?srG?Z@OKaZ;O5Fe&aEa*80+}|11~}p0wi2Q+852K53B0$k1;|c_tp+ zD{#=tU_0-0ysstnz!^O-VQ(WzIWmNoEJTB4F>%f&U&4&Hp6%6$eXmHKx4K_qv~IDh zs2m_4|4>Ho1wMQZ>K&eZ_a*hqb3b)S4=-IWEiewza`+?J`URvtlm8DmxUaIjPly;RMjn%nA^c*iW3Z0`SjD5Hto5 z+CGob_T&~QNV)!j6dn)))o(0{?>CN*o-Qyl#;x4s2M-v*NLr7&`Yr?=r~hu~1hGf^ zx*`Sdtp-ud3CL%hE&wXP;UDZl{AMu5BG8&9Fw!b;`i$^X77ni9A`8-E9uBX~c2F{q z(2SVyDk_X6oRICHaKBdV7xWO!oWg?sq3*Vj%es)TzR=sk@b$*fQ9diQ;NlRR2keLt z;o1lyKR4vDq{+p#<#-Q_;*~M-N4gB~;-b^x;?C+N|%0s@{<5Tj9-qVC3~ zPS;*>F0_b?4B`+LqxE*Kr@}Eu$k9}S@vjmx9R+C}A!w`gP#27-Bt+^T-e4Z-u^5SO z8jY_S#j$4K%php-<~nU4$7LVs;vj+U964?whtUo-vdmNr8G|b%IA9o8e`H1 zIT8mw68Q>}J76w<3IYpk?h%U2BmoK~=RzgX&K%co?Xt=tA&4sUu)aV-0H#4Jyk;kP zGCF>e6@yX-hY~xk4xjXiAPT{GS}*kkZ198!D)l8H$IB)EsnVpZvVo!n8Cd`%OhGG3 z4lGg3Ay-i|T9M+MvLFDjrU+sP7~yAf;TD4vDsc`s!!9k1C57%KtFj*VYkZIq z={7SfWC73MGAsXdG9=kWQ{sUUB2ngevp2^PIExdFhSMbK zFf@Cz%p40D!(bzDG9Bb`It#Np&FUU;EgvP(H}&Fvynrp82N-gW{>HO1YtuZXQpwKq zA{a7|_7Z};Ob@#XBf{Yy>H%Zy^FG@%EUt4cvU6SkTrLAsXdoD&v~mIQLMQIybcY@Do*B6FXs3G5vEchG3@pK=6v-5ll-r zS2RgI%|#D_E+4N!w+}BpZb**{14u*$_52Z*!^hmXHF?+-ee}D-h zNh!t1N}G~O`EM5+Pew&;D!a5p%WOH}PVN-oPyPW3(o{{og-y>QMB7bI5u%Yq>j#i> z9^fJW=mJ4!MpE|-M*B=ln~+PXQ&71~36QaT@WUDeb5R-9og8&6Ahk+8wIJkAAjF^- z<{=mgbcSlx$ndlvu(b9>RSrp2NKIA71mG6`kg-A|U>mez5?u9FT_#q=Vpc!J*pA?y zO0*CbqZe+`R}VB;6O>P{uUIn?T@UJ53D8U9Yrb+6vL=8WwBiz`m0Ht`m)ulDUy%rA z$}tb2v~WTCENNVSRWF7W0R2=NX>_A(6oNp2)%FkoqCqS2;9l_+^sF^3u+>s_jmP3D zGUtI7n7}YN^=}UL*v!@c7S`tgwNy_L6n|kBSoI&|0An-O*7Vch_!9(k1kQ#4O6MUK z*bQY3wmerh30v0eUKUwT@d{G)9NZOWnaD6V7A!h8&)Tpkiy#&l;}OEMV0rUo=M+@` zG)8^0Vb|$lA&3BUfgbe19q0i_skUAJlQpGwcIA4u2x}xQ)xb6xgAoYwXy?*w<85hE zN^MbXYU4{7`~j@Usctz`Ec15n_V)cGwK27z7Um%yH1#A?)<(!SVFfTfOJY5d^KN5I z0q*M`yg?6ZQgY+VYAd(>F4qDj6=a1hQ_F*F#TJtc*JaUmMgw&VO#o5p0U1S6c44+P zYnK9VR}9O8QZlWH)-KeU9rM+LjrZfS9Rmdk6xwjNK+3@bA45ia`hE{t#Ld2wtB<$ ze#cgO1%h-<5OJ*&d>vMNO^N{jKtU_A;UNfBA{E$f8F-}}_#-1D8}&fgfMJ3uI4(z* zduLCB>#cb0&IF+KA2IV%2WDW-~E@xUPj02IpM9+;s9KGS^-afO8vJGAHz zU|5D{m<>bsDQ&nMy_aEi*yO69PGqnmev3khxQJUq4nkp7lDHu@fgS812#&!UoRN*L z_A9b>Q95hk_5g8W7+AabdM&tY_16-^Sa^w-eP;~;mQm3x;_dX1#nzZTqv9XpSOCf) zzeoTde&zP|*em*&kRxLe1zC#+w}J~9GZR@e)zg1L0)RVMfU_zF+CeMCfdnu@WJ>dr zQ#X_27zPs6A)X=f z2=x|d2bj0nmK#Eo8={QAGGm58Ll`Ot{-FjGpq}mdp7A-K^?9H9xt|q)1l+<11bUze zx}XjEpbpCAh|z@In3 z4mQA_ReGgaTAxokrCU0tWqO}qdZuOi#T1w5xH*tIpkn{w8yaLIejru($eb4!odH0d z0f3!};+^MYbN;~+>|m;?x~i@EsHSZ<$A9FckVm`65D2OnJK#@sk6P015C52^wS*)}ao1z!>nDxEmOM<$??R zK-lErbF=l3f0uf`7$K>e=K@{-Y))|bwUt{`#9#E4vDqVF`E=QJfl&-KwL%jdJR^t*8A;~Bv3sWpuDF5n zxRG=&vN3RboWt`sx^Z|V2b{$R_`v^R8XWK`{#p-T(8h&`b~l`w$8bsa;Ab8IxrN-n zO+3Jb6U>S8$l2JqN&p(_q{*WKUa3&Zmx#($n7$99M@mZ;iZ)W^yoUbU$QRiwuDfb+ ze0TitA6~&L@^E6^{DL3Q-fE!E^o6><5ZeRz9p&TfJ6GEX1VjvUxq2z|W*pFSk zEF!z{4Z>gXI}zfy%X59tF+Eh*FR7O5KMw05;G`k{ zFa#{pozrXLCUW94c)}+jA{khrAvC7lJLV#!-Z^xj9<%})VmvBla%Ojw>#xe%(J|w% zV&k`K=6VFk%U;}v+|v8}hJ8}y8_JrpWJ@?b?g3!#zry7?{WMZzHCp2}V&fs6;f!M* z0A_w!7|KI7N&$RSE2;oE9AQsvp`0N<@-H49vHdl*J;VzFd9)mNVO<1?{PV%Mku74j zTm@ESvQ_jU3rnCk5vq(BZNK^7#aA3_lF0i)i;LgZdf9)eCbC;8PTY;;-ue**)^ zXNZqqcL3tUzYhQk8a#+Fp~8g>3$FO*qM^iz6dPu+^W=xdjT}3A{0K6nNR3AS>=@z5 z1(7l(`fvrq4m_&z znD&YX!ePh^LR0m0;R3OYM=@PjmENhwHkHH8W>Y!nW@sVB*xK0*dDnM)YqgW!h* z!x}z}xFCgP{~B)+ka+2$U$Y=bzKl7u=FOZt6BSt4bHj%bMK8UWai{8=GdF7K6Kq~C zC#!3BY;8MtNZh(@_WaqU3NEN$ zehZSuAVaA2Mj=PI9kE6(^8gb@g{$%Ap>80C7}9S*2^Aqj$fbDDikT@#5pw`I(~3cX zY?BW*b7V%9Raj~DK{U>6a8M@YScbqmd;#FbJD6nQb0*#|HPN#WR+P7 zW|(58=%9iSjyWNTBIZOy8o108Pa$gRG~%2))oJHOCI*M%m;ktFC7_qV=qEzV1!+wT zDJ%*e4)~;!!w#>oqXGbTiLz)4CO{`0b=FZCTA`c?qU9)HionY+PKe5CtFAs(W`bvm znP#4M%n^L9Iml zk25ynsG~%&zKR$M)il-*2Vy$%ODyER3vavtj4R-*Vb&U~O*4J5M?CYylCQ8i1+4GD z1Q)x|vJ5J`Aj5_=E3a|%Mog3dm}uDykz%6yOA!=*4041M>t`>R_!9h5NnPv_+bv3< zEYh$r-)3;Y2rJ}pf;l6&GgAtZq3lL7bkj};UFCxi`FZlpAQ^Fo z9~uIKh1FNr?Da=7&v|n~J@0q6erX%^^V5+D?RE`Xx&i^KGWha~3~ukuH&bw%RKkxZTB74-$QTEOk?Z+T-RzOzc_+<>83BFxo3g1 zIC$b1?jaAai7O8F>?GCh>*FmRD`w@M`99I*r}Gze-w3RtWfbrJ@Cz?23=e(jsdu(| zimiv;<{m4_GKB3G;y!!hA?j`r@SK^y8Tt$fA3a6WM=V7?|H&&l>FwX|^!v$8jV4Ck zYczy2>;V|_*adC=cRQLO@CV}a5c!(IyD+IQGZQ4*Kcs>`rReWn6G(=Z9wRR$H1ByC zEFr}<_#*z%%76bG!yYsQ4>2q-fiq+v_=x3`6D0*%5d>2O6T&_dCIp49l7l}QvyDno ztbRgl;=71AC>7p|g|=InuIAwg1tPG4DB~i99{8vK9tKK`Eczirg6PD8Kv7he(9)AY zR)i6zagK#rBeSGvGAbsH3w~hPzivo4F9uAIx&fmZ6LUz!B+?-lq$8-@)|h8(3TRAp zq$OEoN5oVwLf1ptYhEauCjc^RgbY?GZDU9>Dod3SS|k9_n8r+wsRin48uNUiw@d0$ zL9%=p9tEdIuUUZ&d!WTUVt7hhB{NUUR81;(*gIA(Oqz#*r4xI(%gBh1Y1!Y|JmbuiYKQ)t2pNZ3YO?&1)v&scsQV%5f=rqxD*_@mkNDnHZ5P$t#I-~@Sw3<+iGTX zr(`|tWmteWj~SP+sSRFY&$?JUeNqkoh45FeY+J+K-YK`^tE;hst00Rq1*4(OW^+%w zwB<6lxW-v+f?DgLVeVlKR?rYFx`$n;au;UWqryS~(Bj=~s-Q$`Scb(7LA{NTd9IH1_T zY)U};O3Y*iZjn`|<^r=h&PL(?*nt@B&pDs5&H}o#ZIt?jALMu*JMMCiNhxS$hI%!H zZWx*+cWT5ESeKFpte4UQY2t=zq?F!|rB`FcF^qZ3vcSow88>P>5!$;6OSNdkOB`dX zHqoqJbgU~vpkI{X*-4&tQDrHnk@* znOY3s-OaXkS!=DITkC|6u_c10b(}JDlSs@l88&dfd+3U)TOudUV5}O-{J$q>CBgb@}#@|qBkLdo=qDoVv>PctSRq~Du2;fHWNM5 zbgeYJLPno;3(yIAe;8o7XHYFN>3P^h0!Gv|VD3(z*#Egx$a4Fochl_MqvMzB{yby_ z7ppogr`#sY84Q#0_s7b@;2S$NNW`i35Nvhn}2_Vu$wSH0=0o?b{#SDE*8-Jg-y zTKE5avS@F<^3cKTmVVT*r)ItnGT)?J%|?3FC{bmDPxm4Y-}d22F-0`@^F|ET|F6&J z(el{?4h2L3TO)?@dEc7VSA#aAd1t23--64ciuETf(f*i)ho=kaCTq98<9yHm_}+E3 z3M{Z;N`f6B;g5a<^q*Q$&|B~KQjdI=(u@=vx1p~qv8|sBBuN4qF#aq)l1raot&G1a z57zaqfkL@0TQOFwkl8f_*B3-M_G#EhMMQ0A(C9y; z*VjV(=(zVexGIPF>LZM%{4>r({3R?JlI$Z&C_mDYF*HQ!Hlhw~aL=ChJ^wT5l-?KZ zQ%XvYi9SCH&7ui-FBHHyMif{Bou8mItD)-kj){tl5nG8u)Q6Tf#J!P^*7xzOiHary zLbCN^Q7h5Y4UCswkZZ9hXE)N6?ugzq?U+)oetM;0ABSWKlhL!7$tgsgO6)#Ncsk0p zyxrM$DPB_o-md*RQYB%bCS_5&uIa@x&*#<4FkNN#w0sSC(~3GcKt# zs|2FXs9zIF>k$dA`ZPCHX&CjL$-f{Dqmn5t5_3wZnMxq6lavNMRD}`=Jy9tYy@6FW z=-)jF{Szr<&!Q(!(do+Z#*NAQ-;!_pPzy46uu_sT$$2oI$DXXNFcJwbJqEOkXR32wTxEtF)<@Ge(_7gt z-g=W)ohL~~S;P5x1mD=xq4X3(k933c)H{=@x1!P7Tp3XISRe1qD!B}M25JMBjHmmQ zk7}$MkO>FgseRAV8$!}Y=rbKpvz$*8vNNM+pLy2v@aC53J8Uv`bwLU@DHUsUji?`& zWqQPC-mUtQP)qzOmFHC>G2m%KN(AHv6lP;ni8KmwXZv$!h_if=K5Ue!`am<&uODc%g}|HgWm5>3pjKXaSV!W49e^^6Q@w zIeJ8yuZc~^@4d+|CEvkPj3J@KNt^~DaCx76k!PeeUinXx^EuK8$W05mVhUMNX3zgn zMk1tQ&viG-3f7;ewv81KZ5HTQ`g;mOMNPql1#qb##2YL{CKWQnB65({(F{>&DqLtk z`J4h}#*WT)*}Pk8nzFW;AsSPV_$7}vqeubr)~}2rO|W>o#y8-(ugN!a%>ks=md~qS zfE|#>js>0!P=?n?mpsogVk`=nDH%R}mpGL-_N?@~cWK-kaL54xWeox<2sb^Cx2&Q(ybaJMTd#9gE85*f2N(boQTX}ty z|3b2ahOcADOr>r~+LJ7!;lI#i11ldjdF5J=AZOCgXH7EhgC2k&@Z~4e#}IL|rmj)j zP*~yr_!2}e zg(RiIDldYn)!n{HrA++B8Ais&4wZY)sV9Pgkk1Tlxnobhp-G5jfz=vfirY;OLZQ39 zb;LnLi3lblJs5pZ31#WmZthRdpEqu9e4W^eA)c=OcHbFFCJN%GL}1`Pric$NWQc7p zI0ni)MP!bF)uP*zJYhbOHLP)8m7jeewELv$7ykM8`{Q#`je(Br_Q$;Y@F%8-Vk9|? zl0GB}jMK(XHT0PA_gHB3SUL3A#P#f`qnbN5? zWG&jHNv6a;*unnFp~0b{;q9SOvf(lQ;qMy5KOBZ9Egi<#q*gF^BJ1DWlQ z@g+0EI-StkZZ>T93+92np?)S8DAJ{$9!+o>H+o(<`gdsbs%4bJ6w0wQ3f9CDIbu)A zupoad=`fZs7fVh)b{$8MN;a_XFqURCcB5)6|3N=fd`}S>hO~|t7eseEh-B6U{xgV# z!xZrtL$+N*F&IP$p(Gp)g0Jjj#0vkZ-R>Gds507MB}dqQbx^UBmtrs!4xMU#ts3)R zr}%K@oH>s_2oo)ulH0a}yR@M~0CWyTM$}HQi6IfM!9SspKOp$ea%~Lff0k?S^T;?3 zr1U<>ks4R1Vh9O>r=YT1L?XJ8(ib#K$Z;iv7Di(&2%ouVP^ukn1c?}a zfN?1BKi%5e;{SAOYa@)z5M$`tQuoP}^ycQ~$*6;8nW!(Fq-o*Obu~19H%U1 zc=5&B_d@7k_+o8s1WOP_K0rX@LNe_#{lSzBasa{A@Eqx|oxbgkQ=@nO-TLutCep0l zO%fYXqw0sw7kzu)Q$tsW8qf?zrJzLx~rDME&dwVuqn9hoQ&aRfu@qo@%=!Pfz z5=3?hlCVUyd?V=XdPtQP;-8y}|XD^?0Pd8cbxu9sPs*jZQ2SU29X zZc{dl86&jNrZMgG1&kq7g?}a7qexb{z_587Qs2MJd=HW(^|5kJEa#-8)heQ6k z4w-RtfhoD~VpZdd$+sR>&EzH|J27opbpLKUUjJ$QF-3oS$7dV$e50#vTTwRh6g*zr z@CCX5o7QXv)Vx(nu@=|5Lw{$Do4M^{(3>9*e_5Nih|F$_=k1i|ZM9zQr1dvvP6LYA z_p5nyMNWu!A9i>0R_5DQUQp~eknXlL14MPOm>QV8{oX0-wt?sF`uBykfxQUU{W+5Z z$$>5fbwC&?*;E6IHO(g--6t#Dn|gRK)V903yZ2>&YjpEV^!`EFPZ*ol&P`{;Z>8W?(>8t8f-_cY5 zy;Hs=P}&kGQ0pw*`OKH?EHv;8-&X3Ee-;lvPr{ugX`M&PoTnz92LzsHj-J2zdY+qq znn}KNp#ZwkRa%mGQC59XF?vz8cTo-hTYLBKN3Fk~od1^KKx}sx)y<;^qUZzw0=-s1t7ss|wDxcTN{h0ajTld3@ZVJxY z5Y(f3TfDu5p4c%=v!CsFm;KnuxJ7Jl?H7}~^9zjYH01VWy5Nh>NZPyBa~V$Ny-5V9 zw7Cp7tL}6mwuzQ$_nDD=;|RL>WRK1MP@TyK#!a6#Ci5+--y2KqJIq!-SyyVw_BNjT zdUZjUC)K#R(ie?;#QNpS%6eM*QG&^wFhXQXjqe}(N$-3cwX=fW<1k~8bt;g{ zvIA1%sN+P}=mCPlSJp91da@bs)bWF>B$i$GF`O33=e@dsQEAB=X5nS!gaMZk9}92a z>-!sT3Aisdiqjz|YByLkdz9o)-t|-#NbPzuuF`!i%O*dVPSUJ4Udg}?kWh(CW%5G4 zXC}JsE4BN@xxv?_`h+5zQ!}USD9Ao8b%j|+KRN4VMXi^gecurz+j&61ri@B&CPM1aVV0)Nk0%4GjZBgLp-~4lINgJpM9sryzkm!F44a5Qfxt}Q^=ZXvf zXa~_dur>81g}C>>Wg}oRlS&AaxjNXxum2iviJ*;bbT^m7=j~N_vs}Mk)>;N~kSGq@ zf(ZiVh=C6hJ)XAva8~_ZTKt&LVOR?JW5f#c4_kI;2?7eHfOd+CQ6`z0y5EkFI`Z8qwFeQrr6_Lz{pJ1bO`Rq61vY}Y6hr37Y{yV;8%;rD{yp?(eGwb^riwbr zxa?s8)73_#SO+xdo!CiP!WSOp1BEAf7kacb57K%428IGn$=?fP+G*Z;JdsoQqrBC; zg5|kxxPMnLr+X@oCXYx=Aji|%Xd*g54@=Jap(l6WGWtPP3W-a`p*WwQGD5#YYheS- zC?KndkKUtP$qJ##Do~v4tMAyzEv>?O_CgR^mR#CgM6mRUfW0wa_{+;swgHt03IbFJ zV?i_{FJHHVvE)<+sNh5L^3F@cL8>K^^u`{=4{lF-q61-KdRG_&{pUZ&nYG0~OkVed7L)z76pkI2@&xkz)Yf|cL6L@=GFyW^X~i|U<*s$_UWXGDT)t(@fml5d|E*e zl-J_mS1{L9^#ciIE`!6R%||dI38ZVZ>LrTSrIXgCjGX43O83uVbLKlWkNVDBR|3yM z*{nZmO87((yTNRjGi+74IL-{jJ8C)Ib8OXVw8`vqP@m%%+>#RGT7xzzZX-&e?0|NB zz+59+2N98&Ax^G;KrfS1$%~k{u0<-{WqL4GLQQ>0R^0TxTWYe-Jz$D?QQY~DA zuRru_=hyQLUoVY(T$~kPdrl+S<0_Lw0NCk%&$2ej6}z>v!N(?!O=%O7xi;H;pH<|p zuCyMhOGe5%sl@29n!6WpD@YF=`mAFUfcp)H+O^z_Z3*s{CNPZ|yS~k$U`@=`IHr`Q zxA!__%p~PNkIVt`N>rP6Zg^JDH(ebDV!5 zD3XBTP+Xv8NRM#wGUrTEp4Z3K`P6=iR`F}+M4aTR2n0j1f0FzLZ2F7!HUB+5G^pS= zDO*Y(em2=LTd$^w9HkX(Tn(O?(=cPpDIj3qYVTQO=C$yV=;e0kB;Y_Uvt^;=&ctdH zB#$xlJo4mI-H-mzaWB!Ypg`Z*8XYmV^F&6ck^sKfn0|_Yd5sVtlVA_0(<5Nml#m4S zm_EHmgP<9uxt7Nx-f5T8`=K_`%aqkVJs-R1r%FL^bZ~rEQUUXasbJ(*`=cJCw%?i1 zmL=l7^RBxOO(ihOylyq2&uUh*%57SIn^n_KpBf)EB=&z1EV)1O>ds+GwV!3O*56@j z+%@O=&waj(NAhK=d549+5u9|{Q*)L#na@qBetEYPHw@HT<<>Y1)%`O3rKF5FrWu2kxjus6ETT2&q5iN)5|2ttyq`=D)h|d+ z_j%A;5#hHFIg2GD-u?=0!jR3OXg4r$GTHC?;hrjy=2(9HcBo-R9Bna%t_wx3AjCi@ zOGy|c;REr~hFaTFrA@W7>a|~4$db}@kk38jsiVVh3e|;VX}aRr=1@17JJy<0v?OF) zHae&^WMK~S;(qcHaq{>o;22xPLV|y9tJ``-55n){#!o3kOpG4@^2foo4`unDGRGdomY9}61 z9smVBX)MhlCHfm2{&_|@qozCUOj+GDTJ{VYFdKI3H{`D2N6T!L3|yRQW>+)IS)_Mk zzc)7W6))r|Lh0{Yh?Xs}6gE;H3?x}b2VPPE+MJB#gr2Y*d?cLH1$EC*{YRi4r{qPj zGH$3b?j!S#Rn-a9-f|42OQ_kJr@V|Q>MbJlf~5wc39E|9( zGJ0R<5c>HM%lSY#B!Z8%HJr?bKGS4R)dsVc5?U8)%nfPIiy#R42pzGJ?%EN{LN!iE zC5#s(fzURzt+UtPsp%2$gEmlG4$i)FZp_+<{>M-LbTZI{_mgph zPJcTCFEO6y&CO>G4d?X*f19i?KR?DbN?d+axUS>F`^*Quy~D%9gM)(u0|ULiy?Bbb zv$OMGNV&DO6(5E)Ha6lF<$nofT!s2|85ORK^ty!P`aRKQrR7!C?YWA?>gwtbA3ju6 zRFsvK{Yxn0ih}XRGOif7D6+bK2l`M{^!DxB{QUgWtgN%-{rTvR4CnhGw#l`*WDu;!Ig@lCsFIV~X z>(@R$KHlEmo}Qj~TG`pzIn>I^!NI}S*7m>C%ErdVcv@LsUmuSoKY8**S63JBB%i2j zoGMBkKa@Ha6TRl=UE>oty~)0cym`fR>{(E7#`Sac) zCY1D)XR6boD#Qw_a#)g$;|9ETSt;MOYzwhGi!lw}2>76szv!fsOOv5X(KOs=k3&uP*^lLjSq4)HY`2U=gR(qVWD&-;lZDcTYmRDKAVN}7Cu{j zr5ur7?5*xJ$>F6n()Cl8tJsv28P}+TWxVvO3*|XK+qck=P51{=exGTbxl4W@O91cU zS$p-vhkc1zY8n|3Jz$Jvb6RxXnKDcU9xsML9|8Ltf(|iVKp=nrYV! z?wTp$hR#P6$gUvCxAY1LT;SB?;nH^r95v^988c@d|VO z`k?R^r+Gl(8jsru>*5-_0!E??p+L$Ds;V93l0;KkcSYU1^LM-c`x~!1`FmXV{hcns zAt<)5djR3s*f+9fdg$kwIRKhP`HIf?d+&sh3H6b+ljkI@fuD6{I z{p5?;X8~y16Hq>2)-R2yo4Br8if3db0EKq={Usf80Tx1<4Hsp8U7ZJj%RYRjCQ>pd zm_XOBI~sgY5QeZt2-9`NT?@T+pz&#=Z`+S|X+blYiFM8sVE~_@BG%Ks-iJSh0OA9T zh^g5-@eOUt^PnDvnSuoCxe%y328tx4inXhG3(0TnB_{(#`KsK6mbfU>UX_IS`^Z6L zmI$E|F0oen(F8=4E4A8FcMYxw(+E1PLdK)ezx$mMT*=-Go`5wl8rnz*GE6wVf5=+$ zD04t0NRA&Cv~YDN(griYx71D$ENJmqNM#C@<4O{$0agON?cq-HjtIm=Aelv?_%ln? z-yFEDh8sRn&$!%LHFi@Nj2YKeENPPzhhOn19mI&?sVEk0bb#Rt2ENr zMnr%h_8!T6S-hyh^D5jG{$PFl8!3KlL8(xOuVdn}i08rJ8(FI^Z zDk5nJFN}-MYNeS-2PfeX&{n->dwu<_w>R8Ki|zylN03lupnA+CV4OYxnrg zY}99=IHIR2QSX*~P0h#|GBD`LV&12f1MLQ3o$z}q^4xvO2-K83r3804w;2f_8U`X4 zIs-p+powu^#Sji=+l1OO7JPd++@iCRP7olQsBtM`QDeO9Xs^C_@zb`=alp~f1x4<2 zc`LHre;XxH8l)R`i){_t4X2=r@o2Q5D@ScoWF#f{`V>)v?zgLbq*2H29@S&PwZ{q? z(gqz%^v7o%zMa&1-Tf17f~*^{RV6Q=W(X(NYh-k8*h1M!&EpPFB zoW;(9KoRbd(QkkI|oHz{icyo*%0 zL5s_SA3;xoq{%{AQ_c?UQyxf(WS@`Lc02oylNIos_6~muJL0D$54u5fll8bDByV|e z{RIglHsf|>KCRrwHNAmM)BotD1zZ3$hRvQpMOrq@K6$0zKFa217H zBplJ|4u!IhbjU+2EocJAB#pm3@_Nmfi!e9?Ne7IbykBA7LBktoUN9YY(Rrc&3D<5+ z_bDs6B?G0aocF${h8!=ki6Z(o9T7fnr2ICjC;v?Hp@<)dw{6pcx@CSo13mNUWL+>P!au5AqfI)BArPN9er6Hx^NxFA3Cf=x;Ke{d@Q*&Ed~9=>()PxT;qW^psp__ zfjcPp0YCuBkfZ4!SOlO?Po>ZHsY*=A@nGB^Jo{Ti{2NdQ&?G7_AT;GsguFjbV~E!o zj{rTrC?r&DDl$ODQX&Jf=B?5}1ayTzxh!~M^y`T!E&Vml1>%5#n{|h+dfx3yL#690 zW%?-jBZ2@7>=;AJzwSdNM_K^@FSrp|XbMm*$u~iSej#T);xS;Va`!|OWF`Pv2BdVD zz0YE)QzB=%0=o3$R!R`Dv`@mgO~>&*GZ8fw-|19ChOQ0FT?wsFZ-bqC-Z zI2?aOd~8YvMy46iv-|JE zFA?duCHSQvH;W+o$P(K69Z3BM?kf}vHj4#74Qte<_}qsdyZ{H?G-k(yfC1wkPrz|xL_n_!BlR*U3Bi)FLkjkOmlx{J`iEzBXtc&+EoE06vt#B%hGQdl_ktYk+2F=rXAV1YA4 zkR=ucZ$-VA#tmdzc$IiEmYqI%+X%i7nBLi-x|_AdwR3nU`=ZQC`0j~$bm;5H7#4eX$0k%K-Np zVVuFc+LvM<)ha&QRe%V%3SL*a*KzrWRL#9sXjiLDwtIgt26&-hcePD)YYeJR%In5* zuq0*Q7^@K^)#&BhOOp9#ydRclSmjVK%bK*bGq>Fzl`a>RR@7C8GjGP5inn9R37Nw8 zbqKsoKZyPy?eDK~+;k;wuJuwYBV#BH;jIkyuD;k}H9*14Q2``Du)~6Udf&pt-dbU) zvimk=95~Y2zl=FnF|4#`Xjsj&Fe>6>1ey5k2iJ>IRw?|?mN|Z@agU?!@>xB_Y|Vme z9nWvJW)xiNqAq^G?o$E9p8|4QQv|R@YeLHlYp&;Otbtd2yf5`hgprNO1t#OGq*HEg z^t+N+2lNw3Y9|PGMZYE*ladh3HGO^CuA*VGw?R*;?v-I3+LzS~1+y?kn2E!c{xsHP zA4jSM9L6S;MZht!2N)(ny%+-)IqA8{XLoENo zf4WeN?8n*iH5D0_ylehg&h(`}_Tz>SBn*H+gNYlsnjaYo61l=pT}W&Si2v*-5hj7N z@#~*GlJu_&B=T{~#w<@)^Gz-F*3#Jqm)MpmSx^`n%4CWFo01)C2kriTHdshKEQdJ9 zW9!Q#=Ou`5+NA5*ZDeFX@85>btfm9f_FBlcN$Qb^JQP%H30#SVJJ(=nn5hysAZfRNk{SJ`7<+2ANCn05pzl!bkPq{7mKbK9_tw%*d7+l89e4^N@0SK z==i3fNA7D3?GDxMlZ{*r4lTzSY|DO)Txx;|1^pcyy}Cb$Bg0N>Sg2GE9K;RWxEl6% z^|_IQctQ`STEf=x+siYLQ88i(rLmBzZ|o7Q!a0Zn?wFh8DF~e7x5Joke7Rloabutz zmU0rXpish^*mr1Dp_o7w@Xi;00(>Z-*h7 z%D{Amo6yU!qTzu^1pfNYON`x)`VUWmNrB;Sq6b5Q!I{5)458kSC`nKCs8_#_iaEHI z1QMbc*F~sq5=iaC#Zk~31wftjY`yU;9#U@1ooy1By#dTNU(I4z<{IW_YX#F$$d@ge?+~C_CJ(oJq^ic;{h5gbomj}JB^m3|9H}RVmVfQ6e%(;YBhD(^1V^_{0cdbS z?ys7;$v4vGM8?x&vc1dn)H;&yvgg;IC#`AV7M30Ga-pJTwIGFqG`X{;qru2`9)aof z-AQ4yeiRF}!`A!ofHjeZ)ra3#V;{YUZyWzmL$O~#YC}5tighCG`j_GE4X)V%A%h7FXB_Bd0cGj~-)(cHga}pz-eAIHSzk4aHiWly^XWhn23_S^(^$&k{u`&@X zwVd%&n`jb_Bx#*CtJ5xB=fnZR>xpr*RLfV(w5suG$0Pw&$Mi6OL7TYEW;7f3|+K z8@c=Y-NOS)xFdnqKK-5}*~tsYVw8QG>&gR z@w_6j)5fWvgza?Dz~NvoWJBi9*4OJF3phNaj0EU#mRKD@?f-<78?^~KqG$z7EG2~4 zl@eH(ULMm6bEqV7-c6<{3&-YxSj({Y#4zk?DWW#I^>($$*c@s9>*M{=POU=4cvi(M zy-nTsnz<2VlE*xqAyDy0($UoRidlwiUMCki_EXuD`(y@>1@rX!k?+P|i&71ATwcmx=vdp_jb6!&?YJa(| z;5>VJ=BgYf8+L@PS1ly_g@3jNHy^^difiOZ1(IvZE&+RNDMjoBx)c%klS1H=!T^f( zwUIVfw3|+3mo4v(2#-9YbC;0vx`WZn&aX^TL(wYP_1Tqm$t?xz=}~c&#A@NJ zxu;x8QnSPtECWH=N zi?`n=P^N@6&(&$mA6+pqqFFuhl-TlqR)(rn(G9Wlyk|aW^bM(>I3n#f|{v)wyGRl z8~3dVv`?u2++$!9^_@m+fia}ibE?mhaXbyaQ_f1lVFF{77?Tb zWZMwFDf_X{)_QW=>aE{ zZ6h-6CFHa0315p&JhzvAW>oXcW?rtg>eJTGH)A={QVrcLxkE(am{9bMm*!!4Cj80b z6*HRV(^hcPr?xrzkeM##2r84tV%7}u2bU-DnY=kMbzzY>}ZP8P#UrtfUl9DjbTZi3c3&6$zexq5r>%>J!ZM~Xp|q{ zxT{p#$wWv1D`QuS33@Y==yZq-$qF-NJ+^HJV)ZL|+z3tWrj)rIkT4&Z9I_NYQL*%v zgvBM~sWfqz80)_5E_oN>ibOZc4@d|&E@E26M*~>AldJ(I1dTC_`ZXY++||gF6| zq8I^fd0-BWju=`Np>5KBr$_yYZq^!ilSI|+VX?`nFfn0*Y$8Y8aa^LJGg-N609mbJFFZ@d=b`N4$jtl6vwF!WQr9_>%C9)wz@2H8Q z(!IhFc14z#CJZr?Xrqr}NdIS?>zw+DA*y16L54(ba>TE-&1-N$J2xzGL~89pSn`qa z*&hG^wG-K40MV)-KO7`@aL7Z;EjcOPmOYzjc>2lh;CBs2cI~uNWdlp|POsdjU@1#p zuAIYhiz-R6f#lfg4~loL6K0d94kK%xSe1(v@u9&~a%6f{(KH2|RUK-dmAhFc-BP4X zYNEx9l{L3KILl39?kGfS45=C}+%)?0bSS4sll#?)l-`jftTkeIXBw2#Ku}$UaV%0N z>PS(|CPdO_)~*J-a+w92{?NXfcaHE3U+xFhwgs|$aOW{XMFinprLAbv4NCYjR=jnw z)!FB$!i@25awnyoQ?pWB7t7cR*KrRyn3q}4=Hd5*BGfBWc_Tno#HZEX1LO)19SrV-q@vE^5Ukt^;u!TWJ}bvgSQA@w7Kc> z8*z(dPmfY>xyz3`NQrx=XFHgDMBPza&3m)n=M!-+j-75p=9y%m=16wrk)N$#tV9(1 zEkeC!jl>k$ndW?&qX;2KyQdXdLys7ab4bYNHLJy2oj-<}`^$+pXJ&m*7Q6AzPxA3uR&f?tWVA=Tycw>j|#BYl}5w_=N z_~wudz6t-lSDbzAQI~yttMB2L&fku1Eqc$$gn0(OytqF3RARp=!sa`D@*%5*+I!U@ z(q~5YGX0b>e3H81^^3iL(yYDt1JV0`7r}6!PvQ^wNp6R+yYV>^TC{FyOdq8&;(WgO zavbX69!x>2FRBQUWD`5`POWig#fH9XaeKa-o{6~B@4gRDJgZxlJ|CJS{5T(}w`u+4 z6u3OMw{Whp*}6^Ttgx8=?rz2n5c<$+Y4e`~gL!RznQdmq2<$6}~B%85nFNxD#jDFTT4=s)&p2!;R!sPB*%4(_0^WG%oe*+67=8~WkM0vni zhNxIQ6zW11mQxgD^kk|{<%L{2gE!EW+LUzDU8?mrDLqhJWZi}iQ93P{hk6RU$0V{X z3VkH3FE9d+XhaOiIDbWlyy^ zh$uon_3Oh=>)in&RtR%|3{?3-l!#9P9%;(~k7+Bcj=;IT}<+ z*Xu0pg4t9ky;n$zPYz)Z8|9r0W+SvYsIIg83 z^wWmfYlla0bEHoP2R0H&HUdQ2W3*Odbe>~3!pG=Sb!b}wn%ps_?lET1F-A=tmXk3y zfBdn*H+B|Xc1~S3#~=YxFpH?}O{+=`30(%qZ`|*6>2tsFrs^=9MW(&V3`d8`(1%E5 zM7VAQh3khZaEIc=v?IJS2EK1RDn1J_-yq5?$KJDl2&oCahYI&t3Z}TiBCKF-b4;oQ zp>m?*^8W!TD_V^!dEz1Eah23@)pz4+pT^a@$2ETF5!Qiau;Z#Hq46;}=-*7`#ToYLt0;u)jf!C%ySO4o{y zN4{BEO>pBaWzKK5R!`@(N!i{_FbQ;-xd3)gf*eks-u^V^;;19=>)Wqjm_3Rp3PWUA z@Pzpbq3`$;sc>v$P{ecK(K2BWGxwu2j)4(E?JWhhL<~(bfpF3kk!uY9=!1rfl_1ZJ zut14F(f7L}-U68iQ?ABB=quK>ry)A1+Z4e6NPccPZGrH3`Js&pS2s<5jLc z0_vv%wLv}yxCcFhpvEe}p9oR8EK?On8m4~t5^Q7b45!j}y54;x!XJ^l*MvVkFL+*B z;EIWK*N?bIKlIu^;q_&I*%f0d;nbE!S}jW#L6H)q=y`%Zz&IXvZJ{3oQssa3y;uTN z=^)e*Pv2?v{KE24+IAGjt7ebiQF0=X`0nT3R^70sIo^JwVnmP$cSQfmT<#o68L1rZ zv*vK!C)m4UsW=IQX0g%YRi9X@@hl;kGB@PTknt-^liJjWt5-v5@q;#lTI1a?+R#D^ z*LiVfA+4^t&68LYgCBF+(1>$)Q_ZTO_ELp zjXx~+rea3@HAV_)jN`PUjZ$P1f`T61@4x!A5bM&WU* z<*F!65{M_6*^(6;H%tjA#UL7==+7;MfQ`NmKCk1Pe@wHyHzgeEZyJXlfm<*CXjx*4 zo>VS1qp*$#=Zz9RoVyt@JvkeiNp2o1fqJFCIPvR6h>IC>uvzhbi1|K|pMg1UuGws= zf7!FrbT!31oV#PO3ML+GLb7W%thay@UHlppluX!rPssut@FKm{B4=(n(smA44|`S& z<=U8+3z&Tnuq=HY`?^IL1(A_8S&_0;Q^ z_M=}<0)9PzZ>5v)%YgM4SwY7uvHEDU9!7XLmz|FnEHNe(8q@0L+-qV2>B}HtUzqZmTjhn?Aey>+P3Y;#%=$w-U326 zge(XG%wB7U2&bnsTYdK8x%LPY00nMY?cA2^ z-3IT(7Vq&6>+;U(E9f0CP-@}U?1k_*8h+$Amdd8^17*kuZ0H1Ft$}2A6M(+jJ>IQf4$EIwuRsxYB10`s0wSI4fU@Q%uZ(&wE<;IA1fQ2+* z2n%3UzyR>0kkGj^aPIu+W9;sxQ1A#}>baIR62cdPNeuxOg zVH^N(9LSLz$^ih&!5q!u9D#6!ZkU4^ID@S%9a%XepehtwEruXS^MqUT6m0Xuesep2 za6E_gsIK!_uXUz2>jWx-KG*OfSBMPQD1$!kLQmeN@CQW~2o76G9;s0w4cS@PBlV8C~AzqC~!<{4)Sb3b>kmi3cw>UQVxb?@!pcItVrXN7Kq?#nIGlrWnL|31 z1t>`+2YHJn_XK}+l}GoKH+!XK`5aGo^$xYCmU$B%h?u75eE)2OWD01oc#Ci)SVH(& zs-;`XrCsW!pMiyczyX0cgMY~OWWxGo8VEssCPcC1uowFdcH*!w`Lw5Mv`_oBxA9vy z0t?6RnD6yJ2Y>-^>nH~C7C!W!KqqzLqjq|yc$%kyuqXd~(kFf@g?$(Z3-||;C8&%a zh!OPwu0NC~z{DAW(OBC z1mNMHhlUa-Qmkn4BF2mw4+`*A%*)1*B1e)eY4Rk>lqy%UY)SHA#Do1#Ff`H6zi(INYJu$x|-vi$RBO zExxs@@#IvID{sD(InyO}2#sM%)~w3962H(hmLa(I;1$E`#VdYrVK@KQvzKuYjx=`b zo~c==BA2^!vPvv;gAE@zidQPLM6l$ z;z0x=`PweUEV3k&QA#=GOB2c>i$AtpDGUEBp_tIyhrmHNB8w%uSf+7jqIukjO>IF) z9$7SX-Hl=%#GQ9M;`rc?Zv~0kGMq59$udzYN#$FM6tfGWjXL@$k_3{1fo#6*`5>8V zDyOEVRdL$sRG$WM1s;TOAr+n3U8>_G=k;met2q6s*E%~eq=Pz!P6#PZBM?(e3%m+D zEU~B&Xu$;s#o$S4VE%?=rl7Kkm9*1VTimBg>_LbaMxbh=s&?Y}ot}0!7^_RO+6B)K z4E+F)u16M|5+=nsGB3XQ>KhV)&TIkz2n;^J8J-N#yLP!F0@dA7Y(@WL=ArQ znMQ~~$R0{0F7@KTO+rsF3q(FU){?ix_30AI8@)tc6a&lv)N8-Jkh=o#M?U>@20$o< z>dkzCedq2J?z!(y^qE``g2(?ASt)*!b|D-?&le144W9E@0=>5!;18o1g&!DWHtsQG z0l+AR6c{MM393X%DL4ZG4w42P$PQYyTi@TP1wy2WaD?nDVGy#Ahp=enekRe*@qUrL z<%Q^fD;Xe8Y~T%eT;m$>=td0|NWn^sj)F!!BEP&x8%v?@JnC~_`)v0 ziHE+bz0EzzsNE;if1cxqJ#xjUx0yGM7f>OAi@{lOUIW`0)x`;@I@~DdrBJ6`E z)Lj$8|#h6-qA)065xSgq$4Pi2oqU! z003J$r7ZXup(jc)kbeIgq{5){rb9q2i`bc(0;oWbdAPtwVw?>bQ)0%JtiyE+VZ%B$ zDZ$mWCX~*k;OAn)L=O_@k0-PyAW;ZH=8%dIU@%T1NrDy!u!RzQ`lW1wiIQQmgcjRS zg8&4e25rnjnG6g^r9I3>nBQ22NP`cu%#}&hAPM8M}oSNa5d#!o4`=9 zJm^7%2&oe`rNwJTCqjyC zC?*A8YRDS+@rfOnA|F1ONLO>K+pda~flYdnVuNcl@3o_I3%Nl%#Ofec3i77#b1oI> zz=YoguQ_hjNCDU~Rnp$oHK#2}Ua?`3TPR~8)Of{20;Ar)^p<;yVw7;>TPy;dLqH2r z1Ui)4Am+Xjx`gy^Ea@P>Jk-y+o+U{m=y8l-ahIsE`7TNF3J-IHqZV^(2su2lkWyr0 zUxekJuYmt0-x2eQK%lUPD-w|iSHJ@l`la1K%L-tF&KRM5SfN;)b6t$IV1JizuxY!S z8VHX>Cp+)}k{!?xIs9P=ahS$9O39FX2x1|e$nQmL5C;nYKxXabUcK%`;xQviNr0Hf zI@U1_K%^$1t0e0PFRLjzugQvIz@m;1ED}cgq7OiR4UzQ{=#c1SuXdvd2-+cuhEUnc zSf+>xp5c#v(7=?d`11B%)(bLo+H*>rjhkf}<2cv&tfdB(A!$US9b1Gu@@RsPQ8Vbd z%vvKxMzRN#ToG%8l_444aEB{G3udsu9hHs)H!!We5U8z}oql$NKKx?7!Fijf#_YA% zG|T^5=J}Q+8G+*_QR|;p(JhYiS7~5 z{-oaV0Ka)~1P-JyP1ds6UX#L6q);*R!QqI6I7VDe z1OQ|_Tz364cvCA8TbKhM=CDN&0T7LP9^?<+z{fTOYmsF*)*Uk-04{Q&Z0$urZB4*A z+-IZnksa*K22c3U(G>I&QOpil$a@f2EfH{c>>y3Y<Ef<=*L*IXuOawytBrS~H<$Dfd(+c`E_jAWT&{6EeDM;=;!^c|C-M0(u z8G=-Q${dLfgrM-#j}roY0yIli1w1q?S%Eqq@GOeHag;y?LXbgt)%UhW^w^FpMEJeX z_tDw`+8XV>1vrp`aZ!ooQ4bMip88c_N)SjmDBnUPLO4uY`iLGBnVwCFV72HJ{bUo0 ztR4UqKrhfkF909YB_O%Upt;c?x-H;Oc!D+fgEe?U3OH5yA<-KF16^655sv=^f!sq= z9oId0pc8>$E0N%HNnxj~RgP8Gs#%{z9M6I^L;)(24O(0nR>b(N1P+wKH|&EmXkg_9 z;SmjhCpAh4WJ0jCKqgGo5tLl`v8;NCC%WLLRD=_xu4rFv9^c!#?=EPaU7}r_ zVH!3=B5;7Gb>bY6)JHT*EBpgBM$k2uP6Vb4&(WXHnWL#WB#C?l3keS3v6>gqgJ@BN zBtDcpZV}W)7!KluKU9M!pg@_qArdiDG#0}@_(L@wBsLxiuHjk-FhDE@hd54QEh>$j z;h8#CBrg)4$4taV`cy|6;71l&NV>!Wo}@p{5rPNyL>-_=*j0agxVp4ivUJ}|;GEhQl&u>vl z2<*ao*x^)W<;)OBB9wzEER`vcgC>Z=I`rXK?xkIrWg+e)(G33>xBVns62)~@O*{aB zMHJ;*-6cm_rUKgI5&b3gFoIMeN(Zb5KO&~v5XdvI*+KxqGXOv$^wm#*-hM%0>1k%e zsF0~V2T%f_L=b@&36)){<_t<_4N~U~vZfKaX7m^qF(B5I2*7$!o^39c_t-;I-T=IO z#?CQc!5OEFeP&iH!M5C)a>8d%`64}J0x(9W>_LbmmSOa0XY>Rnm8^#`jVE~?$v30| zL!^Q?000`8!+N6TNML4w!RP(iA64|7TbhV{B3(NUgLjrDg`TE$is6ZpVPE2e=K5Zb~H>N015NCg3DD-J4 zQw$wL-Oh(HCjcyfFSuXLG6V+}Dg$Yn%|VGQ{KKI!s)s2N8`Q!y z2gj)I~oI+=4pve>9UGyF{XwRGQ_WhUd)ONdQ0uv}XXxEs2m&jMC{+JB48<-)25`(S zz~IK#Yh8J)YiJ`kdLyec5ClBX+eHZ{{6jLeEWTjiqS{*`2yD%2Y(_BbL+Wgb2y0f< z=>qVAJ051Aa_l^oD%*wGX&BG@d<=Z0Vbvkgc^WVp({BBT~YC`Y%1YZROfUZZZUK z`X+Ef$OLN-6kJbTF3AD>L%v0Di7EduM%chV+}0cXLth-kILIGEH~_Bgz(3po9bA9{ zTrn1Bu@-MJ7k9B2fAJN603DbC5|ptSpD`Mzu^O*28@DkMFoATru^i7a9j7rIGeI5a zF%q<^9-HwU_c0qsffaax7h!?}fH4?fKoui0BR8@mU$G)v@gq+%C1-IYS8^rGK-{K; zc}i<~=FRlZEhu$TKrRV*f`brCFcDh>0Vu=D0DvIi14CGYDoBK0?Uf|ZfiCYdFZZ%9 z|1vNKvoH@cF&DEjA2Tv1vobF;Gt&Vglu8&hvor^DBzTc8_`x)1vo>!tH+Qo)OTs3j z#DX^HgGOiqi!vywUF^P>o;E0n_wEJPA7F#t62?xL%&8Y#rKh^6*jfu%{_ zF@huV!qs#v48O34lr&DDshYBB$tD&+9xsHv!atM)P1p1)ON0Qpf;lv$2W0R; zIJoaLz%N^SEk=NCS`GhobL?I4CdXwp0VZJNE_4B>>h)8Xc2vK{t>&t4@+!XymtjdI zl4!#}sGVUurAh47de~R(t^+*i!VgY%@|LBf(qdfaAO7YdT|=Z4v>-iD0u=CK(e5?n z2C!cILAZ`90F{TmPjD`q4{DTIIw~L-fd4J$rPwIJB#at6LITpbrIN~sT0cg&* zvfj4~oA$Z-HA}!Of8Sf)hDZ*BSTPjCh(5@Au(pB!H>d%%;R-bguQyz7c4h;Z7knx` z?1B`;C5Drzh9m!PeJiAguS7UxZKZAPc5}CrgvfgEbc?q(dBgb4HaKxBhyL*&azl7l zNcjH5!zB2me2?~q+pBalZ))`I-v;jBF8KrnIE1W6lym8nx3z*>`8YaawnjCzh9rSe*aEoVz(j+4&PL_?08BTsw`s-na;MK_-M2 zm>)q>47x^AHjoeb^MrFsd~f(3xO^SzgRpbePWm|`IF-*Yp6g_C*f@=`Gm!Pf%!9zfKS-#p-+G;+x6*xy%ztvtgyNs0yZ68E893oHvB^}RJ*kYM}l8Ew`Zntm~e)o&=D|#j?2{|h`Caj zI#FVKx~sYXxjRC_J01P2gXF_MR2jav^tG#dNND?BL@2`UTUh)ENW`9V9z}1{G?v=g*-*xDd*d<>=8SlYY^Y`fLA^ zl%_YIREfY+fy$O&0d!pnmaA8?3s3Iwu-3ssTB`s=W2I0Lzj5V~_4xWW?%af$(i!Za zjuZn6thgaC_$HhOMeGie^K`IOHiZt>dN@h)Y-i6c3jixtrT!QDMLdlrac)b=CNj@{{){=|xLKEXo9rOXNU%zfK3^IY7HUN0+pnL>5h!b=a zB1OFLWaCc4vnna3k_itA55o;P>=3uuCaldY4-e99x)X024#gFD@@c3g>>&SS4Cz?> zA`^L}GKLZ>TtuLQp{l6T)n*%}9(>qbCM}07C`-!AH(L`Ro(6kwQeNND@tCaYYpk zoeoi*j2MHEJ(gIph(&ynik@E@X`)4=PWP0~*4` zmXcCkm7i8$1)zgzoI%eZNzfs{AO_$G1ORqy?MGEf0FaC_%R&Ow&uJ4Pz?WjYz)+fh zW~J8KZ{q|}LJ@-`6sAN`Tom2j)Wr!5rLI8nh(@BKXP#Xap{d>8JO%%WR1W{$FkrGw zZKwku5ca{ET6}2efNtOd>EMJHZrB5AqPYN}PR~#0#R3p03}I z2A(i$3Ab*k;EJrI1r>uviGzkSY_W$2vg*4yn;KGx8&)0ed1Z$lYGFr(gwO2MqaCELDY7z}Sqxfb9DL4M=8UuIbK}AAWHA2-4r$m~=NUEVg6yC_ zyuoK1IVQ54at;OP1zQPU`A41Y$uFNH?PtSWPR%_(%JueBtokM;$apkT;7mu|m`R|} z>3yMK*Ad&jW`M3KU`KFgzLua*f!T2c%_Ibmf8?iu6|^8i80Z@H#fg3J3(EgII1|vl z3lH()*Xg7(j7ex}Cm;k$06B6%*2r)*G}K4}FW8X`=5RGFSX>CQlY;QA52#g3ujt$S{GlCwQXeAE%n;LaKRBjHr=~uX)2iprucN_Uv%! zyXN|`+0FR1QlT|z*A@tI2&N3h3%rP$Re-ZgoVfEM^Yj;}00z>t6!V_>94JLHxr^5b z;2r-+!%1P<8j}+2pd3tSL-obZZmO#|#~F$gFoFN0d1Rssiqh%pv=UD_c@%3RrKvq( zI@6dgBm~4LMhjd6hw#8^s$K1jRKKD`Jl+(iGSR5#76l_286hZyM4d0DcA~S|grgQ= zYV4eXblR&Gd#u4_9LpjT}_u*R#xiPp;aRxIhC^u zsh|^!>GCW9llrMUhIF|CGi^yoI!)VlH3PyZh6`8|K0VQvyXUhcZXC-Y$Tn26LsOB` zsHhV{9>ZRlU|pihOP%C?w7GYB?rcbFkm&zPbGlu8NX{#+nADx zyxo+8y=jyy+#!%V`9i&Z@dfi9Hz=T`NPfF`UjmBQBl}Hef2Zn&V)#N>r2z#r4;CsG-n=|P$&E_Z5{f`^V6OIai~K% zYJrAkG@ki`hFHyNWm^Q%6H>G`Y0V-e_#sAPU~5gNU{QJm!_s|Zv`*se5D+u6*p6&> zMUV~3Y3s8>HG`zGA{K2z&s&nP7O$)$dv5qK0hV^SA59v;UU^WWxWE?pMl)U7P0#M# zWI1+}qw4BtA7OFA{)#EWg8_Z7n%@(twuG*|%51ObT}!En6egWvl|LLS5szWTfr)cr z>YSJu*R#f1-M#OD0SRWd(Rh)%`xj1>dE<|j5yT!mbWS918(|m7Qs<=z=BVTFo}53!x)Unyzu#j zdSAL;$%Rj%&&kevLZ>uaC4ucfWUG5F%l`HLzA?bbt9ceBWhp(0!lZri-r%n&@C;e^ z^jY7Uiz8m24iJR%XG4FSim1UrN2vcu{0sP3-f3Pz_0l5hEp zq1-YM0^3RYJ~032j0o+_2=UCXV35mZCIA`7Bh(-~bif67ub>W%0jx+fCCl613L-?B~ApD&;55L23acG7af1e% z$OeZZDI|&!*sBN0u-3@X3=;wk?FtgRjtx_b5@iek1F#sTU?WoHA5_f~6A%~qY7fQi z5KS>CB#;t>>=*yKAQ?026%}z79nsimG4*Uw%82p6gf0Nl?jnTfAD}@PKT!{_Q6osP z(SXo%M28USK-@AxQ=oC3))A>ZE(DkA9EUI)GY%AyE|UU~7zWTH5MUkNi0#PHz!dNx zL~%CK(cJ2BXz1rrZb=>{A;OSR8t-up^RXJ;%_HGW68mo(4~zn=D*yxRA_5^i^dcc+ zY#}4j7-J3i(k~*{C7cSOIeIXsY_bM5GVF*1BrT2>VULnv5|k<=0D)m68A1ob1AAQZ zB}o#xun^_6Fzb5KP#~%haKssVD=XEJ{-!asgfi#Ka_7#n=SEPvrqaNCXcxbrB6c7= zIw2~D(I5Ypt}2`EDrXKXQABC#g%|qgD>KqBd1)*^Odl7~`touu`Kv7rOt1oQ7c!9{ z=2FY-@-EFWEnDIt9nLV5Lv)~q9xwp|39}D_4Jb!NF{zOse-1B^t_yat7@)u*R6tqY zA#yTPAtAHG^l}FI^66SJC|(I_EOL*A^H6@0@H&z)#jXv>kpNH-g1qcB`k@nd^T3X> zAz#BYFD*HBq6q4My^g^LcMCO_bJ&`5J)iRyVe=n%v6&X)0?r{kY9KqM@;yI;J6*#& z(F#0s!Vq{cu81V6R2H=#@>|BWUe z(1ZUV0Y`?x&9(_ajSNL;0u~WM7Rk~%Ny#x!j6=ICDF@=z5Mmj^0}eDaKR1)X3KM=N zf$ydul~i?*5HaPniBcp<5JE>zjV99|9v~LN133PPos_5yitPwAr3tCQ!gh}`*Tzwa%heK6Q*M7j%HQ0tx^B+ z5l$nuS!1*!UTn({;t#sv9<%`}&8Je6sR@gr9>N29deu*VRPKTlU78>hq=FX&36Ydl zIa`%Y)r~b@^ii!zM$;f1vVmF+Vh#A=6L!E92uFdq)tIWP81&&E^x+4_)mOm_SX;wC z-wZsPK)B|i5X9ie-1S@&Q9-fMUYW~56M_T20S>GLAynodsKI5nRZ0yE84|W02%=%h zwM#wp{6KUI4W(l3r4S5`a~3rkpdY11S@ z?3PW+r(h{b1q|{Z;NVgN5W4_(wgi`6b3<4^b43uh5C{R+g!XKc!&MCeR_AqcKejy= zqE=YNRk+F^oW&rbwq^6S%hbRh!XpO&U;!pn1ydKWR+o3t(RII5OnLTV*NRaYx3e5q zNgEVo0d)i?24N~DAyU>LS_W^0(T!Tgc@4r_g#n1BmwKlb)Vg*xzIMZo^a#{d9sr39 z4$f@RGko84eA~7$Eh22j#%};ea0V86@lXLa@gK|~LPj7C*XVxnH+lcPW`9+qf00!4 ziojUs!4kv?3)0kfPmgH#k$mlIa*<7Uc*h{9$9lB&bMqIb2ml?zBNv7@uy(N*TFisB z5rj``aI>&*`*J!CHH8TQ4^q{8U09LQ*8W&GR%IA0CN+*gmxnq)JR)x)pkOw;0EykR zTrcm6kAh6;L4_4JIp%S3#S(@Wvx}XKhH3RNl~}PHfN%c+97a$8t|b8fR*heijepOL zg#wN(!8m9ad>uIm@whehnA7+eN|UXJ?`aM4Av`F^AplYU6?u_uc8e#1gm;YQ8bQb` zq1!mCg%9|SA2(z(`LsA$-aI*(9zaLKgI6gc0;2bnAJikHmf0XcfgR{z2$CTj5VHK3*eab^I1Td)*lQOo%lKHelA8i|!$OtScAU!>I-^Yi zs6jjwAtT;W4&`}HO9Gz_LIBR8j6L8Uj0Nr_x*@E&p_{@Bn!^{uiHfh;q3!XOoy&S- z*mwIe+5jy)tN~>-!V+7nGC!J^&lvzj8USeEAIjh$q=8>0m6|`JrI!^fso<7=At~k< zUTylbvbY0RTC8uN&leB!LdNySu&nyTLoW#e2NTyS&Z& zywN+o)!Pp$){P06;)t9p>N%{yCthdZ72Rpu-figp3j#rEI~rmVG3w&v2|8y{s|$tdH5i zhCn=GK{3Fhql+Of;T(+^%Xl7ycbfSe?!g&wV449PI0c(L7my5*|4gumCD(KgJR zl%i)?WaqiNXuul6;~S*8GbFPZD6`YcsCxf_RMC|KYJLHtx?0x1yu%nh79E}1AzjSN zJc((G0n|+b}mHj4~Ahf?gl3(}SZ+F^TwA$nS+HakK`D9uFpafjO z8|;A`TtPO{;2D~y8J-#d+#ngw0UofStpUJVv2};>Nyy3PZ^9!SR$~ATnL5WkhswQ; z-JK?iKwZnT+rACUKOT#1or}p_ob6ps@^xPUzz1?+4r<^Hz9AP3f&`e6?G^ zK{5Z(;2-$(2mZkZ6k-`Uc zom)dfMT5z+zJj)%56d3Lof)#Fc1UN z5keYNfq0+xcoCw);iRihfvs^P1Z1;*7hmfGpPo|vOIMv#YoZI9gBK1xQOVxHz}Zn( z9&&YkLgZF+?_-qrqd)#bApij%TC#2d;BFJbK^`QzD~JumgBHMFBLqN=6hHTQxcoPw z%Dwi=C)V`RecbdwDPlc)qaDdoes^)5$(o-#03rsuApihGV^y%Ahic0d6tqx{RvIyL!n!sS;tSf~r>q6E2)|uvNquQLhnTcK|?#Y0e%b zl!T5zK?d*wC2aFf6Gn2L5|+yL@~KM5vcwmmGUj9d=@L zZZZ@EhcxW0^Nbn=%@XQA(IoVTH~4HL2TXnLiI@P--~^8jOo9kZ2DlDOY_S;KYTTc0 z3L5En))m1EJ;VPfy2ldD(lzO|kNWsxrHO5NVUiw-i&&?|@`miWM=3BzZlj3CWSzx0 zqHewRdYCS8$}-8Uw$oXMojiLGVh0xf%9ZWG2y=TLU_>%Wu7wd_W$wL&n74?c1VO3jZtPA~o_t2p(6gycfeX&y{dr-Xb;edp)!FGgB3l%x8r} z%Vfbaxy6C2y!0Lob<{+e%p1xk_IvZfNKA3)FNNfhMb={FEVfr<=e6^?;7YtUeL*iZ zwA51@E%!=s_=8h7I}HnR-G2XlEZxUhT_VuI&FlLX!zq_omB}v@-)tc?6cdfyV<-`>aeAN zvOT=pZAaDl>TC*LH%d5B1A@AJD^GpKtt-jg@$bdnyIGOEoa2t&oArD5lh0LoQJWLD z{&4LVm3;LhU2pLTtK{Z~y{FGBfB)*zU#{#Gk3QV%T@->LtwM~!2;<|*`Lg!FvZRkF z@8eAcYjeS##Ls{IVcyXMz=_;+B4g9zpb7H?z{0#PP%3MnSJrZjLXe?RE{q_}Y&ez) z4kd$-;UQyuIFk+fFNMZpK{#--k1=Izf2lj66HP=!a4v42r)+9-0P3kHy^gioxah1w{zDe|j|4eY`(=<$n!b1YI+^`}uPy^P8Y6;BYcrq!Vw2&yv7O+C_;fq#WrM8^u zl~&H=mERg5&}0d>f6$VX!z@t@5`hzL%s_6L45m5J(xm9CfKiF{%b(S~!^=&Jgpkkpp!qyNm(}t7z-#K7ra#uxieqoC9br zoyydr_~uS&ZRMhFq0gUn%F+kN$M9RWmC$)9KdYB=whx zZS4FIdorlPj;=S$!Y|lDh4B1UY+5DMX63@s_K=l*qjg_t;b+)Q!qu@dS*s>l3)|Jo zM6T>P=E1U1h%7e3cYAGMXJN$C^!W5dLZ#qoU%JheY$6-(a0fMNH4;UH>K^~BgDh-m z^An|B*RisV32mQaTWwvz4u9Om?s_}E-@Yig4O9OX#HevfwI z5(9w1N?vM`S(4)8tawmMaPgsfAwJ$p7`^73uwMdexgGyd%!twOKXzae4>({YKX?Z} z*a2OPtRWF)XoE7^F<%^&?6aiaSHvSC5Rzr@u0^f5a;Nf zLRw*x7VL#7?Yc9kdCe|y1}t8Ji`@{7)gq>&s?Ta_>@|mq3qF_h;QByCJXV7;ihFcYSCQ~RJ1_`KR|^)-~a$xprRn7hyxAIU<-SInq>Dbu(Rv^#F7KR z)x?4Iclu3;Jbb|z^q@q|a-CI!KU3$?47YI|ZozUdQs^j7?MVM(Ar5?`!xS9G0@@rc-ovhpn1PLO$uNqMp)j7 zDrfm{T&|bD6XFnCIKpK!p|!L(bMZk4?Mre@MxwVj?hrpA-39!G5Vd{tk*qw$z7Em8 z|ELInCw&mGbBxRyp7k1K{#MtH7uUl__7<*m46dFu{B=7QubI$2(cTpR4d; zMEudm#gDeene#mh{jwok+}9s-{mV>!L1&-y+Yi4>au5Fu5a53$)qi=kckI+G>E}2> zunU01ZOa#bob`Ud#d^{gYWe4O))!f|XF|6pU<=?2-#36oRe;%afH8G`Lv4Zz>D42j3 zhX)=~C@D6$dkF_@nv#RwwSTr(f<{;n5daLu;00g^I7oPcQI&$!k$%R<6_h{^#vlbz zNP~zMfe>Vcvxg~LXl^@*Zyd-$9#~+GPz<|JAZ7?+U-(aHI9Y4h7oz8eLGVuW5MwcT zhZI(aQ<#U-h9q22o|q+9Ra5oR7f4v$TGSpM!e`s zzUX+ss6t)Xfy4-gBT$M*kc?NSB1s5dOE?$M*cDXpN4GYOxLA$!c#S+_fh+-gy~vD> zwZKE%1>evy9X>9xxY)ToEuZ*drCWb1-==^Y@Dysf8QpgC#i>mrx9qpp$y$k;9RY zys?mD2a8<6el~ZHGiHx3iI3ViP27ls-uVA}97%vd`I9Ws1VAwYS!pjP$#>r&Yk~I_ zvIvp&D3gkpmXSh}-Ds2J@{iych~kKdn9!46SubFTfYULScn~&UfgSN6aA>J|e6^OX z2bK9GmHbGRQe>4Rh?RJW5mf*bj3t@4qL(Phmx$( zk9vqbj~S43X@&xTI+s~2nW=_-QDua12Y=}mP=G+a@PJFHc7+KZr#TX-8I`NaiLIHF zvMdEg+I4S)?U$q`@Z_S%4#41QtiofX6VHQ;MT;+ATZ!dI6f8S(;5; z>N)AjXFTbXV@e`rYJO#bri4HS))E$&U_1Irffx#ZRLXX&370*}gBuy7fSM4LDGVWl zsVL&5*k_$AN)}s?2ZS&NhIij745wa^uI=nDfNtJ{Ni51C-2tZJ^l zC7zY~qwFf8hee_(`Ur(Muk^~RLFB7a7Ez){2)QE`lTcLvtCp=Qe+7$$ZyBqU`iGaQ ztK?V=LGZA}QLn$cU@Cc(fSE-c+pz;1p354d%__3rsHbNbv1aI}D@z=1pbx> zG20bQps4gPt}*Gc5{Un^KB}__`-vv2t3|+-LMt3ZOK2^0Xfd;$ULgggWT6)6r~*5j z;Fhj#X|*Fus|qW$ztKco%NSn!YATbRof#Hia47LmiBM~^{fVxyN<7Z`Pd)oLe5z{D zX}7e2w=Jg?^QoO-aRif4Bg5d56dAR6IJE{_wdC2Za=WtYNrsPGGC#|Op$c|ODxqQF z1!l_&-pRRx`)HpVvTu91Kf6JUJ3~Kpa?tw3+u2qP&To}p}vO7zEm&?G#7`B z@Vva%loA=eUzWd&xxd$Ry(^c!9ci~u02Gh#2#a8?1e_F3RSm9C5CmWjpm4sj3KK6- zs$>9RK_CTS~|i7N*ti@4+v2LuHX&!Kn|{OOKI>7 zr_u~%kPt&44fjwEHViA>a1YuLXDz|Fr$zx%un1#_2`cOYF8sm=$^iV(2MIw7$#BCX z%o8wB2!&7wkuV9E@C#LyMZYi!5oyF5T#FsNi%Wc`O&nDH%Oq(K4%vVZK9CD@Py=u9 z4Y^Pd9H9RWvXBEkkPGMF5FT(2wa^2B01v7G0BgVxpRfa_pe7Wuy(#JfD$J9>pu*s1 z$46mQD)0|$kPxa+4I@z!Cb0wma07I30SaKv*Nn~Ctj*iZ&E3q+LIA&6B+m2@44AM8 zQGm|rtj_Dq&h6~Z@4U`tKnG?3&-HB2_YBYSOwaht&;6Xw^X$*?Yz0=J0p4uT*?a-i ze9#Nc&<$3LfB*o12LBKP1@Qy_U;_ZK z3F{z70FVmZP!JE25Y#Xs%hSsYN&t(X!lif#D%_RDTolKg%*))&7y&1tA_;WB)J^Tw zPYwUoQ7zR|P1S~QS@UoV!vGAsa0!S&)n5(PVJ+5UP1a>?)@O~@X|2|4&DL%0)^82h za4iWMT^zLVZXb;invf0!(E;i}3JhQYtiTN;-Ny;>2LCW7tl=84;mm1<5;@JFPoToT z(F-apuR`qjz9sJo!R>>6EQr)HT=hJ;-LTv$oi|h){D3qhRG~ZU-y+?N0tz_ zjLW)wNk}0O1YvC5WmwbU-#7m6fCW9eQ(8b;1cV_V-3Umxv><|%$jH$t(jl#MNF&V% zX%M7Kx+J7ze}32R{@=&-;Qk!jvpw6f?bvy~KkpYDmH@{ehZB>KkZF@pftJB6%aVv? zTr7a4nl$I%tk*o4$C0cR+^aP@R5RO?Ta{``aClJdkagkkKyY6)U|IWwyS$6Oz>25j&lbSk_qSuE ziuGZg)x+*6lw^4qKJnCQz;UH(pg6(m9={K%dGVI?$qxUXd&8dN1?i(~cq|d%*6s|8 zLuqv!8T{c{(F`eTg->US#1(OhJLV;?bhn*wmwlc96-@A^5E|AzK9F1pgITuPfm+?O@ zBv7Z3dyh@cUl-puQ)_|8pInB-#aEl1e)g-%W@^rPbZs!-@~izgN((17=PErX_SI2O zjHc`B%DC{j^tun3-JMm$50vLz3|R?XKB-Or-GUs61}ssC`>kaOGg{T5fyrx4Tl zh3U5I=x=%7{oVe}``KHt`?iMptqSJyPV%3Z)NNnRKe>i~z}P=$%s;KsmIBE;h}qrB zhr7GfyS+HfrI_a4(f6B^*JsnjZ~zC(;zSd|0LG@^|1YGBPr)2*IKHM3Mn-0}FNguHENeC zq-rue|CpX&^#Y|=O*GX^f%sW&;WTn)bitxi>o8qmJ3mwYvd-{-peG1^tIzr2=KRki z^A2y@SwfT9W6Sp7BUZbG#>#t0`GH)D$(4ZZP#VT+X5rD8CA%V7 zMYXU|WN_$n2b;=p9-4emjdv0UPrYGQq((_JBSd(Fd#m7-^YKZYF8XPN{7ApF`z;w7 z(KdLhA+IWtJSKZ&k~}UC^%a>2qi60#Ht_b=@u@HFCQqt9C8U^ApSw=h!RR3+M8{u{ zxJ*xLKX@@fU2z1c+EHzMSrOrX)ej5y13rPR8f&y&_qBZEorQZxiFc9ot}qJG){uu0fc3EEK4Hp7N|5*X33g3 z6T}7;{Ziexk?V_jdbtYDeV#7zCa};GDdHd(CY;Q&1%xJc`n>||0$+V(kXYr6&1;34 zc>}08|KD;FNnG(6hhZnaomTKNb}k@eh(LN{VO}#z28v~BL!K0@lVepg-JSKzTA6?n{C z8au^=ca)HoV7$o`D_=BO#}jFmPCp#0hiF~2y-N4foLQ1M-=0nxUuHN~fm|3KO_z)p zXS}-nIw2-Ehv%Ch+*rVxE0SD^5j2KYOw>*!DBU@7lV~fTh)2yC9*_$p9k_ksl;u{*6DLb= z)7upJs*FZ9V$ouq6d|7Zl<7JXKP14cg!co8D4V)o2<8}MY+sEBbZFoAFo5|dkTJ^X z?Br`5vg>0ksHeWs5R63zqJTuPG*_3|?N~7%PLmWWR!2Y#4itQZ8~A3}iiO%xLELd5 z*rTU|Ftg5{o?<-qPH-v@F1mxzX`V=F#)tn^l7BpmjFMaPV9wx`CH0ih$u^oO=6L~A zHN^}3zxA`#EQNR>rB5ihmHl|)bFfyh7ILuxY6CoH0viZM92?-j7Ri*TFVlYNVD$5s zehgMFWm5^aS&VJ47uy*(Pwo&xPn+-?96|HeM3uP?^b}dN$@o{imqx@gPQD}*C_V0% zz9qq{7jPxSaHU}oZthXCzdV?U8^ai7ekF~kT-0G{cZj=bV?oZo(qOOlNZyUds7f%? zkMS?g=&}_A2tj7u8>T ze`XpwDEQrDq85;s0R6vh#m7XYW*5zW+nRe1{Tt>@4Yw2BtF|kQFf33&>K*e$p{rI| z%X}quW4pC(l{2^|>^-w~*Lc=pxef_KF$oTRa}S>N&lN*-#U{lXTGPlXFqQ?zR%W9~MS&5++9lkW;FBjPkcZ+V~8a-qqlA6WDHtt}!V|$;wY%-ea5SA*`)MY2Ew;ji5g%=oUyV8+bfxSzzi(!+#- zjm+&w!A4WA=T*cLf|1B*?;l?(rg7gMJ6T|wQ+O^Re6DpAzQ2Ua9NZP2*ma~xJEt+- z-nR-~<{>JhgL^Xs!i@$yBaqQppOjO$6rgVm%HTSnW^@>C(L&PeaK8mokt}MOF2EZ> zPWLa>>%PCF67cD%Zz+hFC^|GpqI?Q;SJpfd^DRk-}bb1q&PruG+=rdGG=yCDc8ns1v zS!H-kXl&v4@PZ?sW|9>!NR@MT+zBKuJH&RH`kZ4|4YmbU;V~5}Fl10GakZ0ZBhOCa z^zjOke7;7xq#iCx(fG}cw#U<5rm+wODvmk2d4^YZzGc4ot+mS!uN7uHQqqGh2hX4l zv2t;Ib2guAAWw4W?^8YfElX5u-oV>6dNa8WNoFG-q)9ec`c~^RO5#9rlSL?IyQj9A z`<;3nwry{R?qw4Px2RVd+jBj08TA>}1!JcnlRWXAnG4$H+5E3rwm`#d( z`|dMct<`V)jlBP-yE(SF(DwUj@N#PxQYd+qDVs~q0Z|?M(lrH(nP=>}{W)u`C;h5J)Ob*aDEBEtQ-!i{D>h1&CH zcZPMc;Axrk81eM#swp6~kT0Bj4U&@$4WXW6p>kNj*CuE&U8FI2uZf6)o}PmKTLnWL zKs-LI&L`|CIm*W5xt*H437dlbhJt8aaobMD_q1N4+deJ&-Z8rV=k%~X7Vs7v>RCsx zIjs18K`~%o@x!fRAb}E+UMYxIDOgG=L`^BwL@CT!DcoP_Kag^!Qe>G@RI5_-uu{x| zQtZA`+^tePfpP-9aw4yCl9cj&W$8zg0drj56o2Lafs{AkI;gKmC8SQ8a@K-!_P+Ax z66G8Ml|1^vEVe)`txwLE!APLqFEC6VQ7f|o@rQ@k>%t^VVsi&F)Nybes-R9CNRg_r zcZOj^Qz5R*J(&+w>P=L?@hWLEKcdwN@iWY)K|^1lk%%!GgS~L=4v@ljOK26KnJ&FM zF}NNX%#aIl3WSJ>2fy|PBjGq6$H6qm!TL_B!^3JnGKJdx1d%APuqxPv8l{_CYUBp# zUxS1JDn6O1>d81rSjY#Ilos`4w?M97{FWaJ>P!3Tt~+t>U?cC)Q1k@&rJ+iCGen0P zCV_?)VgobuqCan;zH@9%x*?tbK!CY~dc#Nj5YS};%@cafSK8R3HK4OPL?3#Gr+>`H_g3Crl~SnHr`mpgv_&tZ9VO zqW&>crs;tV+)imC1)wGmwTS;|!PP(Nir3JJ2W!B}oAto-K*$?(g7AteeIu(3Jxta+ zTu1<+I~>|5_%Uks7pVA zbPF`Ox1rI4I}6&^JKFc8vylnZ;W+q#x~{0{Po98z7PoayA0C?GNqw>dU6br_h%{p%Z8Q*NOAsw!ZG)A_n*Q1`}gne|2%L0-QL|^ zV{XoFZ*OmIZmw@{?ymn{Utj;by!v->fjK+F{N1@b*}S^FzP$N+FGt_A(dSq9aP;4^ zzc>G-qAyP`&(6>Oi$woDxx9Cx&yOyS|C}5j9UmPXZJ+MXAN{&GI6B`x`VSSovxC_k z!EBBmZ>`*e(VO>T^!n!d!TG%zeZI1JG`sR|q2zY5eBoeq?%?O_-p~1i$(8lx`&nJC z_<1lhy+1v@KQ+BKIk`76u{|-lu`;srV|Z(5WOb!yz31MTURYT8FEBkj`*UfgduC>4 zVWM+tac*pJbaJtLYI}yuZ*UXafLYtmKWK&^UU1338R$*IOLt8?{_prooA#DW( z1-bW=lbfBLU7T5XFGuGmeJ+X5D2UHbO-)TsPL7X@kBW*44-dabqJxpa_eiu++E=;I zdhdYX#{rG!@4PQvtnLgow+vo(dq$SMsh=>lEVeER@cR(#5q+;ndwO~W+lQy?7W`F` zyOR?8%g=ko_Fz*|dPYHWgZELYW`3&1{o`|(LcH7mNYhSEPWQ&NrKP2wwY`~{nTd(X zJut1St9wsNYieq$si`R|E6XdYC@3h%%F4>f$Vf^`N<5Yn6B82<5_dZ8OZSV(KuzJ$CjslhOy%059~t5vy9)zJ9Qf3T(Ocok+LG~n zr6eBH!Mf7PVy%3YtX~t<;vl_R$Hl?=uLc?TeP_9{-^%7{?I*vO4&5L8HMp%0W~nw* zEVg)`?k*1f$Ah>qWhK7G$;(2Zml$!t={tOVE%vG&`cVwjVJ5qq=)7sx8%>HZ>$9Lm4chj_hxII zmPguJ{vNF;Phd*s)|qHDq=Dsgq*)q`_Qs$Y`K zSwgkRe!Ru|crO-yRrs$By&6hwSF#$G_QK$q`t(&t81|DV0#*^6Yc{MAJVoAUp3!l@+O4;Cx*+-VC#|1U!kvu8rO2eH72(hpWJ!S zVp82ExaVPY1R^m$Z4HY7PO;xsGS&}mw`LRhua7!fXiwCN`fXwa0qTyf_OA^@2;46Z z&aO8AJu|=GvsaRwR4RKc^6xr%lF0Gbhl$rd7cG9v zl9%g$k1&dx^XMy+8iKhHR!;yeFEw!-<0~GFovNiM6^pFHU--;$hK6VpJ;Qs4en9ih zZD|juE8KNjQ74+^}Uu#fwoICRU)ty7|;Emk#&G>NC?J|p?PAd+@pBhfFuCUm?g0D!t(Hf2$NuJbS^l7)C+p?e^<+W z{{&MGnfL{~qIkSBv`)3GA{zf}Wtw1RFlUkHWP2yNI2iv2xcr{lch1T?8CJ zY-x!d|7mWdFxM7`T^lp&NgiCCl_Q~8nY&LeV+6Ycc2gC{DYBZc9tZ*ugIGXGQdTv+ z0gcA}zhPe4{IT36e9tRI>X9n;a_WA50MN1`O3IDU;d&NsB$}sU6Ud(zrpz-q5QSIp zz9Kk_>`pr@wC)XaRkWildB?ri4A6|n?>vQajK!Tzm37NIy%Z)5bc@cXkW&Au=!>T( zO7pSA`~9qG&hH|!A5-jTbQrN=E+opTE~5$?5T5D`XOF%IgankB_VaK#GlOD`*yXr; z#;~PVun7UKP>IhSI5>nGl{V$v>ZeVl^wHMz{HQ%6$!7*j7+E!CpC9F{@2M-=6Jhnd z?$5+_PvWq}&Z~?zcetk#;=H7=@uA$kk{i|0#yvuK6K?%a+ez?{RX{ezes%vk)oA9I zUObD^L)Ap~lm{oGc&spNA0 zZvI*#HSN>|SI4r;9NkI$2}79bN71?(lj&K(P=uy3lLX;FXN^u=j6;})t-dV&WFcER z3cc~OTyYfdWF&HbE`4i8ugL~#8QVd44_hKw63LQ`)aybU9KuS(0=JQnrs&ByBf1WJO> zBk%fZt8m}gWUl_28RJOIr4n*9Q@#4xLL^o_gufN%pGURsrXVX+{^~*TB}c&}^pCz< z^y^t`hW^WV#7H2aPu)7DH7Sg;!ac5nG=zAmQSmYBP5CRun-zWGOT{lgNQ;PE2Iq*j zYw8ydV%3=8Yt&HcKEl07v=OJZ7W8raJMgO#Bcx-HM8k`SpMqF~gcV21PDO8z<6G9X7U05gWut?1nw?oZ0)$wLBIx_QDZ z;2Sgczx!UPt`UvB@ImWx%rO%R3E};zB0h_ET~iGB9Uidz7=G{y{*aCC)Zl~oHu+!Z z`wvtA$#F1(I^@2jT>dgxMNggFQ$4FL5Diz!*HbBeD+J`KK&lD5puqRPfwPpJCWhYR zss6!$t6L$GL6L;%6`9vD@l912W{mhIo|ie0aB56(gH;S80EwjV%`cWHeCK;a^}**; za8L=EB(?ArC!FNiD6$b1J&TIPl%NK};4^Frb7y*QinW)?HP-bsw%9ZZMer8bfZZ`u zBYVy3V*R)+UE?ixTW`2|mH&DN7+Q^toAG=C!ZL`DGKeP}W`4^WPdL*7y1%O5i|2Le zXLaXPxcMIjFzBA{XTscafzDoj;W-GfC@(RpX<@oYcqg#SVVQ0Ug(I75nFY5 zu)m00pAIFt4DJ6*(&y!gEf7`CMe?eIZ09s;u>%JI!d4Q-GqeB~#S?om!`Zbw9xD<{ zKmpra;{0QrV))w;SPW$vc_`ZXsbL8HTmr&71eT{akRPG}2DHGsfWV6v_3&vef_`Q~ z5?TMRqMioNlc-K2Wieu5HjR;X_EAq0r1KxsNi)Nz;lvm5gt?;do0-=I$FG+IiLo2t zG(HJ>J8)fGpAS$nq^M!&bPUH;Ohmn5%()?s0X%bz=*SIM5Em(2>S(qdOY81l#T9jd zP9jT)$xcaHGn6&V@r89S0_+#Wp9}-+RG&mQ3y#o(dHp=8D(v~B= z`H4hsDM?`(X)(98@nuSna$2uLS}+_!Qw*;6i6cRN$|?QS@+1qG%Ah&P;3CN^NJ-ag zNIyoW(;|T&i~uY=KJACYr_1f6n+I7_bJ?`A>46T8L7X|=4w)BoDN9WxgPgD$<&3Sg z$nke<0Xx}LxH;k5PCxA;%U>oXMdUD8B7;}JG*rfzD}TZDw1&QHoaQ_-%iI94^TWKX znVH!B()5$YT(UfWcMI5h2R^=KMj0w2vnY?=C|}am$+YO#q<70tmS@5njo6s&_$Crdrg;i=@Sc>Nfm6r$?o?0m?lG)N3xq?;s0{f9l z0Wm0xMxxMJh2({b;8TzLwy@$RQlYoL#jRGw4|IieymL74vIBUmf{($x&AP963KZ}P z-_I09WAI2`OYm=6JxY`))ed}=>|2`TSbDwo7CD%E_3|^BASiAMOSZ2-J+g=>uPFC< ze$20;I39RyP;reTZ;jE{Z_mD>-+a#9Ep2ur(fFYk&Ai(t?vidsmBX#o^x}oZ&UA5unnlG1y zvKYtOr!yq_R1oYAFxsyA2(K=4vSxAc%cJ>hhMO#v`6|-CW$JXAK<{K6EnxlP{k~o6^X7X`tVAsMI4EhjC0xs%;(60bXH*G5zy7o26 z_6_6qwIR@gQ~Pd9`#xR!_I%p`-S`F+1`X}@2*yOV7Hck`Vn_cQ4V z5F$XdVFCI>*MY^`LBRW6I=5ApqIUQp>WRqv>2Rq}fy6ioghB>zQ6$ze{7#4e4*6O!<0%-5DqW7n8r zWSmKqcuGMCJ^&rYPfu$WX=zrNXhsfOfkL91(NPA7mT&k#qbektzPWv9uw!p9{hMVU zB^0}*px3A>V7Mpnc7SqD%_^K=*8*Y{NH~jd5uR@tq5YQob@;OrNu}XHrv#CmL_v#j zo??BEQs2;0c><9f|J#)q| zdcTShzZ!lrj70+MUyn3q)}KY!sjG=^WR7Zn9kUo3^M6QUB~c~q^a?Ahl}{CW_?YNo zjL-_fk!>>8WIK8pIr?E})bwVI-4ln|LMewf0I8lCxRv5WCD5bvRZ3a>2VT>dwJpgZeGErvn@WeZf&EeAG5#9 z#!hFkuvbTt{!RP1P=f_0u|aqTE93SDbAgawYz#m1vSxM5?6hRxC*zuIKap z3`Pv$$X3s$ubBT^9ZA_xJaqWowx+SP!Ns_Vqy>`I;ELt$u_haPbDLwAo1A8=yYvI{ z(w^>WaAO7{8rXod^tx+yup9rB8qsfS=|y&lRxrl$r&IPO&cCg5s%?<;wmZ>c&|x)> z8hl)8!%$;kwskYswNuP>Se)^92>(_T(Mn;=y-U1FA-VOwy(H(ZC$D{Q$A6c@Y$sG> z72ACW8wphW-i>Zwsn+-qpS_zHyH_-_R>#iU9$#9`qCsNqn*xP$8Ky@N@B$C*TbC=dnthf!gS*#PX4p%t@$XIl>&i z8``Y!;aFI6-st#15Qgt{wTVXs?dLa<1M!y5JdU0Cije0>H}ivsU68DXyE(nl}l{7Zfb~ z#W|ti&`&AJPc(ZJ6WP_X<2K^_FIJOc_v=Mb#nGl9?P~`7wubu= z!oQA@LuXnpRx{1{+^4S-d)rw3XQ6yd0O3pltu*S)!V7a-OwMZXZ8{x@%6bkVUNZv6^3ipYmUWzh*jyq3A)Yor zMQ@evQo$zquLq^|RiUy)QmA-$v`?-PsQjFCs>a?eyjBO7l!eZL>lbr|Z69-YnrlGl zYKHMQu5MaK8~|Zp_MUG$`2&%3qoFO8U8ALK+WEko!hlQinj&8;`MR>`#S~#Nzo>nn zS)ZVdQLOsi_E7cy)W^fRL zzG8Szn8f{V9LtjOn!P4vgHl;N{m&*vNQ8Aza0fMKCQNHa!q#H|YZb4d5*?QI5U~GA zO9aC!WC#QqT4bvNTz2+ItIJ{nz`l;8KddCB*}b3XDAGNxtlewx_e7tRb}c`Aqcj+6 z)|Oshs`uhgte$k#uvd#E7UbuvfVFJv&s9Nb-d4a$bby-sGXjUHtMfMF?9|Hk-mEYw zpUqF2_*cK~1_u75X39rgCzUm^Moe!KC4XZuNh{6S*sS)rWRj=1UCMA~SkI$t^@}uoQ_Rma;8!5LF>jZ={?k7z@bf?9-h5%nY`A=-7|r` z);y7Os^R6!wZ5^&w%q8#idHDsl%I!ZrfXDvFLTz8Sj%lce!(*o zaq!}yilGrtv=5e{6P1qSLTcGXN&I_084vvV(XNdgslI+@!>e%J#_hCV?>9FzNeX99D1IASozwrCQTy9G zlf{3OzIS8uvpwW1voH+jd0(XN>kafsN_}$LmHnJsCw)g?po)b=gxO8{FKIS`>i&n$ zI2o7hUwN%%6XjybMKU-K@09C~oK|ly?197zEfu8|`q0GNCkq{@7#3-ZGgF za?%^3_ZA<}rRLLfYYli&44v>|XO6PHIz?loekV&&vB<>;3_bY#HV-{NE_{^mXi(N6 z8J%0lu;LT@p6IC1qiu&jTx^y>!!-`4qYZD%S*v&HP0gv{THS@Xvtzu=M;LQA-H1eZ zL;FR=>AyXfM`B|w&~Fejw$1f11?9Foc#-hZ4or}`s})plw57P^b9B4}k~vg>25hr8 zm2IW+#=^e7KV|*)TJHXu;%BD?I62PG87J^GdB5R%Dzxgiod75;l&%PpN;doq@w4ot8B$Y&*lMGe7NEoK4mCYK0v z&{xRo1WI>6AKv?W9TZ3{sCMHsetHxcn=IX#h=LSqOtmp6H4xVUOerEidHPJ$x5ZhD zBD_>8wXp$GR#%iLEfvl4q$|j0Hr!hY8)(GwXGS?Uh6Y>ElAwYWMGtw!S7)Gz8^D`cUW2WRRU}+lEdo3%s$;|Zq$ZF9j&1A>eQ4in z5Umi5k_uVH5z|74+MvVUqQgVbsAP0R0U8rohmPt&M^B++HqfzW=r|l@rT9ceZ?riz zR3CdFS#RK@%>Zg61g`}we2f&zy-z?r^NE&Y9LLJ=5K2byx=!{tOt3p5!ej{K0c!b| zXWxxl73|a$J)`@IdHX$+2OSCqzxelk?NM=zR`I9<#H+~hj}>ZgzgkQUmdp3m%Bx!I zsaiVs`#6PpbwIuBAsmPf8xlZn1q#fslg}Q* ziKi$5UKDM7&)=3FVduKBbj1=7KOy$8PPC*k7dBG|mhpDD@GQbp09&vF;tZF4F7;?u z?a>?#5TYvP@heoKK>pWR5h|()!#$)7YHl4ZC>2wIcy>VF3k{4)bskRpzr_u_9j7Z>q73N#Z#FroB&`@E*ksrnz2RQ(Roj~2+UWZF23 z!=^^V4-MRFJpEX!%=2};-s$nnEGkBBqsh zCX-=JqJHwY^Z1}AS(A+HxE8@W5Cv((fqEiBa6Ch+L%d7o{e(!24y`FQKLEjR(;3y% zGyXg&sqi9Cb-Mp8tW8TOD0jHDN=7|YZ@55!J4;+_lLSPqD_&o%Bl_a`i;SG^NtPGW z*0wJ~P%`&bT^?(p9JZ3mzmd;=Fe@@7S(bIec(!HAbFtg_HQQGu&_&&$UV3DQ+F4iRQt=QbPWPLIt9%n zZ-nntHowK6kEVZOA_yl?RX>nbq@sTH)Qg5*e7x_#S{`HIkJLyDIE2?@*0+9!>%q*6 z7(@TIpHeQ&KkN;#e^V8^q8X z*D+I3__e2CxBmwV`oOqGbS72ZG{~(J3JQb*{cZx2%8Lv22Mb;? zv~(*$FZm)c^ro5RK|ES3giE_w z`Ameyg9?j<6jBe)Gw=5h1K;bhfX(;*OqHyfCQ_U3pPN*=>1mX|xGXcj@`nksFT0N! zUMnm^LIq7iB@bR8^Z|%HJMP3Ao=ekZ?X{(~7?X8%vm%Mo#j^u5T)S1IJ>KZR>{#LAcKPbC{AzKvcyxYks>CWiBpzyJ z3FsTKdc8DI52T6JqvKeZXU8RGCJ%WLNh<*LK$|31)iwQFxGEsLd4R9)QFW^Mj;+;po4E)h3Urx@U$jcV zzsBCTnplNxkA|9dW-%qK=fkwj$HbUs)}J0)QQTQ6+?i{-R=h}zT+?0G_%;pnjcad1 z-lHJWmqT}{HlHtFdaT_4R?VsvJ(j+(+TgP_gRBeQ6pyiNniZ{B{k9OBL1{IH2e?6v z8tDx0EN(5pa*bQHewMl_U?PG|q1w^

^sN==&50vZH&vAVaVS)lE!m-ZS)Yx4ha1R}OuuTM9#vW70{eh#bk0GLlSb`QK ze^GI3xVinZ06*7OY>9Eo#fq<3gmn9=hxGPqu`OJI;!=c#mDg&JzM73I>XimA(Ft6a z1V+L_Lbe)7{xX4U40^{6>mfnW?Kt+Q$u(P>=&(D9zuhVQ`0H1>GX);-jCxBB^(#Ae zWzZQZ{DO@t+Ra>ImW$wV#59<>s4<+4j^z}0Usk> zn^IgqlNdknXR8SWqwb zUC^aX8LAO}BS+zBM?a+wtMZ*UDB=9nG@G-OH~V&PrQJ004})_L0t}(Q^uu50hV?AK zQry#wBGS@I(=upaS*tWTpmg1_aO7;@2ZVY732c!lk>*nj22SJ@>%B}Zlk)Gm8^-k% z6N}3SK<)^k&n~II^_eS)8itpI`MVnlxK!(jg(LNhwzBWUX^EwW~U z8RqgB<~td%#~@C#LByG_R#_OY4fp%=tjyi^cY>WYAE!)n1sj+F;?HwUDLo%^o@<*& z&{}{ysG;VUT0&yN*|#ayK|m-1Y!U z!s4J;aeosGA*9O(Z-XjXH>zEO+=8UFyuU4QAO4qLfA)dK!QxSU{hp%KRd}FG7HdnBEosetC?gr2|;h3vn zF66v4#Rp>cy1yjPxWeTQQOL*FrQ-=UN?`%^kY-JY4Kuj*({*V7Mb+c&>^NL1H?Zr^ z&@E5kF={M|*k5+Wo5kEMI6h2^8K#Bu^|i}>;=CNIrKu3*$NVxzH*n1%$R`ZypZ?B2 zh1vg3K`JN(rU=l{`roF-UB$@YdZVx~LEb^a34ZlQB#%A+#d2MbezMt^3w(6}(iX`6 z^l4|Wz~RUHfS{G2-`SBX&_FKSciEcntC`+}Ua1tp4opoN|ukJ_|20 znbTR3dX#))JwW4_h^QXVQsFm&+tlyi-7Bz~XdpzuZ3u z4L()+YtU4WiRVU*kQCAT>P8U;hto_2?bvd^ZjUbQ2mW_s{8{@LMQZ- z=Qo>WQi^V+>puzk%|-d~ctuEHs#iWnyEo>Sl+#&@@n1V)A*`=8>u*J4saJ+_1ze{Z zw#j9j5BHCcd7At_A)qu^; z*2*d*#CnGRT)9r4p0AN=CHi$9^>hpl$z>vzf3i*_gX9bQF{B)2BZ9vRZNZkLF5xqd z6mYf-L|99mSjIfCd%1>5;q-EN5es$ijC$D?ND`<}N4Tbt`mCO2Dg)8hWUZp^FBd2F zYiym6Oq248%`*iy3CRtm#oNw#o$#9}Ci>SUdu%)@1t%cdXr(V6CRIfeV9AUq)y%zM zS@Br2>zK%yzub!QtS`qWz0>AuVbHVP= z<&$+yqksxwrLxu{#m9;l3!q~D=~BWkdC$p0D;C57i_~@1kVn0&YE*SM8ZFu%vaF({ z=E!vk#Qx0c_}CUJZb-?Gb%RO#Q%Qr0R3($zn|c;>_uG2q8}1}!YacUqP8oGfg$bm@ zW7=m1+2!ytvc+uO{;n%g1b2s^L59I4XmALc;K33k3A22=`|rP7wN-u8C+|Vm+w$~%Uss?@t~APX zk~C0IonwuJ@ZxJ)w5|r7N`jKqEuAOBd4VSRQd~_FFpTIobc~7H6FV>slyFvRJ%0ri zl(fc`#Isb)6Eqr)A04ewj@p;TwxI8b1yJ5t`e^Zt2X}n%4p({3^hva5Fq^Tg&=V|`>9C$m zHtHkE6flXd7g<&9lu?jPU$w08T|(mLavZd@PR}TY7^yvaCEr@`NwQuc#>*o*moE7d zOo*dh%19|42e9NtWoAlbmI@-C>(wVrs`+g99+@9#HWCvi$ydT<`Y0J4lUn-6)Qmx7 zF~xH-GFP3KRAK=|?llyR*>IXgrCwmR^iCkbT;fE!r-k10%}*8#bolWX$1hQ!J87{f zbhc-!q^Kk?fEZ;?JOyJgFAL7hy=TcQLAF?FVpk!@#wM)e^lI7+kan<(ay*bnTRgd3 z`tSA>F|;8Q_e4PV5(Gqu_$GiI=bOt=Jz@l+o}_@BV+GvdN%(nnt8l0gt2R!J{=Ym* z)pJmy$zKe)K9eOSE?=3qLKA2Mo~X_>zaWMlv4U57*zO(WTI8>6yv$prPR>7d_&jDV zcHbBlBnZVeDjqsB4M%%4_LeNO4UiybU2P1fZvb+?e7~RwY}e)}WYyTl+p;C9$mM=thsa54`x@%g|s? zqY}o>&sWJ#(Oihd^!I5Gv?UAa;$x%VrYMl9sv)JN&-JT8^xb1pIw@kjvS5uG`QZj3 z_crDO5Pv)z{0AS?&GFb2!jm|OdV(HuVG0)iYeW0`Sy}owT}4D3J>|cN7*P4gJ;(8w7R)1jdY;hyu$Z^(2?sRCl6Y2F!)XByx|0@KvM~r zrEs6}sU#*vx?YL<^Kd8S`EI^IGQmYw1f=pfrjS-~=l<#ObBrbar{NW=T~P1W2;$Zf zyhV$+G%L!#Y4s@b%o{no21^4m1eA|0c#gTlM2qvW)N&!5EbsMG2?6xZy|B7KA!WCz*IZfQ zDdiJu1;P&xGpB}#yj=qPCPlIf2bK3FJw=R#jWk)=FWNTQ5BxQK<0^KF(IT4%{Vz>{ z6Ht^-dmwL+ijq4m_BZoQK3>nfA z))x8s=B<}v<-u|ElLif;5S#H)Wm7whA>t}w$p1SfTIuo(9eEDX0=v+0wCI%nr;keLnu>UHas&1=;Bufadey?sHpNq%;zVI`?Mk6piI9y^~%;t zx7ReZe%d0cSEp81?71|xx|#Ym&)!BzO%yBzxF-0CJmvJGFz^E*6X3P$C_v?31_t!J zw5{2C-(m+kCh!$_wcjK99F7+S+JZW^AQzUH{W4b5kfAz!eNJcD?pT__YN_Zz>KBj$mtB(hs;9QAz@1C3 z%^QyQY>7fJLa-*+^78I3fy`zbDbbB2_$FS)c8KpK%LI+g75#A1V*;bL)=-eKI?AK( z83BB^1ZvVQsnW}_nk#S`Mb^S16>}?O36)zT)X8KrI5Bh@0P%E1l-v+Cl^2~JkVGX? z%s)&90v9U`C$o)I1@EJ~rK0JF@jTP>qL%aGGVqa<^9BMa@5=bN83cqGcMmM=ERJO2|;RQ-0d2OzEZmHj4 zC5ibZdKrm-3yCi}B340x@NZ;U5lni%T&4zzgRsx)bOYtjZZ9bkGh_SSTY$&4hNDD5Ri7D=?sWZcVSQO2YZ z9gY^pWM#*MX7tvIxyqX4yOsHowG^|h^;;Vy=C|zMZFQ^g{H+wc5lAN(Bh}fP_@2vN z6;arSBcSs`>AS=I)&=3?H7!?JG^r?{f;_i5ND8bVycHo^C>Nhj#?k`xK&|$`W$`4b z_M~BX$6Wo6o5f4G+DnSXTZzR(4&+*d#HhmJ3#w-DIPkHn_6ue4kE!-gVF|!xVR2wq zK&Naar)&#nMt79;{zRjK4zNwy*4};5kCr+WC%s#ir+!{0m^qY(M2a0pyY5%Hktpb| ztm?n6w0X@O6jm>i8g1Av8#!3V~w?Q!0&z=8&eaP!Wt9G8l6!Sw{rwdizF&J zj?S-1v_8f|9?plrER|}I-Y}n@zY7M9B{a$rsUbNn1;RZ2A~0hfg!Re4UEvb6!lQ> zqfiQo%Ua%^n*RBV{0x?Dm;5d*LL@C*A`8aUEzimt1)!1__coKkwUwGHf&Q(sz-P^Qm%F@)Ef~><(u}AOaAcA5Lb8BrJg}7aHC8TsJ`PRB~BA zNW#&KT3<@w{IY6N69y)$b44$KI)6PK4OO7j$mS^Z)~wk!&g7@XlwddH5G7Qdx!uNG7ck7l7&kuxMz?N0>fyBkt8MH5SqhnW2J$ovjGt27Xp{TOLn5P$)TI`M*dSs zaCiZG1Kf`KRI*`3u|dwo{6{V9NA%8dz~X9cI?3^HQ~yB;7$rL&Hc_TA);rSwZglpt zVZQ95`Lv}2p^}373DXycZ+N0kHHaxICbjWp!q@m;)K=*H`fSzkd>Wrk!jZ~># zal}Gn@#8Jyrf_I7dPU>j z9MSaGn)@HkDMyn0?Iq{kuw(TVpfLaP*LSY{BUe$WC@_H)KN%eXd+9^WGP1_2YqO}V zXJoA=_udX3(G{1sBkuoJ91)={1u-6l17I;QXd~lF7!`Da+VV@7=r?Z5DeeeRT7l|| z6*WH_f#^<^HO^BNGiv+KpUjA&!`@2tP4_t(KJ;(yADfElYFyFf!{HOP05~sjZf6H` z8=R9qTRDP`F0YF*`jY%_a`50G-naE{A%L@Cy!W6i2hi1!a%j7uqgCN*Ut=kk{Z{)% zBTjN=qCmb|F2&!Jp4+<84JJFbSCmm&{x?FF#77>qy=yo6M=6@3`5Ik-kGZ{-d6kW< zW|iZO8^X7r3bt?@A7j1nTEgYE^P^k?9=$u~VE5=U#Mb6%~V`Nz%$s|J48)LG$ zp`7NyP=_TPg8)mOEbtS&H>ITWZ0z=X*m`w9FCMuL<{S{fWw9-v=~8QLSQ_~&caA5I z^jDthR(yBXjhah~=98fS@v>)|O6S}ki;!!jY- zs1J7SIhcazpCUxV=+&~ewOZiPNh9*=H@5oxI*@WQZJ;*VCv7|-9nw!av_3lRKwTao zJrN&Wai8ayNOGu<0pTZI1|Q=28n!t$sZ;}O(^jcf54p6u+OoR3-aE8b21d6iE~IG5 zzi_`J@1$%2LX$Df7Fm|y2=kvp7Wbbl5JHw{zb)FsElE4AXn$MMc5)u`a6&q5SbQym z z>NW}>!yib>ZzliInN}%?v^)Oe10@wSq4^=S9vY$!as|rMw{*w%`3EZx+lqi9_3q#P zxQ&XnAsIxZM!P4!%BNH5@X^ZM7Y_ChBpeIGQjA~f&YJ5=)_Tk`6b)tp@g7z(8U?(! z>7fSUa3L9d|j#YLAB}e{Eun`SQh4aLH4xjd;j}wJpKh*y8 z@3-gSD7c#`7i<_r@odbM^@xB*4v7~=ptywb`NJJSL*!wR=&XNb8sK`xAQ6>dg@a6h zhKC|VR3i--&-QNYOmA6FZ+vxhyjS=U{b^IS5Xl)gQe1;Dr@YJ10I<-cx7e zJL~*=+e_H)a5Xf563`GPW(jGGMA{0F$88=G!;V?RQjofX$wUnkvav4sD6IM+bdewA zM6t_$b$M5M~9!0%-P6xXZSsow~a=}aD+neHX z|DZx>8?$=v5-_5=;=@{;nb$2lI4-o(mo@{~&z!U8exS9v`O9A%rx5nK|m;q-BlE@wj1uE&J3KbRCT2ZPw zJXT{_|Jx0{$Y^_MpqbMe<#SEG1RH#B9m8zUo8_oityQY@iai2Rxm>{!(&A~EU5hPT zuoFcr{=vn#-F_keZRQ78(=Mm+VG0q=71KVy)d8J5dvJ+@EoDeqM1+SGTrN%D<5Y%Y zwKAzoOcT@i=5Wjqu~1V;G(tRQ*v8ifl2H(LrqYOUV%gn`2*?2_JibxeAtnUmD-y=z ztZUS9iJ*}dcf^Q#31w*#tbBJQFDHyu&XFn#{FO7!-E2pf-2eV)RRBl7iEYg9~sMC)rbqcct&sn^ubUQ9y8bU5X0ih1Uon zuJ=j>n&Q!lohJNG0P(QjYmP{%O0E--1EV3wMb1mgOP7B_5qAxEf(?y?XorT$Y zs<0+9;w|0ZWW1&FW?%RItN=Kvm;8e~ebd7A=S+8quQBqIn6W*(fbJ=CztB9<6yG>% zWf(ynTe&yaiV=xdWz!-t53!J%y=X`|f%kC)3C{p>?awKF111+~?#R1E1Kx4s_BZ?j z;=bLsUuV<7++Y>Ao~p%%>LTCkSwpCAr77a|L~{d|)>7DoHADX|O{UyNWmNJ*{En7$ zl4y5Rocpg{HlzNplbv4~T8uyZGcqH0v}G@TpMr0El%0ba0DX_;^4h8kwK$JUB$)h1 zA&aXL2Z1c=BST|cUu7Upt)+any$slV#>B=2~R) zk3xp&QUkAM$DW(dJ16BRZ(FJweQ#S2u@3iouImd1`?#1ze7p?jzBuNTq)=5)zD-TQ z@(PRhV^#ld;8grRu-@#!*D#p9So8~XWaM9@tXe3 z4!mdmy%&O2@OKvs7^C9O$XFn#%;l|v-=4&F_>ZT|aX-%Gxd&ZnS1Q*Hbi)F@;l ztG!8V9yZt&nhyZpfv29sP{KP5ju}`&MT-nsPgsgp{xzPzQCgHlU5UYsebGPHruTMd zZ_Fz0QC$?vqTRdAKeSa7p^MqYzBws1fUv>{id&+DdZ>9JyhKR!lzsErz1gdVFNZ5 zv4XN3rY>X5uBz?^BFkz||*ksH2+)eXfsfk|+irQK+nG7_~s8ykMru_LdmMQir&a#LeRVbGb zX@ZsX!$XP2KmdL-x3BMFMV8Smd0`v-d4qBr>s+W)=lo=5`8&yS$z;*2%GVkd=@%7_ zqvNY|Vjo)hM6C%tty!&RR!Rg_$E5FIUsouM4f z2C^LQ7P0&-H23z*xwC8Zf)ifo%vaCBjZ@$~Dzn8Q__5CXj^qc_py(pW!J0^1KX;t8 z2_uM!V{7lrl3mg5$vbZAdkCkU(q=F{P*`2k#m-Ts{uuzN1tV@K`xm;}s z2HyiRW{!XHy$btGj%%7Y>-T68?;2wPWq9Nq;Y{)hDYF+M$eqi*zI6)ObO4}-VR4(# zY7S8n<)ZH*Y?rk^l>?~@RSfMG=j-lFaZ%-&(OgD6Bq?=@lI)3d#O8QV9hyw1%?=80 zm~k$P)S*^cOj}Q%Q!kBTBC(3;5F1>g4C5BOjl4`J%``DBIoqcfaE(a{!@keB*_K~V*4g}S zd&Na4Q~|@#Y*CbI(C&M$bp<>X(B$YoKZ1iwvJoEW@PNK|xiZ0Urxd!;1$v85i+Psm z9%ogt+b4wYpSDHug`}i$kEFgK(-dm=z)hXi4ziF$g+x1eo&JFN$P`QFOxivp;VlvMqUbIX@gUwZQeyTkE}_ck2le4{TWCH-4&=ndH~4 zu@cWT2SVqUHyafg*tZhn-vdZJrpMjVgkY?W=@RI_BX-$+wh|R0; zMq9LgHt_s(8y&y5n^~&h(s{eGX}jr2sW6)7Qu1A%XXL2oiK&MyG{mqq zKH@vpo$%XB0Po$C^IakLj#4AwWR?Xy&sb+g?tu5;X1}o(%RG>R(iv_fe05F%j*d%p zkx6@x{{4bC5utE&tJ^XObpu>;qqaBi*bb9S4WYFRkv!2=VY;J}s&6FOz({_MrNCI1 zAus6q=d4O}t{>>etdMIy^4Ge2A4ac2p zH_2w#p$rxm&X6ICv)Y2R4G!4#NCd^Ce@VvWW2$)uoCs>7WHvs@;DYOU!50@(L^@wh z+%`bY%)0Sphrk=V6axFYzq;xd-0ltec!AiIeQALc7h8Vqe3 zPixeZA2f46etV#GT1ODZ$x_G3uAnZ~V`h*h;@zgq8LN0uZLpE2GiF3#(wEL(R$P%c zyVG-I(0ptpcArJ9nx$IgVV;K|#lm1}i;S?V1Z>@CFhNeCBF6ZEN*KoW1|MF3<;lZ5 zN@)tF-wl1^3{B1=u$l{GB}bGryn)NjW_Zfj!_PK>uNUTqTivG865Wm{W}E3^`t{kf9^~V>*Ic+5uTHTI>5duhOP=(vbA6i1eJMMG54%k>Mo)*+vwmc8-6G z(107kkc_>W1&XsH+7-GtEACuB2|wHjFtrovb!IY;+E8C-s31l%pCmS71H;3c+)mXA6#U9Whmg^L1&jZ(%V@E(-~%EX`y>0 zHeO1O-jdU`Z0*NvOBiZjbQGo|1DRF1G4wg)Z@HA0R1yUh6;;(pu~?V(sAptJY$L=< zv$CA-aNLP7Qf=w{vXp;<26N}sBlQ7~Z5r`JiU#=|YuQgmnD6dLW@oO6P%82CTJd^b@AHvFjQ^#Pn<}R(lyDXuC$>L?Z z?9&DP()x8}sQydlpNIB>faup-o?~vn}S~_bF| z?!!1Xr2d(XW~+kv++ic*7hMTS=z*W)4^jZ)Lzs>N=#^5=d(Wx&-=-y6M1sCq>a`!K z^^kgz=xIYpozRrpT%wLNhstD&k4?+24(Jj((Rx7;4YMV|~a zdT$d?CchB)tBiMs>-E~8=f~mXXU#9NYJ}_XIBbON0X3{6nZ!K4A0u^IVm-?eb(WxI ziO?($1(b@E!$nx2CWaRgs!gA$#z8jI}~9H}H73E`wM;ZJ%p@*8Kb70t$8dmBFoSO0qIZil`E zq!O!FEn!vJ`+j}38SA~y--();esjG;rIvki-N#V2S+jQpIlv4Z3Ti$2HtLrxUulGM ztljehAtbpqIAWG&K{LO@m++r+R|CTZ8dn**(Th#knFbe7s=as58$f0THR0k2` z^Gpp1oz9ebjb}~nf7&)9(!)wE+(mDtOuJ*{JK)~6%9OEML6vQ@tW7XVrbzt81x6L6 z-u|)9B7&|`f;HcE_;Sz10A;;9R2F5`1z)@nxr8FAj5foNf1}-ynH(Tz*-4-{z!cky zw9tD-*|#*TH(^zgXd8t1v)qnE>HBZ9#V~&a_O5{^p!D@HYaLK1DiX`Bno56#(L`<7 zIA)-Jd0;({i$GQqnN00U-TuAliN;f%sBrzX@R0MWhRcZT>s_(|7|qHa*%~Eatb}5p zj;02PMKg?DQuZwvUeEzIEyvsbY-o$U98O7fh*>C$le>#O03)Z_N7|tyFCM}y zET!%&BXTIk&Xpm0u=+h^NvlMM>9D6Th1OH91Q3*A6nrWB${>+h0ws*!qc9F!zj=H2 z+5GWu*b;qGDU%GMpQI%`h+O$|_vo)dyaGk3UCJ+EQP;?{6<+5=$XL&%80K;m%=jYS z2Xt*#KqjVHLt9jret@|(YKA4wX$h`29kH$~}vWgECO>_r8i-7haXa#i>t>`7>l@TR38q#IZmZXBrmp_B|Tw4oS5xU)wm zvrDZB0|^h2ecrQG+^2ARIU~oYvd@%ng!~$`LdQgW6GD7UO&qoJ<2}u{RR~rF;ALrw z-+Qz-Rup8rbeI2r=mClCLIh9&*yeN~1vvmwwHa}-KN$_2Xq!3TL~99D*BG6o2)>Ay z=oXP$KoEw;{CKv1<)ipiLP-^I2((05hLI@jV-AJWKENp1A2u*}Xs5V|wn{VCZO;*K zKtkvZ+u-q680!%5xZeC&^y9If6;6uO4qE7T>3+mqzTc(9c`DP|Ti-Ru&V4B+!_tbr z%>iyKvzUv4OZmQYFWLpGA8CI^sk?&@KRwc^$y3nVAhlVMkA-0umQs>6PM-h?738iJ zBd$FMe){e>R}I|sBYsqu(p2sJnf!PvJ;>%e>-S=?%Zq4N(y)B}I2bQw(`BDWGbd5Il|G1&^*qt$j>Xs{< z<1iI=r>RQA`J;~borM15hMvxsO!PgTD{*3^k288QfJZ8ddp*WVTt}Lfw54CdUj>A*O$TAh5lfEnd zNcQ@F4^z=&oX~t>pVdLmG3;xc8!|2v!Judy>Y*etA7o5Osnr-ZgK9>@qo!mqwSG;< zzf2LKkf)y%4FvpX=ixFaJyET3Dbj<_|Ni1MUGU7CdID9zX1)lW7|VzczmBG%LyWm( zj1kx%6?%UzbgP(bx|lq>qL2q;2dh>kNIW2ajWz+lN2x?^g)Gxlc$*g}pUf=jImf4C z1k;e<16ZO;b}pmCF+tg-bF5m08F+3O|5o>nD3;UJbQ!%z#-&Z17$N{fwp~Sj0ZAvy zd7-;}Gy$~@J!I`FPBhd35kd$ioLn}}H>f|^v#pV-boG{L$rO>^{gszA5 zUSgYEglEz#*dya258jz$@=6SLl|l^p5s)Yq88<@oy$@# zz}97HEX}u5SdrgMm2S26&&P-`8CP^0jJDr9i9e0UFYQ@N;+->Ns4*Yx1N5gAFUg z-XyRM1HE$BtBa$>_G`GR5@^R39E0cU9xuCoj-!&pIN6QE-r|$An74yEzXt}z`gpN= za&`K#%7)?k1yA3C(IBuekaI}}Q6IA_GK}L**xN`$o_K7ZWnDa?ccK5DADiI`n4FWM z=}y!bkVtgUq&di0a(&$|fc@HzE+O!Elq3gwAMc}nc)eU_z$Jv?+~j$u)HQPOMdB^M zV`w_?&{F^t-5_j)+WltcmP$D-NC4FsoSa~Uidbfe+$l?ydda+-Cp(xqxL@RO9;CI$ z!L3rwI@jylxyd$N2hBXUy#Kg~T(Rx+TPsz39P=BX(D%tIBEgWElKARf@Pd{2;qh{p zV)Y!K&ho1tpJf4*j2z~2q(|d}(zVC2slrF?DaYru-iJ=g#|9=Ee@lT>$NO_(#WKmc z*q$YBJdCr(1vvN-wPTK3-pYJcxDq6!QrS5*{P1U;1Ir-rgLeK^%KPAQQ<2Cxz`L-< zpCO5!YTyMKbU>77?wlt8@-q2f7>H9C0yp!jkw)QTVPks6J@K2B+A4njca9gHv6prB zg$^T%YacHXeT0EvV&s{v#nsIjqQlNgis0>3Omf6OK#6xC#=%SoQI(B;g0_X(+#xZp zcEiCm@51ONw4-;X;8YQ5lF{e@lr>P|;a_b*Ja$HuBVII8058Z2nE~0Mp@K=IY;5T; zRYrZL%#yzn{aq467(fr1xUri~tI9R;&0!HzW*ocG_t+!{zVd7CJSB$j>VRoAHR`DQ zG_Eyy_45fhzP4Q&rpH|HH>__|VN|8a;G>r_qOu%Uc zJI(~DQ4$ih&ThF*)J1 zChXC;X{umnpVZVJw?jsnE#s091VJobttq3Q|iWw985jRRE#P z>jJBWF^IpYqYHmp?=Y6}uCb*qQeBGBeXi-KN?T79TR+ic$F;5!e#;@|-a8a@s?RFJ zq;4^OW7v&zl=N0|!uVDINs)e;9xWGs*Bc#+LUagF&aK1z7Z=f5jDl_xQ3W7z2B+rB zV_^Zzth6|K;l)giYWhWHz;@D{Cy?cf)WXbSTK6^oeDou7RqbC4* z{?-1v(>jhfW+96Km2cHxf5q4Th#vE*M{hraxuqW|OMCU~av7`vIeB_{b3|@ z^BuV&yc!uBtb*Y&Oy`4Rjr4jM0FcI}kIqbp+~9rkM>bSkKK+^ zSSU4l@MLrujKEw3Tw>o7mC@+;l-C5z9~c!ec|=F-E-?YHTbLC{?3Iqjoz5>``X0bt zBa5e-MSt8-B7X3|5B=&D{wQ(C|GoEv{0kIX-Iau$FMxq%ZJp*4kPv@^58wQ>s@qqX zz>8Ob+GsiYnVIj@sjY_<7V;iXH7v*mmkN(Yx)O{ z@_Jme86o;eX2}y}eJ*dOT3fasrtWC2Jiy#9C3|V2`c7J0%3!R~%@$x6I~Ux^a8+0y z&AZ)gz29DUcC(oQ&85FI!8+d0R&BPoLoVUfg47pTbdzEVq$~gl3gnjfyJfT^9qwIc z&1WGM?7J?68OPZ~lBq5^zhBXdgeGu>;;@UPXCX4^*PdN}_iy3bd8T1?yRUn20-dTh zgX0-0>;?2t%VHTK^OQT(kW0JAUekn2o{Ddx{N(OWV?xWG2Jips0etUQ(B9mnO<%lB zZUd)?u?tQ*T9@$SseIXDtsHGyK<@7jWRTN{jnLtH-aH{j=P4qeZC?Ep!JSzY$ch_8 zlG;A4@-fF4TwP=wI879}np94Hib|WwvCWBl-5iWozn=jQ0^G_B0X{yh4c#ppVjY&t zdwwKOYY#{Nax* zi@6TLy9D59@#>>PX~P)60+z3+bfmtOnc4aP#LLmX(t#~y&~b9~Q70l}d_o?|18cn? zsy{-q_{2TIT7)V=?hv0YztDtxacT#j$Y0?|bU1mIC`J&RQ%fC&=m_jF9XVOh*mq^M z`RM3qpnDmbu?!d$;Iy6vTk;;G=V5b6jE(@?N@r$nA6Bcoaq)v+4&Y~bJP7yH>a z?&?F_%}VG1Gnn%VFZLi>T7`tD#MW&bU*oI8XsiiK3p5K2kSW9SP9sL?Qn=>8w!IuOu>KM>st zu;78iq7rY_imC{Yp^^n`!QX>(kd?w;!NE?;YmqCg4ze}U4fiGq^H@C5kVGps2Zlr( zl|-|saFWtci4Q3{$KkE-Fww)YPs84QiwYDN;{Hd1&)bEjcI5%uMSHP(0Csg2Sap#n zBT?7+&?i+f9Sz;TYQ|qXJ^Vr=p-(?FN=IY|b#*5)c4aZIX8p(wJU@P^{UEThTT_tO67bBch zIC5~NtVyJdPoaTkeDuS<*hPLD?QYeDS>k{%$}8$O@3QeB=8zxB#1a>D!s28c26Y6l zt&wch2x*P*#_@^&_>iO2mjOTCZI`4LRUi?%l$X_Af70C36^{pfA@@r`|KfJl_DqD4lTaLN$b z9yBq+KdUpYC`?ph-LXVLB=^j~X}S%Ss~caXBqm)oggYLMhmVK3v(#&~l*IdGj9n&F ziQYI76>60uZye5^pRZL@6dqr)$yPqJT7m+jUhzxG71XBFY@x?Wux%n2rMF7&yV?0_Se($zOxbpdsiEl@%%d?xif#+52Ochx{0ik zsjgD+t+>kmsBtHaOJ422_fh58Q`e;EyHO?2M)ly=M1iT2YE}fkD#SM$6Caj`CT5xG z-2z?6#aeo(*&wMcj*rbwkkPu!BqPWoqE9*cQ5$NdRfmxs+FKn1t;6UpiCQV)TxCwU zlUNZzd-3ro&2v?T<#j!I^oZ4Rjn#JvxOuNv`0M0rKUpt3Ht5ARl-4!y<|i5k`c+{z z*3^MR57Zl;-uZ!%9TLzE>9J%E8@nlL>WQ0Ngqs}ND{ytIe>|Z+lcVn|H~5KFlIAv4 zY&6Kct}{t!#^j?}X2&92=-L%DaQ@_;7-Agc z?Ut{IBZsSyN1FPA=LMq?^)-!dkdCWW%BpwBbJT4+cDS1s8w_(ZCxU1E&@6gO$y%Tw zjM(5r%iXCexreG~&-QePA#1PS`BV2LMbGV2XBK6%zC-h1m1XaVek;U!J2XWhZT9x|+EioVWnEc_HBBf3Z;SAG}KKr{;9&nWxE zS>6Np`JZbG(jum%qyA(zC0axPN*Y=ER@D2}I1oMA>dnuaogvO(iXm=re)E`8=~)3% zHv}8Gd!RbHcX|q6AQ5t^;D#?wmz<7n8hH<}@Es(D&i2Ga|734Bms% z>fi)Lv;R}$UD9Q7Jp>N^#8LHmWBhZ%{%1egK}25d!x^loZIF%=j+x#$)7zhE+RRg5 zwrhQDoeVW)qlzaVg zk9d3~w)D>Ug8q%B8enf3tn%@3qxDgzPB_*YoLsj(o3}a)P(t-4ORw!Nbg3 z{c}@&^5k(H#8Pr;L$TXVp_{vb23 z!c}fb!56w;$VDE6*pdpk+f`lV=uHB+eSp4?whPUpW2@(5>n_t&|K_%5Mj?`5v@2%R z#zizfyJ2lCRcbLsGilDoUWZ!*dKd&3?r8EcyU+{_)Ev(niK1;08gjiDu z#&D9aqI#mLx_(hL!|Li;v-6p%dOcBh{3T?sHz|Bo8`+1LYuedsB$IPZ{MA~O>sobC z2#*H$cky*lD?qgo^Vi1A*?g+_8_yR_Tbj=?Lq3sB}$wX zo*=Nk%V=}|$|p;#VeQTGu+1K`_1EcBZ)IWeyXfTD=*V8Mti9C(vJH30q)OfhM(c=L zz%=46lp%oAyr!_w>8ds=L9Z=sJ>fBp|G`8?4u}yANBt zUtNkWlEFW>%OuR!-eJ!}XGrqK_LSYg<$(Q_qU8e1?<#Kl`nfYmQslchv*?;xycbyh zlb-xL-6l94ZyLAE{~c)s_aKM3xQ2oq0sAoR%}aBb+Uc0HI5L8Mu6P4M`;FoqnG0M;ALu^a#=l}O8zyT7q01?IgvSEWX|+@a4%sR&NL(7I&h7E=3$dkJ$}g5w^K zYM$N{O^2zW+=af7|9`SIUj4QDnU!DB^k>s|fHWJTc0A;bM|eq`cvNC?Sz~rZoH7jh zdxcDgdToxy>~RB;zrb|5xG&~?KSV~fxF2-AnD!1A-p>|%c|zMfC(3n9FMYR4_Fa1W z2154JI_>WFE#d}*k9q2Wx6X@N7qS1bR?OGzHc8_sW9a8l$to4z)!4riDD~->=9Qww zsaWxy+x%&H8fwP&-2$I?NElweCCUUCPiZI5aIoGa)#A+@X(9y6JQBBU_h+}jZvm-G zeDeds%Oi!<^SkXkD#$)U@_zI8-MR-h$O>>FgQ-M&`vgQ0qLYt~iR6BHT>LxJ{l-fRHTdJ>L+Lw`7Cc{G@H7CYj0Z-r0I~?PAi6=%*!??)_}emn z5sNpS`uQOQ_s*2-?nmgK&YumZDYO+=c)V?(@hhC)Ex6;_AS6E27r6bk42}^m*vJFt zeh7Dg8vzd9#krT^9J{&e|Bo9Qm(gf`S2haczueIHOq$-T`ybI0Fm3)a2wc7Hj38A= zO1hcDpv1-1Z?auqJW|i)GYlnPcHVkbDC)CwcjUOFRU#XW%Vd)EN~c0Kn;RuC>qM_c zwTSs*SycnS!T1x6?7r;x)od#52qsgKhP5oauT2K=A1*fA+`c_MC^H!+3ZU*L z2ncC>3HD;Xg7?{KH9(zz0K(#YXBzHm(bO#SLdwhLr~DL46_flGQ<=>+?i`nE4gRMa zT5i5Z#Fyxyb+`6?kC&JA(to+3akq3J=Hl6@;`jBsp8sDrbdOivAF=&dcl(B4ToY*D zKmhA0q@kN;41o3(Cwj-xE6a8V)G5@wId1-+GRTDb9UQb)^3R0^+UPh|?%k#uE9WZ}X% zwc*vS%8MJC00|7Is8?kzy5pTl0hQ&)?UL_;3}{|<`1LRB`DjYrCsxw(L!VV*S@IwXXH*-o$W$@ zNvm&bc}asIFl!ni{pXlDl6Rfb0ma9K{20^YVQ-w07P%}&CcNQ+1ru;{VpF2M#ivq{ zPIHv0{lDGNuULndp1RR8S<~XtP?hO$e!+BPxrn#isj&^0-%(2BYMGR(R>G(` zkqNvY_-*NSi#Tn@cG&!dCw52xU+M`%%V?&RwN3A7S7S$p5B}B(9Ky*POL97BA6*>e zj~7%n4eqy5R()Rnw!EStKgv*jt$mbb_L_A^`r-v~TKM0HQ=|VNPO-rgpum_AFNo+# z2cedvfX0e;Vtwb6Qv=7CziirDCGhtT#-ZzHNH7}HbL3gg0+-w6OOmfrvfb8~2#z+Z zvG(A`y|5DP4Sbmrl%MclhSFJ=XY*{z`(n_=&X( z)?}U!N=(C^iSN7_@FrPDgsOB>gY?a5w3fzl13aQ4kZCcrY=*%Ui-K{SrS$4H!>pb2 zslgStO!dN(ivWHXb8JQy5sWd-hzz=PTRLX005yHF>8$dF!*z)hHJxGIq>qJ1aw>Vl z235K_edoH|*Nao1UVOj9E{uG5Cn}4)H@RbP82OcvCdE+~az0ns30VltCIJMzW`ZjO z6w7Dq-U;OGj9@|g*uL0@{`^2RQYEzg_);>@4BtV>{ScW9AoWUVFFyKguXL05C1k(- zBT+c>R)wRIKeK)*T1K@(;1Is%Ll`PyrGp|@piYvVemUtcSp|_NowS(cGV1Ial~;j_ z>48L*971fW#!tFwy+l<4qcs|iflKilMAd>{PgKXRQfc&Ck$o1lb&>=1E0_&x)!#bl z6+P+K{13+N`Yp=n?-%{eG(B{ebV^D}gS3>ibhnBK2sp#QFqD7_f`pW$A|MSS-7!i^ zcY~mUl+NM%Jp1gu&py|=uJaGvKd$?;)_Sk^OZ#5A**ouhAHwdvcfVI*yWws5@uHMk zX}e^L+sAq&%%ZmV-UlByAKQfsi^kr2m5;8^HV?uqTQ~20e7fP|-)r1+=j2`$hS%4L z{HawppG9>7-Fr2<}A1Nk}Y^ho+z0lEWELmQiMEN$J5 zgAM}YvW6BIp9itOw_E1@_Q2kiue#K*1wNjTIJ_F6ve)_U z`;n)DK`CkWD(D%>G48LqGj)Po58ok8{N4Af44)eH#YO{sJjt3^JVg5xuoBOo+PQGT zt@}0j9;PORyYlc`59qr;e3^6QDsabo(5(1j+J|sA5s&M1?B>JQpRe4+W535M>tGf3 z2}IAOC3IZ=^!GZjX~z5Zcd_9^I^XIXQ(DU7V8bD?x0|`Ja6uHkJ1kc4UvZwKW+5A) zG({Dnnh-pLVK!1VE?`*jgwGeS{Kh37Qn-3)vp|>#jb<;PhMpRv5ZI9Co!dofUT97* z>uCr)hqMM1JRIjW+YXnLOwBWUD?bTXJ+5%LjkF%0odOSN${wyf*Cd8S{$znhMcv=l zV3?b%f~nT{-1k5y=3gsqaG71+gR| zz$duyVxf1lzHn#3Q$!lWc6y{;w)XpnLkW_6K(&i{BJT(Egoxu!RaCvzGAF^ywUfju z1*@Qh=l^{4PM^>Cj%05YL|S}B?On(n=J0lSs2r=BXI{(*GdW<|jUl%}!Q`S(nR74g zIC=A69J#7kUr(2<+aLd^?pGxRZ_oEjH^`6v;6eG?xscse#STD0@sek%WM8fBjKM(U zVdKPre%>940%Uwd9+8^em(WonAh`PF!v2}=<@J-w6qDLDYJ>JDW`TLdLEwi>_@9fV zF6Gmjx7kPD9#6+8US{-2Z%U+m9A5NU{PWSl{^$(@PJluT2@S$9+p2acy2|`%Ub_7Q zUeLNklziUN@b3h`M@tM>Me9#+(}MC_7LF_bFgypblB&NdnEhI+TuoT!aNDL1n|SE~ z`@YJIir1Eet&+LRl`euj`0nqQYBv{gO=M;;bF* z80#j0pcH@wimM5G#A0Eeb`HI*DrNJWc)X?!U_zpJP~XAWY2qjobs( z=|D|0R#tNeaE}M4Kdkxozw6e}FC#zo*oyQhPH5>G^yonViX+%902NjkY&Y7{#j$qJMz@Na#dKZEUaO{^pgGWhFrkLyObL+m;9C&7|i$*}x zgLKiHG2urrX-=^B5%#ZmhW$BRj;2m7>%a@8fme0|>E^0mO4Doy(xRMLqvca_Xmx=j z-S=dJRz96!8nFE6-e>rhH>|jeRW;n7<32(;=M;pL)z`@&Kk;dpJ0{z%lGMti1BAKRe5Xut| z(@^TxrojXsNhfPcjzJ8+@)%0YV6#$TORPBRz$nden1vuLF?*l`g6fn`o+BIiN{d_A zA6c?fSn)Nq5R7T0MbHzL;h!;j0OQcK=jeR2(c(OOX}@!s)yQJ!^)uoOH1QB7Rd4gk zU~6LJr_x=(7!z;?pgo5g)=~QgqZ>iw$Kj)Ajblp_cmEY>3%5o+5r{z}jk8_Z=|e!I zpN&anIvCGj?pBrJMMzSKUYI;A*eXh_nkoA`{JM`0?$v|_VuC}E!B)y>0Vu0$%I)iy z@T~^Z87goT%-@QL)lb@FCNp~l{#d7mi4DQRi=#ek+!aO?F{S%0!?Ranv*e+V$$Ctb zQg}anWm#YoNV*l3VY>4VBnNYd(cLyD`JBv7eBrEsc~9Cq%g? z*1*{;FJdmp4pbvE=c#IoMqO7oV1#k7fIzav)I{a89B|xR(}_(L-CWb$+^4^d-^+65 z267hAN4H6eVMFYYNO72YVN978^4HfSz3|%L##mj#%f(;T zux2?9DY=xLktC1q*?-(Mn-TUjw9w#w_+ykk8b{<67#r>w>+U#Z<7*~0gSF?j|0TC1 z^~eD*b~uGPo~1cl7#dLNU_-7$sj6vSS#QC|4uOCpk-r0Z($e{dB{jRZr=f3yxF@Gm z97*gQNYfYI{vrzBvyL2E`m2ScGIF4XEr0cso)666Nuv1+m6MorVn1}^_~*n);mpPE zd_&BcTiKb%$eGvPna|&uKhjy?xwBxdvrwh8aGSHpsI%yzv)G~Y&413~6fP3%E|Ov{ zQf-otlw4%&U2ajVnl<*KQAA8WE((<{iiafNwy4bYbWMx^uGw1vBYFn2Z;B3H#_%qK!MEK! zBHcZ)>7;q^WL<1rZHy=_!UkXG9x`N$vjqCr&_^2#`{2j7^;jXXXBab^B=;wg9wGin zhfH`_ZfrO}?CEGAgO~Bco1z^t;lMpKa_irFWOJaDJeS2a^kQ@K0s_6zo^Z2%ud-b4axsJrqahy>V=SO! z*#_lb#@LZoSXa6kw7W$$Mu*Ns(J@Lm*zaTpc>~MQVMr){JIF9_y?oT?^K*A1Bs8EO z{v-u7XDO~2``v~}FLWd1Zw%b$Z0Pf$?^y7bsblOI zyWcl4zgR@f>z3${Jm|Q;-?aaMbK_!wI5hI9-`v0b|I@jr`CraG;osl?qVBJ*p?kvB zCE@bVHFE#=TDku(=l3 z|FP{iHrCeHuVMR@wYAITmEF~)-Q|_-`L)fZ`M--@gvElDm6heCg=^b>ZT|Z;UB9rf z@IUqXwdvXEnVG5S>1)9L-&DiaT7B~ zU1RoyiUh)YenL4Vp%`+_(i4h+A0;9eMZ|xLAPpZIuRZ&wvWBMjZ{NRvUshILT2l7z z-Mj64=dFB|--YxC1$^Uq_JeO9b{3>`<)YhjabI#1zvRZZB`*tdo)@O2rM-CZA~`wvnz~PkeSyVdv%?~v zhrYfx@6l-VwRs=)G&3UNS!meP;3qM`!NCt6JPZg3xF3|K8dfD6*(e*?ARAFH9a8nr z)$aV>-D$^rxt4LEe&OEU-l_NBgm{GiH)-$S;BZaa+uGV%SXlfwX@6v>nPF5&P*+)3 zSNtO*`A1lQz`;tOp*mrt^}8EjWMrgkV07oso&TxbD=8_-%gbMD_fk?);{T=H3kwSi z3J6|n_uSmvoSd8-930oM{k3Y(%*@Qdz(7w=PeV&jL;XK&djcs50SqPpz!?noKb?D0 z0Qf(sd&vJz-T(h}?m0E$S#@iQ2L8XC`%fifZ&fiQY@%?DQ%raE`*J}Hzt z^i@V&&g@TpP9Q*UMuz|S={QhGD36SoKAo0d(`k%~`FoR41Kea>T_PO_17G7>9W~*m+ zqcve(>!}Xq(L5RVUxYek2qrbXc*8>c=erPMpyMv7X-=gY2AsR4Md{wVWu*m!YK*K! zySo)t<%GfAG7`qYmHhg}@`_}R%tj=|-$bXfoGf~u{c76B<=;vGGCYV1uPuB~J7M8- zP-kSY(p@(ny!WB*yT7d;sqmZMrA-Mhg2b8|72X``>{+Z=s8{5fS?0*zsQA%#MN#Cd zH>_L%f?ZEoM-Zm>DIFbTQrSnH@0{~MR6#W@dnq3E6{WrOvC=oyp|8ODX@pasp94?Q z!@re~AoJDrp^16c1`=bw`0hH%i%Om2&K9XL70iSbp4ImEv6|x*7&6dZu>X6!YjfyZ z2@MiWG%Pt}E~U$wDx!pKp|BsD&Rz2%)%50`&<=J-8 z7*BJbt&NquzKqB57=r7=wOLq2xIE~Y@yGv0xljlk_Y{t$9_`RXI#-X$-XvVH^(>{X ziQId8qBDQfT=fjWwX~VoKy~`K8wKad(?(jULWLlqVKp3o`E=CcbgB%$f>D6JWa1cd z^)bMyso0IAc*@ER#&F(IbWQz)=w4<0J%f#;aE=e^*I=y5U<17QQ{=+e*!QY>VFa7w zOeP9fOc#yaCdflsvn-hlIXn&(*69&qca3N2-~d1v<@A^onjIpkvO17Y7h81yU3p4;Sw9ztlYpx5AQyy=5JVhz;IpgE+dLP=17;uH z7X7WE41pS{os442S# zfXT`gKv$w1h1(sT`%1Y1^i|je?PVP59&clXt^LNH=AuPoH-xL5ce$FZq+s;Rz|axa zBe8};WBs~b>ll5I-tz9S?&Il61s^;L^rXG8oPVl6=A)|%v!b=OVKCykNr6khU}Im( zK~5Z-$oe^jCN)iP^({(LJtmd&VQU$wmBu194zqK@;0+7!^p|Ij#Z%{foTZS2>dj$${H8KDNDdgc97+OdwSnlYU{HqYp zV9RsaYjr{kY#TbG$S(03GyEfROct>3ul;oCOCyxn#WIfVl;~c@+>Bmh1f{Agn;&CD zP~7yOV?ZJPI9h(Diw0B%QqfV1w%7)f{2;(;TP^?5hTUAB=JR4h+&A6OwhS6VM%JYh zp+I{0*{KFTIm27X=QqvAI6r z|E=?RH+7i$>FiKLwr=7+`jVx`*0KKe+uJnG2AA8=<7fp4b%HM$MCF1Dd)+T?{3sEW zyC|*$IlGZsl?r&*ur6HouxdYRr(sVA7XNe2>n0r;n78 zbgwWO0HC3=od+;U_W zwv4(aN$3%V{VVoPi!8DY9^NU7>?sLJ+zKC_Mk#THBGf`}Jka*4)js&G{XqK8-O8hDU5&cGY7p?s{%As4Srgofv9 z(E*g@jq&ei;w#VM%Mn3vC+xv*BNKtUAho-v(RVMp@BVvrw@s78QWjWix97(Nl=lX! zl|%;c3sB;rhj)mEaX7gLLFZfK%8nc&DN;p9=-oV$i)GjXhN2t);5YE_+M>TyCDEuN z;pdMpVoX+Zitli8EJGxmWh7Vko9;{B&yYbXnVZR`nJG@10Y{*J$U9fdW__gr@(q#i zp5Sm%AWuh36F$*8C`{@>P$igIffG56r}$Gve#nPh$5L)NlI+k^oa6mT)slZQz8r{( zVJwOv;>5}kGGE@;!M>EV_#0yFk!I~xXF>LWyn2~*av2#~ny6c!IF1vrO@W=e;i$`8 znVDS71zy^mQ;X{&sRgKCXj!N8suQg2fp+U$s12_!GB=Q7S3I1&DfsgAl^;W@7YOc= z=W)oH6qK17*Ka7@lorKAeP15wz(hR?y+3g$U5z+pI_>`4yw=zlvX<`JCu}st@r|$h3q2m3qlH0M=M7Ug!EGi-*AI`KG zM5@L4YsU1nGVAPY>I|l`m_Nax)tOOGagTzhGWqi%o`Hzk-q#V;@g2^;`});-j(lp zKQrD^kz{RH=Wk`^Guou_Jpg$I!iIsjTtY_NgVNnz1xgo40X=Wa!eC--;{9K5KN07s zr04N`y*8+!Ur~8_LItF=h34K=D&Ab8za-VeWXrHpJLd(DnTmNH5P6_ruFLswWS;4* zx2UGVdl$v92k)3}h(pH3gKdN;AC-i?5ej9NpaI9y?-rniN;#_`o_J`JW1*}bl|Dhc zfRd!-k6;OCMP$jeES*_&31OjbNi$Hq~fStez+{Or6m z@r~NUx{{~OLLbyC8ij=F^@N=--eH)_Z#)2dE<@296!aZyk z0p<_7%!N`Uptv`rOBYBATjbebIgMf^T}5>jUlmBN^qT^;!7KzOp2oF@?DAe*uZLX$$w}O=jU(^ALU zQDh4M9GA7^Pd}PueKg-Ix6rS$8miQ8sTRwka*c-xh<`dlL7Yjcp4ir`hSh(t(ffMK zk9nPRPn@!^J>_L=rT1lx?@*n;Z7r))>3t+X>;pUzu5l%;Hs1UczK6!E|74L1Z4bJ zwREr1XRb27qIGDFYGMZp2?Wk#Aa!%KWT_2qJ~hoPE&X0kPG$Yl3B1S+AO=z$@>C6? zCk11|1N(DrhnHiguxeh zb~_o_7t;CmOBSNl68<}cQ9YIDWrUU+Va_4L96WgcdrdUS4GZ=OG44% zZ%q&`$p4pfKi{Q%)uqbXt*+FqY1e)2-0Ng_OTCACR>AzmVKRecdP+U!zFjduCsjq$ zjjIp_>1QWTf&|`oirBSpOee7jTv6 zSp^}lBGPtmU^M6pQR)LH_HiUO$q)*9Y_A?ObYqnJDOLL^S4e?1pH|hUbt6NK<%+eM zmsGT&Fy?z5uAVJM2`#Nt{kOx^5@vA82xz--E5HfqdD@tn-I$bBH!xSeW`1DOcZ7?p&;tMg#zbf(WKSz{rlMcu zM)iP*;}BUR%`)k}DrJ9_S%&ZDRgtk@!&M>rW5iUWB>7{P^R*JfNRM4IrGYVo#Awsg z(R)MveUDlv2U};9M&8cj8Hqq;K_E~y*(ZG@BmxP`8AL36GP?{vv%_;6emnJT;*V$% zj2ILi`KCWx1Tq2r04Spg&{1ALBwNxjhu>Q-(yvsX8(W44C>N-75@7V?fX6HuwEC-D z#IPIvH^uugx0714SSKv*Pg)vM*()L$KRYl-jO!mv^gt&~7EorQU)66{DMwU)NI*VF z0D-8$It1{&YsjrnzCY>q3(dh>S3`}9!`GKe|^X1)-nuujYCH{nOO4>!Uh*KMC89oh9kPM}9gvo9kzZwBL&#U@kz zhvx22-+jCjdiedR7}fsy7UaQ$*icy7e)4Cw+7mUcCdR0&ZE& zV*S_Tvi91m_galq+SvCybE~_R_bVfj)fC%cs`(!td&3lUqy7wd_Je_qwRdr=DADza z=UcuD8xW^`u-aNe#9puBp|Q!~=BU#6^Bv)Thu{9jP+ZPY_4}Z`F9FubW01P*O=NuhH{wO*;sv|$X{BTH4!(z4P;igVx{0U2wp`?H|n?l$%IZ=qrc^R zetu0l^&sqN+n*p;enL%F#1>A%d^R4c{M;6M8~o*u@w1-^&;EouAieJ*JKulP;W*Y? zqP?&`W7Ym+oOL#N_{){@!sO-&Y-MX+8ObL;KEZOv@%HzFkLOW*rv)k(;bUiR0jDX+ zF!%Ny@PipW!}F-IqvsTtPGje!Kh6n@XYneR_0KNJs8(v)PT}SIc1suOgp2NH?lqLZ z0|;Y(^MCwR{@dzow89>rbBE*V^%!mD+rKjISF3SX!auHtDE~En{6p-t0F^iwxPN|` z^H0C}AMk%W_nH~TE9%()IQNVutD5n2qW0YxCfr(-1SQ|1v(>lHCCF7Re2std=%oqs z7EA9)-Z03NvYiUoc~n3xZBIs;Df4EbVt=YluBeTbk6K4Gysa_o#D=eUKC z+q3-a&Z5|x^;mRrz)aXSayU@;E(l7lgn6=2ximz7eq*$p@x=Q-&b|MK3n9Wse|GCr4+{iQ<$RRo^6g7&TDgr4#=Bj?LM#_SyOSRrk_A2s`F$IanAYA~C=1A3 zA4<5{*pvWZhL)|v;vyTa;>N1qPDK94x&I5^dK=%;HvA~A{UsTMxFdEaF+?Q9M5ULa^5D85x-k*3uqMnCUd@v~+szUmkVN}}iOx3~!fNT)TexENs z^&Oeithl(@zf>rSHk^2i{gErN6Q@w6R|%U>5hEheZ{1{zkqtIjkQLs|6)l{s9n=p} zv*MC6l=&fCT}JckBDG2G-EL}uLa4!Ut2{Aig-n`9q!jdISq(IHoA7ApS3c)ufir7B zeDo@#MELba)CDr@$mSFsvdS1_uu8;X8J+>k@`tRVbFFa57!Gk-Zz)51cd8my=JC!$ik##bXD)A0lBmB(KQbiSDY%yCnV+Z0hg*m(Qr~zHo#)~704n}j zAW|UyStP*uJi-^MO7_ekY9kAsSO%Mtc+?~75Me!6S8VUca%0atAWMhveiH7Wg zj9qeH+N#hIT60U-IevbM^X>!{4)fR|6aZVd6TOZNCo$oKxV)zlVDTps&}4sFINRW! z70_1hkok{1c{wUVOx&41COCDwAZ|hZJ0=l>1>w-Jscj5FsLlI%0N-_Of0VgEUm7|O zS@Jfroy#&$;CWg@w{%;dNOW_lWL)gB#nN2vGm&ua z@KLCPa-ZP7T|F4R{bwlY*_ji8XP*zB*g6P{iqzWsbwHiqj8Ms{N~kUQiVyn~}0=%g)Id*1YpgkA#?Q{kRoOv9MWRcggf$IGN990f_ZC(lLlMWDp+;X^K2 zRSc6@AhKDyFrd?PZFI&nBhig3q+^a6XirHBu3BRT)AqAAOC$#wxFGC)QfG8aD{a#{ zl9<~d7=)^!Sc81}2ICH%ck+#T{)F`xxdt1j!>9(hh%vMpd{JzM+^W68Px)ZSg1*EPB&vN3%?YS4b|U8B3g& z0@2V>1tp)-TFS^I>9ojCP*T@<*qHabhu27lNGByoknb2gfK9wF&7&!GL?DDr;;1er zDz1vQgQIOsODSk`_;^ZdjY;wwS$TkwkTLw|1-?u7#NE6{kMvc3BD;7uMH;7zMs|DU zNBVk|kPl;43EmSgCFx%hyzW(~dDgNYb#$@urc|h6ye+G!A1Ra?!|terA|8lo68#~| zcDh%=(XF@sW=YN4x)1z48(&|~pvRauOEWz@SbszK%F`-;4d!+gRfUj8X}n|@n7lQu z@FA(+XN1}Ih1gW{G*tClhV}Pjzrf0kiamuGQWlDRnL4IW447lt?o=J#j7&ZB{X%MA zqd=cE32k2=t*XLogV>uq@!_P*i<_Stg!1SP)De#04R#)o@r3$QUe>H*J>E7P^$}{X z#cBVR1t$@5?T?Tx*AMU0h6^?d;J zodDJ95*sw5FK&b2I}&J6;*jSIB{SI!ru(L96WHEs$v*so;o%C$+H@CN+YjR}Oh(bh zh$P-qi5ES4*1J0XxhLj2M2CV1k?E$JHWvBMzmU1l6rX!c&>__6!cti2zV}By7mMc~ z+(bg#3%X7ESr!2`MN0(_x?8Ea99b*<4@3Iw{oe=9hNUpJVvON6qNbdrcHt}5LK+z$ z4S#RA{`5s}M)1qxuKk_cf5OI5#iy!uikXeOAF z{KjDbaRd2J);>E2DV0IQX}rOq1kdMBa)+aJi^x)j?ll7J;-u65a6hK%p)do-d6fTQ zLY0E${XXI-riVmgtOXsg??7}z+mp&aSAi=07eRf`H`|B)0Lvl=8~-kkJ7alP%uW=2 z+KuPmv#bLzOEnW;D+aVZY2yr}%&UxDJd2=gYXH+o&$f^T*9XuqT%`hx`>%)f0?}ON z#kE_H9SF_+4ko{&WdEA!j)l-Zc9cVK0d`V-VfH@T$4?IaM*1FY#)vr5zjy37tfLHz z|7+id^8Z(=1P4tqc_RvQU_4C)(WpGJH!JXln~9ewj1Y&X90h z6{DhtAOXlVwrfs&TDJDyQ)Xfu7{S&R5Sx}SBz8O>X1>(<+$P&o>70v)8-w4eA(}&A zC4!$<^rcHk#k5-}j2-LW&z4g-;z0N)#HaSpLtn_q;z*5l)2d=~@6*kr`8bgS|G=5L=!#P*fU0d?re;aL*2+z zi9Uk}XKUtEbejvy+qU+Io8u&CHSFfK95itQ55Y%{0#C$=41RZ+8c1j>ku}-kZj?rA zFy4wbCQ3-Cvwq)TGtm>h++#nl9lfpX577=}?ThOF&?|s`sIKbDszPeo+2Eqx1%S=v zK1MgT>QxajRm5a>^?Hu?Qv7Z=WYt0k5g!PVHV0zCjJKl3F^M`!M|l(rFyb5+jJdKF;##lz!3lY&L2`}Kngq*j}=Gah>v0( zXT-XM)QFCEsrdG}nychP;v^xcB5|ORTFa0}@0LN$5;1#VW7?G>iOcouXRwlNAz115e|6B7b3%;_nDg@Og5k@#3SB#uk`#@pKN##ckBb~+=ii2558g*dcY zsNnJ1Ff@G7%(~O8m6BooPIL-?%aDLgNV6t0=TrruR{ssI-6$>Q}Sjvxm#2D-B*dWbhkd2J` zysI0tT^@rf60RLla48YUfJb`5vx+d`oH#!e6uxJ4;|$Kph#~Vtfn@MtEj;8N9_oe% zkD!SB@Q5@#@nd7eJ3MKRF*w2)G=itd!IPihk$%QVIuj~#u9&aJq@uly0wz?vU+H7M zGQ^lbC()J{vG)XU;wcyb0PH6K7dCtOt2+)`D3uh*XM-3%tCa{2Lvdt)tc>CO{bPUk z?_yAc%YxAo_-~>c-^5P7-Gq*d(~V2;j!VjnOKFW0r0JT4nEF7_C#qzYC9 z%;Xqf-N%jJ-WXTj7+0SeJ-jlCW+Vy~fOI6@=|)E1@kJm|pDwbbct1<#)nFaBN0uO{ z<==N(h>VFg@Jym6OwdUr-K5C~-c)9iRBO`wuQ93HBuuN6q7+XS0{rpBB0?rD{!ZAv z!{38WGDqC;FE#yTFwy0R{!9%T$$&^1;Dn;@>gI^&HDjGp3N`5nDDS|!;9We; z5zPYitXv?Bt-~_)x5Z-_go|8kxE$Q&2wf&Jb&1l!%Dv?A{C--agG;gs>M{B>a-9t^ z$X|#lR?tq2uqwMJ7qXBHJA3Dm%^yQ%Ys+HWm}DEfFkE_@#8^QQBTn(?#@zTz+y272 z%QLjYSOx)JN zFfI^oIOLNr)7)5o@;S}OYVmFjW~)c>^P}b5D95W22l{`ud-oA|Hg4<#N{>7gIn42R zW0^>KspO?Ym$9rHiU^wmY5#U-RDT8jZ-upRi3DrIuWU;)id)Pf9lAlnO23@A-^gyS zW=9n*=;;_`9OYT704G@^@Z{#vr8^U2S4aHT;+E~Z=t#J`R~2q8t%)vgp@HGGkJ0@t z)_FwIi~KT?YuKdapwIUYzgC*nSS=1Zj~_@+hz@LhkD7JCamu-<6&LZ^&+xggsgKTR zJaVSLs)Z98vdf8Tc$?Np?-AHHSNGFqEmjuMEr4#$18x41i>>Se9 z-D=(UQ&8AXAc2?Bp8iuw1@5|o8@`JhCT&~(#kfFjT$ktw+mv&n^rD;5OH;;`=nU-` zT#rYN2XVQF{h=EnL&zg;5m5(?SF>*W>E`y3Z?Tx$Q?e}T^DK~*hxQ;@#|C>EZGK15 zZ^!xXJlDpV^5M)X6I#}`HQVe@H9W!v4cz30o5q!58cV{}cMOd@e4Ji#FVxx$VA;0prJIgc3oB5!7TMhj^$hp-emCV_oQ`uGp9>6*eK6&jj@3Wt zc0u;O<~oBGSRl^#7Oxp@kJYlOson27yT+UDCH5}3N<4I>syM%|^(($( zakKN*9-)SBKMql&mPqt1V%CNJpiz6biNZ8Zn~V&B`KgIWV4j{W_Si7O)en0ujvjRJ z`NTR_JP}40`@v|gwE7R175{n4Jm@Xz6x^{`Eeuv3TRa?7-os;e&;ly!PQafKY{NT#h+Z15uGi@NxqrdS_y+zsO+OrB(K_>owz>U`S~Ny*V!ZlDE(U#ckKNubYU+b#wC zI6e^Lg@-qwJNLvNROtLj2mxrHKVbT?|8sFW>-qNUUN0ce8SvbHHmXHzKa1)@TWSl32j}!SIT%VI27`)%Csf|#@XM6wf5Bt@f{zNvANN9#2}i^k6IeBC4iw)cen~pd zz>vLxsj{>+LXe_<8kXz{dYo`_1o;tu#v>$$yj<^B?flyeerV~Qhy!!~fSI(LbKv1| zp0Dl@p>#4|={3;;{jUsnUfrd_r80rpGos!Yrrq;Oo4OweQXym0vA{Z_Ufr)Ge6KsD zV%js|KVd03yX}BGgaJGPC2l$c1ejmo94&nPX{WTLJfQaFNAj=~) zh8r`nG5iP~YDAb*u+Z+T4tNiD_t40p{qB+TGMUE##J%D=VC)IGk>H)R8g_iP~jZgWBsb4 z#G0`6p)6=zRudOam@YRf6u|2}Trae1@vv(h3vPp-8-F~*$h8)Ng9vQsi|<>%%IG)n&`(nkc&eQD{D^TiwpR{0Q=vIc#8`k1CwLa?y1@4J2V0a5C#C0Q7MH1jEnnrM zzo}Xwn5sjRdDx?=U;9So#s#Eosh4dZf4o!ih(|(Awqwm3pP4X1U5yQK078~B7 z{1ybT)>>x)%TD=0PFZXN{AS9D|e9$wYFs9d7u`now z`^`vZ(8l<;cR_z`1HiAbJ`F(v3P7Fsxm0_L7jF8E1jR_YslOR5hYrdd&Nn~#b@=y1 zT>xM$AG}~&uPEh+vd)P09yey%%A55X4_45Ynzp|H^+Shi=An9oU&v&M5g#z zqsACg`Fm#T0AmzOy`WjW_0xU~yNE_~=h&SuWv;AIeE9{#eg+YyLn6fgaqj7MVc7v) zWoh$RR{AZcsKq+I0$o}2pA<^h#VNFL!F9N)1oOXZuVa8$a8-K3c4Hw0B|6nmao-Lz zqan)5O{vhC_{W%jVV#?TOTx*j(BFAk+QfiUoCriPkeWBuN1DgW^JTi_M(5L!X4InS zLcPxN10>RUODu!D-L}kcMlF-s4P_kB=Awcd=kxBOW6eca03>N)lB9Pr+EmSZ8dgn3 z{E{tAoXX6P+~`8EG=Db6NkurLNL|I>=HB+B_w^+F`Bk^Jc7tnkqctBtU`i?ZPzfD$ z{;10qHX*|e1d`Vb+z=MhgG=tw3FKrjzl@880OJ@cd z;=R>o@p?s%Dq1VhYsHy`bAPKZ?y*0NyTbM+UJ>eH9Xx5-01bKFygH_xT#;4Cr=N42 zQihsaYDBI)v!(p~N4?UUW}M?aKR&Z%MMDU0kCeK!+IW6>Kl~tmbK|Bdm&my>$%}aA zqb@f;6XGH9YEV4MZI+1InD@loi7LG!q6Xr{w4Ws&Y!A-o3`N<0IGhUg@=zE1ZLtak zi9Q)Q{C-$0%AKTlk0xF>-*Z@GOlR!38f#9!xh8MyzPIc$n*TrqC>JQ7YeK{;{hW2T z{TreWV_c=MYbrv+NRDpVdrYY5TFotKmPtsw>FQPA4df(PZ$H&ObfkOs8u$`K{?>N_(1T6mlR&ca$LM z-{0NCqt`9n#cvbzMfp*I%!2a`J;vGtW`VA3-XG#a4|DPj9 z;C9c+UBMm~;*Zu80AU=OTTjmgdf9 zDp4wtc-r`5a(@Iynh~<5-Oi7A6S%_*EgfM&3hK@}^|KVTU*9lGL4*2{aSmnqTT|N- zuwE*yBfJ)wUUa+mp@dN`L3$8;_h;Yfz3K?r0bK)%K%8Dx4R2{FRG3e2xZO#B;$r*G zGr%#v$uQZafYps-fsvJFKkDI;Rd2k(Ln5iXj&S>@ZYIve`hm)>=^7@gtfr|XvOMc4 zFQUnXq&Z(2`0euAEEhnrWp@h==v|ps!`?Z1m=ellAwuw(K?$1>QLIsblsVgYtKM=>jPFI^4Rli%^wKJ>P?`uZo4G z;%OgzgM^Nu^rb7SOkd^!57PBY8D zyQAh&iD_2v-}f_?5=>venJW4TBMvZOVw&d^MuZTNpSbQBp7%492=#>VrFJU4SJ0(* zrQ)*#m^v;oLa=`MyFTTpU@i$W?6o=39fZZ&6atTI=Du*3-N5XQ;(=%$xVOxQJ1S% zwp<)VWWK`E6)4Ksg?bs>77et#x^HkJaPBx>u)*8>@Zn7xnoVa~Spm$@PlKpz@We^z zz=9}C*F&4kL`UX-{dbfv(1}RLKM9Og=6VT7vagX&^s_f^M)T9srItsS@HTa$!>&e_; zy}Wz;E`(DpH41^4fw9BE7kAodXEsksum%q(t?_7zw!B!u6u$$XALlhPsjTt4G83<} zV}OwPKQ(Cw!m2F_f+_$Q2B0#n=h6dW5fb`VM8l8FSRLnIVs6cJQ26!d7iYQOs@M{J zSTxKe)?E630nI=%zvE2KqJ&k_JLJ{IcEOFJf@}DrA3XqoFk-=Q#vY(xTXl&RW&zWR z6CEkr*6+s!K5#yZ#m_14Uy~`PZ;XO~o8C+|)<@oyY`cUQ)p&tCZVrai7&@j65X3KT z_L9Q}t>|tKc9#*C^p?B4-khe133zx-Xs>q+4}fSF1fX=x-d$KRFA6%O0D!Oqpa+31 zdrZL>2btLaV76s@JLZ{k^u5jyGq(wB0D>b!&0fHyof#gg`17Lp8X9`8C#6-O@}1fDM3`FHIZok0LU1O0W8qND9Bs=1)%&n&QO%VTUkPFDTQaJ)JJPBQJvg z&W`BFDx3rkq{H>thzz;}5VS%#?1MF&Vgy1Xgz*h+xdfzPV>S}bH>83|qypJ#S`&^V zIa;3w9)KL_!VfitXL$hxw4+{tWVDGSzY*Lo2IENx1VQkFK_G-oR6#eSitSxh52%() z7{GVA1P#0a2`D7y6%#*H!xL4*K8R17wPG)J;UdO_Ai{-QIK?fZ0DEzv07fCwwV+8T z24gseP{0Hg$O1ahgE5F7B7MP?j87#vnoo}6luSV}aD!t^0TYs>ozZ1ozGFz@WlV5K z49sFJHU$FI7jfz3UfLx~Oy!?#;eH+CN%Z4C2IS$)WK3~DY=~k^oIu}{T5pv904f1M z4Cq3XttFQcq-%5_MT+AJexOT?;4`G7Qji$g45k*w=7)UoJ4fR0O8;h!}wu=!8lrVV0y~ej)pqA^S)G_)L*Z7=VdcW4Yx85}-pp z#6$GuCovJuAecidxL7NggD0dyJ2)iLO=N1SW_Fh6MlgWhSwb7W=4XxnsDZ+xQUc;t zP7;UCSnkP$5*&iKnS{h8CtCESKm0>Hv?hy|A>mv@$8Cfh$l4&pP>xpULmX*dA}H{j zLR}QbdWI2u3R44wffvaH1NdA^ zr~r=H1!tziKdb_1E-IrEPB<9ZM!-Ti000%7Lo?}UA66uGY8ZX0NLaw;h>q%|_Gp6Y zX;W(isuG0}BB2s;3!k=60Z5}uRNf>wC`+IMEeK~=Xv05L)wtTt zl<)v7NDM6W2uzp)H^@UeOv7wE#02=lI?Tf{_+}CzD=S`Srh*6(P);*^=YtC7sm^P^ z@~pJtsXPvBP1GSQ++iN>p=5rQ9Q*>i#)NlO0<~pj9OlI|{DU`Stj4Y?OjH9QJb@HY zLpdCdFPOs@Oo29NLrj?Fjy~aOa!t)%(?)s)w3h0$%51!Dx&@1~h>8elPfjulSBH`IayEW&rn^ zullYp`<`$5wlDm~@Asl__sXyRvTp`t0*dH@1>A4@u45CFFa7#20SoZ^7BB*P?*J!o z0xvKFkFO5o?MyV}Lq?!t4XZFJpMx=+#wFJ@4u>U$RAs6x>AF})!vLeGTcj8|JG&1-`rTH?l zB)6|6U$XjUvL+jF{a$he3vErfC0rJRT$V8+@jz@mF6HemOIUzQC4pT$!9S=29LI4f zE*j&N=^dMc8a_nyPA>pdFHERyvZCfO+rUBrPw+_J-@TXe~T70^LChyqLufG?c?LnU5r<_ZDl7W3SRu0`6jS1dFB$rW16 zZ8X;{KF=)Pitcq&phD-igu@l*2zjtqjKM$XgE%(~h73R|%!5Dp!#$)K zO!z`OWWjo{K*9llFO);so^9IJ^V;6?OKXKb=RyRKQ|cC`H2*8LwyBCSMa}sqe*)+l zPfEgGRnJud5N?DTqlFy&gG^rZdS=iAH~|&-u1nPLKM-5WvI9LJgEP|e=OS}5!*pxt zvo06_PkkzqwyuxbZNGeROuT4}iouN5=#3_H#ck_Jz;Z2gWmpixKRg~(XKQd6bIb^nSx4DYfuz)!cez_!(JYhvOfZY=iSh*MM^=;~UOG_%+1o`j>yZlq4?r*t;^d_Zg{UQFyB)bfTb z{DV2LHeqLoOOG{KANG}2hw0ksQ~>ZU=JpZoHmWkkubPCg66+gtHa725a0c!nL@jP0 zL-0a3!lw7JimIAIHd_}3eKtefHa1gqBx$dyckh&ahxbyLE4m7Uy0WXg;`ME5*Do+^ zOB}$ET7VWXOjyLiKe&Q?w>JD0cuwCphT=vE@QE|vtbZ%TE%L5_=QmGNbI>*g$9gQt zCM{zfm@+hUP1J@rhs81cgJpLAxP$M8VS}y;Qnyl2fB@xd&pyQ!PHBt7xOPhUO!T(m z(zia*7)>xhQa?mQmjyTcLk_d6N@4?%-#7EebOB5u35Y{&LXSh-0s zuH!dilg(1L&oYE^( zTwxaWS%`x;nwu6}!-NUT9ss1Ujoa1`AT&%o^htE9S9HWbsNJkHdaWDEbW6ICC-zia z0bCfuKQD!JM3iREIj6t>xTkB>vA={p%<;|Dv4=z0QUBaV{E|dB#peFQ!eu+8G`bhQ zHrpb0HEYG&=E9Ipb5dmbC*iuc!!~6z#W?8l&GB-x-b=fBV5dMGRC2W0!kUR9!cvImD~H@bvUjm_j+9b2``iBxS)bpmDVK4aBVgDCoFS zq{2V6L&=x<$y=wvue@Z}L#D>eV zM4`LJHH2`}2mH3f9Klz2#25Th5I~#br>`T$%AJAgHQlh^I-TG7yTim(S9Nsjm^Q~m z5d?l&u){y}aom^x*W7Pix7+;9uX{^Sx}}deQpo((J^a^GWxFR)*w2o@YY^_?l2NRH zAW-a5BzonS$?7*^=BK>w<9$+yJ3QFSrW1v~p}`gi-gnph?%O>J)<^-0L<;yqINXCd z$O3^q1QlFEJG6r}$ofP4fIKk0n1Ta7d_x#W$>mFu3&aKl62%t5A*}yH?c4tOyI$Rg zZq!eCQ@pJum_AXUn(rMyKmZUpkYGWB2N5PD*kDWpg%2S{9LUh2M2izZ5@g>|bfg9Ed6Y}I3x{3fAaI4mCU=@C(h_uoNMWKg(9zrHnx|FF! zRLVd_w6TT%3Bd)lY9(npaKOKRTfv4EJC>W|LZuc~!dmB_SR4#d#1Y4GE;;BRLyo<*Ry3bESm4ToTr=Nbn5e)zp z%&`Ih0tM2Cj)6i+$Djy2D6=C5NlbIAEh^!Hpf_rn1*`(RqC(9(@yyd86Oluaxgo~_ zG%P_0x&j_}t^nyp6wp8e1+WN(G)U?ur7Ti~iewIlbfOSwNr61rrkaW{*oGJ?syOBw z3;;j|7J;|~z)LX2ENB(4a79zkT_fVnw}Dour4|;pBJH0Pc}-T?+W4%^&*d&PtWxWy zy(k7~;ISm67B4UZjjAL?R>*44BiF8I5z2HqH~!(r-GBVyM>h_%u_j4@3Q1=|03M+K zXAS_`ahIQd+ARbC0})iPATrIIZP`1eC?yPt5U>!#fr8Uwt5*Jz=i!e*wyRm%p7l{& zN>8RXWs4|i2A*aP*w$Qv0@wnLE@BS%J#>}gIVqnDQdc<+pePy&Zi*qw18uO$fFM!O z89<-~=J}Ecqf?OwiWC4aW}1Pti7la#Lv9chWl)KTO>hO8Vg|50^rh^%>E4QL$4X8P zXqi_ox9^B@fd?8I`M&4|G|sqK=Rap&uW=S12TAA#=L^*vA6Up-w;}NHg@`ALX{UvP zVy$8yQifP%s0HhGum@$7u~MNM)F_Os3A~b`_1$@I&fz})aqI8&B0p>I8jCmohzxk% zL89l!LGV_IK$9=)c<-vGe)yy&e{a4laK%*zfxyV79d@p%!k}0IkRzOYzL}Wy-k1AD znNE~5R%-hB?;n7>7n3(2ZO?H8G+y=u5(9T+Yboj>Ko@RC0PXDzfrF~x;>yxJ|3w6V z8-z<7aI-IrfMOOwV2UUHfea6>ux=f+ivY)Ezyr$AdI)5I%lgv5#wh^}W&iEv^0qpDqkqZ<7IJI~KQ@pZ)CT?+AOoR&zQAWWdiUm+Hf`$p0 zf*!#TriNoAV-cn0Mhr$KiClb$7wy=Tr<6j9m8ir82EvM3q)jO!@Jb&45s4=}o&}7S zf@2&RcSJ)W3X%^w00g)28zRbajsuJ&BkP#RJ^fCUW68oV@CT7YRKj)u_(YtRVvT=v zqm;FD&?3#!NR^54lN&JswzO4Ag)pIqfNUc#q4h`|auQRawB`Ru`OKy$KsOO#LM65^ z5GvGy79!k8SN;(SX^xXw(WHzn7Zb$4DD!zVB!G6B!2lyZgi(%~Au>(Y%M3cxmbfG* zSZq*7Ti=2lGdJoDLVWi`85&RoRK zc2ZQN`z+}*b9&Q(JS8d*;X<1NNsHltWCLFLf>gl@mZ*Ydr{_}Y&(5l-$lVYgy3pi2 z5yHd76|kpG^(jcx#m`!fRjO^kP2Xyl{5BxLIvL(Y;Fw4#(PO3y~fjU+ZAUU30zp}RzL;w^Y-MP6i=YTJiYU@y7YWv3q+>He;{JWe;91ZOD;1< zo?K%G3zxF+AaGJ4BiA2t8O4tL@;VPaW;@;)wt@BIBxXQlgi0hB|L6yE>l|H1BXOd7 z=ChOwvSQs{8336zbfI_YY2rS$pE<7c2vm@e3;5Chk2b)Hu;%*^4tPbJnO5?qC1T=x zhMBwup@1{0d}08E$G2~dGN@0jYV_VX!md`bAfUp5gsiy|ObCv!s`?OFSh||N7BR3R zB5XjTn$QV}(KAY*Y#e!EyzQ2@z0LbsR`1o?I_5EMw0)4P`q2)86qcNH?G;j(``7&j zWv8JX?TF_#Q71l}JyRTUeD66dismA^ZAn_#DMJtl;mxB3L1ct0#21!6G{c(+@`tFK z)Ea*_K@8wBT|hQ^XjlTrGY<4rJC&R=ujNx<_X}}BfYz1RgQRt35U+d*=I3_!XCa>N zd*6H@7(FBLEC9hSNbu7(S1_^LLv1o&J-=4}7`Za!XAm{enhOUNmc|k?3Yu13$3{;G z&0W0pvm3+&3mhu(!dq{Nn_b3?=bqXZ&3612zKG^rCz~<$G+916at9kWe{7Na5V$hq(I&0X+3; zAOrc&pZ@i?|NZfw|N7Tp4Dr|h{{b)n<&XdTZ~k_my96)+|4;0Ys`;GH0hNvD#;N@h zsT1C=2M)pxXw44XEU{9+E97SVL=X4>v~T%nV+F>*5h7s)S+E6N@C9Ko24&C%9U%p0 z@CI=(2U)NNRj>t_K}H}!2ZeA3?Enqd;H3m_@T_mxB=8_Y!5id39<(9uJct4jX$0Ob z+z4U`XzdUrEujcvruO0GM6e1;u;cPfIrxte7NHH@@D1TG4&`tT=@1SZVGJ6f4)t&k z`OppTFb~}@6M||N`mhk|Fb~oI4fLP}&@KW|4+5QR-v&Yq!T<<>z!mi230TMq5$SA3 zF4hX-1e$L1a!nxE*h0g8v%94`gu`X|Wb<@fLA07i$p^#sCm>@fU$H z7-x|eeNh(w0NI@34}@_UbCD1Ks1FbNuMwH>5wUO8B!V62%nXwc=5*lgQi&j1iq=kn z$h0s7ykZ+vaRj%q#L_T1V38T&5gv _bMn=TR0hfq4?49^>&3@Bj_&U=gA*2_LW; zPtV3Au^<#+4)VbXHt`Jc3+Zq}0t|vp{Ad%1j6((@{r*9V(oxeOa@tIgGTxCNP0|+c z@g!C99uXlL;DH%bav6(|4fNm+8Id5bFZ*DP6~h8DH**;$GdS(B7yaM|laV-S(H{Y_4`eYkmvA(9@*uS@ zAr0ahhT$Q3)7%sQ{5nh^2Cfn?Qdk6G8@ytCbQ8Le(l@~ZIF<7khx0vgkr?w49x_2b zWpO6;U>2d18cCDurc*1e6BevM2ciHL{K2&NGApBN4&H7r2g1<=%I>IP>e6#DpTjX} z!#(ly7UQ!+X^|KI1HmO>50$&{NW#1^Fm*1JvEdh@eoAe(>R%QKF44e;2|FNQ9e7<4r;MKAyGOPZ%gsa zI;$;5&CL^GXLJZ+HgVw|Xlj3q^hg=B_D0e%IP^(n@k5^!5aIw^G*dqN;2-b6IcZT# z{}VvFbWp`?`(o}*p{oV5upq*76V%}!&H)VDbg_^$P8VZN>C{e{6cD5|8q88Yi*OD0 zGfP+0KLeCdsS^#sbnV2{+$8cBJW?P|&W~_G9dH5fD%DaI_3>%@iH^h zL>nbVP4y=KUGzo0)LE;u=z0~loZ#*LWgwXDM-NI1cNMHI)w(buSUYuCiFFo#Fd7s= zKJ|e5u=ExMHC0u$Gz*ngrS(-|b>wn`AS9t1E};@QL0B}hTf^#G$uJ_s6+}6;Lj@5Y zFo93+pgD2zUFQ{E3zA|VuT>+@UVSYK-tI;f;2Zv-9xCAyq*7o9c3Pe6SMB0pJ2YYO z6WN%d7>V-_)W8V&AQvTeRV~&LpB0HP_VzS3(8S16=gSq zJ-32o@zZ7BGaugp5M(wu^8gLfKv~`ORD0IInsv8Gs$SF64c=}F7GS3SA!+@{6@*1A zoc5;w2$nghRz9tEX7_>_$dxknfDO=~U2#@y4Ygt?R%fT}XSok*UrXd*2Nl9W;WW^X z{xzoR)~4=uIr8>B_cl25kxKveEIacve=%p}HE~mSb(zBB8aHTt%>rQu8+Z)>xX_PC zc91exa~=00q_!zKS2;hIG8KVDhnE@q6d-T*bPacBdG>IhmtH5ZcNa?q-p(AvKp;es z);4T+QEGG5a7oK`7e^OFr8FK8;do`z2uqcDnH5!4H(uqp_82!&Vb|9rQW-`-Ai~j) zR)L$m_o2Yo9mRKihp~L|vv}bl8T>$fgRyH-R2Wfrew7e@S(kp%Ha)+fAFg5KzR@E8 zD?t;41r!5#dheIGRCX?cmpC0bCZ*IJ%(8`bF>nWW87H`cEtrCH(i%-TJvkB`@U>|H zz$tO}pmeo_p^AEgElK6HfDO2T5%@h3K~L*6itCXN9u^M(H5hLgapM<u2_MPYP| zRWSn0^B<^TLjH1JW;6KUIEhbKB*FC}Rya8Mm>v;ff%X)Nw^k+f6CS&GhX>h|FZfXF zSBd&Ej|QL}KyV=b4R&JlQHyMn`K^+*GKJwHlQ(mdyd^Dml;br zdJEZ^!#HXYm6hfApS}QBR=^;zZRCUi0DRPsfRs|Z*;O-?m)F9VDYKlHQJ6#2ikA_K z(EtyWF&^KUOHUb|6<0u^x#}9A8oWX?41xo!ncM!g6bm|I5BicVLZKs*p@Z?9Kbe?S zGI{R+kV#pPH#(J3S%=eZm9=yIZ~&HxR3XSz8TQ$hxizIbm{K4HpcT;J z9<0GCn+c)MBC5l3s&!GOQ4*qo@t95Wq76BRzj~)JSgc`g0~R?S-U}jPRRbV^{3_uU zR?e-PIw``y71*V&0l*a6VGN>R8pZ+i4&ry20p7@>jjX*w6xh@v(inFCzQFgCcB}H+!k0q2 z0iX*0!A!fx_!h<|iQpfAU<@*#0cgC&ZT!Y@JjZo>$8CHE#^4dOHpqp1$cenjjr_=q zycdyt$(dZp6+usrT*;e!$OGXY|9Hxm{1L`r2Y9^8z5L5-JOgAL%*njWZ(Pi0+|1Sd z%h7zz-JHkU{LQ^w2Pz!6>r4f>0au6xB!)I}4M4M9p{+;!DBsk?QC!81fyD{pR>G$c z#^BK*J<=t8(kZ>tE&b9lJ<~OP(>cAAva&Dp)()%@Mzy#eU_ zw`*O*T0k7Uf*-PgDJH->Z+Bz`ec1V@*z0-#s2fzSyRWs|U<;gB4}2D1I8;5U=r-W4o-ph2)=*#Y6GM|3jSdfq(C%G z8?{xNwcT&PRrujI)#6R^4@guOhj(2)v%F*S!I^o&A$*zHg4PNBn`;TA|KT2xy(z3W z>7pP2G;kG`I_7zYuNDedvh%Ld0U!2y=77GJg;+i%=*vY=^@7eAB+AO$xC5fINVYW%}eim&Sr@gZ8 zJ4x!{D#EAU-m5;kqJa2j3GwGd1MDYzMR5{nL5L&2cLta%<9=K_-y}0ZA2~l5X_kFA zQ}j#U^pBtPn+f%aee!$f0gwS#Qo;4bBIN<|$2J@0Z@+bN|1ozTVKbi|U8Y2l-r{Ex znZwffLrVG6sNo?Zh+J2{6)Ot}<{!r4x!|Jfzv`+uVeGfRYyiT;KMw#38a#+Fp~8g> z3%>ZLV@!jF6f0UZSYu2hKO8%H{0K6n$dMoa0gVAfGNsB)@Ze=qX%c11JZRA5QHfJz zqcJru`uusYfkdE0eF~jeG%3TQN}DER>a^j*7g4KPy$V1eL9AT6T21vYtf&EA7lKlT z3P6!cmu8iH3pcLZxpaMMt-J7HM5K5XX55%Fuwaid2McBf&l%3bB=e*}W5=-Iojv<1 zglhTe(98%ib1vw)>(tK;P5qMvAce1R_sq!(VUWtTcI~W5DVSv%I(psc9FzkN-?uOn z?~*=F)PujU-&FL)p-kBn2$L$kLXJJV_U#Rgf7ZMC_+QE7Q!*|;GEqEum=>QTsfP{Z zKj>9b#vb}}{>=L=_qRG4cT|ky4Qf#T93zGgUxaf^K^v?ij1W&8gU&>$v{Ho+qx2(2 zK~?ZW3K6a714VZOafhNoBV-d6M4X|5mRd=qNMnsQ#^oJn;PFM;c=i3r(Ro06lngx4 z&HzGGki>{F71S(eSNob*lCU+ufJ7VW!l;sH-r6TUYvrA5pcEraW zXxzbvqdM_~UwFrDDHo}6nOanr*%5=9m3v&sV)$O6up2xSvXLFSBNP%GXf z6oCiEKBVWNc&+eFSp9r~VgbtkPD?GJIcByfa*cXw*rh=30uMBbSgPbleQ3%lw;@eA zs;H!)`WC!p$@`P4$j$N11OT{tkP7AeSr8QB^wSSGYm%AI69wtxTS1|ulh7(HhLvo! zZw)X?i`MA79T}UrBCW+Dk9^#3$9#jqL0`}_h(Qb+^f0l;dVnm+Z*3FS zK2&Vy0w|wwQ3)qRm`!)xa+%y0$~~%_vtTWwhY39KAR=?Q9Q~mN8f@U)w?{ks%p=c{ zb4G7hm0x5pX>R<(Pv`&t_`{C^0C1qq#s(FVPRI|?GlxN0%;U*HzXm%jLwMVrRGMK0 zGx>2~M7P!@pWse>@loAgm)@Uk+qij#59tg%%=m5iA9g5yQ}Z1?PWjMQdXFXeT8htQ z(b{nUMfy;1Q%s2-XoF1#2Z@3XSpY0BPs6W=f{-!O7^Dq6*)CDWD~c1^5f*NQj5`YW zg)%x(omCWYf)uO>^5~*G&M;4VBKaG6SOSkkP){Ztxn3Hw$3Z`E4`{t(VW?X8Js4Ic zbJ=l~)4bsW7U)oPL%@eGi137Bw4((8*qSSJ$buAjXdk2)!YW9VrwSUy7%fs-jpCq; zU)UjT8<3(Gy?DX@xnwXi8%$wIp7$ffC}xBmp@~h*$dMHaO@?^699Haj6+BXehS+gc z7A6)J9TWr%*=Pqlu2F@83(&_J<0L56 z(w3E>=s7nUFQCp#sP*coN?B?*IkYGi%T%dTpXwB(iUuM??Fvj&DASxoZ+hL@LzAAg z(>P94azDLjsjA8qb{@o?(v&L6R^W}W%%h7WGlC+ZidXEo6)P^K%T+m;Rh1;7B`+}y zlX4nXvG$a#FKjF>&6*UpMsubByCCclwY;S_8MLS8@18OjoEFO1?_VpmDR`lwMd zhfUXM%UMUXrd76iq^(udY7og5Q?$x@!8yX>k3^acM%7^iXpf5*-bSUbbNQ?G0!tD^ zObV9&f;lW6I(1r}I`*;KWo%20no{K!stPR<24wg21!Zg^Zpdx#-Qt-ys-E{P&TSra zN5ai z4av)5R^29Xij}Ga@c8B%R1|v!w?JVr0CX$N3#VuS#AwkJ7HBstR_Cr2?y*&5%u&*6 z%e1HMFi2SP4iN^XwR|u#w@i#t6|dN~yri-(tqe?~ITgs;sRBO2G7ZrgZvwwquO@tq z=BUCKFBy)@hWqAZk06GtIbpIN;_N6WpH<41!*V+PyiP#3)4>1aGIl0F#jv!Zsm1I6 zM1(K#fHX@QQ58Fxd`k>xxXaop>053thl6>`dko!Ct)w9d+2cCpRq>=X-_yY&99mXG>tktH#j2@tox z5t41p1^e9DMJ;-etmK)<=elR~?@r@AR8_B9;#a1)Q>^XkcLx056~RCxE|Ce2bA00! zX)|2joHINlrWrVKC|Da_aEMRY;umK%QK(%JjNd!F`4%}`tgwqpY{KXMCix!!2fjCS zhc(WfrtU~wu2Yz2SLS`D`Jb(x6r58;=TJ2|(GgMrUR0tISonIcz0MGm)0fEUes@ap zJCmBIA?i|p?N|vs;O=3)C|rLk+Ra{&I9#F_Vmj&f3i*xiADiZ6}M4TgG z_K&E3>UsOL-d?%3C=qXV3_O~yhW9b(2W{@87yQm{9|^)o(uc&&ha{G-59aS^^PA^B z+PgQ(?mb`0(|;Wl)k#F@(JcJjB7J#mUwZ3BvhtDep=NAAVdbCSyxXT*^WN?LRCj*h zo*(}zELiW*$6w*(J7oD9Z2nG-EL~5BBvaUPkHc%J{fToQ@0+(bLrlT{4f2o<(;x)F zCw}Nx6{m0skbr;`rhYHReq`i+wPa*)2NHUqDK|qd_g7+fr+54Jft>e!3{ee)@B~so z4dp<374(22w|5OVK@X^SUcq?kVq{wt5_uqEjAMT>=YcMicR<*GotJS3u>$`vC}4De zFvx_4Cxa1)N)wn(*yj<06+$0jJ&(a~g~NdowOIT&gkUI!T=5V@Fg6ju5I^t_C8C7n z)`VAq1)8u2ZYo zfNn^KPEi2nH;G-hgl{o}Rwac7wTFK2VUXts^jCc>^NA~ye^vJXg1Wbgyw{4p*NSC$ zh6~{f86 zXpOg65Ch-~=KuuQ){W!X5S+jk{U(rY6_AQ}hwYb#6u5^?H;S^S2G~U&wTB+5SaFAV zk71~Y`iPC~kOfGTHEnp1RZ#`i(FY|tSqW*43n_sOIfe2F68VLJ*n@2G=!4OSh}F1} zJV`Vj2}u9oZ6v9ZPGN~f36SMzO6T}e=?GYRxK-{5kB@Tyit2)qHTR0JXpi;ie}2c3 zNLdh%FbSJrkYGua-@%lA<&@7wg;sb7HL-<1Vv*%>l~<>cT}5c$Sr{dF3@0;Q8Jh0QI~<1mD7fp)pnUV_j`L8V|{6sNdO6&pb6qw zn7F8v)s&XawU+jUeSH8kmGF+95}A@QnOT>anpv5+xs`h9kqCL3r5O}(zzL%{oSFa! zz)4D;xm>BKVXMhu&zA?2&=Phah(I!%hEbb*cbi+colDW33(dOtM@m5po3_T2J2>n`ROUy$%=Q$pS!u71j?5Nx}L>pexm6J4*Hc8k%SO8DJoKVqRK4BHEcGikuBloP%ece$b@T#G)9+oNnfvaAr7t zU=o})RaBJ-pKS8$9$r*;~f9D!tngP%F7 zJv-`(9@?cGnU9!ArpPG+2|5XvP@H9#sMNCmsH)efCo!dvngZi{Z zq@6LKo_eYb5eW%uo|+H|y$Vom8d-08a&ek+ZcwK+aR+%Ih@mK_v)VYAs+G4YZ}@l> z!1qNh2zYTAtmdhc#9AY%iiZW)s?G|nAu*}bx~JOOlViA(9m%WYnh?bquEu4r)?%zd zma7K=pFonXo3gIZ2M;Xgu7o(Qc$t@*+OST+t!KHf1+fR=nxJSnu{L6^3>j7f`;LJ? z64IKm(1@+s%Bk^6uU`47>zM)g8mxqwu{5%=FIh_-n+JjLZplcgvihzki?Z_ywA)Ig z+_i0iU1ArH?oOkwV27ZU0b)H@vjCEp21kQ0Pw5k$qA0opnam9bq5mc$eL7} zGjpq(m796+%A56CwvJ$`pKG@LN)(&O6#+{Ur3(@*BPnqExDOY(d#0(j>a(%?wYJN= z+!4BJIl6}7yCKmsf#VL2JG}T;ynpJtxOcYzu(v!{w9QMt7KXb(p}SbYyB{&V9YkWN zo4P&wu*f^V#;b`#8;Rwszoha1ys8cYnd_blKa13;UtnyM3@5qO!Zc4_p`h z+noQ~yUj|lH|ae0XT8{Kz+R}p3!Jc2fy*F zupg{{3{1ZxES@NA!aY1pJiMGPiniquz#9k>5c!mHbIBQENw#8%0~CL6*zOpQ9sw^r=NRUyG}%Ed*@P!87&(sPVu zte*%h!t(mFfBcgU{KkV!X~&ViS5aSdjFTSGX@!-<^6STdoWN-urh-h!muwMnoUEg( z$foFD$Ck&CyvC6{$@P2xtbt0jn5@bdp~+jE5>qN47p$iqamRG_$Tf_^Y8wJO2WWw%?8oR#GHr5EX#2V%At(Q zlq|X8%)MRd%h!y~@Px%J3dPLB%`eQBsfB~i9L}a(&i0JPY%IR%jLz9igQoS)Uwq4) z#>|dP#?LItrA*4xEVQVczx-^?uoepBfDhZSHfcA^|GW_ajm(wGheqO%dc2`$9C61x z&iIVJ_}i`L3(-nzXmgMch2R9i&<+!pcp1%!iC_n@49_vy5qS#EB%8}8z0kVc(3afN zgluTr;0py&0Ow%;3K%WKcyR;{)y*L-sqm0wSY6LWZPd}6&{^!zbzvH)p&G2=8n96i zvOycRVGvP}4ftRVr0^TTAxXiU)T+#755Ny@U=YOcKfpBAb8!Jozy@iM2G5EJi_O@L z?bweE*^w>TjU5M!J;OmQwZQkdN-szp*k1z(0px*Bd-|>y!j4%c} zFx~f!-}%k|+!>JE`t9HU?cDsW+yGAC`7PiDj^NXM;0cc3I-t^W@g-q0Ccj}OXrd-; z;wAtP3hWSRzzq&_QYQs*CwQ&fN{zd{{oBEf5E3&ng)jy$4&yN{<1k<3mp5MQ-Frj^s(M35Fjc)sAB-sztX z>Ip9Y>Z4xZrEcoW?cie_7xik)*wIt-~|6LH(%p05Hs9kQ#NdF z;_HkMOzqTAE!9x0b^giOSo!SG?%7QYsM>)vRs`!#12qL9HB@6YSOWmKZVkXsf zz=XOa_%H}WK+`sz5Qluj)1J?xEX@oJ*8Q%$*s(dC!w;VmI-^rM90LHT zqdKeu0ApSdWq#(slIFE@5OY54?e4~~CJN<{58LqDH$B*2?eF}q(E7gbL~ZhcoE_++ zKJ4Q@@Z-4vKtJ|_KfbZyNZ|?}4gmfGK)J3ExsCAx>CaVX()LTv)E@1Wne>Ck>U3fM zL)(BuNW?=v1VlnaL?M6pHKOpUCpV# zzpJl`l8^MQFZ;8<`=oCXm&<~UZ~MTB`<)&8tnd4TU-*-6`VCzB#ZSJ+FYU>n`__;A zys!MvFV;vc{kBW}cDeN0DaFhV#Zf%|9eTf-UqC?r{V*8*N}v8bTK@H~`^-Q8^4%Z( z@Bg{+Z<|gG5DmsO08r52L4*kvE@XI6Ai;(aB~C2(km5y*4hLrBc+p}QW`ktYH}n6)EkqufCl- zZYuw9u*Ml;r3dus)vssY-u-*{@#W8_U*G#+O z1{-wnK?oz1a6$?zwD3Xr7F%@jMHpk0aYhf-X5;-ZSB(BOPaiC%W6m2Tt zg%Ade?<+COypK#X)0_`YHQQ{DO*i9A4^BDl3*m(V%5sgVJ^7qT&p*ZLlc+%n4YaUB zvnsSpMp0T6wMQXMw980OtF%#&F4alXO(%VdQ=CA(Nz_q2^>ZlyL{Y_b)u2peja0;7 zB}~>?U1hZ-T3yOjS6hMF)zMym`W0AJr5cu`V{c_NSwM@WG+0TUMUmNCBUmMZvaH26 z+iSVqHY{zuH7i`P$OX4sWz+4*Tt?Y#7u`nP?NVNK>$Ue@eDl?JUw-@b_g{bm7IBUKR{B(o{sOIc~aG=JXbYS7KAi@nt{PwqXHy!eWd;`us3~Uyv8Wiw8=s|0fgE9| z-~kLDNF^2P2!jsdAP-RxB@C``1MmP~igt`43eyWILjaKC9CYwO6vj{x51^wMPnd%}JOLCYy6}lHoM8>= zN5vfOu!jKHz&eB>geM#W9RvyE7|VD@pQO==P;BEA3o?q|bxi@^kX;zm;fjI~(TGS? z;t~ni#22zrif=q*A`4OoS!AIHbg)MPhgifTCUIb-7)MgJp*a8);2fq9%L@Ksg|KWO z9ACgj{+-O%&re9`f^$5994S;`NQPO= zV*=qHPbf$M(gDbWMByI+EJ!G@@r8c~@oNVEF-A3h^38%669D2QXDrW|5OoGH1@`zt zLPEigmH_}3-~b9f0iaKQmh+zo2`B)lSrB#p000L~=tA#F%zTD(oDxN+6wbi{;Dw=vXnO*C_KW0}Dssd%F0QiDGq?Ho~7T_9d+h#Xc z=v4rKRjd^)h&hIVkPXOU90_#-I&hGMcorlZzAS`1mWWrq0)Vdo@GD>i+cG)eV-Vmt zhcT+TRD-}X1&{q|SS7nogH-k)fgLRW064IYRXhL#vH%B{KwA*e1`@KSovdmz0FEyL zuNB=e2oL@-1pqA8AdN-iZug4XzWx;ezYT6u4^oU{D3-B~4cHIlvDKcmAT|bp#WuoH z0BQs?D|7gU1=IQzeBi?sQ}Dz+1|gLKz``H<@CPl&T97LIgKRN1Ml`KkkO^?(m}*U` zDXhV?y4p1)`Q2}SD^d<)q~HNOvxY%JF^_+MgPjrZhFB3R#Blf*0ActC27E$c{`$88 z7}hX{Jq%(I7sM3$00$VVU=47z%o@Qkh!cAB6Bt`qD>UBlKRVn_9J3PuP!LBy`T>q= z4!Ouj?n#nm%w!v<4y3>f#*?T2`;RaHAjJk@v5Q}<-xyyw!%cp2Fvfgf090Wgm0WW{ z+MF&}JcxAwaDg~z`V;Y1fxPC;iZ954Bc|XW9Z^85FPWkbZ5TurnSRO~%rS>33}PMk zWeV^DJm8=fn88h%MmOFH*RD+g9RrTAggfGCP>Y(>Q|QJ&_)!gD8zclka2hu(7zrjunAiVZ9u=|%x?ItRxkwrkcS-P32i|*h><6v95t!8eTpy4!Go|gkRLPuhd=m%#iW#j zrlB~8RLl_ygQS9?r6#Lc4f0-}kgx&B@P-PK0=!Y!oaX%?hpjvE^PmqM+w6N~LLNX5 zv38>$Gw+A5Tan!D{sij<5&A(wz;#$2@J_CTBuf?xM4un(xkxOPv* zuVeEc1pSpf$odf{&Vp>+cRbbc|2O{knT~yA9sAfL;}}^P$EK{Js3e5Qh(bg<&cQik zZ?Z$m$V!A9qZ~q~j3n9FWL1dHbw1zkwSK?b_5SDlbN)Ny_If?X;||7gnRgQK2nVEY zVN2)IdD4lU{%;6y0n70D3N8#;1(qj4ju~O{`fy8qp4qpLkgyy(*{oe?7&+^(O8@Uo zJvJSEcBlb|JV{zcINIFck*u0e0ElOzYxk49n61c$IMWR;qWpvbPk?GY_Dxwa{-Jq{ zNHL@mAX0n6G7$fDR0X=tW~;zCNdf?$lIFCd%-7PqV{KpQDmOA#tx zZMTtRN2BE0>6$j=0zc#~MG;s5+2w!*EAifrL^KTwc$}4VMB#01C5tM1&dMWnS&H=J z5m+u`L$zLfPVAjZu*|G69svqM!&OQdwkH|Qn+z?cdd~f~RpMSGN@lo$#!Jh@hM)y5 zNW9a+yel#{(aATaGxpIyp-Gw$#{BNDn#mVHH#CrlDEMrb|!x(0Xm3jsl zM~X(nU70S(5F;kwCPq^5D}@qGY86NV-CYjQG%211uE;QC2Ex?$8GEm$be8f5kr}EF z;~v_lxKg9w{rEx@1)5r`xmclHBVqTb#JeuJc(172<_r%pL^q(5U~X(Y zB^76gFc z>%|b#5_>PBdU(#F$h<$!slPa=-_24^uo50_OLWvMOtTj*O*t1IO@1+GMgR&gxum=> z5>AgWe;skYCEJ15Kc zzLtFvmXrj`{(Q@UYReDpmV<+qLsOQ+8h|2wg+cp>A)It!(EEav-$iMK9N+_9B*{IdgIM^Kw>2jSd%L)C?2Gjjv3t-HZC9PEy zNcWymKWpgP8(Z1$2E<(0i;_jg{57<31i)Gt;v-CoY=8|K1wGV3Xy-7<+Jbx;?G`yk zRmw{*g7Gpk&>!~p4i7Imo_P#H!2+nnph~zCzh)p}n2uH}t63-bULufiH@%3DyoTA% zXdA0tA`}z4T^W4IjgAGEZ`X`JGl$))yX^PQ(;jiFuPuHP4CFUNP z7+?!~Y3vZ1=um(_0HTLbKn4H+`FnsFzzID95oz>?&Q|~XM>{z_`A4U#=`Y8$<3qY# z{oio)$({^i1y@K_RsyF zyZb*^Y1?B*>+Ap4`u{G>&=%^BzxA9@Khnk@(*^@*9UU~X7wwHMJwB1HT>po*-rAhq znb}-lSzlROSy@?LUS9g~V|`(fZd$L;Ez%upx?oM`tLOfgUH$#rx5>%LFaM=hFOPm+ z>hE2DTRZ-?eExOTyC1zHV|1wcKTXV?(C$y)YP_@qpyoT zzb>LSKchAmeSVcoeN{kh%Ij_YZ?gJTLqo$rT{>N@E*UE(^~d_OdtGj{qg7UnR+V;E zRnzflS~U;t83U~xM5nAz%AqG^kRPSd!_P?vU&z4=yvsNV#oh&SM!8Ft@99~ z6;?xA3Dl$^k+YBB-!G`GelE0mDqN%ebalMeuIK&1)mIKej2_ep-5*6I3OTlbc!PX%oRo&Ehq{E}P zoTi^I7e@SEUA`Q~vm$B0XzsF7LXvv1Qko$5B8rz^O>VU;L-EL~EKzD!{E5!pN$)gM ze7t+K|6LCeOYLpW_eD4`g>F~Br^%g8j5?($1As@-y|wMX*VbQ>;R3##-T$$xyHEM} zvi?n6eV$U9bmY7PC$}wt%N!tTXf4uhq7p260_& z`{Sn#+V@l*bTJzmugW(U)jF=-hxj^%jFJ=iy5vW?5y3m`NFLRd+rv74HX5@~A2ceVhEB7} z6pkd85tyO*_MH!>jhKIpj(ApYeq@9t{u+0>Ur;!HZeA1l$(pyaiDG`*`1i;qyP=W~ zzMVqBu4>^mjf9Zpnm^MqQM7_-s+EYkDoZa{vNrfaJU#|rYAh> z!5P}jMQcfMmY+emv#7$jlc;m6{l2+tRXvHJ-{P4czM9Um^Z&c4^`%y5N!X|7F_xW5 z-3Tpa9>p(1Wp$5MqdJApZWs@5M(kgnG5b5*a_i;E_?uf##DPk7N8Ha7?&Or+G7+wS zq1Bw@Z~xXl6YdQANzmwg-sq5Y^85IYe&C<(x$99$99afIYycskkGEHp-NOZoT=HU2 zvgV1pUM4O)bueV$RFZU`%ZRrGLf!@FXTAx7&{rx}zPq%m{)|oJXF>^i%M8QMKNySX zDe2y2XgxXnNyH{_12lp-89>jH%q>e#Wm9^^;l=J#GVnWWnxqJ)r;Ha}h-cD7qm^bC z*uk>z)r)5#m!}}NV23@r2oC6#cJb&BRZ)7E>mgEgcnF_)?3s`~9KQNxta4cqTa2B4 zE!Rce#5O_p4)tEN_HHWk?J^H238(J3o0cp47&LRBq5>dEWj@{d0R+7z59^dD_Zjp}^}%r%XG+}h@B(Vp$Xt6b_ss2z znqH}to=a)z6N8@8`iE_{7nOw}sV186y9piunVE(oYR{D|vIc1o3Pt+2%IC{~ZQG2_=t=m2Kdb)&~^tlV`<{20h-%?YJ_+IHk z_KZ^F;Xe(0YZ7`jL`Ue)*Gd;&%$ zhUJL*yEYd7+rIp%LOU4CE0h47AtqjpRg02fEwP}72tC4rq?!aN3MScaqcCWpDgaR4 zD0^GT#97iC?c+q?uZ!l265dCFF4CGQq;q@Eajew=rAHM%VfK133|u1wO_)x&TLzY0 zMWkLx(%m34)^6hs{<*Ll0$qu}Bk-sBcNrqQ#_6FecouB%MD)N|4y^q2hf}+Z4`@11 zOI|+oy3uOt*ma~{*YSP8{@pUvpRynVkMOo?y5lHzulUKg3Y~3B9hshARI^b`*pxGH8YuA`m3ft0Oqa@{l#1CZz8on z(dPVK)EKs(!(jAht>ydOpD+I;)~6E?YR~bswREd~z4J)Tx4DUrt%t!%Dc(p>N-foee_!)Ogq`ILMB4!cAG0%9$*3pT zNqnEzSg*u4wJ^oAl%n2s*Gjty4^_$;7zo0QXCy4D@aDe5yWJ&@KsYH+e;@%6f@t0g{iCe>7IHDa=H{{&dgB zFTWwpqRBz{Q;?^%86m;ZPCLmn9WJQ(x<0MY3qnzrt^z-8iHhwooTS%+@QMq};2%0E z9B0(XRPw6&i=Se!NbfjlEI2W+V|_I$boi-o0N{x9cK^v|YAw^J5%~=25z)n9ha### zyP*-i-3%8IeTt|uHg}0R_Fc^wY;heuJ=%ch(AMyc#?V&Ux8d(_TGXHP5uS@SGn$`j zYgAvJJiG&>pvOiW&r}IiZ$Ld<1nnrM8hwe$*|VhrkVCw#8i2EFdYTMSV>F>@EX`n? zK=mMhzt!-sj*=*KXS_w0(hHiK?HoUgQW>Q@52{q55<-7(KFDd;Rwt*l$H+ zDC}RUKCZ_*Oq#?pEP5UYiW0$@lUbW~*y-&x{wp(z`2fA8#ca&IhM_R^>>f}AXk$zl zwZajIti|}CDAouUsI*K9lQV_@?}BL{b`zxvY^D{XTWLgH{Ri4c>@dwQhr`@o??G0v zLZdM38ecD~PxUSCpA%*}Ijp8r?8b<;FX0eS1iUNs>|AJHHqQBVu&YrRbQgR<&E%=O ziDQ|G)1rwB6mT;(^^7)!q(W)7=KugN7K+S~4k4F#sFmPPw}gG0!*{785ykL(X7~G- z#2#$3|E(j?sO*1>W%=t^zXUk9cB|2-yaa|&noB528re`B3f~E4(u`3Ni-BA)=1PgV z+7k00yE-RE*aMF?F%k7TS6Ozhdhy)9yWur`59`p#NqYHPCQ=qb=#lchFLO^t0x6Ar zV32i3qeYCr7#dv({f=W1>jO=tu%c3s4YUBZy!oK{C}ukb;F1RNTS_=b56*rfZow@E zEQ;mAIg~lZSA@n_n#Zr*Lb^*M9bnehn%3Y8*2@{z>!a2`%dD$=nHD5~AJpiX?2tK) zd+WC%7m03vWAAYSBpQ!+*fY{B`C?n3N_8F70$@HYW_bUUtuG*Or#KJ*VE4G7^~k&8 z4iSYpNsHik03HAQAZfcYerhq^9(n~pUy**rF8k`D!mo>)6YN&xK+HSLtb>&dC8V$A zW|EYG7!@x0o7w+M0w(Q#zBrE-p1wZIK85oK&-wjHVVhU~FSQ!3m|vMBb11z*in%e7 zrpOq}Vs~l3(kZq4(ua{tH)t@6I~^A1WuWEFn44vD6XZ)~+{dtf zpd{2th1rH>^Dbn#F5!AToG6)@XZoF17o4b)*LNI{iUI7mWQezN!}7m`1oe9*5a=ZV zmVF?V<4QI&DJk?T9q-F-Q_WN~(@YFY$s-c4coM@9xkV}jKP2m;oZPb4xrJArM2clb z^xwFpb+gMep7$`Y?$OQ%{%4op%C%?lWz0E5x)HH{z6kjuwOB}E*Jd0HDiFU@PJQzAufx0 z=q>1(m;AMG>q?PN1N{w%eKadGw)kszM&A3}L%tGtLs8Omq2(|i+Lb~jQr@+SJW_9- z9vJR73-2Tsu<&CumsB@oO60YXTvyeeuHLxSug1?$KwnLutcnIv;c}RwvDJbvkP-#$ zvW@y8ff41Cu&`U+D(kCuUO#$w#x;SSzE!8=cV#mWe6>SnbLf zIr+iTEPdKh#r-4US_`n=WM#=}vD}+y5A&X%*(nEKknz&4$liTkdRwL>Pge6b0nAj+ z_?dVw1_sr;bqpIcGwMTLytgCP|l0_=7CiFpd>qyPsi|V<7mxq&ehH)?1 z&!SDAgSi3siF0-7?sYur)r?Qln6K6THrj{Ep|$F}m(ll_fZhjB`PynI@pY`*pQxPwv9txYa2P%Lc$cfJu4v-W^rd2!%CSe5hOcL_CcIYUNnjY+r3LHFAkJ zUOgX^#uWgOM)m}-*-@cWb*xdQuj7{*ly9}fokypxHSQx>1Sj#S0`Vb#^^KprHl8%s z=MCx{0UweXz#P!r669-ey-!<{M)(`czd{cwU`QSC^9*D9SrOrL$e)uLS01-AeXF@I z{it)n5faGeeF+JtfB*!PC8d3!t$pxY`|#g(YFj%B2}dD2#=|=%s@g}cb$tESFE&VmjRt zPTf)w-7@lBAyoL?6b4r+OY)O$6`dY#OT@o#{@DWLQ%u;OypO`}lNsB|&aafUU3}boaifF2&)5GKSRDX_TB|Kv6L4>Z4MdlS~qy()+N_MB1Pysa_3jr{>7C;Y?Z&N4lQ?((`|d({&{oda}i=hnKe`OJC!AIBx7*&kD%bawF}%2-FU4=jp!-B zVGs(L?Ki;oFz~f`!Km=rah~zPV42a$gfX9*algcI3` z_I?(6mI{+R==8K2Uu_w+7W!ayQmxU^==TjSKYKwc#YGhN#s4}reADI4_Wdcj!C2Np z($IvB!eo5MMAC^+;%Q_amc7sOYe3Dlz;4hz738UBEbFtZvohm_CtpACO+LFm$t*Nh zQP8~l=?w&pgaA)0;yy9d4_RJB{s~}jp+cXzuP4;8k!P`VW7sf1k<~`e>@Rq%b+}{cx5xwB(mGr>YDH=pirpEeF%AmtzFW9u&4(2y>R7 zoxI>YLLULk9Ok|wybN;rVzD|&Kj?)DFD2@gMbv)e+WMZRx0=Pq8EyRoqWpDa+XD)k z7l~YE&|ND&S&8|(dQ`C1v9-?0CYWoD)UR4;e`{1yINvf{TF&Xi@P?A!N{k|s zb9RojwTu7_7JOHQVWHf08!b;Ff><^b*?v^|Z&4Kmd-RaFh^eo_o9DAOG@X{h=Na<@ zp!0eI>CZNOroVUUZK^7A*7#3fiu|%su=1+*hro4ZGh66t$4|%eTeqxNU+7JNlDGJh zS9cge(7BPY%pd;>@0uzoPRsAujBTJFt_gIm@hVM?Zqa*p^^;*zySr?wk~9Tr8x$+q zPv+ywN#x!z+xBP0ZL8s(+p{~6)T#R1ZE^OH{pq1MdT2LWI0nfnUW_Q*-t+YRiMq69 z`e@ZVa!zq(SM9zI_pO{jEkD%N5*^%)TwA0ernZ~wtG{5+ns$+d1vXI zKC<9=+%S3ewVv|9Fyg+_ngMO2qIN4)>Ci}NdW?V$gby0R7O<12sWv)bW^1C2n1Abwme#YA#7uoFe z+fay|M_*_^@f@=dMPy)j{`if*dxZzeX&_+?=S>%SCjm~z;$aNJb6mHh4F3Oi^@3@V zkZxodWln@4Mc~fyw+m_F1PqJ4zx(R0$NL;r@8+g3JI~?xGg@M{BTG;tmwh#>{r+^f zi{;XHWMW>}OY~P>Vii+1j>Q@?6miAW@n7C>Z15OLD|iqx+n;fpK}DDOOZ8Mk(E5B3 zGui(gr=O!BMiVcr%W1yz=6ls=Z|Ci`NbS`WAn7wA5Mv+nF%X-?oI z>iV4t9viD>ukzbOdeH<w9C1<#a!^F*I>ZXP=P-C>2}}M z_WI1L%W=BTes6aC+!~z7eg_a3Nn%+;#{ZJ`op-vbqmgXn3e6#67aEIT)J~xd|X1;c}A1wxc zkL?EHW@mdjIc}BJn>Lx-uVW|lj1$eqB7$m+*kib=47iS&a3!7zYmAgi;p!C)f%9_6 z7H~v;d2(9pY;-zD1>L<<)_9>JFZ5M)$fB|s8aJdq*3LGJmv(I6q) zC&6j9Vq0%hZbQ?Ig4mkydT`-XYP9buYPGHJ^_?U54q7Gi=-iEwU_FWvc9H+w^z@?W z5vPj7zd0C=HAa%H69RENwyj&%AA6U3+0!*9MgXWRpdyNZFT#_7zJC8f{AwyFA;?1q?U zeS&J+<;}3t4f*;ZukCr}-g}|0w~gPP{A`oH3R;fEWO#ym!e_V+ zNjw_s>;V#?Q~Ocwnhd=73^Y+BvN!4hT6Xm7a*>}C%1h7zu{&SH%o2}-{ITH|u&t&b z(WP`>`$5RbpXKKvg=<+UyPnNw@BXm9-}#t?m?XoIYVH#>?y%_ ziM}qy=ohwTCqOX}3Izjgvv7mk+w3wxu@BV1bV7Ju|0B7Z=Ox*OkBc!?JDN6+Na^)d z7ZSHn{l0~R_kPppl6_tb!@>Np21bS$_7H=>e09c!E9hl|fCC)-&#^0VOPNJf0>rmf z2?8pp$&Nq?<2a`8NUZrW+J3|B!=ltZ%Z$fN#=QV*F-gp=%qqzSocV>+81v)zKc}kunh9ub!*efV^eNQTzz-Cn42Rx z736+h?CY(VYYpEbdtWL&*#vCbD(p&CUa@kp-()t_SZ8Baukq8 zDLd`DJ#I5(_SUrc>(r*8VV$X+9m8@8xP@VCD~H8}ScNz**IA31*%}9YI6JGn^F?A+ z@>zJ;{p;&@Pj#BPfh-x*zz-}5FIeBd4D|V+4=E}KoUo9{hSKxk?9fhss~=utZS&Au zs8{R32*ealQS$4bw;P-5v46g}Htu)vyrmQw$v;)+6Li)SdHA;r$NQ zzZpz)4}6SD+O_<8`x=*OA0+lz*7#T;6$XTgnwqNOQskAOkIsA`1n;JQTSvlFsG=r^ zF}~c@94DtCe&foMlt0$frs%o{qJ-YQBVIsntU1mDQrw(EdVbxs1TYjEf=sqr=y$#INgS zF=%FrNkp1+lud#zYkX7fsUW4zoL-l`*f#0RU1j^CeYNj%p3ztCUmL{=Sw~aSVoXQ~ zABHIvEXeN$mbIio#c-N~{L4p2%L zGOv8ebU}A#R#31^E_S!f|IWw`Cw*LZb08IwjScjO z|I#kESE2A;wqWNR!|&oxXLYuxbE8`P9$(+ik#7Hb)9g>> z0gA%WibYC)20b^L{v{;(u(JMbAoWJu?`GmoxoQV(9k=lJ%W=h%l?9&gatbgg#7RJk zUWD34i&0(@Bk5xyR|f8!{C+FlMs}^fczq^Lcn{tB`&HqMIl}Ml62>44Idp@u*~|%N zZlrJ(`|?g_%fH{myUio3DUv_FKK}ab_3o4EJqYVaI4;fn)gL>ohbWfyNyos5CZb(` zQI0OcAectPrk-GvWOVj!V?R~`M%rxLqH1xr&9<7aVD?>XN7(%b*!9O))D+pfr{JXz z2~??sIO^;=uL7E?<=IHMn~p$XqE#GU6CH6zZ57<^hGw8{NVvh#LaXeQmYlB=Vy`WV zjAVX7hf>u7j9M?GxATR8FU@9>=v;L=f|i(;D&^F5aP9G7Pp90V_UY=LJBI?pJ|srX z$NlsGWkjpi6m$1qOReD)r10Ve~pBvy4HL2ia&J_C-}T76Liep;0Aw2mz9Jvv=j5vH7C0c3B51!{F}4=kSZqf-REU2qt*WX4_~M#g&-vcvAEE zcdkr;ce?IucKyR;$Q}sRHR}{ydg4@2S^q^^gkttI~ z@42$xkKZ_Y++^k5o`saWw;pY{&e8`G<+_nVVy48uxvFOq`ua{p`=tz{yE=XTd)-$B zC|3Q1vAYPtjgI?4CN>#nSY^FynnpAd4%BxKF}!Q`1wsj&YP+4#OHk9ED28;Rv|}d> z?elv*jbGXb>N-a!%-hDKAwa3#9f=8TNl@b-a%Ms97Ue*c2GuBb1=qN1#Ls16-)gG= zqz|O5n|)S;6`^#gr$0Zs-(kboL3@2ougQ7@ zW6uELWFptwwm+rUx~a@6poM;fl`p^c;Q(XIc^nJBTF{@w4#jUL@>1AWE0BU2v!0eU=~lpLVtUI~<0LQ~HlxZ70t< zLin2*`%$8!3E{y!XWB$Q99;gY^9Z;STrVJ z%pqpXF>~xn`PkK0W7pn|IgO27|1swLYwQMW+=YAGRdU>MjG*NO(JsEE@0jf(Gkz;( z+$-j?;Q<3*a1nnnf;W`G5NmUu8)>MlLGp@Pd_rnF8ueUw>4T1C-LwS`s4@i?oMa%J0p+N~JrTS4nb`4#W_)Ha zY6ZSN_sO&?>RKI4R3=V4rR5&%61o?Dv-qQK%g1Au3+)o-9DXXC-$}{hRb>YwP$5fF z28qRsm^(OO+BKRydrFDpYwE9YJQ*fC5hY2EiEPPPiWv4w8P2pCSkw7%s^)4Eu8wtw zk<;bbQx;p`5|uasD~rMVxDfZM?R}LyzPlqNP>>(th+ZHuK+ zT1^_;@+UdYOl1XMA+2sHwGH?bgvZefB zC2(k-rU}ekPMDs2XPWMMjo|o^gu?$^be`Lt{`G2d`NZbmF9fsGv~K0gTNB1K?wQ|- z6kl(=GvW&o-K|3H`y1SRe8y$_*!jl2x)*g_KUia#8fQA1u9T%u7rx7qYLQplw~DWn zVceSD&qrLInnA`+e=VQO2F`c-Okb059%a@0^KQtuHBEjMrP4ATi^AIk=`5BS#Be(DTG@J-jeD%^&8?2{@U6h?9W|BDmu*ivU;8cNlr<@@ zzIgLr_oyW4iY0HicPvE4^P!OkNoI-7m&**AboiBtM0UTuRB82l(b{w&tYSGaC(%og z1d?I$0v-oi|F|1Ty668RsM!<5r_#cz6`61&R8cIfc9}+!az9CQO~KVY5+{Ajfm=ho z?(ujL(JSs!b7`p{d#Vi)rAm~-kP27M)UMdXuG$tVUxWj8<8w*EE6M((l%z%9=j@Ki zdX-SmOy_w*Bm$*w=DTF!H@%eWc%6Xs6c}MH@I>Upz3&*^GQF_ekW##v%Zd*35+6-W@=O`G!d7tKC7M#c6-;Op?Pzj6?BnW9s+_3az#-)Tc<@Yov<4q&{A8*PQYc=CGl5>(Two4A_x!gseeV#)1AJF& zNM0JYIhHIAA5hEKfAW6s*mg$P?vQdCO0MCKc9-}418+udC2gaW+c32lFBH6e>xvFB$pAoF0m1qB3vGaw$kJMo9!G= zNL-71e}+;OL^gYV-$nn~CSn&K+4&1O2UT3YdpU9^HYMs3!0@m#Ru{E)P#4sIIWu~b z0~10L-;TGwPqkUz&V~mn(snN-BQBU`b76j7ruhqp1f|%&m|^+#NeKT#{$GpT_ieO z?GTrFMb-pp$#nY4jYk5PQAFB+uEc6`z{-Au*V}3 zp1YjOk=G@q*5KCuys1m_1mQM?c*iy-rb%RpH#CD5-QM7HLCG;Y#{r7 z7W=lsZ_<4|*~|ChuvgaIqVI^rO7WTz&uveu$AHXjVi40+q=EZzHwV{YkAE zyEP2y-NNA*>BIhK$FVKBJJ_%X*q!T1AqtU)Nz~uTUim9=`TZc=Kx_WsS3$r97U&pr zmp;oM`bO`;(^1zV8efda$tppw_-IwpP>kcIb&Cb1)7Sr*-pijqQ#5`nzKkGLs&Y&m zdlm!Qo`180lO2>0kti#CC@7MGSdJ2A6GNu4yP|i*Oz~U_o*SsZr+q0* z2J!OVDP?^S`N?98YO-)0qws}1HH*dy$`eg?mG-E{85aDRjo{G||2VR5JL2xFXW|0P zzb{|s0(=V$xY2M3-(4jHF0dB<;E~i4@#57C4i)(&dCqYjC5+n*7}GzL+T&S!-K$ z_1)k#GhN#6PyfE$xd8_Fo3E#1Qc~W4!6LnXA=s?9QM~_xLB)R0v4%gn*c4d~k9v43 z9~eZtQs_|t^L^<`cbqY?x z>n{sBCTWiAd`g9%Gp{t(pvZu*c3)kvDROHFbP9MI3dZu%4$w%>YoKCgO^E1C*5K6w zGhw#Z6L;r~+)?=61l^+p@s#;X&zy}mPNb)C4B?QlTnaqW~5(?LK16IpriyZ{}^BikADUmQ77D zFdToZP>EH`MzM2ap@OmJv}MaP-DIAIu4jJvVVys}=xtRTn$6{UWNcXn+MgyVyD>?`XdI-dQjB7*t~rP_ABg1}@-_jV z5cvTr-HqQL{8exnK34)5Fq!XUSJb3UqNh3!pDUTJLHuf2%Q`IAs-}4zQ%Ih1j?t}GLcv_!#Ze_B}(E9gx zzWp3vFGmkWG6dz_y|FoL+-Tkq5}n8lxa_G?^=}N;y_XU_iZ`YgW|4yV5f{})FR&+i z>#HE4y+M)X%;@3puT!7C@Wm*E3~>6IepGXKbLO{+@A*Y_K>NJHsZaNA^~NZ)+Ha=- zH&I}M;a7hjjky?_=Az1nZ9A*^4;VYPgsaKb{vR?g4f}sN=UIFB16IDxa*J9C@J=B! z{~@RDhL7Uw!5uC_Ex`h8so=N!c!+VN#tY;-o{#^|ZpX8FCn%pt7_}?+wz$1ojJxnw zXLqLQ)baralXf;t?q`sBX;Lzm}}g!D5nkU{6p*!2h>8?l>5M~ix(ifw5lg>{eg z{{?CZFn1;T4c*-@lh01IR)Hm4;O29}?hEA+A0_{<}kwwQIX3%g&h7|&!K z0~b__B04e8(_%*gf_lZx!rrI8XDMu4EP((r;yj8$^L$@(%pBYpGpd@F&M>Ip*DtN| z9>!l3xQxX4Rs^Qk^)hm%a3uM25l+7mlqlu;g_J;-fY_sqWRd~~9}W*+nYE2!o8Bpw zsuWMpZ<;btCJvqT-;=~BgA6c@aApK4?`1>fBc8leCc_IMSLGK)eM%A56UjwV1y33e zQrIIm7=c=n(~W-`R*7qvl2O%*2(>8e12sq~v>wMl8GyH)3{pes4ju%g;dIGho^Z<0 z*;YsKYb+pX<5{STW$5P`&jeRBFYv2;Aj>PyF0Y_$l{T5gpT-1*cmefuM5VHoQN2r`>k!aa5`^J(6jAYhZf1jFH|10A;77%DFYXJ-Hm5 z^(pH;$9+Dy!ZVJccw@GrmH>eCXa>n-^ zBuauFRXJN+>O=7Z!0xeOx*a_ch3r4CF=c!n$3rncJDdMg#Q*BXA9p)BX!gM=Kbj7+AgX^T$7u%f*RW?lSWVyjKQ4p|0LffpL{|r~eCf$-l&M1!>Il?x3l1 zS^kG+p9l1)r0*8{-E?WQ+~L7yrN^rHI+~xf{9s=MPRTb4PC^1=zaZ*wX!F(gTkOz| zM$P#zH(kRP+yMsTYhvzFo8q5ROHEmW&fM5cJ*_X{1?SCsoqWh-bd|eG$XuiM*Svf% z#s^K1k-1_dbSLqiqteh1OVwTOTv}N})ZUV2^UY1ll@aYbCq|1HfxiP+R{^Wb2aXfau^Q1t-f~it1S?4BH z;?$YV{gbVKukCM$ZVc8o2dSkuj#=ny%WR43~ zg5<9{1e;V=2#{&ZF|%AR@=J2;HpjQK8(5GGK?O67KEW!ToZ|ijgN~!O>G8nvQB`T0d)%A$sv23ipiE@5Nl7QBi* zL4GifSzWj%N+?5CLpGETwpv!2(f7RH1l4Rl`!AG4@g8A2EhWTJt}&KFIYF6a^<0dwb-Z#7^B76JmO598GTY zHdO9l5<1R)n_9}B=QccBVj$QvUq5ehVqg~WGfk&Wtg1?(z?G!~H5p^{H3q|#c;0SjdpBhvfYU~?n zRDxN3ZypKRH60ilqd|Nd!v_0FT5g4nQ${@CF5MP!<*k{sY)=hZpiRNW7Ph?Soo4^E zNSI=JYmN!39MKo#IShrNNJ_WnO3#@}agcC2%OYNh;$o;daV!WGPZ>2Wd>V{{P#K}} zP3BaOdBoKpJG#B#08Wg~l=ZqKcpTiOcS zaY~dLZcHq4^vX-!v@^|b-00GCG_t!w(A$VIcb25@>tooA5t_UwbH;J6332Ul-Mh`de! zFvWR3&2GkdqA zH1g_-P~`Mr96s^kd)8Ya(dxGoptm{r%|FBp7jq|?bp*h}Bi*7W6B|*&`q1Yog#`Ig znj7PEg~e^J*t=c^Eab1p_#5-a0fu})#>(e%nZP7T>wS^Gy)s-{KyOB_VLKVMaydH2 z>qZ$)d&Nli*fW_wsSyFzrgWF|cWdS2Pd6Fa=Xr!x+_LarQRV3c%iIvdes}PU6}qxY zab1m2x&2Uk&9KSK%w$YAw&NS$b#8tyyf#t>sk3oyv{8otkZU0US!ZZcN6Z za%2q($~)p)g!ceY1^%Sbt*M>nENLZNV5Qog$I zS=HT2MzUq)*1H$4CTlKllsZ=zzso4|G?uV-lXSCeGvwfG2QLbF97}i@WPHEj+oRvh zGjQbPv58ZZU{jo^##~LdNxAxau+FlE1>a3u{J>J!lCKr#-DlYyTrAzlUqF zUtOn{Pi1Lpx;o?gCVRnWXLI?Pwc9WMZF+e6T9qwmH;d0#*Y9mSlU21| z=yO=%GwT^`=4@p?t*9T^bs8mUC~?Y}sTT+Zi-&sLpfk-ugl+5E;EgC9t{z=Hs2*biOJg}b#9+AHNrW_H{ z7*l3)80uW&IRiHpmF$s#$wDi_Zy6&1xbot5Tjwrk7cY5acLh?d99^tHd^i^-)h@D* z92m0~N-sPVwCy4nOGp!UUOq4QKp%lJeE`$e5IazWJjhEMUWl7S1Db)77xFSos5K*X z5-PG^r@M{3j(1$-cmH^n(+ln;UcM>-!20TA!g%ghyq=R^P+JKo0ZNlG*gjx*7xLDV zzJ;axD3eR3%NlaMdgzgvX431LL&XdwmSmBuK9$j5TWOS+L( zSf_Xet{-T%$2 z&GRO@(K45t_b~L^=!I>aw{g~AcSDOWEI5utS%>odfI- z@{7B|UU&7*y)JLUgiX@{z~$<|MAB*QCYMDonM5B?b+mf(iTan0P4G(_CZaA}nBy5b z&jYG>%(V+c#oM+xk0~$fc)%yoKC}otb>klg`M&CLKFX~1vS^3hq)u!BIKi$u=rQ(k z;1D2b|IKZpIcJ|tcT}i>Z&Adh>$N~%r(&XbUteT`DT-kvLzDZRpMo92PqxBotkY?H zk~7{U9S`|U=EBA!?I-LGRoLq1eh4q_5OvdWu`+LT^%XOX0PMn0{odh8?^`ELH3be` zKmXCB;K#LeB^+RX`%>)UVQ?ypqfbT@<+H8WTi08)xueMI0kn1invjJ%P)u7-TubR!mCdPyqPV7Q=rU{iD=miYc4I0r$`vs5QqTT_Ihw!S%fXpO`nyGtr{y?R46kEoyU#;k( zH6dkx_rtUvYKC0ytRf@}_%|y(L^AZz4~2#)fJ)f?grXDX8h>RB#e4O>_A)g0vG}&* zpzS|}3AM7hxtF5B|HaX!IaI9w+f3u(jpf zGj~;V9MCs#@Wmw49J9=BF!k?*b^GDh2o9SICEtt2)z)RRZr@!B$CPj8q8ni^9t*r$ zWvrwUto{1V(a}RD1xl(0Gy2c-E{(svg$umXSd>taZ_w8hn!`uj+g!HEX8P$QIhk6Z zk{&$%G1QNmDc zm*ruh>uEpZof4x&^Vgu~1+#6GZCk5>6Y3F%#Q47)3GrdLA}kTU5IIpI6hd4M%?JMz zO0~{8QFiEKjiNFAbIjO8^8AQ@taI*Y63(*bT_HN#oaH&jG*ogy5NN%d* z@rsePTykEL?=b{;!*EO^%0tLU^!p@9UMY!IHi|?n#YQ!ih2g69Qmp{MZ)1`BapdGz z*B24@Kl3fAwpuwdvMz_1B-;tW5;2oD;3!$$FX|cMQdkR!(pdWo!4Cyx=g1>ZQV*9; z#=3_~A6`#HDICo2Ce-t1eY_vU2_bs@Do}&GINk!oXE2OWr-+*!fU#aC%ZT}!mV>VL zj17zJ!uj@Qqw>BN6zXXxc$Jh`DS#&EKY?NQx=ar( zLzvNPvXgU-|8#WlZKHD*UtcrZ@~+iGxE2b41>prYJ(~i_n+;>IVI)^j$h-72dzyAW z*#ciR-i=G<$6#ukB3f&HbmauUo-Z;mA!w<`5G;qKV%SAx+loUSMKZw_d3eu!#I@OR zvU+*h@Lub>bXohL09xZUEu*1$OR?LbIDS~g;(#JnM0EHGL|pk2Z6^Op!^3j)t6Dz)B&t+y|=31DiDP&9-6`0USn1CB^v!VO%@>!P|YSHH<{95dP zCj9C(>dSfqc@Ix9>UpEETtf2A5K71V){qSAOg}ktH%SvEvM_9P__PAq0PE+k!wDDq zEU#o0F+L>oM#RS?!hfgcG~O3id!9~Q*Xk>qAQoO&Mx!>1hU!qrQdDSfP6LHjV06#J ze$kV%#Jc7$F<6_-ZRG@sJ{9K#5dmP~&Q%{$p>p$VA-SNgsg+vUCD&`kru;OBKWY%y5dyep;VMUPwB2(!Cbv@EYWC^I5N_oEdJ2&wtNXakABD1^pO3lX3DPCss zXgP3Xc`$I zxGE{|N?Qe8C|Qf)9J({~H-*-)N)sbJexRWO<6p;LCSewFCcmMKNA#$0Oe;pl(*kqW z2RM%GPES)mkKs8^IvyyhFU2sDCbk5!kD=Z8>~~R!c)THS%%;DBO@{?1BJV0&l;Tq$ z0V5vRSOb$k41DvO1YxK|(sLs~UKAO1VZFJUj9D)5&IZM-Z-U^*(kG#i*CCFkS=1sQ z2dj4p88vYklm>5j&^Cb9Qry_z+Yc(LXCxstAl|GM#DcFRmE`N zM{mRb%;LR1Vvqze@cK%e+2GEc1l$<OfdjBnf?CI@wL?wvr_$+FJ_w>f-M8}QT?eXg4%|!ZC8Jp3p3C^D{!*k4>d48 zVc^&%0mNUG=H#Q%AVe{oY66IUZ=%&Sy{>R0PYJ7A*$;unYEvePnVz&>ws~&v_}G>a z8AAC3F(4s-M0;Yx5t9YXY7@uER+3*|ybL;yKJBWqT4cPsA!7Vn@a^@FfFVqR^t!*7 zoFOtPUrZ}F7%=P%%z0p)4^?2M)*Iz5-b^c)xt~LQC579n(i-GjzxTA=G`~!(jyCB{ zw^UVSz&RT{iWDxDpAhpb@{L&8A2NMb)e>8Ms@DnC&0gHnS@C@s<`&q*L*#^IeS(f~ z+IvIx!N+gOl-P{&{x*ej#PYAsC3rrvZqYKQ)P9@^Bm&ACj`O^+3frrJ>%6h4edr-;q>f1h#V`+VCV=mYBd$0I&$mVa`%6rmSqZu_K*Cs&V03&c(TqY$J}i(T>4Y`wnf>?dKc-+-+Rn!zbu4z-hKXMog&$m@2l8J95! zY%B)a$?|4pP9p00ew)lGmqR|Q%fu#{Ul5e2AGkc0)Jf)-{l7$$24JM-Ye{$Gc*E*DmB{tNi-Qd0J+=^#OYFni{34<9g`71(0a&a8qnp2&H-lZ?8XTJ zV7k%Kra&?Gcpk!(>{7sUS2zrUe`wKguxr$@vBI$1Dlm+apg`nrWH~=444*k-3pu*@ zofn;Jnqj49&O(L2aSug>m7ZPM&h4)Xe?GcH80EK8_zie z9~W6EH>Ax-WFcPhHg33Ba?>Gl`Z3P1VJ9eH@Qo9N zx(=ah?|5|&WC=__4VPk0xk64@;G=Y1#6g?$m=*Zh8ulSC+&DlfhavWlh}p1O3x4K? zv&a3@E%PL(n=H1E1(sVLZ7Y=X6s*F0mV?=Qg@Ld7`424^ojZY$-s~@zY6`cr%fX)` zE|pvyJXDUl3Le60ZrgG~lw8O-3hm+s1(6f7GfnYHZSOW!V{e+{tZj^#UWPU8P&7g`dN=PZ9&B}5AMfV zMNd}t)G0Pth-G($5)X;|m|kr`9V;;PQ$^ipSUs8kn?n3hO1C7!#EZINVr9gMms{dk zLGMrKwA6B+5|^MnUzny8koi=P>P7vMzX!dwDlWby)e{|!U@>BHzG_xbo%nPhkpMDF z58%bmKCV}D{iuVktBjSRtURjxLIY)Z_NxVqDk6bmlT(MFUTf!6Eul<}S@!X)7SEqs zi|ZNViN3t!ridhchEsFVIZd_nS89+8m+jltoVGa ztf9D2VQZ-?Ygu8dHYH-YMjNh1r^&&WEe$3MUW7YBLg>Xb<#TK69w-jt@XF;>*!9xK^|sOV)CZ^6 z0_VZU4XerRNLVUd)(y|s{j?F^rx1S=j;i1I>haPshe*iNO3Ry{tr$+bLZ@4oF<@(~4gx8a#F61wYLQtOB;)40}Yv6>i>H?ad}c_0 zTA+Iq_MdL2_-;R@Ce75ex1Z8pAsY6F8}*t*2GDXL4!upWbh90m#mKSdY_cXbV?&sh6A{A)~_Em z99T=n&O%H^8rmSDs`rDFN;I4f67CK0D~Gcy^kDiKM%OLkCFXi>kiC@`ZC3KTft-5v zX#v(k(HJ(hoGlAIK1Y3M}jDR`g(eWSM8eAJ-m(d~LRRj<@ zfQ>Bm;ReOe8p9$nwu`qp_DwlBMj7PfxdKb>s{ni(gS4!)%nagU6r#H)!+m~>$WuCR zrdm?`9%t{Xd@aA=4jAcG?lTuHWRr;u^a2pj8X}?$)A#w`l^avFi}04biL@oZw-_XT5Wb z{?kTXJ==?F|$h);{YjrT6P%t6T_JM%*k+$}U`}UcDc4sJVHvnht zzGFk86WLgStgG0Pz&(`cy3FWof(LF>c3ro1Hdus9r28~M@vQ(Id{A6oXb1H}4_#n8 zS$hvddoP!1JIh0_kYukwU>`!tw1@nmk1G&#cAfoK1EV$6RP%y)aF#U2pJccgUJ#Ia zyYdaCyS0WAP%ptSxE+c~hZ`dK|Jv0^00`MZ^QCNn*2!gb$sb?5a+zHob=z?a6&591-MAf-I1d=^d zZGDJ`DbHs$td86&KiEh3jrAdb+ixRLM7_hrG zh*;T1T-aB?3XlSJ5Y57u^Q2Y^gH}pARw|`d9-+7o@RgR1)#46ct=>Fwx{$mEQCHnIn?^VjMIaN$yn3GVg>73B_D=Sz0bG=MTY3hts|c#i|W| zwz7d!)LNDnB=&WEjjeOD#%z^KdMmGk(1`(3lC>uE6My(C{)xrtOy6Uu^)C#VTl4DgTP%XKu{cofY+Uz+p01w)DP#?~W8J zkAgOj_N4btrO!*V2rr@ukInbbJ7bOjD~O*JO+Rb9I$unDxt#e@Cv$-EIn>l5?=&UC;N5wo%u3rJ`A74M4k^c9x%l~y7eNvyFFG%~gql~In=ON@ z3oPC|jg>~JqW#26SI^RRNkndXS$eJspzO%kw=kUEO z4?Z!Yxkmwpbcdqh{NHvpB|Gw>v?dngQ zCarofI|8)bqzA z1#zfudTHD>7q~}e^EmXpR{PD*31_j3Rm@{_+t47V8Q?(a@a{r|N!z>1+lJ?v-_ef` zmj#<#^7MS~uUhPAq;zysg&VdoIA|(Od&EWPKXdlBHlSz+2d#TwEv{PrtaO=HZE+3! z#CpGJJu3PdC{Qgx${5S#cZL2T#g&>C)TMf%v`nW=>B%`{YA_Y_%*@Cm^vAk` zSYjiCtyJxWStNP9fTD2VvkQ#`pkg)z9_7#yjCUVw>Kyr6`<)MmD`qMxQ;A{bggn1Ne&fRtg%9NQZWEl_ zAKuEnyhb$1xp%1D*07g5Nd$Bj2ZPoO`xepHsJ8lvM?*YOWcB(PhGD2=fo`(3vktj~ z&hB*|q&5AX`z*g{TfU6K8yz7YVMwH^WxW`$QyFE)hy+nPH=pv4|D-qG@)8ji7xjsB z^cD4u4Y(#S2koCuNv9y@rlhd|xjn)^G;jfQ`v?-~H0tRCUoy!_rX0Aus`o2+$hLU? zw^Bc^za>6(dt$(`ok087p{h{iM$t|F9#?8Y5Z(8ubGr^mk1v?AxjC+Guug5E*h@-n zndA4lBLyo;C($}oK6mC{TDgY?B^Mx>f@0xcj%Fz~Eo|DD-FOVanweDk8IqU>^s^+% z3<-b2kLiwUb`k7!#5)N~%h=e6CA`Q5F(eoB=k6xpO?dwN^@c<$-03ePL%#|ZkB3}b zK{a$;V!9|E1D|%zIoYdSm{n3s>HEYUZh7Nve>&uZ8^M3mtnub7O)&ySM@y*+a$cMV8M^^V z=wb?3zBCU^c)1I`LbHAkg=B6h@P^x0W54t|m+bD)@%OH`<~sFLr`>iJ;9wl4ks&8m z0TKfs78v0cHPXT_pmOL`MFOwLM%&{(1PcY3bQo2Ni4;*4U!$o}|IDQ_e0L&7$Em`T z(LAPHD4=_gsV~8?&}_?n`h_rgNNJc4)jDre!#<^0Mu2ppMI%*Up`O{*aG5hT&*>BU zT~VCH#|*<(K2!QYmKIJ2?)ZF!`nUZ}*0#;tDT}koRLd32{lrMr=N?vQbk1xwK!>yj zu5xFLqoUQ{!U?T>^DM(}OI#V%CXHSSrnNGbi6@L|7PRV>o_J-dqXXwqpF(BZRQ}ZX z)6ro|d6z@pI~ZfMehFK=U|B-bIZZ6i_<3=m*o9K&IjWlMsi{!qb-Fuo_*I~N5v{=F zlKt4`Bq5=j0o6Ppj91MPwTit_?p-04;W_}mS?V@JYDT|4#>Cs>p~i{g z&^JXf)w`Q{Pla$xBuGt__NOa&JM;M z1G9NdT+QmNaQPnA^%4S8fIGTdAhH+5u}V;lBq&9sm}zn`vrcEw&sKK3C!W^-Y#eS_ z$B_e3E_*Ya2g+OrracF0t;KLwl*w>Mgc18z*MEP;>Zqf;6iV7zodw3u*C%2T@l$HF zU4_g`tG}I&aB0Y^tW1`(HCZt8VJ_le40m_xrxF~dN4dW}@DlmG3YqcJ6m?e9B38_x zHpkB1rY6x-HiEAF6mBTK|GSToIf{DClrKMejEa>@aRiBA;mNb6FA3N@kC?0OFm$p` zU0Ci?^~gy~r2=nJvfeTCb=4fXz9d^4gPKiu!gx?aP5vsZbqcMeRn!1VF-mnA5H_{p#KwmikI(6Tye zHjdrDvGQaNRXxo_y58(dznFf71!t;%(6PvWbol%vH;SKHC(nDN z$TNE7nS`)xA5wzbdTgdSY>W8zMTd0l81C=9K2#27-2jcT*yFv#Zg>{D^*Xr1+wa+D zzxPc6KZ_|Rs(nIIxW?f-cf!jxK%~S+E;D zIvmZ%gjUy!LYNGeJ|RFuPVlS5k;tNxVET=v87>dMs1gOkc8TP6g&9Ol{l1B;ktu2V z#BUTwk3ho5Ad!59yfqwTC938er=iCcm;u0l*TuEE5^S zT_1<^xN0%f?DXia63IqV@|!<2+q}nAO#$-Z?!sboy^^`UfN8u@c*fn!~o*qDd2mNw%?3jBJ3uWPBJbT%YX|21*>85w^R1pc}aj zmY59=mMJ@gL=p4Da@e!C7@sBCKKrG=J;nTJSNb7-IfPLR_ZW&UOCt2c(A-Cra5ODt zjKw{@)Yq?+h;M{QfSmvAPt?$WWNWk$NlTd2mvl%=`s$iw6zivHV zvIQ8Ddu10rAJYSs-O^3$eYIImKO0f6Hp;lNPX_GgV4+}Gz%t18Df-B>Gla7}7PEcb z__KIHuWp5p#7HK^@?^zwxGD0q4YGcYp>kvEMcVd1%XK=jO7FetmbI zeZrc@g`KCYm_z*XBY|C>Fni$vS)mj9qrU0w7d3C?8I(mC`3JQ}gJf1PoZR>cmN{|#3#75K)W7Q6Q+&lAE_!iS6zi|( zzCtHS;TmrX3KIi)$P*~}W?FuA#cPe8z0J*1OR_IDP^rf1_5S{-XTub;dKbvbMX=F)JY+U*k$z{Hw9mYi$|6)2Mu>6sfrtFW3~Xs@c!B-p`#;tDAPH zoAb}XG^v#sGsL~u=`KrN6@Tfg4Z1O|k>4kNSovED? zo={-ry+?WTw*aE}ICnX9{v-(ymYR{(y*asKiySP&C+sDh= z1p?}t9NT!lzH41ApC9Wix9l)<(C#hIeZ7DgU={J{;QQ7={T~xV=PpNyUU}ytTgQ=l zH|c4or-RyA!1MTMz4^0}4U?+7xW-4ETE~N~CP=rSaW`cqF^H-HT+p3!V}Ehd0ng~N z4XD~N=|MO)?@82B;r4NF^vE6v(*>$2ZeU(<B%*8P#h8Zw@Jm zyj}+FjZn1>xCR;+Qw_5uIR+b@53i`Wj`K4m&#yJOm6hJC>W8 z_9N|TZKmObp`DHI4VHB7Zyl5~z z9_zGGG0k8#hBUJYvj!$ts}m}ENbp8TsUu)%Gm~LX7p7Aa8k5oOz4Ytt&5}*b)UAm4 z+1T>gZ9^xn1Qv$y={|?4T-<8W4l72yq5iZUiFL#r8&^}A1^#t6o^>j?Kagmgex6X> zVdZ0)azd|a*3_KoBG=kj4CR8Kq>ri`rW_3SC|OIUxq)n**es~D;B$}?*WAp@NukH- zHyu+z;TgxH0qY^WJ}4MH8NVud!MkHN)na6|yztHMTIxz$6|UycghgSqQTqgFzzkV1 zAtYP}68!-Zhr+btMzGtBovK5gsP7&X)X#qnxX%Tly5o+YEUjh|%fmpf(6w?LtO4h> zp@g-O$~B~2o!ku?>G%{VHTmxO+_%H!hrmU#yLnGKn%^jZKcO`HJv0C~%?Tat1qy&F z7k@YzEf`9`vP}!1hc3o|^VL?L*gS=h-+y=m&RVX}G%M1}LBoZ?(Oux6L^xIz9LF5a zQjKA5EKA6}L9Ds)%w>Ztaf6r}`&0J@_3;KR{w5vwCUlaR!DW*+5i1>lVbZs|`{Xa>gm#*6G3cE#Uu=ic$u-0^nV zal^-O24j;??gSn0kUio0yY2k5t6g@Z6L({){+nIRy_f2;69ND29Ljdq%a$D`mdDRt zSj*TZ1=d5}e}0}g@RZ%g{13X*YI7x$Km(ifp`b{^)m;wIxq*SaXl;`R$WqfT{KFpZ z!>+1>u58qy#KV!Q!?DT3iJym-@WYwOLt!xLg3Hkl^CPZqxYE0WrpcrA#NWU0kC74l zE&SixF30FUf3Ied{w3m3kmtEVMwfeeo;>ibQ2{92XaF}Mpe1h&FrlG#zagt3wqq$_ zeN`iC3_HiFAz(5rXgwkb3L{oL$^NOFDyTjus6{MvEe*b#{EN2r*GL}hGzpcII>B09 zyoO@Bas9yhKF>ASazl0cymCx{VD@_yG?_u{9wzoVTY74wCBcGm(@eZf~Qg&0@B-kcsr@m`_q|GPWNFp0(DO1LMId?y2k+UxHcpW0MghP8ZXK>|qDz^rfm(`aSK?Ymr<+*b4 zho*m?0)8n)D5w>T26XiVbbYfHJj%=pY~?y@m^TwF2v_fkNmP#tE^q?u1D);{MSSH-|OivgXkRCRl);$ z=|lgkJ5!m5mA?-;h)0`OOFw9*mji>7A0LEhANRYSGNoo$wSLSe!4|cimeU{eejy%< z2oN*d_p`t52ME9bG<-(GX}D|z)-!IKrDP~lKcdnsFq}c!)#O4hzn5mVl#}Tc6X!8? z=vAXdo{nIuA7mjITr8dOY;|m@0Z2lc@gN8&81qYK^RUVu8$L^(rRg)^m5JaMg=j|Jn_))h|U0 zn&@crnS<-Z85~J%o$Zm87yrkuu3)*Y8aK}oxczx^zWS?D#!vGCZfz%pf+KhW8^uIR z?!3S0tC9r~pA(3ktEf%p0|*6GWbyvl)x#FyYSF>j%^M0NdiwvdtN8|~F_$+KDIDtw z2OzfX?#eXoA8VAMuH$?v^!8M>DvU2A`BjeXC@*8GvC4ngIAvDpOwv{nXU}1eL01fDZSj}P&9Fn^dTuSO2g(@XGUz| z+$NQ3;@XEtZ0bIClw#_+;It71EZF2N_AMpmEAx9@_T%T?1ib)D|>}s-Wl(gd~^8f zkiXh?*HYP%y>d|YN@nu#upqQxV=GhLp_RfQf{}V3wqRgpJ9J6;0wB}qnSQfkMNx3)p>?R$lTP7j ztZB5FPv{$7X6m;UDCSVB;hN~IX&nCzA2N)T|J2ATupTfC(EyHGuHWUJ4Dkf#%67Nd zW?ACeV68NR#0_;m-VC_-T&$X3cY;D5K4^IX-Ft=BX7C+(Wkb*ep%3OPUFeHbq3DDm zLfI@}YJGW{gC+EOwA#+Aj;Zh;IF_h?m6M6GlMz@WuxP1XKB>!^sUV8|FuvC5aGnxt zGR0d|X-qmat9ok;?V3SoN_T`qCIhOjyPR03rFcnuH`Sn9FMcZ=b+V=pM*>Nzg|L$F z3|kSfpaD462&0&Izflnlt5WT#w3C`{5y<)hMOu4^WoC7t0XItGKUF#+o8=Omychsz z-FVKTbeR3q`7lkoNNT}Q@*Nd`Y`RWDZ~*~8B4&s?BKLie*9J?9sWoM>?}&y=Z7Sf# zhE>@}4NyT(9eUD3)CmRSm!OiX-h@kP(vcYJo_$WAXJly_R@Z)?@)0l$kccOYU}Tl2 z=2QK{pK+^^tuXibb3qaJcedmgxhZ~F2*8j~Ivm{xE(fjfV&Z%)Hl|udoVKvWB)QE7 zmOGKdmcopX3>ls>7$j1tU{%&>CWHY%k0XZ0uoO~Q-{X&WXNDO~6 z$|quM7&QnDhI4!h%479_>etR{k-QD}V(g(xim;J;xiXsu+;{lU9@O=fyPO~@V} zB++F{-oj%fU%VO7LEqE`unJ*mc$dlMzaJzUw#LQ~QP3}gUb$J?*O^-E2&}!_9;}Y;B(}3N>Q7^3utsr%&+mjvqn-El$W{$E zpV>f`y4gkRM;8c2Hj`!Eb|a+a0&w4G4}cKba{7ri{V7UJRBhUW;_V-P6gKx#bz6st z15xxgFX6NlBq}aJ6vkm1d9?D5SkyQn343@ACAfs#?g=;{UD#;UgRCkTK01j_*s|2( z$-OU7a`94$HmU2VxB>42)=q#H?b}kW+fQx;vJni_qq}TQAgcwk=^t%3>*anU>frNy zG602zGAE52ig^U8F$O7S*qqU?`>>{-yC7bSUP25&rZ(v>$T0rXOvLq|Zzp!+U*Ge# zSAcZLfcP^^{*QFv8+?UM+Or;s5RO!ek9N>D_@F+vcEU%wZ2~y_n`e$kQUE+3tGGHE znyU*iyO5`SgtK~}BYIi>1PPIgMOMKW;R$KAZ=qGqgNOBPW|1LA<2Iz2sFQi|WRfAz z5HK!)K1xz>jCC2|&7k{g`KbFxa)9~G5V~Lf4qw{xR0yeH9>`-?L2KdJEm)Z>+YQfM z|Cpj5f?4%0%wC%8?^Gy_SDtL;ZYXOg)dM_Q)W3EA<=p}lPI*XcDUl`qC`<%9I5pLp>fdW7edhlEUmR@;z@s(f!;TXS%54BPrBA7&s*!y@v z<>~pT-kfoh@#fC%e%2fZ0!fVuuK_-9lqBe={q$j2hts zW*_x19+H`=(Kq+Ml0E#PqkTJ~C7t~7`x<3nJ3u6HBZ7q$mFlywI3U@DI3rwg=lPBp zpc9tp$iKQg{kgGVEbAg^iwYp_D{e5AeI?8hN?i?!8UIB?O^zme5>EDD;>eq5U9Zks z8RYErjUU&`ZJW&>dMkZ(n)L1vHCeo5|DLN$a_PqW1I53qYwOsAl~>jOML zQ~TMMrU#iDOZ-Fzg$q;4>%cKG_Q)yabz@*5mqvXVdLdC;l0B`+hX<d>C3^C&n@o@MKsG( z@XGC3#tyx&(DMToY{>DDV9Qa-vwrMVQ0P%4iDA^v4@>UnAxZXbi=xa$(X*ikgwwNy zy|;7&vGFQWR123Hb`-h+gWS+*F(dp$tBRMhg;r2~rX!JMvdk7?!G`F})kH7tqIrhD zNsVGz2`bslqr}RCm_r7dQey2S2W>cG5=`X6P6ns}N|tCLGKM9*ywS9%AvA80%+n~W z$cdvE&P#Wmci6z-J1lobQM&kr*bgbaJVQPlOf0^M3Jsv65!=zyCnIF>pYDoJu}?A2W=h%&|%O*wRFv??>RNf+H~INI|@ z4Nwy5pdB3u1KDWzl6mj|Lh|Tl)v7K=k^l4^g6&Mb-g%+kO)~Cv0CaB7b@Wr4Xa`M_V7J<6gknw%J&a7N(Y>{ZCdJN&u)klbA6xd) z=!{q0j75j_bdV9zmwr_Lu6a1Fd4yQgJU-O?XIJBDolJ=SB>tZE@1v;gSSh88uUxuMlq z+Gx+U(SxQ?%(Ov4+L*5=fo_q*w;0GC)Vem16BzA!CETqW5`G7UmKHas5wcoyeK$1TCoG<&8x5f{KbpHc$OPhTE7>x)hWsY+Ny>6 zq1E~t3-csn)MVD&>8K&HZlJqckX6`=5tA1-&tJZd#Kvm|nKNRFMCyq>i(wVQG~lh2 z*k0IX*LZ>bGE@cBY4XyY+Q4H1%Sc6()(-gMq?T?09SUs@o=#=f)`f!6SeRm9At2^t zl!8*-SKd6X+f32GFeWG(A(uhKbHm6iOcZT&_u**o>ZpcsZ70#lU^oNdM7!f~TtGj{ z=LST)uo!&w((+jh%p%8UI7-UU@Uyc~8mBj=0W3N#%jj$6a*j4Siv_E%opi>LQO=`L z!cwGHbF_O1IvLQo;JIgw_8>h9_aae0ZjxImnrKU`egou48uHZHHPkfiqc`T5z|8RB&NAE|wO zj5wYFn+8ZKRvM_GjzA z(ClBoRv%Ya9~Ty$W@c_@W)Q0xi20~r>+5T4YpefZw3nBc|4Y)IpPxs%+4s{^7gJOB z7sJCR6XW}1qx+*He@2FHh6e9?dl8+T*PWfW9UbQ#9Z%!l5B;HtJ_AID z(jffD)Z9OIdunQGe0&@UZx0U-4GawQ_V#umih`v)H-dUM?@;S6SJFT*%qOz&{dtFgwU2$oBVO~Qaa!Y~qx63Qb zN=r+Ni;Mreyq%Sm<=gZrDf`2l>TuI?@1!ruu3x-AefpG=@*ycH>0M$766Mw^H`b`s z&@Qvo$~Arp4@bOpUkZK~6B82^6%`Q?@h&tF>1GE71^N5?`}+ENdwX9yIo;XHUK+l< zR#$%%7xem%n>}r2uq7es=_!3wmuTeAuO0kn^hfOcY$ma9gkF~h+k*{i-P z)_^(#N-TrnrJz5r$o~P_oTo|uJD_d)56~8=ATUq1{a=9g4#m5N#j`(-`C3|@Qupb{ zzc}J${sG!8{dh<~yC^1@{{IYU=Y$gLE}2C5*6-m7ZY-g_0bsj4b!wrZ7DTjk34cmDrd*L621H*#`L zl6PM3=j-_>#;}8*no;2a?G(si!~X-&ezsB^$?@}jX^2WMeOZbEudGv$rk}r=SsjAr zuJWD#3(zhNRHSn&%Oc{HE69HM!i^)#vC(ZE$HQ4RC2j#8bIuRk{SVOg_J0^*a|?@s zV(Hxf2Waz`Al5*GB`F#LZY7Dzo%~=#l{q43)pzxE1xu$nZ{^?zqBQcq+jFl9fx55% z1GKfj6ha9}`hhz%#ozuvK>OMq%Af(o1KQ&xI)`uW91?NA&W`WgjV~ZE_40W?>Qtpx zSM=jWjo2K?e}J|}o!u6Rt4H1KCt?R($3gHYqLXEhdg$4FwJXtW8mgV9d2f>1WC%5j zPbCAL)k-Uj)<92ak1gFB4`_S()=>YT=Lf5o+1Y{kTw4(1oP3L-6=*g^yVi_1YmI}q z`D*-p$k?G{Dk!TdyK4Dghd*X4T!d_kZqdvQjB#jcN!(+l;Q;kZXbSsh-C_!PKT`?Ot=>qhqHDzv1w zXan||-2WqvZ=HAT!oK#`r(jJHx%Cv80xlqi9v8rPlb2E;xDJCRh!aqS8SEau?O~mI z-LxLGboH8|;G4F5!PA|zy}GXHc8_1b#%8uTQy>zu3T*q}mm6}bI>|P&A3XbNFSizw zN&XJD-e3Q9wDz>n|9JUd-LsQ_9G`vWrwb|meM`{)*xUbJvyknRZPf9>A~4|9UW0b)5- z$&dkNu*DYJ#3h(BH@#45#r`f^5OWx;PGKpV7ra1QxB4%L;$f9D6`G`&Sb~mUnT`TI!`S;tXj!MCU)k@JXg0N_ak0c*ti&(__^ z>Muv-H9GVa>rzsN&bibgevJJ%Ja;A{9guF0zz)R;2m3$YM`cbd=J2-!q;$K5lk}6B zyDwnaE)ZHEF>H7Wi1!T(Ojx~bGC~MoEdns2`@=e=M*2ZF>6@z8vy@)&{@O=s?*H;W zEcX7PEeSE9mlWqSxuyXa=Gq5HruyeaQdA*QF(v&q9WD8WxQCi%vEVf7*?*9V+eZT%^`E~cwik-P&As7Q< z`f)i1pgtHzgh+;x29C%cMI!hPH?Z*c@=7K%`lM-g1Vi+eIVI{U zjS+^wcP_G49~*?rOxa_v-lq%+d-{@wNZ)E(8eH}`4&BsFfg6{yH#IPYUAPZz1YC}W z|MT%ib+5n9xkOfcd4;3uwi}cT^~(oBE3&?*zJrD)xVh5BdV;^J7~65=KUQ zo`0cfV{1+@KBe3&FQVTpik0)jTiSUbrW37LpHG z@q7k~p1_7+FS26!pb{}5l_jwHoAxn(YKKQbT`Z1g(;mi&{|eqwrK|)Jwl{*9e8NeF ziJDt42KL5WprJ^XhpsUi@4b>U`#G5)0}v%70O&V=Ndj={vQP=Ur42B>c6x^Yn*Aw# z%w#aI+sGI9P|^NJ?(U2A4y&CoA8`A?hgr5i(e^ZCo3}q9GRbG`&a#qw>u9l$uAy+D zN#P9;b$dUdvREW_jol3i(b<#8z|y;W3vDEu%0Ua6*R_v6MPj4tevR(@K}s9M(nC3e z3DqHtc3_g@6v{KCmjz7-L^WhIHUxs-N)~^nVEAlaCW28TH19pT_ApvvmbnFkk;cwCdx_LBM=Xl&~qf8Q2w5cy6LCwBuyp&xwG<_qwSM;li2`#{69OT^SPS0EUMD0os?*cJ0w_59B{=qi>2L zdkwT-rE6E8ivk|c;pBrp z)|>$OyPFLV@hQnJ=Jo?VwuT0OVAkJ(C*)S?Gn31>dcSBWhcd$~<$r*7R(w@^d<71a zXB<;JtegBx7fhx1#rS`Wwv*oLG7?J};L8c|)62-Y#Yc)G4>606mD^+~`-$3SDcc%6 z(V94tv!{ud&T61HNCfB~%@W0*X^E7` z!pp|vFSC+g?Z-3nz)hE|fDH zcoSv6lBWDN+HqXbWG6Xs$I4+;!C{WK#>l-9M&?s73Wsg=5X}X zvXak!Zsldv<;zq43|uy!lX>Wfzt!89p&pDWnjJcGQr1f?egwYYi=r5Ofpw7FOWBoJ zEU}8^22t})Dm$aHdYffzc2->nkKJ39JF$q+a;g|#l+xwa zo97WXX1URi zh&ki?iNa12DxVc_Hs<^p$zPQ#Jd4O{>Ub2eoEHSkFTS0_G)Nc*hgDqW_L~cw$mP}E zEhLFY{LGH^&Me&O$YjjUMZ3IgaxAud1B%=rsss|R-HHYe?l^T6aa+L21zukMepc`- zcl&qo+uf3XbC9qN!b9THPtS@t1qyjOOQU^Du>O*_EgT9yNZxXHqI09ZOUSMnU#25Z z4cZ_KOChMJ1WU&&ajf3qnkeP|TFUZ8Ts0nHNDS~f7Kk$CyJ#aSWniy1icPc`en%Hs zFufw!Dh2vQj{HOeE%<-GcokB`AKWSWZ!4zWCBN%##g$>sqmu-TL4o&8e5qMgsUOp8 zan)DtFN89JUaN}{Syv6p-$HXhNmOcXmyxrQt+4Ps52P)HGY-MAV@ zEbo|k2Oc&5D$wF~=V~=}usYMIfV`Y(!tNqS8i>LGh(~A5)Yqyne`?-L)W6878?k5rbQ=C1)SYpZ zdLw~mg1XJG4J)_baC=bGFgNh$HZmzRFjTXee}Kp#>uIW-r`^S8Z!8*r1U3qL)Y5k~ z9tt!ZL<9x<03O=p3=?IV9?4Rc;xf;hiYl9wJ>DP%TLhR}K2rf+8$`+g(EO6*?ngFV ziwsJSCaQ1E3M4H;xvlOxEeexOSEt~xej*OB`j2p8+iIt$&+C(`>Rl%5lh9sFJfNO_ zic=&R1+nLid`rxqCX>nbL!7BS1u79H9-Z8|#Qx?LUfPf?ngPX_OUe*wf`RpOU$>Ug;~7qc~{m`R45S;{vHdyF{DV+gv0TFK~5;u8i21| zy@wxrkN)HAsThaZvuum~^(db)%mWU$mJwa2yPIA1v~ry2rUqrJg=`5JmhG370IOd%3u z8NvhFl2${~Aw#lxL-O52ifcp4S3^jaVKv2JwAHXi$gq~s&?9)!vlG~K2FYEP5hJUi z%#(rLTZ5ceem~Q~|L*nh6hYwM0t(Cbz)T5)^b7UuS)vc^?_jG)q~mIDJ88 zx2q^JkvCl&(|XxG>HW7oYi%}~qZCCt^?sIeh-{X_QX$r}Yu|I$K5jNUZ7(Jh?p>-5h^lFn+$w!&y*fQnA>mO}f<-_eUlr?Z@I)d`)+s}1IfYI!>c@oMpY_jkB&V<(% zU)Z*&7@TColQwbJ;zsw=`)v5r6Y{N#PjVtWymnx5L(&!C%d;b;;DSkf=X#je`W`E_ zqaNJr-?Bl$F0OZf9J_N?Oz4h05VMD^`0Qra9e_n-?!U5%vs`t(kSD zxuka^NzLCVTJaIMK9PZ_qYclXug4;r9tF>8MA&&ZzKVljD-EQ@K}Rprj!fmg_p)t= zB%KhZeg~g!orWI&tousK&*P3DDaA+-i-VUj+i&$cNT5Fi-8UyZ?;!4 zd(`@8kLix~Zn}?;PeEk}5;r(?6NY@3;_O2DXvgzy*U>?t_xGZtGm^~{u>J1I^vQGH zA5il1$YSD>B4Y6Y$UU(W<-V`it4D!dTY57G`AKjAQ8>(Rxi(CK=?FP8pV0{em0?mwNj?~U*& z1u^Qz8@+F1j{@HI{hY76A`-p+qQVevyH8{NZ##KqZ2Iq`8#Xx%`LaR%=RSkeNBGIc z`MB2^Pv0*9gxtUb+T?7|2E+^)OHTP>|I41bD)L_)qYu9U$4~;RQo!1!;kGK%jcWor z+h|8Sne#f%jxo)doQBoQ9>RTpPp?2J^cu=!yl+qfwH_48d9$5Z#)gu9cS%!)dVQbr zL5l_4<3Xh5efQI*k&W80S9v1aL9||TFZdREX`j(}YwMPX`9rbqmaTe2|6LQX1QxAz z===-XiI+XK=#8(H51R_)Ayx^~qM4dYwtU{i!mLBL`ryQNu#~cj%A^W8O10duBgSg^ z^Tu=QlLgx!=52d9~uU=Bbu$)6VyV z6S1@L``2}-1Q#fDSN+hDaA8B`PFME$){~e-fIkI_A>fqHRZ{h`|BcLmx`!d`Qgow5oEFR0V(q`aKa9(rM zWE3TggfImzbGR4*6Dgx?zCv#+H+o6>%hGcsI^S+ZB;#{tg`x7Yg7-x$=(G}VLW3-3 zD&x9>5COje`-`Ohyd{LBSBa$Zd+d=ovOGd6M=~g4#84~_&_9@bTbx*A))R(5#cXC6 zV2IHT`bU+`D*lq2UDoWKbhpvrpiX@m->Z689Dws?lYbQgoQJx1x zFVn{fiJv4-hkb+iPP-CrM{>U50|EV)V}ub&mwYe)G4N0dIN6BhFz;t{&2nPU6i{5$ zKF}iY40v7S_q{Fiz^_2!{j5Ky(oNn~ky*0#)v4jvfn+5LG5)47J7&v&eBYB_eCdw_ zbp%9-n8zZK{S>CMMUW04_9)CQSqD)B9X5zT=GiL%R$HvI)NqozwEUZd?YLle=%!|O zET^CE^t}-Y+fk!&j;q&h`a~;H>_I+oL-AK(f@G`|_|A|ztu5wT0OkhP80pvVfY5}G zDgUIR_)J_z_H}$rrN|c?fpesVbPTD;8{jW-`=9f~*#we3$%JRjB?vIuw`jL_M2kWLfa5PX1tR#Xg=?Q{q02al710@Mh zAXysmW7(WH3HbLb-fYo9)#{Ye=!HbWhUzdEQzMA8|e1}wctB}K;ZVu6sOn$GJ1-_T*QLM4Ar&8lHy(lFO3fXo4iXRNj1 zmCO?V3y$QHJcrG}N2zWRC%Ob;5QRuhK2QoK&;Sgy?^hsQPLjp(X832<^&d=}GtI6J z)GSZ5XyHph;IgEfknR%G$MMnppUsc?@rv2y1`z{G8RrLsMKLN8)@Z`fa8Asq3?A!uqVh}HnEd6Ay#@5 zGZS*wQh>aGnYAM8BcT`}m*1tz$FEkdHg&{qt_4xIb>wc#Dn>a^0ji-4*EiZ*x23pveX5KeU{;2eQD~C zCA$9l-Tmdq%1!Sn7v9#xdu-k7v}`6{9jke@&i3%wCL0$fbJ4^7I+e47f3V&MNWwER>-Y{L?GJEd&lu5pf_eoECSM>x;W>DDGbvcwJb6rzJ*_t8!sE9ndg=3Sj)`+e0UgItFa*#CHPM5 z?v5pMV~oYg##Af?{j%1h#>`UYnwV{eiYsK=~BHz_T6>JY*n04 zhq?7$3hDN%9!Q21PEOdxj3=qfK+3o(?J)7J4_TA&4n~$f$MgvM7(EAI0I1}2|1+fhn=*pe8 zPP@bFd#>B#2fzlbY}3oYt7^6WU$L(HBI_c?e|2#cRDMlpX)lmAl|1^ z0cxe0u}az!GnXzOuXgioWtcs5Z+s)|a({iSP|_wz5bXNp6cj82BiMG|Uy-rJzD}mu z@YN3(H2wTzu3XxX%I{%2QTsV7<8^KP3^lbYC;7OH)@%LmAwRjCe!7NB?9~?j&A-0C z4l~qiP4x~4z0Z1G@lQg|Vxbr1u|l_qRz=912J0LuYNNc8%gDf z{PRuqE1s8jkjKt~@LMB1X0oJHuNSJj7@^6XC+!Ia;P5$sbxoCzh5jH{1wp1pbf~7o z$m;9{TRg~E{i{sxsK%&>ydm(VGD0%Onu&Vsiwiobu!X3W-yh^w95{Pj`b!n|X_fGg z_|UDjVg_zyq4T8b$<8EXO4E?AF;Xpo>!AnhM~{5?2@e(lG>#9bPNCjQpifcg zV}3jyFlC@5Vx3M^!Y}7a=+fv0~4P|(52xT=y@Qg*m564nTz$~HBiy9S8P&e-$YR)Ak z!gEuKxU2h^%P;DZ=Y67vQHCd@F|LX48O9u;qYi%RkBvt?oJO7U;yDiMSxb>hdFqI2 zP0<4k!zs=}tmP(*dn_C~fKeQ4vecN*)y#$s33A~8B&+Y*NK#&xC-;b#Q@T_;+j*1L zW5Kb+^s(e~Yf$kh&TsJrPcG#!(t*hhFM8xx}dhY{}+1mK7qa1l0(^OIa(E`v}=d?h_r^9;I~>nRS~8j+me^Nr66RNlP$f9MK|z zfyHpq{$i0VpXS)4aPvatI^$8gJBxZ3i~0mh2DD3tJWEDWOZU~6j7^qIoR=Q>{}0f< zSX5(x){vQ4uhgPa{s(C9Ea_YlQC^h5)p68;u{!*V>UX1lRI_<*jH#XSm7RqW zUiOdBZXV zi4t??aVdu+%|$abX$Bs{a@hW8{4>Q3V*DHQXq;(iW}!>tIFb}W9y{|pU3s<$qF{qq zXEPSSXDT2i)*&S#Uujx)zWK2Er!|v5y%D5$)6J zhJ1#yIO4V2E6V}RbZAsP`O=P~?xX$vY+5K}Xq}!0a2kZt~X+0m>Fsl10Ie(@5rB%M{ ztw}K)LI0B1N<>SdybZCA#vHQ54yaME+EAC?l(PBQWBrrGrqE15ToT5+^2Qyzb}Y>M zlEq3RVla6;LSWJ6*Vg*%`TCNs?G5hFRf-gtFu37uGZdKRROgrMmNN&8j{x zzq9>E@cD=~zWS;>wT7VKjegIkZrw?1P*+X(z;?^uig?{BA1C9* zg;SYLFn0a;tr6X}v(YPQtmy`NC}lxicbg{0Zb^6?*7~_fYaQ=K^T>W?K6=HZfvXxo zf|YY32ppDfZE^BCd|9+>)r~)0s*5m)$gUbRY;YI1;aPRz4zcj%gM z5K*=v^4{dSj#EZ=N358wwunfDeT-$@kPb-y;z<5}HbSoTwY>Czg5KuV(wBnqUJ^Fg z4jx*?uL>%C;a|QZU176uLGi7h!l+tHBZg0N-EKe8Mr(O1zj7qXT8o<}|76sAu!#z&ib_7YTg? zmA#9V1D(2~o(nC-XIi$sEVxA^11SCtfnv^XajlCx-3EnAx}dn#BMKWII%S;HL&a&w z@CPoj8;+4HEACo#Pb)s^(QUJ6FnM{$|LU>0sUvj>N#Y3&5V5>AH*Nj$_d9H&#R-7F zyqED1$PkWEW{TA#p?_l$i>vM^*_SYK7Uey7;o`h?NIa0!7T@2LTIbe2;v6Jxo<$kE7d&9JAz5#&$ zt)UxFw%9jIG;sA8-FF^xksNYA5Q~tx>af^!KRR{KwQ;Y|*wxY_?qJ1{oqV=z2lSI3 z28MZvP40LWc&zqAjaH^(5S!iW1wB9A5`TWfXt-x1BHWo_U}V1MOoqp)%T> z|NDod=H(+PUqV+uWtZveulcx{is$qebVu2|M}^Cqk8U?5n3?Z;?~gtB_;K3%=kB-g z0Gv&UWP}-n3vJs*_~@nJQNEonlj>0gO!Az~<$!Q}bNP6!!tEC!sU-w(J&H9q^SILR zk=3!t#>LtqAl8P*AApu%=|?;#NKl_Uct#7-*HdQW@{SkBO^2h)>IhKwy<~G>kUWYA zggUkp`5F+^JEYur$Jc+$wuv8aOd%D%HtnH=p6-f|HXvpL{cr z!6jjcY>eh?KJ@f7eH3f&iMt{5A>ZXXOW^XoRpQIe9A^1g%KZmprju-+_csk#G9f^~@Lj#tk7ms4bUlv2 zfWRk($X*Ph4aCB%9`5IwPro}I|fKgcG}q~eI(M4O_x z9-W(poqrVx(42v-Q(y>@tX{CAd&l2s_I|YU;xuJrf=^=f8y+CqW7D;ATR@oBXSwa! z%s^#s*W274Dx4K8R`C)f#_$nOnGG{q{`zw9!48mG!QvOeD28L?pg-+I6S$Jk9W{T- zs$9x>&{H&=f7;@@A$fm3J!+jFNMs9xMD1ggS&2Usv!ZXo*5+8(-8eU>3OM_TW(9CN zcW*D8(W&QoQgD66&gVZc#b#*R?& zxpx-5?0mWkz@$pFLHw>K8>(P(xP<5ae}MKaKBF4fQ_j%@CKu1dPej)&*2KB@d4QK-yjH-~! zyE3xOv@c9cn9@o@#81k8=#UV;p0C!%sG7W&Z@yf zGQYWZUGvyd1piD+WanOl9vRfF9@O3I@itbAB`lxKEbUjeq=J;<)ZEZbc8@1|37GFy zIQ3l(&WMrRY)uLjdH>~2#z$07M^3<1Z;DtTVuPvwJWo{NKcm>^My1{Q0%SS+qR{#ncCntRT6RlPa>~jA5XJMqT#b3jIPY9XQ4S05MMz z>fQ809M+AOBF%kD+1IkvpObK6q%ZABL9QG$)|%ajuLd|GL#pRfm7_B+VYhy*5Iq4J zNV45dqH8`P9FeYRT39kEC6pHBRX-6$|4~RNsiUp~jtYv5q^$`Yew6ia6s!fk=U~Cb z`(c@fF(l#z0E1BF1ZtvtNt5HnF&rh!$(BOJ94t5g8}hPKew|2(Zz@-(aZ5#DQEc-m zF^YpAdT<7Lq#Hj0uYmvSdlCx|o$<$c&AStc&td{vb4QtaSKw7Gn<~+gJaw*&RMrom zjN_H2BvZHV!bqHG3PNy%FUqkl^G$Xkw@0;V%4Zyq_Y(rrT_jmcu|M;5=;;DsWLL99 z{_k#OHbP!~iEm3CXB{RzHQR&eA{b7PPIO(BYD%b8q24PnzG8wwJA7`&==x64^^+-> zi*Jrs)`=b^ru^;T0lw~_nLGK1mck3y6!B(ADdifLUy_50+)lep@6+O)Z?d`+KWP%4 zb0BN+e52jjAEf<^FSXzf)eIddma$GOU zi9O=7GIOf~#~nYD=e|N8_ZO>TZ^Q&{c9)u2*Sy;e*5F{IuG1@nepGs6*LpTX+rIUL zgZN-2tIWjUgt{Z0oY3|x?HyJw2^`O&?}7GOVxr#U zH9*8&H8+Y)s)kn3FtN;z@oI(0DlFppg!0KVx#wDnZ&Y`*sk?Y>W5h-ZJWW)eTW~c@ z{9w0ww^uqP3N7jlsQF>Kf0F>^VwA)XS#1CmHVP*grG#-NKZ8Sm=G-}T9qFdMdwZw= zC+KcxbZ44cI?brWVw*{;MyF8flRyx#K?uM_zB=CXrkFnrYj;S}-Cz1`*(06tRI}26 zoId#eXVMi1`tpBYk*10z>=8s1loT;syj9hLLHyQHyv zq`lqpp!#8&q7O2<5#5Oqy-pRW-ePa}9j981APa^=SPmF=OGG_KjZ!$9C^tdUHN^q- zcM5b89tb)P+x&c!cGGjVznffOa)uMWEG7p7vRlSiFBavw2kjYRWsZ(gZZ$+QjAID= zDr}C#`Fwg4`~C$TTEsnCEM@y__dGAT;BkHw8z7`i-fKEUs478oH2m~hWBfPBH&0bn zrAdxAywZN{F}u(RbmYld3X%CZgl3>k_B_)o0Jrj2vdIj8sztz5F75Ubn!?q`8Ohen z`Z%_H2ynh6KSQTi(P+{dT%bSu(aUjJ<3Uy9LD@XpHCpx_a&~}!VAPrIuFw6ka@+k) z+w?0Ger!an0id)7Wwelym24=Cn&b&e5)(-VWNu_r(Wgf$+{FrurGQ23#FvI1MVl#U zZTv8|%O}5KM_i$$4w2g2iwG79SV_iy^el}u_O9%>iq)*@3Pzr0jYMM@-W@5s5hWpO zH);PugIuHB)0Q&GIt~L7WPu8<5yaIN?%1=eF=Fl&Yxq4I*8L4)Hr`w%E-{2}sqa&v zvW8(92sOn)m2C+3HAH1Q%1Q~#poPlK^;LyNfFh?_IEGscmARw1cp%D(V5%zi zolX0Z7F(6eSe?KnE`}|R7wZU(Vl=%Xuu_Z+6i&JnDfJ z{cc89^GhIyAx-&Fqq8CW$oBpTO*8xZAs9ff5Xy?R+#z!}0xOa3d zbX^LvypsxCVk$n6IrDPt1Yoz7Yg|;)%RC5m;$~3>B&s`CNJ8B;U!!8*>ok(U(ia;H+TQX#u~&OOAYR!#)JFNk#V_(#LxS6m{>nOWxF~-{v=EMxp$L*B zwYx3MAGK~q;b|p($)mPKqA9r7-Q-7QuTWxFdw1#X zv#mtQ@F&PD4zU6lzC#Od2Yx|$-qY{MjeDrxO{}SPqMiA^OXm$AikC0s!SK<=`ti=J zD~X|9r9Jwvh}LK94xWOp?T>Xr*c=9 z+<<6ol(-lveBenqA5_7i%9GNqQzOKX5I=)K;O;QV6)GvcUkRzEimzrj(>nO)7&XdW zl{3S1H7qQ|ma?@SI8s$KEntz9stIhW!Uo_+0=#c;N;g%}{PHn)zgLp1x}1)hdn!tF z5n>erX1$AdpodJe22>U`RMVqM*wD~2C#tI`xDaMoPiW*p&4`WAsEg1@5RxqrGa4o| z9&a3WaqY;3V9corLhU#iaKI`a!X;?NdVqid> zC&3bZ9w~Q)QDqPs1Y-u((0Msu9fQhkpL}}~Q&*7T{F1=EV{2b$-Rfu1hqR!Ke)yEL zET>9keJtIuK+%#y3W%q2h;Q6OvY0vFX@>Jjo^4dLGTWv{%^SC`;N=4yV>jXe)u#jvS+ZyQSz5AlW`w7eY$_p=deUi|X$lvmWB3BThz-ILyKZGIYH{KpS z*@OiTTxkh`y%tr^;wGK8b3XlHlnOdC?6%AhPC6>7UVWIxY{CgXq=Jnwocy6~`NdT9 zg1b;a&j9(inb-I|bWX|^oYqYK@Iqwz+%Hlxy+V~o8r|^E)e(*7=+`YKwakdDjGjKW z8fv)*M{2p;3^g!5(Qan_7y8EbRhG`978HYEs0*I3E#>D6s&?s1`fHWy`%r z8J$)gDCV9Q$}X{bpSa(cx)UMmHnnni=hM5C*zR;{cx zqvIUcZd9W}+WomMJoomUC@(def$$ZuPm}E3shPmB_JGHxFHvQ_C^X^o0m7#zL|xTd zUV3Z_SehEuYB~bJE0iIX+~bkfR@UF(_W_uvXhK=3c1{Li9$7h?-`*0Jwhw=!_{FIe z#A%|QXN8|4b-3sRN?Qcc#Mq{X9%2VH(B@-oYd*C$m(5&6vaZ6vQQ$k zH#Q7HLsLn%T?Nd&5g zewbl9N`PiSa1A21yWacpJ;(w@AT$b)DGo%n5Aazx=e9LOwdz#%kIKmnKg62ao41)> zE!ticz8X6>VJD?SbFV}tVg^(U490Fy@a1SRGqov5znGJoDl$rR|L@RkxHKl+p&zVC z`7iW)NF;uZA*!>y@I2BK&1>1cB&gKR=P=4OavjQ{W~KHA48R(q1Z9y#+c#j@6&R2; zAd3T5nXz(0hk}8SwMQ$#Bi~ffCk_omDl7c!PtE2OrssaSY%*VKV#}qSekNFAwKEf5 z-v3wsO~UE9f>BWsJ}69*jxwYlros&w$3(5X!pLoF?a>b_-HTKWjC`@=t(}8iUsy0x zzy`v69cYkImHywl!hXe`Z!QS<)<-3cM@Yt}jrK9?go=z0QQv&keQjLb*sU!Y+Zt9GUgD2m@ zaITs6DENW<8yu;Ne@mD%2Zy)2p*f<9Q!QKp$$;y*nLYwWPq@N$!;sg&S9EEE+IAR8 zQASvuA%_6jea<3sl~#Da96UUjRG!AU$)NHZOWsXow$)(NE;GVu{8W_l>p?k;3+wwZ zCWSM{l`I6wG59jLUyyi^q4+Q^!Vql;Q6QE-^8eKV8(>+>Wa2dOI z<>g!T#E=t5N{WP_1rddhgZG7%f+MLW7(x6)T*-b>Ul^aRnro1y#^>?B@HqtSC8hPB z&l{zRQI*piKKaAfqoYdRGO6vDHmjmsttMr1$7Ft>`aWjxN3`pZTZM{l5zrXxkZReB`Dl2jYQ^lzczA zN;7QZfgfstPB`EgOV4ljI(lL?i1l7ZnR$cwO<8Rcvfp$g;=68@iszfhPx+(iGoIpO zU2jK+d^>1~N#)qbmo^n;rsFq@lttofBBMJqokTzb6?83n`}^CO_AYOoX5o6iQ}MP# zChx*lp^P>RS0`VhO?;0oc1t&z#JH_Ppzu|ujNFvy~L%`qrU)#oo~V>2J8?0N(^4~>GVf;^92{mCKA>_-yG-?FW{+thv(!f@- zv3uds>!PgU4k{YV^PgY%0*Ew=NXkj<0p&_lej`C^*Jf{WmCx;U*NHFZ;?NQBWZ#D2 zjkSVdKJ43>sCAP4Mty`&9{f8*iBMCJY#3~BU5=IE*SBx#!`<>#>4>D#FXwK{ZLuVG zbz3MRcsnEW=`MI{q4xJ0gV*x=^*hg=5Wu`7gZ3h7RqA;_Y#K0tIC>iBCm;sEbu^(o zf~$7U;~AB)`!Vo#g)8;(;*tOH6O1x8;Sk0L4QMbHgHf4e{zk-lM~1#i9tTwy!XN}6 zLw;IfvI+Co5ybws@WSZcj%@Cub(rEpeV_vS=o1KpTM!}FV~ahVMRCL?2%2GQJA^Ox zuoeVkJ?;&Xiz^W1-2%~EGjqu|ApJ@D({B0)&ykn0th4C%~NYQvlYvQ{XLeY6=%CoPphhTP*0Evf&{N$Q=_l<3fwDD87Bd_>3*=ZSvH^+3 zeANJl+35PS9cH)v61N;2MzXTsj6r0HkMkq8$2vAr62Y1Y@%1hj4D=8M7#5N3Z`YaN zJ$0q2gkex}G5hluAg9}LenTRQc|eJXK!LyWhk#(ns~wd9HiVdm;c2k}hd+*!aDuIc zB}D8Zg8Qj1uKRm(1q17W5^lz~5bKLlMlzd8N6`c(@wx&y=zx3;qE2HvA7(^}ip-Q4 zBi)6)ed-X7~Z!oBz!h=y{7cv zD2kBC{Y_WlmvCg$1X+6js9P7~Vz2lv1K5ijjGURgZ$N9OmoN2GFpp~ZT2KJrSJC;c zcmiC4!*XS^UVzbnlbtxJ1w|+@Z*jv^Z+oFRsw)Eu~dMT_@|1@*uB^x5Yvcti; zDS~LK`a6cP8%~ohWJi4;(QA3vvvJ}2-Dwj!+f>=)5m7+QM(L8}>eY;?rEdqNPkS%o zHItx}C)Dx%lAZjT!e}Yf%3~?7gx5w^^H5Ld2SLsU*ZHVl1EACa&wc$>S? z>5o6ZqTC25I`)OkGqm2cZBQa#)j?f(q7?bW?M{%G1@|z_{i|LB;?Dbz1&-fI69A0B zrKOb4fW1{mf2zM}y~a;GFQmsTxVne|DruFpnpyyl2TM}LUx$esm>ZnE!UOBagM#2v zwfmB96Fw)kv9qFcSUu^XMYN6^SLI8|Wd-!opPY3utDBgx8%Is470_zVQm}{v^%@g- z^I(s=AT08Lghn&?=eEhD90pXX{rae**FO`IUetYjwL#?=WK)3YPa^e& z*J##YapS38;nWeG76c@@=8^i=#%Vkgj0bqJ#Qc0%J1jQKd?kLO>9mu|-tABbkWt8O zJH!{Buj)RbR^skg7nSH*mHcs{CJ#xGcgW;u_6@V$l0<=~V-Ui<0rR6!+nY+J56yi1 zgl~fyUt5R{m_BSv*U=#{n8$e`#c-QcV zR{D(@JW(ce3!JmU*ErQrW+fuK$na$(8RQY+^5U!A_60PQ4NTB+q-wC~d@2J56`9mr zvD$S*tM?)no?DIEhcC{ftSF~cZCf;WSIP0OcH?suw9&S)5}vm&&BFUdLw`ASE0dsp z^TK3e%Tu>A4ET!BK!qbuo?p(~HN4(+!aZ7055LdH7evb?_Y6A*r#gy*}>7?*fniFhcoLgP7I z^ME<(2RMdB01X`aR67}JT0m50or|zlqZi(!Aq_(4E8RDLy<)5B0GSDw;c<~n;>@Wc z(Z>TRrjB|J)}%HeL*3MK=47H%$mV#G2i!P3*ltprxS|%fIvRQU@mG0c_nxw<931>t z_H>T546RexE{;gFU{LqOk7)2I*k8%ig0Se%Msyy1Uw3%{Pi6@iV9o`2ZG}>wPxA!j z=Np?v+r*ZadhV}-oE<@mo7ZEGC%?Ie`HG)#&2!7TpJNNan+=*B;P8$H*5lX3vMIlx zI!g#<9$xz<((3HV&pLN?$ ze558Cf>vAvj1 z_qnOr!^Js!uNFh)DRC(;^{bh2z7V3ZZXzD#X_CLmwf&RbDhP7fzFW4_?2UO7O{J+v_Yr-HpqGW7zDbMf&93mR{>eOV@d@j^!-zS zoYE$_VmJ9SfC6<0O$^ZKraJG!jy9*{*PI!e)xJ+*Nwp#OS2b!T_~HKD z2**_t|K~1|AP-q%*hvL_Y&TFZkoAp}H20B(lc1g~o#`$yl_?%TDUVt!o&kyIEuJgO z6S0{Oo!WV#%F7fZZM}E9Ns0!bRM7&<*9CIx7kUv_k&%RUKmf+m1~yX?%x{{v`0UOh|N$meheV3Q-xmyhzA$Txb9n9ticBxs^BUkY>$z2@J)!Z)7(X$y%k zJ{#fG-bD7DC88Gi@bcY=uyEyO0~My}G}+ zwJdn`HhGV`0SB(V=U;oxy7{aLxvgCLe7{C>_$lk`>Z1pRyp%%o-^8z*c2@j?9~SsQ z^RS87&M2N+=Rex40xL2PF{PV!3{)v$ntPm^2UkyV7$o9$trHpRT2kuDF*@R zV+%Le?WPDwms=(jv&cQNyg9P^CbCXAs(caiybH78CaSwRGSduC9T?T}%wp?DPxj;Z zL%i07e6tsQHiTmr++z0^y^n8VdxhdI(|m38!vz+?tR*@B7J$O(-toXb2MIf)>zkqj zr~;KyvQmfD1lduVFx{a^0v<^sElIC#lVBc6Nl?5*XtL^UvWSOA4GdGI&rSy`m-Q}UXccnTRyvKH>bn&p}zW#!W zMJ5_Z-GIWT&`Y$*pC0y|+-;B^9%nk6Po28)hs6WdXplv9m(_in-_p`k1Soiup7{-G zTMtcIGx*e$n&V+0en_T@iUky|r0)UvhagER(6Rvy({b1`V+!&aTT5P$Wq-I!4znbY zA}cj-K}Q3c@V68?8(42Il_8(2bi3xono)~Nk?VM}q$NUp&x>2E9sobU2|JS$%< zfzxcTJVgsMm#}_WW5=77eOxNsx}{23X8AFn0~rP)BD?AJX)Ey3qvqx-zP5(y(!Jvp z!Q)w~Y{{s?%uJ%1NNy8NE;frXFsNQnH`^sEdfgzOqF93{1JP~K48UAA0(qReDQ@qq zYRLr~?rPgS>NJg18@sWHR%&4em=kaD*gTUW$a9$Q%i2=k`=l4CM-Yo`5}tap^5he3 znl;O}nJV22s8M`3H~5Z6@t{W5Dq@iO=%4!Xwvq9^dc(7cb;TM%Do7e5rs5Dx$_B+Y5kK7h_)#F22~G%E>$EHgFuvS>jf-l_!hl65*I z8~JMY;Bt?qm$U;grQ9fqdjL;xIqCaL>sQ82rLJEHUHf2L$bB0i03!okH}wSebA&zt zAjupk$q)~VKG+gRqmzh!7)FFTBY-3iK_JnM+)TIY0}daZ_u*u&}5-(J!Z(`#F~P%k08Sa1xDcMxQy&6)okSG5s&^J+@6c zJ~{@18~OoTfKC;C@(^9w`vNOZ=$c_h`8DX#DAD zP#kZ{_jpO1m`)CVQTzxo-+5&63lFIqKSy$h-e~M2^)BXo{bW1rbd&d{hZ`Wx!#~ZF zD9fAE2-*yAV(R&cj`ZSbHLRzL-a7y$TR_N{Oz_RLr7*{#(3`c@7k>(Vp($~x>vw7J z@?la!a8J^)kezj-`rKCA$?h!vl#*z)xhxB2@>XL)nC4$Xdci?|%si$I`VM>128xl_j zKd!eWp71s%cA!uD5|>+0aE%u(07H6#$|T^~Olp2o%GnGi(p%E$odT z7VvxsPoN)4U_b!FIU@MBhLdUR9tykpN(QZ4o;Mw@aKfXrF#zE5h01Vz^Al?T4?W&b zH8NJx*lzU5@JcUvp2!Tr}J4rBzYm%rPuwEB1n92!M)eH@z~ zqMM}S_kQjNV++^9yM2#;*GUWWZkRkizh1o;KW0h#qD;f+g(mbYA-geK8ZVB$h;2b9Sv%gL z#!ooV@o&94UTrHhR_oxpZug?el)zi$vABrCb2@ax=(y{2!qDxE_JCVYV7<)+k@;;kfs8!KJ*GqsL*`*0c!#pwR}uzIBX-7Z=*(L$ zq;b4hewwdCZ?;R9d{JF?*8S(G6v*S;ZiON7e2jav&QOvTJ(R!xjA|eSaUB_^?9T*B z>guKuZ&Pup$}_^36Vfcw0`ggQ-Z)v!sS)fmr=L8vqnJwAMa#(Dt|B6rpQv^~^`+E9kt*%2gVIikckzt6pi7mVe5UVB z_rRO(!IE9&?;8w+l==Qs`NSru&1$p`4dl~ zhivk^WiALO7)=(QQg-ZS9ryauFs5l#9kGz=p&+p`*8PF{R{{BA#a63fO`C-0LtXW^ z$T7-R`tJ9RiWr1q{>%-WTir!kuAl7dvvm?bO^6yboEu^F4mkD}VU4F*u9||l%*ZDd z9h8{jF8Sx6ha%sNG`)h)C#WxvIB@p-`_+q*6Q{qjEU1=${rRqR%*9BelB8j3_Z8(1 z~atbB$jur>?Mv1G%RDuoQ?bM^Ht5r2e?| z9?{`rxcdBU)h&{}QGc`lV>BD-`u(j*B3wktl-;fV$HBMFtoOfLijWnMQ^n+jM-`R? z!|J`xldp0}_KG6JJuQmA=%Z)6t1rFttd1JxA5^2y;X1BZ`&D;yoPnr08TqSXJA#QK zO+mUOk}370XmJ&j^zcs{${zf9|7E)zu9w- znG{m7q!`{m{9RA!dv4H>_9|Uu82m`?|3O4D9E5=c4@VJ}yp}DSQwHSKAggF{$Y*ln2iOs~jA!wewl(Qh(s~p5l zmb{D0RQ}=3Z0{f9gm>?)=<(MV$uAA?qbLjmguA40*>=W)nXQ6}5sOr!xWgfD0?i?c z*Rs6XC!xOjRODkfT??{2uB6F^6xDjeHGl+$O#31H1?C|%901vIZSYSxwBHv7h_A9& zV=*Y`Z*x40kGIQ95ZACj~398*@%DKu2vD zR9&@WmzLhVZ#5F%zz~f)?%ajKG@w&vu|`k0FZo7^AT7E5_r~h2n)xrR97av+^IALA zMk4l<(UDRKiMdW&{7;$N`z1otb_L|(p;?Ms%G?J1$cs*iX+ecHH@`*dS33|paW@al z2G-DVHPZemlKn@?29=bM}>&LDWngS<@h{3TJ%iGtX{;DXzq-a{zvMi;365+tj}@q};XE+j zs-TjyC9F^0UbEz8)XmfUUSaZm-=jw{O+;gWF9`pLySrlX1UgG!Igi12-14$a&$Y2Z zVE?V6_CnL@_e>9}Xeo4QblB={9@jCp+J4b&LW3S-xT<{>iP6}O97-c1E9t|BuTdt6 z`a<+AE~5^1ODkQAoFxI6H8fY?(o}+-=4!gCPsJ1}y*cWg`|qoy_3&~26$sE@b^V47 z2T1?^0oivj>hu~qMPjN9FzfgrBEFoJWh{7U@A8aR!W z{z{}aXnREbmKMz#JFuOYRPBst8X2~{cEp?yOjCq;Z2z%GU{ z0|o*d74eZ`TkPBS8+mvOLU#k zFdyfiyXx2!@!by2QPS5I6FKBM1?N#gv{|MyJ)()W9L{ofCc^wiMw}x@AtJuDEf#oQ zt5hJD6Q-B*fj!NsnAN;*HsMSXzZcCdVg=$Q3U;D?8?D<9xcx9#`9qJJ2iXHlxs0ox z1Y5pdEmTu3FBGy(i^QK^NBUd2pnROwDm1hl`nl)>&ZkDoI>-r2ua+p>Dwy4STT8EH zDDJV{>b1+1!CUFdLZ7pax0Edu*KUJ8?uT*MkIqyM3XX^;bEWSQncFH0WWDB{vgzMG zPw}gviXaF4&HAXGJ%81#KN)@OK5(|M9jZ4wskTyDX!PyCv`M<3GK~`w$QLtLm&UT{ zl85)WOuKtOIvgwWrO@Z}R>upla&pCyd(s`K|2gus=Ip})*U|eWH#;QLi+V!ezfJ-V z*!VvjP`A!?^gojR_TakheKP*z`|(xN3mW%t&c0XFm)^86JWJG|cNCG0?&)glzvjNa zzkFBpAUilQQatN>`?~%WY|TNp`T8wxaG9J$Ny25@g4b^M_1*8Fle<5NSGR#Sows;g z_gpZORIS0vi;o#ziZK4YVRoT zx-(d=q|wJ1;_<80(@Z{SQ~ooh zyE=7RkZvxR{?>f4lP+LU|O`<(#9tA!1#o!@%dmY=5k1QgFZ9|IfjRi(S>0ugnbMnb<-!aH*>Sqz>p6Q zo-GM3Ll6HO5<1NoL_8Eqxg8pz5J^=ZJ|q{Y{RM#@pB9EaK&QVGX4M#xZ|?EsI>M$b z)DmX0AsAV_7ll0&CD-8VI`6yo+0x5DERluO3nMB`Ka^|FujwW*`$oHEQA&%{sQV^r zMS-f6)VW+ic`z+H=>~!?ZR)cZ?KkB4Mn1;wr{9=MR9mxM*ig*n5bZBg7dWZ(CTYa) zy~wf`q5CXRhYI0G!r|}3-!F#yUJb>Mm&Wi;2U(s4z3qvMDaD8xfQ&6hlYWUb6-?BkG-kb;#-PqEwCgvJ=gbjZ@!|(!PBp2^zs-vb~Hl+NTPuYc~n-ALt0n_SO z=ZA{K)cD1mO7+U7oQZn)_B5Ot@`#WY{YjY+QOYUhz9x_Q5LqLX6e#Uiq zv^1d`0byE(NSYein}e2|4fI4!{cKFE0`JB=7TMfeQYP?09P_5Zrby1?eioT%9@0oY zpJDhhS%DB+0s697uZLMbD_K=UZrrZH{cvt(ME+fA{%%Clj);P|NSrWMu^w*$bUM!v z-;;&=IEy*_rsMITthdEceA?iY!Y7TZau;4)5~kr|=JPh)tll7}VX4&9utfPC{&{$bKY5upxvqm@ zG9Pg%>zx@7ZGLKGVW3hLmVTL}t+LCzQb=T}f>KFoMv(=1 zq-}pm)pA;)qjO5?R<999vP@R*_aVl7}i9@&l{t6Kj=TqZXJv;FB|F zK3fIXa#``a_$jQ67Pe@ciqC1D)y3{wIg+@SU>tKEoea^ki|!1sF0?haNx{llBtL>uN*Pu;Mm7-hNO|gui& z15rrDDV{(AQU@6K!VI^?5kU*WM;ooB7=feWY@kkP;O#)a_2J`Qp5hGC7Gqb|GexN5 z#^c3JfxFE>FW!H3*g%>jiEuV+a*Jy6sBH2YZSr}E9`D~2miI2wu&D8_pjoLw)~G)6 zuoQ~`Z3~Vg;DplWk1lD3wkZh$odJ(dv1QCq`r>hkX_5A!AUP=J-*^@P587=Wmh35( zj%K3`MZpa}G6E_HfMQRdg7E=1bQ;e^Qxt4yd#`eP|NHjmqUrFIZtvLD6WkpA^5Bo696zf#S`oT z%b()G0Dzn+T-+{j9T*qH3mTjPPrb#%W$R^OMdt|EMp z0Dd=~6XszT7}|wf0|!vWW5Xr89ag~Br+AZAxOr3HuW%f;_8xYMtaqc0pp60C?l#A( zw(iWXkahs~DF#>GP}JB^%+XLBXgJ|$D1K__MHkYS=;8FL;mon&?4#iq@#v{X!yJxC z6lRE#(&&+rDqu)-SEzAU_0b3tXtZwi$2XPHoA;wl?Oh6^B#Eau1OR~fDwtgZw{{9F z55>K&#oO@j2IPTQ$G~#&?*Wc@NmJmQJX|pT5FMPrI&*M!sGbWOfa-|*X4JxoqFOGq zA}Vv@fHEj?#G<{5L@*E6fMQHw8cYYq8JfbU0^@Xp(JUlEaQ{z}tKb=9lsWrxP{25t zw)gwS`1(T>t`S~}1`453-7aX7Ub&uXyfp4^TDq<9Jd5O?dbt10KlSh_!hh=FfH9C0 z<^hic?(>!~0O03M&45!19WwI?dY zCSnk%BZ`3!$}|+D>qIyXet~m_xyQqS3C2sF>OP*rujT0hX!J0H#*YZ6WmF@VJTv#w zGcE7t+^QEeJ4)wTXz{%XMe2xNoe{!#iDZEQ#`yoFz02>3Gk=~yLYVmaLzLs6?Q7E7Tc}bg|Ft^tTf*&{d~0?Aw6T?TQfWE zJ)gZg_91FwE#LQX;SguW|3l#>Rn^A03IFKQ!P>8*$Er0G#QG#oLa|BtX-xIG$=4;- z+J)>S6jOMI&*~BD8h{$^T%EE9ntvE?zT%uA65rT=HPd?x2Pytq>{wf^hSP~}ZfCD0 zx7L7vZ6M!l%-h1zsW+k2TU<5kvv+H>EO2&TS5Dk5ZqqbK?E3A84efC_R^=8><`xP2 zM$Yk;`SJv#!{&=$Te3A$jXu9U2eu^CehYNMHMq8n)ix=fN?)IBDAr7C)odGy|DNjD zA&%YnHNIhWQe%yaFKE`r@4xF&v+MOQK-;foSI7}l2=FgJJ7+ggZ7+OcFNS(A=wvS; zb}y1^KLvL$*kkbFlP(2DCd*2((uy{z=dIb3gH?W#>=I zuRlPVePs31Scg;exIN6Tr=b(4C?Ao{CA%}{Pt2n;_8#j zmF*;zbzGyF#D(2Q1_!?jM~UQ5>ri|+)~7})_pjH>-Pdbp*Iv2TtN1s8>(_IdH{lXD zIO#XzGdHn6ZqCkc#`tbOIoy7UyG{Rkn>l%#{pU6p?=GMFu2B81_~YI4gf2&bg-)@z zB=NRRv7p}Mr)*!hCMa);-#pAyDMd|=@%|?id^bypaf($VflKg-+{zL3W_A$31NiEX zdr=EQbAycic_5(0UWelCfkE__B#Q{V$#rn&Dc~oIJVA;dl-fD3 zy-=A4vAG;8H(Z=49u38#S3}V_vlxh>k{|(n8#8(N)>N&;_;zMb6TnNWRAh@^C>Mkr z|LCPNg;wuzV8zIyFPHHuK%u`;NA%miY8h&=7USOAG!f4YNwNzpSGaz=$7O8FUu@iX zu>;5Bd5Ym*jP#w${m@n6bVhp9_>}vpMLvI?t@iEKs%w;%H|D+%$5mg5+g=JmyYF@G z_NesZ7728=x#A#}TMW$(m`1L;0LEllIy$Bd{$JQWlUz4L6s;}8#pNi7m4Sed}<<_0(+7{s4b?qT6U}l5F=%PcYlrWGXs5v$pB@!SsCx*s-JE@02VT>6PsZgfcTd}YsloN!~Nuc z88Dp{HZhXT= zD6wLCT2@6R!eaD57zU@$mi`GNoeriZz13jqKV z3R2Z&ut;+4qMt;7FB<3)K*?EYm~I780ULYxJDsH81x2?vgW?%L|9*iJr-T(YjUXk> zZ-&Ix0F6V~(t#dE1-%06eYsMxbH6!HgR(s5tjN^w65s_AmEABQMy%r!y^J&|*m;)c zR3=_fFOrJLBt%$24h)l(M+x2BL!d?hanmA`p{!j;_*3{%Y~*@Pvt-AYDqdjPIRaYz zv_VOK|E1#C0N(nWfwty3qrhYm+U~VPSolk@8Y(t`6?{^wg#yrTPL`TN_5U2ez8Yi< z0pv=es}g|Y5@H+;D4{N95PkR;K*KMpcuL~^-!Y*OLd>N+E%anmO(wBHb)`0}p2 z31m`bM>nr=c3Vkj=dwiOgFB{m>P678$eB1CguEQ-GAFw@)v{I5COz$rglb4p(~lDJ zOeAE;S4oqY-*rKr|Kv2h^EE4M<*8%iGuPV71|@LoaY)QS&hEf|g>RFI0UW=BD9?M0 zPNHL+sw@L#q?A0M@_PUTAXwMG8_iM}?WLSbyt=6(bv-nYIns)OdmTFX@@hG4R0Ygm znLh5o6wcel8%j@!Ov%ay6Ad&ERu~E@;2!y#(|cs|0^M``gEa{MU^5SRQ3$v%__@yHj7DsSZ{GR>pf!5uCr}g(VlMg#VV>=iJV6;ff`y8Y7^wHqD zKBB_367}R>>S?faan@s8Tb27;ht^(&o`hEZ04QYJAA_UJzNkbs!4}zFR`j4QIxc@@ zsjIpB`{-%GXJuXo)amp3$83mGk{9I;(-8BRQ{1O^y4)d+!B=Cn(W|cgc8*UY&o?Uy z{J&7xp~*M*R1Y~K!lc`wbT_gu7d4~n12`CCakK}}JI{icy*F_D+#NPfqjNb5mp>TX zTJnlJ#6ZM$sKYKhYxv?^;DPK!O=0~;xEEirJGOSYhU|?u?34M{_7OXt3ms1`wP7Yl zmdsvD-P(6e{&?+rtv^1wb)lP{{^u9_m`%^3 zY`nLq5bi_rrsqke-rJmh9%DA9e=~QzcV8hqrov1w3YmTORsB5YO2rf8bbJm?5T1*J zoo6*>#xN^Mv!z|r>$Y8=KWl1U>*#N8dYOIClC=GG#ri1XSug|-yQ7sO&tUrb0UN*jHN?|+<|TJ(*p}TfQ~zxd;Fe8m<7o;9?hCGh#MS+js#GW43obJkY{1OS&_s&lEkBI z$B0MgLh^s(o}a+5EO{na3L>+#TqSN^I5rx&@D@ua|AEH)2aVP!iouN=E%bMg!De=N}@9gv4_b3~!Mz zAPrRD3G-tC!p?utmZ1Q}FqFc>xb=ZZqte2oed4PXY-EA-%_vIvvX)|URvf)RK!{^A zx{E@nU<;FzySVyI7(=Fb@ZXleaKN(_ZU0RMP$r~eMXbtzp>z}J>KMAGDCcS~?}j3! z#}nq3CGS}!??n{HlSbf1TIF>l@Aoh$HHP}R4Bg2rq!?KtSY>D&8v{UlivnPICQUh< z0rCJslsjM;;(0th{eN-aJH-7J;{M|4;h%ATe~-Aky89RL`}7~;_X=@y{9nrNzh&RY z%gd*W6U4>l-<#{J=W%)QU%2nnv$}A0cKD3`{#idg{YUma`DYwG9vwaI?mq2LAhw&1 zj*k98eh>Ec_xE;pclUOG|AYJfIehkg7x#Z(JOjTQ8|&-qkIO612Jr9o)u;7R#8S$y zU%%GY{=4tHurTxU=g%Sd;^WNB{QUg0_4_a~a^KyJnDIx9et7C}Ky)fR>%TKIGt<-m z@V(>XPjaX+`5~;G`D?y7JM6@9pBd4=H{k;A3zIv}cu5arm2QnY`AzE|Zs&yMeY zCI3K`|6_LcQ{0>NtmNM@(N*8esvAn5Dc|a6(6_$y+3~Hasw(=Lms^>YTbcQ9(6_j_ zIKLn-H#hfL^Uci6{PN|?v*7!=G108X`MANK z3W^Hqk6%-WYAT)2w}Br9)=ydm>c_W#*!N+u~`O_Db0GTaY$e-(yoM zu>EPL?t*u>-|W1!?YO2Mfnm#wk$osL*Lryxx$0o!7>7Okn^Oukc`LFNy-xY8pVUUI zvi|{C(S^@Rsqc?zC@cJF7#--%+KW=Ube_T88*R}87Z986Mejbt!zX`n^KMcSos&P6 zaunSbRo)TGH_Vcg1xA0{xtwvd|Itw|lwo zeNTF^KR@~pev4^6z*2qFvGs10`gZ%f-=xI-HQDOjjC>c;ft`OUzDa;LeyTzmE+D}% zjIxV2&deQ3@Y`0NOHVG~b)Gc!m)V)Sdp?d&%soc-BA@oA?+o4%hV3QQp;Q%E0a6C zc=0^fA~Zqe3dO=|)yWP~Cz8yMfV>_iVi*Pwu@ndZ)+Pl&bMH~CYZ_`J9jfRtnDTz{ z61pk8{W+eG*Re`-2g584yYA~+v*1ntXA^&L~{FtP7%my`; zM8@De?P2T1@~^9J@a!U$r}Om>Q6B=vUc{r|>zT{fBSEqAnvrnH&GAIi07Tm?QrH+* zok0k?%a@>HMF*EkjSvrJl;yoa8US|JIpbCBkSdpX$w6&Dbs5HF+MonwxK;|TObEcX zi*3LO?=#2}3mw=m3g5sc%DBQ9)R%wNRTq)a4In!`Ri!1%)M*!Y@zX(;k*GfdZ2pw5 zMG~v|gsuWl<8kxOtoq<*8U{sMi0@4K_J{ss)XJ})RY0_OISJc@-Y!FaM|7^*@DS2X zdXWW5Tshv^(1TZq)|-C96PRP>)W#<6PZ<3~U93;&Ruz+b<%43~rk?Qv$$Ha3V`e7R zT>wsLPxE^~XPLj7%64xmDH9fD{R6p*)dQ@#hiE6q^xE*5>nNnDSNJ3wv$Dn3wuBhb zK2cA_WUvx-^XQbzIZb1R?7W{20Ilqy6V4r(3;wvBa&-7+;rFn8J?9}QrRNxYro68d z#){*;7bd`TXQkzH^U+DJp^V+*ZO9nejN8t6DoxhzTP6KTYOUUMb@P1`IkLWd>hCq! z`Uk;ThLUk;t`!E=5>gcRix>r6R7lyuhS#S*SS~D337fe^rzh z?>TwDO%WxutX8%CiHT+A@uz8Sw%tb63913Oqj3^$eoD*CR(~r58pljl+U8YX$4qGW5u>)__rnI& z(@b!!>DCVQ5s3s~)(T^)!wu*PBtzaG{}{{$9?k&(cHqG-*iyh8O1Wv9$%h!?&mW(P zW~^>^tP1XBK2n#UF=hA1^@5Z)v3_{w6BhaO7OZIiLY~`Hn8zMPN9XT5mfL(*!hYLBBIuyi| z5&#e+RqLD2>?UgCCR-e|vw`BVfG64&#Prh-Ef52dho^9Z_mGG81qo?99^_iguJISo zr`sI>caLZGu=uV;EbT*n6S9}+I`i2A=m@lS54BATeb*dn?e2({p!B9+sRl*4UPif* zfd>$;jF#YwWbP~E6eJ?=If3^6-i8|84BbZn=WN$#dBgJ&0YuUQM`!_Xesq1JgM&t& zt>12}9YE;P8rlMtklnBlyjzBka=)3Ps8q+JWF1?1u2B1Zz6m8`!&^uLw<&1L1+V+ zktU~bV6_yywR|}|sLFX**ZvrjNw`01QDUHY4CnyEJbBq#EcS&@rp=KLi)_`4oXluZ zO~Uag5mBwAVaaa|IE(SPiM3zoY6CQoAIwmhY_tV$qJ>$)f$}jFOEf?YG?WFrxV#w2 z!5En`Xy9v63v>FBXXW=4^hXf9?dq^E2#x{ZULoK(yo#>(i*e!+%m~s1tD#UCgJhe% zP}FH%CIN#aHv@o~o-Hcj2mrgy48+&%J3VA0Wov}lgXB5&`a6#w&fCP$t0ZeXE|{Iq zpAG$ZMuYk9Aqyb}8T|%1F5o18+(T%kbQ8Ud=OqqQG2RUm;UcJT$w zBQ>_1%5FaZ3CU!p*av?ud9m1Jb=w5~7R;o9_jxbc2@-zNl#)b}_6LTPJBPQDhZH_+ z6xEzYKARS2keP~~9xW)E7nV@8|D{C4Eu@U9{5AHY26h`GVdPSb#9UJ2QWi^KW}lvO zn@EOFI_FnRnuUn0rSfb)GC~4Jbk96w%DHth!4 zr`MSxwzRB@SwxqF9k%o{@%hNf(lnb(b^JF!kdw1 z*;-^vUiJ`B2sq_BE8q?{WO+y|i$+wiL>+Jgg2KcNOP!TU9|PPxc+l?O0=*-16Z-Oz zmU99{D<~N&{sgeM)^k*}R8 zA57hMFkJr|H~h7QU3K-&>Ydd)i^YmwBZBDBgCHWp>Z{izl8_(>qO4AkD612zi%6nH z^zIuG$v%G1J#)`JbN>F!nRDi}>%6b)SbJX&zugExG%&qvWRbu-`qawGmPD?AUZm2H7vo(?qxhH|yl`g| zG`3M9t${?@?6BR4oGPVoDe>`YdQAD!qpC^cPcvw>X@;`q*XKHrL~{>cnHikyGm%cA zq8Tlb&rhYW4Qsh0+M@HW(b}&CHQE~2Th35iHNWBkYQRIM@MH#!UVb&+>dk>K%m3}P z#dI=9Py(8Xbj^0~@JH~7&e%tP+EIc5rZ>qtuH9b*H4A&qOQ!ZGOO5eVg|CgT$qx#S zAhKRX@6<<44_-Ds{L}s@4MqJksLq4d*#+{6NNqn~kLYYId|9WR){d$7aALR1>+(UYVL+fN{09-nJj{5VZqXwGfEqnu#~$*i9%x|?WREO# zg^cp52hP}84SWnAuI>*{4O>E*iWrQ7R8X!KD?_6gSXB(Othih;dPz(O^> zB3%8#T>UiJpuMqz1ND#K_gZ+7N3;JyuL0mmq%34L%9RfmnoYRTMKD<=m|YPpu5n+D z0UO5wyQl&C!U2b_0mtP5=c@r1u0f+N@`uF~(I|?_Yg867=)XK@Aqi8~czKn(p&KmJH&(l4mdA2;5c;5f_{HH;%I_aeK7IctV9xq7or`VYl>Hq(0Y zxJF=wBV7Ld?rHszoP4ZE@_zjxh?kZDF5$BHdegtgjbCuKe!;YGeD40{$IgJIi0lCZ zih;2#3F+_N_jY}FEjd&&&clfU$xeY6kTj>hqobZ$*`g`=qL7)}-GHF(TiM+&{l<#M zy1zVn(LKhjWlwJ1Z1YZe-1X5bHtW_ANk$l!YGI{;nC_^r@Tk**w&e?T``ARIV{WtK z3oLP>(`#O-nC-Em z@v~=I-sC{ySWOjBMSc2*(Kt4hUjWW%L<*vrLwsZ|@-BSa-7{AAZLhOS{gYxaE|LfW zx>B+(P499I(LEmDUImn7!<68RCpARX0NclZCf2w<75|w*X|i$LZX!D>y}>>0#yLa9 zKw01dlRc(b2%@?fV1MiHT-@&5%|G1{Qf$aw5U>}lKic(fcbbE8#_S!!4GSxUGm2Z# zv>lBHcU#`ypK)|*(f!)`M2hk9Apkh_F1~w~_Uk8j0J}gotN;s^jh)GIvdwwCpriS@ zWpAn8iS3aToSfKD6fnORCF`jUe}f77pu z;C0vtfj|6D5#*!PjPAs7n9IsS!pd!@Z)*Vyn*nREoNtjUV32GV=3&>7(|lqQ{2PF( z7f(Bdgbj9y&>?9Sj#~HwjRe2VQAF+@hWmvuB$)2+H8Z?I?Rda1fFSp$VKi}> zVFPTI4Sru)n()#Z3nG16Sua|-EgSRzK?aJQZ7Kd>93ak*6~7##0_niEvVTg&feW%> z+^^su#N?UeR+qungy)vH^BQH{oPpM|gF4(@$}ykk2O3JvMhn1O{A6nS0x6kyL#!;U zysHdExdkpi>|Uwm*_|+h2dTr4U(jG5e@UUuM&lsA0hGE&(39e4HI+M0U10@qO4(r0 z@uNMR{5^2@)~649_Fzea_n}Gwu{(*b+ z7J!>LB@JgKw&u#ohTbiufJF0`z$-p1mt}xY~bo|{_zQZO^3@bs-Aa$q~ z5KzS!Ew1`4wZk24na_Den^I=qWB(OdpJM{&adk)c&3{q$p8H9|xyEYce9ug1mds2M zN-j&+-@uiKi&uIVcQY^cqt8#Af5`>^0yiw@&|Uie`uxY~H&FNB8Gd|Xe7TU$w~lnD zhW3|3{hylJi*ad2$!`~X8SQ*B{|RWn@uU;FjfK4k`VUG!dFuG*@jZomug|+lf97AW zb(zCWNm}rLZ~j#>m;WjKt~D2eAServdq_TLGyG!u-XHa%KcDYxYVuxEe?L;Bzk4+etq?SabI+S#VX3UKvxQk1gxP`nWdZw1(xduncSMuV0NoAU3wBaonXIyhc=&s zljuW~TOTWslbLRQ$mnI3rt;A4>|sMPk2(~}fuBE|952!qA%|2oCRtbW8^5Y~PY3y2_xa(x$bq2c1X566x~7CmY;)>+U{dYq|A=f889gmfL5cmr33fq<;&E zVIglJu=Irpot@vxHPQVc;K2un-VA(^`sXi}LqIj-@l_3}u5)ZaM!c2D>ophg-VoksuNL3@1d;a@@Zy!xsr* zLcdp?V}7s!vWAw#^Zr9{ti%;23v+0Oj{sGhU-&5feqZ6_#4(>w;!D-d5~b$Ha+KdN zP^}J4{&uSd_$|YqPdKQf+`DC=b!Y37-HzI5)vrgFOYirSydj!r_Pxa)@$^fZ9o>V^ z*YN`k>$wrk@A=vtKPPFNq|tt)Iq3aSp&qE!G1sv3jx!@*qjQ3r`)eQb>Beh&fHxm& z(3Y&oGY0ZL{_AOXs!6G_D-q33=1&__aBY?63y#+_>-=*>rI*M9M{}V zRrfNY`xMbzEEovM+TANBy_c07Oz{d6OUMy`%Jjhuis=@&%W*<+Mj{owJ3c~CiGtW9 zR5XIlp39Z-65IbC-zP}Dy7rJR!R1UvPSfrQt-j^@+y(ww2Ppwu>}#%qYxfS;p-MgQ zdh#2k@&TVd$6QALpFIFjchn+wr3VFI&{|1gfa;NeaNTt=5gSYmnWlg}U3As8auM{> zA*N*Ktr&=I$NB6B*f$SO~!0JKLy64}owQ5=ZpJ z+D8Z^Y2%XxnJnU55PFDlZ$5zFaVG!hUGVcBFvE)ATM?y@085SZA1W$F3{Nbg@@qVF zp%&ztSR#U|abR5f`AF9DDap(&1IR2JCbqeltCkJNL} zUoKI@2A;m5{aPC$JBc(fRXIw(=+wHG$L z?KG=xcb&3~y)bYcAR;4L!#Dkl5*hom#{33uAv$pJ?|Z5vsz1Xn!Q0N08{ss#+p5~6i`Wpt9M z6lA>uZJZQ(;-Q}~S8Lbyj`ypJA(;za4!(lG=S+Aj-gand^vrO=c7My~MT;EGXRePYy5 z>+Cs2+ki9=8sZvSQ23-USM66s$w>(rKXV7%p+|)HdY<|@tCe>ppK5ttol7Zmw~=yk zkYl-Bi|%ZdwB>2p^THPfQK;_S(b@MJvx)c@9qfKa<|n8%h2b{?&|TF#&xe|M6oMlK zC|`(gkh!mgwKA^zC1k%}>~jujqW@bD8m^R~P}SGg_3;jV)-g@|&>U4PZX2+muDq;; zYimlhO80*E{c1j?ibRq+ily3k=PHDuWZQJ~db7me6wUI%b9ym_2@5-Gd@%Tq|2S?- zeQ4=%(C|W`(Y=TNA&Se6Kfu1_mFq0u;xdFaq(gFkAsyG1+hF4qYscbkFTc{(Oa650 z`I)d(%B=L9D1IaDCmpL!n&$n)|qd1RV}C)G*vId%zg^ z_X{o0!+@k|@6dOhTjC<&ZQo5VS|%xA&qQD9ekhEXzE^Q1=X#|YPxHI(i>4Y5E~cCR z_d!pSR;@3|;@*EXq--rx$Js|i=bu%%k-Z)Nenw3C-=9S>y=i~X@@%MUT~Yhu*=sFj zC87daEx>H$!FNR3_sET#+R=4Cze=)O%y!W5|G>1_U;h3Ub)G2mdPrr)-vm?o>s%Xt zB(wP6h~WpDN7^|n(oOQXTM;eAoIROoAH8xqa|&9ozI=o=GwseiJM!xWm^6_XQBC&j zl>2#iJ0$S2ez8=;K3?1hctqC2siCv{CkF|K{ISM?dlLPM zHHFX`!cl!&#(E@<4b&@_77;uR5T6*G4LP0ZD^IKWoks_Ws7yg7`c>-5Uuh~R=KHZ?Oghtuui&8HRZ8}Bd=3Njbp)W1l8_T+C^n6;T*W{M zV9V^DEJt1MGY-;yOppfJ>1rfrCAX9f`Wnmb--FKO8clgVVo_z3qatVm#V2C0!lHUb z8!g!$Hxj`&{A~JbL{$w`M~k)wYkh8%jAPuFF|WomZr{cUALR?q-UwJ9E!ewJ&^6pO z4l5Oa7Pb#XZ5VfTY2NT)5L}EaRKS4?$mME`A9ap(3!03SjVEou8YG}EF46)Jy}8t5 zSwS64v;FG7`=3RP*M^Rb9vjswpz$94&3jO?6+!b$V>L`{8B}I6YNBP&PTZ&2&0cbRH@a9{~%_A*X_ln%8jg zs8=RjlD{ySVD18&T1Y3b0d5JJ&2pJ0WXG$p0r|ZXAK3!|i;(+AK#8Cvui{VadmTYF zoyW^i%fg&-Ch(!R_E!xHT0NZYQPO;BEQ`hDWm#53EHzmtIr8PCd0ugN_O&9MjE3X* zFDNc9TXwj{N5{?fu5P^A8jz8NQWH65@~_?7i5s^Qy|X{6i5cR&xg6nx^bmznOMoGs zLg*+i=13@3G}(+z(IX|Gq)Ou9draN5&=)pinqC|>5L{S6-l5WS1 zp3kPoP-EyH=?F15;h)Dv5GfwGe7asME`t1~3bcYDR^TF;&l{`nIcpF$YnV8Td17OD z4p2M78V$^v%*`6q&KiHc#(izgT4pVT=FInJt@Le8H0Nv}bKOlZFx;R+HjrJp?G5fZ zhk-fUfjRw&*t5%ITTz^fH&`4S?-%)Ww;nxQ)G0XypVz$v$#GRUm z8WqO}p3mQdECgN4zCsHjiVOFzWnbHcFwceXu!RSS3lUEi9-hztSdUkPFBstI9g7#D z&lh4K_G;M)F)G#`R@Mo~*az7O9xZv$LMXNUsF$WJ33emN2{$bU!HP@SDCpbhf3x%)KJAJkY`24bHworf0S<%3|XI?#J z^l8DUDPy;fihhbF5@tny2W80&0kDKwPQ*`*bbVs$c6fJ=b4ItvE{+QWRG!{eE%xpp zzruzuf|FVpjq%`E8=P5hVv3am=nMPJl{l^f;LVj}nWM=NDA5Z+l&D>j44B{v(}lF) zWHRKEWFawBDj-i3&!fc7xi}Ad3Ra8T8Aeb2aKw(sbw#U?5PWhNhWx|zP#AxThipk~ zq84&eT7ToVm!@#p8iv}L=iG~UvF{K+j52u>^^!&~~;PC4l z$7VD#xkFKwH@yEi6+iclQO-nNNBUQ2uk85f*^`R%#P2_CjX9(ofqS`i5CFGJ!ScBC z!Q36nR>{Kv{oiHZ@oNo3q+Camlh+j*9?%G3|qWx^tC?J9s>L zgWch!=yW2HOvl0y{z@FAzYV*+FwnlL- zamX7>f4+W|dorT%X<2=$JB1B&>!@2Px>SP4jn8aVZE!7fWho9rR$B$>J#$~^mVB}^ zp*GTN5n-MXLFZ(>Vc@o5Xt2Wn&24)h=MV0UMFJMHlWKN3@#xoMhd;Mbx$~8PD@7~C+QS2gn{isZG%q(JTJv7Pezb>|bsX$OfAcLG z+)80HM%LX4Q`#y0H2#L%-^_W-Vs#}26I*4l_r#1!GR(j5+xB$eUShGKCC8SQnfI9V zcGIAXBKcD;J1BD{c^g##sm0R2%gevhAYjEAD#HWihWq3y`I)lpoe27?H^jCUL4Pmr zmu~OF!c2FcI{6Gj!8pw~0ur~`c5c(|3BIwI@_Ol2crZauwWjB{c)tI>!Vg#AaXlVN zwJfQT<=zkB!(O|?5*@=;%;CRRlGD=Hy}>>p?frxx&u8?z(LtMWGl$j^_k7)UXzAlE zkV^?{KLE;yZN0v$T1Rm6AbJ^`=RYn0MmYcwP{wl)_VbYT9!on@H#N+QHo0x;-_Zqa zAh+SskOA~Q3oi8A;a=b&>rWgVhM~10H7QpuVHhB=?aJAvz;!PeYDnyd4CJb}X&=!p zw62K9I8GekBDNr;z7x3614@<+CWogdeEJ+fk>HvCj#bP9;wxVq0I~MvdRzC`plv6x z?@%-%=@FE|yuFsM$#+e(PwCk%n$;1x;G|7=f1NW`W9y|b^i7U*2>+eH6U*KBpjfl5 zq$trOG>-2Qb^mRUPpXB90k4PO=apMft(GHE2C*n>f?80^%E`|CR!1J1riAiv4Pxf8}r_;ne>cO2F@dE5$ z|M&3q1sV2t)$2bays^WH_lo0r@xU4GVxU?v*hHoI_#oFxqIurVe^YmUg$1>p zClE75yyKkc4$ba(rjjBuBa)qZfblB;+jbn21D_oOjy1J}{qhON`x1fSGquS6n4waGbzTeHdsh^4ZFAF8`KpdwO`9|f%8?{tEbHMdO zo+9MBJzcXJWhL&eYwbDB#<}Hk$k)(Q|47&}Qu6Ml_Q!*Ab0|XrKD4tzQ2+7UyN|z} z;T{)!BE@>gJ|2eJSd}aCLvO|j#bygRGz!HoCPrRoIfi9CFUnmQaIWIQaYVc8vHm8; zWq|PU={q}}3xDo?ynH)kMppSkHJxUIpMY6ST{7UjND~`Q5Ip0Mj77!hasf}R3 zJ*Jok0Q^Zk6dUv!3dEgef%M{-&=xhv=4itI!F`VfhO_zfTpPhw#FpFq zHyi!8PlUz`9GY}I4qnOh42J1ahKdoRjmQvvpXKQ2mCHF%K{{QA zfR!sM-Rx8ppzggaIGnoCXYPb7eK^5q?CR?B*XiM;T%&K*1naT~IMQ>)4ytv2o3iz6 zCQC{jS-z5BM&rF|+CNn`4%3jDDS%FfGNP%4mTb|Qom>qBnS*fvij0VKPh_4%=n?5o zx~$Mbmpx>!J^m$z8yV?xJQU0|3WTiq07nh^?y*&qd)isOn!n9BuMsgy0#P}9UV2ua zD3+J>_c0X3N~-MGGzUaYrK|4?&T#3-LqXO^wuco2cqRR^Lpc=|wllHQ`Cu9Kp zV&uEpYy*YLIt|rgBVh~{J*F6U7Ae^{!lJmPg+$NxX%+mN+03hB@eZiQ*uJZ+Se9ez z;a$`a&0weSczLH%rTm@ca~UyrAYgP@y}oPsq*~I{l?b0^TUc4+{y;{h5o8#DvaX9p zYqZ){+;n@n((fEewMlR@D@04tS-nZ-k#xKr>`#9a8e+1~AUQ+o77GTAfMnx z^rXO5exq{r&19HH$N1DmpLbG%*zU7FI%MFl#xW5`?K$KCiudczH!D_}>O|H8D_ia6 zt(63xaLo1BH1F<&^}GzbwGld>&HY}KUwpH^XbEtnB1Nrws}^7?4&ardZmt{g#fjD;ml z%~?H`JanWuTL%UxKym*p9s)l8Pcylf){Qye{sJSQ(pNGGpng8et$=N&-lP%9xt}5z zLZ9P^jE|x4zzHE&JF?0UAek;cT2(pGa7i*i9?pP_(I_r8e~)Z@~8k%NSoLfe~pe( z3#&_sdt1y@34V^1JtzYp9P+F8UV>p+@u8c3o;aYNlejei&t+}}<`M+?a)=!Ax4L!0 z+!+-k4DZ)u)AI8)CUi^u@Zdk9kUEd&h#~c0pP(>t>N``}XVx1uBA>O#Ts8&R+VvH! zibq^u1X`rD4`~I0vF46-nU&P+JQ;Sz#TqV8IR5B8dtVwWYL@eK@@!KopcIS70-135 zF}8auamF~ZBA$)`MJQ(cVMWGGS-h?n9t*$ws_`}E>ZctLN$#UD%(3W!vjbNp%T>}9 z0u;+l%@!H>uzEa1Y?8(Y*H`Y_A+KUEFik!2rcAS>Fk+$bx`hLyu!^WMg%eFuvT7B$81hsJ>5hk4Y#t8vBlM<2gY{U6dVhx z<+WO&nKbS0I~m38yq3L+b!6+tr)pyHCt%HxW1QiJF3+nAh4{Sg4fO|t!1yp9zB_K% zxB5ETH(!plc;*I>&`oG)5Ek0Qp?N1_v}s{;6IRbLl^)*whCM@6tjKV`{bt&Gq4H>= zWP%tY;VU0_{@=?=K%I1Klf=BVkB;0$107<8nPsQjl`P?${>JOhHI?UKR_M+>=6f2m z)KjO^_?*pxN(VY$T!q4RfX?vr2J28InFbpz#XXHHEG;61pdJ$Mxcg;ID+@N5RvIk% z*8Vg47ly&%M%t?(0$@K4*n2N`zZm`1*LLVd@9kV#aR6cy0ElxK&@|yUdM~i?Pj%@I zLufH|H&Ora;tS|E#WHSL7}ul+tuxE3;?zG}`cJ)05156C{7X4-EgjPcQKBEB;WMHS zmIP!fk@Y0$Z{x4px^@E`MHk!_1n-2=U3`0xPf>UVQhwaqw#VSk#C|OdqmXfyr=UO- zOo8NY1y^T0yaQ~SU9%un@|AZ!zQ@>YbUZ#V21g$KRW%uZ* z@0Gc~;R_={}vDY@UhkY5AW|CeXlF8}_by{IuHFp|7Y z4D$h^V9;*&@E(j+7|x2J#{SHCeQ-=E7^XQk z{d8?mh)fYlv+)`H2R<$Fk5eksnJ+0pAHlCL>4u)gss(WaE=mnObQI83YxE>W8v8!# zFmRm{Xhvv#l08q0E1s46di6fhSEUNMrJ)%*wibGvCxovMe%+BZ$)q>TKk|3TdTtXE zwZ`?GBET#JUA18ll52%(3j272%W$PnQKdx7fveu04C%;(wC{!7@ZbqpL6c*}G%!*d z>!!{8uy6s>3df@q_jygjP!q#2e=w4AT^1F$LlBV7`D$3u_qoPn=?ULo7X$-?2f4!( z#L-r}5a@nPP%>~eFj>7(?3u13cysTLz86^C0IaP65>cUIcPr%(bLI#HGZx344I5Gt z;}R-+rf+#_4jA$a^FvWRsOmd9A>{)R2qi7ZM^!_j$2+cF7{NWJ&hM7Tx z&&q=%cJs`|{!Jx7@giQU*$PzcWi>z{SO}89ut^kvgs{5m3hsk*!hw`OE`^}tHu}6; z`nUMMd-{5LJr%M1AapJ&a&l&W8bkmgb(As<829?M(R5*%Hc^88ow8^FK@b4d2Ty!! z$5RsjV$I{KcX~FCMiT*V?k&}czp<+wJtsX_2c)O~k`db~IxK1DV`0t*5-lBpr}FUhvEIM%#1dL%W5rH~boTHKGkM3cis zy>jo`AH6m%K{7|W3bXNC*GRGoSG?Tzw&jkA zJ!;S~QBujn&u1&hL42;g+!Vb6wksA~^%NFEvE{QHo>ASMppd)n2VveBIU1#F*PUpO z%VHp0Uql);AlW@efDKCe+8Bn$J4IJU1pWw+^Rx6o4SM&pX}mU<7OPzQ-r`mim5QeO z=K`lK!E9zbhZ7(hFVdq2Wv=2?h`zO@)rMRoJwZt_W;Q+5%1_b-@vQc-@(TTi`C>1Y zDxL=>dU*8*D)2H5`UFK*x4eH_G!4c@qPYyvf>6!X;VZ)x8{G=p_tA17dyOQV( z7J#077gP|#f@$y3cDw;w*5ikx>90UVK?xs25K(4=-jx6ySG_C6?^lm~TL;$)E6OXU z2_n~cIL>Wgn(=-(*tRqyiXd4K=O0FH#6J$YW`_F%bme0c;8%KK5xv?yR66+}dM^Un zf^aS5!WFRp5AGYV90}l#z<#~PegBhMUaS3fS-V1e@O@KimFHmD!CgYA_X|*Z?Z18K zW$n6_^pE-d4Lj*gB~sn0m-J6(>7Pm{+LbB{@{PRi8(ID*k6(E+Y^>y6#cx~fzhXcu z*cUIPSYen@vPTjCjW|s-K|Zu9=j)m_1_)=VKjx7+5w1UxmN`|bKh=^sGpIi^lR3A$ zcY3L#s}*-{b;uQA%j++5kyL+?Df9bj{cojuL0lk4P*?k(J1WWVdTe4Yb&vKi``#7X?=!MLx?r0*W>@w7h&?D{llEFU_Nr>KY~E$9Fz z9;2lT`{|IRgvDGbKtZkHtmLO}dyfM3861)3W?w0T(ud&tM2BGFKW<5_noZR9*=(|C zf#{vmKH=OXu1Xl~(1G0cyt;RT9_f6&4@&U|;=6Tb0#cl1rqqp6OpSb}U7zSecDIYZcTHi!8)&U zmBFKg`wSs(H+kcplL49DDt~A)7Z5RB6rJ9wG?uw<;+IR4@A2+3&G)*=En>--H`FR` zTSfVd0aRnW<*$wD@1R`!+aRy8pwODz(mD@*WQ z`l#r67TmA4`|%r^5^j?Y+&2kjo&`4{XF}ahk2PYz*MapnYT{)##7%Y;HEBrCYRMF& z3E#a@EtIP**|z6pFItEnP9Z8d#S7P5gRf>U$LwWVXT|n>?*+TZ5NbE8bp=K+0$JXT zz6NM))Y0|6l6fb$dMbPMJiXuai2(ATp8VHnGHm1Tb8Mcc6h?KPml`fSKr}j~kmo`N z{|v)ADk_RU27>=$KoppPnWN}Ay>OOi{ zR}uf~ZY7L`P369i@|T>phoqJ}e)I8rcg@BKHpKjY5INVoDgy3pCgY^Q1=+%VX{l_V zHE$I5g`h;*!n3qLnQ^a`^`0pkU-iZp=vsUPGZ|Uln*8Or@XKpH+;HnKJH|<;^E~O6 zoL-cTZ>j;j(x_cg^^3+sGyRVAyi?s|G~-H=B*Onu6Z#e<>REqy<;g_`=%LA8(DOe> zf_E7h9CaTsf*BLc3Lg!!Vwwuoe+Q49rQba_kx!t-QAsH{Y+~+53vDwxTbR1gIziuE%a>}Kbi4u)jWB1?1 zpcU^lamcWG`4MJP2i30n@5Vohxq6QQce)KdGU!JG@^2^wg*V2dWq7Ze-aYE@iwK$i z&2ipppg<W5arwg}wJXp8~ml8wM}kV2Sj+Ou8t zk|EbY(xYrQ{WN+JhuQWVgh3_%NZh$=Ixv*PBjJmGGn6utD(W=o0k!rrja3L3CHS1W zWE5(XsqEO1^)%W;Zs+?cTBNo={_|lKzSu|NVg=+Z({%mvb`c7r6vM$ES%58??oN%) z1_wCAHB(bu{dxN%z^U`W@#ciY+MQe7)O5mEyFou!G8t%IqsOOgv;$1WS?oj+sjuY7 zzuhpSMm4Q|ir0?W>tM&Li32kjn2yKo4QMB$T}K$kIVk}Bjxa*?lXs|k%9|t12hT!} zyEqAs;`S~}ErKyw!-+11kzu3L&?Q|UR{Y%DS zv@CIIf&TAI8;Mu@F(m*{^4tT*fME!ughPQ3xyX8o{+@j{)HVVjlk;NjQphD6&!05LmV1}={#WR51@A2)WdKCu>_|t8 z`vJO9g=@yGvE5$8NHU0pPvQJv9*Cd7_kLFKN)$*1 zWR7nc7&G2hkh5@#V<61h?F!@A>>+quWVotZ%AMusCBw!b_Nz2{slMvEPq}HTO}}{XJK-aCpZ!x2`)^ssubf4(qvI+F|GnzEs^Fr_aMArv z#nG1`{n9Ycw22$pyC;+Tt&a8GdRi~P3=fnK-wwLxjM3DvWBYtIbN9}bdm-r<7Mh9v z{#TlUNgNB)5p5YOh*3BrIX%pHG?W%o;dodwet<4TeVWXaO>ZSA^~N+&&F*@SJXl)xIEbI;mc_n{S9GY->39SOM2 z(*1ToSd~5`E-IIXlmRtV)*_G>AaYPhctc82A_L3q4IyO%<;sWYX@YwmI?~tqN@AR~ zjYc8QI2H>h&&@3FFFIg&u4ghT$W(wQpn`%k^2>j4lP(4%V}G;g&s!j0=Q~J{ty~YG z#$o|mu{alJ)|c{RiEyuI9M>8(yu-I;(uEe!2xIN?K!7MwBUG^$&F`x0>xy`*yF5l_>(G@;3^ZB8v`lPHi+Y8a*sxD{Q}Fmf~zYroA~Pf zw{rQg%3*i4AG#?ObuFs@H7?2||Bk`Swv?(Kt8 zIE2k*-%`3J`fqfpX^ z_xJpa(v(I{Z0a;xzFq2;lWQ)QXciS!-P7s(^f8mAu^xhD!;*J79!v}4uLr-e`8oCu z+9@=h@7=sjN9BuJANZAtlWc4PGn?$_rzGFYBuP~2p_+yWX;`DP#n^jIC(Y&+`_A9Vn;sd>= zk-nod&N#)=-ag1opJIhDdN~YXfM*7!9O}9zQzVT8!`80ur))3hbXXc~>h~6sEJ`^KBa-E*H`Rk!WvNRM`eOX^ z&Y3FfyuTyxZ7<&+#^D}i@6$H*YcpUO&D_;ej_)%mjUGI>=B?~lj%&#f$tu*b(AxGP zhO-Qxp}-Zh%vs27FDH7{;Q=b>>!#6}zN6W%H)W1z$psN+^p*Elt{9HW8k0-|#dxuUt3p#n- zaq0l+SHYz>qlF1F|2B&i8UEsX|;R9b{TP+JG=~J5bL8$ zH!9>WvS&p^~)arnP^I#6fOa>BdeLgGO5V2&K$v&||*B}%%F&t%Pl z))v_uA@wZ~F4Hx@k|6Uryk`I35!ufyNH_l2V{Ci;9Rp-H03gF!r?Wz?OSS>zIk?Ag z)0dW}ly={bYJwj&`i9>9NIGfb6%+)g(_=EsVcnLd_-n*Wf=K*PDB-B!+k9W5?b5@N zLdnWXBw`wb1!-q9r=&0Zthw-DI2Bqd%WyIp(R0jiYeeo ziXRF89w%o3a~f?R?|^f&(^Xo~PaNdb>cScEv<)0RU=kVoZjMj0CF`?e+TArW^ft5} zDP<20e`?MyZ`DI?8L~&4&Jt4l@6!*#P0kHnsJI;GO*!FK`lE= z#Y%l?bpJLj`1eG_W@WkAOk%Q+F0oOT%8FNpkq;zKdnm~9kBpZ9lND=_WWFaWf2=U+ z#`t%PH#QEam?d*ROVHR-eqoBG4ZtY3%7xKkUD8$9&rt{-Qdnn@574EEmSw;1#^Pw{7z$o+4h$OQGG4vYUhlEibwnRUgPoy5E;f zq*Te+rP}CYyP{*gOi=G^5;pb}zbmgX83!{H{<1eM3p-S$QYSK)MbRM>9x51 z^#8^3*wvp`^KBk6=5^iIxw$X>;aIB$FH9Q!L0bkpRcY3n%M(}5mZZZ2a(71j1?YpD zIQZrDzIy9fH*3fC{S+2sx*xX~mrFD|OA(zGNy}IK%7{mV)~fW#lU&)PD{@ld4gR4| zgKU&0k0pT!s}O&LryE50a5ZW6D?VQ|rACRa9bzA@FT63C!GHp{;z z#+gv7p}nRtlCSw?MsDGhN||w01*Kwk4}l~8XtXlBWg|OuHU`W9@DB()RuHCCK%^*G z37umom@HU7=`e>F-Sh>lp`^D~IpW{)8IiFHPFen(b@*^9GF7=7rS#&u z28v{?ixy5PenuU|Y{XSwxGRDj%RC*+lj{oQDK%4ma+@~}P;Kk1948@raPyE!64E00 zOOfx-6PtJ#xGw1_Icn- z`ZebHuOy!^*|-}i-3bfTw)}7I$~L{#R61^TMKaD-C*RA~%9E_e72*b%Ci?&=2Je*U zgqz-`Ka*Au_YrgJk2LlmeVKD!WzaBhwa74TnBNj$IVaV?{ri5xXcyGy#eq@+W- z1d;9*kZzbWp8x&a&%Mq$`^CJQwfBozv#xzz-{1FR!x_t{$wr9e*I^K}JE>FO2{kBF zw^)D}q9lp+9hoq8cd6oS3hWsO$$c$k5IzhPPo=rCO(0YVCr2kImwG3U3n%YHCvh(V zF~mRIH`>W5u--XV(1jtBDOJ!ZQP4Gb7$;lMrQpK#8@XGslUvJ$bIpZYkB0MiC--3u z*TD;SdqEszy`#+Up!WbPih)iW$r=~0pyl)iU*m(36XHF&&|aRyj-eNBgBSj#7m<)R zsq_Db`%?I*X3 z-x`JA6f=hd``VK)7uG!vPi@IH5LES_WtKnx`t9E36x325G)#`c@zyPx!dWUaGTRFy zOw%dVIV80{q%6rTSunJMJhV~Bxn$dp9IHZu5LpBh6|*=K z?>>v97|9`)MZ0Z?=k+;2>TRTQU6h`&qOFAvZ8o7(iFD3X6yZ!9Zevqll7B^lJ9Z`| z`W!f7nX3>Gttcne{S>pIN&2TpUyRQfg(i4ojLwgzEt4NVOljx0YPhT0uzOt3oA=rL zOg*6}!J51ngx+4sUv{u(gve$+xP3(~>m3(NX)^uI^z4l3<@TqE8iwNfxbHKm7c=%b z_WtZHS>^3?>&BG3#w4;GyJ*B#)|+VY%6`=)_4_wgz=2x+Fp|IiW*1 zNobkEFNb7khN}tjb@Z52Rx*!H#KGz+V<9@vs^`kTsG{uzN7SocEVC+vqBXvs38CTZ>ZzammSR(wO1x8YPNe{7ob* z{dUro6qFJ6GH5rbRG-slc3|COV83ZPlLcw7 zYg-nk`1Bqa1*cbK(x}3CVPb~7fG>>fHWg$%*X*Wr0bdm zNkCBiG-5=0lhz_2LPqrK2#wPYk_azS&%839A~3TZy|EJ?TSr-q{e#KfZ>g+xU#?3y zv-vHI1o&MMm5uedscmH`t^HJ)N2{2fE6~?D2&xV`x;;D#GrW6AR%j=MtK{c+Y#<#( zAS0Te{2q|MAVJCd;;G*hy#rdgUw3h0m|SRQ}PUTa!S#|Q2DQ!qGNW|A@L> z#$&R#d2&Oncc=G>N|!CzSU_6}q0jX6ea=%zCv-il2kZHmhwoTcnv_^~c<~Yao)KPY z4kqi}G)k@m#!Z`EaBCd=IeViK5jBOO;!q&4`{TvJq(DoXEsf|g=JV?{2@F%@>K>Bk zz2r0*(14&@Ozr2DMm+Ls?&*X2VUjIR3z30ll3kM$J+%2+hBKyEI0SSAG9w3&@s(fa zJls}lT1GZ+xpVy#O0g7c{S=$Al)C+tu(F}6S;TnR%8OWCg9S5zd3aN&^f8iV<-Rzl zUyH&smq<33DD_v!F_7P~Qq=H4k9uGP4y_;Ww^nGDrAU9BVZ2S3e5=WVtqWE+^;fs( znbKj{`9lsk_-nX>H7Sg1%X~4`RnHBvvd%oFOe%Sd+ZelZN6^@**JfCOZ9s zx@tq+p->>7=yq=`D3xh#&`7o~40mxiuq;bDz~glL2!zP_5l$oOdJBm$!4$zqJx>t} zwp;6qVb^JT@ZvacD1r0C>=Uh%{9Y=Q`SvaD6E=DD3_nCXWYRSEi;@PuJf1-DWYL=v z?G}#sLe)}wm(6AKV=%3Z-$06Z=>Nuj$H}tQ3iq|8eqArbg#Iq23N_dF!cRV_=xz5A zCFUtT;xh(9z8s%63RS--i-C?pdTaIk2hv2{?qO8y8-4nsq1;%k-*$hM>U{UaPj#dg zu{3TYn|!51HP@{6_g76|guzHSlw6Q5*7L`q}c-&}QZxN?Vz3Ind9^ih%6P{YK20$=TnZ_Dgr9i(Z1LyLJM#D@`Lq zUxH_l6&0BmPxaqzbObV3?^Y%LczRbFy<%>Dm?cMV)hs|`e=CE%{FYn&jPWghI168?< z*}?CN*g~~MWb@NR#@U&%I(6&2)ncp$J{HiahQxo3UP&&9aXSydleT7KH;XSea$(C! z4-S4%CO0#n8lGN+akw-) zB^qJvo#Y?HmVy4#*uEZ-zk8I!DwbTDy>zKK)t^3^ofNb(=d8@OVObAa4yZs`YI>f1 z5$sYIvmO@kmgd1eHF!=~#$dUbr!efg_ieyo;-Mm~z&x8o_?us(1`Cdht~z($oMlrI zm}gE>$`}OhGJT9nrs_6N6Sz>|nwQaYPp*{s=7#we-KxB5}Qu9QrC#X;>L77cs=JZde=Pv z6UYCmsqG@d;~ZbVLhVo&|CRfv{F2WO5}s@Z+}34Kv9r^NHXhO2$8RfmE@qb^CCtu6 z$(#JW1D8^d@-`VJRMKS>-lv{*y!5P1)x)H`q{nHJ_u;vH_Sp`I&co?z~8kA)Y{23eC8Yv4}rrlYBhFU z*8;>f{b1&587GUsTen{jg*bj^kb4HgcP{m%kYQ6NaDn_l@x2@f`~u2;>&NyS6jCZ^ zQ5Zxw*-i)k!5i|%ZxLDop^T(qB38`w;U72x8GERP`Ejkkz}D)xU)cE~=vC>jpZ?=r&C?^`C=m(W%?wS{grURYrCGXw~|aiZ(tp3>wEn7h3hQ* zGo9>q)v?fAlZ$&>EFy@SC_Pc9L@rXHEXyu=h$iQecwwI^e|5Cdqx4VNj?l%@4g%MP zt}8y~-aDj?&l+<9ubWoSpIZ}BdUhm#%8Ja}r}pWmw{c<>oeISbkKFThx>}CG)Dnk- z1c(6@A$sSR4py(TGNGG%64g+<^>MYJ(gK-p8me*YD0_|@=JcH@Nb1H}mL>LZ?nCkc z6}|Ka4kTytJR?V#ChtzOpX|>oDOal&Im9{0nD}PA+@=!DjdEcSF~b^Um&#=o$XZnj zS-_5hIyAh@Nck**3Y%X&khNYZQmD}-A0p&Fy@ z?`HFFsJS3`_}o#(es^P-?k$HAF9KuQl;t z-yBJ%ICGm%2)rwMG1oLW{q*cxn?=!xx!c^f9bOZvahAK;_0Qa-7c8}up#)ESN}Gz~ zn_|q}YnNDznYj6p#>XYa4oic=yH>dsFRuQKZN~?EDbKG=VAgT&7hUX4CvU-Qee3OC zy;$B)-U`G1>GSxxLGJW#lT(b3)CqDb9d{b-pr_V>;zMuzMxHtySXKr*oi8V8C7MhR zAJi;*g?Hus_|C$(Gxii_yjlLHk@1}D-CXJ%2{gHmC0)TU@{y5?IJ8vh1XGavg|^Fz zkP?opW_;PL5ypo`b&Y_-$SbmShEU4B2k4}R_TJnF+ys1uNvVJ?!FSw&4ZY2AWsx(` zP5wWWfihD`$vpw@$J2{n1+KBG29tl_v7TuUeUCa#`{nupeBm-0m!K9B$rZ;e_~%Vg zCwB0GjUvE0J1!!75Mcyu=3TP<8E^INujc-w1eAAdQY_vrSJlKkf~rF=LASzV!Hi2n zB-&ZuF-b4nLb0nUBty^Ctma0iGy0d53fX?Szn;11ZYAUUz=ql5-U;=TPZpJGy` zW1&zaS3i{i86+Y`4tfcJ9fB5Ln#hl9$K@bs=W55M=J zWGXe(r>SGq4`l?e$9kwg4I02tQYt(+g#Yq<%ZT1rCB6c^dMQ1-PHqtX>aHcW{CcWH z0q)ZFK5R+;hV?#n>V9@f-fWwmrqkZ< z`;3Kyq|Gw}n4SDLK_-vL{Me^8xs!tKH3G{?(Vl5wG#iP#^LtMUYKuxMCOPb<2||q> z!P*zj?t(75K~CA1o`ynh#%!oy6Zv4T_rc}f!2zFfQj;E9LjtpeLiD!%^O8dOfA4kDNL`)L*!85CH|7WPCwZ1a7Xp;y>KF1B$V zvl5x#Z;bHD-$CQfe%of@qoiRoW^QwrwiTD*pWzWwzGA8Yu3K!LJADz8g%L%p==rkn z!#?lhhR>cs!MCgLFNB`>u|lqc{2Sy$CLmF$hKQ$6qD($S(KZr68r{?av5VdjowG&c z{rqUF5%D|-J&YN`Q6I`1?U#NMK}YF~m{FMU!!~V?Vx@fM^G=yqKAP_;MtUZcj6Etw zJ?g2JhwmHQbrr%aDKWvuqJ)7T0w3JwLvFdBjXEv%|wpvCk4WrBSh z*qcnEH|?-98-j=;qVPlfvoU;IK1zX)Nskhx;F*L$nM7?!SmX?)=opTA0k#?9>%@z% zzdnBb9sG4l*y&?bvXoyCd9QnEK~U&)vcq&lyf=6aj-SU4?nK~7E`wL#FiJGAItG=g z#OjD5U_k?`01BqK3^_sKQf7g#mvQCV(KWP6#MNXn%C^dAw|i>MUCEgvAabXc*SUbH%Fm3&%C%G z1XWyATwF3xT((=B&w*oe%wD%L}**J1OU;%p^M8*14TsohlCH&70vCq zR8@H6hXwdlh3_@edXv)z8;K}5l&EL33>6#iRl|P{RK6H^>t@cb;IQ8tI2g6PJz+h|4N!& zZvK@tqw^<-F<5^kB_#t|RpkNz(D5<^K$cP(mG%{v4(*nbr(|*6d~+3&PgNl}KZKEJ z*KqfTlH#Vw1;@!yHpOpIA`svbPVm?vw2v8Mq!LC~Nt7BzkWvjCsZ`q!5SMus0GS0; z<1qRgqPx$HhyJk?SINJeqwmaW3}>2sg=yGir5uMW8xk%8X~&{%ib>5Qb8TEg^>@EJcpy!WDBGXxd?Tl^qC{7mh&5#o zw)yO|-F#|;DXN}*>U0a}vjr+SqKhwj1GRX=B$@b>!w#q z-%9=@LMY?V?iR3){56&K!cinn>opPm}V$EI8!g{ER;!JeC z-nrK(rPaKIrK6isKMwsUgxcGPg}rh2RNsrSOzYH#wFJy}JM6uCMDxRIuNTJJ8#v#k zrPL>++iw=ucLM$~vC$WKs~?@#=c?4Np)`=^j%xB9>c!aZSDxuNE9rZFF<}0w*GX*9 zg4)fxdEjVzz<{f-U~ll+t^d9IkIv>F$f3S8vF=7L)6Cn%WZm8>rTVeGj_kc39;HJ* ziN->REP?jng}vb=*vJak$lC3&FalQ?IkHna@@H>&Gi+oJHhMHavc)xe1{*!F7`;jx zxhx&MqZzr~8wKfM0^DPFN@Ez|U{rgRt{R4TbQU50I1%?aiSjt9 zKPkyQDWyCqbN5rNUqH-gQgL`vd4KX1KI)e$_b)Z&U&g*4SZAnQcxrdQNhDuC--uL3OTRf0mbjK3a0F z!(;v-&3yLw{D|Is(9sLERfbx+8D6^EUqYeV-g%ZWUoL~KmT@AMiDEFD`3O!C z1g+W>uPEc?!zna#WpvjmbF^wh`7ztu2~NlGHQ&orn5(u930X6V^Z@*G1VK^{slvgs5&`g%VB>W;(HpA`igKc8bO~rB0smlo{finy z$<2r5>}GTuYWf=*2Pu{8sZu&y1Yuh&`kQX|>mDOSn1(RvbRr=`*hwWph1YLjdBc!r z(K14XBHuby&K>9L)0}|YgAn^S}I-$Q$sfy7* z29b#Zj{^9Hpo6G#q98c_cIIx~x4q%}z42$jNIOhZ1?xK?PbrD38-=N^0^3}!r;>z4 zj%)yjn8yJ6&kXk(z|rOZJ3_Dz*!;a}{d>n#fcCqwGKju<5k$hV-XL*g|6~9hnTGsF zXI4j-<$rGv{-Ed%G5^+|xnx{5W&mRuD9X%TH&RZ6BXZO+73wJReid&Fzh4DxTS-7# zf4jzi~c38S9tT~gY6M%(+b}*v|z9J6JDjN(t4ydEYpq7_Y1i)h(0!1XjQLC0q z+l9v~EbW%0KYX~fl3-NS-hC_VN6KOOGCmau*4s`RmqFxC2qd;)CAVGCj9>M8Vw@a; zY55Br@c?u^Lop#x`uDnW^eUYYu*9RZrYdN(E@*QjZ6&--;;l)kAbM*XWHqC%>RN~ZV?gIWQAtkeN} zOL194f$pz57d&IZ2EoTHe}4N4iU7vdAqj`Q5}ZIKAPR&9E@A+zb1( z5`wXi-Iyf0@GNY48nlnuJ@X;M+6E~vOJ#X_C<@2ns_Z2OP5YDk8P9IW0b-XABcPA5 z47&(2V0_)|FK&+pxWu*PL*18=kS@Qz(+Y8o`*HhM;-T_p*tV5>ghDHD#)A?6&kS4K z(nQ6Qv>fn|a#g6TEuTJfw)4L08U>maK z`;=(*5d&{Wu9_6Vj-rz`P;9B8=}R;G(G13E;lXWS4kaS_$Gre0V4|hG8Cp!wCM)!ioM$|3q76Pb& z7xzXF07rsqN}y?PHg%_!lmm2FNA60^^kOoY(yN|UONqyi>dUP~KRXVBtm4b!2TDNb z1oou4rrPqfZ$kgO<)nxDSI5H1k1|=~kc_Vu$GX_>w?#2=GQI4@K00{mj!|~1!*eV3 z@ytAkr#Y4z%PF*rX0MKw?VrX9`cKV^wdcvLSwfq`_Q7`59#eKySJ6Bqi z$}39!GF*)Ofgv_&bq6LZ97vUy^8_lroDFkPeh;ybcspIs0ho#}c9`V-eHHH49wT}} zu~|_zKoXbH&*v7D4L6XNW@02_P*myVBqQ#?RX_aFYOD3=Jsk7N^+WDxp-!IJj&9NY zPFh{032eZ$-3&$KVhi++GIR^<3wHuS7DTT9m6m~w$gL#qe6v{nf`lQ(eBF!D1a3;x5l?B?cbK_;SBK8 zP?*sDarQU%>{qX+A}g?4Fh}WaY10dq8Rr^{TIwvBzn$Myum8SbY3*^Nvy83L(8Xe9 z8}6pN&Z^Nk_|D4y>y7TVtVYvBo|R*no8I1gjqh_CR!%K9dWQiT&1)>yF2ip6r}-K! zf8JTUE!^l|{`)=t)2Q7HZZ|dBZZ@pH+}#)eIGXL4tTx{G?uJ-sh{r_fmk;f&Aw*8I z6RIzRo{sT-_)@crdebIQym=Ati)J?yt8K9IUK@tHG0ka^EF-aTr7N3ME}4R#;GQJG zIk$AK+w4n)q*=)OF-$7yc8n*hMq$?=L*k_*_Vt&yrfhOr1N5J%XuROTt~Lxw7YNpZ z;@4Fkg+7qzsI2Egs6#yK%qpp8o^YCoWtbV86jUA38wMOg9GF*ef-|S%?ruLIaZ=hI zLMA7N;{RW`?f@eQ{=xF(bi2Kif0OK<&vK)^E;? zB6JsQBYdt$tGrTDq`a*-$Ha^~e*C1+tQ)yI=5YeReVP75#Zi1x)!g)<&dlI@E3*3z zFoU!X#M)M%w2bkS_8b*M!y*NcBqCra+er&}bx6=LSTbyf&HQ=q^nF1bJ$dBM5Nt)8 zLu<(<&x`dyb;wcP^XeTCM9r|BboL$J)5h;%npi31Exfccc>i{pt{m~4Y2+x9*h_23 zv~~aMnySAOnOOAjGIm3IyjY|%+z2nGuc}k;-Y%&(jRAAHTkxPN!o;l6a3zSJ<=(cR z%I(_*ElgJQe%wUi#!ZWbUhp|x$JA#&Uz0}#uD{Ce?Nrj%c6GM?;l42nh9F3k4Gw4P zKit>jPbE@LyfX`Lq8N?)zOq3A|I=cX2X-*8{@)hs4eIs+ZL$7Oi1q&J?DFOsO|hO` zUEW_DUtV5b{JYN4^6LFRdi5MFucA&*Q70#NCnu=0b=1+y$;rv_@$u2c85&|eJU_cX zI6y|?lQ-8ud* zwRL}ge{b*4Kdbd0*1EI3{m*ON-B|nQwXUsAZLe)DFZ~B=U0Ry^e*&#&o%KI1>pz8c zV&s29tOFCHXo$7HzyHUNAJxD5@_OoTT3YVvvSzD4qgrH9jl!r}PE;lR--@Rl9UW++ zwW;kJnrUtNUfbB%fEHQX8Yd?ho$MGD6RlfluUz_8sa#2= z*zjexMnptJNJvOPKmZzO_3`mRE395#rb(Y|Jv=;IU0tj^EI)t#Y-eX@WAl$=wY0Rn zH8n-OR@hNjPck(!Gc$Yt{=KQGsgaQpT46QQ)kQgsB0YX5;)m6eq*WuBG^Z;KTTu`)3+{r?av?LUf@l9KYjAyyI+lK-|?@$vDYP$&uq z2Zf1=0)XFGSa^7NxVX3w2m}WQ2OAq33Jw!BN0*|G%u=i`(xQ;^i}(+^9B?7OzN;=s`H0ah3t3d`)dkb1wHbuqdDeEZ0hN`vRC?>^prN-)w!GII<{1?(S9{|`o-{qe0 zso76w<(!cc*KZ3`<^G)!wDwOelj{Ed#EP+@k=CvEox?xk^*dbai{&&JX>L5(8Wfh| zO`>*n-1=P=n*Nf{&HnFTM<8nHz{RPPM*L^Sl}5mg-Rh5p!HidJt#>z&kphcCO8=*ug=-OF=MCC{m@Ir9QPN}|*Q4cGgV%9v+%wl>Rb-2p zV_(uGw>v$2CYb$6$1a&Afz#(QPw9zx9NzQ5!xP`gM=O1ssWv~@3j&Y?hf*ZYn?+mc z?&muN886?gbZ7jtSTno{X1555t_4}`^|Hx|awA2kHXUN|))~VfFQkUjxEpbI3v(09 zIV_Qj!Cm0jb-NtcqK2sD-O^fO+>%mReJ?4JPudCw`FU@5IlpwW;#m0N;*Uqt6i_jn z*Nn+>?$-hiNk|eQF^zT@c&y&C9%tV*uc`;nxhP?SDyiIOD|^mLrH?TVPXtfphU?qq zX35_O+LvS9;90vrW$ie6W8GL?#5X*-f2u|4D?4~-)S9tLkt3X!i{JnLpm9<%Xv4vQ zmAfx7uJd-TD~P2Ju%l-Ag1PE-=?w7ljz)kWkH)^0hL=!pRRBnAz{C+c$MW@NS*v|K z*g)KF_fmYi)+vg8r@3a3(-;$3hYWPEClvkZ+&&;RLRfn_5uIq=x?7?c0q+qtczJVk zIGXGPKqjqGcb8igU+zH6(mn#smy(22C*KserKsK_xEC{<~R&` z1-?FpL+@ag+Ev7hb5y_UC|{SGAB1KQI2GnJ zGa%r|e->+?d^aNo5eV;y=J)3UQDz7h`PrctG8>e}Q1}t?6YZduf@r*Tnf%_BbV}?# ziW*Ob1+14agqQ`j3M`JroE)iH?Rl*Uh#SB{NOFNS8{lucmen zN0)_1V^SUnoV|(QskX(Uf!k#ClrHjvkD;~{oe)hvFbymw$ju>&6d}e2RN91a!dBo{ z&Qc&v$q1HZgwk3p8?_~c;{K#DU4NmusKLdEQ2J?!p`)@wY!{Zr^csB=^?M~8JMpo~ z=QP(sfqc0(QEG*2w9T36DyeXMM|A8X74nW)sGlx~F}yfPxzzEXG7Rm6mN0DW%C}HW z4QQ(;e11UB9&i8jz(Ku+=qrt>#?!Y-q}e$SDYyfrXP*t|pMR@-+ou_QqP2~hBm-1Q zx#eGQcI}8QQ=ACNT03@WYd1Zu>r+0kh_u()ntxhf-)Lt3=A-Jax?oQF3((`us-P8P z_3Ey7R~Iownh&9RG7oxN2{6LhTj*s z54%I=_+wsQ_K2KX+W^fp1mAy$f8W@5fb&7FXEl0C{43p*jtI4YW$YRN{Tjm$C5ElT zrkrs^^i_Gim9nTV`Q+Fkc0tz5In<(WgF=mzHfQ=TpFY_v4Zy|F!zejNIfPh_Kx6nL z-_vMz)2FjIl_LnOC@AqdgD{ClfCxiPVfsRO3`%s#pSK@C+vfb7aW4zk+tiyr&kTd} z6a?n~Q$Lg$v6TEVcJs8HvQ{wSZ|cfC4Je3#?j)-FD?gq9gH$i(vJj>~m@Yhbs)Tfg zLZ0T}2n3jA)AC@obG9kU$tr%zKmQDzvx zDUqbN1tTqXbi08Wqm9qat<~?(;l#n8cTYr`(+CnS>tjuPknJf@@`5w!4NN}=B}oLm z)03y!(TuN~ed*5-j|TO4;7NmNo0yG_lCMG0>8RU%b*PBB%~n+H!HH7`wf<4W!>D!c z3K#5;V026t|4psm9KWukP+~+HMVK4qgCLQnPs;RSx4!gAs6dHJ+dM)|DJr6Gu^snS z#O`ycOZQ|!PwiVzUUl7_(Zz~>yeDr5Jv#Ej)iuPV*E~V*5%^Ft_mSMMNCPkl+(6!I z|47e)+{lTmzTkFx4t?X9b*;7GE8syLp})mt_5?!%HcEgm3a%c9c08Ubb0*;f9|-+2 zag(3!Z7r2vy<5J&9BsS57)9Nnh#5M%rMoYrRiDVbb&$b`mcg#V55NJ+Z18!!okK75 zLj=7CK$tHD33*gJBv(YPj;vOC@#Uk?-H1GS2=FT}ylXEUUtfY&#K$w0k3baoMg>nP z3NMY!=Cs~dG**yuOchDt_gu(N8sbNJD0kH@?VIZwzzh${l@D8&k79lijzyE#Zh?tF zA9H&TIN1#2m=ayMj~D^Qd{zTUfQF5PE{Oi`lmOgTZep3>!Uo?O3D-z?r}GpZ2oPK? z;~SBEDev|5(foq_K|}(*hn5sX>*&{xC4Y^Y6#c~VroUEc_*7~94fnkYIFVJk|3cUz zz{o(;yQ#;yBMZYD`5`hs;G3;ST^;|iU{K{Y)A{c&Xp8l}0DckYXa4KeqqA3_U&Ipt zv;mIK%i#SQ91x6STLr?VoW{sxaAE!ta<%cfN;5o%(Ji;?HTT);sJ>7Oe-!~oHQ}>B ztZ3Y=OoD`N|MVbpBM56>QrN(_!&(CDE+?dcA>2kfe5xVR#wR>ORsF*|rv(Ub@23Jg zRJRq-z~RTdRPow%mK~B)9s6KN;zIoh4uRIa9CfxDPqHm*;H~J3WYl7~-=@ry)zO25 z5MM>~vW29NgS_C7V?IJo1pNGx_!9~udMy+q_K}IDi1J~w(H}F1BG!NbNMtxUM8hA3 zX&cKE9jo^(_TuDAt824iz6m^n#t{ifYWv!+Vey^;am0B*-G+Q1p_%fi@5trTX;WSHEegy6VES?}bJ2?xkv%ycsh-(jFx`(M^sE^#!uhY`=+*hj;lU(A+YNC&xFtOc^^)NK@vk?99e$&KA355!nzD4jKc#ukG>10WM#K zgi}I3GH@TlMk+xV1Cfq)4+CSeIcBkftFw8ov$>ntpuf{)Uu5mRprQq&Y2F%~_Gi7? z$+~o5z#M~(j)7U4B9V;n=bf1l1s0|2T$$Be_0GhK#+bKMB;@RvM_N$ql{jutyd)m2 zdL@p_7;)$!tj;EPDk-;YC*>(emJL;bO9$u+9Ku>@h%Py{NET=;;$_&ObZN)Q9wTNu zMBgIGTqMY%*ue@lTNp7=Xh}s)0m0_xBRt9k>1k(7zi_z{qJ09#b2kKY8$m~-3WA$_ zL$!0P6>{D*6_;L9LTnN^&^x**MbEDDkW~8fN4V~lINTlJP-J{TNHN)FG55#P9Ezf- zCMs`AY;5EQS@RONUEq1R5&UD9LpH%??E^# zd0e3UCJ|av0M9)Wys%r=qg}pST)N&=dKW@f^$|#?%-k<7qD}ewb%54wtc2SL6lw^? zvZ*+^DErf&-ak-5N?pz;3H-dmz#h|F(W-WNX5!%gfsHO>5JTM_=ww}U z)KDna+@p3W^S5yz?ckG2SSx$=gb0a83h$R|N^pDG{T0mas=7+XwD~Ehp`G9m0TXK{ z=6B1{983}XRD=E^s6C7i0BZRNv7oi}$?#vrsaIO`47;$sf!f5L51!}J8#dT)ZSbcI zzg=n9=%!XZPW`5xs^@)(LsJPLQsD>1@I&+J;}u}OpIAye*XEN}L;fdOS&VBN$Un8x zJJrdwihS5T zij`&WIgW+O#Ddv0_oX%ud~Y6_YaS_Sra<6O95zqtv`j%;e!8{Hes7r;ZJEDmnMF~z zEJ9n?|1_`av~JHeZ>6>l&pCLhV8CqNMjbZ)8Eie*Y1>i6l1hF2DU`+)QOI3|5x`N} zAo_}C%T_iYa)pFXd+~!iJ`;N5+VOQf(EVqzQlxcIHFwa=chKE-AZR)n#X6aFJJIwD zTUsYab0>)ywl^QPofo8X3c{t^^|Z7jsj}_duB?v;E0YQ_Gr7epgGp5o1SgXNY-{Bl#j6Q5I9Y3F@&`m zH@95hM0*Z&^>vhR3=$J5cC)^7N$Mp`=_PD|0&Ra9Km1Ab=PJ*IHfW-#AO;9{4>FZm zv^qqmnp?KFm#8osndVBPKHKZDhyzag1i=8QXd(MFcH;xX917g^$|Vav;{gwmNzpX5 zuAIHnpZYr)Ffz?6{C2BTEnd?HLe~xJr=sffVNC(e1O3SZS@Kj7IM^7rKRN{lhm_zS zMSJg3X+GbUjE=z`Uk}!w+N#VEoFQPN4ntHW1ASqA*?;QowF}r0aLSO9nE9s4o2(Nf zuy$rYrV)tiPuQ}Okp^c$MR8y6bv^b1aqO%FC(rjSKf;W5=fM?*#juM5}iHLE_C{oL(!gUeZP_J=HR7-uZ(pc8qxX{;$=ic5% zV-g^*f{N6ie`?U1WIsz7Fx&vVg(9?3n#-U#v6eRuz8l|d9vMy>!Djf$fq=)m7D?$1 zW7-barw#A0;JG8e;~izZyI*giweTa2mfi2 zaccQ#5f1IhB$$iB<)WSMuflPK&*ItU_Z$v`^t(e^W?9P@am(kmx#5)_04D$FPvs@v zRdW94@JlbkG8J%&4Pk=KB$YlrQ+u_5@G9wfBj?EcVEDS+$bfT4GCmI+e>jIfeZ9ew z6`V!*0|wLp-tCrCS4UsTmDgDXmbLVjcNV5OtTwShbMm>rPgF|OTGyk5*BDgRFeM3^ z_~0ov1kVmO20Q&?wMHRT4VWOD1uw!Sua!<7 z2B_jR*EmM)@?byRt3iVO#F4%2vhBphRZP&*31TVXV0QBQ_rl#;Kf`X;*yIj@&YzL> zfiPPSz0FH2_|KQ{pSNEw7WX*B$3^$H1Oldf=nfME4hO{+ut$$xCng{Bz(K&;Z_h)= zqQ4mpjiSou|*;nG#nQRphw<;`; z>crv639Z2)J>jWx#X;#0fs(^tG(s@CW4DmFzV z_JK^$oc|1*;51eI$o3INfJnD7y-D%ncBR$w-;r(i(N!Pe#SdXH0{RQPXBU(&k47Xh zfed)AcB%{NnW^>3OY19@jB{M{f=MO7f)Mx^e9~Bcmfv|+n}w6LTynQC%=qjoS?wzO z%T-mzRg!h-fihh6evC!pnz-$fBBm^pj|bOi_x#|x8uLco`gpJPYUE%$jkg3`^}8nH zGS`43pPm|ltY~hY8b$#ZKTy|hOS^-p3oq2(S|t3L-Zo$e3KYHDw;KNSisLsuHMHa! zj~`?0?k>gmHi-SE|I5jLS**}UQC;oJ&javjpGg-UuCzluF^bq4%=8~&lF-VYQoJ^m ziejS1xWegPS4iO2djvb;?N&@-{dR~8&fa{PF79!UMfGM|C0j-&o7wn@>5Dv)Gaonh6>& z(`yT$OHMMM`R)nEg7{dvetuS6vhGnNIpuR4`_UxX!xn z&F6!Kz@M98=rGq}%V37yv&qjmNN=SFG(^_v(DkkHIl-$LH`VPMY97}gWGHOrN+d?d z9H)5J1FVn^?4#6yjtq-fhA3W`t7*DPz=TpW7K2!^Fy@zCYiaM7&YQ_YN~TpZ6` zhDBo(kDH!w^)GePkSO`ILZq>M8-75c_vecm$PZiyQdKSHl-^$GQcVcoaQ!=?CuMJCQZ4!LAxv-z7;%jJmydOh#$)C1 zKuRoGDA~9ae~w!1{FMA$}m2rzN3krbnUw zhqM_(i(eW`MHbpeWP7C?IN#_yr6xZ)Ps+oKjVuAhyf`ojG`Y$fLAcei9#BK z0bo#AHO`a6lJ|Hhz4ClogZ1JU!HYvoP4p>>FES{LDLy$+Or^c;0zAqay!`_UyHL`5 z*$a)ILLPLEM|!%OKrk7kL@tjAKMf%f%X~e^<-^tbROoKgmS20Sd1ox(-T-Dn6`-~WHp4CsaPSha3o0SNe;b3S;acY4=zE#$THy@wk*7H z3ORDLmBDH=Vo!U=>}0mg#rb9{*WiBvqd;80Md?4F=FT|Y)U0!qosWRjvW=89ek~0V z#dNB(GK4XVP)kEKj5ZBz3M3KQfQLGW!GwX7VH;Gl+BXMOFR(T?mH%RetJ&CTGP3e( zvL-uNnigUJW!Md$mqi;+`LDm+4iN4T;^JcMwDRz zmC|-1{7hD9UjqS9go1PqiNrI&=33@v3AQ$^tV_@OLiZ6MZVIE@kjT>8>H06Hq|It~ zw6Ft@n9dozZEkvB^xR&eHM-Ju@5xl=hX^dB3vFTzci-!&?^;W^1|pyN)H`4nvG=Xr zoh^dP+Qa(YZy^CN##mMfT5s*Mzt#G0Y#=a^5({kY9u?|@X>6#7N zRfTR%DEZJ;Mwfa!j;5@M6MW|`6UGbWI+sE8_h&$}dN!VJ6{uUoSdVNVq^1UTR!|*U zNlW(3mi-F_>^HYDYkJeg=C6}6yyotlR(ubMgfn;40Rs&?Pp-qs+CfxkG?UXli>$I%aH0ay|TVrh5j+s$TWY4-Q?oz?3%u5KE@| z9dtT%EajjnO^zM1g46N1>1SWx)1?mecye9OXPJ}QT=ec(0Vm{r z$aPGKcEX!{tZZ*P;*srkpIA3xTQPuk7ti=k>s`&@ERZYpxjC>Ejr4BvQ)jp3iH>;!>7i7i$Gy`>U;ld3lN|Q{&Pu@X_mm8DcDtuX{V!$z zX}(8Ul(~n#pm(2q>L*dd2&I0eKdM*`k{}x zKKbqY>)#zJ^P~&_n4(M1zP|oV_PXZljywnjdwB>8P?Z*VKirEyi`zJkdq9uqxTT0d zs+hTuK$Do#zr`qy4f!(CV~L?-KH4LY3ZQ|INUr5tz`|=ljk`dZ^Ecq*J*c>?SStz3 zn2+kSzPt-S5)71vJFgXFLA9H~BK$xj+(D&)n}k6NserJNJ3<{yyXDI@0o)HOsDOtc z0G1O%!fQbYd_no6JgP%NqA)kz83>TLFaMt_L;vGJjxoPovx|vHE?Votm-|8r3_}Op zLol2_>}v`Rum~he!-U9yWRS2nL_Rd5LU*&m?g+byAiLGL!=}qa39LX1jKM7vzm*6x zTq;Bc@V*QH!6;FG zRJccEGd|e71B69OBtj`%L^u3JKrD*Px-_(y1O2H54tYjsR6bN>65B(xWPCqagosQW z$3E1#XDibLM1jkrhMpH~ee{@EG^oa&zHiH;} zhB>}c{Kr#-Lt^X>^qUA5aE3qG$Nzg1$B!UKj5J3~+(?e3MUP0a1z?Ec_&!^_#SkRF zK#4;e+X8xXh*Wt7eXPin(gbdJhj+M!HxP&kzy)@I2Vvj=!~4io%f@tE$e+kLdKxo_ z8A@WK2@$M9A0!l7u(z2!sW^ZGC0K%1(1#}g09+`CGpK@Vum+(tNlyH~B~!?r2!IU4 zMuM<_A!&w=EJt(%K!*6DF!~0Rb4V-Uf@f$3x3bEUY6nap0ev_GfnWlQlCkL%NMI~V zwT#S`s6mEE7iB;My3|O!6uKEp1#kGN9>4*R`jNQP(uVd;X5)C%J~P7Bk!RM>_Q#1gHU!+Ntr*IXkh zfCqkX2RHx#MaTz&z=l^?h)xQDCin*>V1V;P&-7H!^<>ZXbWiof06D;b_oUDIv`_ey z&->KR{lw4tq|&9jfpTX@T1NYdVnOTf>uxmC*V%+1W$v=%P_(OIpEPA z_0b;%(jXPmAtllxHPRzR(j-;VC1uhkbQd?*fM3~Yp_0lf| zQ#rr{yZVPzD2O*Wg#Rf>18X3M4=~ZvG?1HE#fKPxMKHS-MI~v-1=_St0Km=g&qP&J{$$ifz0XHI)C_z8_GFWJ=mG|iR7j=IP36@0^i=)K&vldeswZ1u`H4DQE?M@Elwq2eGtN2Vg(~(#)3;P?c9aS>{UFsr_PT3v)&ztv2!9b4Y?33Fvawu%RtoZ6Ok**DCWm6Q!@J3v+0w!P)s ze&kh$eN6gWT8D^OgP7U=Yr?=qTAZC*ECGSKIIg6tO3S_6T;0{o)yA?l%9eoHr=5pu zj9aRuIRCkA$gDMy(l9`WXaQSjIoEBizCDP)U0%}NUEUQ#o@h%8c}oB=fCx*5J6+tt zCETY>NjrgD*^pD6Kwddh-qB53rWIGEb%}M1wSh<%W*}ODa9hAl-^x2(ETIcyEMN1* z+}H(R&E4GEHHipVHnzgli{;*`^k_tYl3#MP@MPJ74-iGxE6KIe88;BF=tf(E~^<`g% zd|YN75G}a2H!~p^HYpk2K<9m45{_OW4iZZ%2n!GkWbhpYreZSO#@`Ja6j2c-Mkgn( zU;q2HVFt$GhfqDWy_9A6IWAsf0*fXVsAWY*E-`)w~q9^#N7m$edz5Z)g@Oyl15p+^SZ7TKz2nFv~N249Tj6Po1> zc0pP`$&fgJ>mmpgXqZ|M%u*g?K}Kaewi8}+h!aSiWzOXP^;H25V01p`hEULf(10O1 zhAlqFUoPPW_U0@(E!8CFuWDv`_GEv4X4{nvLNtI&QHIYe)-JB)FD~L?ZV~9TTmO;T z=Qc8DbzWyWwrI``iRt|U4hevCN!)t2ey=aVHYS|U*f~b(~69_Jl53K`cfDULA&T8<5WI zsO}(d?SRPkMxo^{Y|zH;#%&1I%K-gZ2E~PN*p6-OrU@P>1#hT_UpNCt@P-Ro37pXx zp79x=5gLIY8lyp)ff#^N0Ec`yhf^r5si~T)+3FXOTm`4-_l|G*e(DB4WrHZ>7Z`yE zV}{BlTMQ>@|E38;AO?NdhE3>GB+!SI;2XaI0KgF(!Z92GKpe$k9RJ4=h*|iCI52`L zxGK!i9IH|+Y5@UfSzU%efk!xMAAc1Fck&_^@(eeK=>>!7<{b-f@;?W3B7TW?$b~B~ zhzl^&kr=iu7?KM2^RTAxlCFsY--!Skq=GOY1X3Uda-ijr@lp_nanOYuz#t9sCQjl|5waE$ zXyt`Kqi4A7RUedAPv^1jb~-lTKwyN1Q3n0KZdi|XU8jkD0K6jV2bKULAtE4xFd}8` z@+E4b62%34xCSyXtZBHSEE0$<>Y@)N(^5|s!P9nDSL*rBb^rMGc8l(cL6DDQK1LB!mZ=X8g7hwr+V@B~ljhf{cZPauV1Xik$5CSsbRV@jrF zYNic>CV`M9YGQ?b7>En_2hZUqXX+rVLU4;#GupAA2l|G8_@y86jK6AgZ5T|+ z=Kc=yZ@){I5C?JahjKW4aR3Ktz=DYO;Y7H{M*XW-Y>cP_k-eb|5f+<)~ExRiN72J624hB6^y=n)(q9|c_2Xxp4W{;Y~%5mwhmU~5&z{mck00=S)01yPAfK0)J3KueL zSP;lRA`T}~tk{r&90nFQa&(AMW5ZAz~h)P%<0Kh70wCK*HAw&ENq4X(Ki=X)DiE8yK)~s5$a;?~JM?xI^v_h2Fbz;x6 z4AZJj$hK|4w{X**s0EYRAP!ySw&mN`=FOifr~l0WFzqnn!*G)_b-MWR#5{aN6{tAi z1mw(`H*>z~FGs>9@5n~v>{spSy?`~R=BjhSBWCmDAq%A9Z0oJLb+1+_xO3;mz%|nd z#m5T86V04i81DQzbl}2-^&>W27%_3tNSkHd8}ja~;l+PnOfo>1WH5~p3iKra?(%cx z&j%U!AJCg5ZX~?nI66hb0oc|SK~z*gGtY1_AcGA$sMIdI_ybIYyX0aD4&0eW-(U7+ zHXc?WTJ@0&#=x}9A}<8;M+c~J7@vn9zR1yUG)1#XLYi#%;6eiO$XO)MMDin%MH;zK zDnqGN)`l^HH=}D%M(Lz^jT8e@JdbF=f&U+YywG8jor%a$jViU%L_$okb0h#hvKdun z6S?qAGX%VOC!Wt;fB`{6kdnq$Ol~%2RD?cd=%G?()xwpt(Slh3Ujzb%oi0*YpO}hL zRAx%`NRf~f_OR(@o;PXn$tM&U;LI~Fl=>>Ha7m*H05hax&ONkdC8&3oVmhd%>i@2##S3k{&#HBAzVRTdlMI1`F_W`0%B$MW79Cs? z6~B0s%`Qs3De=b?>A^>;6Il?63vnhrHPs1m;|UP&WC1`G=)mjp%3+JW6?(^D2}!a5 zpp-%&fHVtm&sr6{)7(E-tq{_8D-;ADd>E)V;DIM}h(7&DLy##uV#TY@ERWqdS6rAq zPdt!d78gqhh!IE(PsS~*#^V6Lltpi!Nk{)KmOR< zIQ1@P%#e(*5J@ovA_fAUx2(HQ_~DcUIQ3|wO+DWrq3wUN7bKY|6}b?}@Y;(%enpHc zzdY{&3#@)eE!ai5_7yPITpN6|#X9{_L=4Ps!Ad<3C^DDvO{iWK7+ zT`(X72P6!qT&IG<$X))xhQACxN1bHYc?%Z?$z<3?sc41eS! zAN?2x2?R;LJurA{Hr2u54p^w!Eb_e(1<3?s9`B@!(w^v4D`kAP|0lA}4tk z$&`SSBT9%v9FlOSyva@r-V(t?7V!*Q%(9zUVOT0!@s4X0#TxHug)VdEOLeL+Bx;n+ zJZKTVj+j7>xA9~rlev**R*jmmD*z}iHjx$3Now9a=u>pTiiEJjhbimMI@#IFc5-Br zFgeB>MPh&wjvJ45f}Ul-M4lX7%Yp0rwA;-ZhPS|+8E<*b3*4SMM7XlaQc+Vv05G@*KF%%4g+r2I4MSJI zDM7~+0RQlg>mDJ7s10Kf7T6Fkp4PxFh6{ojdtSNGx4sn_!TZ*`6BYSEFY(21QZ~#H zArHC3RZNLZMSR^Wtm(uzoXQp)VgXi(@Woc{N{ksyQ5pA^AY6D!aU-mf4!rlCKYlEE zx$GMcn_AOj|lXiidi?Bkr& z7{j&ZFrzig=w_PYAF`MT2~GiwXtd%7tHWvpD<;qt7bBLUo~jE^#y`*pZ7sqB1D^6mfs)<~rXw&U>DAwNJbWA$Yq4 z7Ltf=Okn65Z^#l@0gio0-Pf zu~oRFz94|LteuISN6Y6yKk8)Mn@Oi}O*<{*BihTumuP8W@R z7~=6lZ25>n?~#n0AYYG|`BQ4%BF>-P#=sAL+ut67xF-Y;|KJDq|KSgQsLml+kOeyG z0gO6#a{viCbnU%agk20p95y-#LPkz}^ixKpuz!;VlF$z*72UU;ttppk*7&v4$kb!#p6v)G0-xY2N+; zAi#B50RCJ<5M4v~12%X959A5pX^*mD3`1zs;c*6zVMbkCo(2Mk^hw_bJpX|237iUk zAY>Q-BqUJ=UgQAA7}}n;M`!y83%V2#Hu_4duhfA zBm+J013e@|!m%N6ID$E_0yMEgIcUNuw8P?Ag&i`X2j<~ppg^m|gCzLh3Ho6bVxh~) zVnak)#~`BiJY7RP!XgMEWVir4{KGeh9VP}!IK~bL1e75$h+T}sKcGWQv?FkU!z(1jD}Vz4 zT){b9g*^^pL7HM$EP@EuLKHfeWi^~Y(qdC>Bg8@4L5c*aF&(mn(H?w4LoUP$bioGr zU@i2*KbV8%QDkStK|XMUF6hEG-~${0fF@+uGjd>BO=Z_*MF2cPTj7jzWh2`SWIlFd zez{;tMBB7g+p%>M9Tr4_;NNDP!at}3Q4WU@yux&}f>b7iDP+StsKYQUK|xFaF0cbU z2ty5KAvAU%Vs0B$7=Tdq;i5$aT$$NQf@PzzWM0MOM&O&i#s2}n`5Oe%)CE2Qa45n* z=tEo{Ni0!JMD!#o5A4*UZ`kbpiQBNP0? z71iQxDyB%f=T3}(iNph2(wfe3rMbCe&ROPDP26&Jgw-X45@g+HhEZ`G$3l#uGqhM{ z-~j1q=Vlm!J?H{HT-PQjj%fXZ0-nJ?6b3<%gJ&j$1V~>K{DTrO0E(ulimoV&wy2A~ z=!#;19AE&9)~Jo%XpGJ%j_xRr<|vK!D3GS;378Etxc@+l%IJ>0yE#{3)OYs-O-kp%$v49x9?Hs-i9`qc*CeJ}RUZDk8iDGc-b^ zLh2lB&KO)Or*^8Rek!Pjs;DL^CU9v*++OaX!tV86m~zn;@Bt`Pz(VL5n*M{DW`;dT zgqt1#fl>r6j6;6Z>7C}Oh?1y@UMZI9D6&#%mM&|MHmkF$=nANZGOWOhLMxOyQF1k@ zvPP?tVym~_D7c2JjgD)NZs~t^#QL@0`<Ke~dgu{+t$x1AvIT11;t$ya`+y>dY-Gm#$;Ty_fS`Ns^ ziq9v2LX-i>6x^%Uw#5TD0Tw)BZLh8zemL<>AZeLe;jKyKuk%SRF zO4JPU%op_@CqAa{nx*STyrY21BR%rS?ut(VAV)&XNi%SUA^d}#n(xG*?<`s`{X#_~ zj^O*kuSqP6+YsE}%IyYsY(ZEgMrtHSdT&k25(0%nVG_g!Ji{|ouv%=wKbRN;mx}|x z?gn4)Q;a~X1uZw41eXNDzi2Q7Pya9MUZ(z9gi#`;QZl7eLgkMHu=e;>LNrkD!iDwC z=?tH5dot`DCZti^= zKa64)b4v}kWD)l)PGo?IEW;!2r%BY@+pKZ&;_v;kryElZ9mmdr<|F`g!8UCMF8o6# z^syGpv9^(}Bb&qm*ab77-%E-_2Xsl<;jkJuvgt#Ldag7Xa+d^ z!xeb4A8+x(a`EVf1OeDZJP>0KcSNF5N@WhQ^ZBd?6NH3PsD)xEkxX*zbXo<%)Zw0m zKKui#3iGS{aeoH#Tmjh=(*Gwchr|>DZvB$+E59=p;RKuVYu8MzBIV$7klv@5^Enf9 zC>t|Kn#3Z&#BWYBM*yT`y0SE)(BEV0lmvE(X?$^gx4h7khCrdk+%P z0&z<8M&M^mH}XkCH6-K2%3?vwzHH34syCUV1+cISZv`A&pHPo9K^HY{7Bt(qv%yGeO|7T6n`h91daMiD4)9WbJ~3GF`_TPa_of#0e(8-!~qhV0XWbZ0C)g9 z?7|W}K`@|$eK0^aL_>NLL>BNvDKr5q=z{_}1bpXW$eQ0Xpz>MVH-7VoemnMbA9hD@ zfkMCaM3`|H9REO6^S6&jw`Bu|#bMmt5yTr{b5yUm% z!h7E~LU}Vm&_Xc;xK<>BI@UOw+&DxVc}Z8q3dn|17kNV{@+hCRS&K5qE;v>M-Rdbs zCcq^Ce84)S!UJ4@EO^5}0KgfDLkM7bL6k#?vH~}Jc?lyFXNR*^bi+SvxtbRVn=?0_ z6SqQ)fO;4M8sqpv0OF7zc%Bz`8w1DO)!h~n1P+h`IuQgEgu@$tgUAF>IUoe26NEk_ zLP2Z-St-Pbz8yqdI&SZQ)xt$T`~xz6dVUZ0F~fSRGlT(L32V(1^rTw+0O@6j zwO>0?lX`+@dqO;+a&J39IJLPG`I}>WRPlLKSReNBgZ6RXpj(49)Ez-!LOR6B1Jr}D zyTiv%J3n9o07!a4Q2IhFdk8eUl|_OxEHqbW0(LGusAKytG8fh5TF4fpaO=#HBbYe6oeM#L5 z;QvAsJb^E`gRzNKmS@2}lmZi^f{I&ucqv;|jNuoZMFEf=py<7g6TNYlJJT102DBQg z8@K!>kKs=}@AtmqSNB#BT^V4m%A`Rxi1#$CXF=>c02~51+e16le@M|2+mTGUAW=?o0je8&Hdnj|dotA-$5%XGI$PLpF5( z>op8 zsT5ycMVM7FvkgbL!~ zS+fCBFZ}!GmvLjqk0(}jEVnCVwsZ}SNH(ulfU=kc!U*K2gI3FzMKV4;b#+I(kRR`b zJ=>-zK6)(BT4X>fuYcoc2Nyovr{u=1qauIWHbAX;$wsgSZ30jr6_r8zRqk{<_v|cR z6L%|HeEEraMCH*sVBf!1=HbVe55TzU?|Hi?ZTnDO3)BM<2qO>~JTvV+yz&DoK?M&i zDZKffA`e3N94MfxDio_>!VNiOtUm1;#4a@uM-(Wmc^)w^H5mdCBZ9d~?Eh;)pJt>n z#E~BC&?gCXEN=i5x;X5qX#PQ`$0Lz+>O&cC{O`EzGC+p20;Lm4g+KyH0l_A#oQ%uQ zVoWK=Bw^x_OxQrkLkVY|LE)(f6f@+^Iq5`cN&LP{F3;t%qh%gtqEiuoj5fkE%qL@wr;hYJ|bN^7lAy-ZZl zSZ{I^REi?KRjV!d040)VB6+Hve}>W3SUN?8kyKfo1mJ{a=79uJ(MV&G*=9*xwpON& ztti)Sp>hBeJ}N2f)ua?V0^D_VOjc1^pA@ONd62PS%M`G@&RT8b<^Q)PTiF%p+klhO zgAY;I^e?GX{;7uGhvjp3)_y5|D4rGYvqOvl?Yp*1ia~}6;D85)xThdO;bRqGlNvy= z8%&OwIEk^%w%--RN-?ho#t0+~1UmND=8#(&ncb3Qwu#bDo+&0N-|9(P>e*=im}o-{ zIA)$=&UNdBKn5}4YD3{2+fHs}MtW+Nv>2+3Kz;f^F;CX6+rxjXGF#brADM@l6Z$gY zk3e21J7~S%{TJ<+)wY|Y0)lW#7R3^9-14rf22*GzPs|jr1q3AI0mFwb-E{C4H@Wf4 z8N)!aQdo~Ys?7EDSo7ly(Ymv~Vi?U1+o56II+oo6k z@dxjJb6f*_>{kP5g zaKx|D0(p$3FC5TF42%bp1S;@+KUrW)h-b8QF^_))0Zb^Gfs~u*;vfC!R0TnJHvgTD zY>dg;)~M7K1E2*A2Y6sgUI@bm+9-YMtBdj;M!^sQz&5UM25)Sl7)R`oh##R{@McKE z#`KLDZpsU_N)yA9NO6iu9G(@gSVM$J5L`M8VIF$*42jgl6aN555z$zYBl1a$=wl2D z#3G3{+GKqCqT)#Ih(|0QZ;lS!BNw~nMG#hCT(^*f!v9$E1I0)njg8#m_5fJ3t^}YM zTbn~4TVlXK#NaJ^tVtd}0!o#5@{@nWA;AO*LZN_S6oz3*0q*gSUpSJM1zDpFBl#4I zt$>stX;l~w&`C^Yaec7LrE5+}viH^UAVC-xANX*KF`~p2iunOEnR&~mh;o#}Y{>|q z^$2bfL^OXWjWD@a!vC$aXvsXc*ix~p#Q5>R!{^fgQhDy_mM;>h72KfrH1n}BOs4B6r zPJtrcyg37HG z6c9irz$VF~3Y%pks zVy+VzKsXe`0}P9_xbQV@Qu?M04G{Jz2W2RKLy6=ho46v;1#wP2G7Vn9xV+fmo0%C?*?)26LusH0Pxj9cNtrIKb`XG%ES*RC@AZ6sszTdW!^7 zSMTu9#Dq0WPWWNfHswlL@<^f|eQ7ppyTm9a2_TQv;4eyc6$VkqKkQNJWrwiYCarX? zq4JQwnl>qf;^ej8ePnKTTi4r+sMN$g$Y)|Xd;;OdKi(mvbrZ4OeDpR>G@uL=@!KZ> za@CTb&Bl!H+SdRNcAqgCibey> z1#~Fp3`tjdn3=xypZKZK`v3Nc;0i?&Y-2my8~68h72Cy+JN49oDMy#hes;U-JSi_ckh zP?Td7uHZx)cCT`@zdr3aF@ThGw(Xl#TVJTnH}P3--G>`7_Th#;KbP>2QD77ls^CQB zvR}d8Pj&q)k@rTWt|j2^-oVQ9qU!e!@P>X(nY=EuG~pl8VHYIJ6*>V6@=yPkj{7ta zCM;kx!cY8QA_4^D3;((%`I>J7BM$}HZvo$_0Yhp4enBzBp%dn>o;raOE|7or4}#7Q z{cs}4&*?^#_k_pK_EDx69#S+I$;vBFnhMJ0FMwM`UV+N zO$bZE$c*p|W9<)}O>x*z_S}$}JfI&Gqp<|S45l#TD3Aj7uzC8>{JL=3eBuO{0qU-< zB<#)IKC#vm(cusk-rF22AcB6agWApc7nS0y`lJ!0~d#u@uwKBiIfYE20b+ z@gOzs8KJS~+{Ye^hzznz6DDF4y3qzJVIVE1Akz^dKWmyo@*~I(2_2H-f-wcZ?G@`W zo(fC32!DvVyQ6yHWw=Cc+KKax6Ka8PC!w*is+{ z03Bcl07w8I5<$-HGV50IBc9R^E8+mqBK1BGA`dYz39m3!ryAks3ID+zgzFKI0%9u!n&2OlfC1n$KIL;h>9aoV^FHSj1LOb$@UuVt z^FQ-*KLOM~pK?IyQ$P9hKdCMS475QJv_T9+0M64OQX#u0Q4Vx;M|reIee_3xG)RSX zNQtyajr2%~v=IiV5sPb+j!DYQWQR6zUF1T;bh9)M5l z(@zoAKoxaSB~(xy6+#;|QvGvM8#F|<5`?m#!v5hLW|Sq!;0DdWMcwpFdh;?fGXyxZ zI8~DwYXSw5(^V&8@s!ajSu-`SQZN-TQ~779<_1ksA^`-lRL{f%r~tS~feMBI0RKv% z9pXR=hJh|wHCI~`C590yxo{#D;51baE2lFNsTEh3&^kc~1K2?^!U5@swQkA)NB?2U zh!P#}K^kh)E{&5FS>ox?ku(dUIdRQaqmv~Cc3?e%9;pm|W}u_~VIMSPU9)K^rSn?> zkr<6}IR`>Cs*XA(7GOhDV;#gL4;FhIA-giuVITH03D#pfVgyDp>az79PEuu47F=%? zFkN$bU{hvzU>vfm>`WG$KoZ|16U|s65KE9R4Pq*lFkqLqV`=tgb0}vaW<jyMm!E zfA(bWH6lkM1Huqr2ZB%R}u9 zaUc%i8}OkU!fPU8@l&oKyLe$}<@Qs8*3EKm0VGZgNz*jh5icXwcK!Bm#}zWJKpeQ? zaG^jL;s6QG033orAUuE_c3}ygAQ;erAx?o6vH%G@p&v#!3;3ZFnt&Db0SZW0YS+aH z&aGkaZ*}9TbqP^$4dNk`AqWpq09eEikS}+|wPxW_bt4F5p~3^e;S8wZa0}uP@}W~s z_b#O1ACkZzh+!AZlNbi#8gSuz#S~l^fXe{Sd@BllL9pKf0Q?rw`2Va9cbnF1y>(-g zhj5?57h(Yb{?{NfK^+9*1J)rG9^e9G!5frKAgW=X0H7R5VIWw68|pN+WMYDk>k0tpGqDI#VDvAsuYgU5)rwE&v!v7Fe5@mNfVn1GAE(&Ecx8aJaZy7kP^t z*&qy7Nz%b`$yi{pAsR&D0*zn{*%lK#jD^_Nq*n}B5i&yY5@ZcZ#;h3w3AO9-n1FS(Buoe^2!9oDw z0qUWS0e}qP0V4;(hk;m#8=`cPq!hBNlxI1lYPlTMcOd+v7Hou28SiLsSBq`-k>|NO z8{-3@AfKTi8+^fgL*N>y0Rsra6VO3O6aXGNw+!H66AA(t99ST%A%eddd?m$K|KW$r z8L!US3p4KN5bu*TCM{wvox3=me_4bJR)3|Uh5wlwke~-(x^kERA8?@wp1>E};hILd z6=1ptU{0>2~weZCD>$g0LK)=12Q_ZHd-F5au|)_Cpdr*e5PATT6gW2FthrR zz8ET6xLw^fZ_=O|CU+XLKp=brNAF4?4gnnU!5c<*qW|~!Oa?%l6@wTAx~Vn#iGBH` z4FU{Fu_q7!EyUnCyV{Y3`L7w9tiJkDz!^e@;O`dJXZgCXQ5LYt_92h~o>{^GwkmA; z?`adeo)>#?dG%O+Q!#{LbS~Se{hG9$)&Mp`c3A>`1K|(W0Dt3=$N(2<=TW6SC9>lq z2LGWREcdlxJF^>G{eW*CmLUUhA^XUokCPEo+f%5(9#{>K$D5zZ`@LCj1?C}_apH;#hrQjKXn#8@Q5v<$ z^;RUnxc}i4@H@ZHH@2PonARC5s*NM+Zfj-r!2idQxAE?=>x8(2gACfENIq4o zd?Hv@RmQJ6VxT|>d}wQ&#a~vw7u-{-RxvUm!c~02nR~nQG7x)tBve4gm#e@H9KOM} zv`ss0=bKD&AiJ{Rr-PilDco*Fm;h>tquyGR|FX&YQgD&>JS;?hEvm&&%A*wY$Q1 zSJ2Po2f#rw_#vnaz0eSS!vV;@=RucI!kxb$n4sFpS5wtn9KIv@Q%Jlou;7)6VYWJ5 z&bPdz1$G$OSpYTS3r5}n-{^2R15C$O-2*CyjdD!DS-ZS3S=N+;s zI^RK_KBhe>!2J&B;N($0x4(j0Lonanq;pK7O3nrcrD8b@wx!AQD zZN|_sXpr6Kn~o1>Koy|)u8IDUgra04D6ui zFP@&!{Lc~Gq>+8ik-qJ1Y2<-o>Hocc?&-en+2HE4e(Jxc8SEbF!F~+dfDXw1=Yd(V z3qQ&eT+Mgf?HT_dlwRihKJq0W@26f3Mo|(ZpAG)L4cI{NeIA|7p4bmx(t+Nq*}n1H z{_&YU^I6~PDPQUvUKuz)@}V^BXW#S7zVr=0@wr^>6}-DqKltT+-=9M6TmSf_{`I3? zN^C*$3js?2-|2Cm@Oj_Zo7?({+>1|N`14)$k^lRjUiqJX>*b;A?cNQZKM)Eb@0))5 zL0|U~-}fn<;}_5rvf&-nVHoNa){mb1$J_e>f{nm|1PdBGh%jM6H*(w@v^B4pLW6At z1qxKiAwfEnYykKOG9&{z4F5u!Jc%-;%9S5SmShPtW=xkdYuY?X^QKOjId}S8+4JW| zApd}!7bs)Tj}Q0uy_@rI!ozDuj+x{i6wzKY zGk*>}y7cMP!IJiDTDA7JtP3KWXRGZR+JkQ6?x_1E@8Fw@n{^)+eth;ni8cv=UqZ?P z#Hv-l>fC<<4oF~u2LEz)U1!;C$6!L;4b;dy@~FYq8h!-g#~KRd_7{DZ$@dkAA$q8o zh+dhP5>fxG_)jV+;WCb72TDcNj5gkgV~#qWlptpdHV7m^4+;d4L~E__M<8NoxFLES zs@EBcTS+-3iNHZAoRv4(hhGT#oivL%M(ik4fMlMDW}0d$*5hVB1{vg#Z7fsQT3!qi z2q6?s#NlFCwx?xaRBAOSR)rcGsBuN9G{7w9D6ytWW=2YBrIua_Q=6B)31@>ty2eaw z3AItkMPrD{r;~nycBoaYx|*n1uSWIiaWA?r>TQ8|!?3ewb~hi>AaPi|iO8stVHcoM>7zN+qf@|D!4 zOeoTb7EPSeAld42%P~()b=4}Dg@DZM)61 zqB62vuGMzmP4&!y)x7mY-4$uj8e-g=(RO7c7WaE^W1G0Fiwm{3O|`DX$bSH*EYj-$Ek=L~POpinUx=*dU-nh4OS6+AKy6=wZ=3;g3`9Z9K zifY(-o{sv^9@pM)>?AWkBJ?0T|GZUD)2$ir+Haqx?_mKS{6aV@8=gRd>os=r(h|)o z^=wN&J^UuOFTcvSH*7ig`tL8G_h5k^zJb6+4e^*48%Twxjln5(Epgxbj#j^AYA&Am_`T+a*$7C zBUC2$#)QR@j*M)iO|-}rE(Xtp%9sZ-faW|#Er75pg8a(Ea zS$UbqJPPs0V`&nKv?F9En`ld+Oc9P5Jf$yx84^ftMUplnRg%7Aq~OgGl(1u_>}YvL zXmawFP}!v-dkM^Jno^irA?C5%;Drn2sgk2pCJPbgNp3mwnd{WaCZ8nAmyuGN^zKb`^P$`yFt0(QMU3K?WsDyP?WWC5AFnW;C)kUp+yQy1q3fG+;wx@GN z7f|mCS(xSZDSM?zA;if~rxJvZh9K_l^Mg!VFs!A@T>`UxaODnfgZgsW9eOYUN@>(@q_9Fa@rCbWw2;15exBq42ZEr&> z+PC`Fv{`lRaEl9Gh8@=@dsS|dFa*oCkgyHXH78Wjxn0HS)`szwZ#<*+-SFzyT;tt| zQI(4)C3(TQ2O-~()(X%1Y74lIn{O0v=u_|3b-xr2R)2Le(KQ%+-B(l-0oyj}Ap{5| zh2ER=rU4ZYQ9*hYRGOf4sR}3^)X+l@Rge~{RO!71q<2Iq(u;I32vVeE=Uwmj{rf-I zYtKn?kh57cYbMWg-9 zymFO<2Cf^OoZ;u684=*GmFrcy961`t46;qS94aH=+dl+=6I_4XXT?~C5Hdg5&N^s}63=|XjhW%Mp= zKrZRC3FI+}WauLqv_HuCMxct^hB>KeU%{kCWr)DKO=R=UPxrOT76ZR4D*HKsZ!I~N zO01}C82*SaIH_nBPjI0Sn_JzNF_e~s`CE`ui;2i+y}xA`DO&5oA4Oem8*b~zti5uO z>m6}K^ZNd|->Qj*@_pno_<4;rg{b7IW>tb~3e&@%89AP{vovl#Mqb}27o_WhBzEJi z{TJCb8b-4NqfPwtfDL5G2*GYo@XmC0dGJK(@O^Q9Z*!CN*wC8cMt_eR8>~YSlHCt% zNKouUAdVB^UU79GUQC;4Twr<_6r@5Nm%ei3L;88!0%Bj|0t7Cu8W*kq0PmMb_}h4T z#viN({rY48jdE#O<%Xa2X=NTD6hluf7DUWf<#&#|y@GyIe-c9nv0H=%B3DqsH&J{n z+y}s2&q^YWLdq#XNh0_DAXs@?iJrS3^gweQY`AHCCw}{EG4@6R_XQs{j}Mu&_O*cP zx0ks!El_{UV=s4|KAg|}zJIKPlr@U@aItoy{cJS$y^&@PY}by!x#k*nJow@2sJ#91 z*M~5TP24#PhLpSoPC$_eqh_W)5M)pkXwNhvUZrQE{<+y_*Pcv_r=H@6$Kp@QyRnEzcCx`AGQ zud&V$WpvVLblXG3{u|zS)!@4fIR98Ap)r8kWfqE zP;2#2Tl-Kubf`mNs8b*D3njZSQyY=*1OkQPD7W#n+!e4QJiyFDy`UG^hNR(fBPZyQ z0(!7KfUXn=y<_h$4+$5f^$t3rCDtH(Q+vl!7*1mW3grQ3K_aq+BXZRv^3@~mV@Zn& z2@yr7q;K$~C6LHU;mB&)$eRF)xgneZ9oaaIYVM1q*^F%WMs)~Bk*Y`06b6{tF@=vo z=@r6wA#}0|urh#74*|OzgD)b%+`Q06fKC?=*8zZk7zj@#<(4bmco?^`n{(V|j1aB6 zk{wLd%T4|BtC>2V^m>asy^IDF#BTE_OA_!F-gA_Nju!wBj$+>}5#3Z6U$ZXAQjyLxBV$Np=GKTV09_k2r1kFf}#AmHFK zXYeZ=oDu-IEui0)qPPPnxAcf-2>7cP6R3_3MWZ85X`@nNo_EIZXb_UbD=F77a8e`J z!Gid|lSwD*@t=F*Ur=JO2PAr^WIYVDt%8Hs75W`T!n;hli3GT_0X!BWJ`KAuP9+5a zZb9fKQ9<1saRv@4fBRxDPpt{E$@Cvn=xp4Cvt7dU!(R78)v;pta0%Kdc*7X@(GvAO zo)l03Z7xwa8o^sA0Fw%MJ`P-j^p7!43DZb>^ff7ZE2Y82%{(>Dk~Lw0JS;#z%vK@T zES3BR&T|4E1R%WL8hP=!L6$J^g$l1KleDQ+m-?+V2XCZxe#e+MTo`%J|LjS7&EFyCO=r zjIcKxuq90CA9I30O+nyiR`WjC^O?-cRK}}5d+cW=I;tE7DjSwh*tq^Iwolni+t`~L z*GZ^y;)HVy!*T>7uoXF2M&DSds0xgpeO46Bv!hCG%F9ozD)13~?e{GI9aUk_r`%Z4WFz0t zh-aDTe{Yp4{1vc8X#+(W|Fu|u7Ad1Bm3jVavC0+a7yrj%EpaR^7cD8%EUuI*sb?#$ zjVNiRDsCDmX)i8nqbh9|Ep71)oIRD|*JF6zSvtI3I!aYGE?PFBS@y%RY$~E`rnqc& zpo~~px=2OzSHG-2D@%_f>kj|2Rs3aV;LG0jm*4-F#d;D^epXz5K2T1CSP7rL81a|@ zS`}nY6%>&blqD6^gB28mtTK4`BV=j2+&dj)B?Eg5b8`t}NhNz)CFk7|4(cl2^Gd#* z;%iP-LZ($Ma$qC9z#C5h1qINWW?7tKwM=uFbY%5izcRVO>Idv)_o-`?W=kLXm8H8C zK8mZ+G%Yf%ta*4)bDx$_`*^nInPlx^zE>~_7CTfMhwJvOf1a=c!9w$8A*9(B(8A(AfCi4L9C5Ohu- z;fIMz(}@vl2oU3pPh(8>Ys8#0(qX8~zpKb|qmTs_^*g_IBFsFC0)6j9zbYA12`-p>{ zVqro3>2K7$f=RyO#oBL`c5p;}<(2Q`&h~WP@N^aG8Wmwu5&x?0{FPS{7$3uNOM<&B z;6x1a1~ni$)Or1)bD#aIT2zOIGo9&N_Y;6--4(vLM9FK}BXPm%QbFzD3U-INgnE2cS@Ph5UBy4L%?*vw%FO0rHm!us0P9 zD~Lo(+JRi{aDEO!f4GNrMC2E`1g{!LVviDX|6^k$}i4Uzh5A~G}iBAuWats4Yz7;}#H59;Mx?l6j@F$Luui7IQLw($e zRA$=Ylw;6u3S=%=*mv*YnU>*s4wh5#k*=1}bq+fE`R)`XwT&w{#sZ#(r=2bxp4%PH z(WhF$vK&AFWwqFJMb_jFR?gFawGx){C2p)DO*25(iKqTJ-c5=kz(zGdr>MAqxIu># zc%LIv;|1}of>)OYj}pIY&41TIR4RRjrMl8R!NWhc41L!_PhLG!NmQG3&NtrHGV zx~CSfdt==$V{qaAz~A`5x6h}%qNg;=rfi32$d+cfNq*);xAO*2PXIyg_kv0}*~%;i zgC)a*je^qSIJ)Xt-`Hc)mZ6mhn(YcGs+ILK61IGoYzy--dc0c=4}S{KedloxcKgBY zMt-Hxcvo?N3<>q3nG{x;pNyUdFoCb3L{XYraG9i%hX9-00dFF~T@J%PfanxFY|(6f zh;{K0N_QN+`0p|>3APdX!m&?T7P?ja=8vuAdL^TW0sp8=V004r~fw{i1XD%UMEK2FFO5a}q@YJOz ztE4ZMvg5$NdFEd(2Msd^r*&|vwXzOvMtL-_{=c=TI94(|)l~)jYHT86ynCY<_kofo zOmcx91J#jOICY}>ruT90QqOT@{q+Lf8bEU!59H(F-z;MAc;b~ZNr!{R==BI)&@PQl zxZ>e0bWDK@>qmV+Xv}8B2w{_TYZG%tTY!ZxV#rN+po{oGhBMkF;TWsst>71`IhmW0 z3!AaJi<9W+pMB8_vO7#OTTWM7A@4VvUu-vGskz6yoAkDCUcp@eAO%MEX=JPS{wDUz zPTmzQ5m2q4_dC~{n7*R@^qQ$0^F@aScz}S7zGpFl1!s`(i5D}HnqVy6v;MPy@<>uo z;aI~hVBtJuF*un0m-$5D4Ugv=elJ+Mu+WX@g+ybrO)L(zuLpL)L(1_66;NqbC?A}T z9}7N8gN{I`;qax8nOkYsnK(Y+DG9VZH~#PwXa!^cjCfNK^d|0%!574L0EL}FWBg6R z0q-cB@As_SBLa;G9H804AVlH-<=r&=%_H`y=pU%7AC+}QZ9{{j6y~Hrdxg_JcXj(z*PS)E# z2^W}zyFRRIJio=gVd<7IXd+sFy9t-k{Jes zG_3TLp8?2o0hjZJ4|L6h3+0&$jntJNS<4n~7eBKu=3|4ZaQ`ri@b3U{r)~A#{fmbt zgp27L=R55ez|vJL96|V}PpUVj(PT(QZJ3acn7A84E1;WaJZ{y^y@V2Im>$nnbFQXh zLfUPwY9vxo49R`w|23G%jU5V(A7*Aqxg&8^T!2izouMdHHIX;QAe*g0SQe25o)-o3 z;srE6y)Al3{mM+&s0^PoL>QR9@oVaZ~K0X_vQb9I0Hso9UzJAOY&nScwV z6nb#RmtMntuj_4j3M4CEu<_>sj|=U`yHYEDX7(TApMCwuSiXBVNm;*j@=q?B`Rx)< zC&J?kJpzCiVpq5y7qWm*kAH?MMOb#F^0bq4N4Y}C(UNvlXIzElN)UlWdydCU?g!mp zAph}M;UcS$J3Yk9jZeGC3N4Pd6p{@YIJFB6j4Iq-^AT_M~L}x!Q zuW~@9GJUfI+!XgR;?{Q!2q2K^PB(DdE{_fnTh7}Q6aIdna{r6)^QwM=kY(a#{D)^A zj6FJi{S@rtPswlwM!&0W=bU?z0Wq)fXM*(R4=^F=ew_~8U1ZT+Nz4E-CCKTYCn@&8 z?)k3}h?%KGZkw}di1an4cehXG&`~OeCNJ+vs&T(Dwmc5A|2E#6ZvG{@Po1Ay)H=<- zbG-JxN5bB80Hs=MS-E{9xe|HeXKf)?8Vq>kWNXeNqC!P{;V4c=567go9ydY zTvGSXv9x;9*Xc|1@js`EuS|ZP zJ3l^m!I3iiyLM8`T)1}88~MBSuzOv&_3?f5e={IffAMDM=9K^2k-H}sZ^x9F-?@L& zlF2wI*EM?QF=^^``4|0oMlgp99dzkA_jc-?SC{R^rPopr^LuY|YNSfKU&9^cY}w8Z zJ2tHt@jishAJ(u{wDIs?!-9r;d7u2MOjaVCm%iD`!n@Pe-pfRnZ?Y?N z{(ab|SygnBYX3x!NEx*nlpU_UAu;w=l0Ryss^6XpcCrbwHGoiDr^-RUB??5L7GVNw zCyIzrz2Kw-g?rD4JL(rXvQ!QsNAG!wK5-{I{XxbO1RshAXq1qt)< zThT^)ceUPI=EhrGlRpZ80yNgd0eYtN<7~v8%^<$Yv%6>@hJssylXGNv3A5$<#@)*LY46E6+AL|f$ez|D6IxkqAVPC4WAOc z)u$hykY^)cenjFgYjv%BDfFT7@juMc(SQ7@mSi^`e3DtSTF!t0wgSPXkif7QyhsK#G&tft<<|?d>36FDxB%ZwRRF!-G^oPj6|2HbB1~7pC z{Vytcb#+C!ytur)yt+95Kb+*{zyBOWOY;2e;+*(#dVY0wM06#Iq9l=)yg2zESMvDe zVQdl|25BD|xziaJBpWa&7HuxpDshPc$PpfA8 z+FJjywK=o6J+*Q+)i6IZH#0LcH8n-VBL^qHZBDGOe*5)nbZvQPZE0*}X>fI6V0p1` z<#e?B??CnL*x-3*=T7JNaeXsk#N)Kr_pHP2wDIX>?XB#p24UKiRwKY{$RfiP;L`rg{q;s%f ztgmo{h)PxzloLuH6N;dO0BtnwMrq9mx z^v4XGGEE9E6z^V2BG(lkt|KL{1O&GPgbq2m&)L|BVB{1B=OrUUs(xOIZZ66slxRypb(_>K)Ob?pf*TS z4?RspB}cOqf~Yt(YYNBz7nPj&te2~qp;;^XltB_QJ;(NTsJ-0cYXqlOUFl4LG(5nAJL?sWm^Y4b15K+m?o@uTB3zf94k_2fL9E=WWVs6X-Xoxboxe=Qx z^I@IE*S+^!flQ8WhTCnY$S(%I`MiyFd$Yn<-4z4P^}iQ!LDby3Ee&pYLHct{7v(*F z+NlAAH0?KNm z47$^6?t4ay&I&l@O~HCxkYFv|!AF>REp~3(FDqOy*WMBO$(V`QzyK`VX-dz-7V3gjYrvDem_Ey9u8YO9`FkEikyG?-X^ z1w6T4IPW3NRTD^UmUA%5s&r*wlVX$Xu%2rF?biA`H70j}jEG8Zq`OZ#2xah8kaTAJ z2bIk5*>~6=Il9-Fo*icBkRO8nIcfjUMD!N5EGX~J#HZw!#ajjG(rAZw#A0O>wMwGn zc2QwL@pf^sBX1~EX%9hkr?jMrO04Ai(@!}$A;dk|B*}lG*%i&8l7$BN z&y??|_G-QxI+f{s8(|g&@{093vX%k|NvJu3o%S1DV@zLXFc#_sQw!1gE#%gYi>0;( zESqLj4nmnGMIo0RaGEKrY3mM%P^oL}OcV1qiAtd>H;J(Q51wu&zP0PwhXb?M+Mfpc zXSJPQ6M6G0NT7M5ib8`lx)XXs{BY>j2bM#h?8kb_Wb{VPyggI~dSJ5dPeX;h+}!W} zlrO0GBA}NoB!?Zh|AR_qK8`jYQ94OKc&{LocXOQc#=X)RJF&9kNPEJs8pV>7!^fR6 z)~`@QfHNwK*pcwoyqhY0^?z#7l&dtm*HUbT8<7D#2m*)MH8`pV&BEqX-agZXW z#4DRRxN`$+sV(=gBTP-oXyQq1&C%3o%B9B-QvC6c*5B8!PRYVP?EW4fRm0);1+p-Q z`S69>?NYJEdnYGKTfW~?2V?5b)~K<-O)}i9{mA`(h?bB%1xgo}3tcGem6F9#y5WMD zI3g9q2NdDXs4bo%*)VzM1FCV7B_9A!Dzlp%VoLylh)VKM(%SOVsc(ZUP=ay?;d)Uy3~4N=U@Q-N-6kFB-8i^Ia0l_dt4FG4 zjNJc1k*BU9l-1oL!fzAD^PwS32#uriNx}PE9}5$4#F0JTeaSk$L?B3wJ(Eff^C93vdA|NNgUE1Ssb+ z0oV>4xfHaIag9xm4kEp8+=RRck_J%RN9!MzR0Y4KM9x|6P9Hv))Blq?b`d8alBm2i zd?NunR3NQ%M{_0VP2>?vpJl|-1}=>Uq9Q2AtD z0x@Gj6H>@0c+7T|zVFr>DkColyupw{c%Smdmj1kzt1%w&!Y*e>aq%KWwmZf*F=Bpg zj%k@!mp-$?9mE$1Gb|?cu1q8YQta;irUXb*EE(t2dzm4C-b1RIu>Pkn^^{&B%!r{9 z?H%r$L7Uonb}LPIvs9tZ&WlxBMYQ?)-g~o7&x3W03U$S?M*7Ghwxx4M3-RA0Mj#_!VtVT#TQ0 zE(4=!z^%0dfvh&hLOK3o=eN|T=MC1()z8=00?%jv$tAT(v3~K>{m6Yq*Huea=F|q3 zw+JMk#!+%YDF0}NoQit1>C~173(?SD^eDIQ9sFMJI-X#=mhy$0yz=1>F@#csH7BL3 zt2yrlH&yd#H$^2<8|lvlo$c+JlrImPN|Wa5-O*$}4Y}(|JIlDC(}UEN`hBgm%n>9j zFRNNQDqCu;TwwHtx6Uc~_pfVW6<;}_hLx`aPK^Y`&V~Y2r1H||mT4Z{A-KAD?(ATE zh(D16!e!k^cKyZMt#pR%VMkfRb6ji*LIc~8Zxu=|e#%9rjzruFK+Xj`y?+up6!f|h zD+4u9;O-jJGj#u;a=9oi^DHjrWw~A@-d4oIq>Wv(`vLkhh#1x8TEmhZj=4g8QdSw? zlH!<4-QaK119{#Pm*^VeOgicQ-4{qvPPwD=>ZZ?69_%qJ=R|9p_0vDx{mh$r(OUsZ z4Y@3&-hYE`-wJhg4)Qj&S7mocg}SsnnLafRfsKqs8$*=A>w2L?9Tct)>7uzns?Zw8 z#Y)JUPB7(k@@wktMI>zfB^=mO8cQVWh!L?7Ef z5;SQSj*S3-fjrB|0DBS>pf7Bj>|w-PoR0Vh7d?tX*FU)P_ew#`>dRSgPqREs!xwe& zeIaaT&lP#76AHkGy=I=$8LQNwt&8?b+Gw%VYg`xDFhc2QpYPPy7ssSUt%|2@^z9Qu zWPW2x+N#JX%Uee$ryGy(t-b3#VL|~Gab_lDige0~Ou>qvY(ORm>Y&>uJw$_}bE1!1|*ocAf*A9_Jm!h+Pi zxSt|v+A4w+Wzox$!Iwe^k};Bq26WUkI)-qHjt~wlP|`FG(F9d$mVtqC2CZs-M6C^C z7E1+MM#;p5^s9N8gmD%XMwl8}MCFi&>Cx=-yqlm1WY6(@)d!X67T~a^GQ*M;W8nT+ zd6Lg$9~9u^6u?WYnsNmd^u+a;7UYWnAtgz0NE$0O^iOrJ&_aEi36gz8%!+KxnsLlJ zOH4xuqWeVWGlQmv2*)Oj zOE#1|*a4d3nZd^dl7iwb;L~HyAW7#FJy@?aqCXTqWN7)Wfg=zJ`9nef5lPcpA1$uI zIS;{rNMbf*6K;ja@OH5CYntq%nl052NkC&5nVr z_fTtvEB_GE=ks9?Ktci$^pBA=I3$S#YjXWTym~kqkZ#fGrHJ<(rw>J{~*3TD8*z( zZ|i=nan$X{a;y&$3`{Z?N z?}wnb&`53DVooj!(KRyb6+pqhr-GKv#sr>!w?zoM!b^icsrjUqr3Ta#Ii6Go> zN*`41kO}g=^Uud&+sB$g*mgoB-Ao!&Dr+@0!^Mx)SQbwG;=qo+b5rYcn&d%PD-z4& zi0GL4sQVEcUWeuXi7llx67%IWaE0uXnZK|%UQEqe_Tf@p%97Lv{k6;HrOM$e{uFAL zGZ&ika695=#0!mo9PAbpVLUc}9kO0O$qhHb9*qa-|H~z1%iAg9_V>wqRv)p*TVTD7 zg%@+*h@jXXgWYFKVbRQIbIh;fCE=8#X~lX!bIdf0z)lolsXDOgqWSx*S^N4xWjN*j z67|bx1r>xzZ5dxK5gtge!e`=B(^N{dPx0qB5z1`cH~k&`Cq!;pXkr2#G0fXs>}ZOX zC0JucA;qs^R?(Y5^+2#iykuOwSZYzbLn?w#GRs$zp+PbzB7^py^%*T-;tDacFpXX+ zUQsNl^t~JF%Voj}F{4DkD=rDPPo1NaTnxOv#3r;&_hrpjXm#NFKIq0*Dxdsk8Hbet zo(hyoss*D|C9a|+X>2U2NJz+13Y9+a6bbtIEOSmywB}6(#1vc?UqLfiK^-aPJ&>~} zT1nr`Vc|`tr&(@nSAJ@eKjCZ7Ay+{Lznb0JOO9|qMSiJ!|zq}mHtATpO&H5mxI;)*8sU?le zmO!Ng=uvZhWEvuRw$jb9mN_s#@ovr8c1C+bO>ku6N2gK=QPzYo3QD8{RJsYG-y}cC zjjvBbE@vw?H?`X}R%$hC`8qN-TOS3KhUt-^n_(9H%@oVcYLiXz*%Uzv5Nd!vnGg}( za~Itw)?9tJZZoZ|z?TdE56DhSzavIJy;BIiMiOFCB7BFYMz-zDsBK`j#gH5~MBV&7 zuGByesA73J>4Z2Od|Ieg7GzO|h z)4GJUxtOT|^fL#^-BR}1LfFO4THkni`Bb%{!Wj5_9)vO?2;tGi-_j*`QNLc& z6R%j!k0kN=<%rknmUHU1_58XPm-K*|emptGG~Hdz-P1u$-cty%it+Lz^wO)~;c{32 z!_glv-=ApKpX}csKSbh!BT1R-&%Ed-&Qr1S19|fOpN9JL(+9Hr2a4wgGKL1ea118W z3|7$$Xh)J!Ep>JxN#e8zYdHqnE(YVxNMp2QewwmJia-`i5TG&YuNEBvX0IOR`J}7K zr=j5BIB1v;7+H}YSu-11_aE6zA0dj3yK^J^7bAF%(LeH|M`okP{-dWH zBaT2)B%Zu=3D$}k1>GB4-=*x1LY^BTyr}7Yn(N1-+{qY7r#`-$j2b4*9^UEgixD5H z;uzw{7~r}b&*S)Zt#u&B>|3$+H{r_xq1JEl&J9#Z&|8jyLc;DhZ0WaJ?V;Q9^_Fyv z3Fl*hh6>lz11~HBFI@WoOrM>6r`=$eW<;0MP*3f6o)b0DBpyy}hJdE`a{K|^K+rcV z1t~mtBeMy$FAOzB^jOmXwsXwa%$iBWaRWkAZ=W}WVaN=EsrNA@PiUsjJjQ;#9jenW zlZ>n9mYe)8t&?Fyy^8Fb((BUNn~JG#Nzj=B`EX^L{@}#hrabG7f7NyOvVpC$HF)gv zk=+OMutP*^2d6fC82iOVXC?{yLuc;0{yX;iX1nWVKF=h+x;9tOl=N=Uf=;x^CEciT zz;IE9&DGBL5wY2imowvgoTP{}Lmq^0YddM&4{+s=R6-AL@Lq3g<6OYxT>V~8t;CNJ z&Z#Mq@|-mib0+Lu>-?>Y=G@`(LG1+=@#!ZaJ#}SWo0oIRdmq1(v>Nar5|&_dGqaxJ z?SDDvI3AXqQqzO*6aVg6u0xkzwJh)4!#QxU;G0N5%P)TFEJE*p#p$#!adzDONp0@4 zJT$y$S}DPO)n0S?T_$FA&~gc+53)F!INY1rDOh2@M(Wx8u?;_jgjus@E^NPBkbbes z$wklJ*9p0L(YiAmb-twhLJ-=zc4Kl)?rKq&nE%RLy=93btt>YAIsZ(z$?Sc%T|DVu zp$dzbWhvcU?RTBlBOALCzx4K*4faVuain!*eKdsY^G-}Zd&K9?YbgTpKak5q1MfB* zk~bdIY&`n1tiQkUL3jPuK^N$tMmhPH(ABJWy4wI2c8r5sp~g~Pu=7UNf7RPgeqnC) zejPQk6>$HT$18R*?M(m)G*NGSZu=#&pT2^jv9=&}!e~y#k5MjH-~E|eAG1@ruYR?+ z#Rc2W8riFU#hwEL(55u2!#J1M#83#L9PpC9;1wCm3Xvf5^W4KF?R_ZQ5*XTP9r=Cr zV*NcyFR2@KV(4x}3_>JVoNOFgRY9|bh4!;d$K2-@5a~FMdD(cimj=UU!1mj(vs$3Z zNXJRuI^)OQ^$;E-PF&&T2=W{Y_!0jB58>fYj<*Mz$p`cM2NTijZ0*0Lc=4dh*{zqm z6ae-CmE_zo+jlXBSSI+D^R7&&*utwbRJJaZ6H;e?nc34DOKs!%)dp zP#(E{dgLO~@a)X?VnK`oESu-^&(bOVqe|z3|S|HzNKRVkO6%ZaZq$Ad5D zvrbA(jt?IZa4sNlKq2h;sXSpSYUKETP)R74a*Cd%A}El2&je!et-_R6;zd`A{;FyW z=e_q}*2in=@dAtyr$U`;JuC#r(zU{+Xi$oz-Q=8bf}n1coX^XnvqP&fj1kP1ciJ-J zt_V{&mBHzEn?V-6vUug9KgGTGg1{=`%aQS@GTY%yl{CY>XMo96oqxZfolmWi zCxWJc&rRQkw|!tm(f#*O*CwwrbIjAT`&^q$ZyvG+k@usGE&dSatoJ^^MD9qKwMCVG zs*8A5xcwu7x%t?hL5tAwd|wzE@=8WVqZd0GalD7faark(=B9vNh&wbkk5*k#a(+JA z8u`0_0Wn5)(Cy77;i8{Qcto|vQ5#$}mhgaRDb-0nytwlJ_m{8W#^6Qm>A~b+yg4Nf zxSZ9*1=tXqkG(v%!g1d@j{4-!wL8nJ8K^|oLeSS)U&d2D084hQJ@y^U|HczMfQx_1 z5#G(D?;PD8UBm8-C3)`_7C~<74^vIPD$?wV6Wxu9LWt*Bv6%m)uhJ08QjS%wJ=%%w zSAJNw~!$2BOiWE+C6g2Th$j8+kYRq_cD4zg#bwt-{^2 ze50SIpd_VtmySTy+0Chq`u7%h|AA)p$a$W842q9=1y83T^XuuiyCDNl>eaY8Zg;Ed zurcI4eISJx3edFZ%@AUdxZU)GFQR55=zfMa{2?e@J;D-|s$gUtOBQF8`LOj*rNKSl z$%1FEGA0L~Xh3%L0tMZ|n4@!sw za~hMicn#S##48HAgdrC-L5B4pCRM}LTF?PisZd{MgI(5eRU^NDqxg(IhW^VR`xp>c z3RYQ6wZZxpA>ioFW{oJj^4F~Tbzg}RHMXClIr>Q^KdQ3tvF}wHUC`SmQE!iAaCAOT zTPq6cI(4cEZWa#sLLisFr8!P@UQ=@y^zn7x-_qIrXi!@x&+AqLvu(ekeUsnSlacBu zE&uQvuH$N1PfNyS*S*~I4P25vLbPSqU~nqY)1{B>v8*SllB0gEt1lqRE9lo-828oK z8|sHWdXIj3w1o`i+3TPG33`(Jpgw)u~D#A1AU@;BOi1{d2Q zo-Vdlo%<3&_on9T$Zz9*pul7fjxrr<|QIc4VIbQ=T+~XP2LyM)!l4Bmm=B zC;KrEg@hgwBdJZwg~#+TlUI>D_wjKKqp5)rEYu&BOHa+aWZ+6(8Uh()eot@7B9W{T z%`*11=_WgyiAVb^FD8JA6-5foN#q#U3whYgW8Q;^d9~|GJ!~HY8^cH2Le@yP)yZjV zDrnx0b&;QVhrl}ZpsyfZ^ zAUmmv>MePPrbBVSs`E)7zaVYX)8vFFHbd%SMSnF-dZf&&<<&{>u4oD-exL<8&E})g zF}M{g(T^bmLLCtLc}hGy>b;^odI2Wxq^Z)lFd-N!&{kcEXOc${kf((QDJy`vUs1}8 zR;#>Cu5m1>iI6L+ee}Nb(C4;$zDlVpM4ko5BO#W+IV+PSUrdIW!=e;!ieea}f*46> zK(hbF;VxqqJa)1a53byzc|l9;MJy2ZEB%1L(iLv=%VPC7Yp_Q?F3&EXS#Hp})3fO? z|L!|JGq@FSm*X0QLgRbR5#%Plx^K`&zWpp0JdCfac%J!s6ci|N zri5~x2?WRS@r`Ci)pX#$=YtBAgHX-}T<=$b&U=pfU~GF#DT$gY+J$aR=MS+s33^ z+bOCZWFW|^AwJGgp3Wyl_A27Ob+QyZqzQB@?UsP+U@TXhu@;MpRF>qBL{IthzpfhZ z72&SdA@_f-rJ5Riy=g(4JO!a{?CSMRH=pbFeOyknk}UTgsux7h8mh8*G4Opp$@fry zT_|R}8k|S1@s0U;>uwb5KcOl?cC7=WEsv_ySH?M+e_?MP&B|V%KD*~o6i2W5(A$`o z60dTjXVBS`ba-Y^?!dIY%)yBe8NGWCeeu%kiC2a7JT|kwknr^~`$^DEUczgy&a%h5 z^ZIO4qII{s1YS4=*feJzJxOfM=d9gtGR{29#bYr6sT_ z!y}EA3xTKz@ca$~n{RLA`=g`@v(}UK1~a>76G6BLk;ib^A8MDa6(3aL;pAH0AFe#w zW{dXaIh((c#k%Lh+jap=`E%N9O5`2$yN#UQpI!A^+Kk%x1ce|2x4*pceRQwD%fIsa zvh=F`)ZIyg&&>^6xtqZjGk?lYnzs)aet%`o#M}ICp>hZ&Ajl4`^~5}Cs?c{4ANmR= zrfT{i3%3-fWfliMQ(x@4nXmT-u{vmeEmJ&VVSzn`DRts<_A^3Rm2Jve&u0I+zVsCf6LWb17$1u`(oxjFNW zXsBFO`&L48A2scpoAtr!C^sq`?AFKjueqBg_oy!9PsLi_73IIvy7^PCqd^S2%qNXF zqM;NHEdFN}%xiy;bHIMS%zbDnzv$EjbhDN@& z2Q_d!UAdC7vW^)SmsuCTvxJ&>cg&re|3o2ho_qINI;p_zZ??z=4!g>=l=YpJpSY{2 zig$=E-}<*oHeTH(TY5)3N|93@PB}&zq=XLN40-0Pq*udZw%ct~s`_|NWgeAL@6c>G zr24hFQhE)9(bP=Af=^X*t>t@4(6$ebWjlHIt=jY87Gw8#h60cchzI_`jh|l#jC3XLr_1*#1eKjmT#&)P*y#&?+j)M&=6+I9qPm8$vOI~qn~P4 zul1KfQp8a}a9?KYxuWw>@5Pe@J*(Id1j?jEy<$!(PkGRfUma}Z{QgDjOg0s#aU!9qwVcMr7`ZW=l z^hnc9Cd;VdUo^dm{_zUJ;NO}MJ9%AoE!}lz-5%|Mg^Td91S&~4^&S34@=cn3>GW?d zuD`t)X=4~9wpdlK4UKS&Zm)%Z_KzUJ2`Sk;A}DKof11F&+52a9@SnU`2`|}e422Jl zTp9tP!jgHUguS!~kRE(==st4w{n02*xVb;oYZHowIqjd~s!Qp8ikt1heI%3aW3<(u zq%BA}SwMz;6cPaH84txR1gUcaIsAEVtK4Ih(?BeS`xP(M{E!e6+0cdCxZoDmLjcFt zt?lrX;*mmtKb|yzC-B2q^~Cv@$SZAvzt%)ea|AC3BnPAWqM;ulF~-~_Sq>6&nNE~q zh{)yuOEsX)Cmz>)OD6@u{$n5_Syc=|xgp8u?@ll#J-#*nsH28TqD3G8647Z-p+>Kd zxTh0jO!gWt$!r{Oul3RB^g!KLGF$ei52GJmPoa2^qM)7!`}3fky+eYQ#A$^CUp_`z zFiu(uOj_NZv{sq4{DqQPLfLps+JzX}+D_W%PdW-r+P*S$`eA6_J^AXdq21o3%U?ry zVF?dr@+Bt;M-(cVTur~mOt*huGjUSZR;6WPW1W=Yk1(}NNQ?*|| zV*eOeBu#l{Onwge>74Y_C3>p3cCw`Vr{j;GWdf70_ye454Mp%UQT#K4Ve2+YO;^07(|7@g02~3+#Bd#OEBH&>PSv0Lz5bFC`V{QO)Q0Zs8}j2Pty?jeE|wb3nLV;t0s)t~HUA<1=bvJabi z&sZpUTSKpfd?)gwx1q5FFMi5dn?9L$q^xx0j5cO+NBtkXXJaE~gU5c1l_i9FqX$~d zelYTuRFb*j!rW6rbwL1)0fnzUIsf21uIBsdZJcI}a(2bnAU%|(D+T4+d>5w9@^0Q^ z)Ph{xXwbyn9hH21=|okR+1lmzSY(7aRyTl%-lY$mMWee+QjBGT*pQ?S>S0gH=-xIZ={eLhE`YrY7jtk+iw#Eh6DzW?zzySRzA6{heP4zqPFxG19^ zBSscM7IM%fS_uoy5K0R7!SpEl!{Irt(#OIkvErAOIh@P25l^qgS6G==B#0~PuDq+9 zXb$5DGrh$HTPuR3|D&h#rvDlcPl4|t!X$2=tVpO<=snHExvcaq(HMC&829;kN)Rzm zJO8}B_vxyxLx^<+xaTwjl_gWJfGUqn07syZ$2*lUkC zmbN)I?L(G+-1lDzVS()gZ#tdW^7*}Y&=3i+RtSykBPo3CMB}@o$G_$<__BF_E0V{k zn-2{bZ)WU9RtoO)GVNC1Pi7z6xQ54)Ki`c_bCis7!oaphLhWTa!fR{P!u70hFC3=6 zY@-dg2|7iave<=*E7pwbo3V9{cQbeVwNjsx0-`LA!KY5M$IjIS^w9g%PbP!Kotm%6 zUV{bFHIBFX7q;+BE*~;J2N$f9Uq^39L;eb)lNZ*vboWMFQI^L6XyK8)_5EM?{ewv> z{JzWT0z_K?0>{NY=h^tX?p)dSsvYLMl}W#SpIQgAwb=7pGU9jF^Su>veACOlK56tk zI~rUVZ4Rs+=@OAq*NxZsllOS)ji~#w?B3=k%?B@!wJ##zLYoj5QS3ScMbJ#5M@b0Ji0;6H@4C4F=*+nYSpXB`T5X6?QiOZTMIdg zM4jQ$mqWEtcPHj>MkLwmF$()lQkze3mmAcSC$B;_fj#Myjs>bGQ3I9E4EC0Jl6Mi2R>OUR&*y1T?Usx0%XvroTfE2WOT)<-~XeSDK z2dN3HKnC;)rrltc4qN@v;@6_)6=v?6zc}x_fVyYCf8XWOBkP?=i$?&Of?%p(7ElO` zbVE>drNs1CkY-_sqp*z}nF}(+6+vOD7Z5p6xcd#+utB3BOKxPp5M1$R!t2fUjWx~_ zzsd5;RZsUwBvqaDYn9Z!JfpvzpDkk{KA6)YESqqkaB(gjI`3I=0Ui2T1BEjHxoKCU zLkcXJiUtAG7bVy+3otF6^#%O_{#s8Io6MWt&4blmcyG+#E!qAlevGJ5mGjmgfuR&B zyKkiq)dlDXndgs7D-ZJnWvJeR7&X7!j%BME2|gdFa?qj+gQWrr`5Dcoq!tf7sH#f- z9{{yLO25~RV0TiCL9-u=hbsE9jB)OZ!D_P}ioh04X$5S_#*A6U&7rM-Lk$0h`A6hn zLW2w)K3w(h@nef&C(~?otX0Pj1t@dw?D;e3&^B{Q7Tr_y!?B`Ohi3iR^=qRn3uHNT z1;8Y%n6`42joKjW&cS7trRguNLKyZ~^7+T_`9FXB4gdggZ5joIp3V_42!S3T0IT#V ztnhCQ0Bds%dWwfJ;zXUl=PPV8G6nto`uFqi&yw_Sr_DDUX9QAaU|0wy=$lGa9Ad`? zl(^&0ZZaw8)rCuCxKeR3l~PJSseD+9Db8ra5(rzUxJ5R~Yym)B)o}1oDdq@Z5CZdT z0>B#o=wQ$nf&uUfHwq~e4Mza_2O0v#9OH>c0*tUEl~r1KWlTz%_K*Kh12Tx(hDU|@ z)0kv_=@AKc91;X36H*euOl9sQr%iNn)FDjagyRo6dWPeTG-Jdh7mV0&qk{{HQb)u+ zwG^R+GVr(n00G)m6NVVrNMn!<^uR&{Dg2qntW}l@nt;FA zS<|gFbvh`?Rr)#n9d3(aDfC*wkxm9 zeq_QSi3sD)I#kqY@WB*gXmLx>@;jP*8`mU&CdZ`FQ7^+t>@ok!DXZ*}mS!OE5CUd| z1@LMZJB4seI2WaGz&vxbfgOjixA zQ&UjBSC8#c3nP)i5f#JqvN+|Ho2sQhD?BuWJTr5tG~a!@9eUn=FAI_z>ljN3Z>5iJ z`oORg_m5eYucWx`8M$(dDjbbq@07UY{)GvOea_UB&8Uhwn>l0I?u z6;I#6C0G?B#opO3DE`gY-$^@7D445|3Z=!0JMjjMat!}6)NNGq$?@yI|4{%YlZ-!> z@xNr)A{Cm0UYD9hzVaL+u$ZUDg0tWzwm$qUkADef&_3ai3TYiLJDYDtz-PV z2nt5h298XE5=J{A3}XlrEv*7-|B9XhHMqeY@-QPMXcNS!!ayD7@F*T+i8_k#5F)6f zgzl3e0CtBNC{nSCS?X8?W&{8lm||22>|qh52gaUdqyv;tojZ78n~QN!bYe6j`es58 zECsU0RV|(xFQ63{39Tf)G=v<5C!KThdo00#WylCjAR^R2PRRB3Gt#158415 ziTFsO95HaTcnB@5fk!K1U?kz$$ONSDgg~+qhFbqhhZX=Jifs_U58d!w0ypVMUDm9P zbMj3ACQ-LvP$5l1%;Xr`2FKdT#0>VZ#wu1}4SUEeaVDhV?ij(sVO*k>-qfF#>Olhl zEMpY_h`}8fxyxQ^lASvY02M0e4q;5900F2C7T|=;M!J)eahwSll+lfBB;!Y;v|NUrJY*&YbKo+W%H-!qn*{+X@M1#6n8XAOVuc4`aD43y zDOvsrMfmNH0J=Da6Hp0^VZ3mnJ{_Bu{E&}+YzhFWc%D<#2AT*m#eBGOYMh`Nr%DtH zVwAue06Y*hD_GB$t^=t}I=PYq_(2t_=!5_LtocML?s1A5xy3M$_0zeotW+)tLw5i$ zhQp|nm;GGlQl%P`9N=O??6^cr4HB$j>C>eiJ>4>Cq62TxLmS$lhc^uBE}HJo3nMYY zMkc{cx{@|!oJ}eY{R-2+vi37S#7aAEQ38xG><%QL-b(}P)$=hkCeVn+`cx1N5~>xD z0@&Rt8Y;QcGM8VZX@*6XC*5Xr6s)?&@ z8`+ttqnZXWLlcV&NFIzt4;!IE4j%t}-w|Kwv`bNHb_1N^)_Mh=@+2ml#=@{e+*ZQY zCGc)Ha^8<9gBxQIfB?q8jsI#GkjN!5lJ{j|IOdYY0=}`0CzFG!(o@7>F#sOIyJ9Ef z_{1`W2@0O!4}9RGAI_Lok^d+O`uQ=*ZpLp#EGy?ZTNc2oeX@$9>=f={g&kMD2v{71 z2Lo(*wRnzcZ)Ku`Hnc&rY0hKgj$s3hB!CK+NWhyjO&`)ka}}?M2R5X3jd;Am&Rp(t zgdyyd0U+3Jv&BePq;gDDLs`{7+41m}tUpT}BMurNz)pLr>0y6HOSWJ|V~C8}CL8+D zr?xdwa!^vD~&K{OYv~D4&2k% zXG5Fb+FJ^rAvOt2Zv-lW#^kmG-fcuj%Wwuq+-9$tM+`X0!x<56H`y)muxQB~>rzN3 z&S7e958U34{YgA0go{^mq$$R%3di-F@|fUSc)Hf#?vR}khfZ$dHt%1@Qeh8TY+@6% zphseso$7k8{N6h$!7U~vjB1x$D6}~Q7Vcc=snew89?`)X91_t-mz$3=D5Jede)F-@ zq*Q;nhC0-7jXz8V#T_rY(evCAcuuk%m%yq=lHwo;N&W3qf7Z8MqJnAoqaTw_Ml8tv z$5I|65E{WB*&{!bm&gB<*#h_b---T`5)?L#t8D7Y<*s?m13u9&IZ_PdG3hnjlIwrm z-7Dg&5U;6Q^0vR7!f$B#%#WV*yGi46=Y%JVA-uKy=-X-RMi|PSj1NOQ; zk7bCL!!J^T`rf|#AffzC+^+KE?{oPd@j&N!A#A1~f~B?oeOJBQ{Fcb$N6{BUh7-Ql zKQh2c$@M+}&QR`khWNo>{0&{)y#y6JOgm5l@kK=<%$oTfpy=^_V+yc{;APKe$ka0!{u%N!+KOs5fTq09D^ma*+WE5&Cy{AYKbY(!z(Zv zEYO1~Y~1CIUn`2CM|42axx+4q-Amllu*?A@M&d5^MlT|TBr3#tjX^kU!zE$_IIO}D zvf&^3z)0)?M%2qNJfJ9gpO%CJA1VYVgaa$`9xVPL1Yt}LR8Rx9PD}*BgOETl0^={T zV<6_>{3-v$2Ydq>5Q;{aLN@qAHk85|GGiVc*D;{N2pWU{1Y0#eVaMD9yxl`L`knz= z;VUWx6{wCdfDcV*)gf2`Q>ny8e#JUUko zMx10yuA~h)CLn1|D`cNR6u{P9rtM`S;DM$qdShIY9u*9Y`rQOl@rD!dB%%@*e+mU3c^mQ3YTf&c_G>0tMO4e2NX`^aF^7Xg`d@ zDhy=hbtfP`P-evOM+p!^JiPw{ z(HLcidW@EE0y(e(qp<=xh(apB15Tc(imvErrl>-cKn1Y_O~wRL-sOTaXl&Z(m3pTY zF=zaYz(};fWGjr!!Re#8Y@PNfo$xgoz z^@j)a!ehiIvo>pKv;jVBgDu#?Hr&Gsk;1q!*|mPvnT8Jl41k1W1vT14qk?O;4k~H- zQ#`W79p>R4N+`Q}6R*93af;S0_(x&B{F_8_f}p({v~;wiR4Dz2h%vXT?fCHqi>aH&9wyx{GF6^?d2D}04#;)z&F7B%C?AC7X_O9=yt_ILS zv3Tk4{w@>{C>S1X!Yb_YcF^B?ghD=q4lv}@veL&w{q?H13 zUEM#t2paqYngPH#NbN(whX@pbk0=2B*025EFaGAQ{_d~+g1{Rz0RRWE01q$$7q9^z zZ~^}>0xvKFH}C)}umeZ11PAaG00YE4!URw76l~Q6>@Nqr0SEA}2#+uc+wTX5a0#cd z3Y#zpudoZ3@Cm~$b_6%zq)rkp)y50@5X3}Ht_#p^o0ROc?1DKgD3&O zCg8(EWCOG|Mqqlv8&t6sUojSEu@-MJ7k9B2e=!(`u^5jr8JDpck8vXe1H@Fq8Hcg) z9ReQAK^xC89oMlP-!UHN@fLeR4ReGaq~%(+r49!Y1Kbo6T*L&dUw-^B5Kpc_)Pqk% zpAArNN7RBi)J_vWaTF^A{K~Hm$S^4DuL!)s67Ya2pE4?^vMR4KE4OkgBf%RWfh*54 zE!Q$C!?G;fvM%p34@^M?6$2dbvM{gI9YjGBXn+T|a40V`3!^YIGjj|-^D;-XG~X`` zU+hX~CTDu)AP3SWYLi0bz%T#<_s+*-WJe<(6gZ#(07U;EC$t_%&;mJ3nn9%R`nK=+ zm~L3iE)w8?KmRj82ed#BG(i`1K=Z&G@PI)tG($HuKqIt5JG4Yk^b{m&BSiE>PjnP) zl@BO^188Ttn(M^+EX(yVMe%4WC6q4g!3i9vLGs6Aj8i%nSt@kH7|4SeY(hGe0!Ih{ zEtG?!c`oPzfasELM!2n4@N-5lwM0WSQ$O`WJ2g~KH4aqtJWWADQ?)_wKy75f4s`TK zBk10Wbl)aSNKT%8iU59gGa$JkD)cZem`r~>1~$($m1v0oq{2M-gFo1V%xy$1z{43N ziVHACEsTTOUIW|aGkqwvRzJ2>KQ>iIwq#4RRSW;a6i{|$`!g{|0Si)ds)f$8x25EjAz+)VcT@&FoL4X#FL2zzFVE)6!*{nLyLo@Va z={9yOZ}wDcHgiw3b3gY$TlFtY0S-j>V{ddu`ZH*Ybx6CWXvZz{(FBt^X&XSPlv3&Y zpmZzsz(^Fr*I5Oe>IVlr#&75L<*>KV&4*)4cSd8ke;YJ_2RL;QLr zbZD2gSvRk)ns!F$=|l7>0Q~8CcdSH#OhAsMG^Uh(sK8@&#u!j}m6uqG8|;c}xtD)AMkjhf+jwOsK}liuL6RO1i$(#zzQq?5bT}XSID43u=WQG{6psqx|IirAA&}IGde*#x|id+ zRv$r06@!73`Jz8Ij_de8tGV+2rFge$>D7eFvaCKYiIOk*xlxJs?j)=e`jzV^XVki_ z3$(7o__ss#5fn?r40O0J^b@EF6bS#cvD>PIW9z%O?WgZ(wtrLO7(;!P02TcCXQXfW zUc0Om`l@Dmw>LVa7yN+-yL9hBVU@eNA3Re7L6%_wg9miGlPjBRshi{Iyi=~_Vy@=u zcD;X7$fUswP{&N_2P^zTl>)qfL^~NiyHjvG!u#{N`}fUH^bRB)JHUa#D?C&;7#{q< zKwrFpjx~69x;svoOnh(nj_<#V{D_&GD-42%m1TaA!#~)9%eS_`dz;KJ1}l6S z``26PZ;U;{pZ#V-{z6ZJn<)SKWB2hu-yyg${s4!K7_vffJ{C7=3zee58- zzy!RsIgf7Q-}T~$->iRz;}^W-OLp!PG#m`gEiiQM3(L@JzT6)>3%)JTT42W;#5$M$ zJNJDnQT-r5W6IA51U$yh#{Pc5{F{gUQQUsF@4i-xe?Z47E>!&51AW_11>6(#=Cfw! zYx?Im;#tc?P2Y4*?=kRB<+d`ZMh(a*nrgApfIyqIxCx{VQ@ObHnwOP5VC|74n(^UckjX&&L_ z?pG4cIzi*WatIHQsa3CLrJRuLY=gCJ;}&~%D+DcLKG-h#Sa@-$SLy4gDq-u4c?%DP!<8Q3LB=76R zv-?lLiX7187*bNOu9<&K8PLH8A+#t!$hIr4JMmIu55uN31nm-c*nxwn4tys?KIT2L@(jA`J3N187X(m@`04)VjBd$?g^ zq6s6cQZGiXOXr^!tL)NC0jXrHLg6mlkTVj^>qWeWO0on(m6Vi|KqlFP`n6if_<_X!d!Q&V-(MVHjV~Kz2q0THc zc2>`ktF@LomCNG0B9>}dZs z;zJaXHSb!{>mX$O_LUG$1aOeyL&5mLkAL`s9|r&c2(B>=!WG05=U^28AV3ez!6SwI z=tsdk0RW;IE)XacRvTCaF9}%Lof)K$0q*( zPy{`uLLOTPlDrIZ4SUU{epOUV4~}6BLJT4m!=MCZpz)7xSdx?oyW(B4xR@<|5eE+h zmMdXm6pYo4f^g%>YVh!bH8QV_bX<%a=lDSw`I1J~`%lce#|<60fSE2N!aZtH1T827 z9xgyg`^=yZQxIVlq%vYD6(aym9OD#&Km{;92^oF-qZHtDC#p_qmsBcdm0yHqn(oUEe}7MUW3rVF&`hF}Q?H^FJA{*(!w?1ZPE z(g$zC9Hv`;iPV(Ib!Eo9YC*Dk*NTkO2?Y^A2^yn~e^gGdg`G`av4s-uw1ky5`6`B7 zX)$-)LOf?vR`NPC(A&^8E(_&|XEg#^04UX+h&Aj&NNR}}1R@v1=)htGFsswfb}^<^ z$yNu`)!vzvl@HWs+bYZ3mw3#loY8DSM4OT1Vr01%5iM!KX3o*8_GU9K+CnVXm6bDn|(!yUlRY?^{&$O?l>Va zh(Y**Ac~R4Ka}BJ1;@p|CJ`^0$Xi~V2)CvbmI)l%@g}ee_jq>DC1{QdfaW?^zi%vY zNuJB!t2TJLsTIT^XyJ<+4n_wMfx&`tycHIA1h;t6E!xi8UJJ+aVwBx*dSP^xJlhc*;~0Aw1R;p=gv4Y`9yvBMNU}Vr2k$Dv5>6YE8|%9r z>;kw)wh0=g;++tWxFUR}h@Tsh;&bUW&8O9i95z{tNg##*5Fy2xAdl@a>nKcV`wtTu~^tvcz#rlJ3&*A+xB5W@zDpfA$B zzKE>rIvEIG2GcJIa#`UllPM63620n>vX~{FJ-d1%fDSaZm5c2wlM>i>#egx65r#sb z;%b92$3Lv$YjryYyp8GcU4C4)WA`)JFk#y+Jn_HmsZ4 z?YrtF4k1tsL`t=8i7!Oq6nVE@;_X09%iF>qO3y33_}(<;o5^hDV0{a2@RZv{(1xwJ zRgt5KDc*$?|KP^Nah{NuH{{}S$vDL3Jst{EA;V;Kwil0=%MDF?9Jkf%|SOKZ^i1430D4BXuVUK?B033-*@== zE&hH(pYYL>y#WUD!F5sb#In2sB0Y0`*_Y2S+2fA(61IIUZSwZXZu(c3RbJgS@A=Ok z-^A>fvildp_bS3(q)}r883s{^Oq7KJ5K-Lqu`i^=Wcw1R`^xM4h{voXkMcB5D4-w_ ziVOWru9x61nD9Le`3gKKT1;Ob63`7Y6uiR8ZrT(GyPA~w4WAVhI@j&hIb}PNa zFYY*w2SklEKCD-A5Chfk&%W^5Dlqnv?+3Gw?CdWD3V{$B;VZJHAFOW))eQ(oivYFA z0OM@qXmBPL5b}6HSpo`Tx{wETun^-y{-}r!OUVaJM+3;f0>lC$I6)4X(01%lmGH2) z^pN*vg6MRw!g{LT1Tp=_Fx7VOc}kI?e6Xbyk(30$K#ZZUzM>RFi4rSOJ1&u)GSQwk zQSM^m2!3JwYHALkf^N!Y5K-|IJxHEbQKbJ`(UM4t%Pau^DnJeXVCFP}1xnBsC5{fA z@GGG3rh3uwWWwXvt9KAV3(*D{mr?lKu?NeL70(dskb}#Pp$`f{zzB;Y4!|A|j2pXg z98wrxD4AKt~(%3kr)6NlXfS^wBKnhE30)r|ib&@Lut|GPSB1@|$C2j=3jm!8# zz=|d#1fU!KL0pisBn5CWzHuwU(a!&#ax)~WjJT-7)Br0}qbA=<86}b{?T8e(K_27* z8>D3Z$Wr3;g3F9Szy?7OQZFNF?jOV;F6FWbmom4Satfa^(}V(eenG7kNXf==m$cH! z2(vK3ayM474cI^jhG0|#C=nlX-FCnpk3oL~Obs$Z8~CcrxC|L6^CK}LI{Es(Zqmv+VFEj$j61v25X1623*rC(0UvS`iJq~P>XFNUvk-*f3j&EE zAnG3$^gSUhITx!w5AZ(qjR*hQM5p=^d78yPUjjf^O+eQ#HWRA|mPQ0j5Fxl=9{2$s z8go36QV2ORJyBr|DB=SkVjnehL*sKR>QW`{GDJr+C#GN>7&0{v;UP(rCQ0!%ZPG=N zG@|}t6%qmhbU+MVAssTbfR0q%e)1SL>B~^z6edCiROn@jwAVOvygW1y0aN2l6E)Fh zCZRGORaSwY(X6GAswc{ zTfa3f4dgt1^bZmO5Fp|i))iPCHEiA$-s1HNpYjMUhA;c{V?@zej}cl4FmM)$XW6x459nesE@Sr)(-txlik2v{Q0c&EY&D2vSruus(>r-m zYfrFN)l|R;p-un&3L?VcX0cYmbT%b<79r1r7v=zMe*)U@wTlSXZuS-6`t@j)_HhgJ zZQpat>`_ut0TqV81?s`@_V&#Bb~*nR)1p)NK$Rz;0AwAjbmc>B+mUSp)NM7eX?@K+ zGbtbI78OhZAF8i&v(__*^$v@b7ZbNLc3?Dc!8&a)Ci68_7kBfZ1xwp@X{`=!Pml?G zlTt4i70>}9)`fSClzLCHLqk`>q>?4k%4~N>bzh@-C(?0Cc5Nd!cEJ|_7dAPvcYE`J z2)ws~gRD~6Ieccy+-?w$+mucr00OfWW$RT^%sfTmybLn$@S?Oop z=KF+Jd5KnEn;43pm{22Fa*MROkl{SDmlQHei*byLiPej_=t-m0_R4k(mDr3O*mYqT za%EG3x$TD`O#r6BADAJNPGJ)whmN-xk%LWq^KylM0(f|VmTb>(*8`JlqJ@j9f!peV z9n6sXj*@eX0=xktrh&`iK$1Opio-I9nR1Bbm6aB927~T`LRL*cnI=S8~ zR0*KDj#c?@xYp;qmJ`3o6Q@&TQ^QoVfYd&DiCLI+!#RzUHj1bBIKu#RkmLZMb{gB6 zZ{OMC;yLZ+*%!I!JaFM`#iMKy*qfh~fs5Ig1)0ahQe~xi;{E_4;6VipLT+22p}otF zfftXO`O4k?$*u*9XO3#R{9rYFXt%?nh0 z8T@v-ludb%1sY|8+7`v&hyFo-6QWjiA*z&mwwPLkof=qZ+NN(BGrGAYI~tq^I;;O7 zn4o32q$5oLQ~{wEB3xm)tj+qN_luh0)tbK+ZRqTxqZ)06mQUe&WIg(-LAs}JYosR_ zug?qx-0~mJL8Tdjb~Rzf0K1?&!VI9H9R7h1sFoGX!5*fed(SSS8E>M=QFmy%UYD0M z&exB1I<9$|uIt)~fm(hku@C$KB9cLG4I&AAQx->?v^jzeSfLM6+aOK>9^T*!o&g+Y zDE?&o328eD7bvk)cWe)s-T>LEL)wMcTg}QjVF8d8K!=AH;uYOPEJ=&#x+Nr(Tt^L}u9ojv?vJZL0Pb&t*0V42$zAwTo?J<^Bebv1k080GCQ`~S2 zVtz!x%5`AV?cK}8oXiD%-}M~O`Q6X!d+-viw$qu}2M9nKLx&n}p z(j{KvA->}8{o*lR%R7Cm*Np&XeHq--BgC46)19Q3+^_x{uLPXuz8f6F`#H-7s{fcM zj^_>z7rm=`$9X)seY&ze-Avd0ssun9AYvZMlp}i69-aH-yWJx`01VLC6u=;IuDcDm zz!|vP#w4EO1JK{n? zM^*)ZweMjXhG4K++y#UAC4gramO|4Wkj90~#zPsP=eq49-|a8l*TTRb(XA{VbnEW^ z>HBx^SF-RIlI+XAL{8)eWq#)=@S`alxQi+1?FZCpg#w%bbZj6lcvKoYKb41Gq`O|8 zzrMD6tHI&b%iFEBt8#woPBU;2F)^qbT10RqP*cf5As zIEXM|LLP5;D15jB%ON{a9$LJJ5g|i|89RDR=tGGE03`oQmQ?UYfytFDTe^G+697t; zF>BhiIrFB@ohEbg)EVPnjGsh#rusJvfC^gP?2)5|qU4xq@Zd@NLh{TrbM&@tGU>Cb?6^H*EB3geQ@uy%%sJ%p6dl9lX;dd3b zWm|nFeeew$)g-l&ANU{ufEYrN#Kk{4umnvqBrO9?N!ZlV9aK=N^6a-Pd4~I55~`55i<78I%Yac!(8F?nmI389k_4N;h7J8=0?}saA$K zCL;>~AF?D$IwXOR&MFX8FiSTiu4GLtB#~oENvmvAqhUtk2!l6q)dPZiNE~wv4u?)k zX{ChOINv{tE$Nt-{aLBtB<>V*M3r4W1jQYPT;b_tr?#pPn6rtgA)2h&dKj)hsi`3# z+)&^qh$XEs4l5;X0Zu>tctZnAf8e79N%{W(QW7cWuoQs^+6HB)rR)iCR9w(R0G}nt zXd-~O>aNRfq3|gQACs_-2C9BL@Z!!Tq`itz6m}efg+cQ!#P7hevZU)^2@AF`U=82I z>$~S*6|6}jU=s~Z6=0Lh7-KBMO$8>QK@TS-O8&?- z{b0|7 z7qokokB(8jrXk(V(o81=L>7nOQ4#r1mfq^=C#4SG>ul+-7XK#2uAw(wj2k*|fdSP< zgnQJY2wG4EJX`<(lD)!!E>J;r^kE7jtYSOv>fTx+unh7L!AMFthA|}N!4#@cE#Lc2 z_}Vi*`8~vZqq&7UaABI#v~MEulOGMYWIvMluP8$#N)dT-L;%+3O=oCXTsE}^YrsPt z(-;FulHtT^lq4+pAd6Wdx5EFMSVvrxGM6QQ7sfQIu_Z0U%?sHRLm5(SOH*KnJE)Mu zE=6P_36kLtofJfw;O{+0MB*SNbV$A^ag8o%BO^=lfohP46lgS33yhJoM`|*Sj(p7< z!4pS09^{XZ8Aw6$=#V{zMwIibn!!W@p+r(hmf$I*PLg<{O@8rZx&(k9$is~lcuR5W z>7_BD*GblV@;jjvB`H19gJMt#l{olJBKj!DXDTR=w!9@RE%Z&<;PN)dWJxmBSPJrV zVqMq+QaRtrvvVG1nYd|YHtAOxQIRS?8^My6SlLSQaWkCaB8 zjYhG{2axi?LNDsAh6?|Np0cs0AMq&}eCdmyZ}2BTM+s6O!ZJ)WQ5`}P`cj3(lqZWc zrbfBv0&Xno13Y8Ixfp=apdRX`fZ^zCJnF-gegtVs(+>|8k%(2D6s4}5*FamEznL;j zs}AET#BzyIqB>3hrXbHL28V&X#6hTR9gb=41G zYem??rj~W9eMwDwY1wui;1%St#hw}`05evSvb>c|Y~2#q#msedrG1DgL8~f6RMnYE zZPIC7id90k)^-2Wg&kNg`df7gpc{)C;r3dPm%a3MysybFTY`I-;aaY^2|0o^HDj94 zVqp%;y=Q$r_1vsR*FD|DNp)HBT3wo#QUdq`c~~*G?x9B)BOtGXy$43{VK!c!+AL@D zBPwACXf#mx7Z!lf+^MnmG%KCeei3=%S*94AE5^`u7dqfWnL!_MaghoM@FPn+c*lQ< zaZ%7a81;%c#1|21eE$`-5qn9=lF6@hTU@69_D{wgoRe&%_XS@|p(ZsZJ4w!vaWa3YOhi2Y#IRwF@Z;7%o^A+Jjl^W!m=FDv zGSl?T;!FQ?UzKb_99HJdQKPDb>HHBpqd2foK4_=YWaW1%x;|x%i{2RNfb1c9)jJtA zP#6tEN0XMw3ONF1;4o=bRoc>OrnPBHj4(a#S=fgBG)#?6lmKti)$b{SJ)A+8MG1`yFS8AlYZ&J;z($tuk)9i-sMnhdrX3xi%=F&uhuZ?eu z`Pq%y1|_!vI$|S7X50$Fw1N!oAYfyS*gNU3e~~Ryh%cI)*xh%&!IRcwto7m-mp5Yi z&CGwZlD$lAvq$8+;W_pi-GEd$>Lk8Zm0YtgC)Ms(ATg+_?KLMKbdz`>Vu`aYONl0cpnq!K8J|_a@=)mbKSKducyeF%kqa@ z#vQo!$PTb{g>b9<(M&gurd8Z-{l1&xFt&KuS@Y#%FyZfr9=l6~9vGqzthnEnyG1;6 zAS*b&+?TF9iPar!tb2{&-qgHXY~FXA6aF=d(*)*6?_k4QcT*JBEZx(dkRAMDni<(+ zmOA2elEQwQP!}TSZ$k5$|GqWCR<RmOfLkqX%$59#0x-lazNmwdWKf4#+lBoTdo zF?|LIerwlu7ZC+dV+YvueU(>$c9(#`2OAAogAr&%#iw=A&v!4c5R&W;p+P6m<+1 zm54W&ZTQz{`qynlHW0gD5!-hlao0I9_=X1<8RW-eoVaOz=tQgF615->6PQA(IC?&% z35fHGqPB>G!G?U{hD#P=(L{UwB7okvK6m(6S?Gmd=!xfOjG?G4q_`5aKn^zWNX|%j z87E%T7;n}1Zn79_v!ND77J!*7%5;ESyYX9RBzw~T|km0X_6<2k}0W@D|wP$Ad)P3lA3c1C+P-Jl?6RS zP2y-d30Y7J*?H*rkq}u6@NfncBr=1@k%NI_8kdx?<&l4JjdigCZvg)aRcV!1iIrKY zm0QV`T1k~%d6lKm4(?zIRv8M2a3F}#1qWA<4RVkc!IPdwjCl8uFX2T0uue$Xl<;Rl zJ-3&s_>^!3lB@v(Z}16`fS8G?n2X7njp>+=$(U~dnTweV?f?vlxd=~l2#630YxyZ{ z$(Fu2e&jfpbjgQ7DOB<}dbx#&e`%3~=t+aQ7=3Z6-jqPZn+`4Dk=D-G$8rwNr>XH$Xcnl;e_k+q$AnIy7#7_=Fj zAX`OfWiP-6s07{@daY@I31R>gt+Id;} z$Q}vGpeNriRAy6u% zZ`z>d=?m^442fW)x{0IBd7)mKp?&D5omiLusitjFdO$U(gTtov;ihmZrBte$nQ2FO zkfnIKr8&B%R@0{&I;4Lpm=KwrMtZ0(v3zjOwC}ikpZKRoCa6d0L-c zim5)TfMF`8oLUaP2zi7bVyJ$bE{<*6UKuRHN|OnI^V zilTK9m2UB`0Q;i0Ik5i%HCZ~G#mTN*`mPvCt<;%$5j&k7TCu&lu{r@+x?rm}TUi|o zTn8!`AuF=J`35C>Ab4=6bkGRxxvvm`W-?$wzyfg zM~k+%84Sd^wocoywWy@cal z$+qDLwY3VjkjuJqyQ?+3Y<&Bxilbwh+q1rEjDCw7fIGCHi?nmlo4w!;&YHOG+P2ba zRgXKjkvoi6Ter5m5+jO2(AyrH`?sCzxx4ARcbcqpAWfNIo~LUnjq8>?`gBrTwN}f# zE(W{DC%eCDF4{xA>|wpTi@n)u{dpi-`^kuMj)2rrEj_o0{)is@-V} z`Z~Y9rNBQ1w1L69aH_w#nXJM~yv5710_?J@ySxW1xz0Q3gf4!a;nUx{Jj33$QZW#JicYP<+Fv>%mbA!mdll zBTTm?EXDv(dPFvYDi8 zo>Xe3q^qD&{1H&IIVT z$&0?~jK#=&Uc4H+&b+a-3(tPs#f$dI)-1Nz44>N!rvi%^!aU5Dy2|y_$~_Frul&QZ z+{YsTDGt2QYa!3$NzcA%&lJt5Flwd6z@Yt%d*=JJa(vDNEwMaI$?QDM=JL)b%|Z>m z6Cc|aFuVxp>e8wTqjRdV;r#!`s+_|BJ;xsH$^+f0K5ff*E7We0(g?cJxtY`lVzBre zr4HH%W4W&U9M$FAkL2qSUz#g0yKqx`gOl5S2)(f*fJyV$)kCe<1^v+T9MQcw)&+a8 zW9y)m2@EYt(=WKu_|?%MebqaC$9cWb=90pHooGb;YJ;uPh5e|SX|Re6unsCsPYuUmtp*4# z;}1@*zKAOVJch5p7dZ6<1LbUtkUQKn`cMMPlJa z9hBJ`i{we(#Sp*`d{7d}@C;E7A1ol=YQX4?-sr&%>5(q!lRoKmaNIbq+~aKFQtjN3 z%+o;*)d@B0q#^?vXC4)FZG1Wlj; z)6M~JzyZ{*@C(oI&VKL--|!JH@eYsh6L0Yi|L_;z@HK$uufZW6A}m`pA|;YbDY7D@ zpbii~60hJ5FA^gpF(Z5q&kk_iz%KK3G3+H_>?`9$p6~`g5A;DV^g~bdMQ`*$p9P74 z?cvV!P4EBo+`bN#aP(78^;K{6SC92suk~Bc^FZ!Rq0vcfYr;qxnullDi0&gG!s}K9J zFZ;8P`mO)^w2%9^e*x5<@r>{L6c6#g|NFf!{ESch#qaDKU*Ch_E5Pz5CP6I5LK4WL zEX+a@(qIcEp#}d?1OR|CBw;Nq!7?qg-#3dMwG8;?)X+=bw6GIZuPZAfCF(d&H6|f~6GiDjL3IL?p0?<&)zajwg0cr?<)VYckBZ%M_W5lqprNWZBZ?%a<*V8FK*B=1rVAb?)TZQ>2KGJ{$hI$Ek=dcq~eKtReKJ zf;S4BK8-rnB~+^gTPo^wcfTm+kDsSf8c{AjxrN-gIHpV1V&kfOX zUcI?B<=3#QrUnpuvTe4wZ>ptjcgycB*_3SoAOc%84jD_C6VMRByiFF>WqswX;WGbd z6|dEL9JKd$@VyxwV-()}dGr}UcSfCBx7qh&<9D4;f42Mkp6grP&yu(KYGx@88*X%P z;lR3xxTlsPv`_{f7XU!P9A&ilgC0>DGD9Czh*%{b;!0XCJrYao$%$ih@xckrOmy+Z zu14IfJ^k|QtiP#n6iUY(ZDh?y*MO8QE2sVoFF*j!_-9Fk-DObQVcRzNAPK>PySuee z+*;hBcyWR|#a%*yB)Al}Qi^MEDO#ks6}RG2prsUApinmVbHDrU&g{&)Gs)K^pECdJ zI*;@Capq$}3Ej5!oM^w$-hIjo9hc-_d(l0BpcB(cCsBDeL0%O_Ss)1Sme_Tk){@w> zchMSm?$$#O9QPV4WN(LlwY}gt^{tT4zH<_gtSAxIQW$f0pqRl)9-%|2h^SNd5>J7^p*LXKbQEmF) zx-D1vy*n2xdwtYO#mTj{a6qlTS9xLufahWu`Gu?TZ&la z%hCzLa9kWUw?ad^REpuCk;sCxj0GRU=eOG#7#^m&akxpVx=M=wTFk|8i&%Kp{omJJNc$76-gdui}A6ZNaq?XoexuXD~W7wD5FnZqv@tPX6X61 ziuw7=g!;8_jf3AQaUa8PJq)lqe=+iWZyC4x`y&&Js@tPY-2bEF``ab+WlG1zQfns4 z>~4vI)2mRgLHtJwuTPR+Ex3byjl+D5ah-o%y;ENfy(&zE2fNyT$TIsiBmH^9V#N|~ z({ah@wTSh?dhJ9YDs*PdzkH_G^57u1UDmgWgm^7zcW;B`CZz`P@p3FRP%1EBAn?_F z%-B=w+atFhE`L(1mV31bP$`OWf5?ukp3(jjVgvpA`{ywd0MdnFU0D;#=wV@U>PF%7 zZ)4Eh$btXOz`%)6AeDqXzN26i^#T+JV^p3PE(l^Ke-BbO`SdSohe-rLhetF_LOr4j z7cR9S^axUJr&^NEGC|`2{w}YGBwW79z)6MnHeoY(I^^i3DdX2YxWf4!|%(Je=Aj{ zP8T5crSR!vJeT=5n(1KIv!c+6iqYBNsmO@(cRH(FFR*xLqiKDMf7EKp+qKMINf`2x zULWnVqT<1`hb1(N+$y2XbICp;qRfORsLrC3mU0?ZX*#$X6y6zDsu)!pl(`z!g&5U3W^#$5lqJqE zl8xkwpOr#B%W8bdHMCb`Jn;gNguIQ91S4g~brG^1EbwW17=;xO!MnvyBP{oU{&8DT z8M`0Pcg2oYN>CGuW4^N1{f6#}8}SU~u)3N4MMr0ATN9c|=j zJ8NrreRu9+fDha0qHF_D4~lGK5W9p$b()0Kd;S?W|CY7X#X=${BC-ylmHWVW0vqP0 z^8u~z8b6yq_wbL-Py5~b2Y&)x*U+UGpSb;}t#fgOHoXx<*Rn(3SUkyev4bnXtjv=i zr^3~80d!8>!>XcDlxSmFo+_53$8H>;tvAm#ER7}o;CK&&eYLxd!;G_H>j zxKpZK5TQ3ngy;)|ZkCNwnH%_Gi8+`5%gPAg_%eG?#u1QlJL$q$#53NA%MkXS@YRP@ zG_{mMkjpV+e%PEnz<)@Bvo`5$EDU&FoNSK{%1sC&43%b&RaMRApDhVz3p^ZYi4T!` z!p|@|SO^7CEDQ~>=7JMU>#H1Ay2LL$w=f)90v9#mjDg%gc>VN6$^)|8pD1}=DaG<xw=}l{w&h-8r#J_$!$&Y@Ovbn0kEY&7Y?C zOmv*eGDEIEPwhAOpQd!q($u?tU}I=vc|R;di|G%5S~%4PHQ6)wr_^!n(X`AByigd* zwI9U<9Byfe+czfqIY%F6sK-jc0kEe9Y*P8b4TS$N;PJEJ{I{Oy{m3-knu{F37dcda z{-@a>J?Y$1IrhAncrI!)ZlhF4Ct;# zhzW!Hof61xgL-sj#yb$9L9v1mVCZ(tG&Ahg1y1+{&g*FL(UKByXY${{_PQD{-Yh&Y zpMX&l=;BN?@sXEcL5|2U$=d`(4ucuo;J8$R^>fgj!tjN7mAb=9Qnm|3wH&eu{t8Rp7+Nmo1g2GaTe?iG9H@ zPdJC;Dm(<28*&Mb+UCcHHl#z@c80b%zXkm zW*oU~OdVYueD-eQdjy2wBZ){tm;uab7Bre5GfIl(+rbYAlCP;AHlG}}B#-t8N^pjO zs@_5v1fy*i5h24VTu~@jxE;bn81fQHeMHax;=cU*bVpUuTOmj^n!cnMvVtOHONWmIL7hr zs4fp1uXG2Kn_vJ&#nJ!-@hk8MSVBZlf{|R`;(A{r_XHd^o~Sm_y3m&Br3tu*X_rJ0 z03U z-@wpBJyh$nlI9FHV3vM7l3H6x2FG|5yl5|*8W;821TLDNIJz&!UP^#b9P1O*I0eAi z1}E=q6F8{J0aAe``vm^8lR@_&;zxII@GpK6RC~mFSM5Hi^-N<_KkASl@oMEsb=P#f z8t|L|m!VQM4G9Yw6<`1meG7Bz+o@ba$dSlfd5X`#Yjs6bTRI z)S!~cK_anA0N%+jo zBp3?_BLgOr12w{Aa7@5))Qi+#3*giesn+%h8`ANm+lgi{gs|Ye(iK5XMxxLx!f-Z9 zyBIOBo;aV^_9bEx>-V6s_CqP)=UneFjj zBh}yLX>atcumCThZQ_p*gd?ok5Q0U!t>V9eisx1UAcaksG4%mrZ5IY|9!UAtCwD1*Vp-Eo%O5)~9JdBj*efrOF(qq?Gc^)R|J*M%6OLYki zxADNg)pfvpQ+U}*`tYi4Y^@Qhq_MlnytB}}tIqsmk9qf$dC#VK@40#3gE_jGbb!I)lYqsbti_PF#jvHtNFC3eo5g67 z#hB>E$S9bqxN2<5Vrp}vyUt?z!D5!svXT{Mcv0y%oD{cUikBRk!;Ldn}FRx?ZfS5?=tRYgvtD}9SR_DGBir))W2}TC5YzL1b zF#X`s9?{}o;9c%W@lnJ!HVliX?-Sk%uTbLU6}JCHOJpSuQ7=wnKa^q1hEau>LJErk zY|CJR57F5qd13>Q*de#Fxh&IAJI4;XsEd>nVL6;*?6u{e-VG4IOS}0BV1#-?;taui z@y@%+g`3010z| zAtF(ml+U|`K`<3hq&7;xzY_ku!`@=r!ICk~kQrh5&jCtwSj8MGgu>8)AvVYz9jqK3 zt#D1b5urCAqo6g%dPg@;Bn8Ztws6`SW;nb$5O9@7M9w&7a@De_#E+LgVcJW!dk4enYeDr`JEO zE`Fjl_Opv0KTpv_`}*nW>BHgt@wYQH$bN8eaJ2V7Cj0p{nq`03-ah|&a~`j54*$J^UGTVKC^T{&M~JX=^fU0yz2S~&f(aI~?o z_hWu<@yqVn%*piR(ZtNo`oL~Kns?vW*g(VXYin!&1>Cn*TL;%S7XKr$|A%6qo1NMC zyoMIohbQMoM@NSShtT|be{X+F@9;#&bVpZrZ+m5HYirZ|d~?rWQ|CZaa|_yGub-Q! zZyl&_=_#72D(n~!?Sosin$6UV|KBXT%wq-Urb>IJ=JkIx_PV2^PF|4id|ztvU#iHrQ^=DcNP{wl9}!1pBQxPJOTjE>F605 z7|>ihH8nLQB_$ad83_pqT4pCCB>WG{j*pLviwg#Wad2=zAP^7;#K!)Q%KpDhc8vco z%Wi=>Q2qa9*>CM8{vVbdOGxQ>>ta0}w}_N0(*D?n zjFhbTwl(#?S@sQQC`l{EBUXC%Yb;U1ykFsrmR-i*mYQv6tbC;d^S1gvKN38(VhKKt zV#>CDcQ5Ai`(kh6f3fU1U7wk9g8%)x!k}jMyTxEG4#Qzp+m6KF&1UvEq2PWW@z^cC z6HD#*AC{f6<7@Z>#SL>PTl&g&I7e1?Nj%qD`)=S<-U=(kuW+@!B#Fbyy<~yP`;Yq}|Cka-RG^{uEZ0m}PE^JT6HT`{oR{7(e0wV73Sj zm*xBq%O0?HLRkdo{Z?7@hSwDzvzE%)qh@}ox+Z+>k)|f@WeLJufd^H5O8pr2lUpI} zAMY7zh|qvn@}+1@9?zhq_*?DQr7rfjyVHMo?T>gx zDiuayZ>t;8!q$)OtEG>X-KW7-{p38ePI9;=2Y+7ocj)L<1fASvqI|dEn%@U^fnvit zCtf+huxK?~nB@xQBrpI!~-wEB>p8vc}D)H3)nr=0Ea zdo?W0qb3rdG-Rzb2>4M>&?DxP^#z$=I7p{qQ+-osZooI}emaxtr zy;c`sn#f!E_FtXdm$UhFU4DhuemuBi8{@r8MMP|3UnP2YjB{sxh`T)Sn zGV_4s5V=9D_vk{QbZfUMsjXkY64&;gup3*h(N=>gu@aq|dg<)G$d0{)c5RCg9*A zOHIAN-S zvA{eX)oMTmebVP_^dVjfR62T~=$iq?6671+eUr`!?KYN(epQE;jYK@9+vnuJ@a9#+%^HD*)!Ex`@I`HqS%{BY#pF;hVO?oMj^n#fQKsmdaWq?r(8`C)w zL@9BTOng~VWKap0{*FOp0ObHKrm8jsXqdF)ErvH330!%>lKto@8rqFq=fWn|?{qSH z-_W}68G^)ZKD9qjE>MR7wRC4P-6&5Ws^pI~5*trMQNNQ=F@$fv<^re!A6j1?u9#UZ zjbsjlh8D?-Fem#BVb-fVaK>;=?t)*La8fzWz)ywkF5gh+Dr!8f!Q+47y;n4mJ<|gu`T-Odct&P<{zVZ0O66#_QJP*Ek!|49*Nlre5z9PeWst(DIh1UtBJCSEe%gBZ7IrO`8??-P}0# zwVWTblOZvUqB$5x+$=oSxpW8D8lWnTkqQhe#l*9|QF$7(oa|(>LwrpgE7y%8Hqc_B zy6wPh66iU5WA}6wC%CO#+QYGu5dEY_`Lp#P55O8wMdn!(K0u|!g(Kbl;e%p_Jo$8Cd6ZutQA1k@SG{8*){T-l_jOg$ z7L;}UGfmy^4tbTIL{V3mbXYr?4F%rM0Wd#?GC+kfjzUx+Jr(b6|q=25k z48;}aCk&(yUr1&G00Fwmev`Q;bEi$=|7Mf2)eD(RkqF} zMvu=%>a*D>NCqT3Mql55CTWP%5ha@o>)fe%xO;ss&;Sxn4c zK%F4q`ZfV37v`!LA!90}8b#z^;X7iOW0ICTZAgpAD{H%b?Wx2=&1qM_gas079J_Zu?{t0c< zhy7vkXDue&yuj}Igo$H^X95LQrVxw<1CS7c6K0r3jw>~*e+m}mKO4fIP~tT&cg#7rK1z4Y9h_|#@fIKjCK}Sb zl5+6|zL1g7Cy|Oh<~(5Xd}H7LRffd`5WrQY&$p=0bFD8lOKjf%`sr}ApDJX9J9HyR zH*v)vIVeWmB>AhO)BSM@FAqP!)X|L_AxQJq*F?ieG?69K2X#`4-o(3`NQm|($+ zY&jiMgv}+)J8Fzgs?oxU6kqi(#V(lVKAxWreA0i#g>mpdRL* zSq+8YteZd4tIipRu^F{xSaGv~=$vJLwt1^bcAh$0U}uip=aBf5Xk~$ z6U#_EN&8q8>F)Bx7Y2TtOC*WP%D#ox2N!JN^5oJ489v??%nuZ39~OLYF|Uy<1i!(F zgE<`bXJqkYbKe&J4rUuO&GcN3o}$ScH`PrZ%Ri%GLK}v0Flawb!6sYKbMm4;x5cMv z@Af+j?t_c|RlS>)EcT-;Y_-9PgW_;x6|Skj3q2@?gp{nNz2j2M|3l&-Ap9OM{yvWT zLo-WmpzbSt(Gnfgcid|qZdmgF&Oha^wvinbz-dM*R(`<4W8&^t2Xo@nO3|fW2@Rio z;Nr~(p!lb31uS?uSLVy0A)MCL0vo#swdzvs&eAiM+}PPb*7$OX!QwRg5@WN9QS}Oa zTDc5cp3?b>2q|FsWyPDjil}cql_f>48hLTNj1-Tld45JjU`SaGdxc?qMLdg@Yrxr3AzBsc+-rQcB*XcT0{SGCY4Fqc$#nN?Rxy-SF% zyodsTLaG7Ib+Pc#nBr+8XH{ex+ly(Mh&1O~YRtSG{ zb)9>2jSFvG*In)59fL+N7C69Gq|1IizINxXZfm@@Cok(yNcpi@{lWXt02t;VZSfUZ z1O40DE3@q1dG)>3sFPI`5g$W(71oj&5r1}FI7!XrS{=^E#=jD8_RMPWCmN3O8t%p! zwe!H-Flb9^ew!-HcdSt`pPM$+1(UCE{}C^URl4bvq>OqL^J8Ti;h>%+{MGw7$xREAdGPpSI$Js_%$-V!kIhy#Nko5?)ldv4>`O)pRg_ zY+2Itj)P%Qdl7v%YR3*}r=DmHooN5ct4_DsbKM0Kp)ih zbfWjzyzlo!w_Iv_ZF6Urd5w}%5PaDchNi{e6Lteape%TJ#MtW$|d`M-oN3CFJ>En==R*%m8(Ba=6{mE{!i{77_t^KnA zJ&WOQn!{GzedhTe#ll)%_`z^Hi19m!c_bj8CY(CD+T!n8I5a=|7cl&*#sCQR`NEwA zy*~=yr&yYge7#lFzKPKb0+u{#b^)MWmawiL@%aejk8uI*ZJJ}5^h_l9fM)=E(3`PC zo6e4!_L#HQdB31HnjNdqj@0gsl#_AHwGPiysxCwmpdVb$35lQ|&!HRDmmDqYuH6X< zvco67@@hkT>`JPdq*?27U#HI}0F?a>{8#{i$&8fJPYUI?)Sq_vZcH^#c5INe^7fB) zA2}~3LYD8F*18)v?kB$zOy8`v?bK4Fo8n+bP3+%{WfhERuH>B)H2eCh$hN zlkM|E%8YYQ!XT%UA22rC`|r)Y3pyIkCbz<7!BY%AZqunI#>MVaC1(@EwkR?WFRY%q zUs^MP{4)aDbV;BjzXEhs)PFcAWFO>*xiC+*== z59?p9?!E|l%*su5HOVYSVswf#L&Q>vj+oy`SVE)-XLT(bC}dGcx6ix$pZOo=1?wnK ze2_*tb6eT@Zx-`9+Jg=rOENvhF6Z;FYvzo4CY3B9{dj$tLI95P1x?EpX{Y(2H}j!| zPWtCdhDnRjo0D&*s21`*EV&X%^3Ffpe-5gH2wV{SfD&(_sNQTWzkSHdWLRJ_;Me7S2_T#+OM-Bqh^A(NI)WgHn~C~|wLF@2x4NYn!j(CJO_3<9AL<%k zsZsv2Yu#r};KxRMlZwvC@Ij|S>&Spd2*Ef~S< zHqm-&e4Xr8_P32w!c8ol&2!mx)1CJLx)@k<_5D+u?3)voY?#)<|8c)RqJSTu#P5rj z0ag{55!={Lc0pTnue8ZDs<5y~Ff;yItxqj@)d~aCh-(P|W4e1>mRn5I;VhoJXXkrt zp3Pj($$|;KcHVCbCPPRSg@BDjwmClM+dI-*A7r2GzwkVeXI#LogZ!x3#S)qdB;2w2 zzKQdbV22Pe3foJo+cPK%FseULEZWMpTz?e-QGNn><~42ieZ`%t!n~Nc0sw@`5j#|E zc<3CsKQfZNB|T!d+BNxpoU%pbp9;2mvMknfWbSE`kq6rJBL2Gl6&`W?D(`q~@?^&>j*`bSky1n54m&S5-%_GxT!AscCui6~o!=KX zN0ZxwAHII|e7EEIJ=f~opXhv}9`Y|96Px9uU*)&!`s4BG^hw4aL1I6Y3xD|NtfLc* zxFl27-vdjvPd`uRZMa;-T3l#E%$fF{?rmMnKR*|HAByPzfi<^ywCzk%w2v!(5m5D$ zI?^8e$n*gthocA`u4zUT7%`S?rAYgG7kc+qwL^tC0^rPt$c zp!}uwQwR~`HQwtv`FDF0b-$foU1{|FNn-r7Z?$-=1L5!e9`g9>cJYtfzdx`@-#1^I zR3pd8U!1DHxH0oSZx7o~iu@J!^7?HPSIZu? zD!wvYTmGzi`74HaU-9}iE7|LsIxOuuOH?7LpD ze)#+HPwYDgfCQ>qLI)sVw9g<~k%tq~i0OXm-%*OE5HOD6{<%AnB=m21oBDrPc0TmF z_NRS~ECI{j7#f2^tvpeWt)bjz7L81)ryPZkU+3a!u_2fa*yTAVp zp>HYQ=YF@Ztx?wLN%-3fFYE#O+*nSpEt`q}Z6*m+4Q5%$mR!~e9ZYsj zmxEkFyvo5G7G56)z&>gqzxlMNF1!zUsUOZZ?f?Zs^;NYjFD^{`n^Oor?J{u#W)+#R z2sA!0#RdI5EOx5?`LqlZ!QQ0Cma=gyS3yefU9m^xj&Pi_OoneLr`nDv4VylmqtIHT z>9R~vfVNSP4sELdo@cX%bs1g)9}GU?>T?gQI=s$1o-}5Oj-W&zA2#-o7VaT0JP{ z>)%1Vdu@!hjUV{?mMfo>0P`p#di(|v4d;fin5KZWTTGqa#Zs0lr@3a#s}FRwl)1lJ zTPpSJ5x8bPB+#p6QJyCOVdymgg)FjkWcfgWD8WjjXr);=ZIZ<7NUlH^Y=q9v6oAMU z=r*s|vnvr{CP%t)S5gw6p ztHa+ksZ3r^qNz%iC0L(NsgtHVZ=$jFL}1WMofSZ!jKPOg>zF%uJq;@(xqRprynHtq zC^92}5(JG324ECZc@VkoFg*oqm(elZmR6qDi63?QwuvmCoTh&ekvz{Ep~Ssj7+ma6 zR`SYm&hoS0S@HvWP{ld6%@4KbbD02oop`?MIpXmZ#8t#v{8i_O7pOM>_Gt?g--x=G+^oj$T9b%KKHx^Hq zImNtvHEZKQ!vRV{dX4c?hUSDG9V8U&tR(Dyqn-20N_?(0iR7j`WPL|UVr_H2y7c&j z^2gl#j^4@U-Fr$A5@`VJK?ld$y_0E)G!ak2WKSh~)+9f*T(vp(sBQ*!wkl=RW@rxq@mYC2xVD^iZlOA~bsMkVGrz^+n>FoWDu zQ=0nO7O#P%mTjAIPI>x=+ptb~hw1bzimG@95kV5V(#Jh|hHquUk*1U!^^G}Sv5!2G zSJRD4o@UuMmx@)~Xqb$gDe$@>&m6sn9hyjUHt3urt~+NogM8J;uAst;x1%AXEv%*? zI*Rs?zFV7b1qn7sFTZ#8gk63qp%PG6*4EegtGw`@@xfVs3U}UJN6DaIH$5AwKU6BS z;6k=oq#`6`kf)+ z?k+WqYpW>gBDKq`)3|#(&|x$TWp`V`H<(Y~%&|P;(y&=o@lFtMw)(ySx;t(nO`kPV zq{Kg**(gh!0nWTx2~cj_TzpNlrdhF?i|+1)d}W`8drFpJlc=U%7jx@TqMo_;tOtSe5fRfq>i(>d(8sn|0D?t%xmm--kV6 z`S4e3qba-PJB5I6sd}0(2V7y%k|6@4e>t)2Pxqs!eQ;0P)*Ovk3r?0N4h0d z>1Ho{kgsGP6x2ycj{Y<2-buS@XKC}-wL-A&lAN{=k%1aINNtb;xKu*a{q<3M5>{b& zIiaE`Ag4t49{XxXYmBmBShU6VZ%S$hLdQoi7V~`*HI*di{bEi^t2mY&IUAPDNRxJ% zj4`J0m$6eNZxf)@a(ib7y`bl1s1xQvLU4y%n;@LJN#-cJF+lLaE&*o0YZN1JOm^3faU#p-OIaeZ8*ns4(AnzQShnX3Q$;bz( zxxD`jVS+4|KqDS&Z!;1Vep0sR! zE~)A0eBP$5z)+`$qlTZTVu2EuacBN`H!=J#pzK48ZafrL*#QrDS7y1R|9j1sM(~=T zWy;3$w6kW z$xWU0UYmQDQp%JQ9c{FF+lavP+qW9FBt8$<{n*vQoFyzo@{?mOWrT*p8DD*i#pl3M z5v1Y7?~fI7)xG>xME`Z$QL^?eQIo=U6YFAzwJJ`%Re?3-K42U}68Y0Tn>}nt>2>{F z_LGY$gMc%!Tz^g;QrPjN!8h*DL?0(Y{5P3ll<{)HTCPw63uo%HCW?>aUy1(6kQH%G z)T?cvf=`-NjlPGM{awNaI0@V{T%@V;4skI4oC>tsgpSRNygXI4BI^Cw85$NT)X=JY zx^kIEct4c(BxvNzKTg$T?2n{AkB3{djMqkyb<>2g7|JocoQ6+8J66OdD(NM3m#L~^ zd~$nI{aKLr%TrB1x}*;?VmK66 z2-Gij5Cj2|jN-@&f_ZKbnAHNdr#&B}Urc}KsJwY!B|+c^>&$%H-(m0q|0A^- zGtRrvIDKhRVi`Ugeb|eB1kd(6YaygRH!yC#dnS5-TB(m$Dc)HDqf!o*^`3#Z;8Su9 z5}BLxT2~gIpIn(4VKdtHn0+J4S|HFh_$GJ-5tQ>>t{(?J3$n^VR+B`be*w2MOpbg= zo_$C`WJpnINd5{SdI3}N8&Zu?lD8OANgP6(#LD(VnhQhdle+fRkkZ-EOY&h*2jJWl zrb|Aw`8G(D}u=xrvDTJ?Y8^aId_v z3_|dr6lE3^5s<++5};`Dh-=FTI-}^mFygU4;(0al8vC;s`DbtT&pv1+N9nVlp{jdg z%wZ0eM|aH4`&j?d&mk?UA>^@U`yj?{YEx#!d?;>^FesQ!C6AWN%>>RN1LoQov_Bbq zkuj{7IE-{3e$*-*eOWM?u&TRj(omw|SmwT3X6bOX zCNRVq;S~gDS{Y6l>w1!it0f46@{Q(7jXE;RlVJnM4dsvH6`o$n@VJjtUBz``@|8(s zyWJ_!TeS0dso^;zpIu<_qZ3mmIFL%YL>mBM3~rkFVDSc*${J7*fXTmt-f1F!#FE2c zm!lfeSalotVi)%WPb69*9&$s@Y_CyqU-nNuHl7*hT*b{AXvbB`LuDq9S}GW@VZ<;5*O0cbOoj~6*G_gcySX$!% zl~@&_@tVxMgY2_wnlG#drxoP~ZBlVDz+K~i^=$FX!z8_ z$k?bqJ0E$eiDP!rlGSCDpj+q?O{pZB4$)pzGBc7XThQ1vu+5A!w{44t!m=fuKAz~#);r*m%LTwxrV9Ait%S1!O-I*L}QMM97+ zw%MrRTR{NeU}-A-)#s02UdI~Aau_xZ#$EXd`Hf;^*)BUf#P_^;<$C&RLk{q0%Z&5= zOgk2RPcXbhbGPgTT!9HJ*mB@%`Ge_@@3Qqw0)c(fp(|ENCL7K#io$SPCr!jIjZ=nK z3q+TqC~*7zbZA!MO@rQLc$mNok(M5-PCtz*P*Fq&Q&|A1_cf+mU8YeKrf<#-_q3K4 z+>wsj2&kNJiR@Z{z?v)2sE!0?!;D~Xz=amBQB|)M_L$vFuBCRx`S^qVEM*$Q@tPRc z16z$p*G-gmUgknZTEo^A!%gu{O=|p&3JF&~GvG#xX8Xyl99XR0KQkX@*ihV=B}l}L zVjmq!dOu7tMgGt`xybk7e0@=W7A|P2K&I8_VYzrD=R2eMQd(fcj zHg~(lMGrQ-STPI~MbFPUzgr4Z-ml!XT7OpFO6oT^pI`3-TDyAG^)Kp9r(q=c$K6DK zy|GN#(XtegwMrc}%bA5m*db#&EFP7=zFe~aelMtHgP(ff648%fi%Hx*aO`SZfs>({ z;oE5*OyJ2VLeqt#hp(}l(935#3O0avQD~M#6tBT^(&Su>9+wZ{s3=Zd+7l{S(dY`Afs&;x9z>rjnkGK7{cAS+XDa)4M!QD6)(IwZD?&(s+%iq!uB4ds zb!;3tcdX|u!eus^k_YlKIX>rl*FeC*AURvXbH~`qkxl0yUDr6Td7H6lzf1cocNwmJ z2O`1?#|UhjmXkQ%kvO@MIDL~iOPv&r_M!neVa_;)&dkd&!qw5ujcwf*$#HVe4+F^d zCO_;pJsi2J*a23o0TNWJtv2T0pFbhnPJm(B`#jdmHu@ni;aV#Byb5oz3MWVdglP0}b=-+YWqqshe#hZe)P(J&evTTOA2Kar?2^ zij9ytPriLA-|LBpd+iu!Xi5<(gnZRG^_WynVQ!k_(1GJ|@n#7Hf|5{1GgI2xAe~Ed zzK=!Op}my&vNe0c|uo`&*$6LGogTb2M=iK{)NBWY13}@HiE*7BBH-4xGKA5 zgeqJJ9PyJ1Mna8Fal8;g);Si#<-a3rz|SY$zgOuGiQ*cRO@0elo#o_m(6M!lxG3WE zNM{zOfuW$(uP>)h&qfZij&ZKx^r6hS`2#dotGPwDxy4myB|_j*JzAq#MD#W+@|bv> zkyd_y5u}=Kbw8YQ;SPM6(UIh(xa30ga(~#T@D0k#@5Hiu>3i&VueaQ>`r8PDoJ*c; zcsWU2_iBFcZ9aN>_eqjIT9^KDgeE$2R2MLc`A|>aH2o9zQWdtZ_XFE!W6^uZ??PkR zTK4Is2qiB2a2WswtJ-+_HiO3ng9SO`t`OtC z9wXKY+->EJz%1x_Zqc`$l%@!mI&@Ir=4DmgFGmue=SMEM;yy+J;9G?#`kM@>;FaQw z%R-fM*$ z?67wS1-@Gk z`ikuQmfjWMF(vRC-mv$WDF@;?5o1v8g9GI>RG^Ktr$L4idok zs-YQ=R%6RvS%Xn^7o-DUJ#+f}75#BtnSpR>pzBR=uWGur$$HWK*eC1KGj$;Uzlsk( zzH=dbrrSe1SgId=q1f5)9-_X61xMlra$~ZF;0jin77q4l^1=DMBq!=&6FaAE8#^Djth!8O1 zb^qP{xN^|hBDk9@IZ8<8WsoRj9>--+?|$p^X%P4H0RRwKTnsU8G#+tVx;kmd(2E{+ z+j}MNn?$-Q@15cQYQxNbd0|3$LiqK1p7MaZe)G?9>XEc&?_V)Oc3kNO4W18DTDf>1 zGviqr@L>YyDvuLgX4m#x#*1tYk#s!@G)=Q*(p(du5+(3gH!WhO#!!J<_@>1ui9|O4 z(0>2hm$vjb%rPXCm6i%2`-3k8xe^OW41~^aF++;q#53ZljiyE^a#CPo$&ZobrfEyv?t7DS4t=5ou`k4uGh`X> zJz7ZO9dNvaZVgd@8X+0ePp2_pimZsr)QlXlVbd=K!+omTy*ZOUS!pwkKg1(2#&@;rC znPZhEc0Rcr(Ezz&GV29zsRCTNVezDX;PEJCzNr!FqJr%idl~LK66D zHm0&oXk%{MY7rWSKD6q$tSS2&%Fm+9q-!HJ^7XYyJ$DJPgCM_`Rm`Ve@v?m!*F+w|PaE z4KLsr;k{MxwtZP!uQUxruFI&?senmPp29{?g7GR(2w|G7m4x?$R z-sGgfV3`Ibu*@8;-f<6hxga|x3s}lFO}^`%%fCi?8_x**yhP%Hb@_$`675Wg7of|M zh>FT|$D|n}Z;b0z(2-VXOx5l95HmH-l5BRvApnm{plcj3o5x6un}aA}R7RV3AlmP9 zAqi3%X27u{rEGFuEZ=Unl2l*3P`SS35@>Az@?P!(2k<0l`<^K<87*I7FBh#(FY8XS(elJc-liY%5OW zuf_$m(dKGDqfX+e86Ab+Ek|2v?c>!#EQ!C(y&N`O>UBFT~*4}n_R&i)W8QcywMIoU9@m>TuyUrLIU+o zr>&M9i=dnamVO3ytAh1xOJo2WTFww85edOe=?YNL=H-`4K?O9v+JYy&b#k)Mi3WFd z+1*;jK%nTxJ?_yBP^>bppPegUS8I|SY|0#pP-9iqfGvlyR=J&pYgchsTgl~s7|e_p zJkRTf>Rs~NdqJiu{WvqmHp+(IRS8re;|V* z;7COX7llzLBH*4isV6QrIo=811Uca#u0lc)4)^*ux$#A5NM!#I##m6-Bo)ZdsGPbj zYpTk%57|OExKZGTlwuqG*hVQ>V7moVSRo5gANzVNwUJvc014|n*u8)0rb z%&}LKz{n8VQnAHYjI``741ktnDF9QvpRhDXU`2Il~)G-=R~;~XV*c|(v2 zK}9!|4C3m3_^Ba5Kz+q{-=wIxdCbSk61M$o8OHI9CRd0y+ zKyZbvUtt^0xWYpc>~hC?(tKE}iCVSdKVb}X7CaXoa)!x|xzl|es&H^?#og*A@7>%D z!GQnL5eqllgxwX0x@oVzK*dYF-VX_IzdiW!4l4hSaW$!t(O~?Zejw;z&n1FkTY|XitE;PrUD2f_RRsAM($i zdfIslurxZVCq4sw8l^C-kFfJ1nU2LT!##UWkMHH0Fp2rx9A zP2e5`BAN?+98L*^X6+c+K@(FKu119pV{Sp~2i*&d1>{5eE5gn|`h0X3|{ zzyW|Vtiu;zwB~Jo@8n#58 zEd-vm;v8udEY^e_9z{I-!w`C;@JY!w5Z6Sl;6@n0G_V8!00KTNgf{R(L!?5m0h=hK z7i31JWKJe!R;FcMCT3=)W^Vr`XLhD%ekN#!rW#zr_nAX2h$d!E!XYGrB%r2iz9wwO zrfkmUY>L8KnuMs48Y-9?KB^fUhLTWmT6iS|u<2zwN=ZFr#a}uBMOwr#?uB6@reenA zOx7e?hUHmaXH#aUb}}V*cBfG$rRKGi4S?rOUV!#|vhPKJw$^Vd$iEzyma?lRhbwMyZreDV08H2dDv)R;iY5DVI9w zm1b#|hN+k~X$M?_w0z!}im3{$=An7hLZY8F>Y6qx1<(cE&{bsU!5LEM!#^mfjk*kS z2mmU~LqGI`J;+Z*C__Aa0Sh#0CJ7@k8Y41Zs6URy2B^UjWU8iaDyMd;r+zA^b}FWZ zDyf#LsdDP5o~o*@s-}{`rU(NSuqvyD${ielExl=U;cAICq)VLQL&zQ7&7Ixh-GQj6 zWi81w9R;w#tG$jZ6}&1H-0QuvTN6CMt(sxq#hy_3szZ>T>7@bc zsUGVYPA)nT2FM>x1SnGU!#+0aUjAlRNa9#rX%X}Q$cC)Qjx5QRtjV6N$PR%T3<1iv ztjoS^%C0QT&MeJ>EERkotk!JJQbEMrz!Ctgn+oiP0;E#iCrCu!LQo%rUSEV5Yw$=L zP5jvUAO)~J1;#q-!@6E&c&yHLt;?z`%X+QYnk?9kt=aYf6`biMgzeduED?l?4hX@| z25g+dTiqt3(RPIYNn`*HVAE!85iJJ7y@Z|?1s-zb)ncv2LL6mqZQGh{**-4h%B)B@+#FGKhtAbKlyurK8toI#m{M@_9!6sP(=QTT?7lA49%-f#V~ ztp~Sk|K9Hqti}F<>m(fNXHb!fyzpYzilF$S(2k4gqYK0}eE?{XQ<;EN{pPFz6bvoO1C+An-!0V>>b^ zv##z9SCIJ(73>E8tP?Zw9&c_Y7G%tVaN8CEiixZi zzp&6|sNc0#-g1N)HiM=X?VK%cA<6!OT{GDDE4^vW>R zUGF(}M1n48gR(OoF@P+LgAH~>><$I6A*nqB;bf5VGb3?7qwqFQ^Fiw@4iE$_P_rP9 zEgJ1W5RfcGE95x;qb?7YP2^}7>}ZevD4w>}?igf8X!1~i0I*T$NRxD8nDjoQbV|20 z?^^ZD<|~@av`TYz*Amb-FLXFJbo5d$L|dIi^YTRqDxn%Gq82q<#SAHxZ2lSq66kSY(<~L_lF8~SJy1i?7+!7b`GAk1l}?tgPd^; zSb?R0GJu0UtV1%W%NAHeJj6paMASk+fjq=R(td+*)o4YCGUbHhODxe)3>aCB_8XS8 zX`eJ6r*v17w=~D^ALoDwCpOH2b#0HePUH6C>9#oY_GQ4Bi~+zEL_-=p!54r-cYnY; zG=mga0W`Eje>A{0Py=))gct0CDNI2wf-{6dgL}p_D1vK|=fEw%pAIv$O*SVeFIiBaap4WLFs6ij>IiLr+p!2z(54xe#c`d96EeLv_ z|M{WY`5uHyAsqI5KQEFedGE=015LD9L|WuA#3=j}0D!M{`7H2Sp30`I?*Yt*4=zBgG2DIU6LqvM)QcH@mYxJG3*q z8bmv_SG%=0`?O!XwkLZf5X3NOd$w;ovqwVR=mDiSHhe!erl0?4F83;@gGI3&Tkyfk zI-H<>gTvf?gL$ODI?yAmCqzB~fD*@!UV$@m^{dfyvk$zBt(oP@WHv4 zY>_*(SwptyqG(C)TSCmc2xtQ}XaomngEMSF7bI3DMZ*dHI{*ayz!&^NFlJ*Wyqu{_ zF|7JF{zHa9e8fj}cv}U<&pg`0Jj$m%+k1S>w>`(7!7xObBc%M>r~Md6Ive0Tk*E7@ z`}_<`_7*RBWr!Tf?Ssjo+^A=RH5^+)h=MyL(FD-L9{~SAJRCkhjGQO{fQ2Rmtv7^B z9=w=$5C$j$Qg6hW--H1G+ZTxa*z%Pht zLLwN#80>w{(x;BN9p)Z9%}`9D0G>;J9R!&R{##q95X+Y3KHgb_H9U_pZi5hgsN z=1f9|32UKCSL>m{g$*kjl$7WYnJ{elAn7rZWJw`Q9sp3ea%BTG4OqsMIg@5hn*dzG zyt$L-&YV4g24(qEXwew|ViZ+c^cpe%BD8gT!h-**0svC(DVt)&S-ci8L&aO^MV~1t zsq$U1DdL}qrElTJm0OenF>*GRiZNzuZm)mu<^~o#m~dgkhl{dxioP}3%3 zWy=RIUe>HR^JavO%%vNK(Q@a@WDq5aBoL&?lCMvuq)8MqPujI@-o`!qW$mL$cL!|> z;LAVb#~%Y2gDoCBYh7f9W$6bTK5u1iDh|G#d(BwnVl6#kte6D3^8P97zMg%1_kp#$ zcl=(ZWXhiLD`c3TKj!`Y1wwoBJHJPa|g9LOPt0i^`M#h4o6`oOp+M2!DY#u*O-k-hoovk$->5!^Aq9`mCm9dj!2 z49JJ@;K(D^LW0mF33=0rJ`J~{GB_*e;*iGnY~0dIn-H)ohovkr#*(<$!sp91*=+N} zw%)_>Jso}I@5nkYyHm4T(wPW9Jr5$|kVNnx=s_n(ifzK)I>Zt;M{9!=E-l@}t;$qWLC)CswNBoGUH! z%%$4-#~PlAF8a;I+PiqYj5~ISCfm#?ZBpgIJDGwtN|#GHmy3j;rjN za5kE!oz=!o1`Ig$R4EpWi=yqjC1#s3rMqJqYLEZkxa7(}OQ+WUo>q`S16OVm(H>lm z>1?4jCxL zXGJN_KT2Rg3DT&58~R6b<}{h}A!L0W>!3g`agM6>E`GV%)zz5fnqNT)Y*Knp0DA&M z+x$;31AJZuCkPZ;kb@CQsev(YQ3GrNB^>|QMh=k}A{+*We8G{-9?%d)DNd1!RkY$2 zu}DQVWRZ(q^kNma_{AxfK^&qHqZh-7#dslNNx^g63W+B<8dhnJyOE(!>L?c*wr+_@ zvUBtoy4Rj)SwAZ zj*^t6{A4IiiOFH4qa2q=B`HBEN=|MhWe>SuqF7iw7anhy{Ojd~@)(yrvaXMflnDmL zaTo2W$QZ_u15iNmk9HW7n%gO+Fe6Ey7f=!s-Sp-+!5L0*j+30=R6{w@nND?v^PKDS zCe>=;&ULm^oRdgRA=>4TTS6|Ea{MJQ{|UfgLI#Gz{M(HmvdJsX|r zSHD_Qu#PpQVpZuX%b^Lfmei~sjn^S0v5B3!QH4H@BT$8P)P3pIFa<@5AD4>Npe%ry z4BH6>jKd4TE|y?gT~8Bts4+0H6I2*y0=4z6&K%nv$l^w_otuE=9S#^*+r!@j2YANHU8!a{dtkHDQW70?us*dr zJnrVz!bUB!u`q0t^0v*zjATUhin6d~{%j^}`3EXkoaLG{xiK(ikBn=KQUQlqq+@<* zOleVLvD$N29{n*-A-vsSH7d!JtMgkl4A|gmStbZnpiuPEOk4;uCe8Q9mqC0256Y3w#m)c8ZKO74h9RkwE9udQ}$ zSOB{3*Gfb`9D zeH=d}4DCDPdEl5Ucv14)>TT!R03a4!P;LuRmXv_E=vK74(Z+7>xclAluJo8gwh1zy zloIz0X}`1EY+ME$CkIEk%Yzc_+`wFb+0G%xbEpVe;3X(gZRY7#qJVq+qZt;z_`)rw z@$GP2*dCX(fFm-Ir{A>GCkHj0|DC@H6PeD}7O&UIYx4=>{I>=utQc653*)4~=zRYs zyG$O<7^chn-C`!`Bh*EVk0V>8C}(!opWSk>*No;dEc^@yzwQm+9O-QbO2nI&SjTJm z?V3}1aOVE;y0ev}A-hDSL93dP`n_I3b~ejpKJ&!edG!Qu{Y;juw#rLT28>u>d!p5W3a1~+rj>jHnhHlPe*^*rB^w?hiv;wO#t_% z`&NP!xy1P6VUNri4MJBrWtJ0i{%MAoi*H1dr=rke9e`@oWMfaE-|}aM1vX&~9SZnyHBF z<_M9n3}NT;BI^T1(CL~Gq&!d3oNrg=zzU@=G`zjG-DP$_?Le5`{|+iHi^1%9vV;*JrMwQ2+Ddw4vrxnq`?=^a2Wp?D+xt$zerL3 zOi|51YL$ZF{=)185zG(!Zw3EP3ulqkYB2_{&+-y+5oKZmpkNDj;T>`1N0ReVG0JPyB>Om8q$sc_SAUlK!Ptge(k`5jr3hgb-N^V!~&lSHB3t12V z$#Eimi2xDfB8yHKJ+U4W=;3SvRQf>^2{dOu;yoA@~1Cz$u>+6j4Pg<&G*h z&nf||r8I&0$c*noupwX3|H86`xX>KQ@)iwHC7NL!@WCCd!7bm?6G_A##cw9Mz&NB~ z0Sw8o^ir@?Qkwv??gX>HT1rUDA=7G1A*=8S6*DIvG8P4~B9~_nRWCB55)8c$Diy65 z$zdE4MkWx;+zbE!FhQzv>ol<{H8pBAJI*EHjSfOc>cWi83PBsQ^ESa!HzTqvA=4Iv zQ_uKP{cOM<87d|ez&NmBh};W^j8Hl$iaLvrqnxlcq3fgugc!gRz&MR7Ju3wl6C4{; zmmbq60qP6Y6D7aH9(hhBrocF~fh9bkG;0k%6G}flkU#(H5IYeJA;WAz4k6h_@GC=Y zLH(&g&C@{%Ble7j{U)dq?U5FSC<=^29%O<7Jv2Xw(}Duh*Q~SYNOTU=WhQ5g$COVz zTa-M-@+Z;Le|WRzgwud*bb_AD9>;`7|6w24E+*tass=4cs|iE}QbbFUMES&hx^qwp zfuwM9JmIK3sq{ScG$<$Yd$v@9IMN=6Aq$R!1!h7G4+%}FNllHEO{oz(=}i@DY!9o8 zPQB4i?FvsHv`U2vLKSX3kI*Q|fge=oD`=vyPEt`BiBa3_Na@ZcLq@G;EdNw={ty&5 zKVm1v(KmmSQ|ahR+pkXvXh;{W;SvZv<{^S=0`mVk6O25^DvJ`y&bb>mQ9Ms`6X~O5Gs#!lZPNH=Qr#1eZP)G`FHbZOJwsrdM zbV@gMPh&I=$JI}tmCp=d6x?$hZjUC+PO8w(U9}BVcS8vcgC(s|1h+HC4$M0T)K*!P zTl>{pebu|dwT6WCh6*;zF2Ec9VIJHw)@XuRA$IIi7MqH+RUMTeoe&%Q@W3dwE4B4j zF*U+867GU#~Pn8yBwbtke)j0ps003|_fpoMc$j>yfmRxIgQsT8@y|yKj zZTqRYt`%LOtZ*K`*R8H{5adg)xr0V!nyQ9BfQi79iD zYH$m~Vx9N+Ow@Hd>Sx2MdexR_x%XEm7ioc&MvJCgIVTE&<{zMACJf*g+_=bva&UQ_Z5UA_eKA=!iE@|yjOyO?*gj9IN|{Wc4DCtNMUJW2BfN8 zWq7vS7g^w!Fyt45H&26Y^Rj5EHa+-u!i)#wx;8IHpbfevM9A<9oLK*Glc(zID6Mvjo(6miH3lAMgX|MIN-rlfg%JtvU-{k0IZf; zShPAEE=O#LZg*4sh1kD#e1r+I;%Ze*e)R*(1D&qdZt3}J1=YA#u}~Z zTdmppt?@gq=X$CSd%XQyu1Iwtg@ zr>{F=Hk+2s8J+*1Vx2i!HR1U>g$;3^6s#tJx{TSzkXb>MIgS4r$=H|>3vj_V)4r_i zAGkqT2O|~~!3KtbYFUEB`Z2>b{8>LB3kbCovfu{*z?N}YmwA~cC^mjCcrejhY)^cq z@VB!vd4J`MlLPi`$2>hlxxN;lE{QN04P&7`k|v(hkBxj=mgs?wqv#H~9qwU~dCi@r zam0}n*i3xOSL&Xz8r}68OHnBlU3SsXI-2b%K+4lrh98QqMMsl*-U_)&V~KO z{Cp}!om$DP)J=V*6mm|FUDb0_(X9_g$^72U{EZhY3ZB*;I+r`{SkqIvQgPf>b+N-vYuU^QJSBtU3+KzCK66W&d(`QKpDWn9@ZflkY)?4As*tP z8o2ulq@f+?fg3cFTN5A$>QtARM^CDXt(I(%=cc033|^1Kyz-q`(TG zp&kEV;uLbh3!b19_~C8=zzg=l6s8~-(qb)=zEl<<397&h-rx;ZVHMus14bSexWN@( zp%q$z@mInOsvrrD00to7Fc2UI5V}mF^XQRY(oJ^hrM2k|cgA3I;&+&&y4>nbT9d;( zrMtdUWBt*u9Wfk#42B~n{GbQ{U<+6c3;qELWP%!o5*nsqCA1+Uw`}mgWC4x<@hu+! zHsBSsfBRv98jgeVw_p3;KqVF+{I$Oo#(z7g_-aXiR1)5TRbO>y70vXuq&RKCD0~QUV2pn;B3itt&>1oS*ESX$^-ds&cd7p- za6sm5fkAA&1g6j!EFe@j};0@A(3?r2c$&qU?EUP1c{&xHMnu0jWb(x0gX2t5cCB- zpbW&Fcib z0Urbf?34pJvW*G>23|nzpile?@+ANdvCt<;)}K*gq%HyzGJ%*@7RN|LX;U7g+L5Bj1;7WgGXNt zc;JFRdFF-`Z)h>epk{pWCF!7pYO0Aza!4YDDE=7ZbexRxYPSEb{2GtC;+AC1znRV( z>OS3!sgqE4^8^dBGb_bC%1mK}Gx4;*G(Ee>&O!*%7WTolcX;cQf9*E9mqyv)b{&K;+WN;^}yOfi@FrM*P zXAIbg2Ry9N1%WgpgislXAHabRZ%(P(jpy1V_ejDzat3c z6{`r4PMi>rr_ck7gMh;l4nP(MD8UU(%%Umd5C~Y<%_1_0MFq6{Ug7&d~=`# zy+}CC!^R1@v6%~0;3LX`B48rZ5XxjGLk;uH8g>6pnzy26LAdD_korWVJt3(}fwI?!`D5@gE=`Lfc*bweiI zNnHtoQmfK%rOl%y0K&494Zs0k)UXB|+#*kU{uE#MY(fVVLR5hamKAV&gC!4w09lYD z2LqXbF^WL~y^40A2Q5xQCB#*1in!8`Pm%6-RNk+iDJXLU+~8fPr;jVHH=s z5MeL5p2tO=d_WpUe1{t%tCPgmbFqzmtWQSZQ+=)PAQ;Ho-UK2B2QhfX^>eUrwCX8e z>es9O6QIXpbl?2WxVHR-=0Okgz#J>|*nHG(N^{vJJg#f=s(N zkH%odHF$9jMjGGyju0(@5^kLkp={vj^g}+qSV1&)rxWS{6WQ%<04QP@oJE@a=$G%D zOQ_=t<|X1}tnh_v46K#`&B6a&6m()fu_*TJyX(Kv~5< zbrJz)#N%FYpe{iUPy}*=+1%)!5D#A73QQvaEdv>28Fh|#^K5;|Fz%&?f*x?lwASFm zPP)>2d|Uq(8o;CD)z#xNao{{2BGq2;-g8rh`K%fvKzK)%S#A)NbJ(4rx0Jfo7WagB zwip@6yX$jvdAIbtIRCzA;2GmM$QhlYF1r02kL~aXO7PGUpL{lrA5!F#W#W}*aO~@{ zfo#)f^A;JwE}r5KX!I8CYPV-l&;78|6XMJSVSpmSs1{?O_x0?j%kv@abN&Hc;l5Xl z015b+`y##m{sX?^AI|@H6y$i(mShB|Xa;CASx0N{7Z(DMd0Zr37|{ga@D%cJQv)G- zKecj#(*aAg0tEqYn*{(V_8{$Nf^flrJTZH}QF{!iNc4#xBtIhJs2s4+QMD*)(pjR!NzH&T39Qhs<+ zMkr@U*b@anOGoeqRAv!nhA(c=0vTve8(2$j5C|cMH}V#1vqpxScwC&)cR%-c^hYu$ z;#!YER`?ZYbcp{kOGjvU$b-ZObw9{xvX~n~s1QX+9Qj6wJMlbS#1l@)SWVyt-BoT` z_)SEBFRTDlGDi-?fC2S(Z=5KN%Y$5N^ojBpip55Ulc9U22xyIActV#L{iTD8mxltl zhqP#M>WFddsByW-ab|cPI7A;2s1rO;PjO&{-Xn--ajA_OI!=N_{aC6g$kO;Ah zd~uC!G=JKtG4}@<$z)bEmUMQQ8ao&|uqY6=c#D8&S0JeqxTtdr84;F7Ntk945g-J^ zm~txT21Ni$dIgYzzzS*BJ{Vwk3CWXJ<%#jWs(XpPV`X)W~UH|^^*N)Ts6rG9UuUV04b~2dOgXLSxI>fsZb9& zlovBhZ^#%2v`nE9ju@FT=J<+F*O4MQl7dNb?pPNjnR9N55HL^_%eaWdsDUv#lPtCd z_2dQwk$&sPmI$es-2|7YC6|JBF{G#}l~V{7)kk~jl))E4Q5l$qd6}?jd(==Dxtjk6 zl^hu)vN@aHDTLrjgtB>+>9w2yka^VSX^_cSlG%QYFb+8&hRG?7=Xns#`4`X0M>i;u ziJ|`)A_IqdX?T43Kz_NAfZ3g}Np%W(P2%~H3>p#TXe66PlY1C_NCk6EjHwZqNiuFqtOEM66I^C__-JQ8AmTT z8Fq03RTe00j3Kw1r`qqm6=De(Uf zU@%%)X)cMl6G2c)O~8|bMF>WaH)}znj@o{ZDiM-;XOtRWp>hf6kPh`l2h>?POL;2-sH?8WtJLPJx(2Ly7AnJpe}wU$mV=th+LWF8l~amrhxI;ZW$LaBfd z1~3iSfTY#v77*|Tt&nCtp#-G_2cyQ5Re&#nFb>4fsP)>VN$RjE3Ysfgsi5*uFM5iH z5D5WFu%c+Ntf^bk+ORsxuzN8P*=iHqdJxL64yH;~DTtD*#1n%R2TM?*w3`0|A+VDu zo3a*r9$;!0V)}caLUe?YsfduKV#TbAL5_C_t#aD4()zQw2BZR^4D8?p=Bct5v6TbE zt_d-dAaTx>fdCLoxS)kri+A@509soYT&qC!XJf}23CS90F|wx3+NL-9raW6@ zZR>0fi?m0f4DApFSXs9bkp%Pc1{=Gchh?|}p#Ue_y1H1pb(XLGwy(SfBbq=*wQz6( z8!D>!Dg??_X}hqT>nowEwr=~m0H6%<@CCrLC8G6w*`{hcApndh2uNkP2H*y?a0{9k zyRwV52vxhZce?-wBf}&PnR*B^`n#2DwhgD92n(v$$`cC9Y{okmdBy)i{}2kRI=crU z0OA#W_E>%01qa$|xU@Q!ZE+VD$4r4G@7&XyR*qFT=qMd zBy3A)(d zS%>gDj`I7g^sBietiRG$swFAG0#N`<`U)y}5fQ*d3CzO)0FZ<5y}A0uD_q6=2E=J7 z#4Z>jkMIlWAP!=SgGxLjOpLZpEW(}ZvwLitRP4hCA*hwqq(`#^P0)6&YXIHD3ZJ!> zWo*WOY?W#3oNK&>AVO9$_zRO8ymSnMcASxJ>Y52Um3+Lmw5$KZ))v6@*a~Lwbru1u zvg*hL;RE%g!vYn{mUqVcE6Mpu$3Yat90-E23&t>2w=B&+xmCTqpPwNK6qN`ka$}eSyrd$$8kxCye7q?9 zo%Aeu^emwO49SWjAls%B9otSId&^9~3ZuZt;Ou<4+;ih>!Tf59n}J`EV3dt(%!P5b zpRCLYi@fqI#r7PY`24o0{KrYK3QW5b9mrTvi_mGY7Ph?7(yP#Mp}2IxxW&8})Tu|7 zGYMd2vq|j1mg}i_T)fT<#Y9b9(VWoZyOpc(z^>egef$5?0#UV59j-CWcNF}q4UN10 zdCnV5Y>!LPKOMi$ddDF=)NE_i^X$2PoDdJ_QmR{B1K|cjK-C4|1E}y>HC)#Pg}5_4 z7d6e!i17$`fX;}32gankFB;fly~JdV(ZoAsqm0&*ZOUwI5YeYT)>~!@yw?N)kiIZK zot?B+oq$-auUd`1g)!KL9SH+lrakS`W!u=73)#(_*3cHkG9A+4Y!FAlq#4#-mnqr= zu>pjT3*bB4-_+N;9H!(vrT|OWtbz!wjTo02*0Np4j-AZ4?SqnC%Fo=#iJ40gXatlCEvUY@69B2M@V(cppbN-t;b(;546Se-KHVQ)-4XTQ*j?fRZq@{T+Z}!2^qt^z zTLRLz%B>s`4j>Q*;06(%;{ad=ydXh;PprpqUew_&yQzE9 z-4zE)0O|+PASIaVgCpwL*j1&zUyo75XrAT;3)BaDjP7pV)3m89V z^Gz0hEf;|O7y$3#*SQ$EXY9w0v&pWrta;je6b@SC&fZNC5P3?K6b9`y)r*$JTlF|2Y}?(-}F+K%A!pXdnR^y;qBkuK>Czm796@d@$Z?WFZzukl}xKOPT%JgzZhAMl&1 z7$~pwYtQuQ4$5z@;<5hhx*Y8=ZLtoJuItM82Z7hVaQT-K_E~)~f?x7vs~Aat_{cui ztPXLmuGUjOi*(<^2yuFFkoTAG1;$_u6~6hJ;`coP@^K;Zpl|g5^BBS)2j}v@vh(nv0F_5%eik51`tq4GtJgt7oC6FpaT46Pq`;A%qf4}ra#+3{q)NZ z>+kOP@E-Y9jUk!7>D-SHyI%hax}fj&pGLd?{22}q00a&sSkT}>gaBTs@kGbrLx>R} zQi_BqQ6fZeLwjVqE3g)hkyK|3nDv07sA@I0C+|W!u*6 zTet_ic+zF8m@d3=_3q`{*Du_#WB(q_3S@B7g$-L$w1`n-OOG!lJ`$I%7G%s2C1>XB z(qzn;H*eC-e&p-YP%PHL64>ZY#`y5^g8t8Cm<0}E&p=d7F5xrGlWe$*6RU&iq2 za#7s*bLfD@7BBofF-!l(7c)NUoYG^hbmum8hrF3QdGirLiyp1h^y#2OS3jpcyuR@J zacxJB9@d9hLE`9vKLQKntCQuF!^;r^8+6dXz^MDjFz2p2DZ4}riG;iJH1lYrk~&-| zJrOY@@uBtDtBJJteu@t^=<>r&M%id|Yrh9`3#$o1265wn9D@{6sVwm7#TZ}kDrHC} zo9rt>;;O5VA(JpP1P=~N{HUWx%CSt#lTHK^B{AtpQAM2GYmq0^ZNiDPu4iY~e`OG`-{CY@n0^~~6o zG?fWWnmSz*)Y(ckRa*S0&FxgLQmxgiTetQ0urd-{&XaG;WwKk@avg40IvfQS)AS%Q z=SyTGDzjb>L)w%*XIq3eDr>I|xW<8B!?r7J&4mhGg&S@w1tXEf%M^zzCXnH^NLl9| zZDvhKUEvsY7vC)<0%Es`I+P6!&3@nex1fXjs(G)Q^~xD5tt?)6I-i67>Ns7J zTdp~wla>u*ul&GAlqr^pXN8X^w2sP=S#FslVu;ncb@X@f%+vFU2wO*NI zmzhnov}a$87Va4fmQ!>(Nw>3S0#Eq|830mH1{{0VNk%XLwy-9ic&f=_AS|%ChaHLs z^5dI(x+w#x!2edd$mNz>QhDgvN`9&d_Q_))XQWB|IT{?-P!sUO7k_;6%QydgO(-FM zBymz!IqXaIB^zcnJ4c&l(+ArbuKnNY-zm8fXA9xr2J5a6jWj&r3*dl;KtAw}W=O#b z&}fHIM9_|BSm6)#7==K*un$vAAs6|$!cnFdJ&P@%dCgk@3SD@W6F#K{|L_<9c%hAg zP(c3#JDkElqR;>!22qGZBw`Vbc*G#$z#{2jViTSCL?}j4ic_TG6KUZIEM`%QTjXLF zy~ssQsDTq-Bx4!P*u^l8v5b3YLmS=r#y0F>4@)RQ9qo9>B`l!>NA!RiJb*+%22zkh z?BgE?c}PSCv5<*mNJIhwbv$djRKX2{=x~Qwp&c&g7A{(n%b^oBh%S{q z01!`tq+lJp7|0dC!4H0XgF@ACr9gT(1pwp&5Cb8FI}8F$VZxH4LW3ABgE!d0T2v{6 zD;zrzhY*mxO;n&G7-dIi+0tP)vyw9mrktx>tepHK98c0Yee1G@`AL1;3@JVw2*BdxRot@fa>-t>&EnwI#aJ&7WVU zyO!%>x4JglE?=@+HL(^a5C7OldH>OmeJB6`AjpO_%qkF3xWfPfnE*Zh0Dz4G0H6XT z=s*to%7zlRVtHH6D8}Fc0Xx*VNzojgby!o6+lS8vY@>%#(xQ~K(m9as7NrI0k{Atx z0UMGkASyACk`NFO1c8Zkr;ZLm_#$1>d-=W3b*^(==l`A9^L(EBW>%8Z$Xa`)QyX>q z>CwG`3`#qmA1vDreo38^ z*^;;_B>%Pd#TVLwdXM$;@JyLKQdj#td5C8R3CGV;hn>hEOW*{=cCy>GcTDAKRx)iA zqm;AED7?fhdnU-5OHt_|>_PdvN$?9Jws5V>-5hE~r~o0qWX-y2p=GA}oC9W_wrui0 zZ0?KNs~>xz=;`SaX08L-s>!)@ax-L|9lVmN=-zrPBDga>?Htq`_+u*|#Om`}@xSt| zh#kM*R?7cf%{0wj`k;u+^HsM4p7kpF`14sW^(dWKmE}l8L9LfTsWQXXgS(-Bn@6an zgS!q|-ViaAmCHBzzJAfXN{?aH`^9W4+y5iSH8slm53Gv1?Gm~FYR!65=8;aHX#ew! zwrt^VNQ%+KdA~B|7D+8WtsZoje~zYNkCEn!VQE(XcaGspPkse=pDzdG8QW|)8gAkr zI|g2gx7>5LYaZdGKFo8R`zy&=(==#+{APNwjaHG5n~Dr*XtUW?iISQf=Lp_yHQEeu zQJ`SjnN1uH{~iBNemUqe2yc4Tm#GXR2p^wxVXnM!(pn4BRj1cDmF=>&v!DNL{zdNC z9M)<|{zth_!qSEK*Sr?76G04Hgy#K2z{%jTQQ<3mQU5xmTlaH_7fVc>XXB5Q4n9Uj zELjmb&u9L%9DgN7>_kPKFEJ5!nYvxOHjxWe@$fb=wucW^ zD(@>iyhw~b<))b_=bvItl8*hMJpNMVB2l*Rz5Kvy#qd{3g)Kql56ycY;!l6vCf@E) zrB~~Ipw@!ukaFzMh*kT~sN>lnRPh` zr8ow3J=^SP4DNc8ukom+%Ok1FeL}-+Q^V&%!;VT`Wv$Wn~Ey>_%^d{j6lUI|j@*-`fS zJ@zl2{mHXBjS@Ovg5H*Vqb`YN`IyhLR2pwo9V3K`4?F?Zm~mk4lpB^9=XEe2 zGn$V%#WWam9{?++Ve;6L?)Q)>YUu%Dalu9;Lf7Q6;Hoxa@X-1IKV3CMIW0zHB;E^P zT2D8K9wG5|#r)aq`mHy#YJCIL1Mwt)1uWxd>9NKD2^S&8%@TUV0&_#?MS}r89L6>a zY(l_@2PgkCGx#H+eO709F`*9-hOaJ$0pU0#5X*;;X?1%*HFn*5&(TJfU3V53r~2^>qJKSJhZ)FvM1n?~IQ27ZK8ESIW?@u%oC6=DaH zZSauwtaxW;tZOi2NlOppidm$K4r{FXMMMlo%e1M^^)lK+1=p*5J4_W<$N8(jw?D_Q zt>#4W56w2kU*3S(?#4$4$GZnpYcXII$xzyg_a*Di&?kk8DGA)<~RI_=ieOVSVP4`@!wt!E~$NII=c&TLP3HE z@wOSsrk2pm0dNoyr!>gVcY>L_UFnoY{g44Gz7Dl@qWn(+@UXn0N!A@LOhA(XkJw>I z#LwsxzzK#ic^88`i8deuJc(E><1{Fg#}W{;jHP}Y%{&z&_BfroJ`9NSv4^@gCSSNu zwXGB0U0P<70XaOdTz2}fcD{&ZzKd6nF5l^}7d?JYHf1;X*y#xHS%2SgAu4tWwF;ez z#!kIGx)z>1DZZSpCPQJ#P%f@qZ{i-mZDHk4!=Sb(ZCPM;_h?A6Ao4skpYNBC^(BWj zVr&R8#?_dy0cw(K6z~Wp(%y7dOON!MHh_XOKTF28pu85x)!4D7rI308!6$pRuf;mc z8tTd)O)eG}HDY1>4ij|((JunL5rj-KsFW}|Dy{N|y-j~a1q5X?Rb(^6LpD2U6D<=L zeiARf4)!>SS0UyLH=jYju~7XEv;nl{2|07qtL1BxW`M6?<14}F5nG_Ta=B>scf{P@ zv-zTm@(ydr%n>R|hGUT(w!~w*lVP{Zu&^p@*VJL>SM(r)Yn;e{1w`K1SR%fWq8I@v zr+iY|kr~@PnrD`nTM9|nBCv3tl<=PTXe|gmV~VmpMi~z_3dZ!r5t627qj#-Yir=~s z;$PHXU&bICwI`3d7$cXMMFxczA^T+zcU*ilJenWY>m?@W#5K1-J-_rUnLFO$){rjG zJd_vtbo|9KyOiMM?Q!}=3?$I*8YsgGH>M5`?*g6%gUesqbLY-dN@iW9Yi#i zMTs(F4^gpffpeSKP!Evt*AEWq_F>ie|M2;=Bm8p@cDZEF=x$ ztra~mSZab0Jy^yB!Zd9-u(rG~I-@@lJlL~oLGMM({xWpmB(7P1=9^-Y+n;B4Qo^1F zx?aVYmZy9*PbUjHr`u#)fYLvFwk~LbGk~p-$e#F`tBkj7*{tRwwsd^1m*+WUcz_6u%tn0D87$RMjW{TE_>PQ89`m1Vq3urtIV8?#-ToGOhzGoSGLwXZEaz+w+VkS6xTGPB&HI!qR zm%XXBmqfOWW=te4F|NS4DItb)H^wa(I(5NUp=e~A79$=(y=P&t%m`B!^EtHeIY#=N zFv5zCV+6AxKGnE)u@7V&lP`XvFGYMNFMLRBc8()`$^>d3=+;W!9Fe=g6@_@;K6tWJp-` zk{13}u0%vT_4{YxT0CKW~q6WyeIFfX37Aq+BA{#LoPRYWw#m;GWb)eU(ElQ+c@`VvFTA_2gcWOzb*JcP_)Pd=Pxh1s<3dN z6t(P(#ROp?HBWSn1P|{iAIer8$ooWVtQ}BvN$CHsYrT+|5<8U93{Y=7U=!8mvL6Uq zC+nd)R8cg;cpbXULBNG97V7ppNb+Km61+{$Y*v)XCI_X6w);n>6V9d zuR?mXAw7qYUJFR?9i$Ht=}Q~*oHNKzG{|2$D8Mi%&@N~>%L*A46rB2xOE(V7+vl7f z6h0gjk;)Ug5EMlWLUrFHk%^01fhaP=9=2jUxc0%5BtCddU}FHl<>%1e_a^^l4>D(d7762u?p(*q4Ejh7a7@-;d!KEeF+3r6)c4AG-vARr?Yp_eNo-- zqC_2fDu!V$oY%>s&A7ks-QHKch6Q>b{doE_MeN#>1pIji-%0r_4}A3J8_rdV0#n}$ z;2$l}NafZq3*fnj)Xh^(z883Jvdp6D>0nu);IB`%Z87HB?uj>z_Wa`X%aOt}U%VIE zlLdoB=9iT?nad~-3yf`JEA6{Mjug=fUiD&=L&dx4R|5sNh2PY>d|Ni|W9v@#G9}|y`h=+%l zM@MHzM^^_2C;R)vqm`?@-^a(tM@L5o2M7E6`+IwPSKHgf?a|Y%t=-+-ot>Snt*xv7 z{ySY;`}_Cr<)1m?TJwMZ{kOKZwz|6d`}gndrT^8!!otPO%)V|I3S zW@hGEU_3Q7_3PKKpFe+2PEJltOpK3@6UW9*uaD7D;uvadY>YTEayl}6I^2IaJbX4V zaM9a)(%XADG;li9b=u!?+TDHF-F@ECd4~Uf-rD-_`el+#x8W+9?3>FMn3Y;SMJOOz|TwPsF{P>Dk!ALA6Cl-?sivZ#W;HsSM>LbHdDg3G!a#CJ= zSeHuB<>locukD~ECB?l2i7QlCRR`j1&(GJ_*T=`_$lc?_$>zw$_QX=_$i(DWN9*XJ+L@w4 zy1l)Jhli`HtFyDSgM)*eot>?%t(BFPg@uKwsj0ECv7w=%zP`S;wzj6Grn;^E=p=H}+&;^O4w;sr6B837BO^UM{f!$p=;-L+a5(LCQBzYFenrXfk4Q}$Vf>^ zNk~Y*U@#E`A_4#>2y}fXz=!|{#->$``;La)q%ia4?MlSJ@91P})f99lGCy#i?Wy_D zoyzs_1)KKg!rs^Xre&nJekXzB#2ovwwQG3?z@l0xLT_!!a2^6p!LCzRI{HED^*x)u zx{u=}Mjv!?bn5S!-4LZ9%(5H|v{l*vc)_mwrDCeqb-c``|4ZdegYWOY9NmUbbIrjA z8%1I9`g)2fyNrg&!S-6ls(ZwowWNxy^R;*2hKwris)_r(8I2= z;%ixM#B<5NFFuKeCExz~Wozc{RZDeWbHmO89!<$<@U8KAAzFKu@xriczm4jTSn#&= zS-^&MrQF*SU)Oa8@sOV^$%$p_XIHZKlzFgB#k3KinEa$|CQk4DavS_Pq;Qd zmKMvoe=KbhLxe^BBr=ve)s8(W&21=_Sw~`6I#em~O?$Mguer_KYI=CfH$O|U%P$lG zuI^xHfQ6M8R4BlH>&vVLs`876pS>!r2>xC9*JhRwktVfb%GHn--a;Ljs{53v+T%av zJFTh9GxJ5{hxY9eWa&7DC^F9Mk;af$j|A;$A2w_!Zcj5k54=f~w4_x~L8Xywq6(_o zE;2p$dpTa|%@@%f;z8dbd|6_8Y=>}A=hmN!+H?j=iYm(jE;X#u>YwuaeOi2#bzz!e z-Jb`=1S=K>DC)y&f84tB_6W)3IQt;N#=qgnf;A|~NUUvh=5WljVe5;XN4aJJ!a`Hn zf57}<^3kuxePU&KoWl(LNs!|VeU*y%<^#-hO6%6i?=&BV>-9xD8_r433)7gO0@pim zkyd)OK-IvVmIwKfL~4f(nW_p_y#n09SWmL1_xV=if>m>xKZ()VYIiAj8j0{kqRkrk zWworz19ZyB&XZd2vker})$HQ(W5e;Kf!B@{ZLilvu1JvOKV`-J^*Ivv{E#Hf%0tUnf=@srm!B4*8W`>d@T+5-c-D z-fUD1h6A%7G(u`hLJe9wTso7eMu)!h-e{O1dNgj=u5OZ@2QFdlt1EyW5`r=79TP{Ga`|XsiEZT zS>lL;V}(=lA#4Hd9CBi?+nWvv>}lK__X2V$_pkSr>GN-L?czmHAR#C{DdyMBr}ov- zH#MY8Uc%9Z9VpkvUoBn<+5?5W!m--DI9dRTNAqiH_nExgPcKkFs8ZmR04HyM+Ky<1 zyErW^>@IUXfS|%kr8%Uxb9Gy$BR;+C9?4kZtb4w2aOkY8!#nmi{ME|ckQ0$#Q>9)x zvxQO(vU#51Kdi!hN88+eF2tq^q2!kr8d{4BV{|FcuNGAgpOO!zrC{UpT{j4QM=w_&v^Y(7OLb>fj zuUZ`349z0tY7>mb-cRyAEVIn8*8K0Fx1a7|)_VG)jyb^u*j(gvM`?>eRR@M!e7L9( zntXtLV%_)QQsvmv;X{fq2$cfPaWRxxjTq1$G$z&MaYQ+Zk6N9T-qZz2 zk&Oifrouu}x5^32ERV{Gy@rqeGX)-4qdADd_RqTI;Eea}>6h_PxlrR+H0mk)9$uZo zcm{1>@q=SwH`c6ZD_k$=$Ud=7zM z|AGeAF?THo783nVe#l69V;j~i&$9{MA&EY=R@VC5niDo^_$oTr?4>IauWs2Cziph* zYq~qZ-zhSuZQ|HEiu!ckO@aKgT0F}G$WiSBjbibuf1HYp9~1k0BWK@Z2*3LsraFQ& z#NV)cu3WdjtNwfP{lOU>In3(tm2^sNLA|U?oaI+V<>TkMOU-|{KZvv+kfE4PMpL<% z3VKu~W0DoSb+dp($fdh9~(A+l*~E^zR} z##qD{j@IxHMSpS)F8eaKmGVY(^gDIXi{6LcH{PGe-yybb6%jpm=2%d)*|{qH9^toX zQ9r0VWd!PX_FkFTJ97Dzc0&PN0+RU#P<#@Pfb{;f=8gT$ks4ZvGe|Rg&E~UCdLR9- z;%R1o=+Cb$p!;XhRLbMCs$aFp06*_E-HL}?r7~TJSoI3)Z}rqfW=mO_njtS{Qn13U zfrcW3;639AE(=;(K|>vd-!&|}>mvRYcGMn)5PPc8^=|Hg`4vir7*=UVc@+~xiXC{7 z`dmy6Z0(yA#S8}8t2+_lyQv)4-!fH9Sl$T-I7|Gq-8kCF6&lgBj@0IibAgbRU(`Ep zp_hL%peWcr-i^UGcaSkOTCS-XnX~Yh1&=i$@-614h8)Tz*W^WP`Q(Ka9JF$w77`ZY z45Mb~IDxJO1CsCDb1;MI7^ZX;)(I6(dQ~Y2c#$tPX$^ILwGN-Av_QAncBbOsnq<}& zzw4=)BOm2x5b~T3M#Rx_pU|G;XhZfv-C|U#nF5jrv=I(LB+)^k-9cb+ipYNfT#usU zdSvix#@yY3D-Pf%9qQGG>JAbb&jK{u)E;@RX!x4Jm3L`BlLE%q3`&A~x|HHuXE)|X zKb8^b7%qgJ5JJ8WLiolbP}EJh=Ul$jog*M}6^hj~KJ_5>B3uAaO^GA}x)%cyC(-iE zSYH3AJbHk^7mLlpzG%cI1!LWb&hSJ&xC2jIt(k5^x^A@R|x- z6t^0l%kpCfEQMkTjtnETV=~DTmdQVZlgBJUygUgug$9xY1Mr@~o`m61fZ?f{;nx-N z`4Q9QYVv{;6a*4`Pt$I=;W}vqgpOFTt-nbB;K109e0zrxtV*?GMEfhvi)7F9*q3Hp z3Ow%n5#6lUR+AbnFSX;J|#A{}q6GobPYp zMs~9UMNtn>NrO`RnS6=~dQ4h&PwhP>M_ycL@m#GtE8j|YKfUviJbGWoJB{aY`fAif z+!FxzID7RmZW6g(O@m3xunhLT-y3ctU{}h|&y9k%kWt!0-K8{Mdfa+zHI})jB{oE6 zbIE6M=dsO>zs*#=&FmvMk3DVXNlLVKdb+g#q1Nlc4zge|SNY!8myI6g8JVv_-U~Rs zUo&-CMZRmf_1fq0iwd_asq1vAJ@ktP_3e=?jz)*Hg!dyK@1%dt=r{Iz^yhuX6+k5!y;bUT#2UL44uUrjnj|&Jk|mi80|Acix5jrSVO? zaV#Rg3leOJAw^V28UJd?f_I^42n5N(Y!;Y*)mxJNgf)H2^j*Qd0=crnr}sXDmX$s! zt6UE5m?~D>C_Z=&grlHY*FS88vF(#W`{|G0n%ML1!JYg{W8C@LpHw_ktq3l_eJXpW zw!tAS_OWJ!wqmjL!OM@DO&?p{RZ8xa_m@@7^?evPt6Wk61VTw1TtB`!(+_^47Ft%h zT_#U>=RlTOzC=-ebXNB4KMt8*sJ(r8OvWdc+E4Yjs&<}KL%vrYZ&Z>~exi6^wRIa3 zj3D)wtDJc93|#&Z^1dcQj{9J`f;zG4AIoQMR*r-aC@VbP&M3>;p_0cxilsRd_P3f- z{z)QHrN~(>b9g97h zU!I7$AILu8~Cdw+@Ll8mw_e;w={T8GN9fER`i}u^@D{_!9$9a9gOex^;^>8o8 z5e`(2(3Xour_wi`NH;3DHWtrlpMLSFHKXxfwDwzbZFyMr+^WH*zrOyQ4Ppch_9bCJ zd@%umi=sty!4-CCU4dqH`G&f%=1KW$AwWei4hmU>UgD`} zh`_g1P}2{qrp~bXtaRiY6z~^-uZTU`?Y^nFODl&5uC0aF+2*t6wu_mzlNpfz24 zPil?-M~Me};wir2iL7|43p^wV4_EkpCHS2_{QH^5cjj++ewG@lU5eP^@2uh9xfR;a z1xX5Z<>SIy!Sb0i7Z^bGJnQZ&VEwj2*+0PDKdKizUeQ=LLUS-e zDY@GJgRKweS@c*qH4~8?JM= z;(YLd&Au(R-j10Ovh$H8>oH#Hp_}@n6LeoJ3t>*sN0mt&oHq5`#GJ~zIb#=W17=Ob zvg{nRV&#Hd@XuWFZ0zIYdwpD9t&)|M(#c~6mlO9c2aUFv-U$NN!JRSJ2=$hsLA`pc zRIhGCu0H!HgZ@vQurbpX1}LssnhTydLVMmg2^)0OrXFHFj_A6?O zefSJY$^~~Ufsu}m-rpLah%fa%CDxpKt@CpiWQfx=xyb01&L{i*@iU`d)AoaEVT03ewx+|Ar+(?*e8W^jQbQ5o4j&Yr9*%(XiqSNnAQHO})03g` z%XztznUjbGI)jC2n_02w*T`J}>;SyQeEMxO$Jp#qj2qP1TFhWukbF0NgM&a!`q@D} zDoF>#DZnpTu0J&v^CRFNlHv1d6yK_8ro@tJW*2!4`qgYJ?-?wKZZ8vBmW3i&OBCQa z%@lIEzh#C9Y_&HP<>ANnv_(dcH%7FV5-a?+D}%75i9=hABGEm$oBg*pN$7wUhWDRr z|AX!g=J9^~<_prUKp?wyg-GKOA zO42;pKX`a_Oy@WR~disiT+I6m~D8#5O&HVTDcj%vl8jE8gl+<_}`4)VS@Kr ziSkL|_U=Lov|A5;8?lC*pKMlcQX;mE^rc>OXPmd%okcHPtomG$i0_l_{p=C@kND{% zbN=!R&6OMRGH3V#Wq4}KxnFv9EDkyb=n#*U)d4CFHEh~cEw22TXY@D@Z0*iYHv+ebuxu*T4QgS{?U6!u9;aOEB+xVn~6zkQ+ChADDh!} zhD7M0gGmw1+ZgNUwW0V}lQVtF?|W{hXe$Tj*&cJD?)Q#^x$5sNww`>^>3=u(_NT}A z*8stS$}owl`R42V)A!m=hw{h@xozqfmOO+nZVOWJY>)Sy`Z8>k7+INo>}p?xg?=J` zSG+!&t*o*2;kE@%;0`_VyAPTPy%h3lJary@u6cyqJ+z7M%_YiNS;R;dPm8cy?6 z@ci!t_FKQ!jcNo5t(uY00akTK@$5zzT=kz*qF4#hj9UaHUZCsxqFijTs(nOFA)&cm z;Z&0W(8I015A8FKi$xDH|6vb`5m?4ae@bv+w++6JP4?U-$Gl2l)DzR@dE;cleK*WK zt)2Y!otipxjpj z0G5L9xhB5+Ke9Zj3LH4hh@k|vJn8Ja)!Lezab~@IgBQ@A#mK_@Dr!w*)}15K3;FHp#lav1jfS zFmcI?LpEr8ym-}T&SUo1G_CFuJLCPJ1w^aF;mdzxr@+y&i0(skh+oyl-Fg0qspIAAz!J)XQP>ol449FOar`72_}berS~ zkDiF73NGeU9@z@+NZ0jbs#I-E;IfUS)``wGp#gJeM;xE>#-o24Y34A^3;&pS_ zo@u~hJy4(*Xb(SG5^CEfhbAA&LhPvdU^s1L7gb+yb_)RO`QJPYcR922xMR{7PW0r!S}wc#yKmC`m-9l1IX7t zR~6tQdyl@aN`gYunhMBs)_um7EIW=wZJ zlPM&r05lHz%7t7H#ar(pU0*V>ax=+twJb63xOR)Zb4gQmddTtjgp8Jk`!4sbk1s6M zoVa<4zAyUHCE?DWGV{o4C%EEif-S#4EH-7AQt}J)MQ1U-pFjz)8NDnCNat_(t)&xM zlWg_g;l!w?h~lL&)lY30IBPUj&DTA%HHk-ao*-s^j~vvC>Y_9Hs>jRl+PosRkWcqS zXGoiPaGSf4gqQQx7gsGHYa+auTCqn9TM1^#vUirdxiXLuyZfMRvrtlycR0i#mNIy^ z{UI1dHJRTLe#31}>_g`eX#|L+AAyo%xW^S!+>yf=Q*sd_o0l+FRUq(T`YkzpZa7oHydd5t<^V(o;s@pXI(7n5ELy)1CF<6T)a<`6!#GzN6p_ zMhHQB8;$)cqy2NrpuU>Mu`<~CS|FEXR^P3t>npze#3SP<=XFM@|Lu20hyO);(R@Tm z=s6qz_j$7-USF`o7L;tu{p%YAg=l)#`(OR>$DgV@|58|$_C|``$;ZX*@U>CS9?A*P zjlecT$im-WnRv8RZ+e^0ozH6V#wIy(A-r@gY%jh%YWpDUTc^56<(d?T=lqo5Cw$}a z=q*WeauM+WfA>M^LzVZm+G@(V&*v!Gj@vD6J`a8ZO4dXXx*xr_z9XDr$7w>fsCqgNN#O53PlLqn-Xw7Pa9zpZAN$#UPdc$EHQc7|S>z{PgNuh#e&#Q*wn zUmK5e{0AOT=KbjYAcKTAx50mImYrBdUe#u~X{oMX9Ns2n?%A0BX5YRoJ)~01W;&YS zqJvf&rd>L~-BPqs>Ax|;r-Xeo5uQ;Y^sdJ$;1F?bITB#217*ZZKDMB4C$T#2(VDM| z;X4(d-FTh%LaP3yak7J!)mGLB@US8yqGw>@tSskPqORZNsSydzb0rkU{OReeThw&m ze6C-i$kuyJiNL8fWKZMGSO2*-hYWnp^t{Vy)HKd6HyV+7j9seOcxt5&^AwhBB92yW ze~>$GY41AvI2AT^Sm`q{1`DqCY3VcjP`6-_NG8E3xa)s2JOtuW-MlBfk4&xZ6h*=c z&Sm|AhwGQMa{}w=LCMU1-+qe+-RY6l-+v{@_TAp}z6kpbM>iC9RZ054R^cHPdN>oA zl--wZ>UQr0KDPgc|H!6)@WZ4kbpXxb`^{DJ21P$EmMvI)RB#*~A4yOfb3@WWwIctj z_sqrM3C|@6LdaOtYy$fsiNsTfzWU!^w|q*@3A9Sjt#k!y->YLubr_MY4{YmXx@7Cb z@D8`>TgNcJWW5+T_cI^ms@~$y>EYPNo`u#9_%|#p$h!`4gw5~1H9Si@pC<;FTSe~C zyUUz&_{F$+O3zon(Q3Rsc|6A~aqD0GWu{71*uv}9L(PR2TgdZXJ=K+}9_;R3)ehaN z@{7}^#{v??@CXq@h@3k_W0yzkvdPwpyauLIo zg&%z{KuIqR3eW6N{X#=pLmQxC)335Oqw*H^MrpS!{WqWZe{CBc5>vGW8ZyGH7h-Il zc*aeYajV8+8Pv>1j9@~I+oBXlcsmm*p1A|jcT2FF4$Hx@$-ZiL8)VPQBj zWE#}g9u)DRb^gZ>g$r4@S;EGRSOId-R>3#!i64dM?W?aIpwoS`6(W1ChV0()U7j^FjOD>bv7ADQzZ@C3L&-p~&63g16;gH3B-szG0Eo zq&M&w6)_mc2}bek^T@c01yz@7M^jBBpSUlI0E@XiuUL5Bo-MC-pxfc%Cg&O~_t;E0 zMhB(Z2<7xeNAa_uxiAJmntXVd;>r(}J6-Pxa&*Bj0IeL$x>gZSb!>2U&nd*MP`yuE z-g7_$Bm@o_!36pKc-RPy#Y0SkvHyXhIZmML_9$$6PeNf2@kL!vVnu-XYp;_g||Zxwp854GQt z_TlQZZlN9+uR}Q8qv=Pw)hNDM?siZ3@j`n*5BTE(cR^@1t+)VeSQ49V7P^|gzvgcL zXNmq=wf;J@{(7hWF9H1xvHgwd{a*|Fo9g(^cCKVZ7RsL2Bd_SIk;5(I`u8fYC zShL!+nCtqt(pbT_ED)=cE?-jAbL*ZGw;s&hzPD_BgBQK&hXZdm2S%KLXT@sa?ov550+Ss*qlJUh68h5;I+{1*LJ%0D?+96*c9C0bCVRPJckI2l+z@NL zx(z9ceZAA~qGSEt5Cf%pMsW46?h8>P6|*J9fQv#7ydF#oCc_-dU46&z1hq7)+4uFc z(8HmXjusOml3V;S*WqvVk7RzXBoAcb4bq25N!3GFR2`hiCH^V_ViXjFA~2~TNkpye zjW{enD7c#R*zB$x8X}))n02q%iWw7TiE*&J_TKzJW?^hyL5B238=l60?~Y{fOS}Lm z{2d@4!bSp}nD)Y1_LE?qjc<8n+qT6@wEvF8`KiJf)OjZB{wgH+ex+q0LkYmjoyJGa z*`yM8QOHG7D)T}C-}*c1Cd*E@{0Bz;6~>7Ymj-XSa%|>6@$35&Yeyx@G+WMhFtc`Sh}pb_IwAY*gw zGv&ssnwLC$HW89N!NWe8Df5*yVqA7a>Pm2ux22}+*4VbCpo_1fkvfmD`M6x*Sed+e z=DL6=yh&P^bj#0(_Zi|zqK2q>AsE4{+Bs=WHu3fTxa8{OBYg{X{RCt<3~Cu4X%ugz zZedqx_BiLK%jtxxB9BeIh0DdH`rKruC6M;D+3za_qn_qT?fA3H@#8u+ewb;X{#|5? zg_p1qx@h7}>8IM~Fad(HMu&x;q#E&&-dze*DAgt*JHW&e9kaj;GsiUMI} zXLX*n@z1UGxoteNrO#&Gk*1rzX#`=^lhqb?*6RL{&!d5&)`fgLLt!1$~4Y4J0hXMyaf%QtDkl(WsETi z%k1disG+8%TvXVvXIp!=fXyKMH)oyB^+6dYj?MzPtz#U`N0wJ@t8(O4;%1*s*J$i6 z^nn)ZJ7;Mat>?C2o~p7V40EKBi(59S}o^*k$E!{EF#{$7(z2tiu`TCBED9QZWmgo{}&8B&R_y2TxDjyah=q=2Wk(GwMr

Xr0uz5gGu*sj$4_mc0?5!pP(4j7?eB$y~L{efB}aovjr%(fC9_%L%nT z38z}mvdQX#Kp-rfXCUtdqN6vbiYClFcO^~+*ZRW@Bs zz!+=kvU?)!vWUnxn0FR*FEVhyey8iFz@#i%ZjF3;1XE5-*>Jb`nE{Wr!$Z9Yq}fv?P7!S-^b#Z!oD*_EWNSXi@hFmKWD~RiGk26 zS?g{r14-{nbRH2>yb@@QUzI9BSaE@bNK|FMywf;}IL#br*u@ zz46kkzlLyBzPls2bHita`i+lggaUv^O(a0V*`3{scM{AK=rv(XrI^&LoM}21;{R`8 z<)C4?O9HvSZ^ebnz-Ue|>LDEH-R(&wzy9bcp5X;bLnYmKbK!;k85*Y){?2i7P~$Zz0Dc^a4vs7o9kn=N1M;Kz%rzN_ zZKk2^T|EfgKd>wGnx)yC7CAgp#OB^00m*>WrNK)E3!ZUZ>2T)1Z`TQi_ez!9X zpYJhpyXf#X*9~s&`vu@0h$BB*f76}+75BY9oI+Lh;qQ^h(rMJKPO1w>PrQRZy`rGY zijHpFPh~vhTlkg16~E=3AoK1{&&Ln)eRu2vK(<&+z=(H_NMWwjKVsjKRiNF!Ckqb{ z(n#Be)$d(Lv0|G%BO=bsm_!ZC+;BL(*|g3Y^FB#m6rMu3x4wN+G5&~UI#)hSxW zUfGq}3A>{qie!}%Oh?3-X~Y#spB3!TSkk7FFIL~y3W;xL5mkmUme9X#JAGSns@XPG z+Jj~S3$gK>=Dpd7P$qxM&+-&;UZ;6pSaRa>c)o-)wL2{oO^6OI4GryDc0(Q}VzAaj z=xC#y&YwXb@4GLo`C=6KTit?P zZw~*fuG)Fc1&XrU!vrOM3CbM&E7oau@v1S-ih!}nx@Kd?5e@D8vbw{Bw=eC7B_M=llQab^}T4j3+5*3K)4k=Oj!R{}{b zBxly$XShcR$aPTcA_$3%>1HC@;)Gec5w4TXJ4uK< zz%(CO^^;P_ctR^^5r+3G+2h1MIxD+%L+sR#b1Q?r@mLpMq(&XwDuybZtthi!m;GXv?t1A{4w~) zVC>7l!WSheawgKl?BV-T4qRr$$-SAXGT(+Y)e-&%%c$lpAXu(Qi|fYtI#k)B=5sCc z5DhEt*0B>KKCf}-&S*0i_OON+UH(2& zZD)Gras4-Ud+s$)ASuF3v^a%1<^YlwjnW7VW6z29pNXz~AOHllha;e&fRCj#FMUF^O`3GBsE9p6__x zQVsx<0p9KWGb#KlbPsN6D_57&uCW|A_e+y^GPK(mC%6$9_>G?eklVc;VjJT)E)zMu z2USU_c5ZJdq8gHdr{E41E2TopC-pG`AK%9N@WCGo59&8f2oam~fbQwaeZ)OAu$dPS zE87{)-{8HO@oq~mAcCY zA9L7i`Hj{(3!`#EIrn>nkoRvSy_Lpyj3u|MlwO)-Hl>hKQVZHlxq5y z>23l4DIae3v6{09#^z|PTtoh@Sdhs50_XHp{Xfox+v6%znV8NyQ$joKOfr>Ot>(3% zK|7MBM8wa5b*}a!U6s3xrr1PA036mwL0LVUS~}$Zn0D9ZfNkz`6N;$X8zK`{U#aYf zfDX%SJC<0bRfR+lV`qCUY*qxjn3$~5mSXOjC)_CSZm#ncQr`P6MV04fA3jwNQbkQC zS%|?+pUo0+{qqL!O!Bq5JO^V#D&x^U5=}E_wB0Jw(0iwc48OKfa<7LMHtWv#c-7Hz zwy%T`CPQZH2er=6vc81}tZ`R4>nWj3wYc;j6j%r?3BDIy`TX2~qm`4Kw};mDQbn<2 zPMd<%YBkf6ze#}kNQ^l^c=}>KqVa$3$wNY1@?Eq8_v{J^g6W@cxM?~Bhxj;tev-8O z7S9D)s`u*6b%^+i6`#h48YMr9#vC*Crw2O$c@mv;+xebPaaI{px8MO4IdEOQZmlzCPpIo>&)$PSO7N%sf{T60bbL#m?^10 zWL2i(l;I3v?6ljz(%8dDEwBz;Z7hw(k@zYPUX><-bhw0WS)9!FdChH4sSnzF$@DAL z+$l<#MpvJrk(ivw@;ZHpk?#Q^s-kB!Kw$3Gi~zdSCl} z+2vqnBBSXdT+u$l>C}M@+c=o(Rqr80ePu$T==n*Rw+C^h%}qn-*Ek&)4Bua8%R`5f zKd`pUR|pg435cWwj?{Jga_zfXWrvVQATm9bWmS!5A0Wk>Gvc2F@<(&PG>J#b%j`w^ zf&*k2xE~y?&5S?{gvgE_&a%CGb4Q;clYo(co5}?k{NIp>G5+ zeDWGYGU&4QUd0*yeg5uc#j34qYvIcdvg2p1o8n_i<^KtZI7ew>$DvOn+IPnfn0UV; zW0z8jIkJFARowpb1_MI!iJccY39gya`6vGh;Qd#BC($E6x-=3m@M1~ccGeN0{okEI z;;O&nPrD5amAXxSAjqYu0QegF(@#M>pKiSj8`~%DF7C?=^nE6YqC7R^>`2$+ez48G zaY{egrY8Sjv9tnUYq+I$P&-=xlHZ0*wy5)Y^3_@P-sKPVTLV;Vj0wV5sQEX4+fUy? zuT1VO!)MQdk#^`CPHS1{d@~jx#B9buqCmzMd~3}q_jt- zBep0aekr5K!*u@nMC@F17%64OirctH0--E=W)XlGmd*7vpQta^d!SR@J-p93Tzvop zICn`KEs>Be|9eQtZM^J^fp?b+bI(W>vYaiCGV%}_QjGAK9;-8-eOSdJhRyhaD!T=0 zB6#LFM!3R2xP}`UM5NHut#a8#Lxm#76R8e>C1ZG+r*r=%EH+S2^B#52Ss+YjAM;Tx z({?2@_)}7*M)><=aRe|2P%}aLn4U|MRE^KFlrQmnqNGf^pbQ|XQh z5T%V^3KVAlduBG*+PldZNq!1~GOqE2=uvd!GfqT=(xSpv=Pe(CKoTTX36BI*hhJBO zN^pd`@^pE*6GN`Ly^;Y9sxZV6P7~WHvTMiv**mIQM3k+B zXAeQ1&=XG^K{K1p?>l$J5F`ChJ651XMubg$HcXviQjlX%cLS%%kRLH~CHcH;hRIOl>zzn4Xw$37GkoQi<8?1wG78m{a$iOSob; zYwy-1&ej}?^>)Bw)K) zW_u{`_`K}#KLIppIhv*%o@XeJ?m{05z-M{k{N)ZBf{wc7j&}v0%$Er$3FwJgl|&M{ zN_6JUyJlq$*6;u0>&AEAmoulHUDuxKQrhl)SpLIGcLQ~Q!;G%XZ04!KlAz~@QqRM3 z{qha+Q+oN!P_Ky%dKKXI`BR_NQeTO8CLN{E>Kva*Jh?Z|sSo7V)8;OWWr|YR2v3NF^nyN=jp%kI!s943L)U*~H+ef}KEN22T+uyi;j#B;1 z$H;3ZX-{)*G)3HEX@+Ivh`$vm^YvD;ky=G3PffR=QV)P9QsK{+x90=)aSAhAs-yWl zseSO3I5{zp+0>f&{KT8JT$02zqtb=^+6Dha3kwmQ89aQn?VP@h)*NmzH3xcFSIhh7MJXT#DRI=2kCw{D)-VV^dlt4++Z&!QrEdXmy8qW0$qk zT~RYVOsp1YhvFe7cBd$jt3|}Ma~}oPKoj3ZH;lU3No(bCMN(kraeZ#O(qgo+)wE2` zMl1+d!)`j~A?sG=PS+ZVyJEPt>ATx-=u#Mzs0bES)f+pl+OT7s3{;uA=hwIy)boC_ zcNya)0qL>GU*0O_zQSl^egU@nF;=8@6LD+iulk#dy<)UG&qDWdFO$4quTQxR_9t;Zl5JODegos&;>Ek*9loaIC*Lg z&5ju(nb-Hj-Mfy`$d$^1HIHeZ1!MOvP3#ZW5+91{hNBP1Y=3*6n1-Jhxa(z%D=s#0 zz3`-b!Ezd_6TFy3f$vhB(pIhryNSlIQgy4gXiLFM5E}@!b}*8vOL1W)+&*hne$hCn zOVe+fr`hEzO+DQ$ae74*Z%d>_hm?^V4EfOa_xzF6i}kmpebJFD005F40MWF7l#V`- z)pv{UJEG*}Av0Z|&N5ugQ4CJ9h>#lke3v9<6Eu1RQZQBph0yZOvLtG+AFYNPMCxVk%~d| z58LpIzGs?o(?Go~<7EWv&u6a(e(nBy#-;dCmbsUT_^zn8TeI&x{b$`%c{!PN>1EzJ zhke#v+8%+La6}NG8WRTg#)t%fb-@_+2rxP36p;?TMb#tZ9xl#auzAE_+=4J@Yvj!L zdpmGy0y(p~h@ig!%d|+LqKR+z-r7lGkKXkNO6pYq$F@X`qDFtg!QcCIKNSC zOnGG zS%x&lz!W!`^lyH)>@ST>aPYgaQs9E1u2BF`MKM!DAN`@b9okpZLej7s|3@3i+MQ zm%?!RY2v#q1m8x3SG8Mriyk+$B)!rT>(pV9{Er*8-@e_z{;I`66?G*2uU%DlT$U8y zBXQN8(A?Jc{!cH_RsF|{+Yz{_okl5bVo=@~tIqHCZb_!cDlSX#yQXAtN8;Y9%1hoxHyEXT1$HDzGY0mxON;C8kwDIH}gi~GY zMbmwCK5*mo$DpyaRqD+W4$U69f7%?0>W=CE6%|}(e3U0`BoUMHcGvF7EUjHgYnzZ& zp9sHdAt!{~S|k^YKfaybrMUuLNxL3Ta%+DayhwPZ7cee+`ng||`0wu3sAfoj@xMh; z<89+97-l#xq6ff=q=s~i6V#;WJ4)WE129QV{No-~6z6+}#Vn0Ce_t)S1Ro63AH!le zLLYkbXL4dA!ya#bkdYw{-F8 z#zAh;b#^;-BeNv!i1Y^FPmOXFotCCr)6jPdG(G+hSN-b!!mOPlXz`i;Mocv*(#=p| zB)Ez?KX`O-bumU|@&0jV6r-ww>*PB}JEn}#rp-v@`&B&|s#%^kZ7+^TKbXR7D=A7qyrSC@G-P|`1d2_<9J$P4gUG2KK-cjN{BS|7|OoNL!|mv4`xh;si! zLAj*q`JdJ0Ka~58-+UL+62urnLyMI2Z|}_ zdwpreC5;)p6r@tZXa^c1)b1G-n6(YDLhNJF)n+p_lXoX4+T#Z%m%W&(Y{wC-)nDeR8DpcL~o8K*KW~5Lhn)#c=QT=)>Pjana`%{BBLZ-;; zH!^n?iUv4a`cdYO%0sjKuWk{A^C+~S8@@79+xUO?U~qse${*oT(h>|1wIjSeE~vXP z{b5G_k7l*3${dBY?|C_Mqx6Q?U1jC}K)suVkMoskVzt`>9LQBQ*g8ukzj}8kvj^Kl z)!N~(9};#Nl6%8IW|dp6Bk4T6sMl8Vd$p9$PUh=#Q|x~89{*p_VtHAs9pbkgs+I}# zV(x6B3Uw#s(npuw6xG5;fsZr)F22<1FQR1k1U3q;=vDk9&rx@?3OAE$C0;x)ffk=%PH<(&5VGX=pm@EVg9 zdpNwWk*@_Sdzb13PD1Ev)7ZR*#q}FX9JxMW^=c2Q9W$mqVJ5Nd`2Ax%Oy^T0g^ZoW z<+0QI%>~`%k<;B{e|6w6;U#%&gk7m$BUHIa)qZ7Z|5S&4iRVd}b|n@WbkTJ2LsBeO zkA;Xd6?k<8X6BGvbx|15m|)y_4R$mK+2|oiOzqgNV|o@fP)h0?qloqD#XlXys9qb9 z;8C~26SIJ>%C9(cLl$!3rY<6ZyT>y6hC{!E=+%MpyI!2(I-2Q4#2llmcV6I#!h*=f zd1!o|&{?mW$XF_fn)wJfWEUc0Pm=E8Q<9wL3tj35n8fcV#W_Uqgc9h+p&^$=ahPrG zQo3~A_tr3>^o=(HFT(WIxTFJ~?XR1#6y-Qlp@FpBcP%bVc0-l`w(d^bG<|KMxRdkMW%#j1RI(s!9q^b0Y!)#^aeZ*4y2NV6hj zHk%o3Pt&l7)vdckZ!(d0-Y4Jr&d37$6f3a|2f?o`WQbhrP*q{O*jT+pKkI~-Q=)>V;ZsFVot z+^jCI#B`-P&}qZ7l1j|5#x9 z7&n!rM#nT`@zN*S;|A&vV@k7FzL$Z2yc+-0^sD2ydV+46Fw8#v=slo&Wa8J5@vwrF z>6T|@*sFfDm9k|f>~IOgFrMTpW#$sjPOBoDH%e_R(>iok6WzJiW>$eD)e-8|SUP&l z3>C;Bm_#xdmW2sl(Dz9Q|9mj|%Axh`ucT!2lCZVqT}+~lq3VbkhbW?xEBZOL#4s905NPjhQaj&n^34Z1YQ~kVNCRw+tls*iJ!f0 z%kgR@FUnX$3YvI1aG8Sl8KzmwVe)OM++u?H_(L| zV>0CLmy0DIY(+^j|G z&;gjz@eDBaf+5k-<_+Yu$K(Y1V=BIA>I@h9zxrf&J5f9!B1Og~cboY|%4?MdB26EN z!!{$z9%1N1F6Jf>~0-RG36pEjbz8m)$Nq&j`K5H+jSo0X z+9s-jJ9eCfL|~*xN}q<7%f<(|H4(GhK>gFFnitN}w8p7{7TF;404BHsr8#`OIYJva z#%MXe;1L|)$teL|b!xU{7p}Q2-gnY`ZdGKu+uSjB<)vD*8xE{iUi{Bwgr`=R>!e|% z_JAIUbJvcg(Y4c124Xq^w-MrDPUU$Qu~X5vv5>Nm)4=GG%6RiLp%w+1^E6Vfib}zW zDQg4b>719yX!MXU!oN^qk}mosJDS)P=B`yc`x=qpV-c^B$gi}lAtS~co>bd+A2?2Q zxKD@)pUgTZeti6 zPyacVlgF2_-mj0S8K=>HRv3{6*P{nqSGb4J@OUI+ z#e_VkD5p5T^n*nGuzKj|_I=*T*_Zct3u*VfWt5($=1jo3o7R|Sivi#cY3|1!EU(Js z3bzV9;BUuFMMQK+NgQuX#{8UR?PFucF>%V#m zg;Q;$oHpUfq?W22Nj*M9Irh*1*ABHwX#_q$-+51+D8NcbmOY*US8Nu-xsy z)7v)|mvBG5XXd1sUrsSeR!SJY<}fme^|JY&8t<#sJ+w4`KZF09grj&Gm7HjBa)!Nr zhJ%fUBd3Praz@jBMstlui>HR#_N+^OMxa&c&*=Y;0nuoDeQFGnH#wH${&r8lQ1m81FW&BcY2@5o%yO%--Fl5BFGvM361xd<+Mr=Iy%qI(=a;vXXa@LQOPOu z+tZ@GfQ7yvjasA5fM)BE%H)*M5nK7DoyK2_G(0$?8$}DN14e<)-*Bwgy}n#F~nMK?00Z- zY8BH3j8=t{;2|v4zash}I4OXmUqI5t;+Tmht=6HB?0y-SV^qlN9zp%dlTD!*LzA9q z#ldOoK{NI7)Eoxv&>;_vV+nVehwb|x!Lv96eR3dAhI8MJsOQgdxcAx%tU_-389D! z18CN)(NZ>B(0rq(f8atR#MWW-D{S0ib;ejQ(^oP}u~xxtJVU0KLe&Vv)KSDWgk;o1 z!$;99OP!oyNE#4^I^CD6aTP{x59{dUYT@~0Yp?$rMWeOHU`C-CAi-+p;ip;V*L&=z zs7t}W7gckM;XPIrXW_f-Bj|R)I7Xl7$t*sK;AjG=hGLjE0I~&ugOn0b!*F`qk%eHG zCqe}gp$roMnUWnh76wcpxYdft^g!Gi%`Zp%pQ^2}H}P^1e9@ZxSbQFN&`(s5acYos z)JZ9*WkOMFgT|iwAXwld?<@Zh)v}QOE-Iu@h~v4=TQ0$;JgpCuw7L@XPVnxS^^ zx*{fY*GmUtB7dI74=K7*G;&4(Mkcc&7D_gWaBZPDa%N%*aNUChwf?sixwm$I0BFDq?CD>mOJN9 zkp`!JR>O9#CrEXe992`QkkM=AZxiVMgW17lon#6W=%%b!2VzkP2iNg1j{?*;Zg3?G zd>+jOvxCR8zRhTb6E~(P{;p7I9Cw=558<-YIVw zWepL{O7LOHML!fHTID{qE1T2hHroLw+OZJR17b+dj&GpNP!&Svc^WUg^=F36;D{sO^ry0HF7`e7R;x$ zv6jvW*fD;nf@}!1t~`HtzuK*(^!dz(ZwIAwU5Vp4?A}-sgla|rj?1-(ECj*4)Oqx; zl>yO4V)j#AHIxhm3NKMA(&;4`uoFG8E8j!ifxIgAV9#x0Z76wZ;&}gqtOtVY8zhoy0@NmU(Hmz|AF16^g+Blfbue>t8?W4r_zI5@Rx79b1NEDXD3@bY=M~ReS52=tSoI$wZTcv1{Fw2 zMT;uH)Sd#0qF0FGyQ539VSf_C`mDcptIezhpi3=f>Ci__M2yM5tYR|e-Rb_{UH6_lZ^A-M37m2yY2+`*6~X;Ot)$KN`0TB`A99nLx3m4lj^1{ z56^@-_F}?h(jm)pPj$V$3qsWUSGRI z^KA{T4DVoYO<}MQL3v%5IXCT@&iEO(gIwl_6Y~qb9E{~Y{QIZt$zaX_9rYXI{1k2Q z!t0)p>;t~nPk%>Y7G1g**{PQn6(96m>V2JEISpP0b9}z$oNZfd>f*GXxe}#Ado+cO z^^mTkvR0pTuR2k$?c86Y?}7Tor{5}F`@6#P&GUO3bVW07{Wb@*`w3wFM06AF`}yLP zMTeXv*LUlX56^zYp^LQLxnSs}9a*laFaK?Qo5fvZS~+4kn~1nZuWswIuwmgl$E9-wS<)^+pm#J_6qIy#K*K6y6=<9m{Jo{-2zU3>a^qO*+9m_dOt;|2jJt>0i zSeC~sPI&HZ{inVcY~Aza^WLK;uniDH^1o*lb2$cIVwnotXEpj3mnN?HQ_4Fdc{V7} zg#y*KXYV_f<-b%n6n=jG+MEdLO{(uTFeq9`a750g`Tsq1#% zeO=>Hd#T{-ZmC$W^_kqDfJ)WRV=OzCdCUE)%<+Q~J)TGZ9-e>L9LclL2%D+;xIJFV zC>tyLVztl+wlL_N%*aN1jOTNM~-#f3?ro zEQM*Jxh(+&@|kd{(Se72*zp*L#QTG@mJzu|LiRR1A&$K$MovEzbHK_f2^}wpsWjPy z=_y@YlF!X<|AA{}nVICS9%B+Z@i*i1QA@}YKn220eD0Nvw^=) z5BlB^E8QClS7ocL$E>@I#mL~+r}q}+DTOT_dN8__IW`5( zdf^PB&Cfr%c`O8*VgzcehhB2jK9H`OxHa4JF;P<0vWl)8N25CFR1J$03-5|8t9+7I zx9jBfgOHzPi+peu8qN7IKt#N8yy@j^^`lW0Pv0i3a%a=qBMejmnhYQ+WiD8o`-edp z(1;B6?68;r+2_k7tCiLt;?1?4sYS?#E9JC$RWC)ITcQi%BzmtO#`E@>tw^o1ljulhq&9Bca^HB=Xn%T6kKHri+5^!alKIW5gLsKCPQ<{}uL$ zh>WD0s$&3oV%Z-@P#8~c*~!3-H&lPd_VM{oM^Lq{6yDe$@__$ZYVsW-P-1Q)Pb*j4 zq~|`kOU*}ReB)m`gxAUMjT=-F)1?OfrKKd?BcVLYg(D>8W}ue z8DXu{$y)ZkYxB~pEpg9~id#SArr>&uX5#DS3ho<8TeCPByp+$YpEh$H3$x&lPk*~* zYZB{fP6zS8m|nSv3e5Lr6@1>+dmI$pH|NzZVbqwdt^EP_mu6kWIxVTgeEpt$t9{0# zx(c%9ly4ZO?_coiCyjuj8n zqIvC1578|Pb_*<=J69yuIn`!+IBURdV!=b-M-^$anrl&`$0&AJCr&{a4%|$JggYy+ z7*|&kIW}aU+y_*Q5xp(xo952X`p0ncwBFP|C%MX6`vE8eJBW>*#GZ8Zt3-zqw%hAu z&OK|%@p7eE3zvMO;QS{$u$MSmy~XCBW^%q-etty zjLD(au8%GGCaJudByPT`MuYRaP1syWT)A;&z~Km z+#W;Fcft%R*L3RR1e})AM=rW#e~0;enxI@S#`HxGA6f3c%J@4}Nr8b$zouOy`=P)3 z1+W$KgzTFOeZM~xU-m)Qp~kxAI9pa$>QL6f&RWR5)n9|FRQ@{FXqbnm=dVBma`S~dv;=e`LR`L~Z(bmNOb+u?1p5??Zx>mKTNHx&7KDU^T4Z#&ReztWxTgcfm zB1;YWA$d3)aTQDWt?boq07;EM$)C0BitDH<<&oT%F4Of!Ml6o zh1YFwxRt-Nj{P_7^!D7A0=d6B9Q68Ahsb!rP$SugvD$B|KYdkq`TiWocd>KTmk|_p z^%JjnR66>TZysX0C0`v3sP(Wv@j#enPr|wIZ?P&@l;tYH^hxynZbh_9R>)ibmlXH) zCLg?(H6`&^BoR9DrgnZ!H5)*G%S--(_Ad7Ii=NlNLY1>nv>=usT(f<7*2}FIK~-BW z2e(7@LqQoAVe>w(SuL44TAsf=3LQ^_xpph?>%F|?9K!o9EUrI{ax+Y}B4X@mC^PDr zPiJULC$p-hmbw5W_n8Y)4?~`fk<1LEY`JUH65*g1Za=Hbaw+pG3TC<;+V&ulT$+TQ z)&w!@_2a?|6%%c%igWa0d%6vOBgx2A|8@v$u5j(HRlw%s2) zKk1@Z5x=Mh|GKU5`YgWd0j$=7ed;nUi6!1VibT&M48hFNO`s{lX{0a-SI{=ic5C(}7e zQT<$@=`f;?GEOj8E_(U8|?Iq9AUElPRr` zuHYa-tDt>vi0TozJ()%ZM6`p2Xqu3pdQ%9ckp5YrP)AT+qU9G%(*oY)J?Oky%0gX| z>E3zYNV=f9NiYF>6T8WutIYpCn7_D_zx*~|6h{_VANRwhVCzl6PG!N~V8M1Pr72K& zEL`|YzwpeZ@N9?aqO$PsVBz^&LgB?jlKaV^6@4s8PClp94H*Fo8Nx2T!BWm+X@{^- zks?MbEQ4zil?eF$Z$>VF#?yq#s+BI>8%hZPPx0zHM^I$|$idUlVCc$^sD&CJxMaF- zCJ^`3w86m=m4>{L-+AMebj5%!0Zs7?Q>tH8YA{r4v|DPNQyPvZOT-sgxRyQmTrgom zZZcG6vs?CZ!$~^GzHW`sYg0su*4lW`$5>iyT+LP4d6JEh_w+ zuK*{P!Vs0YR=tZQR8>}0RS#9YqXdT|swz~7SP|8qT&tU7t6Qt8TkjA(LlCu5)^v*0 zwC`4Tz64=EV_9Nr2C8a?bBacGYZxhO$E)($*>apr$roTCKapbL6rv3iN?{Q3YCZJt z5w$dit_uwjUIi2IU;qP+N~X)f(ug5T(fpO^RqwMKN)(6E025&ADAV8~MPklh|3y9d z-?z!LiLr*%fACT<5rE;lp@R>a2A#aEU5p8xRpJKeb+%>_2;s^X)Ve!NLWN1DPT#U%G zfwcZN{65tn`1omSUhYSwN3Gr8Kbk*`FR0FNH!1D+Y-ep|&r3-@kOSH|#UxplY})gLX=_PSPM8aXW4w{4T{e3%VadYuHJ_ z(d8b8rPOYMqU@et>?eEn+QpdiF>bPe6QR>4_i>ToN}*<;TMx99r|B; zY=V04=Jh$%^!{tZ;Mn`Z-$wY9Lv3AlG0Z+`TI{Z{S5ue_l&x@=1RJ$Fn{r@W^kXBC(s6%AqoM!qB_;p%O80 zCLCP3KlGkzxVU|&mSgyn`*79Qq2`+52DRa~{o%@m;V)ue%Q(JvyMOI<|JoJ*be<~aCWC?hRTKs7cY4f@wgnFD-eEbGm z%IGo9oG{L+J|1k%D0l?b#C`3y&R2&`bg4}UcuX9|PILrKh}I5^A51h;O-geP%Nk9- zcb}Bt1UsRNlkNeM2%>|pBk4R-I^v@!k12iismYotqx=!Q1HzQ4(TIuo^r|6|q*N$c zwhuAh`Fdgc(RG_BxL*P?qt-B3@O;M3Y$h{h=HB?s?#CIGlWB+A89$qE#nRvG6TbOy zqJpShy*L>$|1pHA&xX{pMAUxEPx2`psa1iFAG%}D`DlNVQEluS)bu1ApVBLXzo1yPEjIg_HI^kcfLUA`It z%5l`cFf^_B&ko3yznt0x>?dF5 z>D-g4FJLtGr7Vnfi_A0tYsV^Q0UcaojlYgA9Y=j$PeY&tX7@6sC6;A9?G#2=x$4&W zY}bU4nNQzjx(;UQcy2HiY_N4~h)M%EU{#0~j6*>8yeZYG0kOk1sSYNYyUPzl*10?p zwxi2B^^i>y=#tc`)6$xxhK#p2#LEQii>0Z+voOC+k*#JuxT%hlk<63MDQji@|4FS% zSXL~K#s>}#hd~21n7k2`VMl}?zzW4rDKecS$SS_ko@cjobeSJc6;Tg%_NJcoW_oYC zE5t)SkD zg?eFGx|VhdX@I`O{h`r)U}YaKaWJ(+vF%N+WJ2r<$F)@Ewzo2^-QE8YvOn0dpU`nQ zu5kbycI4-0(d7S8ymaPT`wKM}ed6G9mS@r&-N8_`Y8--9V{FktklUAz-SU0($s&a6|YLeKeBRB7H?Ct zmZO!5K~&AjbnRFIB)Z7`}>yK|w{Qy}?Vv;N%U^?zPpGEP@W#a4?K#Y@~8 zE&%++Ywk<2qT=kt;*6qVv7Afkmn}}?mr3u>f#GvuQ_?Lw(PJ92zle`H094AA(%-lw zaO~1>?82Gwn*{bpNcvCN&odDuq{rmq1@y15Hf2i()2p4c*TQV(_wsUh-Z56Q{=d*% z_+p%u_2miHvX@b1#sT}5jbDO*F; zODVSifag_Ad;a&cF0{mB%I{aQ(&L*(Zx|(?E?AbX_b1cb&Llnx%@-o$Fb}*30Of`` zN@aJa-)p{DZ>=vU`=GFr`{<4&CuZJRAWg7!$&T zr}%#^H`lCj!4y4|DKbM)O#7y^)cPFrM@G( z5PT%wu~XG1(RM(!d)QV30RI=YNg7Tnc7(f$c-++>+l#|zKB8J1$s`ADuW&1k8bC2; z^AK9#vJ{N&AUgm9I*iA@LJ2`jQsnB9uI)bhk%qsw^o0sHkUY#?`YD6GY_i+Zf&x`f zII=$bZIe8Ym8y`H=IrX12{#WFGXf~3-zD?H?6w-^0!u~|!oBx=TXsSQNh36mW%xKX z(!!sa>Pn`i-Bmr7)6RW;N{F9~wn9ijqw8N=TQYdpin+!7p>FM-)#-Npz9P3d;c$Vkdg zuQ1kt?37j}>oHqdF9#bNb*WkK>2D|QU^+}%o+t=UoUb!7hvG5m2u*8d!b+)X<_0PRzF401cY&O4jl*$qyiywb1y3W7(QLOIu907i_G!R zMM?bGE@l36%Mh4C?hA)M%~9^G0<~B<7bk>}yOfEWZlMW4vP4g1_E6$(U*oqZ3%3%B z*14M?8VDoy(fly3w(>XE+%A^j$qsai3N9SkP7C)I^)kD*Z?RJ>={QI?_Z@Q>GjU>= z{QPDwz;JsqB6b^$r8%<#NKfE}^xQbA$QY;0`W}Se>4C%cTXP3j(T7i+r2}P={&2kX z4_^Gov85L)k+1d0Y+*Egcw>u`G7@NNz4 z3yJ^)0PH{GzM{Eo`z>t3Lq%M)k7AJqt`G#ycLC%O>JyEF$QX3DHxd#*Tc%Z7O4j5} zb~<4m_oAjVM!bH!1K(I7y8&iUR_akxAi8Cp$44Ur>rpWr7l5W0Q4zLLtV$acF9wRp zJIMQ=YNhwdH%XIHT}CR$O6i2Qk|nwOt!pzdqELsT@eX3^tRN|Jg()=6`YZ%+J))59 zfm44$N7GZwhyZvr*SnQa!Bd|vF!9v*r*h={0{Z&l)-q|i`=!XB@dPe!pvA4Y7iob4#T%fdPzpJD&NJuCymQWZ z?@#+}XLe?HcJIBe|L<7ywOW(}_KuohJTk`Dg+H@`_kb(UR?A3UIIk5I1$95FO5jq` z&8!q<<0he^)l@ltVzU93y70so71S(6aekX^?%|X|_t(F!+vUrb;&?5y&{jhClOV)Z zsd!Ci(#~l9rg(RFrlEVQkDM=?71wfhZRxp-d zryiyk&rS0Os;->l^E~O16d-e6XAmj9TwY8H?)Jcvc?(465{Bt(UlAL4n~D_wHLx;f ztJf#Hih0#nK{u>Xt2iXRx|~H;p}*p2TJ<+|cLYHB%LI!%|7x;Ie5E>2?$qF6Lq8g+ zMhaS?vdKGH&bKpaFF0_qm%D#4A7j)}!RG3y9ca2-ZPeND+7;z&ac{alX4KVQK=S=wgWNl8D?|yObRsLXE%QT`L&yO(Y^VRn(>FFDmUMzK#MawSOw7RVUmzVB@A0W*P?zp9PtB1H!S*p}d zqz}$}ksgz`kbcD$;&VV4)}tb!`ld2noSkoj#ly*3`7VR=gkqET4)GK9p2Zw-jcN(k zRGrTWRgOei(Li|Io1GJe*j8Tx52&+)y4l8(+CJ7ZP?|&r^Q`yRXGIL4_?ulS!0=<` zyEIpr4>Et_)b361HXZY`Eo`jU>m!a1VJW9XL$oMHAYjUBpN>&!l0Yg-b}AJ_rk1x} zDk}ltS0vOqD}`pQBYXKmJQM9@nK5=oB#`ftjjU=18Hw3r*dMLO6@4md$i^82wg&aA z8yeRS9VGz-@0R^2m0{FB0_K8ez4dax|4`<5yO2arsa;qGLHJ{FB|rMqsuvyA!DHnH zh~kGeEl$ns-O&%5{|~i#it&G;Rv*#W>cjoRJ?h_IG`RX-ZS~>rEm~XsbN}c5_AeS- zMQf{%w?F>_uKrJI_4d~->eu1#|LCf}fBk1&U;p|KvU-1cf_7H_ULb#;AW;`{sH54( z?~AA}Ur<}ck5f~qxrG0qrX!}0y$z_3>ZndWU1+$I*uB$mrP6&=A^C z?eFjJ>;2T*+xw~KV|RD=e;L)W)_%04TCq}=Fct6C?`+&|Fx4>9+R)Nk-GXYAN7XtDURe;9=e^g9BU&V)al?|;` zO^u~>%T<=2tGxQEGTN)Ehw~@fi)&i)Tf6g%KBlzvhW|%lEk&=AQZ%w!Q&@#|RtpOX ztMV$Vax3%m^7FFuOOmS7)6X9hfAcf%vj2^;8XFt`Z(vp&rVq#*#!ovSWR(W`NIk~w1Phpjil@LWih9ba6VPc|{)LUYb2QVf# zT3r2K<|-LEISB~~8eILK*ed>isZ|Ib?tisa988@56I=!UU#L}ctLWI_|9@&VrlSpB z_BrQ2)avmfAcca#>tyTyO|7zNwx2xZLA5z;Pjxn|{lBQywI;F#G_^YVxuO|OtzzKP zYyF2>effv`qCxdQogpho@&@|iYCkzkzHLv zwTiTR(bQ^>_vzP}z-yP}xkP>o_TMK0Ew7Agivqr_ zY!0KLW#rGu+v}sHhL>|6`|tk<-s8l63l0vxAKS&~DJc#`{rd&HEe>r8uK5;@k!DXH zfhT^n6A4q}WCC0rtC#vy*l?BxQn{^_#nN>BvG!#FVSSA{=0fbn^L8EWCGZ(h?s#Fu zaF!?CE=({bOPNl550#d;XG~nL)7VebV6WRxADB^31(B$59b_69IUZyg`st}*nfM(a z=QpNo!4!Sw!h!VyT1rVr{IvtfE z*z1qV6P^top{doW+KSXYLAbx?hipgZ0qM$~W)W42JP*<1gnZLg_2*8(POu z+^3C=m^gqkQ7gbT4VddVS>d=^&?WC60GMMyXR}X zGjb5hLv;jJw+d_iaHiAGBEyAER4G+s>+@S9%_ zUwm9^eu`(t`?Fsn5U+k##yf~*F5zLxT?a+~OG{+8eEMopOMZG zcH@?Q_^bZQk5%0J$_fsw7R5^rHBC3}dc(Z)6sQTtZO(P5EuILbVbc7HlsyXnd`--6 zTVkDqS#(O8k0|J7BT?d_=c#LhJwU7r3P!s$!s^{{feG#T={G+gu6DxjAKr{tx6_F$ zL83?!dNdXI@6WW=`Nae0VC&Utf^nvFPiQk+VimW>W-cS38Cfa6YS6koCbDWQeXz}`D%*)Vitbb1yrAutf zy2rS)xJr#>2emo+k6_TAKx4bs^?!!Lq73&zsbM&#$Oy{mQV0)aSk(Lg^)Q@_vWo*d zSaulO(qmjC-7`vfzk&cn1rh6G1ncfZLLqe+^4!)@&qpdk%7zE!QPR5@?EZTgv>GuY zdYIu6(AF?$l+B57^+1VhYyhvf6}WpsH5!v6tm5ea!~8(#@PYPXiagLLtiuFa!&>tW>V?X-%ThTF8HaIGq7m55T7Djlxj3C%I9~P zo@=hZKaxA9^Y&Si%g8p(6UmhDL>n3msWD-IUQFo3_pGaRbzuPDsoW3?F-Dy#6R;HE zFrrMAhaCLy);^Vk-XmU4xw@9L4FuUq2-j)1Wv_Xn4c7LET%WGSl$ns$A4&^E3ch|g zi0|NBGH<&9{bzjSq zlp4rF8K)Hqz>EgcIEGZp3{y+R=~GX}@KS(@*7yv|R#BdKHE`y)=|`8u38UaMz2hDlCCbpCdbirf$6k_oW0ESr<--U zf2P*@R19Pxtx94imxSkRWEJMybDST`Qha$|VgK}2mrZ0!u%I8LIv>E2kbT!oEz3gR zu)*=P3i@1PP^`I{Mp0_|9jI5Q%_AVm@}>RL%~BLFtAsc!ciM;N!@}cI+5kR3D}Ec6 zcVc8gWiO9QJLl$x^q==acMW<0oAmunzp95VtQ<35z_1gCY3oebMGLBpkMiGiEp8|K zerdN{urV%uG(U9={cd!+1I28Rt95?TxfLz`rw<_S{`TFH<)nUhZqGxLAH}rQEwu_D zNDxafwP0&a9Qg@2>*0!JUIco2K5)_08rl7M8?1O{l>k98bahRQ>GSn$hTV6CEYF~!o$K*)R$JVyu?^xY+4u$CrGg3$pC(kLq$Cf zmq0q25M&dHom@(K;r@+gUQI^28uSDh|0zgS=+ijPw+Xd_%u+lNC=hR3F9x2Qnxcod zi@TK?4VNDvuw@-2_&pH??-?M}rQId{tEW_IrgdcbW?_CpvEywKp4zu5ifMhduH=N+ zgMM=?UM+SZZ+R_0$R zfzMChN)W6M=WR%ASHn033P$efJUz5`aJ_Fqi#+o4LQcRiSDF#x3mBBIS_o$N?u3$s zZuk9==VF!JFeB0Ylb4AuKhxD=-#(!nD-Hz5Ep2c|zCCvn@3);5v*VFD6vct#vTGk- z4viCRwB`vLz%YbkOJqjqthBXZ38okd>*!xTG zf;#K@%z?NL@?9XWO}O(LusMP7P+TJeeFsJx{tt10ycNFvd@af4&baIZo^l;w<%xRF z+f`tzZ)!r}noUaI#>7|ZGsn@^9rOs%|9q-pvj(3!mnaTsr@BN%Bss(eWV?TS+tnRx z3VJqZPALD!$?UD1_brx!ABr#(S)oN&3K3P4;f#Oy&QJN~T0#7)Ct%%s%_^tw7YAxI zry*E|0dE&SbxMw;TrZl}hY5uTWK^c!fW?BJ3@IE!0lx`>zvDk%oH`Q*u692!OSMtrJNSPhKewU^uHcW&o5Zp(tc&7gp#oN#UtMY4JH zH2ZKy$_VE5aMEmvuPREX>gs+`>TgFdf>>c8wy<@Nw(adTY?4!z z9f@_X9*1cYhg}ihXp*Eg6wZ>Hw4o8F$z;6&hAB=QeM`=c$UW#R?9pJE3Q{IaT&Vr zvu!7tya%x4znH##!E@&?s6v$!b4>3YN8$V4_Dx;l>*LG-M}}A=)`Ag%CuOeUQug24 ztk^Gkc)$%Fg^0cw@ zPJwSc0eA{jdB#$?kmtD_d4+F$%?Msui60m8D+-auB?8t8YPsm;u(3o{fz4dGtpSB? zb%lE?rfj^&JF3QU*q0O&2vgQE+*&x)VHdhr&)NG2H?D!vY z$WO`_6{Gm(ad!-h-iBut)Rjq_R*fFBicb}*f2bmSTe7JL;6q|@dJqifRp~nwQaM#Q zeJCV<@8^1wY&TW9zK|Hw3L1O;-14MI@T=L&1*bZ`{JKv>C83OIXWSV{}yc^IQ^Tf_g6xh8(a8-(T>cdB$U!UdFguB^Fa7wL34QR~6nWAof z?5=tIP?B5i=tD|i1;<>0JSv~2?8Lajh#^GzIj@0OU_7e2IXqZV7J zoHN&}U9+x1f8kglYcMJd6Y5;w`?r-_rs-pS$HYQnP#EAB4p21k^_^z(j$^YFZVqnF z8^Ay?XwWk`hs01FjIY;a7ue-c(B;(Ie#=@dg;hG!zL^EK2*$yh2i zl@M%=UvC7ntRc$^gVgtaXx#kJeE*@9rngO|x5KQrE3mhxp!Y*>Z{KF`$NSy^n!cgW zA2N=y;!>eUJ59sAebe_JvQpo-wY@Kt3HFP9LqPGN!t4W>$jj!Q(AN2VCTg>LN2VuB z=3}7Q$3xtny@HQFdOw~ubRXS+d>vSeZ&mXN0KDY+S%{x7|xV>b@Jy0*kpPG#YXpNyg zRzspPzIjCv)j<8imgoP*P@h{&8YXC_Ch!`@QyNE}B#tAcv)CD7m^n6)jg!$q?>cd& zD!HfZ&#Kj3rjmoELzrRPLw`b39$W*6@y*^_C>AJcP*bl5vsd_1sl zD-ZC(7`EbQQBZqH;q>17>B_#(`&$!fva?NtmEeJ?!+}s%)d|VzNlM&VC+^u)bXuYD zGdh(JKiJlQHx0K-87};6ST+pMnhSE8`zJeflsJbMJQujz;s18V>29`_b}nXXCO@Ga zx}ArUG<9$`-;GzpCre_*T@4}v4817BcxXF7e|pNb#)=jYj>sLVNCfN*v1XJ4I_NF1J1J|>{06R<5*w0hAr-QPdA)zpgLw2s?M z>9K}I#tRGQee=(Cqck68)Jj+)2u>9wggx2DDlS~Z-@^O4W9YiaK|pe=4O>f`gbZ#7 zS$=`)LpIPNdD1G2d@-BOx9juoJn|c#v|-ffd=?SF`(T#B@*Ae>bV$Us48NaTNT?S7 z{!P*zmnDo(9tL;K%WT?u$^V(baYx@R={Z5vgPgb3<4VTNq4UMzr@;|sILxeni;~_# z=PQSvH1JGd8A*%GHN63#+yd@*vr69MM5c(qporA2$A1Zu5 zz=|!Ww1zYpj z%8oIJrpXCTbCO|Y{CgdzoD5as-B)MP{E({yh}A zIR6%MvVDPw-#rB>0(i8~XTBa?H=e6ao|BuMXFi@q(tiUHor8eO`vXOkd>3H-GwF+q z1ea3+`i*jnpE!>@qShB6{l@r>pI2@$z{?$w0uqVd2P?kBEjoa^k;U-CL<^4!@Gj5_ zZ@cB?PaP!f+}Y{ZORN-Rjhvb{>SE7={p(Ztv-fY$1JlnrORSOd?W_vRj|9Jzb$`9R zyaa^ppKEohwzMSEkEedU4sO1BpL|TDaABPC+y8RgT<5u=)RnfvWs1&W$Q3{j34Vs+ zP)KRfp8NH}{Z};|VAKLeFn5E-K6O(j^gnUv4d6DW-ZW|arglFtw!EcLSTrZRnmE7V zQ)mkaoeoUlATP!3E5!(#<8Yq4l}tHFn!9qFS%-Mee6qSu_ zym{mPr&{6XT=DIbl6{X)cc1^>>eAo&Ux7nPq?$@tTUstYwEP|~xo5-wi&^$l3ID#m z&qfew;|lat zav_xt2WH}CfJ{yi7O5`};FfM>_g zs_DJ8^uzRt1XQ(~EJyPVPmP)_`a>}9eJfI0HTkkJ1IW+SJDr8Pd}WB-w&DqLa2zf< zMwJK;ri%ofbDGTu9VGl{6VsF>gcdcq8#CO203KQ_{yPaUpePsu$-n%gmn|MKSxBXt zZ}NMQvCl`&gwE^+<+9P~DnS<**nGC#hr4vqFWrOuMz8(vlEvDZ(feaIfi7O~>Fy>t zWd*e3U&i(ZL#BrY6Bya#ni0O=P`MM`W{*)L2NC3=KdD@CCA1nnjSEKqLqTE9S8Tat zBsYWbd1t#5oMZ%>A=pZc0;J?hRL_$TP)m*^Z=GzidhknF#sTvAhJq)diNtW za*n=KNInn+7|>UzC!;=KP^Y6Ko{Gwc9pEJ{PAKCi`gqKMo+x078R(Ow6H5wI$dIjw zN@$S{8ome?D+k}+4ucUvXwbX52b^GBwchBO9D2)i!w`BKSC8RTO5|Cpxp9dHfF8cX z2z%bhrIm5$!W9{-mE$QKJ1(mgLd6ESEv0r8)<9(V5@1>Z0~mo}iVumbfW zBvDS$oMhf!j`h3E9pv-EsE*H)G)!)cGTbc4!2<+qYB&}aU;xQM%3SLKDWnfgA4QbK zM+BJb<4ab&h!?cLsDSzHvVqGf?E5^cPYg4TYb>-sczqVpRI~z;g9Zf#NQ?h{t7iD~ zLE-$P|E~p#(Nak9o6;|Sj55t>HFS1~j7PXGSC?wU@iuKqvpvu zelTBi_eKdSNW@<84`~Fz%6x+R;WG}1SNHSs-!U+ zEoOK7MTWb|cDKp$aP;k=dLLqT*`rO0#*M4fTp~bV?1-=M)aPB^s-ofW;CZ5$Fq#L z&$W_8tgIt6FnOcO5W*|zQrgV&bP|1g*0yAQ{uKJ7Z&fOUU8-t2PM$2)8zD3X2n`Cj z1ffPNo?e*w>dV}&lJhh-;=`t%qYB87~?Zj<3e)b z2AL#dAuS=rcr9z3vmwSkA4ZeKv6NP8Pdlqj&9xC>{j#-4YZZWgwFqBUo9X*gg6qF^ z+JH2kL`yNlSzB+L^OUt?tzL^ofY|# zZedgOt5`X_@7OGUjCg$2c$2`0IHlZF@~pf*alIL59Tog9m8c2vmtSnymE#8GvON?l z61R?2kBW>&Y$AgTpMJKKn7AUw6at6y`-U4a-!AB8tejPHc>8}gEpB`9I&qbTWxPyU zhceSKXoWxa_VZ=iU^)l7zrybL#92)=Y(w^o+|&091|j8UyB|{V+)d`h{a6sbJT}G5 z0nCMacIB$tEflY$%c|vh9}PY*j?Eg5%f?(+$W$Ibcu8Br1X)yjq(|ZaKFgn)XUbi9 zoTWZ}naPf9Y7%VRYr&yb+N@{kg zHgUIS!Bpe#O~eVVQmzZPCBin9qGBds z)wB1y7)5(5B<>f?2It8e%ZfQwz4KX;hau*4_eyM3W|k?5unKbziGa;Sogd$9d2FAC zV)Z%8&DI;Kk6`QzG7f(F_&aOu!@<>G0F}3^t?pBBQe&>nH?fkmuuY#G2g3VSswhMq zSFh9IZS*U$Z@-&6EJEC414)Gm(?W2lnQjH+DIQ+K0VyrYUXG*&jLr;4Ld#w1O8nFGRvg+5vFGLjH;tm9OO5>zU*P9`RpU^(F6~=6h43Y#1 z-eS>EAv})2@fw4_xK*EnM;;UKqY4rLN6`&=@Mp_CS-Tq6G0i{$J6Qgl=nhL%kOtH_6%zr?A(V^=WsHE#j|cCMhx{531y6+SkK@53@n92? zDicv#>Jg%7^mHPYb|NBbBF;bq6;nBpK&pY(R+C)9py)#fK+=}FFjp+`js}8sGGl8Z z(_k|67f_o9)0MG+rWWW{s2YF`#Eu6fN(w(|l=>qz4vq|CDvdDlh-L8~_b(ieo)}ZF z1B-@D)n-oBRZi7+pu-_kjmuL_`%}%ordq(C{};9Tv|bdvuK{k*0*^e8ZvPLp`n0DJ zoI3(}fj4{?CoL{H9M>w{h&u(2gqXwBY`}n5mFkS|)Pr1}B->7osXU2`(n<`Po@~^Z z?3kW#nV6QrP~#vOas-^G~m390lQoRB058r_a_JH0gAb@ae4~zJ+kIoGiC9Z0?2SS1ZF5KQmRpzyEH~tWo++k*v@C{d**D< zM8!Haw6in}v;lYirQ5iUSf;{^OGQg+U}WE909TIpE{9l;3_=iHKGPkfhImZG`h~^Z zfx}pXVgpPd9Mf}hTJy>(BdA23mRdnQO=xE;wUyv|r)B-ZdL731vxwFhlhpY>ynH@E zOasPe%;g^mes|kyNpUp}QTpn4z@#H2aU&g7!3VmFdD;a2SUQx8w_g;W9}PC?3A4LC zLp>BO(y7jppX+vq)wR*+#nu8ae4ihT3?fpa1&~1gFvy$Q$wO>iy<InUmubDG4V2L0Hc1=^KG3PU~Zr!l@0SiTw%rq)T;A_~^^X8NNBS>zr+R;j2AL$MocIS=_@Wsi#$V_0`?8p;ykH^2%v_nt%0Tk1GRX@YfKd?IyA>n5s<6mVM zZ&e%h915LpeJR=dWP8#cOxk5NlHD#ZJMjTT%}; z8#N8(7lZ?#w*sN6Et1an#cp&-{9ui1c|B1>903RiokSPpy?D~}<%^F@AsMwkJeoNJ zDrSXooPjVV+aMQt5%0g2k+flI_@yd$!D)2B5gem}Fllo&8A2GZ@vIOmawK|$7j^cD z;+V11n0+W(J9}zY$(Qi9sLo3={C!hG51Dz^{o1Wmq!DPSVL*=H!HgVtYm9CSOLl|v z04Kh`%~!dajMMDBula2BR&r4ZW^J|5X9@2j`N)|qi>;K^=_Mk7;>emfjkyi&*3D?d-of_w-?HZx2=gM*h*|*tHD<)1 z<@Wj3N%_WFyJ;D=qKnL$5>M+^h2i}T8?K1$ zJuyJ!T0;5xP9Ju*`F0FtzH$7Hm&_{5?KhxG-ldND^sC>@J>q5Dy54}#?m)yY?9iI6 zdbfT1>o>C89XbRtr6s$c&CrY}BfGV^^y-%AI170r>sM=rm}Q=uEmRZIa)}0kbWPqk z*vL4xmp&)4o>kJLP{<_{Yu@k;-^%DQ}h1{#6r9EjKtMW^M zW_WSy)qWZ1Kq~sXq1}Ogu~l5Es1#<{4+D9gi`TFBSB>q86|*ReysDZ?N6gsk%^?8b zg|$Y^dO+uLxFqn?gwdrb51kj!bP#{y z%fgX>8nKap$Jd^2a$ea`d`fCNh=^*NsyN^U;+ESi#NH#`9tBH&rQc;8NDt-ttN^eA znBQTVh`fyF|8BdA6F>$=S;H2;FlscS;wE?)y0z6BEG)1aNB#;eAEEV-DgAq zTB#FNEnLLSl1JmEtRTSyMBU*OnK2ZYoG~x_N1B>s5x0tYF%C-AJE4%Hf6+!MCZ-Wq z$-EB^g#?b}v+>kNQ7-GTcBL5LAmZv6itJfLh;TasDb_H?mQQ|C*5%OAiSx*Y_>uXg z6mt9`%eHw39E6PZlf+EckJr78O)m{chk^s4v1b0jh*pq87?!_3gq;xqL`Jzy#QIJU zQND+Ky`=jK<2>5TOL<1zcf;P#?=sBpy!jDlU}((8 z+yJoC7_l?p*jZNCIbqm&rEv+RE+POBH{(JHG``>ZT;Ojwnz_bGhUz&hd}(IgxHu_JLaBmf%A0x$Km?gy_)U)%FjjwmU(ML z^gtNo0dY#1c78+vxJ^brnLH}d52UG+3NL`8eJGy;f-(nul%iAbrS|50_RpymUyPDs#p zTnvqrD_}j1{t2QwDpRapwF&lxtE7^9{EGLRfly6HUr#H}K$ho($yV2u5xaNOQ7oJe zN_`aj63yr`5lO$x2p=Gk+a*!R8xG}+2rrEY9Vk+vLdY9?dBz=#-HplVATV5wlByB1F{|R zvYn`+gBhWCx3PC;+2I;qSmm~3aeYt6s(q8M*f4Lb#+`7JjhgANRgFz8FoEVwScZ1) z_Tzix-8ecsQ6abBD6|c05`*dm$071^1gM z>p!OMg)c4|%`(6Ktp6iG?5Cz{OL_1nvD65N4AY>v4HxhW`XSPI8{>|Q^??3$--)sB ziD&>6IKc|?L}@zoX}UaVFnS=49uYDIZhZ?h<*i88ArEs7U$2>Y^PF!v91VfrPH->o zI_CZeP_YwnhJ(_7MZ63oioIz>Kv;gnFFm1CN3-GqbZFl1H3G|z^J?o$(bu~oKl?(c z75Gom8`JVP?F_sf-GO-=e$x_uiD5rUC4sm=h@JW&jN|gD{dU^l_3TelQ=jk!U>%r( z$AlR>ALiU6x_{;8Kv83+z)wg_L52s-KL@?;IHrsarh<>(B_8#|Ps@P!PB$-@R~cFC z9==TcirV>Ao)iTU>{^A0D)vX z1?WPz3m-R9Z=yIO?ouE6A<+L&t1e;Hz`-aS3SpNcSeRlIA;+^q%6H6TiI{{=D)W1U zg5HN9qWKAA`D7-ce!WXwYSrgh*~d$S<2AcZ1jA$S#PM~_q;|EPcA?O#Jrc`C2*CB^ z7uRy_Gf#fA)s`14uctpsWk@fL8zj&UOGiENEBn$;!&V-h0Fu=G*{(tURURb;tnQ!toSXwe(h@(H7M z8QFo6YCd!`M&dtmp1kC)fjB$1KH;%;?f@w${X1>Y^Vk-X4q{FLY z@KWoVS8<;Bw`6W=sDx%GhOLHHhZ?=3r0pPo_OU-}`np^NHbA(eB3VvL&DZ)B|Ay^B z7WY*3Ym`ZQkyU}z_fik~oW88%&AfpHpXZ|8FrUw&PY!b{pSMd&ERY5?Ue2>DFWhmI zBHm|!0ok^%;B;Gs*``^J$>T;9sY8cH&zrJR6Eyb!EkpopHBITOii^ojw9MB#Je8s}TvbV$8*JFPr! z7*<`TgN{Jx2$NFP!pR{YV(BmVm6jH3`;6EyOz}tIr}QedRAq9ih~D2D4bQ|2k+2kU zfZpJ2`BZ!_bI&eLkcSduD(5o+4&>!{?lwW+!H5O0+n*{tKJTt!Wl_|c!05ZeE3(EBBH5~hq6FeQ zLPPzA(Grit10l)7W+MmpNdVMdh)eNCD-#FCssi@Bjl}j-gRep7Sr0|fXMw}eyiD*d z%LIs(0}&@_g`?!80rM|QXb5hNo+P2G<<4cMn)QgV)?e>5NGphf?XYmSQsRFiQ;B3s zFyNPp5pNa@16nE4j3G;Lfr7H-vbKPTzae=I? zEx>^#?Ur=l{^uOG_6RB2QxIVyBi*F>WbW%Tb``-$su(0ka_2l?6va43j;!RU7G&jm zYR$@Dm0qtu!c4zXipf_?lwzVK9OI35z_#MWmDWlCbR+`cJ`P0mGI?iCvQ`oO9G@Z= zx5gm#3|sXYg-ua%i;8rk@$gK_Pe82n;tyr)VkDC{x!&TG|gt5^yQsq z9z+EF899m@)3j`OqX2z%WZx1*K5oXG3T z$f$uSa-I##1vBRJabi5#{ zPT)yz`XZ@)TlLzIQ~LU|OI*-CZ5q^6HtubBWhB|T^Lr-}YWOh2gTt1f1JQE|@gGv+ zPgw0D1B(R5{3kO>>!x$gGm#f!C$vNx;@fUlB9^dVUA&TBF2G}yWfG~ei9q6g^S%cRk z%k$eKrso60#gsMx{^stXBu956>&=&sU97&-m|!Dg)DRK2td?I@uzSpFnv6Jt9#5ln z!icId4Vk-DCZV2{7i1uF-0L2hvd)VbslvSif5z~SwJjzvW{VTZm;OsSV?WQDS%1JF zU`kKT-)sWlmiG(;E|CU+AGM5doJ=M&{66y#ooVVD#;%{+Mq3%2s?g?$>;n5xYf<1J82PXhtZq z!enHf^JgAMCvoM=@azjgSZA6Z(KN8x7}}rM=>%@99pQvQwiv{v!S>ZZwVbRQD#2Eo zquyEZke{85z~QluRL}Bf^HSMOxULh)?)|GMooQwA+RRZ|Y3sFT>ILi7vxwN?sPX|O zCHJ7fF7OKPIj6ur39409xlafu9#p@iY{{fOFs?MW|YIdVe>i}REMy!ynP0Y+q}Rmch>##{*uXB12% z*chR)fPcHQ_}i(%BwrRUr-ICz#`&NJ1()%X(VDvIR4S@s1C*r;Bc%YtHSewcR3fAc zLEJ@3lD0z}1Cbln6s?nV4CV9~&j8iA%G{YHPYtZVY~{?BrliuN6Zk4De$y^2VyP`U&MPd@pjG%XP!s@Q<%}2DE8`)jrfaiE)RJb%(p~((Nfvg zCReh8@exRi9VNAqqe#5K?6gEtoPn>AjE`4HOQq5oJP_g0&vC-PGc`3OowOV<`#;VxCqNYbZefLdD42yjPoQ4Ex%V9!) zDP0^eYF@=s?JJA>L&SHKsQ_W@M@HgPwi3l(O^TP>8{u)cpwok>Q|;%vI0t|3Y?Zb4 zpR}^{SE)3go3{M^W}0NIg|4y5MT7Q>9Ssgb0gAi^s=SB;cu<7ch_Z~}@E7O^cq>9? zB2u`oP?;B1DlyBdoledus1^8cgfWIx?{M1D?a;yr+#OIr6;{v_ZlSA~%|&ZPR;8GX zuhONcdI2o5zKIvnP$Cvo6p6xk0|4+xVNmKRis?maIaJtty>$ADS9!bpcD-C1S?Q?6 z^up`aQKOw28q-rObh$BbPqXghRKeMPX0UJh@WAfp4;0o@)`lxJ=&9iUQ*P)BlTV}v zP!1|sg*ypXzq#1usip+_m@?`uNrpt3xp8dCSZpivTrJc8@Pt+sg+; zQL|Yj?vIgnLp8qhigI`u@}dMB1JlZQg9Z{}@Khv6*cDaag!F?7FhvY-T`B=r z8ab*ijh-u=z!6fa2w|vlxFAPD{KJ_&r+_f?FwaMId+4XhB-1XJ<_08N3 zUG)tg>uC@Sd>>Ehm?OT@ftn8Mn=iOqZt7be>uZf7ii}i#1Y2@O6^GJKqBT7Bj&N*l zQaOGV8f3&_=MM$i6W?VF6W)55!;$h1ND>TT)jNTk)GHw!cJDY-XB`XexO&S`b%h^K zv&I_wytp#ds^S{q{SZg6Bqx}XtN-FO1JXFa%r!{PJMe*LX!V#hU*)&O%bRmY4)g?;nNfa4=6Dm=B%33=g~2E`6R^ z?Zj01x%w5>-dtPT3IKquK@bHxE9^{H9A_Tqa2X~WiKKul$-vZ=@do%Bl_{=jLP51* z;$VBfns9Q599E?nX#=^-{qz3V$X9@Sf`U0~Trh&~AdG-F6WBUu91QnwNx zmH($4&3bN!H^4Cwsc;)9SDS&p1hPSc__ED5Of_E5fMOclYfAPnG*L%UtEH}~7+<){ zB86+sTAP^4o0L}5vK;WiAP}=H0J6zbbhVbaf5(q2g#7%lpUNd zFv$Q0hceT{!i5f+))(O+P1l;Ln2CG_J1!RK%@EU{x?VN;qAqF(X0H5juJUs36X;o& z9yD(V+6n$uwf6iLO{xxFKy=sgtB#BLZBzs-g7`5*p4~XL9IDl*8PqDPuqf(Ph}l#` zX1e2Q>#O3y38HG@c<|TjcF*_e%SHq!g#_09*a6?ckLk)RP&TO>_oxtd0nMUKoe>3_ zS~xK)p`ER+YB-~>?F=w30Dr`1-s(ACb)1a{gyiV@tt(6d-6*w9`SJGUQZylUiQvQE z7EP#!axMDd#0uzRy&Gx`$RB#9Gt$X6LM4rfzfXVjSI~a?C(7=E>M173D*gu!K~eZ3 zvAY{dj)x{(NZI_g5y7yLA3EA4^z0_{Qzo4Wj$qS@i@!pkuax9$QGC{@Gi~!hg#icAf@x6_Yq8jCv4kke zj|aLQg>es8ax_emSb{<_QSoiH2~*ynSMPLH!x%+@Z>7H>uC{b#hZPdfWJ|Q)V8Vbh*9_Xoq9x)9HB(E9@w#RZOcf?8DJR z(+c7LgRj2~YAf6WckP7W5D4xrrMNpZ0gAg7D@95R#T{BC5Zv8e3bbg8OVQ%AP$*s? zxH}XpIoW&v-}l3rbIwZgHIrF0D>LhPe(S!X%R+azQ*{mv@}0k^Eq!4t%+a#v(eOQ3 zUQan}R@xSOF883wdDy7zcnYa-zd&ca$Di{L&z8Poz94ZK?K0%jUj;{z__-g8uHVR638~DNB-(dWW)v(t(#TB<2+*mqVG7=|y`$va$#`$pB;kBug$Rv4#-$Dp#cTBp-1T zQngX!g$t1?8OU#G&C_K}NCYOH2fDh&Eh*W*`3iT$bm=~HdEp8-VBdF9M(d9B0Im>W z^s*luCebK~)7mdc4I||O$<#jwnIJ@7w?f^3&;0sG@j4m29`XhS7(Q8BrnR}*BK_Y#_A<0;;Ia2R5ps7+#k zMWPHF9H#i0z5}|8U?9YN0x?o3I=~qpV6vU1DN@KpM$<040rl%O&@L}Mb@P2pbH8+< zL5mIq>Qh(Vsxv@WDAVqG|GlE)%_-m?o|0e?AYB6!+oWH}1W3t+5a*f|t}goq0(9TY z^wg!EQa;!*_I*UH*V?guiOD9{V(Q@0~{adtA_5xgRTTWcNhj( z;hy*7W-tT10Af(Y1FjNBBO(*lBYP<$>lOG6zJ}htAHxs(Qs_ub8jxMnqSp8oZGaz# z0DnD^iz9HKrjl2#hO1WRN>qdiAOie;-og95{hvLjutZr?x*%~35u%tyP`5tm$zK@5 zh&qN|iXa79E}*s29aLAbTm&=g!<4Nc_47^i;@q7Q`oc!_BeCSG4FlT7q&HhIKUIXf zRAB1+dj9s5Nlbj$diT#%&~p1N0wQ}14vQmM1M#D)+RPx?)*M|qX{tlTC)B-MUQ%E0 zW#24}{E;5;*f^CN#N>Mb#hnEe-2^Riqs~_`vF0NL*v)5NU_vcUFP>ll5I7{9hL!ce z9BhLBP^&`L{gG&DHO^koRwWT28FV?k!9<+=L`MB9*4o&!Oo2dZaz*fpjJ*lDdT3-l zQA@z$sOH1z2}r$EC7JWL-ynGdguG(Yx^xZ2Om117G&1}3gi5l!~KDWqUR=N>zjKQTwLIDgWHCHldHq(xUfPgZ+zTx#xG=g+s_vdQWFuqaCXE--M5SUjKc9|7Qv_0iOH%)!D z9qxhp=R-D{-2DI#AslLmE-g{`3O|5Hz3iJP_c(9i<-0+S?k^--z~@5G$zwdMO1~nE zM~>MwEX)jk%6-4z;U#$CC9Dfe{B$HPG^VMFd8^qfFx5Xu?mjufYP72UV&LjJ->x5r?Kr$oTsWDSf>~A(}8P?e% z4f8A2>DLCI$0riK)}B)l$hY^R2a+d@&7&;K$>*Eme&crI2MJYVl9SXJu~6Kk0OY)j zA2KBU<4dX9Qkso2Dg%s`P<`YEIYqnhryi0~>H3AITp7Wa$T_4_hxgQqZ+gD~Mf>5X zxADp&wRN@Ibk4k<9}9&)djQi%`-L>TT=W<#SBW;53gD+eW$EW%RtkK$-678i*%n#% zQ~TItllnq%h<>>zz_93cpKsBgvYhhAWekDvZBmPU=Du3W)&nn=hjaoUZr>liV|T*M zH5GB|7#mGyR$I0e@`Ol{YE30d|8^wFpY>kK(WGb^Jj}t+wn(rmzst`6~Y#8p^SU`xhpWv6`URcewpFUMm^!q#HeOF%)&RQZQELTG@MflO6# z(ETi)%sT8TN|qwI5+ZS)-1oT2j{uPske+(NYJHQx4jMw@E z`X@s=9-QRC z`h!>MoAx+0QKQEnIlGw9TpwH#9H+sIgw1ePO5wENu)acYc~arIgN_ZQ0V^&SOBA6W zP#&UGNWzz|BJgy$^@=Q?F6;R`s{+Fq5|~*%$)ON&hF&r5DHdxYS1Ml6PQqA=-W;ap z!UCXLF}*}9NOSEUub)b%EPAo*vaQfh-aHL!EhE)z;s(sn{IqAJs3P4flvQ~y&l;b(|bFU$-Ari7*nT{ z*1?5vtCFYsTB>}X5rbhsDDdVcQs}j#!OuJQrs|hbIK#ay?_tnzUQri!lBLC@+Ak3e zV15O1-MCEHK(2q*XP7oJh1O!OxWCKNCKETg?WRxQVqJ^AveL{aL#)v>fbX_i!xDi~ zLcR(ua!{~W>(n;62D0Bq@?I|KUVPMVpVCnMmBC4`G#n}apInv@Atm~vZFqDd6N(AJ z4EHl2ZvQv<>@;Knv(U4byvfarOaVw-&MHVc&qaUT;<6r7!Q(SxJ6W1hNi8tWBm`Sc zC+Ams^JTeEzJrE}*>wK(Wd+Z~p1K4E!?q-5rC$D?;$-RvkAe%&jYHdg&H)sm9kT+7 zc5x#6=Gf1jL%0tr9G`@3pvr#|WFLB#;76T3)f0EF*ZC06tC_p_yZO4QA>Y~gMF)ZX zZeMdRgNwW8($eg#0$yNoxO<(pWquqn<>?9Ktvq?emUooN-WgeR^L`Qv|v;seVdM z7k_iFcosnL!QlB!_BSf|0OZ*DkJr_EP9HN{Uz6jThRWUm6N^sY@8F>x0rezOhX^zW zcxkV^DEZdw1?xX{^`W~}7J2U;;%~@M*Bgt$2CP0;3;f_+1bKUx$NRb5A->4A@n_JB zFsK!-VN|$`M=f7a>GUcJLsH>m5sv#qDMN3M>G`FL+PBz&lh~nlq%)Iue_`=V$gte^ zKmX9>IhJ!vrjKV$v>9MU5S5c}-qZ*FT?D-q9jYjD(tZ2ee7E~GQ`Ntd%!Ci868|>9 zuK5CkOlLerdH4e-?PISj{YS^7*`@%sKMI3STX4+gaU7DKT|$X1Ts@oXQrdsAeG~X6 zsr^8%yFW@yG7j6MokU)*5#Oxg)7IXsxvp#qJnj;++Vm0xSmB{;dYJ}#Zt?3cy`s2f zdpU}FJ#1K<32Olzy8szh;FF|vYC)VQF8kFzinaVWFOJUWwLwpQg8Gk32X?+i0O`+* z8H$jYdi8)(SF-vZjtp3Ny+FKuJvIYa%q$Bj@oe*CG z*4H41yOZbZf>}XMvBybMhV|5yuuSeJ*x|e7*zO2?AvPj+5{fAbAs2pl@ju!meC|^W zzO#P`Ng$!KKGABj&wFGvd>+lPTtVP2?^}ZJPbrMf2v9nu6eMR9r6gd#pY#wGoUI~> zGUj!DAu_QBD&IqpsTy@*9R4oSbKT{bS7pR4qBg4`#F&JwsDZFNnQ?0E!K41{(Tc83 zk4oa~pi__NfRK7FhMue%*P?`>anDZBFpK8g&|3KES7E*jVIdI_v1wreAei4;1STT-{HrjN5S8+UsK7LY z{sbcEwtnm(ph5aH_MA<8+*i6(biyPGWF<7nc&{Ynu1v)Uf5za+ z$^nA%iK=*}!Mqz)=)CxU^nwG>Ux%b5vsN7Oo}hF#rd0PCyK$XK9>!Xd zNCL2O3MG3Rk*bUwd`5+#64|H;PE(nf(WGK&GX!c)&p^LU5kt@wjz-03VWsCYYQII2 zipYn{44bpoIL57572w0~2mr%TYi@&vJ)$lHhAhLES`#x`97ZaiF{!ab^m)90KdwPA z8?|3fE9M&NTzKhxZ)krMtz$-VWB}OAM7ir-&1l6moo9qtoAd(>4cxC_YGBe;=!G1VtV#CdQgIGXXD3krbw5L9@cWZ+FUOj7r!cFA!`}R=l4zh;YimTvR^Y5hDEc`afG_-t+_Km!g7Rj=>ksOi$jxVBM zKr+Bc+|Fc{*~0h@$>kd|A8TjI7e-%+Wt*Tp;#7ac5!JB!#?}&t+?Z>OlSk8 z4?;}w_ix7!vo^jY%p*RgG=H74)qyTZj{PDYz&@dZ6<~1iYWLa`g&@=pA$kn)0{4-v z0l^t?n$F(5)^cOIes5bUx9;DrsB0}U78@KOjGzUVIMa|~&X+`@=I)nx>})(XGo8gc z18obNlNA|t2=xl4o^6s|{tJbVbIjOQ46?nF`_&Gd;BeT(WL z<}?oUq;f(98{4KEF&C2i(R~7u*lmVgOSx_hg)a*}GW8=F)y+h|AIg$wspRf6kYjtC&11!o4f`pCIU1Xfu@+ZvPG z8gm*84LK`@pnybl5pc#YexWt~&rLj1GGU<=XObCeD*+3>(Gs9Wd`L6s5Qh;UNn4BX zaodsz7SR7&*qeUIG;PUqlAuXu5WRoO)3$gP(-a=5RJz*~v9{E$tW>#$lTZ6^HJb4AzoP7G(zBW`;;*h5Khkw`IlOW+h8y zqtgAeqqE;+(_~}4xGC_@scOrqx&3eM+&{O?KPS;A_#bIZVie)~ZKl=`GZvLdVP@@_ zHyIsS?_DJ$U$C-_n`}=?rk(jG9NZ+F-6Z_YO5`IaahijH{FA^7NhGGp7gB{V|KhW@ zVutoq7U>cZ|B|Qg<5g(#_Fm*k?1D;=9L8ya-&7}O)~uT6^SeqT$V}vcYan{RNTbro zEAhmMM)h~sP=`D4k2#F#%%W%WZvC@?R1!gI^G%}dX;L{smTMeeVA%8b9* z2v8QYu1pA?X5ae><_|4Y9}N^gR*6>xUKRp#RO87N<|IH%zD^%nDpy}LB)rE*@i_p^ zPMOZFkLddWoBXN~VW09#oh>n1H8UAbfwc8l)f|3>w=@;DfAw8`Vcv#_twx2p#eboT zHPJcjtBYLk$g21p0EeR-lqOR2J!L>T1GCHqI`c2LK3aiI@4USnQ8zGwdoeNdO62=W zjhkrjsqI#R{CZ03{FpG+7N6p6j7UYW-x!klp z+Gs-N&dQq_LpD&4J=rWkG()H@^L1OUdApsl!bFI|eVanK5s}wryNFDO)Q7MBzDim* z5iv#TM=-nsw#XQMIK4s3dNNyW|~bPxalQJV4fqCWpxpGB?+gq z=%b5ZmQ~K6o?*Vvvrt>U@A`RXE)YRa2^?eas^FMaxsnOX^$WZ2Xh}za+F^uVk}Uho zO!lMrx^Fm`rfv;!Op*UwUx$x*VfSROeweun7@qc?cH zsq~j`V!aUYe*MYRm1_Sw(@g9qe54YJDFH>lN%}~adzqzs7?gn+f<2VY#U4O7Erbxz z7g7$iBL7kxCzQyZLTmrcDh36kW!+4Q3K^+*zrazpAe2AKbV8_QLcUBc=P4%jl34);P?w_}%#aTKID zN+!NXA<8xZTxXMq8GSXF7TrfsZd3)00|Ugi*O+dK&r!WhHzC~8aN44f4?M*TukirP zR*W_U9Gfg;kdhT*j8zWSsTbvB7JW>+R%)tSYqyWj627%zJ%jx`u_8-rUrjsH`Zwd5 z+pS_DB@M+(dxcjGq#=9&eS*;n7uC+fGAW^qeh&nj#XBSlbHt&v0Sv4b!8+J$*zB3K zDdK9(a1t9qJJ(>ZhZR1+s+BJaI&s$r7R}jWZh!t~Oz6WB5Ci^SYL#~$T>wQ8(n$xX z3L+Jv$a%!m?1gM$j3__*2V7FPs5t;7Z#c%e8KI5^h+FITX2%oulLWxCsWi60v>0uN z2d`hJ$#W2)pU;N~qp4L&_ptlFuB(_I4b%IWBk(B&xQzY}wc5ZWb;s=Jjzg>Ny4W5_ zAW^&A=7lV&ij_FYwb+J}{JP(Eu}}(pJiH~Kc4g5t&yxïSfw&$^_);tq_6PY6+ za>$!es`8Uk1>*)o?5g`KU_ck~mxz`!WY7?mD*nGETv^eWv_`jhkaBs1sKp_tL4%*O zI+0xa<=(3aeVn2U=k=pykgtyHZeE*VG*DGqxDj@Y`OQD<4d-07oV#2?f!Y8pR+1}u2ltFXv(T#_ zBwqTBAnvb{EpLlLE&rBz=|yC-q#McG5J|^7?HOl2VGXU!ic2=#j=e1Q-&UG#lcKC- z?v>ho;hBM-f?-*vJO-!~XIDpb5Z=D4X*O?5Dv|JB zxnYR)!_$vr3c1^jzmy5`EA70)TvX>Nd6Tfm%Q7(gKu`N(S&4K4YTG9pmX4#2&aX7; zq7Tm^8)&+donr6RpSYPk4Q}$te~d8V`~IAPLj>^p5|l0>tM`B@P~B?gIazL&M?c86 zvGq9u89(=jo;g<5W8^gd!L=K(@mF~E#fEgwB$y$fme5zhNM%y>u#bS$vQF#CR6kAN zWkhEXHLEWIzC6@Lqj9tz@Zf_l`8ECfcr(;0SVQsMj2CkwS1rKIZ&R+FkAB&GEZr-@ zWZOn!ozwS%UBcI=1nSn+b&cQ{k2fWz*W))Q_hm2P)FUsSj+yDFt zzI4Yu2~ZK29yN7jxY;W%50W{kBZ8>EvsbbtT$Ee>Ay?dH*-Clx-tO_GKreQp@7Z9a zi^sW_?=NFtIU>PXo=zs73o;PZd1*XceMd}1w zqHxGNaj|Pe@%7;;&x_pIcFi$NGZo3Pp9fvC-hZ5(yp=O75#i9Ft@4#pDY&}T~Lpy{_v<&Uwrc7-_u_WNtgDV z&Ke*l4l0FVB=LT6iH7^UystD_fp9tZT>IQ~9np?^)3l>RKX*n$LUpw(*N#QlUmPiB zWfy{p;+G6}^GwERnN(M6#{Z;?g-=7NWO}N_fOM3-Z>p=YCs-|-E9J|&D3U*iIlZ2^ zG5dsjMm8IzB9mo}8MF2KYnCb8ShUytWhf1g!UO7s(%*gyUw-or&8C6a`l1dpQxgK%+^);>w9Lz#*XA#C$+`V}!|iWZ zqr~x7zvDt#u->tV1lgPaUqE z%mx0;HoYDJXY6x7M-q~hI6tyP`z$SqKmlGVZwX_f3BaprQ!UL4Al_H?V)=C+Mb9Mz z+?3C0+Ytu>bfwkq4M~d>FuP_RCx~aZyDU3nx3@356H)Vsk1R}Rt@8~0!V(mJIDSD)fw z3muTg(2a!Jn&7g7RTu~BwIC6?z}l~rXx{t#+jUug_R%}950i26e-U15qiH*DH+hU_ zVi_o^Mlf}1=;CJ?a=U&-p#&GnP8>V?{++7>v9{`#F=vA{PH2%I>Hww7&j5}Q2Mqs4 zD7yXDM7p-N8Q1sih)LBug9g)}-Qk?>{z2vaUkC->3*u6Y{JZk_1VL zX1@?U9`gUDfQu6M7_u?Btq6<`^Kf|aes$1KlEcNBDoFPU9QTGK&n;+)Jv6j0h=L{X z_?(h>mm|5^#3VFu;e{97VBm%i!l>6xd)@E5Pr#EKh+Ta^ja4XgUL5~MoG{9eem&G_ z3nv0@{g>)Jp7D9SH#H2MuvjKtKV37D1p*#!`cYBw2ik;6M;hqv2P!d+ePK^MB zuzVPS7MgzY0K zq9Rp?f@%H2rLm$4eWLPBM51pXv6WQuyJ4P^RB;hRp`s`=Uq3JEn_yKR2f(mg=x%gV zC0o%hq{M`(j4Lt;m#RV8xY{p-H#0ggE1Z5f64e+@`ZjjLp1*Y-(oP-heiP+y?cA#x zU85S8*&6x1GLGrShh;ZzLy~K981n0evhya)3qU>G6tf^1S2+}~z7r2_iQ}P+*sM%c zvPr-RNpLMn@WfR-GScreNmN5d(k3U-G$di1h0Aj#+;b(X|4PJWi3i>qlD*dbtebS| zm&7ual;Iv{A(=AkortR#OIDSVrI(C;Y=S!5&~M5WcAX%m`uhER`~`JDl|<}qYsxbz z20k?i4_9!4eT)t5EqqZq{gBk1!;bfR=yh>(HOhA2Gwxz z)4%$lOOrklm874YVLyUc!;K(uNO#9$FnJ1j*^=&|nyUMp>N9}#t#PWY>8rB8G4)xI z_uen$@G?EBvI=0C^HULr?wRPB4gUpwzv46-f6+*ZEak!MhA1P$wya{QOjQ%9LL%X7>y48YH)Us)ese1aPhW3(2q7iFV;RC+8lMV$B;StJLYJaTr z*?e&qMl3w1a(cq@8msamM)DrEG9dm1|DsVmdsY4ix6qyuoD)+YFBZihsp$HrSvT2* z1q<0%UkgKaQy(3QIq`}JxQfb^im=t4mmG-DqAQ_U#x+d=r*wfVjU2`MV!pdbnw&5? zb*dwORz@>FHd!Cy!R0g7M{>9luccuF6 z@ldk@rI_+j+|u%=rLG}m;_3)@_dxCTQbV)yH;chvT1%p{%T3;uIp374-xYf#mrCE| zbLEuysi!#Yg+DPBe7f+_(@X2r#Sx z2d8*ui=W~ri|eIz-5YSN_Hr)ws?ciddUV`oHgn-AF*^*@f|ds%L@lQnAZx72|6hMi zLlAsZL{tEUw1*IPozd~e)ZF6&9|Ung?u6rj+L<$uhg*JRJubsR0~5g)7M?F`8ed|Q za9NgYU8rkF_DgHIYQAh$*ji()CV|MtM5K!NbBg3Cv6&#`ixn7)1nA|1iGpH+q0M%V&2M9y9njRO zc{67cV?1_?J5P(JMvJ#&i?2*e8x-%uSWDnROE5ue2tlhOOKZ4eEBpgq)+yG@p4RxK z)>m+B(Vpg1jka|2|29#r+H%L*-p01&EVUJzw-xfVmyb1!3T-lu%{BSlgwflCWljG{56_;tYg(i0 zw`12_Y}bNJS6DBO-$BL%#}&ve?8#pGr~b0i1p_ucUCx{Uc4hK$j@9_n(E%W%9`a*M62(sJ4Tb< zwPl1lk+3{X3An2aBP31A>CTxY(qM*ITaeDK5t4-fXWa;m;aHIOO!5hFQmT+r`Yj=xV9&WBqYLy+1=^XCt9E%_Xbg5H%o)SM;jic6x zA9_d`px{YC3Jg8GBW4u<0C*udM8FFHKlG3g0>}b7KX+#3L5OaPK2`76#^aA?7mr1D z{y01wJ0=|OlchwL#ILIVQxaFQCjFHJ#O%d80EiMW6Aw3Zkezk(%5(ytV3%q9*rdhL(!enP^z zSPDEt44X2knKldjo!9W&f^WvErsPZ6kYW7vuaPNUnHs*_*>`_tonGo##3kA}&q5u3 zTl38}S`7OIlDzseN6q(>%VFBPCdKz?`q{)>A#yG_e;x-p?7=thr8OTOKYQLfg?`#7 zyJjKl=u7E-UaE6JM9tg>xy6>{-k1cnI`>P9RIWY<7U}~ z?@#OgpJ|4bqj$N5U4M!f{`|(DTdP^g%|5rjm0s+_g!Jda40AL{}x>s&+|BF9K!?G1@qqkB39Y9bJ>2I zuB+#dp5FMC2?l)*3=*u58B^+o69kl&8Q2TaZ&CfvMLeghRGGKXl`G;bVh-CEJ;jkse zxcu);+@k`aqb$9n+2cb}k0Z^7Bdn>Ta-XGZ|iV-2C>&DuYf?#CQ@$H^_nR%gfi zE5|63lk145mZe!qdmvBm8HSB!c)p;tUXh zvtO{YNB6UtT&xkLrkf8ok@bwxPOP0PO=hJ6ehDJM-dFvL_`F=N6*neZcYde$0 zfC}Bq6$n0bgT``_@Zgk~j0Xa8!#}Vho`gE(vRuD*y#_NAEDE9>TtcxB8rN6X*g*E> zIA8PCt5*UL2`j<_UE&{;*8n)diWTuO;0g`9?Vl103qt-E79~-kg}Yvc5(C0qZ=#+- zVpnex1t2L&;G0RJC2k0&V?FKxP2R~B6m%C^cvE(A)5ZZoPvrxbX6gj!znt7Q3EW`{ z0e;l~C0Zc7nk4#is+W;?o5OT(v3lG1>ZbV>WT@~#Gl_8Dig>vP4-@z=8^!cmkkE!1 z^UdT#A4zq;S@l%N%f;_6SHu`Z%)kDEp+IYbgf9S?yQ`PS0Ek_{Wb_bT4=fCig8%ir zE=#t7*W(0i7mqQAW4u$#ZGOsDF^cplh99sdfrNLqHt_X`@TO9@SAEUF%&%>&JSp$v z&9;kFnGj4cQKk4q42cC&lzx2kJ5Kr=Bsu%*?Zd)21ax~!x-XguU9bXoTy zONVn`Sygx^h4Bh`o`Pgvs~ygakza4mhuHmO)M_V(PNU~YJ=`S5RY~m*X#uUdzOJvj z#eoE3=4th2VfobwhDBgnGT~zzyFZIpj&CNQAmXdM+0&&doF@x+teE<82tcF96+Y#) zJD{MG<*maJdPDv|UTD>HqmT-liTny^r zyoDH^7F`1DPhkMUD7QX*U{NunAmy)323(?;@LZ4zX3+o{OPVeVKHs?OGXNJo2Aswb zb4{7#CtETMCr~L0&)da5F)qkOQZ?1@-Qj6J#M8?|g-g%yOa)Nc=)oTD5*?vPOpHMS z%hfjBgW}#;Ur@i41?eex$Tp?8W}7^bA-LCAt*CK6M>-6NwiF zc|Q3pY~XYUp|c>$Op8KbYkCU{V%y_uox}(x=g3blzz!DLP@IWxdeXwniDofE+EZxtGA*o_sy#o}LV6N&sL9 z(I{7MZkkzhWegCW#|8ryWw7YN;5S2f*3np2q_#Wxq6?;coqw4FZ?UeJU#Cggn}k7J z(u-NvLmHvdrqv7c@HdqXzloeB&qehDPNTm^YaT|wHUin4y=4mi*zd*8|JV!c zdcB+H7wR~}Ls6_#Km!06No2g=PxM%6+diMAqOK7kQaIG?cU8Y2Q^Pt=>QgaPQ;m`7yod0TS#I)xD07UT6lEvxc)1O zZktz$L%e&odkwO^ee1uSDS^Sl*hw?plccgexoPYUj2u?-w|^Uruw*o3N+)hF&oMgE z9ZKL}cHh~CEfKu8Cylj~F2>GjiuBp7pS{BY11wvG$oUV68pa z@`5ON&Q5F7Mt3aI~_K;|eh@x7rucQo|BF(@Im^CgW|X;oAO-28AZx1m1vRBTp;l zXE$ePp2e0Mfj^Wb+K^yW#U=^B#Y$M0Ak}i`4!{;k3Z|`(b8;H9XWLU^1>YtH!4dG! zc{%JP`XgbTMc4qh9}3KZ#CKMuOc94TAQip(IF4~>tt>7ti{zLY_h!arc32SPSHia* z0>C*pMChr*$PM#_)aU>QfP0Ea4#O(@tA}s)Q^P&eE zd)$U)IOl*pS{!()tvKjeAmlXklr*#F@@wuf&P78dUf#iKI{ z6-#2NRN}Ce#i@FJi@impC0IlEOlBBhZ*A1EelEL{ zoogL7QU!$Ey~Mn_Zt1O2bVWbZ6)SW_X1E5V%0Uw4vSK3ovLkupbn{N{e3*OWRQ?Q}+Q$0AO1KQK_h6 z2(Jl=;wYN*k=ND-?e)9@+)(vgv&4%Rgyi^CM|`{feiFj_U_*#{(NExzNV*sjH@9fW zBO4Sy!#>rybsJ5F9F7#L?cwG^*;eW2))b=e00P_)-*NZhe0?ZuV%I#34r~nL3l}lC zK|P3RvWPsl*olzo^(_I`JCTdiaL7sMi^;2}7unO*?An!zOi0}enA=*M&#ofF@Tr5s zHUV6~ij8Sy{yYRfep|WUXezFmt&Bs0>tq#v-~UUkT5Qnm_zlTDx}%aJEjHPn_>X7>d8AcXZ1KGHAA9-e zku_woEmGk>;T&{ftVOsZ^B-#U@ggA+!wR=8#3m%jtL(|kJ&nIDliB~FR$uNLM8*T< z&%hsEBZzRLS>;PeqOGQ^>27gF0R`io<$dfwy|W_Zs`W5=EEE}kMAdP$l5DH#zdZS{ z^I=uz5w8~yMtU$p|{}1;$345_&xK)v2X@2hFm~sT0;Rfy0S}0k2vLpa% z!+-|VVv#$(GZmIspI!Yhx2@#>gr)WkQDkxwVR7>#Hgp8;(ydQZcGSsFnXIrLV4bi+ zo1C<(vA01N`Oi++9~2pTqaaRBwC zs;Av7t-KE%P&8Em9*-mHiTtA;WipH%CK{$nSLRI0i;c!fUt58~9UJ55@vjYrJkGaMb%8`YM zQ3c~$R^Wf#1zf{)nT+&t!#<=gbvc#Ry1_{R02<6iUn_Fk!EyKudSuOEIAJ{qIHuMI z9EbUK{s%=Uq0;YrOmB#iB8RM!(xHNOJ;o{=2cfQ{8mFXI-EC%q6R;bhTiL9(tfal! z3je>!x#XDtN6tk(piqBNs8bYb4TYLTp?;xIKT)V3DAWiF^&N$(L!rV@C{q+l289wq zJ^trF{d@S2u>0=;^>F)t19tE3uI}zG{@q;v&)EHYgC=(W{=GRvU0&W^U89fx0J~RL z7Z?B2bGA!^0ou$xKG``vKDyf5N59Z!?$*{83T@?XY#=u_P>;Xw z?xr74m#=mgQ4f=-yNSF1yoc|uCs3zj*CzvKXTMN;;}0j@_b1-he^$2Fes8ZVU!#H0 z({TJKPM+9#?Zj-;NSqNuLRi_H`LdMn(^PBu|$1;H9c&1(^qRzTFzt zBJ{ntAFb|=w)A&(eQRrLYiw*<>PcAo7CF(G{;TD~WUJe0L-tt1`^N^J#Rl(|hKA{S z$C3Jgul3DnkQep&^}kP$#|mt;uKOQaw;V80<2U>{b-31d^YgQd3fj3Ei-}L39iKlA zeDWNscKu%MF;L}<$_sqRqkoLHL4^}M2GgK|0i(q}Jq6L-1##U4F)hUn-B}UCQFdt0 zx4OEz5`7eYDk&)`EG*2=&(F=t$V$)7k1I_|N{WezNeatEle=hd7me*6eUR++f8OJ- za_(sG*F>el$1%eoKS#R|jpt@*mt<;}1P6wM`Q`fi2YC5}x_Sh7xp}*~y>oSSO|r>$ zbaZ_4<_$_t9L2$WB*BX!h1`%4KjL7cFfh>iZ5IGw;9V;B{tH_2l?ZB)2y7M)Y__(s zL&Lk~*6+;B%nS_;bai$ANA4;;e-4Aeo;`aeCnqN*EiEoCE-EC-&(F`p!-Hma+1c5d znVA_F8R_ZiX{f0vDJjXx$w^5`iHV89;QyoO;^N}||M6T92!w%w@&6>}4hRn7CH#NO zxt}oiUK3)6|3}VM`^q_vCuzL<{~_n*tBY|b;E8`7q`#>9f0uJxYX5ZjZ6!>Nw$#1) zCV7tkKRGvwjK^}^gg2o(DgS})>zDOZBOPu;XP&92%8!C)wnTjGB71Q~I;D&?@0<2! zN!z4DG|_S{1Xxe@NfBeDCN}ThJqTdR)4wwc3B> zT>J2d=D#+W;ub7>WogFm_R73<5+h61JATm^fCpLOe*MrT&`|8`>NGUXV6n&#G{@wut%qhxq)c8`Kj<1Ph*ex7f z*}PxavigmdwUsHwytegl%4|~TFi*M~`u!WvN#`XuZJi&ZrCT`Rf))T|47nqyH(ngX z%dY-Y5?j%>%A%RuPb|Xw((1+GB~XEJoQ$kS}9|+jG2sk95U7f$46~ zaY=X%xnoJ+;+(yb*s%EO5fb>EK%wHa|EQBK(&=(ab?8N-H%E8gdCyJ5c;<*8Q|DJN zsrz)XSLTkto9153DK~t_jRt9VX*{X9UUa%o_wm$v!IwXCJC#rITWE+@{IhT*>a*`^ zkgp%Fg7&2W?jovZ?s`2=Vr6bgmMONy+vkbs&@(|d6%A>W%SF6#>H*CIPrcZScQ1) zVsdWh4ijy^G#t13o&?q}PY=p$akE{@d>B*=oIJ-7d&Y28lF2U@dO9R<^B#B0?E7_N z@CgdVLaZt12CH0AUf!Yl+Y}S@tI_!!M=wIt+*$89_}-LiBgek zWFh>a1rPkFizC0yl0Y`O&cj3>b>C{-{kNFkTcXhv?2x6%aP8)cFwX^`fT{zmzwD!e zXqYg0dj>eA&!TnXO0XoE5um;?`q5S+2I|U~z$i9CPpe{yb~l_rw4gaE7)k#T5F4P| z%Um%$#9hrC_dd(bUwnRurvMOPTm-;c!5ylR)lH%aJ&FuSUA=^~Nh^z|sKE^BNaIyU z)D`Sg#(Gybd5fa7-=C)z5tehw(13XGHv<5z7Tc7PSfVQ+EDXFzVZa(@F<6Oykta$D zn~&e;yhZ=gs#HVy zzX+HQ!=1m0r`m@S=FY}dDy4(;a=G+ks3*9{s&KX4J(3x>HC3d65K$goWSLM9>LBM*s&G7N6+u@O^!c9sgM*xDwAnvJ^wD z$&x*l@^{7ERUP);XU&g`d7~ssG&_D6;O18Kq;J|~7}l>O7OnB0#=$6k;cW88dRS)j z4W5M^PKuhviQ}Vv48}zvF+TV+EoKueq&|4XZHw`Xms~p~4`jx)xp8}>oRA#H zWXD$yvXDtESD8S76VhOYgO9A&2n%tVOiuHXoh%S2Lx%s#=z%j^HOxZ=FO0r6wDUoZ z@C<2aB9TazFq+j&X#KJo0B-(^oW--~^TKsSdJbHdV*&^GCIQf8Uh1F=&FQ}$I?;Y< zGkj(nVz zAf{MHKGcy}g&exm(3aPyGu*p?dAKH4h6$Fn4eKo9xz4Co2pal~iC2FcnzE+P7}}8z z;CaCtg_uGe*bz?vgh3y(pu!y1Q4Dy+qZ?f~1wL3I5Hj!s7FQ6)KD^-UO-K9T)tt5_ zP5s|%*N4;s$+mO4z43D&GSWXXT?H~B4QbrK+z|h+5DM5~2UH?kA1@IGItEe*e53#X zt(XTP0U(TZ2*ev}1;9CG*(--b{OA@ox}&IVK$(nl)E1wK#uKvbjw3kLT#iW-TD=TD zd0e+<#?Ll@=kkH9LLLGsMmYwOt6de7u>f$#cpqz!59|avNYA?^C0=Se(>Utk1Rel{ zN4%y_jp82<_o}mwb%j764&?TF$|H0Nb-=9b0H8tk1Y(DNoZpEbM@ZGF&T*?N{?0Qo!X`?7a+C-9 zK2C_obptPY#YcQ!*IFP40BXQ>J~VmxQ40US4;J_j z{=g4$k^<%+4jKk2E;AW8^;`e|cXHQU2=Q#`w}MA>e#SC!ez$w3v;tV9MO@@XU?fIl zWJYMDMr`Cp1%Z04bb9|#1p|m?035b9T2xOJGWeI@>%NGsJ=X{xVA?LFK zzBC25QUeA93t-R%v#<}P;BVUyaQ8rP06+%&01H+?3k#=)ZMchWxQ6pFJ|j?a!Z?h? zSd7Lfj5W|veaJ=S^g8I|TmZ06?(|OaG*18k3qBVC?eGeYn1q(tfTYuel9mt^a0n0> zfm8?~=W{t=@dN@f4)lNz=g@2dL2Sl`Rs)f2`oL^3p@O{lkNB~ElM{@`Sda!;a>>Yt z0+CgY1pu2fQYD2_DYa53)lxX%4`N_&G|-JP=wp}2V;>2U;D|$7rwCFwg`e1q0J)OV zRp5kJiUoICMR(8$0FzZ&mqm{Ru?p`X5B5})u_cb<*my^o z5JR8{t#(^bnU1`5l~uWyRw9tz*cSqJT*)PWU+IvLHG%>WUDH)v(^n8MkPm{$mIK9j zaJhJuNf2tF2+kl4eL#|Ud0%?Tm!cUZe%X^K2;VGWSIU;w` z1d6bH&@ck06P3~Fo&;K*(wQ#UxnbaBWAoW}#R;DGiD{H65Raz_xnNu22%VC|o(0;W zF~Xsd1B3C|VGD|crumJonV}O3p$2gTihu~U#Re++i|O`IAnKtwS{{ChGKMFgC8`iE zbE23Sm*1(MN@;usk(q`d4gWc#FR7k+d7wEur5`G#aCj{G!Y@5aqJ2>?4~m>c>V&Gs z1D%8m80w_);ZPsrk5oFP>jwbIvMki1Ce|{ic1owvGN;+HEqS$~Eb6C5dJxMQ2Qm7Z zpJ_B~+NL=ArjY+aDvnwyqVlMcI;oNpsgx=yrqZYR8K^0Wo&sS3hoA_UU{@Vrs2aMS zR;s9~njLQ{5L|MnXwoLII;&tJt8;2Fno6XADyEdlpMPMcDQ2qascEUYs>XU7H!3zY znyb3ntj6iAf7*Bw@CS;}1e+;e!b+o13Yx`wtlsK2$tpg}`lVpHsc&hn*{ZAjc?erz zS9q1KX*#Zm)2-iHuTT}P1GKFYx~u2w0#R{g9-r``e%W=u`K4cZ>y*Rv~KN&M($7tVqgyDAY3+kYGAvx zUi-C78=&Ob1S0?q(qLq2`+^+1xTq^3;kt4y2RtjV52hdxR`3sGptqL`ZkgM){|dOJ zJ2UHA0cR^_yo;4=%Rfh(y7d}9V@G{(ClDuC5O${%SMU!{paIr4=j#E~iUt}` zxcmFQ^*g}t`vkW;EQyM|Y{)&8cX_~*3i?10=g@BjA$wl23Wc!29NfVk{J|g`!XiAv zBwWHKe8MQ4!YaJNEZo8_{K7CC!!kU>9qb4%Ith~?x}!kDJlw+|yb1{{EDOxQE2uls zH+|Q^Qw+WW3&4F4 zW*$Js-8;r?oV^HKyz@%LsjE8_Xo38If&9?CaW{7evA5pYxnaAzhfB!c;-ZMq0s#MT zq2&g(rkl9OOUH0~qgIH8TIdC@8@m87yR{o@a{REH8?vD+%3^yWC<_2DU}=WzB0+4G zku1rKOS7n?43Rszm2117e6zXhiGKUHz3U&1un3C40|1c5UAM|4)5^dy#IUS)NQ6ps zI}i8p4SDOyJ3G7)i_O_w$RY9wil7Dpu?*7C$c}uaxh!pp+sy6BwY=QRgIvzPyv^<5 zvtU?zUysx9IyYPI?@mwB*3jm{f%*edY=lm}I{Lc>;&^ar} zq}(1HH0-@Rj;XKX*4MY#E!09Z}x=GPwX3?5k$_Jg%^|73gKu9;hd?Ej>tRpSN zC2i88iPFr9(HC9N@@&xM0ji213DL388Vxu6%qtPC)11cBeB09Rtj{jZ(&FK(r4SwB zOwK;7)Hm(QPTjFk9mq*d&{RFu+{_-I3mr)y4V+lkB7M4HoxC}XZeOj0yDZRMz0!Ma z8|%se&@rmcY1PSm*Zo}AbG?#d4a$UF)qUO0jV&G1TCLCF0p_XFAu892eXNVE%a{$> zkFD20Z5``s0necYObVcIZPN;21KltW_@EAZfzGeI+0)tCnETnHebztC+qF@lXaHS> zV5Wl|*%M=5FwhR$Fa}a!2SW(ah;7@uh}*cU+ZA2YyPekJ;i8A2$Qu7p3K?tN`I->I zuy$=*+tNLn)SY;Feci_0+uF??z@3<+;I8dG-Uy)%$KVa}kPfm)+v&~O(LGp8-J18^ z)4pxi@tqxrtjN&S41R{Q15`0OaWMpu5BVSrVZaLbpbA7Y-~pa~>n&6V9@RlD)F&<- z0t?Op@dBbtx~na&K2s3;aLWLY3^q>E=pEu!IpQ99b?>d<3!dW2VFZeBu>+CD!dv2f zF*X%m5bmH2>4&PEu z8>c)FquLBdiloDu5O<&s;q~9p-R6lt-5_qchRx`qozmFt-luL8cuvd|T3e)W=?W;I z8w%=C@&&;l3Zc%e{88Zc>E|Zy%aP94+%f3_!30b?39?R!w2rF00s#)L5UyYi)UfM_ zI_kKL;$9Bv+Ai$d?iX`8%me|flPHPH{$#$MC{3*uFJJ@~5EDy)4c747);`D0F66_G z@83@B39c2!4ge!?t>q4h1CMCwjwtK?9n@eAu2Api-Rq@p;9DN-b^hr3P8;Fw>H?wU z9#HTE5sBy?@w{p4QGyE8{-X{*@(|zc72oA8@A6-68~^_f09y_61b^;rcJPOi@LACU zXkZ92Ap_N54Rnz5vqSRrCGty2<`(bhO`qMik?{mE(pb;Sg-Sh!t(*p_tAg%Xn!LU00l9@1f8%6@2U_Bj|$y?*hrrh0DW>;lhF%3Ta>% zQR2jf4k1#+m@%P6jU6>|^cZp?NRcHsJ~TPeh$2Ni5Mq+X3_?ScDQ(iccr&Cxf;xTv z6uIKx3ZO+3K0&rCghUCM47Hf(${IDJRjppdnpNvot{H_A?V6D1R+3>)<}`b-Y+9Ub z&$?AxvuYegY7jzTCJmFpwQl=%9Sc|R!moonYS`7w&O`|qr&z}>GZicRU1^Y?Onk(MLjUPvT zb+=pGS5cF-{W-eX=US^{z1|T5UAqWzNy8NvZSC>52PW^j9KDxbzhqD}Vq_w!sp#$B z$DjY8`n1ihW_ND7&;%^4JhlL=3PFriL!>o>UVug#Cd8XeL7)87?c01?9P%by;M!?G|i~T zLJ!&kHrXhok<+3gWlNTSjsZZ1WY)pQon*iQV2p9-p+}rB46@^#dgSru34`W9M;~@n zk?2w0P$A<25If0a$VR87w%US}#R^rQFcpbgkGwt1)c?da3ezUsg!7jR{CnKmQNBIQx8Yvdrwab? zF`)|b>VxmyQ|f!7w6i)zouvvthz56rF~|#c`srsKqYIiN9)A8Y2Zn;!k;R}p{wV>W z4_07bAX@ROqnBMKtw4(kD2l}z;9lpyf8}Cl%koT;yo?Z#A_g4E@dl{CZXNG#7Dxyi zq~VMX7%z9ayWmX(Xchk_!~+Zkf!?*w5sr(L;2hf+0~x%bj`Y=l9mNR49LOP#2mpY5 z=0hJsXz>po^6-84@jzng;FB*{qZ&2vUlNsgld}O1Ms#CY2Din)kRULDQe>M?EN}=# zG(jQDkcK8ILd7bQ5hEL{N-6%q4>tb8AN+7u3d|vnr4(cp@o<_4?(rdEG^`*3Ap-z3 zXOPY%WPR-eAbxxk3yetMei9K5Dwa4&N@}EuKtW>}v6w}hZIXAr6HJ}Zpol*_@*qr* zMl^0PMo)e+fU|Q;3cN5&FQB6vUI4%f%s~#Z8RQl4s38C_V2@M)pcv;chzk3bSKMbi2k1fM#v4i|td8Peb*v46Uu|}M`(-D)n$0}CqkAW=NkT9r9 z21)-yG^CM)D;gLuEe=_Z!xDnT$iXLcFd_?XyyX>1`HWCblaRf;Vy~`651o|*Fo&T?}yeoJzf!(jgj z+lg$Z+u-;4_d%9D=6IuZ-XL!HOdFGs4&o zuB0iI@rRdLTs)X-T@})Ym{gF*D$mNoS(Narq>tWHim*alQH?v3-00~sIg8u9+Lnv6 z=}u>PMkw1+g$!>_BF1@~f1C9COduA!kg7xsk%SPLPe@~;o_1`(!dwJL1^0WV4tP=tOFpAOh)W_uS85R7Z z*f~m@*hIA#f&o7}-~AzJ{p)LHeMN(xzLTH7?G-`o+{1>z->1KmlfLDGKJ<_S`SCf1 zXo^n2DT&CR8hgJ8q=@(vKLD&eSF=Bd3qXW`HBUnb&I=>(%0SSoz|ShcNA-|$P1y|Uf zh~TPnqroY(BpVFBBt)JbaJSZALrt?CCm^!>F2%2+--8;iCOv5^aFDuj%kD~}tpazkOLn@>|LzKKb zq@CE4Jup;_|5^yEGs8iwKP23`IaHAlxPt~`h!&WVBU1?BFvUldz(~ZwJzP0ioW&zt zh#t|dgaE|76G1RU5;f!!HUtVA_!Fg(h%!LFgrE;<5I9$SKUkzYU!*-+)Il<1w1pUf z&PzEq2LPQ8L^gx8rgjqYhNzBLQ0>(6lU+cDK#>SIXu*jX$+9#{qpVAI z^hAiG%R*C0w7d(=QwUUwhO(PWX{-vY#1Fju2^zo%BOo`ybj7oL$HffIrToMTyvEG~ zqZCt2hIG47^dC2*h#FuW&tyE%ygzrm&BR~ zkr9!IkHQ8dqD{3ct5!&ddZ-6;SU~^?fn=Bmd+-M6G&SO6INiiY$~?)+8>K%`zk^T# zZ0p4GG|wAEFi}(zJNN~yg2GHd13yHFNQzGB1jjm&;nIV2v%g$ zk@G7sum^sihZRf(eK?47C)J5F@;8BA}r8#Iwf>nLgRJGMy#noIL z)hA#qT2P05ssYXXwl>8K7)Xp=5j(D#kEsaAI~6s*@&JVr26^a$KMmADO^7t@p;ah^ zZw1$I71wbk*K#%2b4Ay5Ro8W8*LHQ+cZJt@mDhQt*LodSLD;`ZDA!4N2Jo=ge+Afp z{nu6a)pP(n`pl9A8^?q&ou8D58K?$qa76!TJvQJH2W6PjDg}TmB~Fe-OQfnr5iCGh}MD5&%LOR8PHvJ!?lcmgmG27g!#1!YhN zg;1nyO0o@Gv30c}U`5Jh``Y30{=k$7M0MWgoa@2y~#HL(E%{fdEc> zNrj*TYJkAh-7?$MT;2`Rv8_c_yFDocfGtomAayq`)iEgh7c6DokFf(}@U@88sE=d_ zU$se3pe%^*U(K}Tlrmxfuv*ivg6+E;%fBYb`%T?03HD@2$-PNXxw5A z)8D&{VBQ$Kg+&O{$%L~_zF?TmM^>q_p;(OsWs0a#Ewsu!_GDki3Ndtq@_2!~$OZn?Vrk}JV5X$4alvG++GTFs zXoluM-eW<=3J93GQWy^juvy{l<#Vn~Lgq(uPLZB;Sc#YdS7f6=h?nUZ@MrfeGP>@i8yjTVjj_9KnK-U}_FldkWxQPj~2C|%L zZ`$eI%xViI>z2L>T$~AxfajP1PP@ix1cvFD?hvgl<}zSpg}~{zuB5o0%%A>WgVt(= zc9YiN2u_CRt2XIEH0!Zh<8kYRB3y{|qK2kb?7+TCdwyof{?e_EY^>-_oDg4@R_)b3 zFn_CR%W#5T=!O5IU5LVZ!-WvaYB6NhEPO_paU%EZ?2{-%LM=pm;|u4x!E@0m!|I4u>!UJxvu)| z$)zA-#rKqXod;u>;CrdK~`$ftM0Pd8ckLR($4QW3vYyI<_>L(p3Yqj zKZx5qGKaowzs~H_UT_t$XsxhshCpR)E(k_6NZleg`+mZ&^re&Vi zY|{oAC`gJ)G3H0G>4I2B7@zMCMQsn2<-;6t8V?D|Dy373kX*oU8}&i?-na(e5)i1e zIHiasum=BYkU=GX9T|UY1drt&m+PX)MD@M_uy*Gshw@)ei4zcIFW-`#yb1qA^E9t; zg=_K*=WtYW>@_cn?90Ur03&9Y0cSRJHK&S9c zUq|yE>;G2uRo97WOBV?E4ri!UNndYTuXQfmu~PVkeITE{y=PNbk_+gN_toydWr!<) z43Q)C7$0FR@CSLIgi1c^EPK` ze|eZU2@f|2Er^gZ2KY%&^e+qL8h{0LxQA}2gH%ul%+ZK>sTTmamwefmegS}g37CN? zn1XnfLXZM6sF;V6n2CZWmS+)HAOwwOh>Z$om7gRvpJhttZ<%-bSL32jdG1^|yqvFh zJ1^&yFa>bfhje%ajh%vh(1@MsnaweXpc$GmD4L^58UVP0eMnA&Xr_X&nyVTs&g_IE zH+yFHdYdfqE#LNgk9iR{2`Yc2IiEG*rF*)sdr-8AdQb+AM2Hgb+>96;00<#MLLC19 zP#nf_9LNCxSXc*GXoq&t2DKg}JMtX$@mTjkEZF3;FL?LNpWzlgTfo^F#+c#~+J=OKImke=mL`s>M_?NNq&I0reHgLD{&@hP8zIG+S82yXQu z{{aXmu22CeXz*Y`G@TwHY)HpiH4F_WQmkn4BF2mwH*)Og@gvBPB1e+MxZ>Z6k|J^Z z!=VzRhC&)%j*K~zCPxWIq}Q zW%TRlBp#T8&P52>{CeRVgUupA`V?WEs5kFYdt)D+d3wOiA@H z&O*JAO}NOT$%u;|s#&9h_%i0qnm2PMdD3v_f>tq44PCHwXw;omukPs+jiN&>0H{Ff zEXhRHn|1GY9eOlLe_9RNz}KLKs{XuQ31*_f7$zwa;LQe|7+r zBU^A)J&T`Bv!|G1S1&OtgINpK{yzTv`uDGA4;(RXngvLjZ|n_7AW$^%fQTYZ0Puos zOi*+nfCU<8;b#AV^vWy!$ig9q-=xz~3SOA#1v=e$0l*68kYmC@ufP*QK^WMR3IKNe zGetpR&;>v->KN2bIO?Ia-+i(4;)+UySVPToNJ=>+l~sb&pJ^IWMPdJi37W>`mKdfc zCP`{25(fkjO5==#6O!4RmtVelnU)^4(~dvx+}X}L;*25ESS+5C&J;Bm`kWQ{By&X< z-OytL02827P8edGBThk5+*6Ddt?)BmMOa#ySslIX;sHiwWMYIxBv5AAsIkgAE0Usi zR;N>7h8bsTymF>%RKQ}?gd&OXkOVVp;#QHcJ2mU7&J#Z`mm$QMYhtKD|~feWJo7)TtuIJ^ZNTQz){JYVM_?+_bg2a zzohWO(R$RvA&Q{EgfmGk%dEqfF|5+YAx#^wN&|yjk}JE6f|36gop2(7MWQ@8GR!f{ zY$RxNNMsNOb4XjT#u@kQE1dXsOw!N=nfXT_&`7h)QWq5+($i4;?9|5@9diNz$7sE^ z)*y>K^G8`Y;D7)ZRj^4XZBoPn9Up-GHrxSYnblTZ9aeS1Qy&)fM|^wa_uqPBbc7;` z;3ADQxkLt&;JG&LIM8(R3{tfKjB`2WmwSC=+#*rXzyk~1+le8an|}J{pb2+S73tkQ z`QDHF1h`bP<3xMyk#|(VABrR^jV3H-gu6z>7jJt>c%vRF=gW7*zynBN#6%~XSb)(4 z*g3yF_m{2r%{Tpk1O7MQv{U5kS9N(X@(t^5u+Z%vq>%s8&ajbt{O`m68|)#ipsqn= z0GfY&t$Ph2zylu8gNr~Q6P<97MPfmXFBq_b7JSKiwy_O=bVGyNP=+jqLlxz5OnxQQ z-}>%jyy2M;07m#7GcI;K6vmE*HS|yaKoX8t9HbTK16TnsSdcV4U=J8UgCSUD5&FbJ zh)#UsMzBN+tPxCoH_RUvRoFtJnJ@_zlLjsphd(Xaa923AVo2t3g@agO9;t&OMfmW5 zG^oU7)PN%%^Jow(l>kNnaKbA!u;(lG&3 ztYc?r3|28IX~}i6vm;5!1>&612{Z|_ofqn5@^bhQGT@^ew4g;f@F53hsxl9Aq`*Zi zfHoyk1QjpaCPYt%C44vm0N$X*A3Hfhee%+l!;}*~^Tx;<-~y7-$b}*h!GlDmGjJhw z-z7^DhHj_>9owM7$b#s^7$h(YqtjPKYJd%E@F=22eH)h2@d_u@gIr>WhdBv(&ySAj zr6=Tw3N)d##4#aa!DOjbxfoWl#uSt~bz=WCQKmBCQ6w0_DC$w;3NtL3Vjum$6aZxL z!>AmStW@pQUjdsDM}Bb`S^&V&Do~S_K83N39qUK>dXWp5VivO~MU*@_z*J`80S*X& z+0dpoxstYXqN+g{urr3d&@zSgtZHC?qgHBIgh?pu-!EX1hxRfJ}4Fd7U*43dOOwF zN=~~T2}d{pD1&f-gP_lZ9s@99gzAZLA{d|pDy=JED}Cl0DIp(%zY*11vNtn|#Mp1^ zIT0oxWlfmqFKiBRJ@tZ=yZm!+M>79;kTBT8zN#dGXGOrkOl*Ro6NyEA1}tMLeP$ae z0DuQ`yp09B*0&9oYKI$g19(PK6E8r>5E9X#tA1Cu5$1?wD>4sq8H5aO)GS0d@LWA$ zga;Y8$U~~(wi%N-KiK6fN1^rPzBzUy4|daWKH*($0C6N zIQ*dxee}b?CRSx<9T0R_hCNsPg)409_G-RIqD${ zVWTt7k0o}G?>XdnVxqhgfxuAc32kW;yo#!%v=A9h$Am7lA}ly1x+6{%ENNrj2BAfw zvkPR{mU`o>F$E@+77bh+*&@VJ>FwG)Lrilf$_U{a%)6#&h(;lSv%UzvN>>s3WK-fk zrwNwok?n#|!F3uhcC!zTRa3$7Um^r2!WE%~rgx>7acyY8CF zIz^~phq%z_)z3uW0|p>n>Q27*I1$w;%rTF7n1eg?-frtdKX}gUJ1JYp7{nxo{H1$$ z+J@hV494M)enihL)1o1e5y_}O@Z~3c40wIqiCNglK zzn8u0)OT`lg~T?50}j+f_t}AvcpXITL8BcJ69gVYd;vs|0Q*%SMYtbLz~8;mUq^wS zO58w&EyJ=52(cu>5X_$kqTq*>L_CB602m+uNI{7y;5LcU1CY{4TmYn5AP?@*wiz7K zi5>u^ph%Ej#X$c9Ca_h2MBi6UpAZh=3X+7-yx?jkStVlHw(A=IKT4kIxZqb&lXFdCyW zF5@uA}4976u{228%w0EL9Y|h;Ec}CcOawd7!qClC7HX3VJl6q`-zJ>jL7)mtx?}US zLp>IRDzrmQ(gZL9K>-A&U=Ai>7N%hyCSnri4iv%;B&K6NCS(fcVm4-ER;Fc2CSzV^ zWe)!VkuAd!JmzE?<`1Bk0(2!MdgNE4+4TXy7_>t=lx0J_0y_8uI=n&+sO4rE6@Fnv z19d_*)nz+kNj{_{734!-zQkW@rgB1NXfCI78fJ4or*sBpbWZ1B{*p9AgC^(zb7p2? zZsb0irV6HJM`E3&p#VGBL7-Sf70?1Z?1MPu<#Od_L@9u0Z9uAY!XLECCjzI>VTn3) zUO~)40v;V=B&T&wXLTm1axN%?UZ#UiXVR=m8C0f&E`X9X!2y(Jc?t+3vXH%D1WR1O zV64EHA;dP2#d=}{8Ki^VU?F`%Q~+!lMzjDYzySmr1R+$z9r>r)(G@?0gJp%oK9v8$ zajFD@KIn2rsFHRkWi}~-__X4#tTV#8+t2nj%DdzGr-*fVRab zM8(=|j>I*I0-yezNRGrTW`vT_bJRW@jrVrYW|rk8f8gMBFD zgy=ec`1@?c4c zmS_slrGXyCt_tg6GOE570Ke+%ze47OGJ_T@sg!Q%nQ*73erX4Oq=!mtRis&ooJfkS z$V8-N%zSGFDO^TOm(DrFlbD-Rz!SkHOD@1GH#N`p^#jYctUJ(x$Yvn5At_Pzt78W2 zui`AP>g-|aK$R}d5IARaX4sW3th0jU!vPM6O~)zS`_y@~ooL?V;N3VEzD+;R2-! zt#>Lb8VqK$a;m3RA`oH()0&RP8W03L*SM~jZ{AwZQ3WVyi!?-D*rNXqmW+e(6~rlw z0|2B#ITape#I4*?XRw|w-Zts#7C@xppMqv4!p4EZGV7+Erk^PyNxUuCEUp0&5#t?^ zeo}-exPsJD#SJ`z~I^Z1ak(L9m0x6@)O9(-^#iYL+hcZtvWt zuH1GngW_!&R1Co;=wt$JVVduFcBS}UCEaK*XfsW{m&c}Afx@yZiy=(p=Rr3^r zKBR*-XhS;W!yN!XE5PRat?x*fuIeJN%_=Yi>+oStsAn#4Aqf9L@6hf9-);pLE@~d` zNWh~!(qpR*nBt`YU|0n8`~lw?#0-eSN=C&6Xp0D)@O6EX6bJ+O2t&76ge;&#J;=j1 zuoeJ>Kr+mOJ$OT`Rs`=_1P&*#4+Cr;3oG3|QsM-y5R>l_Gi(_;?6X2F9@}t5yks%N zPHb1%v4YAG3L8Fh=0zLF^?Zf87IA!brG^H3V2x zXp1I=GTexY9CU*@KuRhMR7TLiKj_Q~?1L#3gcbY)l~Mmh9#=#y_bU%u=RAvVWa>cP zZD*4T0VE{sVHR`4k|*I}a7hg3K@{gRZ&MS@QC(z&1;}MV@El@j%N=X8D1(M6;Da*c zL-)PHUReYc{KJaW!9Q3_LAV1=B7|TJ#ufa-6KDWT$Fxk(G)>pEO~bSZ4Dk-^G*9=m zPyaMf2enZ9bP*In5ezj_C$&=ZbWtDmQa?3RGqq7GwGhBlG+;thKlMf)flvcM5OBav zhqYMKvYNxhpuQqG9wrjsOY{#~27lJ7?Lw1tFY^QcGD}p5Cwr~G7a0j<=5BG4d!d*9n zDFo?|7AaqA6X;w509kSMY}i5IDK=EJPiPBcZ}anZ3k*tuabkorw8K@T0%jY8W;eu2 zuRu$`G+n=SP76U+&$m)HHGSWAP}?_t@3&MtwNMWMQb-bi2Q?8Z!Xx-MP8 zHG@BROglJ)L%4)bI9%JcGGoM_2I`>FU};Tp7gI!U{w6}q>S4@7NpE*!7eqUZ2Mod^ zMkK>KbYDS`v`GU1N=Iyl-*5pNFzOQP_SXNibTTS{M^gAgX@*S#kP9vn8}kw?aaih6 z`&N*1Jph;Gr?@o)j5QHeXiE&MxVKi`pw)vMq=G!8G(|*!jHl%}r!xSob30GOJ5xkF z`|*n1eKPQv&xt|~E z>@q5$ryL_M63a1hNUUtjvh2&oY^+Rq1=(imssD1Q$@lVQ2S0d=tYrdi6d$NSM1WSG=qP{kan+ z#_KwIap%S#Z4l0Tl!pZL9<=mQ@2sS}0VRNE?LrQO#0(6THPgfw|AV;aJgrcDMv!|$ z_&lx8dflr1-Dc?z*ha1^>PBX&zYco5e>{|DPwp#=b7y`5#wo{zMKR~{R6ZB6hLW2jRkWGMSsFNXs)U3H0$q>Uocr$V4)VY&qPoE<>di-foBE_Ku zITQj?fN4{wPoYMYI`#kQjzT-AX4Sg2sa338!G`U6wSXpR(J+ZsTcC*|MNO)boq9ll zfTIEvF1%YY?_P_2{W2_?Q%*N?HUOlO6WC`^#*ZNnWbj~3uoMuPblTLSpet+Ce2)1S zE^=wpr%?m#n0m0^q)XSvrs`F8ZK$+u=PuwClQd~*byNLuNRgV`a;4I>dlzu(=FSzO zZavZzK4tl&0C+_@bx6nE!Q(9Oz`=lu5HfW_Q*a73R6fQ1Qx~3oefxgDpPqjAb@1G{ z{fiC20M)XpH)%8>P%1SP`QwM460-YN8WPDhU5h8kFdISldCqB$hihOcpXvZ>bT;KsDoNxt&hbrKt6DP(n85xniMn$;*67$P^hY8?n>0QEG^T({?w=)JHkwCzC8u% zlT`W$c;EqKdXed&GRm;Ppe0<9fv11|A>-6tdELuYE;n>dDMYtAl-RK%JQk`WoRMak z2L;t3js|^@%Gd%bJ!;d(w&nIxKZ6}f7Ins`M~+nFd1cpMdqvHpJbKxM29RJ9Wv3Ky zg`wSj`JMlXT~5R0Z&+ogy7pLu3mt+PX`UehQ8W}uWPySweJb0bx(zI2jlYGg(~KgR z#U6kB!ABTg|LylNH5*{nRfr%cC>Cpi*-5m2RL)uFic;R|W1a#f7($^XO;%_hmXXF8 zP>crh2;$I~tzs%Cv@}ahJ2q|Op?=QDgD%E+6J-;3Hf;b^&*>Prij7)eS=nHGA zVL_)>{?VuGz4->9=exSrDQKdRB|NUCmBmFGXttO-Kxq|;qgsj)Z|dTowzfLF%zX+x zGFkpP1^^k7SqC3?k`W4kF~*^X9&y4bh>CjXA;^?<@=@oGhyL!nCzBRnHI|h+frFq4 z>ec@VbZ>lbzTe)t4%o+m4KKWUrVuvrz&^6C4Pr!&Fw}9TF87IZjI-7>eSnRkZ;W=* z5#0-K3Ynq~c9;hMg?YBIq6=^0ktGeFBOJ982pRYRiz^6YA6{?>^qhwimVx0Hy%57g zGP8*h5F{8h(+N8MVTA~ea9w2Mk@SW#IKy>MP%I=+8KQxp-HcB+M?i!kq9(q|k*{jn zTA#PBhP5Di427sc0XytK4$&3F6#Brx>i*#bfq>y3R2WDxx}gdK0>B&K7|1zlq$3lO za42Vc00ClAs}!ZD405BJ-Ee{{GR`qi5bRtLeWF6bxzI>_42~9>#i$wXFgHG!RviBt zB{f2puP5ij+z){$9Xy(58=_O9K~^CTfuvv_wD3R)j-iex0-z44lo7POeT6$Tw5 zd`F@oBYEOT^Ffj^+SG|L{c;L*ga81SBnS=MaWa8;fgSzm$2z1qI(N(g0H_qmK29-^ zR*a}1A6UUZC89cE@`PnE1Hc3>;E)W+sR?qMK~7%r4|@!hqV*vrPrx}6WC|^s0qW>l zbdWS=RCAC+f)ZScbR>(&(uF!>U&;v09K`I&c0Shb8qJgiBDuOXW)dwJelxm9|My6m5Y%D<} z#rVfOfE;C>D7d=5-HC$_M#C%%lI;2s3AFjfZ(FzgYl73>#XQ%O+Ot>VH6zJBH1nyrX$N|9%$nfKylN{@hw^R_aTUC%s!%DJ8K*$+x(f0!f6x$WnVx#4Zih@zZ0 zg?Tqu^ORXolsuqe$N;zu(g^mxiiS;#N?b=Sw5jmXH^s}bqJKvdkMDv85b_`-UFw;Z zj>&bJc84I})geM?Zpe^O3{-R>q9&$4PiSWnIugdnPdf!ZtjBO^VVgogIM;xuYCJA zhHqFS7G&2xEWSFpx5Pi*gqYn}$0s=rZ(30Q-H@}F?+giKU!h5%;q{)18@3{kH9$W8 zsa}2`ZZ`MX@&xh1yBhHe z3X}0S@o#Y)$bB51C>Kp4tj!8>Vl+{@W(Ox?M{#HyqJ|f!t&?ZXaR622J$Fp^_r*oR zEles7obS0rKPQNSPbs@mNY5sZlR#9dHI$h(@TYcfNHm2rRjZxa0qe)<4I$gruUkpQ~>|@_13-URcJSD5b*glD{ z-KWve~ zI1sI(&}6_`WlBR0Rau_cX@F{2rjx{W@fFTmsL4Y?Q!q zDtqitm+OR7@b$zZ{#B)KH-`Y%&p;sO(C#BhfuXL#S}qOuCMU z$DDy{j=A`b*lt}~?~Q23I(Hf_I>PSKw=TG)gbnO#imfS%y(xBSMH(L?V@Jxf6ZQkD zeNgNbJB&RCy4nwTr!I_Xk53;{zt>Tyh`FP619^hzOJUX#C0HftKk_&+EVGh0ZGCLQ zVpLV-O`T#yR!zr+ITLZDZLOuP{mAUV$pFkP`#VL^pBspjM?t{>3$w}638C=Ct_%A( zZCy_xP*0JhPVv4@X${BzYl6EAR_-Z*t#X>@E0-XqqhOF@vh^Vap*_KgJ%#&6oWPpz zNP*OE#`sG(OKXV~TR4o_oM}gDs5U_~UP|oHwCYhR1o9RvF$COC$n{NeiNS11F(^kA zVt@}~MHF1rur9_prIdMyCd6-fPjqHB;beqf zS8L%a+x+9ucMcA7j?s#x{F#fc9PqN<+$Y*L%pIcI#M2D=p@OVCwxDZZ4$UrW^chO@YWL5VIbNgd?a;|q162J ztWiMstCC4meLkNk&0i!0PEBD-w6uW zXXjinB`&%?Djpa01wJkh9MsrwaCY*o;oB^p;TIKI#pn+P@g_O2CfG1VVdqNEOrIn_ zDPR6lZscN^mC_u(pfCe0K-3K3VKJ!eacJs@?28D=w6w=GF=-nyKd|XYJF`YH6Y<&c z7k7s?)V?J*VtwKH7GS67v;XZ&iJ+zy40<4_X7(07Unr9GOML+88zs3rw?zSqN!}eb z-FrI_hq3*qY!VMsCT6_tnUwq-6Ew?3EbkW|y`(0QKP6r6ZH)^jz@L{Nh8WUS^Vk0; zrK@&%h4$=`HaVJQJvw7r!l@Vz({Dzks%YCUcRbZe8mRerQ+Z@ZT_mpHPag=DuH?-- zrzz|q<^-pT3pEQ-T}p$SdALnK)!mlHwWz0D9TyuP5~?w^aG3I^Oh;mzCKSz5Qp^Mi z1mqT}GIjT|iq1Y-+UNu0cj*WWGq-Zk2V7#5WY ziRA-2=>P#n8cX2$kHC;V3ub)Zu6!GuUiCBy;BRCBQCF+lI^ElQtHUUKG+4Bg0P=%P z=UQ$5k2ZRmyJ8;#VQO!M*Zj$T=jqc=f&Ee=#U)Hu-JCXWY?``RQUeU5|1k35du%R* zqfXlvJisYGGM*iV^N?hCI`G$%gq8i~T{Nf(P*#{)LeJ%wNF$LqE&c6x>xR!!`vd)*3(e>B!bfcy zkgPv@m2_czop~26nE30r)@Jg(->VX*{nyo0ewyJ=mXOO7nR$ zyBt+(k<~oHj?;8SQ-WbEN=8EChh&VbhA2fg$VXvFZJRN+C}8Lt0PS8F*Z6<{K}uCO?n-LC zjM&7$#mB(G4HSPd^=*v5mv6pglehqd)PkD(>Ah$O_QIlRV%LeP zXkWs`GukDet5t=D|J=i*1GG0b;YlQ-wh>Z2o?wqNlg~4?X_tquml%`MO9O({6Lr%V z5j4I$)JGF%NefO>+S!qBV!avvBH7aGs>2^7BF=o7suuXiJ2gPQl~^4=jk*EcTaqO+ z075^vpUz}Vs=vmT>kU654$3lg4vLeL!6-AqqIang`0Emu!MM5j*jYcP-mm26_FZ2JK1-U7%h-;WiGRCIsm`?yGVzxD0-*k?Y2Y^el57UMwCFKLbmpjLrda1Nlg&8wyD zL{uj)>RS7FXc$BNat1aVDaE-N$+DIryclR}20}BJ>n`p4C|f+r*(KoaS_wq*aDGza zZ!p|%`|k4B-|t@Ea}t&D`pLv-ABT`W4z=B62~6790HbV5?>^5^;)}kS4<-xkfhD82=Q|+0%i^$ z6Kd-bsV;V@S-Kp(zLr%IGPjjETa%EZOgs^(w5g|v&-BgIZ}-MK;e)5fu7x_%ckR&y z``M}wJB|MHc~Uo`;|HBgN^9iv-O&s|_L7V(QsW{d%wXwi5TX641Vcl#8%_M>&Pax6 ztVp}(O~_oUALhEZ7gdXUf2Zi%Ai1=IcSA+gk~yHPH%Z+B`Y)6?5LvE~*nQ#>e>DhO z4_92^$Czo41nS_fe*nlzOok?Fa%(u4E<23s3zn7{DF6!s7b(WPLv0{|k&Y)x>3=e4 z8Y}XKWELj@Te=F`$XPlGxs$RxmVj24TjePv3Pb*5y@=sh|4%AVycF^1MIg34;^50#st`T#X!h~r%&yy-$&GrXL@ zA&Qc>ZQ09?wEery_4JwetOM1q?P^@!uKjXL6^ZQbY{ahfd<#`3G5tZ_p4grtUxvmX zR4dtoA!;B+DJ`Vn(1-sm%AsFSN{F*x48AMiFIB8}6>>0If=R5R>*DvEXxAm{YDHI{v6|>R3JGagw^i5mXty=b^RaiN>3loNxC)r&cEe|J zb3*TUlHwl#W3bU*isvL>o<0-a)O{~qRO3N15Q=ThkdNT8<$MkDQ_;J1EXiS>JXI-l@^z8$ZJN;GWx z!L#JTT+Smlk=h5?A)(Wp4G3z!f;B6run~}ZiFCh)Xw`3RApW3kzHx}rrW!^4JePn$ zs3QgA#HA-?UxQk-8i+w#K{+#*0>TZZM1#6Z6J`PcCzkuftFpMa<0hR5Ob+4Skv0Hn zNYbz!#vjwe@}a+-!+6E)jmw8+5m*oUpuc*DS(=vQKa4GO%}-8*B6d*{(+0xmR7jJ% zZG-{H2vP=RY4HD2^bycq^o!jMM+4J>=H4hPdU~nJw@M^TB`lL^^c)fZxD>SP9-U7d zaEXtRK~x|Zq!;O$$ZwgW0yJLgvc4Xl7U^4GRcDx*rbEG5y zgL){}$_;IbEVWd!N_zjoha0wVi&Uk})2*@W2iF=H_q$ z;qK#apmWd1%$r_$SP2G1VFrTQmdQc`4qA*?6sb;GRef4KZG2KX`4HU@&k6)`LnKso z@<{-aj1*j}4nBtl%G|QhEhF15l7f{UBrX4!KY&MCiQc1ikE58|{uH7xuabV7^&gl*>jB>CnO=VZS)0XIOy>00~X#EIvj9)QfvO2o^XhiK|7a z13?)35r$3t`SFaXYE{zN#tG&YvP<7j&n7e<8?|W5c$!}7OS$chW#vApU}0t+E8}?1 z+w9?Kc|}_q{dzJu_*7B~ZT%oAI2FLa?p^>=FL@7cApmekO^LM*0(rMM@pO@b(A3?f zMaAS1eIZ*Y-3wndaj5h@iNbXvTOD-}kusp5~8nHTRtzFqQ zVUOp~y`v_0;pZbfAo=*w%;GzADS0E(=1%cMUpq+f`lcIM?NlHbf^m}08M9#h{tHYB zSO6OIfn6Lz$pUbPBZ1=wb4keSFZ$*ZLp}r@@}CuR7ou zWJeSqXK{+>xNpo`0gaOB0u>BMKzpIrbaZnUDkVrFYmMe{m_GYZP2rigs}J%QOYd!x z^X36jjH@`WHV_qi%aHO~l!{g64n6RZn_4_v=z)Ei{qkcI>ZFPoapTISnNqW)<5}f@ z4+D@|q2|sp_6Gku4M2BUF{gOny6PS4@dJx)u zcbLWqOQcr7Ic2!NvsSC1cBz!%D{5vt)3`ttx9@S`LmU;v3X z1l7*nJ&Ycy84fv03><9%_DTlx%m>oZ`G$P=@O=PVJ4e`QM6^>O+;DtJx+S5IrpI=G z`7??9ha;lUJ>1hF04+YE^1-{}AlehC(##iFkK`V>A+{41__xGjV?L4rCa8~3wb#-& zAXRN>fu0~24HA!*N=LcAEsw3rp8*M;X9##W04+CzRtaNTSU2mvGD^Impaf`I!2}4COqLoZb1(! z0tz6+0qqe?)y9j3Lm|oU5w|#~!G@17%AZ6MmSo58_HV#@FU&2WCdq9-NyG)*aS*SH zoUk5>C;A01ST|KCJmDv!f&o9JS+2j-Z#pDE02?lryBew`qj!`QHRBMLEn|useUjKA zvLaRB7poN40VMT6B!$wHlZT|${S?2)Kwr94utx&5$FC+?txR3X^g|N*3v>ufqBXV= z6%ST)4U2()n)QALFz*-AW?GJJ$`rqwEnk*LN_tLjdS#0b$xvV&e@4I%I4C@|nLp}I zMtQ7-#O>X^sTt=z6`u46Vl+Z+$|V_LbU4xlO?ZI*$wISsA9AW6^j!(k7sHu6n^NZB zGyIXW`MzXqTV?Ds=A{*8ML@X9u6?E&G@d6 zk7NQyAaNAM;X-%M9AzebRe>US)uJhnqRNGz|2B~IJk!4(6;%zTv^}JlF+~Y6m5P+9 z*;v2p2T>uaNGeW+S1lkqb5t%f)Ia`--b=;S9#G34dRPHZX+dQX&fz64#U+tTS=AqY z^9lUMWJ>T^DEO|I-Kv{cXI5%_34dLKf18_uqn1hW7nI9UmdsyPXjE1#7ZO-hhTB!< zcvxn|mmW+|&M80(jBx*Eji?e{UWZ(|haA?f=g`F@)AJXPs84msnkwrEB=2855?FjA zP?@n^JYV)B1mp%qPANu?pL?t{AgcP9?!9AOwV77%mni5&AohS?`62>u&Ay_?if`lz zKx{l)M}fT9fKV%2&QUT!P|R4$3IsYIz?eRa3_QCb_J~ zFR7ais?{(?x#K|XYT&=XHOJsYDUgd+5rm@9>6bG6!1ogXu?QxywFXG1#k+s;arao9}#P?HSG z18PwI_!KAQNc}O_um9v(kAafFn^M&#P};FnZ+%p?2jA>F0s?{v)c%0z;;O0ibIuQ2 zx|dq+ahnF{YvA>392YB#(wYf8kd|A#zZ18((t23y|2p<;IrXfYP5+A%(1Z?Crhw8& zt=ESC_pk2aUkvePkX7?IxW;H1DbJymxTH1aDE`;TJGJ$X-3V6TF}-w#Yw0Z@zZ|5D z+Ni=@IadC+w>aO?Pd``JTDM{5Bj64Kw?GWgJT^#dfM zQjFGxaE{v8v;jF^f@m0bOfSdHmU|n%hl62|zm2rVqW)fcj@cm2>(Z}nHtz5V?6A7` z$MgrFbJpQjWD-;)d_b%4?CRP)=o$hyyWJy2*0@{oK}dBW0)n+HLLF)P-go-SLKQs# zKwQp4DXvhNx_)1~Y~L<(A8L5#<8%J=NN9bATf{w5kx@VTkM3R1KMBOO3T=O;Xgh9O zA%Y5>U)w;Yz#mBeko10{UXBbLURQgpq?s!8|K?Acmv@WG?H5;YlYPnJKehoy{NBkJ zQZc|wkNRQ!!p&LXdf5W{XbJ&8_0bAQ!$GigOypdUHbDUX(e ztp9+Rqv*6))xuMv9;jemU7(Bi{I2lsavrV#!jzqRp;{IXFE|Z~R18L<<${pAU7DJ= z(nl8W`!SgZl1Y3OGa+3k-S`9;Ws?ZT0E{zx*paq@*(gu~e7j%-8PP@00-p&-jGaU!^G+R0(}!hiT3|X zTFDO=O@L4t0km;T00p{e_x6UgVhWEtjJB#jj>M;rvu1i|b6Atdy{jBC@688CD|+BB z`22oO5gJS|Mh+6^L8pEWPPqV8Vk`QOn#ahH{?(@a!SR9M`3xu&@ih2@Z~z#48-0rH zGjRXH1zYE+f~PF7X07;Uol}Y&o0^+4YiQd>K1Fu7mvm>4%rWf^SszWW!Oj5l&`vLA z_^F4x=>Y@JbD8CHdwau^X=6(U^HPlHp=FcJ)K%tDy*%x$YWyYvr}ZJLLx8VXHa{ZH z($UT-5I)^3bh{Ov2rgQ+o2RViq_q!boC0mB-8j*aVMYfnn`cdyW>Ze)0#AEg74nd= zU}{fINwSvFVY*}hQ}Z^f1kqz~ZDv$g7Rry7&Ds{FA3KW!ef+*m`=Ga+oCcn?F9n@y z_XvT&H<)FUt1#Ihz~Ty7$1gax285VOV0LE)sn6$?N%5AVme#fQ%x?b5Dx=qxAN*}p zRUkLqE&;ZtS4E|^tb7KHR+rPMsY&GhXm`x2K7qi_IALx;%Q zcB{=64C>nES9kWRfJT4gywfckg?f;0Hy6eNw{45yYcF9(D$V!+Xa%4%x~q=1Q}MjZ zEWZOkG9~AsK4!Fnp|oc^x@T{&l(^h#h(0RBy6>L3?e&H)Yjfy*w!6-{w-p^4$AVjU z=&jHJjkH}`vnT7|Ra(%i$Ksr~OdW~mppAeaPeIVuQxATu z?fe$mEa~V@TqC&ox?A*DE_B?`aR^U(z$|bgTk0Nmf#lZiU3iv-CA=M1HT|jT zq}22HtH>z=XODC3S+(tc_1IyS$ewkKTduE9;0E#(1^W97-J()?UsW&m*vi4rGa!4L zrvC9f`quf|$)(}?cy{BwZ4uy`8>*54+VS8J@a)ggPEzE_xX&5E*(%EUJL7aw*!M~s z<8mzftcrMVbF8r~hGWHc9**hcj_jgH6RJyw-zE00N zjRg_q+#ns0uH@APkWP#UL-%$Jw~s20l)fHXoex+kD|}w>nR~nI%sO!VcI^`D*6?yJ zpj^N?eqVfc?+|m5Pz4FfxyuS$4rQPGu?`|uxD0&Sic!9I6?F@d>rV8$h5a@(;xjJR zd4x~8O2_`>Y|WDIN2Tx$Un%F_0eQ%Y{nn3urAPS@$@;OrvsYC4pTFppHuL3Qle>8& z0>IfbChUui$5SN=xDWbJVds{B`Fs?8`^jc$2w~Uw{1&t8M4$GK?ffxx{bG3n`dT=V zIExABt`3+1f}+Ss)e4dRQGfQuWiuO$OX9XnAW|wEv{%U!$Kz3RmST+k5JxH50V7oi zkxgQB!(ED>+Lce`G#_VqM?Z|d_eTL6i_`ncx#A(#429wcs)e$N*gR!3hw6n2c}gJ> z@6gmT-A3D8BImwNysv#RwEA-=i-oX6LPq{`r~1tfyW=5GJS<-ewQ9FC)k>y5Ljn-= zS#~Upx`L2_&sKDmi(3%{A0_qPenq%hsZPtu7r&LJ-2SL? zHJ5hYx4P_RxA^Dl^{xCOpP4v3I#uE5K^nK(0J3s&Rn7JQbc9-d9PM@S z*)3_+cyEQ@t?~5wKy{w%?b*%#{&Kff`YKo4|MBtmyc#vx?YZUYsayc|1GY>{Z;Tfb zQD0eNg_vm7h?3x#2{xt>n$_P)+AA6T*rpq6)Oa4iqba%wj=IJrJuHd4Q2?H45*8mc zxOJEthLYw25{O}}^tYdk`JxM!Hghs+wAqwVl8(nft>J2i25KgzY>Qx2Y1Y;# zy8s{wAw-^QL@H8#p)Q#D3u*MWDi*nX-ngP=Zcv;IY;-2a&{+1*E9I0=3Z;_QRk;5q zB{T9B6+aG0)T_!Uq8e5Hp=!KQDL^??@A$Mh zm#Zc+On%|brC3M*(4HP-y`P&&mHsqMH1E>HjCj&>{?$`k1E1Yx%<)b)B47G;sf(uc z<6l8d)~Pz`uOU`ic3q~;0EbPkc}Zz;DK}lEW0xbtXu&fp0DgGIuRJGnM9e)8GV(o?6VpP-`{QShH9DKiWH*4$j{b~~$wl1)wl^^+?-L%vv z|L?ger4A}G1eN#nyr}~JN4Ui2#~p`3>J)FsVOqDxIGKlq!INnCKhsN%sO^8lOr!x#jt$cw<3Ap+&4vAgc1gL=EIz# zzgOv=@)r@47G}XAJUO4M#X7D;>i!^oY2yu9y;yVsbFV$mxOJA_OsKUnZ^So2eN~dQ zF|L&p+(haoSrKh=0<(>(z=ch$KfPA2qwX2{|6YW%2hv}YZfxC)up?8L5$8d$fZ&Eu#}~?opQ^`{w&Rv!C(D^2B0}790uMAhbw~Ew^21dd}@NY9G6m)AEfda99SqizMl$wEs zcIFh0_VB5?Rl_7Rsi)!?co-%ANhO*@lD#e@3b}?v=+$oFwYzt-mR-1i^EM=e>p`^kPYTIP5VTCHj85h41RqF|VMl)}bJ9$n`M^0ls2Uw=5p5@h z`f*}wrZ_^wmzy+ARvU#luKl3w@AW?8O>M;csv{XUABt?2$u!=UbMhP9wg9slYsB4* zzZ5MgSE8PPC)2daxB|LHpUIrOu1k4^@i$@M54p9pU6P@VA^0`Q$U3z~7R#a{eD&1n zcO+`OZC2Pm65UKtBMz8Q_~9n=Q5-N6j_OnY6TdfZRY}o zd$B^Z{qsm3-GMCLCJ`<>lB8}j5k{Di1nAbcE%*v7xjFmI+HqF zS<*=KH}TMH+-(xkM+l0ycZi>mIGiM%V|=u?84bP1AVi;?5&K`b;b+}p_1})aD!t8F z)cFa1Z8)a1znF7?TSk%@f@yo9-g_M1wy?e2B{Nn}_Jot*k(_=zWre69QO@X2cp>QR=@Bgf_-l>!zzJdX3%GBgpIz;c3|rPl4fPJlJ^n4@#*d747{wul z2IE7GKGkchB3XXXUz+~y+F0pxYN zKdJu|APzI_bS2`B2H}%2baBoE9NBmm(7QYU(EuAU+BfgXZGc>?&rdu8RQ=D$gXlBd zRkhHchP-Zkz^@0A z^q%iODpJ9_Iak=ob2@7+h|pf_NWEA9D5ZjgrSbJxf8TSy-SD>DV)d9<$D`=uSJwud z#}g~%=cPs8LnZ3ePsJ)R@TG9 z%w=g^?0stvKf*Z~?i|U9v^g>^Y^PRzXr4saP^(Y8%#cNM8Fa{a_9Hjq;7vFo&p`>4`~*Q*yaK@5Gk z@%;FDXSJD05cvq1SZ?*Q=bO?1IWL^e_{XvXf3~Xyu zi^lM{o}VWJ3U6G6*^u;NK;U`Xf954)Dfx#DS#P{RSWBW|!}hILa2Jq#J^E zB0{4eaV9B@-b+YTi0)g^?wlG(RMLH4ALuO;%6t%Ln+qh4%W_``1+@aP;ocSXK%E*` zJsnP1c!{?Xx>2VdGc1V~j?R)2$nS2+dXQ-CMvur$Pu+!N6{uGnUP>Hl(mu1%#Gfkk z-3vCm2F@uL>_G^Ahx%+%v27nA?@WPrt=R;UdX`jZ>0za19I6UydI~6dD^>a`jHJu# z`?R@xYyG85a{Kg>`m`ma4o3LYqA*3U(+s(B)V;+f6CtQSCBAm`RnfZDNMlCEyJEQ6_{?TY8 zgQT^wZ>I9hU_kbLl{;xa&v{sGJhfjP`nI;v1QZc{o*8mEWqgwPKvoxdnu^p2mNj9;)Q zUpI_j3MtaH{Z>^admntH83pxA|4z z6;%+vsvz2^0DV-DqE+78bBU1wD-5tGV=CyYDj26Kn6E0xea-NuQrN7jIKry9imG^D zRq<_934Bxuqg6j-sS;JH61S_q<4H+ZRmp5VrR9^BAE;82s!_43Q46clD5}wZRipl; z*bMRKv=4lPSEgtUWNe&ZYFB$4RbzEgW;>m_eNp4!QRXC_zF<-RSTxluuYTbi$SKCN zlm>u7_=hlyD$qWS)Tl1BIxWzSBJw&7KdUZAIs*g6(~uZbe<@GdNg`eHj@&Vr`C_Bd z<3TYfL+4^a9X(@LxC5vN%Pzyp6Uhn)}{3 zXSo|~{cG+Ax>nV~oIK3D4A#8Esg?qzww%tZ~@j<8u1n45Bv(OAMwgh?` zfpv|#=2PM9{lR{O{D3fkopX@hj++<>#+gQqb)hp-&7M_OJy6Bb6vaVgRZkXsRtSm*J>g8uG|Gf=I zLIP*)BGUuFzgZFa5CG+UdX+xQkZ64XK>x3zUN+xKFM5!zJJ4GPoD;HAKDI<~%~XTU zT$dhguM)zB1ZQs##yLPoFy&bG4{)6nW~>QfEJ4>z1q-^vs+WNO@k9%P5N|%}>g0kY z0C4t}z^9DJZN;@k9I$!~EEkjy=*(fbqqvgI5aR3(-trk;M_=2FZbsq&I}*Y%s~|4! zB5S1v(Sw2(d^)oq5PMzt0C9m{457^K2);FNa}3`$Y1a}pzumd4FCzFqWUW8#BI~$= zHBw-XkHk44|y+(l7)IMBB_IN&+4m?ft-jNp{kF|{^u zrB>ow0WJ@ff^oo(<@LAMbpV;s2CLDHv=PYADBB%@xT@1M6^>B`!5c~J?e-f0e`9}3 z2w=}LxP?yi0OsF7SHa;?D?m490IvgpHV4Rd2cb(cD@gue1%m)@%eI*d!<>hSu8-(~ ze*)YN0$mBebx4`=K)-J@J%HIPSv+(QaxELzcEhzOfT7dtX{X_~NWeMJjy|=S2;)D(GRk9LOcmK!Z3oo z|McpfAxA>{Eu*s=59LE#+<|t4ZExG*GQOLMN>&kw{>gXYQEQeDIDCO0`GVE?GJor} z`5$`m)AEK`v7TcQTBwLsLv9|ebh5~oMNq4x< z^@n7cb2$}Y&jDP^6>LpxUmOH`gF-os5WG`Y7E=Mn7hs3~1K`8)fI$L%4z@|_4i zfY(1pkFlMwzMV{xolc3I&e)piE`VKX;J83wm(<4Y1tzEYJd5_}{v!LT8l~7lEwI+Mv1yhUV1>oPka5Kw`MZOR>J_HV#5D&o51sQ|B z??3JAf3{Irq62`=Vh6!w{G4IH%(0WDBzu&miy^!qXPHj>R0pwq*m!ARt03a1P=m5v zJHUnAw9zF>r+v1+!-wL_#d-& znHFAqzuDAnnX0dl$*%||u2_No5=KDWjqqzFI~<+&?{uK}a*a>#2;gvJExzQ1#ySBg zEZO70x(CQY#WoK8Y>t1T&D?>E8|XLcqP|9=_XX%~VS8Hc;3apk)^P02+CVwq@t-G1zrbQ5oo>nj>7-ZIUzD*)I?FRq6DV5!F*Uj=!^>E^*05 za_JnpZCt&5h4c3c%5tZu%|P_e>_;^N0?dIl-+?HG;JfFMPK)Zh9|L#F%6IxHS+=5x zI@LG6@1{}6(JSk%y2bI#;GNBY3t&UYwfM%*-EB7pOtu&9$$Qt;ZNmCH8p+*xtOy+w zUK~qdfAIkE<6gL_zx_fg*a-;GH3EMkYvGOA=KqdaXp+A|CXiP7=IoQ@n!wz#KZ>>e-RA5F9-PoP8=dsamfr%Y@l7ghDBL)em+YdjGPX61YMBwk7(u^KCVe z9*!LVbUCQuAd&RUjy$aPT?hJZP8^+n@!bUiSY{;HZX`Hxd(yo7&i}t7-v#%?X$!LiK^%ubM+Ny_|oFQkx?>!mDnemLzL9p$E z$6BUz=waB5dM71L^b^@4ez53r7rz93_WO|((=W-Vf0rdm%*veU%#^v!?CKAcG0or( ztZbUnkHTr^I;C^1B2vIsxVqOX{sAG^(Ok+$%m&k#J3g*vm+QON=VPn>9_=O}hDljIZyHW_L{>e4&l@Gx z1^oxu0M@qCZZMgmugL4u-TC%JwVx>T?F|Y?nClORt&VMCDq@4Z@Tl%nQa* z)5!}VFiFh|C3alM1Cs|5=7&)y=;Vjf=cndJFxM^QN3wSl7DRoV(kY1M-AXNp5xiO` zh!utXP#7nPty>uXg(|HuL7r=|Fi~0JLs62tny$I-v2I#XvcBVDQ3~8t0){w`_eD{f zMSj}v^dHu^bQyNtABr=b^7#T-PB#)`7~$}`p-Lj#C0EK8fYkgLk<*({)m$Y!=gF_d zNkNzbno$8U!kaTRlT62EvnW|Pfkb5`1!p`X0*{|+$fN*#fHWh0%IXvFh-bV0pF_&E~}!s`d4 z5>|0A*}X49VAN10cKQ~C3vhW!JY>3l$6<;-5N0Y1!4zcH4Kwfa^@}>GV12}EVjbP@ z!9vv-?8S>5sw#j6Q-UmDOC>M?JTHmu5u+M1U3JsSlB7Igj5~>PpSy3+Y+LqGlGr}i zg&o(|h@rAF1Ef)J##z+rSN|;A@iIg;sE1t+t5@QyBUC^uIDS+%?WLT}1`V_eg(*ILgz>3K#3AvoXKE(a#&hY8gRB_<>XCCS@wrq7+xgdS@?qPovG zt@~uczyK&8;QFRw4q=jWG~7wF49^!eub z`T6zf;pyq=_5L1ue+<33f?jStzC1iWK0Z7=+&b?aj^2_4W1D z)z$6g_2uQ|&H2^E<;D5=`SI=1#^uKH`O?$z$;Hv>dz~B{{dXO_os7KhjUOH!?(gsK z?(S}HZ!e$CuN+S;9M7-r56_>@&7RE8p3F=iPfs08&F;@kZ~q%V7#rOl8Qvc1+v&aA z+&)@g+uYpTUD<@L)a|cUtgo-HtuL&stgNmKE-%e5EiEoCF1**=++5cNJg$eIXO8tHa0vwJUBSm)6+B7IndeJ+1}p1+!ou^ zR(IYU|I)-g)CB2kif(CbXlX5LX>Mp(t^dUW_v9Y$XynL}VXC^ygEUut4 z+rQt}8RBT!YHrwMFkk0!QOn;_-&9vu_qV>ZrlGv1rUqIe4=qN376G0s@Sln?UW?$L zexn_hOWu?a{w;6lD-VCmaDN56cIEt@i4Co+FD|JssIIQAs4c9jswyupFD)-BD$gq| zEiEoCE-EU@&(F`v$;r;n&dbQp$jC@dP0dNnPfSdVi;GJQD@+W|j}OSzs?$)eQBbUw z3yBE>Mp4f7*IlSy>s{Cz+d@8yg#c`}XbY*RT5e`Z_u~>gwvMs;W>y9w-e36bB26 zfB*#mo(b?@5#VpxnRmI^CETk7yc-n^ekv#^$jZuo`SL|tT3TFOTvSw4P)LZMpa0XR zPu$$xoSdBO?Cfl8Y%DA+OiWDl^z^i}v{Y176cm)?*+>eIVHRohU$waa>RmANaY$z{uRh1GJPFxD4i}=DUi#OYh;=MaiT1&5KWJC zRvYz1kjnq5Sgg04F8ez2r*gT;etS4ezNu=p)&2UY=s2W&z0?1-e?h*vX0s;@huLtn zxz@Cf6IPz=YGPzK;)@t*3mVt;_i<9;AdE^6?!$@SA0w11|8gJCm3))G5s<1oU2c|q zi8O9(I$wtbp^_`LHD7Ma0KpJecV4FubXXquH{K`bBmGL#2{s?W`{OkWYbYjrhv4JY z#soPDiEjJzGWna2yK-m8>+{3)@w%PpoA>KU3on@;+>y4CFObS|%@=uXJ~s$;jex=r z7klSh2;ujV%}^5814;k^>_Mg{=8`s*4}C{Uegqa%YIY=E72#Si`5pbYXuiFY?HHjg zLK9!^1bXUl)-B$`IBBA^!f^RHH<|?YIRdlTwO5(lUpn7Qcaynw88^e=DUG^P&62J5 z(kv4e#YspD5BDZqianrWz}ehPyCx9y3YtFQk5DWI%G z4$7ph>J>VW3NQ3J#y?_2iqNFO7HjOW$l63Kp_O8a!Uc6kOJ)WxWFYOe*p5l9wb@>P z!V@sGO6z&BQdcgX<3br@y4dMzP%r1Onk~Ac9sD3QRCp z-`*+NxwtXhFuQ!>3h25LlQ-BCJW+tq1n;nN@4oqlEb_=6f_xs07Cdo5zynuk@Lv}^ zVS#N9(+qLM6xO`(&D-hRTv)FllnFoK+G{e&NGGlIdq>X*X38^T_j184`vtYl71v5} z&ODpjwbxmDcX7rDWn&G#O)stX+HC)o_I4=C%<{qeP0iKSJBO_<*LsKl=QCh`1OByb z?hZ6WKY^fKZ`+JF?zpmx;}>_-)Y+|&82^ai-7Db?OiVI&%bhphTN60=!+raGdSHbM z^h!G~eH{7YwAWty+wDFrdgWCgv`sGpP4I%e*l|8^2%01GIYM{`7Pw!}L%%xKq*pI_ zr3MwCjxPD)Zu|G(&+Gkjlh2*d@9r5-_d&}a)V$!S_dGrIrpF(v{r8L59ztyV(?s{P z3!eZ7sJQ!U}iH zV;H*VTmjl=iE-Qm9@*HyE5b6ufxNFe^K)Jfb%?*`MDIJLyWal));2x@8u5rdDk5&m z2Y>)5;E7O-q7!&7vT=+j_#q#e5Qs3k0fr>70v}8; zNG9+B3Mar~9x7ZO4E8~aBUoV+9N@q)u+ggt6y%1|>mj-nxk&37Xov9AALEpW#7bIn zLzE;O0tKP~LU{6%pbVubN9oBGtdAh*0|4eU_rN3w1Q_+;fIzU3s38z-AlcwvLAsGB zfp{a2pzFdvYQsR#xo>xotX~ix$w+ZE)0vWNTP80_&1&9fnylL-06Iy^ZhEtnryNKs zR~f;24CEE$7)UWd7l(h)b3woIM4dAJ=q$f=&=$h~kFu;VD1L?+12Z8{0kOBb0INLE3DAc1uXsA52 zYfKv93}zglsY0BjRjEqY!e(@^%))9=akJHd2;&<^P{FTQX;RmrR3Pm$20AKngfFln z4syJQCz|jIJbDgvo^41b@&Q^_sKW^=cu`gtiq~ZSD)Y7s>e@1#K?{jGRj>v$tZ;{m zo2YVyiM$gj0GiMZd;H^plnpCpjoE-#phF++NQMOrHBZa30z!R|X4t$tn6arC! zKY?|~#U7NQ@2#zEnWr8!4Q^jL+d-S2_tp4vuNaR`x{&j z+xW%;0WnQP%-93x$HXu}F?v|s;@qk@zFWZpep?`8{!-MxIF7PmbvzRu-v-FY)GLZ`s07N)r85hQ|eOfm%DogqQ&5m<(OsuR`ALB>M%yVy;={sg}ftkS& zE5b9J;Rql8dCu6|FqGlUXlu$DCUlkzp3gIBpwe~4V(#x;X*d4~8f+p+{3W0!uAFOx+Ec8JIZZG=V z7zbas5hCutkXveYR`9t2edIm!nbRl#k4XXy@#!GM+sPE-fH}sHN`kERCA#>=K>Toz z4geq&@h~I+bWsk097C=E@J26(b@7Zl{c#&#k2aGl6LNaz;{bp)Ok}-vS`XR9Mx99! zl;I3z<4z3^&4v2Nmmk?a{eA0(*7w9Ck zf(6)T0%nMI7=k_@;0@yNQoW)utY8IH;0pRM2?7xU?%;-*P!A0U0ARpJPVfp8XK}$7 zh{`BC$(UF+BsviAY0@~2)L4zyD2+jod|pLPonTI`lTHG0ckKjE@ib5M1OTj1bOL}5 zqu_~K_+_Iwd8Ozl@yLYc(_5ZqW<0Khq71pq7MQZE%#Ej3dy;16NM z4=&)26*zrhIFCjDR(%Ii1cX3_{0MVUHHa5Elvt9H08ogGn3PJ{h|1MfA_-QOb&_Od zRxqIry8sN>001;eKVNv0I_Z@NaR$29463+_K&faINt9~IB}NH^HbG*K6nn;a6EidB=6mW5fS zn_Kpd(MOnt36|7n5Mnr%5b&BHNJO$po6K1uw)u>>xoW(r9;7*6sF|9kSdZ|i5U5CY ziHV%tr(v=GnU>92p0&B0x8asGfpy6D7oUg_p$Ll5_nW4vH3)%^gs@w#37%I)YUcT$ zIr5wW@t!lmo|6fAS{R-3h@II9oT63`JZWalaGd-}A8e+7=n0@2dL9Crb-o#d(@AL| zYH3`_p!DdVYBms=M+mgw4BuIy&PZb$I-{7Bp^~AVG-04UhM)>Tpav12@HwAdr=9fK zmDe{2`srsx%5mM7G>u84P?}>lnoWweGLPpnBU%tKqoDS9on9)OU84riy)`_WidZJ*b0ER#aX3$p-V4t6gG*3FJ=2@x&AtsLMCUbJE%4#Obs;CM> zsdhS;_35btfr@9qr?ax8QYW6EDy-gmSfOfs+!~yVlORMS1v6}_}M;Za|)~N#9pE8QEDod#0)}-Y6u?~x_Fzd1TI;LCy z@UPD>05Y2^E^D!Yy0W6Gu`i3K3VX6NyR$_W0fRsYEKp&x@USTRWZ??5Dl4>xrmdog zqR<+%6nk=->HsARwHDg5ZT7QNyQWtApj>OTGkdgMdwCCl2!v1sIIFWrYpCPuvr~Jv z1&d9;=2aE|4Ddh?$S_l>Mz$&HwroqZMcc7pXsrRzqE9QfF)Foud$|TNP4s4Oue1(h z&;{Ml4UmSoTdTN^+qUPrxF?zbg)p}e&b zxOuC#rW>+rtGaiqHK56gaV-sd`A#~w-dGhcLWVE zzT{iJ=6k;Ao4(_l0fCSK>ifR%8^7txzV0i(_ItnQOTYNLzxb=a{QJN0>%Raz!1>$0 z1bo2dOTQB!mRQgLwcrf0fWZ7Kz!J>AM?ks&G`-XtwCD+Xq6a*ikPig$4Z1`SzXuke z5C|%~!YtgvF8snU9K$j^!!%sOHhjZ4oWnZ2!#v!>KK#Q#9K=G*!i+!&i0}uNfM1X> z#7x}8FANG83~n2Ixk~hX;fFpUJi;YB5a0U&;akB0Y`|blz!W^j`&-6le7|U%#`e3$ zYz)6{{Ko1_zY*I2&N~5eJjY_3$M1W=!;7IBJjH0coFYhq{9uCopuGV9z`erzw#RF{ z#S6))>t`bi01wQ0&^xw&95NT{9ZO&eL?Fl(r9^4ChHXd%yW6_}@VmjA5EojylPt-o zJIj=7iest;0AK>J8)}(cxzd{~!7vSBAj*ywsHp@D>hQUtJGz@(r;iMyy-dr=OD<{P zNh|;WyBZCVOo&m;jLDJ$a!Sk^XUu>L4DnD8$pBN0jJ(q<%hCMK?d&&+KnPnP5M+nR z@Qk+vE6y03wuu|d&|J&;%+Bf&0f)e}x!iKwOg`OgG-mrD9#94RY)SqM%hK$~03Fcr z>>aCl1{cOx9+=S#-ON&qELAWK)9`E)O+Xdx%nQA-FAdWoO&t&akgH4u0QdaN+)UEm zoGceG4Y7a*D}6*Q9hi;l&H|m(7+oKzs0fA>1PUF~>DkcY^Uxl03bBw2Lv2JwU78H5 z(Mx^N1RWj<(7Jmt9geV%Iz7_+d@N`X3)27sTRlKsJ*!epykb4pNUa{rI|)Qd3J0#w&^rL``d*QYzs-od(rfCbV4)y`0scYUK&oh+S99;Ofr!JydT z!`PU1)L^aGdmYw%O$dc>0n(AyFS^-O+SbP+1+hR4DL~qWXVo@A*hUSqsU6vpz1rTf zuF)|8Nh;hsZQI8p3R1w^y&cF))Y%sJ)%7aaG7Z_((XR^s5FP(&rp(RO2>}Df01x*t z4t-J8)GghQY1-F~+SyIp7Om9Vv7%T20MQ`}&d{ghJ=iXb0_iXeUvLC$P=%iD+wKjB z@NJVbJ+vD=-w!SsJZT6Ipx>1cw(?Eh2cZjd$H@xrA!rZ`rm*0|*WQ}M({?@KcwOAa zP2AqGqPVQzw%`oU5U~GU-Q!9Qynqbv01lwg)AzCnaQ&<%{>$&W-P|qVOU~pjjvGgM z;rcBN5bW3+WqV{p5cq%(y3hroa1Wi}&?rtN9stxredLy#n`Rph;25(L z8bc83Fna zjx3+89teQgqn@T}eznV_-NG*GEAAbS4gi>~eb~+62H^$!zzRvQ3H2a)jgcE&k+@INY~h_~<< ziR}*mZ4gg#!!GWqe&^r*9M?w(5kL@p>hbIU?(Kj~GAHl}p*-@1P4o3#@d5wyKp*bj zVY37Q0VON*LCWz*3G&6V>+cZ^u~6bVU(yx3^8ar2j4t#|?iVe8%>!}ANRRMguaQhI zEKctpngG|~JoSoF@(Zf+|4i=w-s-nO^aOFw2`~0af9muuG9o|?v2X=!-}hA?_j1qg zaBuimPZM2F5X+wT9l!TwA1P<=9=Q+;gg*Fy-m)s**buMl=W5NU08kY5m~ z&-d(&G(bEcYqwo1cPtOJMugq|q!9Nhg-}#&Wk2I%14W*#`%g^)Ue)w4L{Lg>>f6@B`F|pad znPb27+<)z~eZg}Y27|N`d041 z6m#v~#hX{}%D8UZHeKtMtJJ|y3mXo+HL=c)S_%e;=B!cH#Z?ar{ku19U(G}{1fxcz z^JvngO#|hOHFMC*MOy==`1Upb?76c~dL0y&U>0Z1AW)7iyE4($r-i0A&NEo7Qpue^ zhYlUN)Z#yFvmT!Gy7lbZyA$1RF~Au@jtkCmHcM@A!QX*akFIlie3qhO1*4x||Ng4; zlfv&QJf8&QiNKuCYGSE^LlH+Laia~1 zdkH)R7hDl23uk%}#um9_kEZd;Gia=`)~j&FoiHrXsGEY+Xt`5}L^4SdPaFzJonn*; zN|vNtiOMQ{3=m6*9313<$Ci<-AS+QC(;_F8G>Azw0azrKX%JX5PC1QJGpI9ZDs!Ve zFWS?hKK;}(!5U?{(Y)RNdi#yX+5(;F&Zk)UrxyTF=*66S*6AgLfxOU0o_Mn1VjwoW zndcp3ju=P`aPm2)6S#()^B@hTi3N>VZ^iYlI^Ro?wnYaejM1F_tcX~MtaK0&FV9O4 zBVdDlw#i=a@&X-kB&7lwKav>39ApII0G?r-$kv^Pj=)EkB)ZrJ9D$CgXO|~N;fD=} zc2!c8Pfp0SUw@^-*C$7#6n5BxWsKIfgAx99r$P-1X(VTROxVt8=ic*YqssJ@!T%74E2EltL; zpliAXQb8S92BPAee)=h=WP!wRho67C5kVkxSQ#jee=aD9f)93gDer$%5ar0ehbR7^ zzkke}#=#4(`Xs~?Z(dKMu^^-n1q?F7nP(iJe0kN9$7%?7tPsfSfj;mC8;UOQrWh~2 zK!zOLUoc0PF2L9(8vy{Az4qG+dc{8kC_vx&OA4`|MqP@xK;j)wCxIhV^rUw=JtlmT1U2%!?$LyLg&2TA zqR^WljL?eI0bf-*Km|5Z;Ty%E0subHjcsIrAfsr<{s6E5dTas!yYR+9VDJwx06-Vx zpqb4QBE=Gw;yzG>z>82K(ed9$*MU6yYG~p#}6piKk8? zgo;4%8v4YMgcsBjPENoFFrGk#V#osq02qTmT)~7cU?Uy4gO@IxKreeOa*6*U!iSa+ zNow~0Ymzc~B_>zNFbfi{o8Od)76@?$vqVT@X7naoD(M!liD7^PL=`Z(;VEqlQ6QQC z2R+_l4JV{(Rjqne0spm}=2X+5bGqh*)|tg^60D&~OXn3MijoKnqLc@Tnlj4SMR2N< zDUy8Vzck^d93Ir9NlGY7vI(e%LbRi4;UY&R8qRTUbRY)+)8tfn#;2@wL@DKv2&NGX zex1~)K>{jDeCkP_TBel_iRr{%dXkC~f&~Z39y7SN(~16Pp|MJ8hBR-nFRJCf8}daq19ElGS(vh zUa{&yc+(6M9B!{%{oY4)X4w5mK?;Ngt#m@#)336!uUovVOktW@)hgzbjX_8)nq}G3 zYSS;Jl@n+4Pkz#)(q~yOz}wlR(LM_O^AP6>skR@uEFU=$>JJ^kc`@t zyfe+L-Z1=}C?HTY7KSlaR;(1?y!de{E#mu;2;oShUAueV_rQtS2K41P7`Ci zpKfM!DXOwA5v^PUq8=Qvk6B2_h|mbJIl0y|o` zDn4|fHBHz*3k1qyDlVuAOkG7U+R7WDD?)G@Lff_(d11a)r;Ss9l5X188p?EhO?~Q8 z>$un0p&(?hidAPYBT;&`bWuJX9a)=36w|QPt)*?ETo-xQjb`+De@)!Wt=Av}h)iBt zN@T3{8BNVD%`IXfylJ;vNCG7-tU*a`V7q!ip{9^Unu`$L7#p>tCUuJcd4_J%putUJ zb$7y@3GYiUE!hFyHn(#;0P+~>F?f}0#9xhRhVN_vv|5D1MV_W=ms{SZrMJX2es6#$ zwjy7=o@9Gd*?*@TaOPGL!AWxp3Xk09vR-z+S8mCcpP1JVF9-)md=PN6I^#&^^T~5t z@?2E`feQ4w$bpV?xZ0fM_AX(E=Uiv(6`STY2m1-RjwGFvM#)*%I@Q5^?ZysWP+ku^ zL?Dfj0f0%|Xtz5hr5>lYk46-^2m{>X-tjd%Jlhb5I*3b6R}&8;tH%a>sN^BW&Mwn@MLd)}uWA>JS_D7kcZ1FWTwY!thW>7ribeYazcn8kPsW|KG=i4b6de%;kjFYK{S)W8nnUa`@wlLuhomK_PRkD zoIB17J-sowX&AI4T(Troxg~TdD*Qr51HOXb4e6S~^ov0MD}*Ejn1*Q>KQ4qZFLX0C zR6;wv!`{O_rUN1MNJ9?PH8zAKDVP8`?7|`RJ`F6u^)tXm+&}h!#Xs;9zzHq+df!~#s9-Z zl+wgoL4X(I#P5D#bJWJE_Czz{r$5#%x_ z1VglH#h>cMIYEP=3da0OsdxZ|5YPup5C|vu2Ybq}aI7>ul*Mbr#{ta2$`gnd=s|DH z#VMjk4w*gEh^APWrgQwQYeE1`$cHBwgMa8Q08j`2Qh11T*x7`0(#&Fc_772$OnS>23I3S_=h8CfT1MH zqBP2*M9QQb$_xmE3{c9agvzK)N~Uy5skF+gJW8s>%B{pot>ntDj7qNr%dyPLrX)%V zs5qs}o@NLFvP4R;bj!Ge%edsqBdDZTActCd0To!uE99Gzng-^B$+BXk30N0hc!wvz zNuA_LgFwjv0);@3%*mw8%CyYO#LUdp%+2J?&h*UB1kKPC&Cw*y(lpJ}L`}=w142NA zKfugK2r^no&Do^Q+MG>LxXW+=E0&a#6Znw-D;P}BN~vrRhKQWVitNeV`N^Q9OR1d8 z=KRX%gwC!s%jpD5>9kI(#Ln!5O0SFnQo;hIM2~2=fb85(?tIGgM9-qM%ag2!c0dPX zP@PQlOTN)Rb_-6z97k;+26l8u0Dwn%bftl0uve_afFwG?89RQ9t_34W13d|scmn05 zfP#pFOt1nr=mvG@03oc;y`exj$xr?KP=n9~FgOA$&;@@O0{{R9b!f(CjK=fx$Zs@3 z1SLt3EC>hy6Iu8=2nEM?dWD1#0eJug4>c$aI0ZBi%n>~(DH?`!$cJ~xh86_?Q;dgt zNQM`f(T?mud;C!woyHrft8I+G;R8tjF#W#?-JJ?eh@C`ICzaDqEYT{QK{ZWKF`dR= zNfzfa!v?*_d=$Nh;DC6rNcx=9MBOjmj8Fn~IXw+PL9J2Ycz_P7MKJNhFvU?IOo&|& zgChWgYmlQk2Etww7^+C`L9 zp{S}os1XyuRDSGNb-hFhEY@iVTA^(qqV+4I-AIjH*rlb>pa=lEngsS30NKLTFQwX* zAlKx8*yQklCe>Q2MWa@g)ufGCunpUy;1U)HjHqdbDA-%RHA%az+r*^_mW5T94Y;<& z#ivj@Eue}s%vmoT+s*6Qqq=}NR9rz!3vxAAMFH5zHQbp%Km~A$76`I^e+>))> zy^(@9#GTItU4au>vE5z&rPW)Y*gKWrQK{)N-!)$2%iV)=L!iao#oXR~UEXyV z$}885NL%fpM7BNMMBH4XGS=q(UftDM>fKoLJzt^Nx9e>P!L?TIgUwS zyj4LK-j6m=g*?zBnaG5mQ{h;f;B56_S9IJ0EnU+E3NkH-36KWuDI>@|(ED@VIH`bC zPz4g8i4-se&rM?g`~_m~#o+1P;TMKspIG04aNj3}VlEzG5>^E|IOC&YTmz2ZHRj}gZRe%DTusUkk!g*#pb*8ateq3Qr*J`%rnb1Z6h#H9z=Yqy({T)aZAO&&Q z2WzMV3w#cT9tt{8g*$NNe8uRDMrDQK=sNc3|0U%x^og=TbdAH z0O;WV_98pMCTMf@sY=!T04s*Z`x=^XPJh|n1wfhe8RNgaUz27K@aFi;h3ke#vy0NZJ8 zfp|;;(wP!IVGSQ14*x?BNAJCs;+dd09033b0HJ5d;@NicCnx8a=!aDt2o&fCjSwII z^7-%cNuTv;pZAF$+!2O00ALTa%0|ex0P+Y z&g&0{@-5bhey(y5Vup}CaS(5{T1E+f0CRzWfqT#h6=EURd7&7Zp&9~!8_J;_>Y-QI zhk>|&e`wJn5(o&d3E0+*3Rq3nh&5`XH;SV05N7Zt9gl2Xyd1$;099cX zv|hNKF#tVaWtvD~n8)|>rup9<==rXBq#0GvDl$bL!5D8`2-nS3r!AD+{;Duu5h03@5%8w74P6``n z=XaI~2Tr`b=lg;9a)J=^$Orh;FMMNX{fK}p^k}bK{n|uV^e#UMZHOKJZP5MQ*Zs_= zd%X~Vh@R+~_`<3ENSv2%9JWsvTVt+V#8s> z{2h}yOc*N_E(^x^7h|Wv27wv?-6)i3QH)2EDjmwSDbkZImN|2_tc6jhPa`hf%2lgZ zo<31x8$~eGwXiQOs%<+GkE%9q=hCff_by%lFbBHY(6;B#r(N&=4z636?qS4WOSX7c zbruAUiQP`7y!h|flkuJqbOJAL$GxCIw^4;BrH4KzE<4XN8~@d$1|8-9C3jDpey;o}d;>iud&D z*MpXwEffF|?$+IdpOiXN>G`4i=C4+NQUDs11yxpIL6U$wC8(f(x@BgPHoXu83^(i< zB%6g#-J!}HDFqWtDH)15B8e)=_6`*QfFe!-nUup6egQTJ+>E@{_*_(WEeJpmwN%9n zA!h`D;Ens`XjqXu#Yhqu_i*EiE8N@zMu`}f=n@pFOOnLJG30zR3=>yc zNhV4aprT3%D7|1F5tMrRsfDtML&^~Hd;vfg?!X9VQHHMMYD%!8B*Dwa7GJUsslZz{;(=Z(XU=!@a2oA30 ziLZRQN-k$b=blwHBZ~aF^_~8oXZ3wA_8mp zBOm$bM>0Y{zz52pbP`ZtEOPO{9UcoNHTxkDYc@NvSui^G8`cq#h!m?;B^o1hNCb%I ztMXN_h+#>gM3~?QKjaKxp>v=B@}LSRpd<{jn1%*;s75lu1WK;Zg*>{!3tn_X9=aG} ztCEin|di+%bfCEE>4RP0mml zupr1QWcMaW=8=zmM3O0$7_Lg-${E1_iwFn@5dqBkF_o&!oc=O0$6fMrjx&7VM^aG% z9Il3w#>|jxIX)*^TlDFUESMoVd$ zl%yj`0vj#>04|}^fg@0bcu-ObQP?e`MjZ`?GSQ8A#G@OTa8Ni)iqdb^k}f@JVis=n z0A5XTrVFhqI8lNEZTO=fIUC0RE_&)fxUBQ2Zl%;i^Eo)M(v_xa89*bF(+o#2z&Qpz z143P*yNnE$uz%bL79Ua!Y{Xz5Ib#Dk)LOvOoaU{T6;oV`lGt(W(}=bNWLtvJxDLJ# z0K}QP zW;7zOrk&AN3Gp@6*43`9J;^*GC0j3i#fBE*6kojNasTawla>I&}5U>In0EU4VjkzIboum{A<1v^^ zf+0?f10VPh2PdEk-_@QJ$}4HX)m-U-hxA5rlq>O&i7aL7(HL()C>T#mQiTSCAk2nF zR=`M64_$0g7xf^8O%uvyj1{>fDoqYE+69ryl&pAjJ+Yn{TH%7Q;vW)n$T?oIOw8VP zhZ4Bd4Ng)3O#1fFwvLEw(2?eWbOIfbE^d_F{GSU$0H7Uo>87ER0QpV#$$4fiW=1^_ zFQ7vlr#=WNzTuDmZ;;{zVd^v9=B7Yugy`1heu!-FA!7hA0Uy6+?`J_f={3LkY9F4+ zWF$AjPX}ArYK900%rS;-T-zZ{c!fFkk&Ru?xYaxCLBS4Yk{6ud+!ilWz{oLDzKrAD zjGQ;WL#>hyJL4Ie#&>as=V^L_8ruE+#}hsva|#@!7`y-g!7=g$aP;HA4#b`+dT{Zf zuO)Pr;0HFKgpGYv!s9}2d7Gczkpm$4*cv&^vga3dsBit{|M>bpUSSYTjKcyrFStX# z(2I7|;}|}7ptw^a0-|3WLtQXN&5Y57e>+?1lm6!a9TkE5yUbNnps0 zpAlC7;6y;cAh}ZEaUks-p#^ppijm+zn4rL*VBCb!7@b6UoCi}p!q+*&$=%@5$c8pN z)j(vzIdQ^^s23GJ-TOhI2u_6HEf;g_5df&4BFP~LhT!)_694f~L`{@Qd`P(gMG#0s z7%qbik|EE?#y#jC6KKZ~xCs%0UmPM~A8JGlIz#NKk_TpD6js_L0^)aZQZR{xNsw1k z)B-eoodG&x83v3w+|fYjf;j+y7qG){y&(npVG)kvMvxpMCeIU!;v5R&b*03QeOn;% z5L+!+E-XR>x`cdvUG>Rg_ymj}0a;RGsU_yyzQB!@CsU&>Jb zKq9f9IwE5-I^9H&nVF&4=EYM)RhD`nz}M-7Hg4k=9f2HPM6kj)%)>h*1H}l0 z1pos)&;v3YA4H&@WMr6zv0f={L?dV*dxhdUVj>^@AxS72qxpfOL7I1E)K3M~dVJlw z732v%BSc_BCr|+wT!T9J1polUI*dUVbVD~p1V?@(Nb1)~0ssa+Mib5oBM?vRJ!MFe zVoNOLK9p&NV!e9s(7(+K;87D-KM5w?&P)P{rgCz)r z6a2%eJOo!7o)l_gIugVHRGlNxBT7(!BCH=Uq9kGFo-am(x)DUXy&Vrx7LLXLf+i%z z*LfRTwq?Lrf;|XBWsZW|NJJ9+LyC;SKg^v#r~^zA1O;f{6a2#wG=OgICU5qpZ~i85 z>ShK6LIwnmA!#@OCXhKlHfJ2(eR;o-y z0a!zY0Kg{X13`R)ErJr*eH|zS0)*rjov7ZW+*7MXG9!b(z(LYHQjt-RCt~L#Gp|_p{3Y$buaNdz#YLtrdugFfg$)TYecW^Sq{a&|x<`~aDjshOTBnx?6mu4$T% zDVx42oW`k{x~ZJjsh!R#oI*k4Km#P)sh!GCB76Xtl4p7js&p2rp;9MtCaQF@=VV62 z-R0fhVI~hHn16P}tYuPByu&}J4UaPZCu_mjs8Y{5&suI{687!-^zKbFJ zfhs;`>tW?q!fKNqm8D?HNt{9s6~))Z!KVUf=&(Zn%mWx~!aJD%#X|@HFtCIE<>g)i zKwti)Lj)#9$f^#M0Kf*Uzz!_I7OcS@?7-4MAkYB9Hmt)wY``ik!$K^@R&2yB?7`N+ z)nuB*R;&?7Q6O9^?m=cfP9aKcpUib1rGi(poWvCn8c^)RKjg-_N{eg=04vagKlsBv zd=f+egFJ}A3kw|XaeTajzrUX?bTK--+0kh#ocy%9sc3&r|9lT@UBGo z?(#w`@viT|wy*mZEaoOJ=N9h_@X8hdZ1kF~Q&R8gS#Lo^qGeK|C9;S4-VMYV3`!IL ztFDAV{=?#uFI;)AWNwA}#xKIcF9r*&25&IHR_+XJZr84_ z7OxSQ%=4b`*xF-ZZX*1lL^pn8IF4gEo@1!gFb{z*NgQd#u|x=bT@aTq8J{gs95E7e z@bS)Z!q%}JV=chSfR8kT8MyEL&X2(EFX?8b^j7bqLIgr8WU3CSQQd&&6(VQ41RJ;U z1fSv-KZP9UF%x5OC&zEq0@QNEuR#@p2?s18`!BGiWCefE5Xa5(sY3JNr+%iy0{lZe zSn?&?MG-^9Cfo5RyKgYBZ`4*DB*gC&6M_*8Y${_hJKm#8G6`JDrQXsoCS#QUm1TpW zWlDU(KXi*O@830#palbK9?LHtpYt#;uf%5mpfen^`_=&d5^OWGGRZ=7E4N^2o@Q!x z?>NI#FtK1se8?xTL^k|`sfM#N{xjbt#V^nCIu~z53$MaLLRB~d2AA>-&@&1jvZV1Z zOYp0Jjw-6)Q^PT|F=-(gnS__|a7viNKLCS5vl>cA^G-Z85>NE+>U8JQ03^`hEMPDQ z9l|nm^cCB4wmNe!qQsMuw3M#wCJo}}odO!LggyKND9rRi^D+Q$1Wqq;I&*SZ+i@1q zU@gc%{K~U*8EidA<~?h%$({r{h^lOrDpapgD!Rtk>8n4w)0*=+-*MIsb_wwG z;lD_|f0gt~qKySgj9`t@%`BWrZP*LiAR`}1Fy^S>Il z9;^0YkF^IsYso2rP!j@CA8cEftXsczK9>Z}>MYOttRuVCKcd7HoWg^hgcnqDX?ymb zIkaH2Heye1bX%PwvO|io@8ZKggIa6hkLy`7v0- zKzM^pquU#=QGMR$K*xe9poDV6xdDfINGEtk$harpd944r`;uHOe6XxPE!YwQ9|*X2 z6L@7$uTqz8Uf5ja6$B`}gFtk^JG{aKTtF|7!|4FP7@)%kWcom?!)(5SIFLB2tI?L7 zgeH7R+j0a9q`IoBM~P?u1dKZbtb=l{3v;|DHdQb-uG9L}e(u8(dKQa!zt1^dke%6C zp+KmBIsi8noC5=vgQTOtI#3C=3xqyw!a$6INpGq4^@N-olckzO7gm8ukitLIR=T_G zw-Y&Pv-Z8K{EkB`AIJ7;|8DaN`o06ZD#P1>H*{S{9_11I2Y3TEAjJiELos;47rdBG zC4((SJOE65#b3NYyu#paJSTl?rkF%7Ohc`81UmeKwv@cdQ@v%UJj>5JJDdI0A{l?v zF}_P}Am=Z{^1Hu>H{HYWTy}Z&pz$rBU8v9{n=lNd_XsBLv2)iJMh#3&;!Lk0sXPUJWzo`Z2CZS!>2pMy5~*Y z&aGWg`ajUz=gU**H;=3LYkeDb%Tq4eORW;9OHdQ`?}CsrSFGIEeg6)--QPvd{k%9N z!O*_Izc>Lt0E6)tgFIjvKmZU3pp(3TVD^!6@=70-fe#0M`1b)~MT-|PX4JTmV@Ho4 z1xi4rDhJ4m3#6DFxa;3Ll`mn&lsS`TO`A70N~DMrWQ>0?cwWR1NJj~yN0BB~x|C_t zq%;E2a5|O$YSp7qrCQa>bVf91(Pk*cy0vPJLWH!C)e#6oP?HS;HE;_OuH3mF>)zey z6R2L5+j;>I^N(=hBLc^8lNV3hmx=`+W-^zLT%4Q}{btr|vW}`cGo?(MCPakFdH(`$ zR=t{aYt=ek59F(PXi>7at&YXLyQyy8T5CCbrevw_-$=I*Iumy5+P1L==7la$`g8!* zThF$>{UL1b-);6#rN@9wBGY0~6J?SE;UwVU$CvNcdu;7~YaiEtHR^u-#{FB$5oe$= zgDC)y!-9}OjJVCY?XZh2LJ8x7?!Nh2s}I8sH8MaCReF#qmsm&)#w3aI;ZVgDS%gT# z?0%yEji>;RLy$(TY`ifGXq<7RxBmRA0THxtd(gTGTSGF*3hj%rMa^D(a>dR*i)j%O z(|ZA=WB%Dh$}hp(F3Qy|yeq#OcgqpYsnqmOiDjIr#i=&8lHm;HWGIp?2$`HtN!I?% ztjsWR8k5lYa8Lym31aeq8Z6iINC3hFIMmWh?=p0=LESoYO|t0xR4gDx4Q?6Ye#}Zg zEeJ8BhTV+xvrp&(RjpRNIK?z3O?91)fDeHX5la(20)?<%kxlj`UIld$zZpf{D%5EC zQ*}*92+V>_Qhzhz5JIrvEmm4*rO>V;%O%rUWnp5L-PPz&)-Sn2UKMvwbTxMER?U{4i_G0+ zRGV#^KKdj`La^Wt!5xCTLveT7QnX01;!c9Q6e&<#ic2Y_SSjulDHKY9VnqwZOOa;h znRowZ&3o||!)=S<*8rLH1Q56a<2k6tKRNp`9#Wj8MCazUZ z$F1uH#%dv-3b88GBu%3J>h`J7R$T8T3+^?Q zKN+#amaXn_ueCffeBRT&EH>peOoK)IG^CD}fcdOFF~jnAOZu~y8V2my zyVlYh+ZL2xotq;Javxv+aTrNB%ja7}hx+^|CcT$r&wc)YlD@EMTu=5=CG4`hBjD(| zCW+}UtE`C&>oY!|uaLrsUXt(kzxv@$aO!KClEqQa80quXS0Sf~e(EgXmkLY%ll6U*L6;l~e8T{howWPU0C!F?0Y z8t7$2E0}9x>;wrZD1E935hnI-X2Fc~cpktq$$vHmP;U$>EcL0d_i)(g9!$J-8<4HY zJ$YdANQ*Lm7U5z#%}v5OIA~*`n8d8>DdF~oZ0P*}J5hA#PEx`bjV$?O*f8F+R{Pia zdvZ&ss?qsx?T~-tvl=B;XcQkZd!S>*dw*iO7FP#ekug_4kZDt*AWKf*BC0|q`5rL^ zTsRo8;bqeIRHVJc-wxMvA-9x_qVbYpv)nOzkJ$W#Os!{U`%X2^o(iW>OvWRLcP7Dy zJ)kNUeXZ+T^TM#UBFk0VF{QnoB320`@td`9A4IM~_r*&DzaUA%vqdL@-8dn@V2J(` zm3mTpB!WzGN5)b4Q_)Wn&MDPzA`w30O5-*8vpVCKpKL}gms>KhO;aRq+4YH(l_-MJ z@i;U^Q}7iXa?$HJvO=Bpvi*=0?4&aClt}%x0!)LmPNqUeKaY8-=BqYgdx&Q*G<^FtgVLV*&peTgqO6#?Z4$A(S_)R!W(=R>_SLBK z%;JKtzgkR*)V@Kagxx;nDswV#Y`$4)pr7DHx2BPM+kCkA0?+LvrpARnF89TSZ&Tjr>dd;CVMWDPFbd zNNAHzUztdWv{6<|qEeYv!?TBnFPAnQxr|RRsM5Xj?w>a)+K;lMOk7f8<&N%hRpL=56x{58?$=**Uw>9>4rwB?73q zWS^v)kgljs!w-+ykGiNL%F_Mssz!&M%TtY@VuBxeYd8a=!Ea8a&j(~p4%m0!;o6!s z+izHRu$X?)NIyN?Ag%4d?n{VOtkhn#psgP>`g0bw2jW*s9(6B&8CAt|=nHMNK&`{1I4fNT^a^aK!yf?V1?A(&Y7!J=+AO zdYB0Y!5&*0PsF0caXAv^Se|$>pp;Hc6G^^_YHoKS32SmFyvcwhROQV-Gl%mtw3zLrKxMhO2 z=%>%s?qFaJQ6MGZSU_8xjCKEqZQ4_3a6+xkNh`~v4a$A-eD6X!qF=u^@&;O83#D#G z*5>Z<$sen1l00H4d(=+g*sR5IN<5p+^+A}5XX+V)a_sHwhG?+GZV9uU5B?cnzuBwK zZ&MyiwP8mL=;9THq7z_;@j44+MpeGZ>r9T-imko!RGsZE?V)Jfy4eWVmo&_Rl7HLb zN21>ZMa*&qzX(>HRYJb~s(+56*kNj_j;Gk`BMw>**$+|o&7m82EGLbnu-$W+BqY`! zoNzuJcfT8aC38H#xn||lv+^Sd^eYz(cDliM>*tD6U$rhh7 zRqr~aUXkj~mf-L7$@P(|cq9dcRSeq>*eyt@)ra%M>+YK4(54^wU2tWtel&23CbR)m zsjO6+6tsuoX{I?Y^x4dgs%@Z}1^Pg6Ga!)BVJdzx925kswGEJ@gl|8B9B;1a`CslXE4Z z5xVD_`j|SYE?qwe_aekJ0jNxo3eL8R3SHfJ3?HN-+LbOD?Lf6BP{Zd5CK*pZP3NH> zJ^z_+mz`s~)a^m4ljQ80K`NJu^(K)jd+MT*@bUr);Mv5(bc+bv!R%3()%duaSvS|| zp5Bw$0%g3G(R(c}63XpO4#U09)13C%k#XYCRtV-gqpQw7a>P5ouCv-h$l-1sB57P@otWQsZ2_Py=XqysNMqx^p zIiA&BhA0-2AWzOh@ZezTgV-J7ozp=LZ#t~ASGeq=B>E9<_ zS!8fBJn(Ifp&37V@JItcK9lE@H^(MSaG6xP$~aHar$F{|3xVRW35rfbiJkGxI`s4F zmh)@Axi6|@D-aPMIPqAtk)2hB=;F4NBa5_Lzx=Pa(z<0kgRfxd>%OyrfaIv{NS zU9#b~b$6e;8p+tOjqkU~z!`RmMWuXL+rb9B@|GF$NuK;)XH*pC+0b#E0x{}1+e$6X zKvioy)oNzyP+lb_FhYWtkxoGQBZ51Xuk(v)<-u#Isz{Y{eT63=1(`?c)_}PEh-a^Ycdwb3yMWD?w_YVs_cJX$BWs<=*Z}5Y|I!CQ>Y%1Yr53w3Gt9a zSQ$-9KznoDc6}VXS#XpwJjO@gaYpj#2Cr)6AojR=AxI;R+;Csn)ZEn2ep7EiRdXPg z3W7!dQ~3vgj2HBnv3~K+xWrH$Z1_pxK?683hYv5wLyt~C6ldem6u16 zrr1qW7LX_`xSh=NBqHmwTe}UlF;n6XhMWqf2I{=L>6gZ#`qmOz22st{M`E_0MZfR? z=pZVL(!DI3KjKF1)n*TE7)GrcM4o7J%f%$y=JE0_Um62+oOb*aN-p^=#1tNz@~dUZ zN-VS#0YTr_Th=Gm7OJ4)SdXQ^>B+-WoE#Ws}*E}!3T-EDW=nKb}|%tq%% ztdx`fkBmLTayS6yaO@HW3njQRfXV2=a~TS^MPoM?Ra{?~4~Mv)1WX)lC@ypE6jKWn zE=5?NsD)Unye3kP&HUbc4wNeM1C|JP*uVj-tnHM5?l#^&ac|G)&gq2%j>Ac7YLw9EoI??|Cv06(3YSW zu2IaAk?etybduO06xbOaB^DSZ)gC2x9felPjS9eMu<&Tz>u5uZD0NAKmUsfA>ll}H zR{g+eZR%Ke>ewJSOc@y&)E*aR5h((P39rW`w8x_?;!`9OG9}~VED{O>Bhz|)8VG!y zc0nzrhyw`QAl7>jAsgh2&3!;3P?EJi0156#@@`T{{$f&OhOJzuY)Gd52u$5?Pd&O$ zJ(Wzm3{3meo*Jb>dn1`fv+648pG#l$fA5J`wdU)3_3k zE@;8xg+rcrvY%Q?Jypm%b10Yv^}_>IY>~iE9p!nQ?UWmB8=>+8yK|;KC!P*a}N_4KjC96wuDx^EA*CqpT z`+`AiIvbruKl1s%N?6VMR&LY)Y)TQa8*jWo5ZCjEw*6SO>yeOK?QyHq*w2oKJZEmD zPl4}jx0dZH^J}9%H!9TN>1{C`_c0%riQJs9!jO=%d2*c%s2<(B21}xZ;KxePhef5N zJJ~Nk#?vO9*F5xTIc#cqp3@~&7NP)xVqxI~_t78QG6XYYu``W=W9jurDA>Eq}-8Y=X zU5D6u^czz@W{ zWiK30qm=1R5#Ebrve>}W`t)9~?4xNk)+7q?X+usFt6iZVE13@X@(Z~Z1|<(wGx~N% zE5R!Ch&R<3kJi&tEqG9|pfQSSO5{`~E0my(iba^2iF^Y8FR-lmjH%#`xv?}HxK3Sf z3-1O}3xmdlqCt8mOl^K5ftqS^n`Fs!avpu{x55*q4ihLoSU3_a8unT0!)Lks&q{Lh za`%yHALe!M=RYV@dSB0L-_vGhjy`=jrEk@x5Z`ZKMlEnK#RMXM1OiB}Gg#Y#1WKqz zQO@8;LAnbwh6LN7&ki9Bl7??Nsi&J4#W0gY>7|_ua=##3&Max=?&TDrCdV)xMA6CW;L7>hS7y`kPXw@xD*2tW2Q~nGWax5BeD90#mB)9VLAY>5R>;GV1Xa;w49pr0a1GO@i3^@?zozgXQsx}Te%?ow)W z_d0$$ik`z2K3u{mX$w~jhd*Fk{-L*=%>{#&(<4N_(IqNMlmWE*Fb|TURbRUtd{<(7 z#c^|&wUj_K;#}(Exg7djN#R1~J0Yl#P!)Y)h`wOz^IgVeN5NDFVZD+EzHk>0P>a66OIx_S98Rk?JKa|S8)GVaM&(h z3^`X+UWZq3KwXL^CuC1or+G47n2s{3WW%5_Q#U)TJep}Yz(D9?eCKMgtiBWOwd|Jf6S7h zNaEEtN4R8dApnKH=T6EMyH*`JQcw63S7#$Gf=QKDE|I(pNp=1AeruSyW?riHj5^(7 zD2w~an@E?(Y-06GZyYA_<(_#t8@9saA{}_W)JilQ50*b9Ni?l}2tDn@+kV}&-WP^e z^uet;{@xq?>sU&a%g{#ZWnfl&veet1DRyV}nk=n;#$4SwH}pEC_rJXf#hvGHjMK&Gk~Vc@C{7!_?g782sgRiMQ)P zTUZB4ib!kV@@t!CTxC3U4QArc>fiPxSvFkkcQAaoTR}dJPcc4~RjL65 zRC|x;5c3<1zkThz?m0-Bxgh9vlT+F7{;_}E8|yOVb8ts=;VTd8#-0O#?qB0chlSVU zPED><`feseq6*OfYVNZ#L?v5A85Bmszu8PK!Ia{wCO)yk`-moh06t>yojpb5-SuTn z#~$sASZmJDc`f5DEd=KiD?_q$%WhKzt!mou z+sljj6ixSQ);OU^zmDLH$xG`e(==^MzArxPHab4*2?~!wqr(i>H9gaH5|?y&l^APh zfQC>ab^PF;5=r5d-|Q$nu5IG=-EBmJj(TvJqTzGzwttRWb^P$M3vc`S+qh3C-aj5D$mep zu87y&mO{UR1fs0Z36^Mo*XYB4X68bAGRkyje%b`?(J0R}L%0oWQ1n@5SYu_q6}@TU z!CxPbsH)X|pCT5#VJ))Z09S3}%qU~ErYxKIsL)FbqKXe~tm-*s$SdOM7}~!=3`(I~ z*Io&4vFwV2opVTDz#@$KRN99tl}8rTBI4GWp4h}QqiH@hi;C%dBbtg=q$?s3U^e*< zu8Kk0RyY%AmM1cv4G+pTPA7EdGj8k{sjW63!kO?bDbM@W1jA1Q(RDM_FXQq-THY`8 zFUlEdMn@{}dMUV}*ejGJ(qA5XXJrSMTPz2XV_q)^I4;Z<8qNBZI9h~ky3?tdxbubk zIpW+l90eD-B(<&Qva+Q6WeQl*M78R{<2*p_Vs0)wEu8EJhK}%ucsv6uzta8l*!gMj z!~vV6DxGdAg45o5z92IG`HCV@vfYgSwbCqOzU^;!7v-|;&OC4KUEi!hD zaC(VDf(%+>Wwn<>ET*f(%Ul0;S0;FsmD%0hZ#>H z7SlwyyURV5p89LEcXa(V7BVl{Z4ZRrqu=Xl9hex#9k@!c&1a8#@XkFPxc{QS=T~Dr zXCf?k|4tM|!Dk!MVSN1p^5(OH8@Q|MamI=wMeUwaIGT>+u5GBt2=CYY@Hgt(Ge=@q zD~hTw+WA-hmmi!UtW!Fy!*f`?jWRz`4K;GG=3uVJ+oi?K< zN{?+LPn_8v8AIztdMLhlr3Df6lXnTVv9IajOtOx%yu2R7+wf8)AP~bQ-gz7HT!jTf zlBd-!SvTrl?ftTghT#>?fDyA#UYIN;Cu_=>mKj9E^m&wcX6_W&@LZ*2MTi@pqy1x- zx5LFxj?c@a?`%FL=aS)X3zb{WCdi{J(?6>_Nil5~1=+l)IHz-2mhH^vefpg5{YuRl z2X02c%pjwMlm_T)pmMapg^fA><6ZdxaS{6=iJj9_2T9=L2>!w_KUjwmh)*v;%+m2JH+*7TD(lndw{!abyf497VGwoIW_Jdc{$XziyupjKv zqZG}y!Bmx0I2?9w_`vq=4ejo=5?YpsC;dB4jJs7-F`3du97n{UzMmSf@Sr11$`$5UYtZs z(Vs*Kx=eZgMHSFtQ|~)Vu7n>yi(;OPd=}U6mA9i(FC;&aHY8f4;55Fo z+~=OCKfj#9J0>5aZ;E)ZsSj-ozw#=)O5-8{-z>cv#iQT0_v?k0-p6kI6VmK^6Qp z@!+Y6#!#|+KyngA!Y`~8zE~T*ILBa(04(p62uWwuUcgHHgBY&lp=+HVTyEICW_X#Y z2iNhs3#m9)sdX0*pY_^2Y{xAE2V;Au^;{>#4ySdIr_vcFlAdPhil-vqrh+X=6f#vg zG*j7W9Pn%GS_5MOe&B{61!|3CTfE?O14&`C3Av{U_T-6?yD6HIS*rWV1A{Mk@JRec z?X-eK3HC$@gLGx2(3xT`kU%G@4HkUquW_;oDH5+!q}noe<}+9=veW{zgmTmMxJgUM z-Q50UY3@4T;~SgvWb3C8}xxZh;BxZSRsfC+Qu44i7uPJ78%Kq|)y_2T&lr#5y zx7eO5e6Zawp(Z`4ri5OJB3ryH3sh{#R&035eW_U*)#pYz_R4yoc!4r!5w}D^ynx=a zh+?B;DyWR!kg*o-t8~N3ohZcXYK{VAkOdcqWOxn-yj=PEs_@UN(--A3ZRHMM%hzxU zG5yWQdHx$t73#FF)lbW@fTfS;DlDEB8>(=yj%45FmD;wKep@QVx+x8zEgRk|a7=_@ zCp<=4v1{CzXt_$dYe76|c}TA-LN%(^@-o)2Io3cr#l@KfqlSb(zWfuVNY%xUU%|WcY=|M zl>u*XpVJ16xC)E$cu8n^S&lom(&py}=d+C0!B8&*a~m#{YF|jcVpFYuhO{Z`Czwo( zsokj$4XCoqt3r=fG1lgWFE@~q*xi^kot-uuQ#W>CWz@7(lPB6BI70V21^n_;juOj% zEvL-WmSAgz_tX|qAXV}5o4&niBKX>5aNZ<)UDn3M5yxCbRcn3NiJDnP%_TY$)s@F- zG*R8c0*sXqNpDDb&3mCF&&HKQ0L_UfZ(tg5otM5M%k>ca94K7_0dE1ErztGBE<)=q zD*!DjrTDfjK24kL!MTVOM;I@4QT zkEFz1%P6`DZmYw$X*Ul|#9MKnQQ3c^am3GZq6+~*o6c`qyD~-Kddjd17bF-Eq94dghq$)9^PH(gD`j*-+Ro^lAABn= zN%~j^?0#c7_+aG&q_2iCx_>gyU)!#~ePQrbZ9kM5ghJxlmJB_d9D3Y6y4<*N;CpAyTH3y8M_(r2bacp73 zA%Ia^#bK$ROk_HJ@_g+IU%Se>BI3U_`>wPxKYFKWM-lu;q)`UCk0f40u(G(I-_vi5 zMAwhU&<{JnM-v|nldMoL?GuE59VmMBNLgpBfpf%pqD^PJhF7wpYj=$Pxn*8DanT8O zKaAL=a?rE@R?|I>avK$|hcwELHcyU5lT;eM9#$y$F#Uc)J$DeQl&^6&VO%|Cs!b7S zFu9`keho$rFaZ4Qg}z>)o$DT7n2cJ|8C`Z8j$v+DBN(HSZTEQ8?)9k7iMnYzXxzCE zicY8Fn!(@kB0ikKXGXxRO9&A!2p=I}X1#>h%|yQoSbrdix7Jyeg@z^*fQnchzaGgQ z@?p9sh%*teAp;3N+$l)u^jG?fhe^09y7Ou&xLGG)&4zjHsd?Ro`J8q1yx~2#;C8hA zr(TR-nY;vYpfT70_{(bi7bc$a8C3c?`DiJ9b@eL)gc}ZWO5Jf<198Hz-H&%XiFTFX z*gkr@ejd94*1I{#-4OX*!Ddhd(H=@*FG_C@MTCU{V8t}<#iW9$*Z0zh_A>{ za{Dh+_wyR}GpzT&$?X)&e_bX#C}%`}Ez>(F_c*9ZUHyJP<4}sX1!t5HfboL>%Bm_OSfq{!ytis>?Ztb)vVmK|JyKtMn?w%o7ZM{u8 zTK;sj`bnihfKp|h2s5l~`3qb_64E{gt{D(mpWuut5`nG{`>cHcia)WQ|I|+nG!pnM zUIGOY99ddZ<{^m-nR8c!g;$J^8N3l6gXWXLE{PC%yyFGt3Zvg)@SH z&|^gtG6Uj#06^7aTZ0Io^=Vs=@o2KBiM8Mb5PkMk2zroCT#;OyzwbAz)64;mfR#0`~bIY0zCv>O)UE{(G2q z=%<~~LA;D>$n16M$LsVbpOTsWy!d{(Wy`{4$J(~bf?#1~mYZ8BVwIU=1t~0njr*h1 zG$ZtVob(4X_5Uyx<4MlejTYYoxWUI z@RMC4uY-!0+{8@ZIP+{#qi(yHt`>Xl?7q*83Z4qeEPax{&#}9f(ZBlEbYfrp_j}Xb z>XVpF!OsBtm|Fe2>{|5g^7P-sk7(krF6`C7SW7Y1#r>b>q&U6%z=M#PI zG*c=?i%Gx6InUR~gbz;`R6lLauIYcu7t-cF(*AO;F)WDNX@S=g%*oiD$|F6LEyyH! z_x^CH$5VS+H|+f}`tS?0eN}x}SHP>@ya-?UwQg&8?OA~nQ)j5*DPPb;!S|M)(Bswj zYfr{LM*N*Bc{W}C8&`Cu25Mv&gN;Wmd(zhcz2ojd_l6Mm7T#%V4iF0cbXOo&Fws$j zaKC6)B{wGp5St$7+7po)Wxc5;8(_`ofjw_U4A37P&WxG0 z0OF;NVLyj5^IL^0*&owxG6~w9oM|Hl$bEE#KgfczSjSC#bj8PHMW)2JvWzDsc3XWu zN&lM9oRa;0k*Oz&CMTbi2UD~fs2p8v7Be^MaAC*Fr~4Xd@xHq-(h*tkHP(~4yf8LU zq41kG+%4IXL^th~s9+mC^t&{*u+R4UVon8Ru2VzL`k7mYTwa>nL{a!#*d>WwSvX{x z`ddDI<#%Q2T%PT3+np#bE*Pm$6UHPkytb}G*?Lbm4*M)1eC;j? zFspISNXON5Ig4#fbO9BnLJz7j8+{LJ`^Kf6>ZZTtAJ)Cg2|jr9@}{%w?W_P@P3zbJ zZC%@dJf8=;<@?iAkHIe-M4lZCW$P5s-WwUO2HfxCCj&tJf|Gif;G@%?2H(5xv5~qJ z@6oSavfiI$e&6}bs8EIZ&S^{B`_3DihxvVZ7;x{mWdAbEfBD(_d;b-m#jt?2kl*(K z>rqtUftyKAE?K@Or#nft7Jr@=1-y6;;xqfZ&(2GojM^=F-dqUG=du}5P({FmkgQC*dxJ)#l09d5gD6xG48I<&zt(rZ_wkViz4VfW$-RVx7kmFUjm)y3P9Dhy{c(HknvSmu(0kq`hKhNYB*`M*;o>HA2}n^}!E0ZCe3B!K#Kb$GoEp|8a{ zCnhC$ubiHuBe{XUb{%VA!L5ZdVWI!Iw+)o(hw8Y#$OOO?CE7P|I3ZXWAUquE)ES&- z^;ke`&0#TFu5{LUdn$cu9EBw$xy@7WOkBPlq09~)farPNYyk&Aqc2sLtq&TGZjP5p zR>IL;VkK9@t3r&q=s56*WbFHLh*shOhP9@k<8*uYNH4C@3J4>>9BjVFv7v82mU#)lLqs5Wa0 zX8UmXLpcP9v_jQKQR93C2+p7^0kWkGDzJek9UCV4qgVw8j!hvX1OOb7rM}!LY z5yezR05Yi=GNPDzk|qFH@5dTDiN$kUCyt{A=%;#H;GpdY93T!8!V4!qG3~oMj$i03 zxshUJi4?lYD%ls6Q2CS6B!TEnMyF&gpzlUn*mYF3$p#Dc-&2J_My&cPig=vf=L?#| z(G*`1Oh~Lr5*1dfS&$1-Ivo{>XCg?4MS~;v*D&>iks^HoKru!E0`TFJCPKF>8Y&k$ zm*w2d*Zdu+#hE)W|CLQ~!v&`6Nl)>%5vS{?*7y*8c4)XYJzs4mR`;0j5M{7If4`?L zH7b4NIx?{shbvz5Uf0bYKWf>irx=kew-Yf4T{Mg;84%DFe=aUUeKq^}5wXMK zhn&?{TLeo|_Bho08s;Xk>qNYhi#3L`>Jqqf_~Y~6re@R7$e6x$;>zM$5$ zZmKs5J8Vx)A$aa(GUrY2r~f)yV^)?h_n`^zy~0 zY0aH6W&ZV8iiaM8^-Pm}K$O?)8rGO%&+mqlaCG6eIXL)R2N7U^wP+2ev|r|t5Ud6Z zdC*ec==bI!g-!hy#4>Mi=1*T*#B~(Yk#C~(PNAN^i6es)MLe$s9fiPf06g?Bo&a4s z!E<`4&&OH!hv?Zf-=B|IyO`pC;gNzU0O<89+&o3O6}r^$?j9zUh?pFqm8Yc!AAf&T z559W;B>lK+kqqQL@;HGnovNz%H=tR5WtG?@GF|}yzzHy*0qpfObt(Wx74GZguLk6g zx=O8`<(CfQ+yMZdx59iP3IZx0iwzY1hV-Jbka(dVpxwQ1eZUs*crh%bz&W=%X|38r zC=h__4==0T1Mn;<@m$B++0<7{#>!v;tRWrM$ha_4h#4a8Hz}l{rJVSr_Qyc613d1h zamTF^kg)>fKZC>eLOwxJS=YWl(gxHb0)aNik!pb$3qA@$*zSP>6)+WcHkC-kKoLv4 zC|_xNS^cQA%ETGo6c1FIo?Qk_50O<>5yM6rI)ibo0Kr~OijNwkbd*&@<5fdZ{Cp(~ z6Ai0SoFGVnWO8HqZGtl9PqD0u?zWO1IfTb6?gdM{AvR#YtdR5&TLHvY3&8ZXMNwU= z#eRlv`alJjz-Ahex+gugm@3TC3N1Ky)jB|6JrcAT`M@?N@C1ujBi7^w&!yslQS)%_ zL$JX05ET;f>U!9ftqwIKg~)##0XG>E>Ll+pwf@y9D>{2 z74ajifx{N{BW&#>p(`WdcO$E{%7_xsGdQ>q0t~qB)2Rk)ui!^QqWBWi=QTqxjic*j zpLlV7y8BD{w3cab{6^z`^wnBxO4U<8s5*&y-W%sFDOk0Kv^I!4MdA4JB|^8daeSBp zdgI(Inu;wZ9y7=C9#RP9PFQ!m@qbho5DIA#o$yiAPPGDu8G!q-0o3id0W)!ah*&|k z@{hG*vUB5wkjb~v2qT2fV0814+vJF988LNiATrLuW`w>!u2dO1Nw0&cJRQ8#8Hv`R z+QQ|Si;dHsT5yi4l7O|TAp-+o_r2(kE!f_p-~e(6*=jZ^X$kKHwnuxMr!z?K8aKE%mY2TQ8!&PI z%>Yhl#LUiM=G?}%haEaP!8#N7*bAh)S3-Oc8SWLsu@|kz7LUJ#;|&;|>S}o!66tY` z>kfz#K!8h@qy4L+qY1j1-Hj!}KD(77g99aP(_1a0W1b1ehTJwpw$JQ36!X5~*S!WS zp!tkYlHlJ5a;(wD58O@E-HCaw!NIvE!837E+PI7T-OoUA(`50AGvH-1h=Q)H;t$fh z+c@5f=s*CH5L3EaViM{Vr(S4k)nGb*9T`zw!?v{WpwEP4bzTn#sZVGMpk5HT2mgtb z2JB%I`k*4>s~+n{F1$5$Z7_SbkVu3O!qmJzr-sPh!{rzt^6U^ZYH%dd&>?&Bp}iT( zCeG%ASzwBJ&?=rqV4R*tqyTjcsg==V=SUrkxQKQN?n)!xcayp$U;zVEuhOE!J+D85 zVhB8jqZy=sG7~{-=c3X|Ngo9bMp_iegFFsBW+*YT%a#5ZmzCwFrOEvf3B|3XJ=PeR~UTz z;`{=`ZvXiYb{l`5S^<6h4ZXjC{;`h!F?ssyAB+3q*UrV^uam>I^Sz_1 zy~SU9I~b1pU;g&)&eqTEZ4AMEwz0FbzHqjqMsEzEHwMw`gEwnq zH*5Xq)uFxbgZEoKx2ru@tKBzSvFPP)^kVPLV%zERhr@-j`}xYd*?^6$jqjLq)c$>G zVtssTZ9H{ledXJ?Z~qdxmp5#dCwu1?=P?@h>|XEO+}zCc$i$Z+48PsF+MGL+b3NAj zZ8YusSkkxA*wdl9&0*AO*UQD>n&qK{#o_qHp^$}vilu?b`GK&{-8~Z>trKs8Z~Coo zKB!&4Gq`Kv*%?sX7;yg9VL93CKQc1X-`|hXyt~>v-@bi2*xZZ3w};+Vjx~o4_dO2m z^RZ|(JFd;0stKNGh!|@M8Efz#X$Tsr_q=Q1zo{YHtrcHtu=raIy?YJ8M20Y4_kAVK zPEpE9lK*`!-(4I^XlSUeu5PHP`4`9ix}frHS}Vrl&dyH5oUE9# z__zf9rhf?TusGC3hzvRcfDQ%}2bV@fAj85Uf`U-~{{G%R!GG*^-`T~XRh7^JoToDU z|H8LJ9fNZ9%5(L~B9;9dJ)%?s8!>9PMA&;_pJd1Xu(++Qtt~ArO-xJ-3=FijwK2T5 zD&}BtZ49q1BO@*$DJm+0Kp-%xHWwEcnwAO;24jHkdpvL%11&2nE1U_=@Q_zRULc+hp+O=4C|G?UKGFkr#YriOoqL%&du(t62zrosC@K~a6 zQi!Pk3D(Y~mUTfI;GQh~KVWV8cqQe3!P;!`eg6&C?tu@E%gcp668s0&Zmm$?ifftV zW9t4s5nd^K{^{RgZI?{K9*+NjwZS=8$u?FD?Pum77;`VPY7dF>6#oByd+-63aY_(A;}V7ydnL*ZpQ+&pbF?@VMLI zA|iD};P&T5e^GD^;Po_~dz*cCe} za15)LXV8#1&}{&_2ciuDZ_4j&5W79>dU8o%@^R;pzB@K~2@D-KS`L?w3k4YT;^d4D za!8*h7fDoE2$TZDy#Q&W>rlT<>Z zTainAY)mg018c815Rq!6p99yu^PZK^0TG13xr*@RTwFklVk^qcJ_P4<_!r=WPzKb? zYsIAjB{b4d=Mm13edMt3uTjJF;4C6L`L(Ew@7Om7;jE=e4o>wvm~j~3PjDHU!i^Tf+NJ>GX6@lESuz^r%1pttNpFY3L zQ63Z=JWaK^%7hQKYO+3SF)qTr2*Xb)eqv&f>Z79+%;Noej*DmZwe+Q+4h{h+Np8A( zph?mx#6|J}6p6UQB0Sr*~I%FTf|5gmUR%TWFu2iovw*u>Q~bFVA$*CL~~i#{g>#ElV4B59QZPcCZc;K z{&ELD30cp#>7(B<=ucn;k5yXb4rzqfCb@v@2W|p}^&6kt64u!Byls0YXDz5pZj*>3 zvDC-q@$E&X&eP!(OAg&0!j!|ePjiYP zSalp$J_PZ)hwGP-c{}f&1iiz>6-u)wg~0J`r_FZ~i&b!)l|q(F)#Yho-@J9c%<62| zeP>&ERItzR%#wp=Jw_@SHSouEloG9xMf5@_HMpLYW`ZQ1rJI>J0DHg>pcp0bvyUi^ zFq&ekIZjfTZpk3xW_kUvRe8?sm2u|Cw;c-Ccr^@E_=gZbsPQsNq!rgMp4ISa?=VYm zdc1F|$k*Q|I3Gq(6Xfj!v`=ktg=lzx2`DwgDMmD2$ z#R^BJ4ovmkIH;De(``$R5$2=V`)Gq`ZakLdm)KYsCSFxe4*;<2wND2?aHW7=gl%U= zId~b8gKBVpNB)3|K@kyrDYXwUz7vO9aObza}W^7VgfjVs$t$z=Xt} z6gtLmDZ=)TgGGb}q0cAXegbCtq{EqihBqsN6i$W}Cff;1JbyFU0RZxoTrkV_0k{wW z{@SHpNZaWLcsQ6~Js^lN8GrButaP_QQM_eVm%oKgqs;Yyk$3B3`{?hnNSSJ0|Fx=h zx@7<{|MnZ=;Pw2A*Hl>O1Jmi7{Et0wzwcwK&!+zluNJ{O&`HTukesc5M$Pr>I3n$R zMB!esSR@4B|6#Q8b$6c{Kh;TI41Cdsgq(s~%n0OELLqNl4oacuW@1{5q}@y$;0;=9 zCft1okb{Y2_dUYe@CN__Hra>>7sCDl@PvN1)7>oMxPuIBjqpoN?C; z2nhnhRt-RSr}&3noZl#GwIh-XBA40m*` zDx#gXwVKgv+N~y{py&UP+De%|-`7Jr?4#0SLz&DywqL_6n(-B{K-SI=>Ad9^If=Lz zc%kS9}n-GEXV{#dCK9?gF!6bI^P!HcgZ33Ze_RtQ_CJ@ke57Pz{?^lcri609o5J)_GX2<{7kUDuK4=Iva z=zyV!g#`f!q-YK!V3U)Fle4#zWVt0h8Gn93V~Mp`jg^!r2mq5+S(gQn1R)FU@DB1s zmEs1E9p{N!qYx|*3iJq;^kIRCGnQqUm{f9>NY`IQ*;T}4Tv+9nDdb$xC0*245Hny8 zj;NPdc9mM$mwX8Te=w8gP?LnoEPI7CJ*k+kX&a20jD)8jo*6joID9PGl76{2xS|4{ zK#Jw?m8p4Qt4T7g`I^Y-7qOXfvzZ^YDNryuE4f*Gs}=>Ja17=kfq!$G@E3;0nUl#G zp8Ef>oWG}%^5=x^@tm#}nxcu7?O71=Xqu=woVntipoW;@nV(F9pBB@YF@~O|2B4_6 zm+twVp!t#rA(LGeoa$n0GRU9$8KL(Mh`sS2QY}Ao`{Qfd!!e2qpg} z2Y=b4R$8ZXI;n1RrI=JHmy#-)x+$o#sh;Yoo%*TZGI+L$rtRpGPKuxeaRHtX3X@=0 z2}PwhnWB_ht5ssD)&xmn;-_vhC%pQrX5y=QsxXAQq=xFD+ZiR+DF`J>TaOB-Mkc8` zq6M{33$_|)6pE;1daQ-|tlR3X3?K-ha0Mk6U)~y)wE8G(;0&#Bt!0+2$%?85s;b?p zt@H{2R1gZA;06mu0o)3$dnm2$I7p@0R=%A|#fu$+dg z1e>w&N}pwVsPXEt9Q&`zCkif5t`w`9DJCq`x{nz#{)0P!>C;-@35(y0kPanrj*gLol%?OPnbiDX;(y&w!yt z>r^k>eDZ3uGyAb)E3=9U2pDh<@FlhY%bG{aAvN#}(9joMdtYBGc?`?8PW!Za3u3+* z3Qiyg3&sF_Td~D?pT+_VLtD3Yd$hRrI~}C+qoj9sDhvX zC8}qfYqer&ER3MFAHcY}MN#ecZfCR(iLeIWkam}QxCy(rA$zWx+p}>Ma^va&YI{_r zTc5alu?DLnA0W4kz`DDIu_&ih&E1(^Ff$KnGu5Wn(^tCe?oi6UAA0S>rC5V2Q(jZnl!e8fnc#7exxOx(my z{KQZk#Zo-QR9wYYe8pIt#ag_@T-?P+j0vIe38&Bs?{x}Ze8y<3#0{jrhl#^(ED)C@ zebje8K0FXWOn3YH5B&?n3;e=-tigW##~2*Kf(*!nT*xkb$cX zzK*QGjaO}!^v`lZwyhFgn=5k4;;7;JU9^fTY)nSoiPix$V#>fizH5vqbdLZ zDoncbin6DBEGX~{(ZI5wEKQd*hGlq$W}>#4gk8_Rr)zC;4Ce*gd@ z@LreZz3F?k#v-&t8_dG|wx%=^neZFqP^YA%?tg#)XcOd(g}+y5VxGq$mq?*as$x-4Vf9x zlXSP37Pb#P%_9xV`9TAs0Js3~0?g;Rrkk$EqPXGg(M10Q(nAK%c+1cYUDDnGx(zl8 zvxd{T%Ff}_&mXb~T8nHnEkrh*yB58>5UtZBeI9>H1r)u)LTwv{$;rqf0?fPAHEqgvzs=LnA-*3V9fyt9mrC2l z(%9!A2G9@-cFs`s;%I-F``%i z0MS9U@IBrLp#$nb4QrqUir~q$jW0g1(ZNXIdl%aK_1QYbol|J4iKpVY>Dz(59kc8S zwOj$KV6q54+X)d2>fFZo0?s0y-X#8f%B`dm{@(aq+Nd2K3J}QxQ31rTU_4voS{;Vt zfDG604&ktiMQz(u(h6EjtUtcX4hq;&4cujJ=48$sF<#3Mj-9wH<(`c(JE1WIVGs5Y z41Ba%_QKri(aW`P!(mR|=$hsWp5(%v)(rn{8`eA!H88xbe5pWF5cr_Z$uNLh9x`Aa z=rG;3MtKRru`hs2MVPQ0I$8x*d6Q$ zu?G5J3t%8{@^tATQwz}G49p&>&TisF4(bOE@9{qEHPPz=QCG&m;w?Vr2C)d@@LgIS z;30zs&z%G7-t4G&=7*lshQ9Ef9v;`8?Ft}U#Gvmfp71|=>{lYU@O$uXtMU2m?z-9S zH(l*7uJFuZ?*K3bcGU_Nzm6~OlSBV5EPVbR=&tS_|D7N|SSOG2K2PYC9rS<^@dVMV zC=T-&&+a1g0~_5xIsa#}4u&(oc&U!-4IkWCj~gm4yzq7O>FD*(Ztf!E<4=#g?LPG# zO7aPQ^*vwc&k>l|P7tq34jSO~1fh-)De{q0^Y0N0>0b6`pY%eH=xh)4gpcNdQJU9G z5Vwr?Umx>fFYqEG1B{^5fG_rtI{3P7@`k_pxo#71pY7T{a*luZV6XSaxbv3}akXxh z^xoTQzxIg#7m8mH$6fjZ;rNly*io+|6=35VQOg1Z z!2mP~;mObZ{2r%BYBg&bZLJ+D`pa;1s#HjJ>*o`{Lo>l1J8MIhv-M)nzSME)-XTuiV z`Zcf9y-WN0_3HL7$|0dZxmY;LoG}Gj0}Foq_3m7^btx~c1^}3EJm8$N*j!Zpl7DI~D!AW*BJE#0p2AT>0{b!MT#=sd_c< z*3`#Jj}Du!c9(@kAy(+d+_@3C;bNx=oq0{?>rpy`R?Gc-`t{MaU#k8l`u*II@~;WN z0R217I+zrYjiF%#Qb<6W9DGSX`%uDfLXKLg1q}-~uUs;CL1Njvh>DO>(Y1^^wB z8K<6gl4*&cHMWT-9&I!vNRe;kc?TOU5=tbTd(wG@B1MBNVJ$`wMK;;cz~qwAHP7qR zrcXbbmfC1Xq-oAN6*_t{6!s@9{7If~R$Oc#2A#)z)P zw%KvrG9evBx+!%bR_>VqfHnTff*>^h0RwwH0;hJp-@}^|~UXkbMhb366m8Tzv+@q+|bJo+Yy>>Hm%^|&9p$IOm zav=)Hx$W%Empr{BwsB%b91h?%oFE<6`6VGU(&?w4adssr5qI|a$D0`lO2?Lj7Ws#S zg)~T^d5n;5IJ3uq5^RJ~%9e}VmxqzWb%pnH@)4vCw{g_s_DGPUK zjXR+fzR_kP627TsjYF;xhw^xkj$ohx5#89v0sv6F<0Wq)zW7H3BZ$3Zp`kcAuwDkO zH@W|rzz-y9GfMbO0>Y$-aD*oOVCpWgiBMdjA;mBUDVT!76uJ*49;AsX{;>}p{=*;p zDAWnOv5nUeFv1`UgDL-R zl-I;2kV<*OQmCa z6)9y6;aE>7*BbitM0VYXO##u6+QcxfGkqsS5p~uLDeW0_Wou%WLfAeDR*nCNMI&Cd zcTuZyq%fdhK|{n-ju-q@vWq%d!x%fE4;V|ar)AD)Jpxy-N_DEPZ7pQk2;10x79t6H zA%i?y*&;dCP^z_0W`KcO;vxsQ9ARxcdHWyQ_H?R>p+%)_Ef!ylxmTPWFb2rafM;N1_l4@-@T*JJtVhj61mFFy(kT zi~t5KZaih+__wz+j%bNZ3}h0Y_^uzxs0$mS7;@Cn!b&D1lfC3*<-lSkRED!q*u0Ps zf6L1&;&PYsOptRjpdlDQa+3F)W-JfZ%E|IUG@wDNI5(Oma|Vl==Xz)6Y8l3Z&hkfG zAPS8-q^s%^G=l?M=tDsoIq+eaqg4&HL-VB0d7?CQ!D;DBH~4#cbw~tkBSV*BnwzBl zZL5*hij@><)yK|>uy68e8~OUNX!fS9J#yL1aut0Z*lw&r`!rJv2L+}@cDO&%Z2&Oa zF|<~$w4MEIE>CGT3}L{o&4_O2hO}wq{>{R~y>A{VTVj%?l!O08Eb59v8*3G#g4njT z5IKyeJlQt*LxJ623OTaZ5w(_# zn_c5*m-Vde&U3d5z9O6MbVGFQ*Shaqbze`a-VY@`zi%Ay9$&kjt8VqeH$<;5R!CPL z&UME(7Vk}#yrHz9=$uu4-sW%j=UH^LE|2puq z@4U}5-yaou?A>!G2et$L@qyc$l*J#Do1Y=`;X4}kY?r|jsNG-n_ch=9*dzb_wQmR&W3d)PA5fdV!)#<3I3Ih`4iz5jcm^AwL8pG;W)~FcAaZi9l7;KjtIBOdCH7tU4Ev zB`SD`j`Fh+yg<`4!TDRk9}JQfOt2VqKf@zJ(qo9va|jr?3UnvJp1Z6Vc!&kLFTx8y_?yC)^FjZ}@d0NTFD%T$Dtx>&L_#h+KF+g4 z%tN_LdA^010_#!&we!N&ia!nsJLF&-XmA`jyfH0=!6S^i4dg)aTL|=Xh7rA}MGh;a zMOc?G_yv48q-j`(L|B7w@P=g6!&B_FYwSNtBnTRuB?2@C3b4jzJQG>85KlyoM@WD% z_(lR#DtLGW8Ni2CAc!!)r0(*^T9e29%nUZf&@r_CMZbr z8Yu~Q88Mir;US21paqD`#+8#q7lg-n47nGv zwH!;cL`$}W%eV|nx0K7eluNp_%e-7mywuCSoXfNH$`9Z}vOJ%25CXpxOTI+R#Z=72 zv`a03C|?i;Q^v(a@1kT`m%}fY|PdJ6xJcSS(2H|AR=5$Wxe1*vT z7mC9s0YHER7y!;hEv4FqX;{gGaLKD|o~+zT$7IXKG|#+5&-A=Yz+_LoT+jD}%lMQ} zwZuyrV4*7@%LOrp50Fp#tk1Lr&;b2P$P7w)Xa{w$hMHMGql_E_NB~06&eKw=Zm0%@ zWJmyTNPc>Vn+q$Qo5>*z(UP$#LCC>Ov9201#hL`Me-MN5)PRLp1Xe(Uds>GRXwYoB zg9K;+W1G;mDy3jR1T8>=VDN{7K}U7;hIWKWWdy*Ae8&;Zv>3>$tunG|+(IZtI(qVj zhnN9*2o@m$$m9rt7D#|P_)-71DkW-AhkJO3Z8#VJ7)E%Y2W&v5CXLdGq)91#L|b#W z8$_ScTTwoJs26RX7<~xS6w_@S6G%t^NJvv4WmH0pNt@KtNp!}a^f^n^EbDT@EbU03 zw1{|l$whV0$aw=E&45Vtut^1#h)g#<712w@RKN%U7FtDxpvFuDRZT_1hX{s5(1JtQ zhIc?lQx%gAV1qV@i84)qJYdz78bx+v(JdoXYHhG+bch8Z2SM#qSuH__u!eTHhjy@r z)*7XAOMEVCWjToYTd1X z{noKaxaop77&3;hs?{g;$lp8F4rzdxD1Zbo0F%WrklhFmeZ_Md#3Gc~rMLjlAwa{- z(~cF`k1W_oU{;tIfCNB*5CGayLRn4pRh#`X zT^U}e%sha>jbR$Y;0}e=dgI`SU0&w>302Gu@t|H524YuRV)|%dq*wtqSOE#X&g?wm zkIh*X#^L|Zm0c_5Uz^ZY$5>xpO=C5dnk=4=EiQ^kzy&sliIK&FF(%^>p<@tzUA$G< z4gLwl>sPI41p_v~^Sxr<`(s3516+uNM{RAt!x;ckYB z5|ujun1ZVq28hKudamdF^5pMIV$Og7?uCgaz*-w9XG6>71f=F(m1AD!X2J*stx^b$ zwJ-n8ePVPr=93_=f81xzXah;mW0*k7Js9Xx%V>rmT6_M`h?VAPehHI%J_?Z88z|b7 zM(MYTzj>erL}1~Ori>0))y5^rkfu(2K4`v;<6ll`lNhp1*cJs?5W|$|d!A@_LE z27D-<9?)W)1`-y)T4@C892M$E7HgGe=dv~ld(1ijD4Pm<>ZgWkDU697papTzhiq7d z;dMH#ri=yn;)!a z&h3&28<+(EH@FIwYwMzY>lrSI9k7LQpa*M61XmD;!Rd%{ITrv(mvw2EcL9KSnU{LG z7lJ^QM$m#ah|_=>n1YE@hp=O(z~hc~i7Mbxv$btC1mt`MxlyKE{Lb&0kYa*>0n!-; zxhrmy&N-l3g>1lwaF_*_1OPC=hmJ^@m5H5xf*F~i8Jocw01yLx5U7RFB!Va!j!TwF zrr(#40OOr+`X21wE^OXb=%e_H}ExONG7n1=gH2omU0j&K{;ksG=J z0K35(y%~p?S#DZT2X&YR%cLU1xuWG6&*yQN6@cZwb_sY*aTUky7I*R8HfsOGHi;p~ zs(vlt#W>*`PiJ)wVwb?|lW3jSsh@;paoj!2V02v zh{uNM0Js@}`fvaUaeRLmHaG(xMTtniUw?04OAq*l zmv$H@^OBGXoC5WQXZV6AYWOvYC-;YScye_Z2W{X`kkF-X;3digCSf8bV?rhe0Eccs zgLRbdXqu*KVtK{N05h#Nn$PLhj@q$i@ts%uOaF+Mb%7a2pFo6cfgkv^M~QBba+r`O zdWs->!Y6&=&>p}Bd2k16*!y1jmDN^nW)Bhwt!=Znk8_quQg>Z#FLjK<)hQqya=`Yw z$N8M6Y5T5Y$ES=HXai+F2_iOP$yW}`Km@#oB%FTuw!e8y$Nm4@_lOdmgsU)yHfQ36 zc6)3*31lEIWI+DpM}GHM@2~g*cI|1D2mlIpeSJn6R96TcSoPY!`=J+ly~X^(2!#c) zFVDSiop*R|{)lcEo^Eje_jiBhH~qO-0Dpc7r2O9MUk}Uhc7+Iodj|*r0tXT-Xz-xH zAOC(JZ0PV|g+>(~Qmkk(;zWxYHx9(e@#95_AV)$JNwVMtL7|M9Ge;^y$c!gv3iL?x zrp=om6*AQ6^XJGE|55-gYLsFdT#|%jVo7m+Nkoh zniK26vuFvbU0c(n+k$OLV&Qep+_^~`=dR`37p~i~G-dzjAgF_AT$)-FGk&-O*R2jW zLm)_yr!nTtnm1=&OpTg9YoDo2vsHMiV5)x6uD;sZEMUg3Eym#0(wGpAvsK4Vy!&YC zliFkvl$DJ$$HmAqN5aKM=a>YLmQ$~8{klcv0DPHP8(iw|so|rJKU&^=Z;(pJwH)T* z;eIz_F1jE3?o^_~yZn2@1PF^H122=qmxFCaTX-7f{0%<{uB30doo=lC+ z_tS(uX*O$l8izEp!t-Xb^-3Jq;41osCkhAW0hy+@wMR2{@7? zkwqE_l6Kn=H-kIu)I%IZzx8@R$LBEaEu8$~Z3e#2c4xnK>q!h-wy}5W}=|4ljTx zz-Xc@W~wP;YI1}~J>K}@i#PQk5+{IrT30{<2dMfgtO{yJPZj`N;|l;;)EMQV;x+0h zW{Zv_?6AKM1cRjQg(8XzClL#uvEW4ul&2h_Va+(;Py>dMa>hzh17ECglK?>q@GZLO zc9tpt;?R1@A1?aS|`_Nx1lw-0NS zR2w=SkU$g?YrL^k+O2|5Kiddo%UHbLo7w-u8l@Z)z6}pFB75c(;|2hKgdzw`2)jIG z!V33HQ?(mOu*#^bNYE|299wh-E|SzaQxpewr!>`72bDArXgDCy8eupLY_LD;v~opc zmyKlvlf-O{9G5x~N+?6nWOhkA^K3V8QqBa%IP`=Q4n5;=OJu}W8#I9=xSVm*00|&) zis6w<-caH8>Fq1tn4>Iql`T7@fR`eOCNQa0M0rh_)e5uWtq z22re23kjf-JMfchh0RuA8UMBBo44-o^7J+Dd_z+dGbt(W4TMD~n_Q5(hMaRB*y|(3 zIO9C1A{Kl>OiKd6O;JN41N!kRtrh<@Cjc-S{?s7Py637Z-+w`n)sk|MVgvOwaS#1A!JkkibJ;13^T8Zg)QU0iXeiTO3Uq*Me4Xu!QQWoK=Dbq6n_=fBtjf zKmb-Ea|{Cp24R3oP{%+PeorEAP-$KFPw3qn?oS# z5I2lb2^3L*B{K%Wcm5@rADQPtx*^h$lC&H7WMXrkLz7gFfrJEoDQC3fj#m)m74`Zi z*t+M@V(qk(m>EH`MmNdN6%!B)$f8ai%1kU8&WgYr&{AkpE(8DrrdD0o`D{^-WVpf= z$)JZV7>d-Sj`N}Mtcd>t)F!YRSY(~dYG_%_+Ea~y^dVqS1PK7Z$CH|H1&|pRO)f?Y zA6&JtalsKQya5k*c!L#JbYmjt3N6X*<*X{RtV3WhJxIC%O)4nZ!Nw}ixLOXfAko1# z{Lzmu+z%OiHDO9`!YW9>!mzf*ic@i#JkoNCw^CuiDDFZ)3e3i4INPOfu_Doe)DyNceAcDn3T}Z5z)G_+xiD>a6RenLqUF9mo$txWYL&DKcN9l`OT#{E zF#aXiHRWxHgA4z1Pyp4(+rVDM64Si@NhgTyqu*Ef&%mbutkctpE0|;kwF#-U()D^*zE5u&hQ!^VO+MxwKg3*XZ1cM&5 z5Nnr>yxad@`-H+^qFF@iGX%If;mh2HXMG(4N?ZJ+O$bScFYqj76J{WBteuGnqap8R zn_4^SaP>f5p$=?|SKGb@woZU5uoqBdE~e9AP7#joPE~ph>JW#!4?+uY_yZiY*fghG z>BIsj;2E{xH_8E^9eW@Y4E7+n8Vw%lbI+vKVvj^%fJeGzSu2#{jom9zyS_x$jI_tth>%hk7JVbxFs)PSV4I1b68JW`8v6K-czu5f@C4T z0)f3jl+JW*xMFJmJ>?gaa_o^nF#);2dhY>E?4rE+vd9nj{SmUNU)5+w z_GRA*WPtHG(AX6q&27ZlLDG6n78vEwP*L9jTHj50$_bc(51IiuRKuSf#J=6$l(GL* z@kxcG7{e5>#4wPc)o6!m^#c`F;X3@n*4P*h=HLs$-ApJz=gG_n(x5;{AK4k;8Mcu{ zfM2>`An;^>3ZBGN^;%TG06DM&IzSSTL7_99k1MdlFO1SJtb;7rLOgVxQPdyHXx_n9 zA4qsWvOM1+0l)xaQW|33=$YQo4FnsaiyKZ3KdID7j9OKk!s(gA6!2jQvdcC&)R`dCVf=iewqV;>IGV?_VPOr%l^ zK*KX+p;1W6={cb_a*TGQLoN+OFciufv_n)V;@X8{>2)DO_@5r`P$jP8wlO4lxuZo4 z+L0im>O`uoTC0WJKw+1t`3^KZqftn}=~*C3ZVZlSK`?MdFlfO; z*aA4n!#iMu*9Zg$Bm+Fm12#}4h}GipwO}SvBteXVz*r9hrK3=~AY9huOhB8oQJb|H zArtx4fXxJ}jDbByU{Rc25msfae4;kIf*GJeHmt+cOv5@P!Ww)7oT&dBTe6@+!W9}C z1Q@nQnT^dUB#sX{i{98>8-1%7(N0LM;9l%E}TU4B05;A5=ZV)0^gEugQ zE1XJ2?7%;qiVWaG$tO7kugFUd;EZ7c3fWbffNh18i3=G6NTw6hC zK=z5jKWIS(JSc=lsDw@^g;wZ;mOvwvfQ4=-hjwU%VyK3CsECf}gn}rEo+yc$Xor44 zvWxChPg{mlx-e`o{D30!^j_xRmYQc0O1lJM7*P;LClwHgnJcE@PMLhh& z`qk&RXh%4>+J2$IO+ADIWW#2%!aWcKI0Ph-qTcDf!nBpCnVu<{rm32)DVw&bo4zTW z#;KgnDV^4-oi@TM979VG!=1M2X@){3^r@f@Dxnstp&sg?zCw^5#N$PtFHBx@LS3gd zTe4Bb=|Snk%nDcT*B87TMNES_^aPiBDVPp~g618AI;f9!=m|6e6}&2}#;UB&Dy`P4 zt z#$NCZUvJuoMovx!s6iV%DMzqCt86Dwz{5YB2Bt8390rfu0;E!&=h+qN#&5&=*)Y~6yVP2z0|Evi9GVHHy072@N9tgPgyPc(f* zveg1KRFzSjo^dK}72!?>h`}0|UqguLn3APg(gQZor*wucNQ^G+w(jbdFY2Bz`jW2t zPHpVY?)p-#$Vvh3nryb|?m_x)LHuDLF2W!d;vsr#)CE$#;ljO*MB^O58rb6<0fj&O z!x~60tQapzIPF7_Z~U^a+Ggp?gmrs`+l(0UV+L@N>m zECRs1=GmlPQ|^64%nraux)e~H-VjRgo>2erC%y1SU@!@btp_J@)-Ev|saB(Nt(B%2sO zLo^W9Pw2qu<=-1e1rY<0_n-M5n!PQ2!Ij6R2@A6F0 z!=|!Urye#HG37`=Gyph5eCh-}`~#F!wxl+O1v>;>PcvO}aB*j_9Na}Q5CKy=HP)iG zcuMtDyY)=KD`C^{T1T>B`PD5rv_({EE7&9Pp2X=ft#32PD6e!WbHs3?@^Q!Sd!w(I z83PmG_02H%Y4LONi^=`M(*Uc^-IzAV#_Q507Guigiim1 zg#WhCWi%B)fsg+@A;xXI;89AIdsCIL%OB&xk_vT6lg7ppLm#y zIdyLayS0f9B*Qq=!#X5G1Fyk0#6vu2L$@kaJjn1kuv+0dTbf^4rHX(vz=F-r1iM99 zolkf@_wIUcgbnC<94tGtH@mYxJG4i;v^)D9G{PNBJGN)LwljORU;DOy`?u?Y^L0D8 zm;160!m<#;rhor=?v6RA12!~shQ(nV0GI(bkWwO~gRq+bJWxXzn87u;gG^KaIAp`D z3&bJpgDr@`FW>`Y8$^0rRf7LSIQ+v{4m&m#J8Mrxvg?5td_2g9yvUC{$(Ovzi~Jij z!W*1C%eTDCgM7-b{L9b$%ZK4GctOn5yv}>U93;>n;K8~-H<-hF#C^I19Xn7I-O**- zE8fEd%*#K#EE@bnDFs6{yu!iTihq6sWm8VBUsoh-AV{=dHTi@*V|;)_{6++KLv;Mk zzrD-nJlxMc$;&<6zda?~#W8%m-QPXQ!$H9aLL2}+rw_e}@9t`^AXW6;>oL7R$ih1a z#0kKIFJ%7!37GoR13)6ELkeKMfe!62fSuQC{6IBF;DUs01Aq^}LP%Ed*`qyns6Aa- zbw#+n-`{@U-#*;uzV5U99I%Hm*a6?GeD9BZF@3@u41Un(ce@+Cb^3K{ZU*bQ9vkYw z6~b9MP~kY-tM#9X=L-ZrxFVobv_PC{3Md5WUy~X%4Y^uGDj9%4Ft78D1TFl7f5E0!W=^6)C<-01L~!i~$^oZP0WfBT^S^S4g|fD_)fad`R4 zodcH{=&g+heP6%luK=v0_41cEnHo~WSBjZ=efw>2wP~v0K!O1PBzOjzMw)UUu0-rh zP{9QmY|1kF5?l_r&qABc!i;3Q&_dNTl!z2_%+ci_4m%`>lTbF9Be#-x>y4!b0YLwb zK^bQ(F2bc?w9bqj%>btwGXS`%8^m6s#hnFQnqZ!_#Ng2udCbrOfNQdO$(w0xdN9W= z8#@CRNg8O%fCLI~sTOE}X$p{6Qb}#JuTCzh3i2Cqz~I5t>cX&RnkK7>hliNXdg%~-XbHm? ze1NR%vN&lKDg#My`JyQT5-`A}H4KvhDP;bEr`BVUO_ruP6}*(PJN-PZ&}dWBlUjo8 zAjceI>>$+I3+M186hI8ptx=R7ZE#Zi)@8TS`kc)%(?sNwOAD72@g^R4wmJVqrc_^I zWt@A&S!5?>l}#9cHX_j#DZm5+zySekA&@9}{;5jgjXBN{VM}qG5VUJYo0epSO!l*) zb1IB&qY?!{5sq?MJU51PYYZyq9NQf(-i{yp80a{Wbc(+OSO8#+XQDBTC==oWW9X@= z?o4RrevS;vLg3PrU=LLICE^fKs#X97w9lIKDyvHn) z4`={~MvS2>yJzpi5wA;c#rH|8uHT2-t$9qhFM5*(dG~(lt2(_``ouF)fw)( z6P!D<#uF!e*4DXP;f!4qH~>Ha0k35!YyMda_TPb*X>p(L&g}8Y6Wag$YvpH~L)&8_ zubebEVisiPgG6tX^wd$WPxaxxpN#e3vwWR=1+(}v1Ed59>;eGJ1l$>+7Kp3p^YKS~ zc;Low?0DoyBt7IYZ#5Mmhl(^OK+yyu6rVsK_G&h|7pbdz%n4s-E*P2q<d&On^IRw8AIu_{TP+7{-LfaCJ_cObv5LK$59( zG?XX@=Bo9>)5O6xxFKQ$wKu_?Q80;0Y?c|t=n^sp(k|({MF;$`^a!jKFSCcJs9OHUEywHhKw2&gY=r?9Hurk~4PNBqwzUO@gqoBgL>t%M$2G(HtsK z3|Xa0^mw{HB5{f1WSlI+NXujjg^EonApm|5IA}0pCkyb$KYp=JeI`hqkeT6K&}c(y zMr)uExm*w9*t}1S3nJe{S2+C$%ZP%knYHZaK5eoC^&zDIy>f{bb!QWL{XX?7pC7=K-=$>A>5IqDca~ydo^<>siJQ@+A+%u;InMnV)pEj|gl}zbLWpV~YCbD*B z3Z{2zqL^?Xm8z3DYF<`amzE9?l*{YtXbjjbn|?JR40K>b9O|f^l9P|+q!T)&c-5-f zMF0rsWdMK`IH}YmE^Ci10pJgvQ zR2jnciGuxWn1~X9{4JJx|ks@29h?i@)%~N|v!&q!~&AeVfTQ}v)s65tpq9rzQawHr)2xD{wd|3fe z+Q&;geZ-Hn^n(h!DzK3?pO?3nf=af_p^b;upDY z{o{UT>0KVr1eehrN`H7+rbf!|Epb`jmeDLcEuRz1j}h`3J510xBSe(YlU8qWYCX|J zdALBOa%M6}nLs}V$iMUPKK~owp>&j&wgcvYiR2O-{{tCmwsZ#}MA6~A`C3F?jcqlI z8Z`o-{^yUA4Jpqi22jGLI0gj$8S+I64ed$9BrO-m* zG_^b}>Ny+a$Yc97S%bJXD9`tys%EQ1SAFGm4qKnNgziv|7G_4C_9d42hcAL1Y;O0Y z*giS7oR>Ua3&A11c2;)0y%4TYaAJ9+K`HN)AwyxUL7zB9fT66$Bi8>gFC@3ckCQ-J$<;Mit!!82`f0HhBWHTQB) z2JAjG$kVR?hzojTo@R_EMdLJlrZg!BayTpfPj5`}$0fo*QJ8wq{!VqvPke1nCv)hv z#AVGRQR|&tz^=S3El2@Ci+_wG=okMt_-0@2zoSdj<9u2+y+?VW%>@y3sNwUvrxtpFlH0xfnW$VH<8@4-!=kVLr{9W)`x39Lj zPI)wkQ1OcH38QPL00ToK8ua)_H6%azn19#up8q7%kv->`?)JhEdG99TJ9?{2ndNOQ z{mWCodzt^Y=C^pUPj1c20f+#1+K9^za*yW2)1=)!;W$i}ji-Vd@Z|Sq2m?W^{FGDH z`7RGQ>XA8qN_HUO`4LLEuLu~RK^pSmA9O7IcufD4qv!zY@;E8;lv zW`p$V@ANj1nP3h9T>?L9P7?o?swW!Gc3L4C(qXlP1q63Y0b`>4c;fujFZ~j$!$hg3 zZmV)?BNX(^LNw6+0`K_?tE}jif*a(mQco8z#rH_8Ulw8Z1EOVQ8E^>CK_=JeKF}o z<3q{;Hfr#PdhiF2F%yZf4VMwc{y_}lBL&)ICM19r?qP87CmN-Q`fAQEdLqVnX&k}; z?YgnGa4{TdVjT7E5y_Dwa<7qyBP1xg|#66C;83@Nc7;O`PIWFxbU4L1=KbJ8B; zBOhTR1HfPng5e$f5gKt4%|s9vtj{N+U>yD-9c*Xzpy6I@a;_RuCku-w%c~1565k~8 z>4uRYEbw#u1S$VbFDaFhGG=HSummNgPx6pZ@ougr7Qh?+K^_L7mnuMuVBsv$GAmU| zEoX}@xymik58o=n7=mvj=*S1#?SD$XW&ryn@MY@Jn5 z98uSl8L7~B;s?C4X6{&kF8?i6p4rRFc#QE9Byk2qx9UsthFZr3t| z0CAcCm?6Ed@Tm!qH2xy1qdN8x?$D5sVgvMn;rcLsC3$|oI`WAbB7O)~(|bs?#&O(N z$@9O@Y3_ok2@K`p6u-AAS_*_}8p(+A5q-4`SkxT#a8#r%6feivk;~$74NKof_Ays? z;uDOvdJZm_;IG8*nLOP>X|I`6{Sg55xE8kyD+#0>b8_+?swaz|fM3a^9$zTuvuLik z88zVt!KGWLJZDk*2aR{fc+;6F(-NA4ba)fo!LNIiU+wmh#h{GW9?oFw@>%fS6Aw^Z zgJ@z^-V#7DBzYP%dj(RbWK!pN;k>f$Zv3J)QgWIX?YImBR2)4(2Gc389BESQ3(7xdLt0Vjs&GS&4Vv00AF3@ z@{eporEKW9iaok&tYUCTvOQI-eP9#qPk`O^Sb_j_O5FJiy}KgH_?S|GqQG zIwfSGT#Vp#y(UA`m1evr2Odq=OUtfr5?HtS(Iv+yb zD~%9>ARQQ=x?zhP?+6))7oS?^Qo>vuYNk#(zs)Pg@#(Iay$Q6ZWUlOHDQY&M^JmOqy(+Cm%Hr_CpBcu_n;c zRNV2@){Nbb)!B}s#R_p${Z>wT)1}B>rqCMx#$nLQpegxZGxd)W8VHN=X=JCl zqYoAeX7TZw`x8#sG)#3RdsY$7uNU8461YU$sdT78I7?qO72Ma>F#zfnDbGkY7F~^O zq#v535l!Ynf2kr=q-w+GCt2RAl)8uW>N8qckcIltesgG0cM7dFK!_8j%_F=(hQJ<3 zA6~ENw??WZX7g)$E5c*8Z&aOE`qK<_P9u6xZ(IVdolCr2I+6+YBv|bJjoXEwZboX5 zT=`n?`{kJXy$y9^b+ESm^zt|kg<_8Q8E-ihpAs#fie?MyexGI?Hv>jXqp0v_YD)Q- z0|%$m$LX-GVNb*be^5G6YLa)~qxT44*$=glPrzMoaF7CL*?3CFWR56+Ov^(&N%xtW zT#*qQGS5&<1dswSDDhI5$1#P+Gk>hxSf0kZ8$QrQKWXJTA&g<1QHkOH z_?tMS{&urTzz0>&1yeA=I}WMyPl!rBL(5+!dyxFE;P~`yl3aMa%HI@5fz-&5AYi`V z#j@MKOnt;{twZ&44(MYNiB>>IYkI#52C^%xLX*L&=74D-?!zfyS@**icnX{()ku&5 zMoreIOJHmc4D6*iHX|z@Vu)JFzzRp-878VR?Fw6|X^uh2VCQ<4HP>%}R8;~(E-;Rvsw zpDkvGHAuai+xv=|->r>V@X>)R6VBKew%vM0C`P^mqV#g-<@*BXMzIR~ws5YnU_bln*SH>_Oy0wSBl6t1w=ZLNS#=`r2*Mja|xJO>~y6 z7FXeKo_^mxc6@Wrk=USW4fkt}?r4pFXie^D1=F-;b+qOAwUSYDeDQ1FH1$XCZOh1M zZ#HQCV~Smw5A6}|93(>{6-V)Z=$sMm`q+U?T7W$N(6#N?wI=-iDChgiTGxqix1RyJ zHmNfcv9m1ICj{KkaWv9V0)W+13k@y=4^-I0d$j!QbjbjQ5A^08n5r%2Jy*No)0nu_M8ZEh{$)`%7SUswNg(>LWPEpIhj_+{4 zj#2WCvB&Y$2mD;DiTE5nKC|}5oQa%{j&6g_v)s-J;qiZl-~RYbJw3KOJWf4{OoO|= z-#rXZ=pD9;b69S3PzBR_gUnllQ<$H)sto(;M2c&CUmV6&M{V7&{#Nn0OX&HiNMQ4> zjFqmVlr8CJ8$9u@We;15aSWKD{FR_`%wo7N0x;#x4qwg+9#kphHN$#pEbT8IDgB>jc?7(=o&Rk{WOKUw%y(*A6a0 zA%FUgQ++l=v$mN>fq~*2<>G<#p$MAo0&9unK;x6}4FQqoxTHXu_r?Z@s9rBj-Eg4b znqI)MhFnG2Is-6V`^<73-EzHgD)R8@8=&&&$_GcIyauZUVdG43e2+zB5GRF zY*GG{JZ~8p{du62Zf#`opduM6pj@OT8FI&Lp{CpsC%b0BsqdvYq$W26G9V98q8*q< zQTh;ybARxhq>(03BwV!UA zCFZ<1d1W6)Jscm8n!=JSb_-70*Mm{pOX1N+7`P4V2`0QRz`{0rv#JH_AAWMMeawEYA+laS-K+-Q@G_cCes>k{6wE|s;;xl?F`ef zoXfpG5E4ntlvY;V8xQ$H>Q%jRWV5i!U~_ZdbGiz4`x4(F+-o-i0K8#3$?L&8_y0hZ z>|nSZvJrx6C}Y3%+7*Sb_|`%TihNW*`5GxJSy}Wct|;8}CX*WWt{Q_bRv6_Dv?>WoIK&NU;Ow&s zar!zs!tFN6%$VcPb{Q{<7@v#FMe&+J&+Dqbvo1i%-kK$8{W&Ws0dk=OWWR{DnU(2{ zy?3mbUt~40xxSupf`dKg7WxP z(Kc;(h)_2*8;7Wuq9j4$(bKy>#EcOk%vR#hKw^y&wm}K&ZySLfiaglQcvw7JpHCc# zc;1I7&|%Uw=>u0M6`Z@EMs_*1evYel&L!8v`1A*vlBgA*0|{iA3Xpepx}UzI*<*ZN zl(+Y8{o!?CbH7^pL-fJ_F;VnE_Qi+3;m}_!R@Z7_hH~Z4tV(k^A^{7$zsP`nzt*+{ zemi^~j}t-+%>9~@evO9?H(siDta#19J8$rd0e2^>tK05X>c8o&&@5p zCn)6X$9#qHW}sf#!F6!;0|wc8jxGBds@16@iok*kvjaapOe$6w9m?A)!Z{|QAfAG` z7ym)f+Wwye-T=wr%sRJ)Q|ku8qxS9~pZ4waHcP|I?+yq!SPaCbiRE|t)r^8{!`>D1 zjfPcd&9LA>lKPu9MI4YkQ?N_>LxR%-^ya4ZaXHpCu83sf)`ZO$-h<4d z3Lm2y;#A~%*-r^03~_xTreIuXQvnhhS8(Jhqz~2??p5DFq3n_&TtbI!+Rq6Q^#9uT z1tx)CFpW%}#3&NX{zqmpdhIG7LepV86xJfBLi6J)i47?BzccI9qySB%=yhT!>yRt9 zE1NkrUG+~)|CTreM`kSz`YqU|@B{3n+XSqV1R|&f46`~=q3CiBa{SgsBT$T|GRmJr zW(Q=%Q&FkYuoY9Q%)VcO&CoL`QmdKYG7H~g`Se;4XdIkJt3r1o1ez?@25`B)@?uBL zqVHVV>2yg}(j{xgYUBarQeMZMP<|(kLaRNGR6mu72i*2k1Vzi3g68l`T;O6fRB(>q z85Kso9ufhcB%cbm?D`wrL%$L@1tgDp4$@2q~odYvqBkpnI|d4{|X9=peMYNp#$Kc{5}ovUr@E3XH^hY zALSfWn+>@yp>%ndAZkXCOSzagCD=+_iLXzKs z6GM@ayx71_88fj(G{s0HJ2v9TawF#~nZ~HofrC;&~?{^0-!L3_W zKW9cTcHiP_Vky3AxrS8c=AA4N0eYMb`$)ez35(+S_7Sy&%66|0HU7FC)NfqZW#hPb z?J)+K6TUhIb23WXc+tfk4ol7!Aib0yn_D_TiDdF7%u=T8Eakheqs$oCCZkMtO%)hl0ky!cQ~xcie~GV(Uuq$HMG7EGW+6G zZl(f7vDS6hP?*#W%rc@%(5k~@JgWTGPo2JXY-0ZL;-}fTs{Phs;FI7zMYfS$uf}+q z)W<0aNh?5hjrLq!r#;i3-8mTFHywrBYe+#(eV{fasxWLrvz514$OIhcq~Jpxs&-B= z7swEIE5vWVv7@xs$l|xAq4@!CUE73n!e#Es&x1@GWCky+tNhK}lK!5LQ;491%fQ$| zymElg@0YK)J}vpu+5~A1(NC9&J!f&otR7yU26T_}5G=uso*^B-VKGDM;l`C732Nfl zI7&-!Idv43_~hSCcZL%t>Th!6d8ne$!1J)zo!i)nw*y4aIPpGVJFl?s`udp&BCR`j z(Vd|s-aEKT*tgZ`GUrhwA`@1DN|yZYzOA=;+5VBSU_%n=RJLG6(@ij;Nd0DGk%n9BNKQ(FVneSmH5;bc}%?MEONm22Qn#~ z*Z;*kdA=g>yrP@@=j0c;SN|A6sV+cDY_s84lrcb-ajzSz;2V^k%M3@pNF#7EL`Z)cMv*6~9<)=Ww zlEBL*H_Q=SZ;+{sG!8x|=IuFbUKNOwAJns?Y8UCZS_pv9dxO179J(bF&t9F6|SorZZr}VE#qP6 z6K(=wofjotQs#hbP)~EWVm?gEuZ$k``LHR|8bS=^Hu&L;<~rzf^!K9_l_g9 ziMwO+Su6ATbQAt%D{jgsdS*l^N7wViCzoa980E!y^cizmS_k@GfLgd$hbo!}RqS;U zsC@u^02T!3;dOKg18u7TsS=r)jjwK_ucHzlGXown6NzoGkX8b+ObI|AeWsc0XJzf@ zMs2?1!e#F{TcehbP`Z%aY`B&Qp*D1K)m35<60E`IN+*8NogpXnsWc4$qs8+D)xZ zpTt&?iU2rPicZW6!{n5vz%?|@O2LkX^$Orvef)&)6P`s99kYb$YzvJZP6Z%&D!`K@ z+cL_tqBf z%t1{JDv66;Lgj5jEnv>*aczQ6ae+<8On)^>Ua?k->1GlzI@- zw)kJ}+>7OG6tgV!l>Q&u(45q_^)rCsXg`~8PadopxLcWz~EoWs~6Xb8jB?=WSc$OY` z7saF(L4Oog2!28}L*Jsp{u7L8#);7B9s#<(DaP9dLBW=aQ6RY==-R5LJx7iaKf*MH zVD2%nxYhDRJNTrnj{s^!plQVi`JycSh@5Pr7dWc$k5X58b?FMsI#U#zB+L_2HL8X9 zxN~!canD?m zWi~0~JE!kkdr|6A65nm)OzA}$pr&ny|Vx*4{^^hF=3I%w5a%Z_7Ne{}|osB_N$K5xDS{H@g5t3K&{4OF<@`yaOW!z(F2*jzr=u%2wq z4N?|fCVc^@6CX+QyugDKofHI+YYmI3$`@VD%eiRHB59kGNlp6&xz~?o%x?SC+LF22 zX7{5ppY_|~SQ2_N#%aD3PRBPqoZ=v1T%8`Rb|KUwAM|fY#Aj%o0nDAKl~Fg#<=I&+ zajjpt{Rmub!~gjq8Z!mDg#EgT$=VBrdr}6i(33FEripzYzB5q+Lqk9e1)wo)v`~hU zH>NV}(;VnMAaZ!h*-6p*b~CbCr}f9qByZI3Md(>&oX>5!k5z3ySh|+w>c80gmc;rB z@P9j+Kx4gde!n>(JNB%$#5vl=TF=I9V2Lj7Yq8$_N1|m=_f4@nwhFD+1})k8fqp}L zTK(y4JwX5Qm6Pui_{B18y-4EV7SvASq~g5k&wuWI6cCRI%)HPl$L@T_qHYEsV?Irh zh4hZMrJS~aW4r9DhpL!I+;d^I^XPbjxJ3Ce#2FJWJklalYR0xH-ER}>Z^l?ICWeV8 z!y{AKJTbm2b|>l#+4ol?>yM9&ljMlt5!c|ZEAnA_A-VW8;3YSBUqOIMFsvk?s@?2% z_#nsVV7FqpiM%9IQRhNN^$hDco?}rec^c$?a)r2Z%n(ORHAb!)Mn=`F*)c1gkKPCv zVP!`cvQu>5Kg{x>_s=h(YU7}FZb{(!%q8ba*#4Xpn;1GL>%(&u9QVLgsaFj_UjQZl zXzxKu`n!n1)(6hRg($^s=c2N+B&D7#9FPYdIt&TL4-uTrStuBZ8fP!Wi6rT1$AwVLu+r3P_O8D8oCzI! z1{{~54S=s?DRf-DrJSuF7bJ=VD&Zm@qvzW@x_3QAGTxP&Emu65g4Sl2E89eiJ}C4^|f=+@!{WZUE^&JJZzlDw$bm^@Nd9^g_#a_@tvbiia((cq@X zRak(J`RGO@CF8$G%_m3mu;6ch?;0_kUg;^N=ablGoN_?3(+RiT`4rc>6!oH)(>kX~ zqC~vOm=#)T*9F-1JL*=tpvmh;WuoVI@K2`Ic9Un8)qT;%=R1_YB9sv0?FmH(wWAn` zM_56N^l)JN6{P*_5@j3EUXOaW@oyD$^22SdT99#WYZq`Gd(PYSC`n@2HIl0Zd>1+MzGDUHSc8gwsF7jt9FNlw#d*;>axG3jBlWaM=?`Wg(SKaOh+mv@-kpJbf{1Yhn&64~; z-~0QTTb(l@d2Hj(Qw-X}exG7~I}&}LRdFxz`^)y@pu^^M%DV?6p1ZEey)@^=h8h@- z%f1J!YSH)AM^}Y$|cW`ARgf&O&ngYvM_Y%CB?;qEU2xs9t2a2mA2g zzhZ528!B;N2r2=G`=1?BN1RJf&l?06#_J68p2)dO7r5LZKot!M`H1?I&EU+#&w2ghP$#rpZ z4(Wzt;~U@ob=kvUX7%SfkBQlvDUn=Er-BC~j#iqTzqFFyUi4>aRb4x{YcS@$)=Lz% z`n~Lvd1A)xslWD4bLHlrXjh)Wx0S;fB;_995-FC*Z{JJhe9Y%%`Uqs&G#IUXwWN&% z29IVv?H-IxQRFs`1)KLu`vmo!{12|ORG5r#L-YN05xXeK*~ye>gBSV>AryK#F+40X zKV1*5;QWwbR8QQ818iRI0T>POsv3O>0y}2u1eeebvJB^H7Up>ev}EdhP*e8?w3&^cniC zH_nV0m$1%qGe6DF5-E%gkh`m|;8$4wa(C3Mkt%7aRDTlITF^ufv!8UX>l|B(vs^F1 zry0>&sz>`A=Vs(Xk4(sIwoCIy%3}Bgznn|MZ!s}I=l*K7qMBZ}(gCrHx!}^3Uc1nD z9G{_vMbb(W63ydOm5K~&6|+c6&Ec12!|BKn$sVuL+_d5686sCgVCt5@v4;|sa?0d0 z*#N!k4Q7$utb%)8&!cdgVjlIamtbG^-ga2pOVPYZd4p|}&^nNrz$!1j?L&s$if5F(`(Dmk%uX8!1o&zu``TCplc;o!(ahjZnmqNb*4a8~?h_W_kJ9Z6n z%b`!?add*$VwevEFU1}w@e}3QkX487`W$r7=GE%WH~h-sBd4LHt1{`kUs=@IS(~^K(#e^Ny zda#b^d9w1&FdZ|a=W#d?Ua`C5^bv)z6w>uxiTzn;x0eJ0O20!+)~Kp}dY3UCFh`6u z42o)(hg!xJQJ%;~V4!@Ba2%keTovmVo8H3otKSVrG8+^)rA~N{U-OzliWIYY7c3M4 z3&$Ppd8f&hWM_&L@s~CZTXhyyih(;h7Z$GM;)W_OrJj;nY)Q{;m4?{=C<29nz|GFR?e;^hHz41m*kf+nYSeC1@;b)rZnMm|^UK4VbBifLja_(#sj&PE=d)}HM(;fgihZ#ap?Pqjq zrPHytUrV4rWAqzE{6B!*j}v~zmv2B_2hHMs>kr1aLpt9to5g7l{Y)NbGf=3voP(ao zKqLdaZAi-2N~r#(?xe)M5bg62>q-p?P$a?5Ru z^(g4p;uY>ojpv06jE4Tg1$GG*;}%OKz$OAz7&+RTkgYwP5l_W(_mLB(28-|cE~?Bm zN?J7}`1u!A!&@8-@f{tci4K-+^xib4=2^i0*ja z2{Yt?it_doQ8?NPchZ4gk6Sgey>NlWc5|`*%LPXKFBmu&5{fPY4$$UkPK}plqqb5XVE=g%82GY|NR`^cMrSWw|~5x z1vX#Rip$-6+HkT~r*?D93%~{qhnW!l&2uDIGzMUF z13%^lc=raBkq2?`2XT3&nERv%J*4CnvEJVHiI<0Jr4fTKWqacp$ikrl(NXhQZS5SyN%?#1=>|h+jmMkj7vKfOSAic*_WkV zFl1ckhn)V?XCmVMO&6&UjRJBDBq5fIY(nokRfySB=*AfDVw3G<8xKcT>{nC_l~Nqc zl_j}_tIuUx$MI>!#f=tc{%9IEr;8iYjGDX}pKutO86B7A{XRXOG{qJ-FY`JZ@>AceS3MJ<4i5F^$-j&kkn9??e@(x|fuGHkAkJ7H9^2|JR zODgsVIr_M1a(^%31mRDLc@D-*O8EUaxd)v(q?-DBHF=4zvd1}fAvJZ#i*Y@WeruR^ zSFCa~o__ED|A@8ORgvEQuUK0Z#ZmP|6Aq34uUNZA6}_bGFpILV8p8kp`S{{>h9Vu6 z7ouy>+XqMb!Xh!#F;H*8p5>7q=V13(45^U_uiMBiP%!uw>|Gw|X!@c(m?6V_iTF@l z^CP{=BPd-ks0Y=;Gb4grYJiS2MDa5u>u@_8i0?EC6*$;dHqsZMhC>gfXq_Put8r=n(@m$Fd*9%NvNuc;vOwep8 z8}`}-?3)>09ml49L#weX|2EJttuFzTFH?f?j&0i!8Z%9M{x|s z7$tx@9IpN7GK7p6hHn`Hrh&fY`XMeX<)C0M_qaK5@O+8k*azw*CFnBdNU?rpsc&U@ zcIEK$`i7Cw)`B6g4TN%f{{10DEEW6_5zI0}0G;Jq?|N^v@MJU|ZhZ9C5H1_x6vd*8 z6#V-i{}zZ&Tmp*|X0p{&&5D%ZDi&ey6X`N-h@}O=d5`4n0`A7FeSI4#y+8a95j1dzh@21>bPb7GT4a1SJ?7Ya1tmWg3@#mJ~7W9gu<1D@;5@P=9peRk5kw_e8Di1zXaU~> zxEvY`PN*3yqqsM20ktfpy)5D7!Je%s6eGbbEbDwZkwL@|ss(^6)fPTVut)Ix`&$UN zJBGT`9-qVqEvx+?m;KU^4|;@9gPurN)vy=RuWK+14-Z$%)&6^w0}bVUEvFBJk_Q}T z_1NeQIH~-+jR)#jR*no-I-etO=jLrW4{&cI1%B+qm-mgO<4oRs0Kg6$IjrEO)^JXf zPgVN9giyb0e&IK)dzmPnnetuv+^k4@KYAeVP=YOcEJjViFK3?D1?(ecDT~D+S854p zMNyEB>#qrRfI^^%gsm-oByU}H0PF*B!6xDQ(7-6vrJmPu1jXVLkh5IPrJU1pYtMkg z1|VQFTz{1CYy+RR{d|1{2iO(V*0WTuQXEFcX-sw1(^5iQ@u(T{B(bL-JleOXE2jf7DdavWcul5y_CtX99JU$Q; zVra4U@ryWZJ7njFEQ%MbVY|FZVJ%W|t!YCS@-a2s3xMTCWdJ`1@7KKS(-v~AL4VW| zS`Uh=Zq3NFrv5aq;t9l)czTu+I?n(lp`vQ0kJ2z`a5;=rIDsgvaS9UhaeKvWygQrc z5Zv}U+d-fN{~#su7ASr7$$TKn32=K>QR@`m`dck_{N%UO>a)`v)}JFRC%|EYWsl?J z@5rmOo!8P^0+bdb0Ot!r=i1 z%UBJDeYuTgxy@)WWTN>6$!ZD*7&0pX`_3$Pk{rdV&bDUZjy$1W&YcC5obK9X<_sb+cZ%0Hieewiggb_iK@!F^b`j z>l^xSB=7k>Lm^%{zxzl2l3Tk`{(=)Hs^e5`oTNwoVf%aSiNU-17k=pWX7dd{5tPRz z(i9;J6%zexw98}UcrgOYmzox!Y_;A?vKiGy3aAHjGBJRD$Foi7l*eP>i6NB~f_cR% zot_q5D3_sesxQ8yz3a7$eX@l&`?5Jsf|D{Mo}8&MzW zSnk>{@UgiPC9kqwN(>_t0U@P~(ub%f5#4!E-4%U+_)piboxvSkApWKhdzX*;A9Q)O z=3+(TKEJwKD*+cU`ocMVi*@cvRe*NWLJlxlnfJ8y?r{}}yUK3gdjKug z1Adm_qD%&C{0Z3HBr`eRfo}o-JqGNG2JS6oZm9$wI0yd9z=HH_;Twg+5hM0~hY>&Q zmbG9VdBeYnEi@Pxn6=L%d;yW1x=1dW5JwwVJ(r?{pupS2pgR+&fz82dAFyBfNA?~F zsWq5~ohA727wb5y?@K9CN|q*5fKo&ja9f5J{3&P`Kl%=(mW+n?sFd1c!72Td);Sh~ zVuc(1*e4E?zBp!ghKcMq&O753?u=6}K`986#e-?4P&$!DsnUaau2lJp#D_}wMnTwI zHPAHke5soRQ0=Hd?C?|GWLsUn_!gVKDkvJZN`p>CQ5E*R^Zi7X_v_8?fd~*5n-Ax9 zUj#O-a_9Vb_s4`^+YcxJvgWY(b`bQ}8239=mWjeVU02LLDTEgl!XJzs936B;x#nKx z^X6=|#d&wK#*hEc#`mBbkv&2TS57?!9ciDHDyzxQ8X?M=Ei~D)nZV8%i0QDX&S0+% zkRwp!?(e}=kxE_QTfcP1(>DDI0&1N))4>=6Th?xm8AK(LX|~R?EksN>r#T}(1f6?1 zKNMSnc-x^n7kP-ZiM$y6t~aa~O&IZF4<-fSSWe4VkB3HJkxK2o3I>&G=d)c+)F!N)!c=6g#3%b7Q^xV-p(XcC0JXRrLXRXFR#V_{i-D6W2aK_tyR z9{1UDYQk$gI?{^bRCRf4F#z=)GJpvH0I<0OWB~Zc_rOTR%X)rBJU>0ZT%R7Fo}XUU z!_x!e@ec8D_4xSs@bK__e{+9-|8#SMxH&;w{Y6~t-96sjKHS{h-QC{aUfo^Y+}!-T zxw^i-{`c?S)%E4o<<;N6fB#)vUR+%K`*U%AasKDepZ&}IwLhy@zki>eo?agwpPZZ= z|7RT@A00oR{CL`*IyyT1_3PLE{{HUn?w`$#!}ZayrKP3C#YMzy;qFW$Vz6&>s2?$A|7XnQp+|XsVSa9IZhT>Ic6MfZ zdU|SVYJ7bB$IBWS9U2F@6D?&|9L*7@~UWAt=W$U`gt<5z~Z_LjDe%C5$` z)^E+-O?h8`Hnem!w6wG|H#avlS2Z-%e*OBjzP`R{rJ`i9xNxE1%Vb_nV_8*WX?cB7 z%#SFqZg=xmQ_Zhxh-!C4H9n#Yj3@!zR#DuR<35(5K9wNvR?2r)R@BwiHB?pA)YMc} zRaI1#6j$e0R8*9em6eo~Jmdu4M}BN9EN)KA&o9XT^5x6t&!2O1bCdFtGBPsKQ!|p1 zl425L6QffjA|g{l3&O&~;c$3RP*7lCph}&hQk}eVm6}GTvvptse_$(rVDpWK)%6F1 zxR2p}zJcD}AzofyuC8v*9(m5r&i1a6+U|vRcFxw;*5>Bsk2*>ZvQkgN0{5IOkBqcW zugD*X37>FbThdY{CML$l#)gK5y1KfWnwn~AYAPx!?|kdzbS&iLq8X77ps#mXGQBYEnlarH@ zk`fUU6A}{Q3RUyDamnKUYqqmjlz;hYvfa^)Hs6p^?j{Fg@?%cj1Fg`!c&HUx z{b;I~D^o3!&y#OvnTK&UMNk)u`&?n|plinpOyH6MA8 zrb>BYlxx~~PZrBf6s}?eXvSDq9z<&K*`0nr4)GKmwy{?C~SI+@HD&60o9&RsBHl0PE{hv#K;7-^%~cle8w-jik(M=LCP)1|y#B(hB0 zc#_>u*R`tH|HP}uyd8zi?9!WQ`N{Sm%O+(7NI_A2bdcjR)Ml0AT37*aSMkj#`>a&B z%owZ2LUQP*fh(1u+vOsdni2En_^>EReWX0i6vPR@P_wK&D$VseJ}TAoPaZ5Q{$zJt zQIOz!T*isvvi5no7eRXR1vD$am#?@}XG^{63T3{{dpZ5Uyws#Y4p)n_hc zuvGokWNEh*f--Mab(Xnk-riKI&k0Xt%HkP6e<%lMsYAnRZqU-jc z%K7U=yG#*CEwerkNMrM!x);Tr;CEh1No-C(cE?y*ZE%YM*T>NJy&7PsTK**S-F3&G z5xR`if{|Y{KH~T!7=|w4P(->oKG8Bt!vwC1;`RjQuTF}oiSTqZiL_H5j_*u4)mO8M z-5FPLrnQDVURWi50_7OuOY~3Hh@@llKtWL=ZD+9CDv#6^rgI{^WXH&H{z48 zkOMrI|E&M}w;CHDx}Q!uFeIu1{c`q0rU%6RTU6{gZ~t?sUA zt7!(&YB?ApT(|q6r`GWoPd;wOauMAQLjV9O1}c>uWYNEf(aohfN5c(qxCQCr?n%8X z-wx+04<(%#>7zIoM}qd4G2am!VDwbVwHV^OAm9r;&L>35e}f?iiUFj6<+K&;iZ+6 z^VH(u%%odk6ds*$+OW=9#-ImCSNw3xc2BP%A7Ql+6!*oDBG@F3;?4yEgdQy@Z*wEx zWdjkx{=ZWwa)_fi5>NqPRY}T;bL7kHHrdVe$&~m`tLsu!+HP4ma6w@UX9Y#s+4rhw z?dZ@XpJ|XS`>I%9u}o}{WXK0&!2P9Bapv<@ShmnM7*Jn<4gjdaap%>|Rm1t`dyxQ~ zX;f3lG*Sg}YT|sJ4A?F*!kL_E@j}YQR1=lj+i%3=dpRoLwp8Nf;)-7C=Oyb=wyU4d z6S;aUGm*F$4yE{E;9LuQz&Y56ti4C>9f1UH^B3MWw`lJsB%s#*rgTokLXFUM1E=k& zcD_#=JK+G)+B6U?gkB*74Y?E)y~#ZUM5PQX!1t&xdMk8+taa{M3xK}hRV7gU5#vBW z8PhPH>N!pQtYy?8-10riRkK+q5;2L^sa6Nt%7G9+XG&MG0Be;xKt!DE--~upI99tE ztr%EIEc0%18-s&<5C1qxhFcrD#-u1oaRZfMLQV+@MT@P|f3UB;I$=C(=%M(NFX7hR zq+9y_rVToI47ZigL(zXDYF-lU94fqwrjgo>nl&h#fD;T{W6Ys7a0!taSHc-9?j4Ul z571;wMIA$KeQnI55lyxnDgOsJ=o86Seb>HElQbZP^;KMv91njtV(_0hx1u3A9x=b( zkbKPrExQOFD?qo0^13oHe0-k+kAy+`dwj|!&p{X`34^jUPg*q7hi-L21OrHSKsaV* zn{5s<0D5%IxQW|(%}O`k!rbVK%q|+KoHf+vd7NX`2eRly!b^8(^g!?A6}`NhCI3*{ z_}%UhUzAuh%*(3GGip1A-M5>s7Zhv&JEH8Kn9WRR9yRUyd?eJ`F86$;IEj(Rr*S*4 z{MR!MK?s-Z3?;sAtc;MqNZiiKC)%!;5%g#vhi6ig{S_N#w}AjSOm`^{n84ypz?a$* zZ8KUybM=yu@Y|r}#m_^00WUolTq5iOyI5~IB?WF# zgE_X42$Y$S1YD?-u=6cQ^vb2)ic!P3PA%}&%HO|hN^(+aeAtsmXnKnS*hzf-hW7=? zJ*6)4{`jqlFhFGogg2-|Em?^q$)S-X#{UC>Kz_eDZhXAt7TXxe9qiEo0DyuWiUhzd zz#))B#&wqoQ8{ivkO@CF$sVgj`3)`yP86k_(skC4geICqZR^TLq9B` z02pB7AC>?BHLwnVEc_!10LVx31rmyM7^H?_@%)a=&{xiTKRjX=2>;mu!(!ft2j&7v z{Xtf*`qn==?@^{X3yl4a6WAW$`-wq1%nN|Oe?S}303M?t5Boq5%+^NBHxSMTebP4& z)n^crw-c22eH55G;RgWY_ZKSmKwz<56I4MLltCNRK_3)CBXmOpaSPf&5Z!tOGhipcJHJFjVriTeZ z1BdX3B1vFd#wED`3%L-Kav2jt8FN!3im8~FdZ~)lMOFggl-(6tYt>dUQ4P4@3)0X% zbZBN^sgY#qdSV%fc&G-+7y)bfZj`1p7kC?HfO#!5m!LUhI*Bo$CuU}cS(-(LPZ^b> zMOvnXS_k0?=b#SB_m$l@bH!+k!)2BSF@GRAmV%gRR=6Vz(36i4n#eg2b(wyRsexv9 zUD@S2O$FYa7&8$j?dGakpH=dyIG!!mJrD3Xn=T`TJ~zAnIonE zm&uu&%jt{a$rZhLYkx731W}O`xseNcCn9PH?hb^mIoaVj^x^O@9@r(jwTGb5&sDWC%?qkmcu zSa1l8Af-y$q_y^@ne?bQ0s=khpp9CA^$9QngQs8m7YoCuH0r0pMyeQj5XE)~8irh> z8k~%UsyH&It*V9f2>{R{E!zSo-O{Yk>a5q&tl%OpiFKVRkbqo%mo9&6H z#9AX1(36dTuHToe0wE^R>Lzm%u@q}26Wgo|gRi)ntD5?61mU4;APes>3$>!FE9Zli zcCa;K3cQdB4C{RkyRF#@s2tm|JpV>z1h58&AO+uAvchU$D*GWIz-=!Jb}=iN+KRN; zs;?WHhX8<a>(;1sX=OKAWJ!TB2A& z0j!#}>vpu8I<{&1wP0(vbsMOMUmkN^xaqpN;k39K+q8L0x1~$EH5UPfa0o1*VLOJoRy(f5 zvZ$5nxsWBdJ_otM8n$!WxWk2vYTy9v5MYlht_I7tS5g8!83wkCX}IgLx(m29%e&B9 zQ4gR9hd={TTMU;AyMZga#Q)N{&AVsd#B8j10llye^WY3S^=BxXyN>I<(;L0vs%Rh^ z0BicX@=K4Rn`g*UuF$|Sr^)?1rRX2 ze=EUyd%6{jx*QB69*PJE zAhpC$XZxEn4}7X7OeKvF2DMAVAN5In*MGyacmgqnk;fBJpiB*L#aNuhTD-+v+{IU{ z0eGMRUOdKRT*h4t#$s&7YP`l_-EwcN|T9Lk=c$RWnaHIl@Q zTw+11fBeTjlU&J{JP;B10adI6hg`>cT+MiF$k_bG+Puwc+|Ays#^4;zWIWE~?8RtY zwhd5N#6SV(jLz5m&SRX&Gu&><(ge8>m&ZI}P6UKPxDQ0Q4^Yf_j+YQ!YhxSAv^Tua z^Q$0&YMH@MdkX!%$Ez$(01L4&1N)p{PDF@?h=^LS!jK>kY!$->EzGuB!;#z25iGra z@~Kt;01>ci4FAo)f=evC01I@w(aqISujC5}`~}(2z%p#ZH66r8J<%-fAaFoREC2w7 zH4Hcmsr8IB#OxuO(2hL)Tt0oiy}%Ci;0!ob)GNKzN?p7yO~EF@2#0_L0uj;vcGf~% z)#h{69kK#F=>=Qe({?>sC{4p@Ewg4V*GWwu5wHlX3jikoU_E!#q)FGylBnk)zI(k@ z&wI1fi`gn&)<~@$z}sPkb$3(EJCLm`l1(0sfO$k)*&ub|CYigW@yw~WV4+BZGitXx{+)j*9(S3&;mMuD?2Q{ayR*?j0mSeQx}D=s zG~=e-*B_G8o&e)9{xwD^T05$4C`PI-_RE-t}mRR z)k@Au7%t!^-sDhzHM@pbO2Q4&0FB5xy^vAfKY1a)PdRr5&SM4!=Tf>`rbQf=cO? zjtn}c;o+n)J0ZXWaS!)!3tj*U_7G5Gt}h+{eZLOupFZoueutU9-W~4YIIbQrJrIjc zyyqS?U@*$ z{!Z)yZ{s4r?jSE21}_lM&2uMj(+B|u`fv(PUGv2Y_sDYE^^wz@;P$su^XBgHb)WS*@A$T{^#E|?nE?3xxuk(V^~6H> z^bw!DfcTN4_*BpMntk<+kN3ARe}`b1197&PfBAsV@k?JaGf?PS3i|ln!6BdXyZ`u* zuj(V;)&v0oe*5|Z;h&j*-t`jdxWBeCuK8uD@HlVa>R$Z?@6-f=26ILM#{d6am@oS- zZ!&IR3NPOL9{l{g-}}}N{HcETS}*(r0oTY6`%JExaBuz%d;etZ`>4PE?%)0Z0YKnD zf&~p89M}L)1B4A7I%IL^5DS7b-o2Bdkl{m)9Xo3D7*ZsF82@67M43|M%7Y*NeP9_= z=1iJ3ZQjJ0Q|C^eJ#o5(>C<7!lR`lX<#-fnL#0a(Hg#$cYSe@ageG_XvgQd}CI42f1gX3`2I29> zxUz4W7LAm2aGa)K>d$QBslBcEV0|Un->ba z`OlZ@YleXZt%Q5}_3g)f9#y^0?l$|={BNcJ1w?PD0UM&NAPCxdhl=ueiwr{Oin_0+ z{3`Uw0A66p1Vax$1W~37$%<|-312Hvx)Z}XFs2q)da)qHA}HvRcZLbz!MS1-X}=If z8u7=2j6+UHBab{X$n;8FEkzakaYACChXI zmRM#evrRYaJF_P;Z{jhfI!C%wq&)Q$bEi8aGK5Ck-f2fS9si*O)2BJ#Bq&ZKdC8>< zMkl2-G)H$@w5B~n+VrD7`TG>qM4!wl05uNLvLNxu`*O!nYsz%eOO1r9Qd@7OYt}KD zw9?g4O+?h!U~>Xg(19Xg(7{%REsa-P2h#OfX{V)@rD%V1*3Vb9`&CM2BmA}|Q&Ba@ zMjQ$1)YEQtij~o8f1H7gYUibQrgve@R#aho+t$B+{arVod zS8Dgodp{&27G4ynH)D;_YA>&Rt$SFebRQbop^{AwnWY%VO?A*h3p$yplu?R!sZ##Y z1ppIz3CEstbO~V~Fsg}%9cm;Mhz)JzQO6k_1}cLaeE-DZ#JP^2)nGGuH|DzQf+n7+ zW|e1#k!(B7Mk!{5)Rv0uf)zoyAYjI8J79tB#+Jglz!;~SoV9S~jvmYirx}4bSSOh$ zvSiLhctQaoXa+R|f{oz;pcC@g9<>y(q5nsS&x6z=A4~R!r~L7$eVQtvN7$x2 z_0;v3*zWUKfv)cfs`Q~`}jvT zL?DoGlwu%s_(ui`Qh^V2u_WA+7Lh(UMqGsuVjoLi3uCuNHnPtqQaD5*5@3+q7{dYf zJ0S}5C_*&qCmmc6NDu|`0c}WQBN@0w4i}I7AE$B8+!nVr{derN{K9 z7DxPJAIJQMKlXvK4rGHGKNN^3(h)rXQ2&4)l>k63wlR>Bhyef;9LNO?!bLBp@>!2C z!70`0CNrvJhnxbY%xXEdd8%%AZlsA74zUIV(D5DaIKeOLY0tB~lO`R|LPE8$jb&&7 z0EDy#_y!^hbX*bu3z&x`0Duc^3!r@e->bDbweX-`Z_vsLQxp45pa9$)H8 znmhoPG&qQOfFaMBl4zK7`5z&@(SsKh6=P7ihcBX#g=NG81^_UFKTzR>FHD0RTEyHf zpujoLmDHTm!dObhTA`JW#GvZxX_y9jzO)YJmHJeJ01Sex+zGU;ifU5f*bQt$1|V+HK|d}YX6~>)*X0Zim_G}PG5D(S!KCawyIGrE3_eJNw~)d z7~&8(H3(PEW!F~vlwM`6PbOf&3u;={w#tERNHj~bn99_%`1~zQ_XyV<6$Al{aSTse zif}1Lt;6Jn4bCt7Kqha;fG`iA#-EZhc6uB z2;b_!>k*@hg>04|55>gwX7hrc*jnwOk+%8IY}%AbDpUy=7W&gw`PuUn$;|5hrls@ z2RT8q&`Rek_t;i^)^nsmi03*xnw5ZdGNI2bT$L~Y5xGPN{ff)m3B$A0Mz%DiAg!Dx zn1W4`hBZxAO%Ok`5YxT7HLf*%5I7=&0SAG=G2Vd&9G-g7%}O;YAzQ5txi{9&UdgPv zX=nTyd(OMoHMZ}T5}ShhAT}ySKaZ_#oYdMq(hd$MW(#e0rv%+3q4s?lz3p7no7@6{ zD*+DT0OXq5%DYOodjFSAtrf%q7JzJb!aMSAb2H4^q@K679`3rnh!n8J!0rN zZkSLWrtscTC;xO1kv=qhpu6fz&iYJep6?Y$zIPvTOK%%Q?Y->m>%+$T5BVN6Nniyl z@-F-a6F=LoH@-`C@33y^lb;AFywh_p{oQXr%U!S3)jz@gc6;C6;V1w2^AG6oqSpBe zW4pt{KR$B5JBzz&IR&1hKX$V}iHkkVOFrd`z=EKSQLB-rQwh)#yMm%V53xSb;DYS) zf(3lG1}r-8L%|80F*8%Tn1j9yEW1NNHn=ODxjO|Cj5QOKJ@(tb0VEK=vo(ZZv(77* zcQ6L^6TlSIj}F9;4+M=*;JL8EK|Rw!2vk8O145+Z!5@4GLzAC^;I|rzJ|A=^CUmX? ztQHtp1^-q!gDH%(Dug}#t1mg6Lm6W}T{;M^D2DQa!7S85RVqLuaYE2IJw9+lDulnp zGeh%ILJ73IEv!R?Fh6mdD`A_tK72r$P(0=s#LrLyRuF^&I7Bdm!{fWc%EPcsG{s{v zE&nqJI2#6i(>q8k!$1_0PV|fe7z9=zf>HdkQWQU0oW(|T#9|Z(tWX0BB#0Kk9c39t zV&pLz3?D#X1y}IJAp^!9B*SNX#BD?}8IcI^IEcCNib(WEvsy&^z(vpK1D;E#YfQ0h z z!~YGO!O=TNTbVm+EJy~EM{|V6hE&LfyhnmafKSs$g0PWez&(mo#r6xx(iwy7hzsb2b(jZdZ~>0k#NBvFZ5+wsLq7BSHDI&EU_8ejNyp1V!+N>8 zQLxGPx|chk11ETbTF8ei003Vo2Q&BrZO8_rtjZt^Ni3vCe_TOUJgtU+Gh(1bkX%ZD zi^r2wf zg6tcCz`U)~QGiOohb%CIf0!bHC@D&+rt_ z@$60wzyl2+&-7H!^&C(0L{IjF&-e^a_mt22lu!D!&-`3Z{M66>oX_+0&I+I%DAID|xagc;2Q zVVeaabp zgKQ{=4rr5g3=Jr3h2xpjle(8%7y}*Pf?Mzh&oN81%!ajmO

QRBhH#MO8P#O@e>` z#*hV3?MCS6t5j$R5s(K@xYbIn6su!}KIm0nJ;+}m2YgTmYUnDUWCwb1h8JKVSh*%-DX6R?Bc)SAu+prbaGqTsGBU{^a)@P*-M#u`w z1b`Eup=B(Xv9c{)fnId z1jiL0$mLtg9XH9H+_PYS0Sz@mp)$|CS)Mpb+`3y^`NUQzCI8bU9n?)i)=k>loz11t zr$m5AfuI81xx}dzUUbac>dW0qX#k@2-QS&F-~3dO{9NwsUZDuDG&qrJ9S^~6+wa9$ z#TB2gz21!hUcW`(;)TnJ6^Q_#4M&iW&3y-A5LgGKU)_Su^%&XU_yeBPqV{#)?1kR# zonO_xHU}mcgJ}WD;EHx&+ry3DN>ktPxd7`$V2yd-%FSR5X4(A2^1aS3U|0*E~Z`3_2WFI6e9pdQS9R; zhGbQ}<0zKm^Ht+c-U;Sw8I4%s<|SfJCa@ze9SPXQF{orq7G1tJ5~aLTHX z0Vb_uPIlx;du6VX;a0AcKR)9?PF-U@W}jdIwM~dj=n`Sz!$F?n7bfF%($(4$=3&0% z`O0KQL}vJiT`fX$5H;@WbRm04xejAXe(9dfhOUH zo@Ivy>6m!hfuI5gL57NyK`1te+f9xERt_A3}DFIW!~Irp5_VMJORcC zhDT6o9L`~Go(T@{z7G8@edcAG;5;{D0A3=76Ntgboa!aa+j;l} zc~(cJW)y0yyQl8ji-hP>hU;1u=#lWkfd~NcIEEGgYp^zIYK{pRAQ3!{uy}>4Gtg6YNu>w9DG@0RX@e9Ktai06-kYVI0R1hy=O=9{7T;!W_-vs_Pc3Bj7oj z=I#(7W{6|&C(dVmrU_8KOko2CS=8;=_UYZ02}lU+ZU_Z2?SXs{iQfsH3L1#wIiBPx zisfmZDA0!|FbI(ni0pCjlq!I$JLn1T?wg*zZvMO1o=2AUW}7JK6To8iTkoT8@0gGW zUjPGx$bcdDi2ea07>_0a0ssOsApZnXAOI+Za2SPgActRgM{p7daoQp?{UXaUPFEOh zB427Fhskw*>&G7Px#kF^i-0ca>ev+YrS0XF5N?*}p&t??ff%A95{M&8q9qatU$_Tt z7=x&(1}Y*s0KlRH9taf$CCl1fGtl$i^X`@gZ_WPdSkLV`A%Hd$2ngUMV~_#2O!TTw zxtQpOq8tbl=m)ds0r z>E-sf_4AL8Yd{b5nW$@A$Bo%VbP-o{fRqV;5O#rp0ecvUVmc-$QYL0{CTIcxX`&`; z!X{PF2e$YJ&w+Cb!l0A0t^Ye;;&4B=Rxbz}o^@Hja15u32v7u2WA|eK=qYD%TDv(> z5QTm?1(P@VXRsWRKq!S`D2IZmMyDu?!YGYmgMZ*!0O$g1=Wzh=afe5Bo|_MezmE#n zWO#>d$!=)=I)u0?bld>w5NCSGPG6Q7hjH+Sa>)8|2nTAIu9XNXZ5S#GJ*uQys-}7> z1K9iYIv_|Fe zdfCqXl)we0#)a(H{_F?-+nRti1oz(;;HwFCf*|%&R(`8b|8$@JgFp=N=!*W8evzhs z^j8VU2Y_nO|NYnh?!T=&2Z$K}1`;f2@F2p33KueL=)Hmlk2loXN7L&6p$+tT{yN-8)PK9@4})v8YjrNRu)& ziIOQ)s2e**t!nk65>~BDUG3`iE7-7N5l#i*%vnEaXPrG8H?6AEt4qfMm@C$9SiE^} zrnGXX-Me;FBLC|BTG%jOv2inoFj3G1Rk{|-O0FE$!YWq03|Q{$`7`LNWs@cI$Bc9` zU!_pMJt;S_6l~BkSl_R-h9K6r($?eM%g4pRQ&W# zF;?XCB>$CQp-2*o6jjqpLA_uzV~swBHeDWSy7}gTcI0G@PX043nG_7szyed*Gl zDFrI1ln1o{3{dSHqJ{ulRyHU}kX97tL}J*34JxQ$W6v090tshm1O@^ssilJUTs=4d z&#;adI*}L5e6!6jPS}{H zsbk?7MG4hvyKPs`c_T^;@`wSz7wGIc9+&Apnk-ZGL4XNh?*KzZA%|#5EW1V(YizFP za_iiu|Bf}CE1C#=Fv1x<7fC+-P%}^|%*BfCy8Tj2*S-{$=fEY$042;|eyxE(t@);C z@&Co&$$F6jkeqS~BnnI$aKc{2K^-qO>%4PA0KVV_X8?o&g};5Oi|f%yGep28#qdT& z006LX$RWd)jIz-c)3t0wPJ}}bH{8$zP7j_&#&cC8u)<0#`l0?3?}apbHT|GfEM(;WKb+*&mH4@Dee5$}P3%UP_u-2;5Riq4-Z2Xq9E1RBI0P16*S)UaiWER|(8$FKW5^>FPUwT#S`}*@4NLB0YE>DKfQgW~|5dfdy&@f8BVPR22si!X+IMJ}& zkz1=wXb9F8i<~92rBQiKDeR#OOIV^8^e9C{K{`@XqBAN1Ktnr`ae{}?AXrw@DKjgY z&y`)o32ev!00tRQml}j%uy7kyv+5E6Q6d}cU`IA6QA4Iqa;ME?T>nTVA_LjIqm58{ zK)n)&REjFqnPi=a398|be((SQzre**wF-bdPzM&B6D(pYa#E<2^j37O<71)1G{Ce2 z6ATbfN7Ya`i6%9TX_ZK05weVFgsZP?_(ov0N&;4_Vx>V#ENmmPSf+$lWA?mfXEStL zg`9w`!thO9R8&-9jj^XG`$}yMf{rc#KpuVN!SPZ^GuRg3mC%5N|6;3Mhs-u9$^Fe| z`DNU!StS5HY{w-&8r*)t)m}G5t6Ar!Pl$h-^f*SzhK=w+ep9cL^emTRPVO&1gnywf`zA0h9PY(@ml|$BViO zyMziJbB9n4au_C1?WkpC@p0vQSBYpL9n!!@Gr)n4vgudADP4sHN~~mpq=|$BH1INU zOkSQw#R0Nl6zLgn2=&mfBMNgE=VcQW+-@*kmw<$`HI9&b_PF^Rkr%W&Z$xVI1939*_8-9?7M||Smp?g+a$ci&O zI$L_zs>NNBXs%xvykVzsMyTL4!PwR|Fi+p(4Sr+0D#Q{0*az_c;g5YZ&mjKLhA3Rn zqttWLihFQFq@fZ4U<_50$~^tQo^$itka_{B4%vOL6EM9I??Akc!Hpg|_qtd8 zd^@0p`D4qiM(K+z&yuZ^#cMXU^%G5YiZl7bsG7Bn&C-A z0APX-8PkF}-uM;X1iIQow4JsvpEacvD{R0(EC5rSKrxsDJiG%jY#jlHV8CpGIn;t4 z)j~Od!YQyr$a&Yc;oJKi7zaYcvnifPN&n6H;NAvyVAb)SLx3Rk@Lz0cjuK=7FB}$5 zXad>2L(9cr6h=lhh!sIl0zhqop7`JcDq93L;Tk#w;t>;xD31Dxk_6VF9U|Hff{qlz zR-^HOCcpwq8N~^}!xp}v7jDaQ*aN-E2oJzYfu$i3wxRnCVMDZl(;Pz=ikAkmAtf%M zjwO!>T2mmcKrFxl{uu=@5aK`l1TY+;3`RycL=r*VLO5{SInY)fhTrRPmhQQj3uajZ z-Cifk+%7s!E;@vhq1%3K7mkELE*Mr)L_jc*oeTiO^|>OcJjWg2LpS`wFLc8_+yMZ9 z0$`zG`%NMfqGLm>oYu8Y1%wj&dH*6O4r9q-M4Zi8ouS#1O~(>s0w6Ml0+1a@VB;4S z1P|Q8S=@pSFhnVAgFL9iGdux7TtF|Z!#p^H@-4*bF<$E}P)D-f%v}Od00RcP&lL>O zz@;NGLf*k0qe4{LrQJcMZCa5nS)&0$30xO*B?Z~(A3+At9x}u)H3j9N-gg`z-!azX5KhRG?Y^2NWmPZz2S0)4jWF02NBS};M zBCH=*s-ainA|y7%ycI;fmH(wy;m8O)LN1sAQ;^-cy(L^m1|-zOFWf_4g@VN3(Ldmy z8T^9?5JWl9WI)z=s*MfCU6F)a1JMN7Uyqj03K+7aV{rwHfM1nr*b-{bWZ1R zLML@zCv{q9b2^GW=Sdbq1bioX8mD%aCwd0wd8Q|Ot|xn9rw)MSL4cgdkzB*3>D28UJ zhHfZ_cBqGbD2Rrrh>j?UmZ*uID2k@&BOn7Y$wG>TC>$)pA*8{J)~Jo%D30c+j_xRj zdV+i!#L_h#Dm-1()&Jy@Ee{}61=;=QX%a*|EF^*QfW0+@FOb7iH0XmyC_(7v&GDvh zzGri~CzyVxn2u?7Ca0N}XPE{k2*{3Lq$zN|;~_8t2f!(rqN$x;=bGl}a_%Xg24{R; zW<&Jd-vu6LYSpd@k^y*uDKwx>DS#4$IEW^Jnqfoqf;sfnK+I-s4#aJ06c{E*R;#t57)Eg4&3WIUYL$Mf zrBUd^KS&6$s{hGz48SSOgFpC#J>1el_(D9C!3*>&Q~`ieGG#VArL>+SRaU0H6$G|o zB2&yE1$Zm0f-5hQ)Tnwy0$%I_I;wWmDmUo?Dm?YBy-2TiL&(4Y<80S@XQ4{{NH z!d4LQ+5qS(EC85H_`^S7t;s5*WZW#keyZOZP^-aV$Lc?D57REq9X$PU9og$6Qi>N>8h;^EsOL@X8r zE!rZ~3a)?=9RTPmG;nH4m;l+KZs;b(HsbO#S zZq4#;V>fGA4gm=W%&9_;oI0Qg96QgE5I4TSY> zuk7;d;AX@@Cgeh%t5zMrE0Mrx{=@siuM?V_JVr3s1;CZL!_UfuUmyaZ@vrInZ}U3u z17lA4&Qj(QgaQ03Ni4uW9B2dIC-2g(;X*L|R+I(40~%BXja7}7b#OxTZx8eE4{L8h zZ2zQO(k0!N?Cy4)?*f1ouBAnU!9Toa3)}4r3!V(m@H}#mNWMcHLPY{Zrd)Bb5X%@4 zlkpgvG56N)L8Rttwx$$QamV?9-KB5Hx&$@+gMCgh`QEK%#&E(GZj_(_P+)>p3>q5$ zuP!38@~W{x2&jD(C<`YsyeU8eQ%)(KVn&3+Klp+kOLF{Pu^)?FY-oar$bw_yL{aJR zA%8HnvNHTE?~^{Vlp3&LS&`i&0MSF!Ygq86Q zpK(F>a1aA?MpWt}*R2a9-4g#{AYugB38pV^EFYVr{AMvZdxZ+R6QKE2M~zH0EC2El zy7NS=UMUP~u^uZe*WDn<%nOvFPfkP!klm+#GdNc<__gvd|M6Eqz-|}=3^K)V*;q5j zDhRuBJTI@j(yP7VtC0pP5&@B*iAIhbtV1$9 zK^8OvI_N|LY=bnk^+1ThK8!*X)IvUB@{bU7fUVXb9Dq!4!#@zsUT;TVJK$f3D|Ev@ zgeR!OKy-jQqyhzGfG&Uo3Ic!`h{FeDw{7C4Ds;m_xc4ksksb^L8NkA$W!FT&zRcj;;`1pI_Bq_f@N&NX^4as&2_%S2;aMB1$#6aoMWl>dW9Yk@c*AUG7T z36w*pQ20RPgC!6|C_t1!aOnq_glh+wT@Qq>fp|zaged$&beTAGptwWqI6^@4nKSb< zcQ66SPBCm<#!xTwB5dT9b5?K7g$3g8zUXfT&3SJl^!(N% zUHBgG?St?U9{_YfHc-R*)=4@94F%9cB>+G?%z8ikUN490KwS7iP`Q<#-T-J05kNSI zgSbFQgaMG9XnOjIgF5`7w11QOw_61j07Vyzu~B4jO2#*x3;%PDcY9~ZAN|=M{_(jr zI0!+A0y;?50?fmcM*;nvf;?zJZ8pO*5JWb3w~0mib~zsaT)=gKIIu|sb^k-oX*(@( zyD@rui(@qw8%2G;gDkAFOQbSHulTy-_{oR5#v4V?@wqqjK)=3#%s|0C_(Bw9!7{|d znH7Yhi-A6j0u-deYG*jci`W$n#502UyFt@G7`Vk>yu$l6Q#Z8)%Y;I^69b4mNhEWr zw|bpdJ*;;|&y|78_U1sa0XCdvkqA+xthm=$w0y~HM;S1s9AO9^V4n9>;App$4v}0F9Z~)m6 zS>SsHnU{p9+jzTEzEOyz1-Elb7F%EWJTG3sB$aMM%Qzxvd7{GF?k@V8VT4aBAYBSbL6KRh|`2Y=Kj_fn7l*OLSU zIL&=8e??f3M_o0zZ~TA1GV!}f>9f)Xtc?_X__X(PvXY&Dem_6}5IB%vL4yYoCLH+T z-v@;cAw~oc<6jJk7ZWzX(*R?~jv6_76!{S3NQnV}y((@OF?+d*5h6&%nhZjGde0lTYH{kJpo_%}w-_x&u zKYv0AV()^vk59jROhgZO@{KUwnj)}30mb4DJFv7{(7~NXNG`b=R*0oCHz2y@pL`zd z(8KB)EK9+rFu+5JB2Y|G#T8j>(Zv^6RR6+67-_80#uQ~d@x~odOv#unY|N3z7OyyD z5f*MTa498^VzNmD!y56!qe7h0N{En4ZVv!>smzpz2Jq*fTCOb9%&@AA(y*`6D*}i& z;fzzxIq9s^PC13ZLx?;1?9)#;^W5{#L4iQyop;dqGf+b3%t4Vuu9zT6D9duPC`&J; z^eZXPyeZ92&)h>oK>#qNGF}W&sEn;d0M*r3ar$)AHN8qt2oiA3Ro7j4?bX*`cfA3R z8-Oj=*kf}QmRMw&&Ec4LWMNiWW_hhajYHHhLecNLF%b?f=SFY5@j#+JFfzcHn}24d$I;Y>;+Xgo{)pha$GU zt+8-%!Z_n`yDB%|hxYyWx&pFfB@Y9tvg*r(wgN-sm+=kRDUXZ#7vY5i- zOx|f{3Tk_1c85hE1%l#9yFE-}ZaI6}Bbs3@Nam`8dn~y?Cadf+gf{u-9IVL(^=hW5 z_Q__Sd48Dfn~T1A3f3?Y*lmDqK!i3Dl&-iYj!|oRK)?e>EN!ySF1s-z*bSkP%3>)2 zq3IN_+{(m{Ivl69-!3@r&XN6`U>kO z`#N9{3706rLaQD*NJFl8PyZgf-HX!vCeA@eJ$iyg4_KCWj>#e5>U}M8ksWY-9csp; z{@eDpWM9g8n3-2TEI=gWnlh`tCg_5#ZgF3K;@bCVeUqR!z0loFfCEe&&ZgiFL{X1` z$8r>;awR^CkuQA*I$xzKXq5kntbhA+iV`HW3JaLZD$qz3K~S+33V4u(jp-mxHYkz+ z7SLb~q#>}lhb+?J$8$CWmbI{Ty6`P+e7VWsl8%VP3-Swh`g>sujbedSNJt4$fL9po zw-sDKk&A?R;!9%aks035S2-jj3Cw7$>t(Np2Q*g1v=>1lPSA);L`xE%WXGBH%Y9$$ z;!dEF96%VLODZGC@&7LHM@2FSU54XhQ^t74VEIszx=JIk61c!N8to8=0H3ZTXujC# z(JSQ>rDz_RJU=edBukLcAS6ISSny&YTR8<0Q$^=Z^{7`5m@@-V6b z%+E3a5XC>fasN}Ho=YjHY@$;*DoK!b4x}{@1`kPUtfN7&SJ0ehOLv0Ji)eMLST)Hz z&1KV}4kSVn@_{CtvjP>4m8~Faq*1|=)H5#iZ6Jk9JF2iV?&ZyyRsAPRWokiz4wf)r zg_T&_TCzRx0CMv9M>5(PS%e_=A%=yBT**jRwt3W9t??Q6R@b^;S+$yhWeQg#g4)!2 zbtIN`6=laNs^pNWkk{Bs3M89bg1|N*u2l$TZ>ZVNDzjKA8HNy}`YZ3H)UPYOs%e!- z*nq;-gS-`L4cIjTQ$YhC|Hz+i!E0T!(6nZH0wxZL+tKv;%24kZ+Hgyns~tS*3dJHV zMpR1|=>O(1rj9(S^2BS=0{kvHc_0HU=v9sxfH%BvEi8G10^DJ)cdiuPl?{sVj#<=| zk~Wx)8j$O&`*wA|*JN!Gr~Bals?xy>_6hv9Rsq}c0~(reac%=#5Z@+5!UYtrUM;Mv z>lp(H9F8vuR#ymoj`pw5m9EoHjN;#D6cpZ&hdi_~hpOecqKuPJ7VhznYxMNSk>&D0 zc8ri7(=*5uKJu?Ji3X#0w0H-b)tDK5)ev=3x$M*DHLFWa9h;Z5LTOc&s)Y}v-!=u!Z5Ui?ZzZ8*}hFK zZM6Hs>Wn-)qg&ZZDh$GfdF&$|bl5Vu*NqViutFZyh>9$EVG687e4XuH@lt|~?0IiG z$k!`IKSQmnZ8!Fk>gXiX~DF$bNh6 zd4~uyw!*Ga?80lND4yjNx%XQ2-S5E!e9DbwD0jTK>PTiCzwi8Y5;NX3VHdl96LO0& z=zt5i@CO^z4*H0cVk^2>s4HmU98;iM_+1pezerztPA9Y8xT?W@HeC238G^aYQvARj zPe*Ure)iNojNN5i(|`Zy@om6HGg^9dN{C9sC_z9<=@6v5rDgPJL|S5WOQ(Q@bV>*) z=;#on8{OIOy3V;C|No8uIcJaE+>P(!dvEX0=lyyP3k`>o`Do)@^}4-L_*|D}2Y{80 zI7ISBL5NC(uKwH)lGQDmIxHo#^u)JcME+<=oTJdXIEla0Ot^3qx?3JufkJk&Ye6j_ zM%|L?6f3H67g~)_;+rW9M!;QP*0l(vy$2S~e^b)97q#dKcdG+fc9XH<{)V|u3o#x6 zC#GW5rcbCW`0FeI;6iKDUK-5-DraZhs$USPD3BO8-nt7OUHQ$2=z9wLMU1P)N>vt) zP>ApJCXXuU)_GL3t~94^x50wHr2u9fM{Ue{oia&<3MUAzI~j-Wxt5&${cw{S+qNdq zc5k(~!ws1G>*pX8bciGt-6Q6Y{`z;Aphbb1I1G0&l4^Y7cV`djp}WYN8khp<`4uz) z$>#pJa0KV`@ts8elw4e*zKlBpy`337t&iXGxptdabE? z&ube4BcR*dJ&WHrP=nlaRbA>hvMsNNd1|xtyB|~4^U5B3w!NJhwBSDhf+_mOQo^ay zYgwO#V&=$6VnpQQk2w`Ym{s0VC5-k{x6|F?ijvhS;D0joqW3Cbc;gVKqZa>KB(&vbSIOLFJg6cgen zYSc<9J3shS|G@GCFJ_#a8Y1LhMnwFZRJt#1Ly)o$v72}LuwZ8Y#cW1tqd-^VQN%t| zox7A2Z;9*au{R~Br5b}#wd~k91#u#gHPS5JLe}dmpc~3y3;0!OR zeoZ{boALlwhATr2p=}9c(60HLS_H67mGzmC{yCxGbH+_cX;29dm3$cBj5fY62q@EuFwJB|@ivPWJkIcUZf(4l!4ju8;Qv zXsHeeF+8IR|4PN0e5RP%&a ztaR&cH%SFZIl2EbO-a2;+Q?p4j*GBQLv*HsM>UE%6=t~N#xaPd+n6H=FEl66RtNfM|18j!Qdt^&@gv0t>E3up_?rBC z(>(`0LpNtYM}abV3NM>AwF2Ok+*XXBJ`4cnT3{BM8)rca@BUtRh~pF;}mfv~>; zG=S^^I^sgmhXb5qT?jqeTSv@C&)3JO)kjMV_Xv&eYVq2k^|j08YY#DBpM}@a0J10x z-%v5X$c)#4VlSgF{oGKKixhr=m%eXleIwxnk9&M7#C#qB$R45sntcOXF9RAg0(-@R zbQS^!T7!Bsf+oa*4GbVB7tO-7u@4aR#H56MeV{i(5CJhWv_4GS7bd#^)9pob5t8Az zAxN$e>!exY=2p-fkytm0vuexYwIExE2jX8{iPR>LIP!ey?)G4kRO%6<`8noq)z zpT?Jy-HG(`21^f+aRBt@3Kk+{@XCnGb^A4J|FO49tM|M?kfp)vd|zaAtAETD($^O& za;v`;_f;Vwie2=5@AtaMHz4F*aEN%E7HwSfRcw80+{etgUh$wMu}Joo8d(%Q@o&-j zH3LpW)JvNXAlm*N4L}y*aQrpCpF+J%-$|}2Oz*4RE2xRBs1rd3_LaP)&SE>ia`|Zx zqR@lx0CLTI)n6bBBdG}1t`J>{B6_8Vd#?erNX_&+l)ijD^*S-BL@Uj0 zD_w;aN=R6F^7|HW>J|I%7WfMkUN@dOqeN^h3+0*!#X5+k zB=v!kIe7FLc?j_Xd2`wRH%6@ZhQ_d=c7F@w3G3_)E_%yXr{s56F^$?q%1!QOU&^{} zs$3q6BM)7lp=kShnMdVmztRDEQ1ok|OyvbcxP`=+JRs9f0fRs&j0ed0dzB$ff_0ci z>UR&?RUR0N^Tyh{!la|3|Dr z#uf#}wPwjT2x@RIi0ZrI@)A#>ewq4|_A~|afk=9ivW|a8de`-P`3|AP@5Ha$un);H zLqPoXGegFESTU=oi~&7ZfnkQUF7DQx4{*9gCG}c_uQ1U0lz~03r6a?mlAzSv_2vwL zuXEs2Mc!UUOV>GMazAy|b?QA#TAm5F5C=2IO3eeq@dh$>r@`th;{Yhe8(r9o0tUaU zZ#-f3^`*qjmn_w*@}7H^I6?BIA3M=Tc$-afCD_3;z4E}GQ8_q6F)POdI72Fs z_%n*G+j0inN4#T62`(ImfF@qv;k@dMJL*CAu+mB?MI8kBA4$JIW2Cw^rJAauTj5s$ zKJjm*Vj=3vCo|j1ULHB{6k%Lt!CbH|VR~6Edh4WM4CO#;8CE7uBxt9=VLO0%(Gd0` z2xe^h@>Q3{6HER(AVu|O{G8i_mrP21X6A}gFPxaz*ArCaYx4ZM7L49jEuD?93x6R= z7mRxEFQ`y%wM8Du9@yw@DZXfA`WB z!idsYnV~bYZmZibVYE!XR45qriDjEl*@_e{c+`^r3}{_zovEG|Qr+EZn+qeBR-78k zerK~-7qFFP`jeNk+U4&S=J|uoj91ZbjS&5efJFeqj}H3Ja9E1vgqtahhn4ZDw{~T3 z!z|K_gmg}7(@q8bE4*lkUEoLPgCCAJOij-hN-AHHCmj&j=Fg^%gqtn$df!`#h9I$t zM4A^U1u_ndC=W)>gGw<3PcRlZoLA#+eKI-uaQyp3nc z!wU(ki$8NG$7U&N+jy2gLeENVT)GaN{wi($g~u_SdzAs33Y3F?>v5ock${^bxqZd- z-zw=hS~QtaK_lZl5L=w|l7PnC_$wd?(G!YGL@$km!f~WYC?tdM$*~<}a(-jRd+RUb z;~1p^?(mQMKas&O>eLZz}DGl+EA*|eDtf!NN1P>q$T*hrA>DV`}5ySsr{nqm~jdAJ>1G#f2Z#-i@Q^?S&) zFBT?rtzr>6fmvEu@Rrvz$n)8Lgr6sJh+17S(2gv__lN55&^hf+(6GEZTzSM6!^$O| zA1cFIzNXCPtjNfDKij$&R*frSl_)tgux3Vh@fjVJFT-Q~JfqV}gM?8*PtlQ%CWa}% zr9$Pc73ZK2XFB)Z`Ff&k!bXWQ7c}}A#4-R^^_ks=5iV7knfXmkc?Ex(x85nj<5CUM zHrxcym`^rx)y^xHqG2|4RE09U9Xsi=rHfqN7Ec_LK_k#1a0$(P&nS$>p3t!z)J12I zBRRplqZdIaF(CE3nr2h?o@3@-r5)W3d6Cp^C1q`wBq4Wkp|O%7kL zfaoA=00Xvh)GRM`%!{mW#Up;9G#Pt<`W7J0iPVe5uQu=AY7*3#e-by{B)NwoRX@og zs+ISsqZme9|5ZnIN_Pd$Hm?e1RoWN(O9{3?zB|%hd{eBmgWoqwQBvDoIQE9_4aJ(dkn4)R*=|m_;X0?_hi`Hjf%aRRe?%SI{v5-)^Wp5RAa zz>$>^z8nu7JMInuF7Qg>jeQDvzy^;RJd83Qe}G5LBlbo0E2?*hXbwY6if z82%4+k;ypdg;$2c$5AuFrG*TaJ19aYi%iiPClUVu5e)x;o1B$IsM=R_oc>|JsM zD_P925})VWc;{laWAw19+D!7WALIdJR+Ms+FoCW0C@B9yKXNWP%Cp*#_u1~?#+NVF zA^TP@?R6g+(ATFi6L6@!Kt#*US!Q(Zmk5Orj9U<%X87GJ6-hFR)`)*X*=PNkm9!VB z;@1HstiIq^6i&BVnMwzmC#x*r5nexqJ_XVqmg zo4gR|;nlpm{cY@ALrX%OGTUdE?NOCOuJ)+%dqu0AFP-hO(QmACv(>gG{Aa4?%rIx+ zG|l+R{4#WGU=Ql{1zTJ^9v+WQmloltW$`}He8oJ7;QfM|vX0x87PD;wp&yoX-pZ; zw4*o7#24@JDuw7V($9zKcQ(z3E^RnyZG$xd#b_3*9w%MQXwJqCu=xv7wYEZBN*~|r zmO~8zm+jrC*PV)#$Ek{3WIRhFDb1xBUGtB4cZ_oG9@dQL{k9cKdCL=I(Se~>MN zS;#Fv%i0|~HNFVqVO{9lK~$?4WgU4U4P)CeS8*q)#9=^9L2Q|*eSZigbx`EoNlEnbs*?4|q5jGj zq;DxJIfCMs^ntqR&k^lUk4-%Wt2>|38u*LB1yzN{d&7fPGl!^;zhg)8wiO9WFe*(X zcC0!>T-2Jym8y6I~MC2u;?jFE797qsUj1JBkNHLoxW*|Yn}Ae1IS z@!a!7TA6F-L5lvU(Utw`s+TLD=!S}jh01-vO(qT_ z`|{7)Nw-UWE^Ox52h3jXpEOwSjGJi z_$QNGpi~4+b6P6~{{D{m{UUH+FLL*8Tsm%UNjTM$-iET%d7I&@^L(r1Y%bbUj!UAF z@~Tyy!8xb;{mSXX3rhx(Y_j(qOZ^9pT_R(SI*vx`f6duj$nUqQFa*Igm?XecxlIv2 ztyhT;Yd*U1M~AeqSM!uyUfso0JJ3da3;l7WDVKOO6SKUrW{!u(XfRh65EW10Tl$YV z-JUGt*r9e zL~#AAH>t9f2{g%2TY#LL=OzVD!;^d>RwggrOADpPxV@VJ0(`@VyEeU99O!#|krvqW ztI^6wf|3Zg$(z>w;rn+cdXs9O#hAI2Wx3wj`E6bkM2ANC^yk+4Ro#D`e|ylcvUoOscWD{X>;IOdzeD=_bTt&>*N;#1BtC zM6@9Y>m40)hwR(Q&t8&Wv^rcFnA~tPI~r3uv3*#=C|RBuLGs8G-Sm+j^;w5slyf@gmIQbdGTLA8}=xTW@|JM)3J|) z>S%rti@prSuB(~&p*6L*b-lME5hvj!Vvhyz!d4C3zNSV9v_<5sN6nN)Z(W4>8d8)M z>7?$k_-8r>FWZ?{gz12w%8FODW zrl%z)crj++A|^BwKipm`zQoYRkbfPbRxxZ^h0jte9u&1;)$SL^q@x)pp3u!2?L`&C zRUb)PYTm;Wk8IW*KqAF_BSK2!BNmX=JDAq9HcT}3O_az;oF9zen@J4Yj)!=J^F4@Thp3<1CoSxx`P!19XGpo0H#7Ec$>ni@AafC3y32c1*GO}grKDb-lpL^Qr(Q}K zGF~h#<#$`+#9~S&I8xZ*9jOQ4ap40k0t}t_5~ZYsiS)IGY?dDI`kkIld{|iQ*G0#t zBgtg#@mf1!F9;|c8X(Ts_w+|74IK=P=~AMVQxyGQLPmU4c9Z!l6zwY#r~MvLN_hU@ zgc1TWLRmB92j4PXYrdw7PtvyLnFn`prUua2#QM3|j-(*2U(*xtMLD?BSjef>;rhds z;woqpDk#05>ZW92NwCnf2dzx<(b-M3^^xP%4?xiO^4wy&91g?0=kN`MkRUITC8S=Lg`J}m zX$njv3eK!^k0WxI=n&s|18$dce;5_^(iN>e1#ON9jqu_MjiM%vD9CwpkGzW*uF_D3 z1#Ea8=MMP{H~t$6SirRS4_)EUrUd)#VmuMxNETPPJ8CkcbQY%s@v!K*UQv@?NlbE4 zcV@xmoO!UZmpNaUvcEnHp&yBVIeToXRpld}JwGq{By|)du&!{#A=)FBf~3RKH^9)p zql`1HE+J3^M-aNo=F@%~hzZ9=nMW@~;Bd1D(I|ju4bhIZ|ZvQC=ICAbUdZ(NteFG36Lk zhdD+?IKGN<3`1srs3t75kqos9@NDPH^AN5G1K>llA+ZiM+@Up1Llx}JH7nVAQUTy1 zwaSfvcqaNF%bR#`c_rIkz9YEe*dF_e>#^mA+YY%z))LI9)>3Q8r_nOK`QStCSTo0z zE&SrGq3Vj8y2HI{dVc7JKlaBe4}M`&sN_szarGnk--c?~h$qYC)c_V98c*IyyI<6h^BWrA6i)LJl!V))F1^uO12v8X5)+g%A&i3JeDyLHz3Q z6cEEP)x&Y)!wLJtN!7zD2#5+`BrRuH8HLM$8hmd$NRNQf_ly(>j27;XprkRQW$~ld zrlS?(qh+0=HN<0f)i|8Q6pT<(TMLpE6KK{)z}6Up=@D51m~bBs1bGmlVbBQ}2~Gh? zHyV0FoPV%e=3^E6Bf=<< zSi-E>1gGn}&;kHN&!9Zo zq|L%mV;Je5X>9%x2P982DF8JBSOJpB(uJV~$)w=k2~gAw@5IO5vyZ(}oddV;*%?(9 zK7ROloy989x5Ur1+k*!xSSTtanSqnjp-4sn;8)YcKi!?8WuUQ4c<~2|Am9?m!2q|* zQoqcAggn7z9f8htdp^-y$e)b715;FP)Qrr^bTDO2W;yvU+QcKWTl5MBO?HdQWJ)HP zLo9$+33ltm0C3=$HUR+f1*iTC)1NP_GBawXOP>=kjjv5euTZT)>I?BaAHTS)EYy6M z$69>m#bMZ3Iu;bf#?q6`SWqNiQ9xW)!X054kuX`J%s7?D_(;x|CB))!!{?hWlwqJf z-WwY%(?~G+N|3o^l7xcj*(x@C-h2UyCBVBx6X_)5jX}wT0RYyX{(su%(9i#ApR3-D zb0@B?RjiS5ep6EWX2-j3_+yh&d7Y(x+NQ_FQUL0VAlWq`StJJh4kUXo^Jx`9cKQC( z3-irt|IIm*u9B|pAm)$3lbb|>_1D4MQ`y_)gdbyEyNrG;naFq2k#rs&YrHrx4sQwzG=iZn~pHTPnFZlGaz`*~}!Y;FBJB2kgI1*&lWF z92Z1SGV9E|LC?wVPnjQByg5ix+xeEaR`b_*`$O!@#GTf^zp`Wx&wlK7eE1C*KhQM% zeN4Ll<3kHtbA@}j#bEgN^&9LwJN=LOZrk5O(%MacR^RV#uBF5ybm`Hn(W651Lvpg? z<{!s{r0uj?t#m)@*8d(H{XV=9JS=tncI>1hlGt8Ne*7*~;bG@W9`7cPevZe*7pLYH1zmp*QnzDbwcYm%)dZA!JvfLRaA|S9Hgp z-soJ|e7K66x=J{_N+P>{D|G!%>pIQtIwR>itM>Z+)OGIRbv{#V+9kw5QSX5d_qN){E1tilMkHn#G1+ z*7}gNk6bs9!d5EDtjdWT6-QPhiQGDlFWP5bsb^4I4n~M4Zw+LLF>K8(&2DR`TUxwwfLydY0~0o*hu=NbU-}){&2G! zhZOC^>nwTPl!{(-zJahe)hhm79#b}JXRh`;(d}X{npbaIzz;5YkBF^ zZn{7@iOcNUnZsO#UajrQw{xe(dYh?Iv+ox!%k4ggTPxo$-O#;}WZdSy zCe@CdWPZerXdsjO1F%P@yX{EW(cQ!C6#5hqbge?QH||L$d%c6x6KOqJVV4acI#Ff} z><$O9QXWzEq8_yMsxWFMb_jQ06Ru4wLP_ZBKig?OL{hr_)+wV6Z|m7&_EKYY93*zx zKkA197r!Wl_mp!nzb@Y`9ALx z3LjT$B(fc^hcFVZ28j$3Qe!iknhi&hOth%%sCNP#$)${>!yv01*U>mNT+bAOaLD5T zr$p$k^@hjUeQrl{>zmyd#&zWJS0Hw20rD*v5QP=L_j+;P zdrnvD88rgf)C-R14k~DZX%9}X#@UVPpiy>{rsM$TonFpZ?F-9r9^GfkX?^x(H5bN! zhLx7@Zoqq+jOqdCHPWhSBd$2LJs@ZK>)c2KW5=4BCUckea~c5Y*QZ-C0@?CqK!7YX z(;|Gy<-*LKF7I+ROi7{x-VRQA86f1psGKr=gPSFI^GeKUGosX9XR242{Lt12DVv7{UqQG+hY_`nw{c{8iN* z1cGTJ62Oo0YJjO2m8Ma=cW%tT;*JX=)*gBn(RQWs!nsCdJ>P@;Au`JWdGis~0EFha zmy>A)c>t8khvFmPmeFBhu0ZbcG2n2}X`hUWs)tVR6?aq^71^}+98i1Zq+Wz9=xC8# zXgJQx9PX9)hQ7vtd5%*E>4^p|dm+p$^!vwW)-iB+=cx%`d9Si6U9;YjwNVpsaDAj-tMNjqZ{WWUl z69x|oXc9$Aq=Z6AcN7@A#z2zp+TdYoTn4jW5z>pBa#)%O!6<-)$nz-7>8xRx-vfrQ zsT(PPKzJ~*#;TU^Jw=ikDB!WQD!vLng0!5Snrav!*mKOqO26T;{(z0xrcHi&{wN%q z$ri^hh(D|-WB~J`fd=-;G~L4CqQvVILxzK*g2KoNZB`;Pd)a$;ip1dd$j6nh01k*} zd}&vMH5B-1fy?VO=730<$K=#F%Y7_2M?-U{FfNh1B6&OqFbnlgSC}b+VO)H)N==^R z=EZcF+Qp1qy)xtZm1TQ+!6Mo?jO9g9Lc}SNAxc1=FP$Z!-XrQSLC-TkV;&-DK7UDigHVLv z@or1Z59ZP=)Lvb5F?;YBmCiM)-PgvsS1KAr&#=ga$Ll{GY?TD zjZz_kii4Gem-=Ng4pJMd#k6TBt32jpSrSGHYJN*q%PgWWUHmL5cs&A&^h^ct*sMTj z5O(hCp-_Qo+G!CrqsbH=i4_OzB6p-KHqknp9QBZx0>r%-&CuG1#}7;%4~w7zu;UTx z`R~n!S?E=np7VY0%bqjIU1JebmzVoGKNW_0o-5~3rMI3vU-SCB%9n{B@Bl?(gODel zxEd4%5&?R_C3Wst51jJXyi~-xC4pHvnEpoFR`PkHWbiMH9=W;!AmVjX`COQ!rX{qw zAR){6)GC=@eA4dg<@4Dpof8oVhB~8(ec%W zA!suWdP7)8*($0k3C&Pu^Q`9vf#HFl9MNS=9KC=eB}rm!=uJ0CA7JqnqRhk+goExn z=1dVB4qSd?hy!r6wtD>s>uljf_R$Cm#{to=*82CD(P-X~scppFwJn6)J04d>5|9a)E?v(& z)Lo`j=_j0ly!A#wNB}x0MMZ1_7a)<_p%rdCUU(sjdI{eqAjt5a#EFzXE3|*|%l~U| zVpEOBeZtjOkC|HG_;q7;vP`aQgmIpEx$goIZl|a<>+$GD?^Ir3c7BhJcn9f0VQ2_laa5MXB}sl4uS&GX7V?Oc`3Xj7P;dvL#A zeq|HXJ{+!alBd|YM5NdZ4w|DJ;_aUR#bNRZ#c{8k-(`3CKw6);=G%vw9sn>`mAC+3lJp<*e!=fm>1 zj{)~tMY(jqyd2Ne_Djs|b_nJVCImnX2QtDz0@%Z4IIad9&lC=JhC_nj`0;Rp95`V$ zoTw8{JPs#WhLi5Y$?o7#VtH~#c?tn}N@;m24S8x)c^YT==xKJ^czL=UdHNR#FAUkk z{X+Z7<(c>8S?+oV+T>x33Ty%j>_PZAJa|_-QL4ho>5gc}#R#^r2)7=Hr)pz38uxP? zIevk(S`RpIF^U@y?ve>{K!}p!K)R*s*_{=|f)t6W1s|h!CqyjcVF&C-)#P z{6L!G&EdlU)2k>Kj3WCVRHs{Pm_@Iw5I)2U1W*@;sG@OrgyGYQTROqKIAd z?g*z^1HTZ)mmZGZc`?v8_e;EhdN5;d*;izm?Nz$x-

+1lB#*_^i8WO=uZP@PkVP;M?+6rc1Lq%cYS_)dsXA&f76K@8~;rc zSN@wO&YR4^(!^MoIBqP)x7WwA)%Cu{7~z71MP&#a$`>Qk8v2 zWkr2$%|A48b@hK};*zR@|Ioyk_aT^QfAqVEy6l?5!onO>PEKx4c6N4JdRl5qYEn{C zN_-j;iF_AP7#$fG5fSl!T;h;_yTm#bdWPwqSd{qM+xF7NB*8yCFfhp1H}t=X#Eu>@ z2LFh}PPVqTSdsXTq2}GwC$~}(w<7$vJRE;u%zy6D{3VBm8yR9bViOY+0|SHS&!7LB zBYyTwQzoE6RmVU@MditpCyI)Sa5x+*63fWSNlHqJi;F*g{8&^}^xq<}prD|DfB-Kq zFE=+g7Z(=?2M5+A#-hZ`Sd^HF=^vDsmi9j=F*!Lo79u7fC-@Id{1*?;k%)+xnE3xf z6N7MY{zsaaE9U=66KCQ6SDN_2lZgL2OS{!J5yAB>5Q$O-fF^X(RMJQyBHyYKtC+Fx{YGEX#oa`;~~u~wYseH|x?!8)rk z=3}iV^WWRNe*KvE_zz87F?wMV*wzR3qrdkv&h+}EY9e1zOE9?ObWgO%YD)88G%?v< zOd5H2=ROppkoj_|yX*GyXnibS$UVsa;PiNCfh<1+^ZVp_I}d>a+Q|z(XZZZq9_X~J)-#3s*B#WEx_7!V9`BAZ*7j!|l8iVs0Fo24naoj0D(x?s4 zzTo(WCVtXkU-XuXz8_HE>yT6WzM;LKj0JSfToymVn@lKNY&zV|GRC?xEw&mqiP2r0CTjtehlDM=dvn(tnSi$8Kw5J>tgVdmP+~=LK}BClTEN~ zgRAYhQNuEn)QkL>Fw>T5%Tf99$A@O2u<8durIkH&r)QJy+4u7A!4>Cpv)lA79s-Jiy2rSaI1{bjOv|4|rCm?-=g07~Gx$jC>cT1aTF;WUqDO=1D=yxkH5Lu;_>;|c}1f5W_c{sgv zGJesMK70o@T4&V)=F5AO>zrsPg18t4c{;2B^2FofK%M}mTR*iY5rCHPWTauqcKaZ} zQ^O^AAuCb%i+)W|J(z~*GBTty3P$vBn63t*u+&AK$l%QRn_@wxa-LkFxNd;@YIw|i zbjQ{Iwum+Q>9``7CoImH<8DVJ`GvO?Y)~5v*gHz{H}qn@fr9}b{6~D8U%^`MaRR8I zB>o)zlvU~_bYu&?;=i}ks=e)=HS_=sMpJ}Ro-f{K@y2MpyqOK+&nbXIzV*>xPy$9a zRwcm{;`TI}Hd+>8N?8CLfW{df;D}3nfB*rEXQf^ikEQ^iG{dTABu^NrrFGQQs}TU^ z1MxnA&9;vf2dDYs6THvv4{NUP*TAL$B@fnzv|Yrh0Gd}r_bg6ELXn>CQw&JZC^;cu zzt3U%7q7rif34rm57PsBKTCZJMP#*b=M#L~4Ub0=f2j^;(gEh@|v4=uS~6R4cZFv-4gDvtV!nNV<CgS+9#~P7-Z%3^I}e% z>-zlA_ly0jKNnY0z$f@L!%jbN4(HOVg5Ta>W?1LSaO(S3b3e*O+J@07vxMoQPR+N| zG8-RGeh7^UO$hpm+wa^<{Q9UfXWZ6c;vVL)n7LLCb&3_t$$w0qCd)4xdnG6Helxp9 zL!9(OIkkoC|yfu;1U(o<3dVA_2dtz?Yrt|Xwyyz zOtzxJEr<~N-AmHXhdWU;*&?Jqk@3Q6=sTBLbD~v3i@y5Jyhtx7|4+38u2;6K1$5}K zl3k?rawvffK;;4M3|>%97=iW9llwH*iB{SL6z4|~@XvKgI&gWK>$<*XJSKKE$J;fb zwF~o}KN4MYMqGdJu9FVpU8SdRfiW1rAt|K$uV+%jIB1@JwxWcjjA0N1PJ6hFEC8WZ zUK9^NMT+5u5m$qH=rc6%Tc|%rnJ$9Xwe8*xp3m6Z=tr-EuKhF=y3gOnEiYGdiBYH# z5q}TuO0s>EB%&mC8tMmP0#ztKLME)d*rEn(lvl!a>q){j5Zoch-tndASlbs5_mCLM zRH;1aFF=HMsnieo8b%xD{M-%Bva@0m3c#c4@B3|uTAXcf>sxSOcN9P+i13E6_Xo7{3!}AX> z|Ng3X?PYy2d6NE7O8$ZP5XOUi?+VXsoo<0(K=MMK%#6MM0;gAo%6sZI57P|``S}!` zrbGx~$6!tif($%f?)Ou7;>n#T%3XxZ-So@-#eq{lgf_U7U`@xeqabfC*UU>x#&Z8G zU#PLR@uwrMdF-X0A?AP1%j&}ZIWL2Av1pTgf!c(6iX_SF>iGEjFK7gpc~f1oDWi>} z!3d>cW{^GQWu&4cE{^Ylq8ycy;tM5}R3-H}C9N0GHptUfi0r*g=oeo`&P?d6O7MbR za9TPr5>9;RPQYOpg&+Fr$1zY}I9eY;G6eHrwIG?D1`@m_+<~bmToX^+Fic!Us-o8Y6bCc{FE!q9KAZD? zwpjdZ87mJTY2d&}Q9ZFQd7>H`{)2*|A50*b!0+4NgwQ^>aKWkc9WhGBu|FnMx&yf7o!TwEaZ?W`qvNMB4do( z)3W@u%?9tRUObL@p+-$PqfOLtL=1qZrY+diam5kRWe^sCTkt_%Mz)8g=6e2V zZ=MRO7*amcH}IX0c(r68&I3ho8b;W-;H?sDB1nI3q?@0I7W$+Hq(i?&CpU_x*?r9r zdVp7)tP*0B{fIpCp^jBsi3vpYMUZlO41sB%vgx1?l*66u-CVjEzJuGYBhyZ(H(d_Q z4?l<|O?TH*wG^o|6QX68JsI)u6QfMYYI$ zL&CD}PoXC6_$I>oH0YAQ1f{-Vz8vc@Gho_1^)3;bwdi?Wh3 zAvF~gL3z3)D|ZV2M+E`1R{}XV6}f~0IoSeZuk>RADl@YDjV;Q8zLum^W_Z3UCVvGm zI4a8sNJFskq%~B<_VIMyRP{*myrZa&@Z>FZER2;bi^&E=xZ{VzEzZv>pZJ9lu~$K7 z%oF{qxOX{Fqns8qHE2oBpQ9CAG2)(;)x)vX&28Y?Bhos=hb>@qhF6|yU(Pqjw3BaU zB!mGMyfwSol^}V5lRLg@kDc;X?XgP3(`_yMTY2;}2FF1K?Jc+;^ZMyz=$rkQlF#f7L& zzM;~@0(hWpPV3YfG}@ZT&@x2O_Ljd%(WF_C9~kS7uQFZVchu}7RTKC$&FUkE?oAtS zu~VV}up^oDG@1C`yo9~ehxGT&&L7*FtL&P~!9aMi_ig*H)z&vNP2`@S;$$MYU56yK z+bPY{4Q=pC3lcBL$AYoi6!orD^^ajyLKLyMw8?F%zZyPa7(SlT^OH}%Dvs&I&XOK* zOR^{bqX%nYFU!EX9!j-cIDKp->Mq<&MIrz>Qnuai>t^E$!~;1b&gTf_o@4c7POW)bcxZF#-4D_1@GE4VynD#Ld_pv$m@pbkw#Pc7v}C*Ijl7vD!NTxU29=p5@8cJ5aq?pK3#-+$htxjRvUStqZ zXhm=Zhb|mR;gJWKej)HX8n9p-eDyDy*fwa;KIb2r*m-%-^={CeamZ78$lG-2bvKdA@*=!i5MF%%{}Y`sjNh6U9a**P%32nT5gf~elCmr3i#4;VA{O3U}s1byak z{+un{kJX7qs{2v~hVCq380J)i@gnKobS0cYOzT2D5ci^x=N6!R_r- z@l=g|ZI5?AL~z9aY3y$NoM_@IZesk7*QXK>003=7#vPhAel)G=>O>X;CRdl$<&z@D(p~-lb-~F0?(HANr{-N;>yGmkhrR3F|$JZbzp1kc0QZBy$2Qlko>k z%}9J3CEVqV#aF?L^%RTrgyWI-O`Mq)_)NM4)R*4m-z=~ zrR^u(x|D-Gj3@ZUd;eQe*SEp?4+$v7K$o0*2MdzHjYWanad&e~HP3Thpxy^dZD#ZN z6VrqBT_dbZzk5J@GK>=m9JQD~Fi7X}xXX8$(eDK^%g~zd4XddUaNr25K0*5muhHyK zFn2@-Q48M>iTM@Wp~!FT{QHw9~9VoL`u!~v%dGI(#Z;$E?!C1 z&kgof5Vqm<42>g*#_3&UaYYC8{vbdw>I&=Mulzy&CQQVgc-Mk#`3Mht;r<@;Bt5Aq zv+UZJuGy{J?^~?JhN$)b1=v6*zwJ7+5FSDUOakJ-3t*rGbO5!0ZPQ8O0S|lQ+eY3C zedInq(_Eg<+o7?FAOXPj2nO5ZeW5M1fY5Mb<98yaWNPKSl;a{E;yb?Kb*|$ePUm@! z=k6io8=eX8Fbp57-S0!uRx38 z@d@RC?Bv1*g_qyVenPW8-P^9O)DG{uehBnD5HaoUj9U=MQ0!{Xv{H^F3Q)4^&hF06 zpd=1jwtnl;SnO5Lm2WRU)-49BTv@yZ1I9=|7LtNXL{`5pfCRB!TF zulB}Kr&~}E@QwVc|4$QP-y)&^An4u<$Lsu5!~2vU?bUDnUVix#O%Mb?q1@m5p-%hb z%P{5p>gGQ;=)eAePyYY`K;S@v1q~8xfTzJhh7BD)M5qwr#D`lBZ7C?_9We_45-y|| zQe;GsBTY7x@lVD{mMvYf4Dm0-OPV!blFG%#=1!hHef|U*ROnElDOVEpC=n^dk4qmm zb=nYWREATj7PR`a#UVp23c`8^OJLTk1Ib1;T2^hym^0VD9T)-bT)K7b-c_3x>DjV; zsrroyIIvQMDcT&a@E)4mqUc7MIR>quJ^JdPSmr@>Tc&TWjq(e(yYg(vk zlUogmD0t}||F8g$OGdsuS*2&Hmw5|4q4W1};>C?a1ic!yTGl|D|9lR8`PJwY5f=;) z?A;}^)2Vw$n*4ZA-{Wh-Xy(d@dG_ty+ZFE|{NUWo=a0URzkc8REVmYdjUbKMxuCoK z_&e~k-QL@&JO)q7#T8N>q_9E@cZyHC1pn&qv<;oAuBQ-p8nK}O)Ho!uufig!t`c3! z@Is0llo29LT*;+I9e3n$pcqB$&_lXjq>0EPgAB^Zf{r+(kPH-qr?D1?M6#zJdo+kf zEDKU0y(+c@GtBX>B(X~QKGcs&G}D|*$$?Hx(IDAqo3c$aFJ(kvD1#bI&pi8P%!xv^Tu2h5HwU#;nMU-NK12+Cq_kD zmDNP#zXm((koI*6=84RHO6Hf)PMhUNdqUz6LL@K5t4yMAZm&Rpp$jFc5B?E#RffegZyTR z@2b=;8}&m~U)^n0QAc2nLvAhzfnnZ3BX8DA-+kQV03IGtCpcKZDWgsiS>8BrW zlDPJqeg3J21cAUAWuQ9#*`S~aLI6Ld&PBb#7F$F|Uv$zF?Y&Xgb+z+-_%YonZbA|; zD2sQ7VL*5J3vJ&-*5?x$oP!GjDV{(=aE)hxWCPbQ1{lPU3~qD}2H>ED7sfD+|7Z*V z0NB$W_X>iFf0VF<;|o<4T+s{_q|b$58{kMx=RbDEuV*&2NdgFQ2qYZj7w^Et>Hhbw z03zpiYH`Fr_OZl&_+uZS`am_JF+72E;v7>0Km_Pf2>{3f8$SAn7yxj&foRSk-wU7D z#uXt=ywHs$i=nHAI5Qm5ua0jq5*7}z1_T&HBkmxA5O0{5BbMa@RzRc`uyG7403Za` zm_`Q(0t$0@5C999ha~_|i)#!d24MsM*0jd8J*iP#q`=V|RXM6ShGd2YdF7>2Q$$zN z@@z7bzz%z85U}(@Dz?1k98c29p9t=e++YF>lnJUQ+(Q>opu#cM5d#2}|G^)paKaa! zA&%~4j22J$gvU5XE+e#p6<}CpIsrw@U=9+Gz-*g4XE{VYszCraW6aKISVKbo%r1f> zg9%M&t!h?d9qNdN7zI*^Y|P^v%y`1JvK0<)jgwrgSVb$;xlu5&lPU0w=N;!MPy75Y z1BE!m5e{NEIth}WW$`G3LZ+ustb!Gw;%H8F6w|$dw5P&s-AmsIRNnnh3x`lcZE7cs z?fjIaXenf%W-6u^sA3g0&}mjL#M56AwWvZZ=~KTWKM@$>5MIgO{yNfCv6ic3Qx(%6 zR>23Y*7ZSLb*V_hs@J{Ru_YG4h(QAI!yq~ptWfo*sNfo=Agm$~|2Va4WXBZMw;gt@ zmc1-rMdBK?X5=0406|DK>sE3t7EA{a#47wCS=Jf{ulpP=eK5-*ue$Fg*EvYN#3EY1 z>L#(FGA)=|kkKq21L7&yTZ-b;JYYZ3;?j&^msn^Lno((V3M zP!;Y`7*?^0h-%oz{bUn}g{0#h_ckPYTtoj1a)H}rA!h4k|1Xk_=whjw(qtIT-i@V< z*c|&9K?)ABl8=0nT=I}1vJplfA#7!*aF{qS?$Ic0I%PJ8XTku~@|Jm=BoUAJy&^fP z8VGO@2Heh4W4^O*-|FO&!N95|Xmg^0V&+)Nvaf+=F_|4A0+g!sAhO|KE#nMms+f5= zXzr0*_n>G}^MuiLcJ!6!Oy^Cn7$SgW2m+Y;XHGv_(4{4G$%f$AR+pN*r|z|3C4Jyk zYiJ~#We6JfS0GJ$IKOY+RIbSd0ju`G*Vk?du$`S{ET5~}0GJg+2%w$9Hv8KIg!Yy| z-J{`Z6x;6>iMG$3uVE7#(hiYSgA1ZRVldm>#l{np{{gjb9{C}>AAonlmt5t0XSUuS ze)vFQH#>#|02n~D?YvE$ZY&XeM-9MeMHN2s(Q!O=!Cr2}y{++;t3O@uTc01?<8Et)09M5XQFgx%KX;S~yt~piSqTnJc!j@R?w@CT=pEh=WFJJ< z7@xf2pKW;xW8P$dSVbN0lTD(+v>_s;yiMslzzWM}W| z+N+xK#uh#iKg3{$SYXyCZ~9M&&l%&(CJU5FiHJSsPRz1*rV3#`Cw8^H_dK?~`F@InC~48kY;H}vDW z7o%E51h#SN~BOHnC+l(lz5dT^Q|2eQiHWNaIv%MB{!O)8vc@ejZ+bue3LY6Q? z%|OEn*@IR1gEpM9H!MOe%)K0>w}D6iL}0&5+Xxo$KQfFrEUb_}q>vH_FAX5XH~Iu_ zkOz6NhK~V&3ebggn1^I|frUFnL`*y`l*29@2p|)(A@j3WgvHfcz!!qO6zs$ox`R4! z0w<7#e4qjV*adPZgDk)`?V7qtx$B)vz|J{qjA*9D11ArvN4qtc&UrIzu^c^N6Artb3j&r@R z!6I5wyvnTPN~he)t^`Y~RLY>70NK%kqm+$yAcC+g%CBV0 zw{*+5%t|GQDpcSGWrBeeK*?|fotnC-mK2=`pcq;}2P&w^o6JdrC`l9Q1Uzue$Arwt zl+4Mb%*wRP%f!sg)XdG~%+B=8&jiiT6wT2jP03t@Lr4ThpiD+6Kv*cv*M!a3e9ca% zOKoU9z7(4nn6dB!%=C$d|6O26hXeqK)JgE+NuQL%>l`6wmP#O1dOTdMJl*I0oqHk$|j_AMDN0kp^Q(M@V2t zcSMPabhSD3PZ+#NHp#OO^dsxqM_de034;RTgg}Cz14`fmI;e(mKscyN$p*Bk0+>&* zp@lI}0xqBhe<%ZF9EWAB24{Q-c+^OFj7Js~k`^$l&MFA&dxuw8#EjHFf%*qjXb2Km zhfa9U3k91GNG%=M(68YIalnUjh=vg@MO{z_dQb)!c*YfVQLXF8F~p5<+ytEh z2suU7Dn{kg|CGf!l@9?t2(b84Id#>IV=`nY2Ye_8WO$k&B~{RoPgLC~RmId=O+Q71 z4mhYZd^AuiP0*X;&-Yl<3IQ)x5LICv)@V&RNM)ajv@>HB5fs^i859U2xE&jHR#tVh zZ&Wuz1)BxT>DkfIRl%bCWBoigbm4nB|CdP2|Y>#3OI;-Y^r%=*nk^YRZ>F$ z<5*SlSOf*onzh-bu)9U54-l|aa-GmhE_|igR$W<}2mrux zgxuiQcL)YBO;@0;*l{7+3IPJg(om#*p_!$|r~O!vod`*B0m-nNh>b<3r80|ErvnIt zRWMSqbs@6lN3(5OxLt|_Ffpsp9|L^b!rfYN=~^}=F1$@2z2!!}EnCQK2_Q>=sUQNz zKv%ViEUoLbza2vT(LpE(4Ahfsor}H-k%lUpjf{X`-m{4wfEIrXsume<){U)Do{w@ zuvy>uo81;|Uz#|oAnOhyD8S4eU;>`M{2kStlHUInmjLe8I%PTxK8O}rR zW`KmxDUMC%o*>?F9f&gSXCA0nx}yReW)>l5G8@w8jI4Y0;pR%Fzd7C=eqW1inL^y z_6a*KSEl-ff1PVs*6dq*iFMcobSj7qI0caa9O4;lfgl{iK^(qxixY+%KImW;=EH3XiGGRT8J+|Z zh~r5ffmojAc^-k-g?q4uF~AmSxSl8jfbHoXf>_KGs;jRJgs@$19%=6WRBH#G>5(7+ z6j6~2xMA$hZnj3_@okBISjB-rfqp1M145v|UZ4gNhzE+G392Au{0Aoxh^2`r5E2Ob zF77n4Vi!WKRhR|Q?Qa?RZ()n+3l_;@ei8)V2=FcKbv8Ro^oIx+h#0Vkkw~H?njR;D zA}LB#E5afz;-Xa0hk@9De;83Rs-n#)r4@G}xoU+8iSeDv?49oM|L2D8oyY)1@G=ni zA!3N)GB@)}Ug&`cg;3}RQ>gPgUxteji9<@HMQWr+ilj-ZB!R#rO`-#*5r{4b@leVd z$R;JQ=JNDuELO;oFt3pr-&TYMX9jNwdlZ1`-tkS>Zq!XNaEYdEiQ8_(A!X#pb8 zj$w%61s`zXJ@uE62H~s;fYMQ)6o@h~D1=fd0EmHPkOy-BZjz>`ZV7AA@p3R%_6pJT zr7iU@_H=`AYbm&$>jv;)CgGsX>`#mL(AhOsXoh^Q_n;U9|9ZY8TjuU0=5(1Bcx`Wq z14aYJ00ss3-E60LDmIB)$mCiu`I9&KYM%7;ae!lQqlO0x2q%aMC-^y!<7dD5eAjnI zJ_N9+FRaD)eK&OnABk=U0BJz_q(^#{mn<)51ega3f4EivZ~}R#`S88?M8}Xfam%EcRHJg!h=V6$Fd}--w9<t`c0nd7^|FJ`0jCR;l z&(`^b7I~H!f#4Ph6j*t?K3mdYJym(tu+x>+F9CXaF!0I0te72z#FZ5G-i$Ai{(SW&D$& z@FB#A4e&IGXz?P(i4`$&>{w8v$B-E*iYzISq)92k-n|=!#Ux0RG7rX_X%j%rn;{uG zv?)!OL0#2!673k`Ux=bgmonuDXjQ9bCz?{NYV|7CtPs;t0pMwy0ZQGj^30l3Yr?Z= z4XRyBu&rC1C_@tI#j@QYH3DGHjr*~$-?xC*|CY5m#vZj(r>NN*6WHd_q>m?Sjk1cB zD@~L)bMEZ1?<_Uet4fmbbT z(+je0*mybl>@l+Q=r%Q|TGcF<^z7QV-{clb#yT+ozL-nh^D1$y>8-A>+TJ~Fg%>cj zW9dr@p+hf!$Db{H@_R}d$DLNt5qKa(PqpI86bL%_;DM3k(+@NRjq;3n!EqKKQyebk z;fMVh#K0xQu=I-*0BCW@8VJk;Vo@;0D56yZ%A^1!rkDbW0uUNxppOscaam?T8hIpT zFnD1AL0~+Qp?WlGIGmK|RcYma3K4*Y|1c~ClSKdkv~b8FzP)%Qd|3u2<4iV|#KbrB zWRnd&-Y{V#kVtY@!YZnCr6-_)3Tlv>O|hxdp*AIYrkbtw7l0JNur$miE&{;78i#0c z)1v$}8ds+~sb$S)S%l1vdR#x$~tRE$|R)>uDRk0C6*haNmZyN1uJZP zQux9WF_>6j5Eh3JA_1qr8Y=CypJr8PNc3=FP#5#8DjBVx?Xk)q0DKTGy6GCk%elO` z`>wmZvPW%)^eQ!MNciT^9l$DwNS_*M<8nNjMlz}uua%{q>gw6jiJuB>UM_1 zDuUP|mBk%cZl-TXBy(i)|H*)X@CrOE!9oN=1gLSy7DSHRM0RyH&A`py3 z!Xqp0>0?rRa}kjS2tz1BY3y%+N|D1V0MQIrT)~7c)QUMcVGvH7 zLxC9_AC)wSJj#Fo7L!85@gNd_E#!p&H_Rap{o+BVLGOh&89|>!p@|eYv5Hg~g*|Su ziB0H&9;2|~139=R+=&Eh2?+oiB=`m9(5f|N3lpZ&=3F=m9wClAudh@c=E z{^-Y@cu|WI60#&i|0-82V+o;AE>4V&dZZ)cLV!!u2OgL}0C9+@21|8vjJV8YU}*Ue zV?09!^0*Tn#uB6^%90}{$e0Q=fxT*SGds%69UYBn%d1fGL@<+!){bxpLzroSa~!8u zzL^knbO8X*1OOAfHBCQu(<4e-#Ti`D3>fsYpq-It8OfN?W7hJWSqXsG+HnaZ3dU*@ z*ktbyUuAIa#3IX>qjYEHEvP*epIPS>Ei_ETt7tshUbTGp+d6(JUQ zh2tnlllUYcQ=1|yRt1~Ps(NGurbq@+W6(!%@iif@8iFmZ*V$@rf*bd^2RAmsNXl+7 zvN3h7Qivd_cf5iD4{?o76M#6$!uGHHqibjRKrX2AZM1|81wCki2RzV%9-#nZYhem1 zpO(z05UtNJvXC`}jHzHzD(p|gNf_2z=pVOu2slt-Ks^DMuR$ms44PpJ4;Yt_;!tft zHX#n^LbA7J9jr+%V3#%C^tPuSR_PPi90ayRZy} zJb{E5ewtcF!*S!ZEOcjbnIW zwLBKzmIM3Ro3P*)EO`YnN0KG6k&Upq)-_rff@U>~@*Laxw2%=(WFsS)zNhZ&KXpLd z{{XtW+oB||ijR$JGkZh|U22DR!&{Jn9fER|E;GExduxI?;vf6C_dooxj~*e!AJ+)Q z3jo#L&YtuHD{Ns?K+p@A)g@rwCQzCq9)b@-Vva3W2!Ad>m2 z8eiMI&1Hp^TVd8#P{?`(zGNsn6#${#CR6Mp40FGu7Y`@UDf=Pxp^qaK++IprL2l^( zo?M8Su+Ig+Nf2Tmnz~9CcTpM%YIO~quTWft2DaT4A_yZM@py+YKK^s(Y=RuJ=$tIb z;R#c$W6DiQy0Dl2Zj+0|0s{s%=EO8P7B_vj90fPDJJxl+e%1pArwSu3{f;lM|2;a< zSY$yc5e)!r!W&e~#3*2cJe1r978o|)+RW{MX10(IK~L%LnIKy6Z}KOEW{rYi|AF? zEaqL)5dfoMLJHml1t7x6HKHH}qJYFALXen2oY*9G76epB3FscqDaEB}SSNZ0B-8^h z7$YcP$VD*0KfGKS`~wLT#5g?HK}%A-L>Bt^F4L{=n5UL-~m zq!JM0K}Z>uS=l~?n5)qsaW%y{`~x3Nqi1A;YTc6;l!rwa05kNVCE$ZWTtoXA1S(+K zrFFt`1*K39B~ccoQ642yCZ$p?B~vz~Q$8hBMx|8Z!6W#ZJ7mICCS@WX!Xjj)SAHc} zhNW1JOMXT@{NOz?0g73~E{H=<++o?nxUgQZe%`cq+&88V>V_%)+1y_MafhC*+C_uyj=t4QfTq?F@E52evJRz6~<4bWNK}aX`Rp(9kUleMmfBvVu-Gs!Y z8O0^zXwhJN*+RuBg+Bbld7>v}41g)jgFpC#J#>$7t^*msfQjl60PMmz=wUVV;Y08z zjb$f-I;VmLsINsIRk&UR94HjZXn)cuQQ%$B4V};x|J@ow+{|^G9*_$`V1Oo`qK0xt z1W*AOSQ|w64BAx#;D#|+(We8+ucFj z&0XC=$ahYa4$x**_`^SdL6klXj2c**x+$4{V07LnffnfCttn1zXPMTKm_o$m8HDC> zp65MCo=VjMd{{wD0Tr>~Km19ce$1dMgrh#{q4t-J4ro;%K&HH2s-hF5B5D`jgzz0> z@g1LoY^qc_89{`WO6i0R{sWkns>PgYq7^Ek)@ryBgasT6nx?6<6x*y`E06Xl{oDlm z8N~a=AD$*@x4jZUu$nCt1qxgmvm)!ZvLKK~|EkF$fL&0hRkVPZ8B9evYjZ*;oGQcw zRv<52U zsBxv*0RVsktPmUM1T_3ZaL#SG)NR*#|E<+J3L3BkCSXNw&Fs30uD%NH$j*dI`X&Ix zq~ea&Kj8pDXhI!W=}dgXKkS0#(k;>2V&IOcCuKs*yuvOng;=!{;0kTfYVQ0^>Ohfjlj#l320aMh&KX^j!q6_B!Z0}xNU`RoI^umlag(hLpvX-v*4sO3D1aGP?a7J%u zsV!4nnto<)t86c=qHp~L#`FEcvRK6svB)82F4&5!0fP+lDujBnr+dOD{PGo_2*Lvp z#1xRiu$sgNTpDuPudLwjtmZHB&cp>s$}q41R=kn%Qf>F{ukv=_O>n4(f~bh1EbtA$ zs{ldlM%7HftzB~PtavcZ8fple{{#XY%P?p{EtW4Qo$m?*;t-d_6HaNB8lbp7+({7x z44jS;%mgU>15WyI2k-8TJ~0cg1!7UB)dlb{32_VGUkL7)bBuy{0RRf0d9OQ$w-d*va$Mp?Ew>RXZRS9 zMH@j-0zNFjc#H}c{DWN4|H3hFf-WNiGZch1;O;P2@xy%<1q+lBj9*AZ>@yEaG~X>1 zq6HC{NH2tmzPR3AeDXKT9vO>D0#`+wCEh`J0y+@H2c!ckM8F2zLN}l@0F*&EgaAAj z1UZl+0Hne;Km;*Ml^Ig-3hkap!~j4Cbf640Cd;B*T);~BFZV7*7IHHvGh!Pf9VyQQ zr+M1e5kv}%!wg#iI0&6Lhz1>#gJYaDLF9ua6vQXgP&q~%L!j-$Rbp+P&eE1dDExyy z;WVJ=G&QT6RuI6k@E-^(g}t^L?;iDY@^#iFwMoc;vk^p7hrl&F!$xetH5daJh(R)N zgB~eE`)M@*aJ5&1|20oyDOr1)19&PUpmj5B_CtunKU9cYzcpZ^Y7jSTTtCFqZER2z zMaTZ_B}X(*?{r7tuSL|`z3oH3?VGt&Lo|3AL3F}71W*LfLnQ#fI`now*jpz6KuQ+` zOCy9~hQL^NBCr}9S~EgO7{I0V=4tB*T-)~aX+;*W1nV7dQS_`7`ZafkvZQjx2e4er z9mC6ofHh1*2N(n>n8Qjgz&vy{6tJ8r$b%JxqdXTxHQ2L4ytGuwukM|WGIPW_|HGP% zHwCK&JV7t}Oh`e?d@iJS#B7f{uwy)!3;pu`7Q=Vj0X)SjzzV~nHNru} z3tU>v&HRB}e58kbN%-^{jqj_MgnNTL(HHc(%Y=#_h{>;%(lhC%)3id+!aw8#)ziGl z?;X~Qgbxiv2@SH&AAQ;`ea1Wh%NLhI41k}`aNJk@zO(n(`z}$W z|M%ooxkrcqMy2oH2cyAXMA;*$oqJmXF8vU&0iPf1L6muJK0bn2{m5UvO@KJh2R%lZ zyBcu4sVlqZPd*e!{@LDT+W!Ft%=-l+L^%9IHn_fnz&_n~zC{GUu>ixP6T3+?iz37k z=gU6#cfXhq{^)y~Wh}iQKtO2W`a@jW7cl?p13$Ufz1Z7?6~eadTSQ*}-}cA8{_p?# zrpwu{6hLTDwTfUAO|B3&TL6GzLx!9Fm2)_eVnvG=F=o`bkz+@XA3=r`Ig+GC8UJLI z?AQQL1C=iUuyhHNq)eIsq_lf?>7z}M64o5jLeuBXkVTF5Y?)LfQl=SCrhGb;|0=@} z|3XyNx|J(NKm=F)VS*6h6^sA=J?XlZZCkf*F-GO;6fRx2c10op_Rbdpr87TjIkZLs z(WP)3;$^FN@!_{}5l6OoHLGOHmn}vCD@a2wvZN}~LW`MnY15Y>Yh}E4^<2j)F})*3 z1Y~Q9NDdilanrWy*L8mb2kbWW>9>@PCwB{BU_nx3b5X2-mX>ns*Rhi7^<7EFwUSL)7q#Hw;+=u`3CaBJm{#6{IP@6j}60GlEn>|Dl=BG^v82 z>Hevu#T|Ks3&j#e95KkPOl&ANVpzD4K8&z9gb)#cTr$2Py}PW)l78$lq!qR7vLOfr z0ZR^B$ijsbMi>(9p9;Ke(@mPP{7}j%=M1qLNhjgh)*!H`3ch>*&vu6(IbLkDFl z&NnmSl2IP}BZ!q*$ZCcZQVh82A5$Lf)YFX?h3Qb0My)B)iYV+Q06wYAK)s;^z0);W zi9Gc|TW<>WQ->VgHNhdkTBVc#V6 zwmom3y_ZQ)#U=UqZo^{{kL8OR}xWLU!wR z-}$B;*RX?=y7$v_>%A`0Ran6VI#Oo&r<;g5_R?V`#bwywkqG#OuT}BYsD(lRMOd;@ zuMHWok2{69W8;7YD;8p%(dWRMfo75B+7uSGXlO-l=#qEZu{LFlfI4Iglt+H~=zy=r zI%zmj3Yu4}yuQwXbyqoMMugBQ$C$9$)^F&)WVU*17Kqsi(K-XrmN0&|{VY-aZhTK){kmBcZQAG)}dS#lUet}u@yq2qxGkeEaz zE|G~%bm9}2SOYxN0E$(#;uVu9MJi%3iLZFaFnqv8D{9e++9JdbTKGcn;I4kVLm)*y z!3}xH!y0rj7ubY|7$5|zc+$8ODIS+cK|Y0u8!@67{}G8uGA5FdRa_(&ukbH4G}4KW zRAQ41frK2Sk#B8;Vb-4J#*5sc4o+}_Eb>8xUEy$$Oi=*Y*pZGuUg~G9wB_L5NR>lU zl9x=hWG{L7ODmep7r>0-6q#rP_i4cdn{;6(*(g6y#_WI`QOCRv5(kQ&*gF?%UYbSe^=T+GBf;NgXJBJr0r2#OkJ&`eIcOqw&io9>A74=99ypcAl& z0xE$IRc5m?@ugAu;MqrWtx4Up(eHNGW= zMDyoA?S~e$pn@V?n8!ZWQHMJ=)S^>K0z0HZ|BzOEGmt$sDn&4g5si9Oj38y|6P>z5 zFA9SOC2c1XF^PmEsuY_2^yDXBN=|_iGz12nNCcSh1zMnEp`K#pQ9-hSdHe$%lA5I^ zu3!MT?iBz@y~t9Z`q8TfR)Xcl_e1i=@E{@d?>|-YTr2oGfM6qAO{v zjiIK62{O<^i9mow560yzYAd2z*EX@W)2*)g+;N54wo_Y(K&ft@DcQ>YHktv=r9)^j z1|@KT7XB!MW_jw|kcTsi@?EkELgIPh_fXuKD`{1u59(6S7M+#pyc@UT(+I}rdAn4Sh^@oNX{#CH-S zjN7dN5**t^2v^Ok4shbFo5L}WDi5OXo?-OVis4|wNdp!-4wfE zJlJ4`TX5ozrR8ImPLqC??cHXbj1dK(r5gKf2!08o-!zXC$_Ug(2{_%JZT^}0)O~@Xm0$Q#?5fhYn&f=^yL+%{lJQLQbh}Dyx({Knye3#JS zjj)*SLS`A(@Vqx`w0xa_7I{=e|H)wCL#4NQX#ix}x-NdP37jfh+O8G}e|qc_!5k$C zH>S6~t?;5akB-a1f2MR2*hy1#E+Je+IudD3q7lYJ%lo0Ij~HO2)&#kAzw`L-BNAM|Bv)cb-`S2D2Uc5&fWyEa>~LkHdcyA3imvrzakw%8 zE%YFPM)Z*10)SkIA~*TT#XV&gBlsO8C2Urcu1`}N8qs5JHZ{$RKWV2K3TP>Z2R2fI zVCjJ9K{Wc&TMYAGt8>OH|7R+W*ArEC15V;rhj(zHJ@2ib*Z`hDODH_D;*hK z+BdD`fzx0Z@5u5~ZJ-`6%U$N}ra80k-W8nRN9Pr-KsV6xiI3zVzX~Y4;q#spaO*kh znl^B3hB0WS&R|1ps4C^B{_sSn`s!r{a^dza-xSCLEu#R5*uesX)9df>M^C(smw08z z6IL*zPJ6?1Kl8ftKJ!CNeZ)F1&MwIG4kGyqLH@9On{tEemLEKm<^&JQz@Du56>gfNFH;2F?j9X=o_ z@GJcmkquRlCRkAM(C!A2NDd>=*aYtWx{3$)uMel96R+bF3kVAC0WG9qS&U-RI3pE% zWDJ;r3>~2%{{|ox%)uU_!3m&Z6=9+kp%3wpNfJE@-PElXu`v5AuM6L86L--Xo5dHC zM*(g@rYM0bzCsR=kw@r279imtnvo$!VIA;*3z#7s*yJJ_aoiq}^{7Y|r|_Pvu;juK z|G2Q~?2ZGq&I2oI0JZ@w)M4YO0u2FS9<>A?8Dap;!T11R1n!{{;sPC20vq2C2bHb{ zxN)9l;G|f~67vwI$T0)EZ!37wI@IxS8h{dH$`rV5Dl{NWOw1#91SA1~=e(dHsKLGj zQYA}*B^mG)wFn_MN-zq+!Jx_}#c>BA@*&643jvWLw@D220WElen+8uQmogtgOd|mx z8IXY@|0aN}x=slipfCOMF99X_as==|2x=fP6>~8evoRg>F(H#NdjJo5ATllU zGBHyzCo_`tBr`p;2Ivn9E^{&~GctK#2snT+RdY21vjgy;16VUQWm7d>6E}%sItQ>Y6GA_rqp6Bf+r9R5H1yjDd(~w?2;l-L8jyd53n;kwR1bU zvpc=>JHazN#dAE#vpmi7J7o(P&T~A?;7`(EJ>fGx<#Rsivp((fKJha@;d2nbuwH&L zXz0Kn(83$=jV%;lxrV?wQ-mp<5-O$AA@Y)-_7XU8(=ZY9GcoitNi#z^bTlhj;uID1IrC8@ z0S^E|;3QKLN3Rj!u(BXIP1rVy%Q$2qztSb8&LMLV7qfKY&T^baK&H0g=iox@R6zrR z^gcYm3%uYTLct4?008!}AD00jlawp0@(G9rOUp4Qby6a4C=d&1 z0qE-=@Ij{}BOcE*JIKH~|6y&O(H!n!8mm!BU*b;TFi)S#i-2LHw8i?k2=@fFPzhBN zv+hvQvVaEQ6J&}cErTN?)mesfBs_JU-VmLn@9~U@5}PVeZ?P-~byd%iQ<+6a|CvPw z$nYQTVGl#%C|4mVZ`EFMRU~#5oqE-nV6O+(DKrxaRf{zuku_C+Fk5Q|Q6a|wWI?8Q zp|mceKh*GA-DDtN^5__^>8zBCB#@(sRlLkqOOKUH`!A22fcXBw9<0DPma{qSwN3C9 z&p>sf-f0*fp{@7!x+sJa=YYdU(n?C;uYSI_6{Kt{*;}p^b&CrboFH?Z;o`0!Wir;bt%FV(19U7 zARSO40yf|lx`7xQq8fAr0LY<80U#B&0WZnwBziY!$Y3r1VH)-WQjJ$jkQWk3&V1m( z2i~w$y|R%!m+D5gfgM=$w3j9-fg9MwdmSPL#z7Vu!V18lANs)?|K4;WSa+fFfoB=w z6V8D;DfNCk#sft0?-0aR|F=g1*dR$xwqOAk8%Z!S378gG_l#9lMb{{L5~) zt>PMgz#68Z0~`Vr%)!kTU>;1E4CVn8|0d#g*LQa(<8YZ}0AL^( z|DhTRF-3qS5Qa{aQ-qYW@x>hQ(^A=AS%#Hc*%rHYOJ`Y~@lILS!h3s}8<+qF=-Kq1 z;2v}V3aH>1)?wqYSQh9R2FzG3L*WTfAs-6&nOT@wVqhH5LLU;DMHV1Tl#iPg#G6|( z;6(Kfu?Pv=XA3$unC=*e*I9`5IBeayE4+77DOCv=q715G9n>Kj#DF1;fl~RGAt>P+ z@F8d$1)4qO8D&a~wd8Rv8bL7nDqn10A8*sVF}HYiq_yv))0v$iIHijVXqaFf&;lQx zvP(!z5Fp^Fkvf76iAlBbjo0a7zatox=S+oJ``XVWJ(v* zw?}F%3dnjtk~*$`Z7(nZ>7rIj*C2Y&xgllQYbm?3c`~oHWUsNK0Y2*=)S<1~g!DSH zu%|<{g6A6yl4(Nnu*vO zdfgbE?b^EKd%n2_yVrH0wS*4(0WHG8jCTc0|El%B0i41?f^s8!x|rIR#ErcbA%Qbm zvTHkZgV>~R`(Ss41Uma4-Vt5s6~vQ+yt%c&#fYs@T;eFwg{L{1D$=hTA3XI)_SCrxZH~1SEVqgkTItHXe zLR6X|6a+*>L_oTvR8k3np}VBJk?!v9?k-6QK~S36`F?-r**#~^?ml~+GylQdbLPH2 zpZEK9&#oLAMeMF&DiV(&c!XXvi3mJ#SRQ`8_d;*y2SbOfE;iwmq{Xl=LOOxTvf4j=T&Dis zDylC_q^o&WcgVESMY?&iI3?C?C3AYKb3OIA+I@2(u}pL&ux#xW!jLd=>fndyF}36l zU*q(0*BHs~U*sOAF)1g5dap3PGbsxE*}0?*cUAVc2ZU1pOfd~_-2Ij%&)jaeUZl0X zZw-2K)mHV4gQs@nR_FLD!{KDhPGL(KTx!==|Mliw>u$?$)9;qDma>rba=)}CeaxTf zm5XrwGhU;6W!U~~L+bC33X9$E%UoXm)IHa?P2Sl%isIxzxL@P6T>qdweeCh?XX*y9 zLCwykn;LqG9p85NLTIrxu|Q^5AYAr_L|P!LC-lEGv0!!&Qy~TyiU<_U8HnL|-|&s| zXIe-cOk{1{kogCeCU(8L0Y`s;ia++EdAzVsUzDmqMla(aw=Z!71>PZ%P-Q6niabK}2V7z3d`P(~5MAd-YYP$~!?a@U|$;;$- zv|>*p|DL>NJY30G59}Uedi>2m_$S}j$<}ZWy<2U{sUOwjJYD9^?qK3j00WKC6lySOteY2skJ()1F z$1YtP36=~5$u?Fk;13E$F3)foq7=M7q`DmSe@Jt`>t|;`!-(_vegobgXcCzw5~9^# zb0)-y81BWyebnM&i1#s6oJ=N$rYni4bS1n_%uaQgac9dIuq-5TzM3F*x-gV4u2~7P zDrqYKj8W!5F^#u}B#_X3Y+JVTqd~gt1M`$=!9XW2!M607X9BkHC?w zqpcf=$lpw*B@6M)7(7ZWYhbZr{4k{Sx%uBp@aLAR1u;Sf`vVf2mT^*Jzc)cVM*bB; zlE18t#}u#0s$;YVu>(}A#@WWh>fRTP+chM1&)fD$?fSV|7S)CEI|d#Ba0D6!_@J-O>Ee$F>}m*>*!3y*GcRuUl|N z#b$Fzdz*y$nocW+uR!HWvW2>5u^$_uRl08;+}chlSfvkevCa+G8rm1CSI>CuC;eT! z>G-1}78L*b_nc^)+uPCHx3uSaR<#Zy+n>|^e(iU}oYM;;3;S?f_NW<)HP-w}B|onh zHG1~(`!6ijb%e|6#cWEEG+*X4U+X!)Pw~I0-`m|TADHanlbShZ&L3%5FM&(S(*)7| z84`||`~17r|N0G|GG*$OZ*<_=P$VSVl3 zPUaGSo~Lb0u8TicNJyM&sEkfr*G}dyKFu*<2=7YXkRB|;f`zki`=sG*q+JYWC{dw- zawhpr1+tjF3bF=k(ttV`v$?-8P6Pi3{wd~pukTNW1#G@D()^^He)GH~#Wsv9$cy10 z5HAIKjTe1jLjTlGUYtNV{4x=b@l733dMK1M0NBJY1Fv1HeWDL?kLba!Q#eU zhAf9q`cNZ1y*OW871_d_f65{#5w96UF%HcCns%BqEe0gjCKDO&Kj+4C>DF|qj6l_I zDKZ3*#RtjdJ{sP#b*FwDU=}SbO|*d@USFG{W|Kv>mnXlU(;Jalk#>>DEWUzP`-EK) zfAi5o*fD?1_WP;Bj*zja??NWoy-F5oI$X^|`KbV^zj?)j?9I`N!_W91>jzwSw}2Ft zv?!v}-!=S_uB8!b8-V^$o!ry1&q9mudcq4;eV?6+Y`s!UfO>yD(n*x(t;};SjW<=tYtg8Nd(E-V>3i;tg>^t!6@GoxB zL$swj{Ka&WWq0Y1x4cUfS2P`h!)2H{))27QMGum=yrDkk;q)<*uV$MRt^z7CGmgF2 z=&n(a@$!=^X}?ZQMoqnT@n?O9LbhLaaeRoe5|5vC`i<+gOih2yo#U`VCSP^vp#QQX|sJNQ{A{}jPc1a9!3w)SZnTVE@_CgzAzKc6yY)^C!N6SHwe z__d5dGp5-eB$iSj=pk`gsB2 zp23qx^EnkGj?Ec7dy4jp4$W+}t-9O7u&F9gq8$Ur2q^@;rgA&!clmPrHbO6Exf6#io4lm8x@;)tIxKj9pOJnpG)o!K3{^i?d=P#NM)4le zGriU+R(zTIb*@$Kz__$*zWMfYiPHU)lhlrG0??Ugbc+rdoxQiGcm5cj@~3&}$u^&q zW-edxX+x=GfegHCm9X_}f?KlX&Z4^S4ei!o@l8mIzQFvbWWxkp{HPf2fpf~h8av&> zSl`+(xfmQ%qJBG5xQuZeI#(F`Ao9!Ks)~?I@SJgq(gUhMmyU#;+dvHvq;p^SS_z+Z z{E)kn=bP&yTCa715L)5JtM0x-6FE5?%zlLRd1cG|huu^!BiTR3{UqQq>TNy$LE`-B zx7;1Kf8X`qJ#e4eb|K7jU^VyZu=hSZb?4pnd1MD|h(Hji!mllt5T5zP3tQx>KZAj>%5e5k8ei>|R z44=3if7%AVY2ZtY73yu^OR9t~CVgIU1m2PU$J-<}gbdmEI!4Or#5;Wkf-*RQvJ`@H z%!9%Wf^v5;PDfAtF!Jtl3SM(;A3oK&%g?DQyJP%M8KMk zLFy5ZZ6pPg0jw8=AEOFSjX)Tc!LtDTiU@ce4k<)9aMg)I09zfHj;OMMLIiLg;QqH0 za4qaNQTPc*_^Cqp5fxtL1mR^~xZANDHk67XiooHFz`=LgHS z;gNDil5v8ZkRbBFNb3AZ+Wts-tw_qfNZB@=zY5=3Im7AEg!BgAx%cSPMU)6|Fo`in2$iH~Um0mtB92pq69$w~yGFC7yI zHiR}JNLPr$-tUoZD1@mxhmm*^)1Jap(1afXV=eMyt@>j>?!}se34POv2w%iGTEyYM zfP@^!y7tGp?ZtV3<2^a!y(a!7n?E`rDq6n;E0Bb>4^L?C^Ryxf|NY6FQ(j?D#j@g92vNq7j}>r^(c@~pbWPa zoZRXR5>N$oTO{`eCimwj4+bWOwU*M@jrwXAP`&`_bfB0f|5!&ofrzTE&t1F zs`7h3zCfUJzq)?SWO$u(FEU4az|UknN8{Jm*dE&dGzJ^w{#V!pfMc9#1oSQekzxZQ zh(M5{;4uJ@&Y75Pk(if&C`gFG-Whl+lBe^-E^MHNs-EHXe(!>E^n)lO26Dm{@;F`G zxd%i-7RVS4@KY@D=WHN#q_{KuQ2H`Nx&a1uTMnG6X1uhZs6fU5s2JkcP?$EUmttN$ zS1yYpnrES~B`Cj%rbysNzMeor)&Nu)@sPhP_mvI20l-(cf$Ssj0DjzU1Bf~n+(d=` z2i!yuWBYy=sq*Lw3U{u)UL|9FzR7(g}P z9GMw(0lioYhzKYFyHcrhJ@Ar3C5ZZC^o@Pj8g91|B+a+D_i zC_&nnQwLW(SolWH9lSYSMqZvnMp{WKP$_g>0n0$&*;a54R+g$28T=|Yq^y!5srap3 zm7rarJXfjI=pfKju6I=xNrS0|iB(w$SM$48K5?ynb5)sFQK_6%K`U0lrd_S^zUH%2 z)$n9B+_%tRzlMyd<^!$k`@(8t+ENSdqSGLi?W-C$F;d&$+I#yI4)1F{gMFA6GxfS_ z-3RN08*4O`>JYCh;R5xr*Y()8(&(i6c-s2J#d_k%%FC1L(85CWeu?w-H=e@G0IRy% z_^JcJhHRz0+`@)9(Yi0R6}8;80Vj2~WQ`S#*;RuL)r%!R8Y>zW8=n4c*!|Pkwx7`v z+|)%<-l^0)&fV-V(`Yl%G{T+q;uvm##9QZX`Ki>hW!17n+oCuIRz$ZP?zjAQZTU6W za;(()_kGJBtJX`a){8<+>+N;R&3-G+x7K~`Hhl3Gz`6}Tqz(Jf863k&EJYt6$sfqH z-?wh33~8q>YNs7)r$1osX0|A6s`m z4e1mq>J%I5lsM>=f^RC%y{qvCwI?8tOUT$Lhr0q+GqflRyUO*SW@kAU`h8 zQv2uiUQgu?G*6%JLA#GNmL_fwDC!HZue_xJ3tZK!Jy=#Q%F z|42IUL0};J2GcLA$v|1t01xRPpgLG1KFH%V$Xhave7iW zc{A)IFtV&OvYR-PJuzbQXXLnP;t|hSzec$0P!3W zzEcKy)kbS49PLAj*Bb%**9O%`Q4u3aHVokFHpE>Tl*Vn4tz&pK7{H4l-Zp@b^K*U7 znBdV(f}%*4Q1C4S$h74o_wod^oCLG>SQd32u)n?C&uK@)!yjS09!PO-X8fXAm^(N7agPiuruleB}EY~VXcUodG|fWpj!k2A`L zQ>whvAKj+4pnyA3fR{pmU%;$$@ze(>U~xDL5dcQ{r@)b*QC0X3io_WL=+n;_f21^R zo-$vawQ5F0O3dq`A)5y9Wt*ua=!_A)ARm?YYf&m(X#{~M;$c%T^)e+364nF|D540J zM5uBjV2hCuNce+UJ$DnJY(=XHxgXR0Ks0P!`7 z&}Dt4zj=vIV)d`vYJKtQ&EYD*K)huDR&K+0;?EkT3Y|2kgu+%4Dy#oOR{_=a+uK#Z zAfzuZWXOCF`7m@@o08>j?T_0Ac?%)~IbV%MxDil26yYu^9Z+2(OkE?9+~_@AJE33a zNL>W4|BPA&*P;lN%l_kdgCjSIO4g8gnE=W+P?O3|n$q_qO1gjXn>5L3B<)Ze32`K( z7ey5%0c=MEJg|W~SyJv4BVdqrN81$vRhT*wc97y~r?T_q2!ui5zj1;+Q3+7A$e83$ z)NP(5_JoY4Q--7>9AQ8>17^=eat|6At@Hx-uPOm_Jo*(Fcx^$M4g)e(etlQj`|@#5 z9!!}(60HJ`Dc7c~`m`Srwokl{zXjk$y(GLv=A@OuUe)it*~3mFcQTH4dp`Yol6o+B zG(nOP^znY zOgs+WZ(F;D0k?V?Enz1#tq8i`C%{;C(in6r0%DW#<8t7~M}ZS={ga2E6ZuOKf|%&| z{DkDa1ZSE=@m0*UWa%HC&nI0HXW((1<+b&w6yk++gt*8tE8`Cisg2i+XO#MX0h_;C zm_uS)NEZ=c00-DtAL?m^8NQ%8!P)U?PrKvHaBT4ku!2im?Utf{jrNi$Gw%r8g zjgH|c-Tl6FN+Nxn^ajdt3F0vuGEznl0-KA#v;ZhStRIC-iu4~d$T&TQub`I5%b>ne zf512}Gd)5K|3k<1%Yf1gFw<4`=PL~Q3VZ@C7`*}u5MQoA9gqa$YtUEVY&cCu9p=yjIIZCe_m(dIC!nWR1ZAEs=rvJ_G6as5%? zZt64Uww3YbR~mu{Q>+X_tUbp;YVI)pUo>$5DSgicI{{O%71`rY>UB!VkT53J0pVWX zwW{~bZ$*dRLDzY$xJ}uLhm%CUDo+3Vy!xn$NM4v4yYh|?REOXqPs2gdoXbZ9!8uowrxle5h)5V2wtXA_&c(gheYE&#wfy?*n9Vc~OqL zrx8eioJLxX?4=wjTICKWFx_69^fR^3Kv`iEEhXLwKZBC`Zr43AkzT+{rD(H{CC+3* ziY^Ug&`YY+l+$s3l|X=2uaZ^(;~A?X`e>%D1bY#Kpf%<537se;*GMEQ6E!$9QWnP* z)P}Yrn6LqK2W)X)dr6jUsBxEx^bo@$Z3ENaOHT8ryh706(_vuFv~6@n0MU9XFC}DD z`jcEVKi56}>P$NA)bz7=29?ay>gxCHm@9nQ^8Cqx_%m!}TyU;0cXI4kwd07$e^G!Vk&z{E`_g5dT8n%}k!@!F(+i55r+nQ!vQ@U>@;0Mzl6R*;=48A@;gMB*M%l!(Ksxzf??T9ozxc#Mu zVKfE|fPDU5iA;g~ql;H=J?KfyowOfFlpk$w_4b0tNg9}gdtCk0=je+Jw>=0)3OMzM z{E-ebzEEWHk|m<9@C>&pdnG|LltzTJCXHB#!1%DqWf1Fj2RmlVQp@53lm)io&&U1! z=vatgvVE=esrrgJb_>8vd*M3x+#*DWY@+bne2yYe>CaAN59GhBXu!+e7`b!0c=W5@hvQ1cd zonI)MsYNAiny^b;zEJg3i_T&(<$UR^sGh49Q)pt!t$V4c*`pR)nQhAZ(OF4nTP?0} z)0EHcQpteeO?)SdnLwzsvI*Opgh3OtM-TduAD+KSoXj?R>>Eh@lnF#|uhQ&k^W{q$ zzemw?_dbXWJF7V4R*Df&`3fJDhbkaJPtP$CJ#0;&z)x!rJ`%5YVd7)%3BS&y`Pb%0 z-i8i!7Vp#`-S3fT$`EjTuAWJrV=nk|94gB1Nq&w_$7XK}6{C$`=3AeMuWCG2@p5W(9#S=It>c2qbIE}HVW2z6tuL&z$^ zhhkZiNQ4x3%)`M88H1dyL4m^Vtt+TMW3|#6cF|DOHe;|#k(U)Rap;7S8MoSO;Z zmn>Zcjh=f_Z72lmd;$3{08M!J8eX&Vlg`}K+L-=YQ_64MQ#qZ79EJPNd1AW6uDej? z-<4WNci=<44Y^RgW4MxfESTBby2VQOT6?Z%8;|$B!W-;DN}h%_Q*IfRzN~BdIIN@! z#Mx_R?5eZL_O6~b(pLq$_o{l(l~rYf%i4DmPO6ZTtuiO4NNyD9?8JnBuanD0iwM2` zyoe#g2A5Lwb^BJ&yOvYO13+dy^jq>zYU2oQ;oZwX4+Cf#^1w)jEh5D6=4YDQV?K-h zs!7TMZ<>ho&%W3%Q*WXd9o4ptzr>9p@C_HDjHR6k@Qv>M(CjX0ekO8+6ZWRaw);`; z2`?V*{}0mh7JDu+H}<^1Q%8p66J`6Z3Z;^XK^b z&lZ-Lx;tIPVxCyZ^Xz|No;N2uSj-bEd0rlE-~OIGIsX0o82kDC`{?NE;OF(u=H0K} z>#g>~!^2;{e*F*TxxKSHFLN*wY9bNbMq(mtpEIZyE=NinunPly_?R#43!)X zeaB3of39z={uk|BURn7M+PSbeKR-V^H@CIWzdqB1r8}o)W~Qg6v0&%Q=-lR5^Z5Aq z@bECEziMwF>a;&%yC>wXrS7)p!>=yiU!6X?-M%LsE;se|nC9nqHG(4pz4Prqwi@i0 zn_b3hvp4F$EY#Ta_V#skb+xy*x3;!6V^3XEO-*f8Rn^~$=Mxpq6BS=;DypZ-zl@cC z+bs(Fmli!z_HDHE%V>$?P_g4s!KZ-&+kt$SfqWZGu`H&T3X=!Mo}Kb7!hWN2*0vs%b+~U`LW!XM$;WoJmWZ zNn5;b8TJ%ZV8PF#qN2RKyxg4J%#5tGw6q_I1t}>hSlAO2;(+mkEeA_sf&h#M4weeO z^#JN3t?T_z-6299etfYpv5DcSF@9NbzVT=FTL1K4*4POa=yB%0&_Uj7~)9`4>Q9^d?(o!!2Cag}u~!E&I&?p4BWHSYFawzdwRKYzAzNU^te z2sMiRVCAG?pJi-ptgo-HqobpxrFEtx8?Tae^@Q(+4T+(mz(64v^3 zUcA7%pE5Es|1m$s#YIF!{s;Wz1nYQQznss24P9htvCa}c~e3w2jq5wd2T*if>{Bz8E()0z?5WrF0IUzvvIAI)Cvg^ zRZ%^9?=5Au6$Ju83rN9kX2?U)p8y|{X)ilk!*VYtn(M@eEdI-{y&vh81DtvBE&M3! zZ)|Y|1x~4Rzk-xkFtuF9?!;YQBz2i5qtu~n>KvgZMBd7!T@+SD{*RtF$Pj#bvY11_ zYrb|+HDw1bu9`M0!zJTOzbf!p^`hNR`MFJ960xK4&PuvB+5T5K-Yu~abqDAXZqvnf zVQEMoI2s`1R)2>A(;PjuX@B>Tgx$E(<$Xy#yp!0l6Si|sNhU6hj=($Gttf3`q-YD_ zPd%{u)6b#Lnh8=cLGrhgGBmv-P*4D9yCFZ6vPT@B^E?a@XFq@Ut_hh9mU{GUC^f7d zmh@**63>xHOE}yrd}uZ@Zx{nujtQ3E9tUYgtDNAX(GOitf(;;9RHVlM zxjDAw0FZxV_qSbT*PHegzqeQ&4wSWsi7^qO@Tkp@fN2ev5zZ69c6<`Ze8bEjQnW(y z&z1x!?0KJV4G^mFI6%V(?wZS_n|b2uMx^W0_0a)Pe_3%M(VOuyzxh`K{NM|Ac@lm@mv>DXtBmpoHR&&!4ZZ~d7F!3HM8 z8ZdxjBK%QX<#2PrAiet=Av=Lxh&e72XE{Lr3Chq5nhHyzQr=jLt{V@-HffT~tvt1o zY59>*DQlJ&$3Ndc5ldzgY#frW+^G3nXQndrxNk@JVy`Caz9A8c-iri4Oi=)+42UBK zK%h#X7m-CT4YWPxOBjFoWin~Ki$UYBjHip{1Hui52#()h)L^UzCUG|T+FII85H=s$ zfyxg=jstH1#5$uH`o$wcTv!f_1!unwA4s%)U2ya=YksgmBdO|bkxvK1j4(=b|II{n zOpNTy_l0Kf=4UqPN|D1vgb2;_LcMKuWL6wZ|gFZiUSY|MdD4u@?|_9T;{xqCw()w%NjExaYh@d+!>urAFNzEII;CtgK@0{jmW~)>xY^Zkq56s z0XZtE8DHdYCv`t|lZ&3CMH_2L9Y%&;mM%6GeqoWs4d%&BoH5^L?1thRjjySCRm1EY z`JCpCXI@E3`hg=X)QnCL_2th~U%=@gGnCLNQ{5OfQV924Z0Lsc{YlzSivw|2XW^ITuax?>EToI%pU8 zFLTSEcTX=$Kau{$6ZP=vbr%OgWtFj)r`kn5T87P{^fW5igUAxU7r8DPhU4X#jzf21 zK*(RT>+^Zdn7$6Fz&79sx9ihjY7JARQCB>07qgu1X%w6R>5-fDcFhy|*96=jG4)&2 z8cP0m_G7e(Nif}*&P!Y7$qW)Cl-!vH*vLpa34k6&cT(YEE&;LB4A6p?4AOLs@L|L; zi5m~jYS#9+mT#nn$Muq8&vtNyR_J~2PSCpi*Ne^{ZWal2>4>`LI5n(vOt54;XhZZ@ zNxeTLwh$BO*)9NRp1_o_oetNaHWos%FrzE39r1yK(H&S$`ft;be_bPE_(l#}91`pE zGiJq1&&lcHI~XR34Awr78J`Kus%kM3aV#()jK6g*f!uqZIldilD~LlP*826$AgqUW zaYuQhk;{KOjCBP^opE}%!Z~@Jls_!|E5XHHAlN`%hon!`SHs!*3@iKa(D=VJ*?_6B z@RuxTg4K&&HUKr`$$|3`80$U5?;swalnc;hlE6eqtP@jY-`xmlOK52S9y>2i#r} zP29Fz_|CSjpX)cssG)-L@EE5^H}DSm_3NkH84<9>boyEZ{DvRC94kM~j+pfa&DXja z@3^J2yV&@<)AeZpI~s)T(mI}cNER6u6B&+d8J;gPwUf@_DeRhg)o(tt zyVGCz{>pZLcVcK!_57i#HuCJbt&qH7j41i z^_qHGNj`)DZvmoYj9Gwd1-2^KsWFSg?p^YM1-X$q`R^SqUlG^$^Zv_w{;Tsbc+xoT zK*D`MtexGmb^gICBu~&xDp4Zhw-)({g=xhP)4o8D&=*M;mytx{c-Te6e`QHcFBo_8 z`6T9nQm8; zNqmw3ii{7iNFAaI9T9din*Z?kI1LE;9wUI)B2v5`KM;t#7Aj}yUO?x%S~(vNs)Oxz1{lW1}X%JI={gb|N%k`wcA2RI%W zSUTh6vv4tE$oR`CAGx?7h#w@OY4YyV1mJt(cmPCY5xF^*u|Eblc7=WvC8qb|@(-!; zTG;UpT@?+}@D3I5E(vNGE9TZKX5f;hzHhVe56bIE%nDw35TB6W%M~3?#+hAFl2E~U za8+{5#hFP~8fC;aLmXRMP^jz=xC2D?fEM)lM|6H(=mwDck6>pZRU5b1yn_vLU8cWL zHsq2Xu$5BhQcNL=pc=q$<od= z4HeSCh3N};tpz4pN(^sYc|Oxro9xpY?q_l?X1o)tTI2fYeMLycU#YJY{nAzU6$xu9 z8X~J&v#VWOqg^dGSo4v)E{Zz!ExKwN1zZtVywT?A9;m%>s!3ePx8$y(YOH(NTZoRp zHUCv@Z&l+iCh}91HMAf+!Yb%HcSiL4RI38-;{Ap~F`uOdVCL9>XRvBv*W~Ns12%q0 z#~A*P;D!uWltMv#sZ~>XaA+LuclcN-7rHJexc+fcV@pk=1t+A3rb%_?GUIDN* zgUqeq3ba_=;C213l9Nyn9=U2`LvGugKx?R4>%M*2Rg$5GzoQo}?o|XB_ciEkUON6w zQCO3)DZg!bjXPWVKCIS1lbx-WGdxdL_))CMRd zcPTb?DKB-YgmlpufN74q)OETw4!T~8cfV`u#s=WEmbwj=y7lRLOsu<&b$ZMXy48|< ztc$v|4gej1NTLlGAG7#~4P0PVPY8$=!bd?TC>mne`R-5Kd>yJv=-@T>v8QbfTa&g9w{}GP=R2 z8?YNs%?xed4{kKbNy;yzFG#$LQMF6HsP}DhZA=q?Mbewc46z`+$ib1#!q4;mrvM*$q%yYezx==B5H7>Gp~Enxdqp zH$TR4Km~6B;6BQ1KbV24nS;eN?CA$ z<5HRU7B=0n?(Y-yY7IQi8V#GxzxmEWmxaWe@HNOX-(%D%4#&sbU_8tIGg?WZ>~>l?)+-zq;d3Uya|oQ!_COp?4Q5M zoc%I5tHF%Z&JTHFHXrOaFYnTn5IRX)Jn!MkNX11IYce}CH|K^sbLKjzu10W<7ByXmS`K@Q=3^|U9kh+hHEu~A*A(jis2vK?Czx1 zRkum_r_sOT9d0%_LnoSaG;3kY%N#G4)Qw!g?#3jNh%<>*=*Zed=!X86<&cvKyCymq zpqoR#@=;`MubwZKe1mvo-LiPqdU!*sWWC(5il~fE!3vsPureYoDRc}uLcuqW7cR)= z8N8-Mk8~f5=&_ej}(_h zV!u~f2tNak$AjoqJ+duXm|*CeV%XI_I*PqJ;x5^9IjN!IM+iX7<5jrLqXh6XV4t3T zIcPih)pA6=bablnb4+)ih>l@N5~1sMcvSy!?06TjIRd2#Dz6denH(EZ?Y~GohO{21 zx=l|Q{>EEhBuze?3q_ce!5jENNf>@O#cuDg9xKcKNxsi9*{f>Q(bfYvEf(_(e+E7J zbeOA+utLEuRAKq4N1Q)F_LY^Q;m^e3N83ujQTl&IJpbU50x!Otv8L{bSNuX68NMx5 zeAoIrY54EY+kgE6XFvpAL=KUW$A(Gk12YU$aYVR9>nT!y(K>BWd-WgNXS&b(lX&Ch z(~|!@KeM|2W|Blf9PiFGFc)m@=f^8MCl7yX!pZHhe~D)u%`#b5hyDt5k|3!K-$eBlYvJ!ylC51R}5lB)HSheygVOxhELc-ml zk91QZ;_=-yGC^%iF_uv3=6XzR8{4uJ4_12fX6JvAp604i9R8n7oTjoAa+so?yzINj zC6oV#MB}y|e=OEZ{Xi=TU6u9L_ftcP?G=g06eogwp z8zl!_axgPo_}o*KaSsF!=9-cc+1!NekJIo!xiF{dT-t3jc;dy-3tf%wNfy38m-u@n z-|ayKPd5Injb1ih{q*Cq>2hR!-=cwLX7Kjg)!&nX-cNVccPlq|A7)`~xnte|HD0)F z3R!;+m{r+s4&LWW5WT@#S$f~%`DLL`r}m^%X^OyI33AbaU1a#m&}Xp?o#}<8TvUBs zu_i42vM{Fa$Ik=8Cd=g+J?Q$LrV)=3 z0oy^Z2?bdkzFw9|2`1SpwFaU5_m89q77zLr?gJ-T&%8bjh9X(z7fv%C^&V6x13Xl+ z_|h2ovwKxi@;;A7o`3yipD)jpa_=RNDKVM^Wy#IabaGZSHBn8mEI0;!JJzA%ua?gm zDW~sSEyR0G9FwcS)bKY$$FcZtm(u&hNjNb~`M5yOjoxua6JPMY3~x5oKPG<5gd9)P z((W2T)6#FJvpC_V7VmyEy^LI9e|*@EEG_aRRkycrJ7-sm8Q4lQ1~k{H?02pg*-9Np)a;^)=2L&=nS{G84c z;}zda#iF?`5B29_h?-Ux#gd*hwXF4v4P7~0rZE;@q7QvQs9EGao5^9#S}FBKk&4xg zH9DcD`r35mKcuID9{ixTKo36v8RbTdFo$~3;QA$drmve>#V@^QCJJB}lO_&0OMe0? ze9Hj<*bH_`f+*%yP!GhuyYb8x%K(-c!`ZpOR2e zIG0YqyKg57gz96n2U@^%=vN!#OT63Kkv;bVZ1|r=<1ttQ#`0?ZQh(RuzR~}?`Uqv1 zz4_akHhzaMiedyJOT6gPX{b+@F%dbjmnU-Mn-KsICXb-V`$>tX)gf{<9*(iQF+iG` z6H49Tgpm<#($!P-(cDFPdZE_v_=Ey4VxtHw6guA%B78Y*fJpVR4XYD8<~bT7ar_Z; zkDsE8q>)6Fe9OE$S84w56Xe#NY8;r||I8le3>l84V{m7=VB4cnPPLgZRBVX=#vsymQj>00)X82|x>U2t-ic zWI=$urL8J|M9Dlm;K|?3Ch>>fQlm=wU^7N^uXott%PC)VCYli_m-TMzU?>kDW*vV) z5%O!($&ke#p~F9^L4m{Ai}E5%#R;bb0O;KsK51%Os6$zVWe*4LOjT@z-}jzaSicu1 zE>0x=89zQn_pf;EM77XAFLE>vIOO@}rEKh^0fKh&`*pv@^Q~jpdd2V~&ha zeLp0ACfK$wi++K_tFtE(?x4)`?Ud7t*BZNlAMFLlZ0Nk@<%)beaMxE1Hre-RAnq^q zax4;RM=L<9#ZDqV&q-l+emp7Qg`?L*hcBrCx5D{dVD1wiz&pOsix zsUYAA&(``KzH|*7mMGtojr4ZvPNrr((YxX1 z09z3>6r=lK6Y^+(9l$sQu#E_Ou)&2B@4<0|c@;9q8pT1)Lc{MZ@I6Cjb8G5C&@%ov z)LwYu?cWYc8G=glJRS=MHTw>LGl_{hq9*)=Z^GL{!i zCJ2H@pJ>fwRzLLoOuI$q|9b{ojn_8!r$$9Ln2|R zWtjLf*vuh__m)>Z?F&m?)FEoy3|`G}Ii#5J$W~}M+5h=HW(r}SLIsI~sfU*{te+m6 zg%AIV;X$E6EQdd=n=Lcx5|tZANWc#b{iG?#n7Q)sc}-B(cD1uppR{YrX%Efc{s1Mr zX|_qT*`V-Wx-M^zP}H2rv~){?@YHO!Wicj9^LCWqMrL~SD`MO}3%z+i&IR66ASGk4 zL_HaSc-XXrYo#$ymHl{}QOpC8v`Y^W`OeukXI%V zb)CDv+f__Ouf&L!%=#FGUJH%&n%>&c-IKY_>NInAgDT9PV9^Wb`5&r^_pB>dQKDj(9`Gw@detn z&HBol2dY75(hoQKLu*#H9SOg0|Nes^uxRosc<&d$x2@)~aSc9a7Q4#-sQ<*D1oZVI zTVKNh>-qNT-I?h`v#y|lcla4Kv#AX}d61O*G`&<(zx?^ae94_B9r6?5YyLwk{oB-~ zWTE+YupiGze}9%rx%nw2erA=lCEKuVpD9TsOj+({pD6V&t8u@vrqMfsIwHphiKhF` z;ZNm#bJYripm3F2yGcsxU4fS}M7Wy#Ga`-5N)$w(d*Gt*cM*O$c0{~uco?yO2Sl~D z`zSz2>b|lBMYhxyUOUcNKt+YH7ZLmmjttIOJodKsrjo>cG0-!qh=HdCPS=6Zk(e=V z9s4dk-$_KUn9KZ4hVqPzvxo%4nwN2Z46H#a!owoT>wuaimyXG*!Q+0ISLnBA)h5;? z6ngrAXkJ9us0gAQz;+?R7tuM9C5uvTcxWQdryTIuTO6Q~-F(z}hVGz!-PthK;BFs4 z$btW+uFH$4@i|Mge6*Z+k*t{YGf%XTibw!wVw2#KOs1@CBdy$ZyeADAZoqD1t5QG& z`Qx|uL^ZOzG<90v@wEA%AN$1D)`_*gOa@=mhQ2By8F3{VCHIvO51`uhH5}tMp%XPt z?sA}$wz?PN)0d5-NVJkca97x)BQ7i56#1wQ^z>T*KG5>P$S;|{*Zx4Rl(+-GTz<-4 z##cGut5S#OF<_P6Q!LiF9}t|4sOda-9!V2`|v=S%wbm0KHycEFOgFK$vt0Mbb#C%Dpg20P3}pCkZ8FM(pyvDRFtSUy{cTf&x)rH8aQw| zC*tW4Kzm%}ACGGp$yUnpw9NW>l+dFJlL7DeZl7afVQ!`GQ_sFlk-m!{c%2*wYNJwI z8?-wej8gAS11V}cw8Vl+IgthMoaauxt6pnTAs0|$e(*-gH3RW(J! zuCDUtQJJL%s2cSljH{1gqE7_wT)h%H;2x1rz6%i_Q7s$#<#Qu^y8wSDz(40Z+SrEB zxzCRR`|A%GS~XEvy!X<}>8VRqXo8je36I$PP{ic7U{xO?ILEVHF(U47BS>xU$4Fe} z3w$?KT)^DV5#`Me5Zdgj{Hv-RHjzAry!xWl@57%T)cBIX5drc=oa>O#<}txH#NPDb z2ITpu@A?`yjb1qWzXEXF`aqr>ULG9sKF1^J*<&ZkuUA2Ugj@if>Hxvp|AVQwerxh^ zv?$2zb=up7V1cO_S`z zREp*`FAWVbx5hdhn(Fx z0KEfJ=6!)) zk_Hfj>>-MdK9T~tJ=KAz}Ceok!2E&IHuxnNfba4HO)HO z|K^*U7>>VYD_N|sk*~G^;^ii5`c|19Crhp)!Z35};$OR9#-3u+NoYZhNHl*%fhgwt z>fCqyblT@ldmrOA4d5|QAuqnj1 zAA7p`^@qEXgXFfYbfB(Y2Z7g#29DK{y-UHvAt~CLzymrmvzEhwc!Eao&qkoN7!n-< z5M;GY8Vbwm&2NV%v+Z>71#R1#uRMO@1hkdtr_ZMKkfP&P^W$(7BY|?>Fu;O)nma+{oNu_ zRvC?FZLK)Ma8t3ZJ?O%=usycmk^>l0#AXu7Ranc-iS4)?IvYM%K`<%Q7oQaOr@P&> zZ72NQ6!CRt>LObH1~Qx>2Zc+}+)bE6roA1vx)>g3!T_`$Zb-E2qbIx9MQ)U2?lL>> z#ZVUwssv+`G&aLg{N&Z9lp&fO z@mPH8o2xu-_Fwic zu^wH8*mpj)e`w9lDGw@NdM%Xf=aG50`K6rZ$koCePWksV{5+(ZJx%)dNdr+<*zTmg zt^?)!1tp~Ar&k+?7qgaE5!unp3imS#!f5R`-#d50*lGfQ7TzSFNtP%2$x1%_oEu=< z`RJFjYe$jNz4yxRu=vJnr~Y6TgCOe1#)~2Nb-`^lK0a+n`EExe?{|{Mra0sF+e8m= znz7zw0=``Vs7F}Sq%p^DEuvYm$KJ`l;fu!;BS-#`oRRkE+Qjx3uR%rFC_Sn}ujl)onN-^*JRjAfpwI@U0V=`ZhtKFWREQ7)aRF9MU^6=lm zex3dFJt*GClgUv+30D|L~5IC>KJUOGtbz?;?f-B>A3)>R-s{ z7StZU!up^pJkBiry9*A0OIbf25&H#0iDpo0*E`4)rk__QUZB%l>OqjnFWRTcRPm#G z9ZAVPe!B%H3xob-0}`$$bl@xt&jt~<zdYAyI9H=TGo(AcinH82;P!$dX-NWMvdYC-Np5oPf5a|2tdZ=AP!17TqR>+rUiX^`qAir zrI)FVm$f9JCiGV-5i>|ED{o7vm#lcG6VeWr6tkRYNI^a47sRRuh>V2(ll&Z~8*hU_ zdAzvrRQy~0m=-`)w=B**(F|Ia|ngeH0i zLylFD9>9G+{ zQWC{H-B|Q#Ud_Iu(#pAAexo%&`%mnT$F57oTW5UL_-~668glL~V=i1TfNCAjH6bcD zR$xr8J$UI>(T-v;sgF~Y|2XO*N6HnS8|NhEN~AH2-{Ez6e}?~HYb=M)qJ^cXVXL}; z*y}q<#kt!|r90Izu$~+rp!|F%fdAc@_j0we^W7e~-~i)=nA4xpU%yqK-%DZ<~DAU1{mbV#-T<*3FH%;;-wGSW~lJA98q!tuq}mpA@6 zmAm9Fj?vmx)pMV%e*_gqqK;Ssm_q$du5@!R9X1?Kn|IypuW#^#$iF=lN8;DCI5PqR zbWgn8XJH_Q02}@a4u9J!iBTgO>mUSp-Es}98Q0?j#I`8Fq_RH}UObI?ku__tXE>iXwn-3A@5Gd z72mjwEb8BDf&SF}av3bx@`saO0CmabA3Bpud)bskt|iBF7G_4Yr*pa! z#lOD&9a;0Avt3j+BSHYEQkAbXC6RhzZzG@1zV3dXEz1MIl5VC)eIZ@Yc)4Z<9M_d( z*KL^3Nf8?}yp!K!xEWH1Yle@8THF$`Y2aUx|B-`y)Q}BkP0)i4}nhm8SZgHtJAvme!e3&7$~ez?4MsMhq`0U|_yo z68CF7ChA~q$sqWB!3Q01$-Hug5vEAAD4GaW;sVYr?p6- zDLAUQdG)}M%m`kYx-Bvu0DxwbUyXNsK*z=DQ+B2>?}PM)Y?hPbm|83ffG#o)o~zAd z62MdLA0U1b9mgj6t$M3HBAX!X074ysP@^tpkGuu|R@S%I)t~>-xlNZU zQ{uM*ij|$RUz>lTe#I;@u19J$o2~?8+NRKvT-=z9SAdbq<)Gg!<5S{QJJCsa6sgB4 zum!CS5}abcP%n#5lg&wHy$9=QOY093#Sg~BP7GiYZN_R9E(<~1+%iu&(jOUW;@hYh z;xr$brHYGbFzizb+VkZS#$3EI@2y`KvHbn8zE&zUDrWg9&@LM?x$Xc@W&hkW)7L!R z(NkKmhlkTHJGv7!vRG>TbU^L9K` z1Wm5TKRhWWx+nmND0IKxL>_4*I%GtkHCWF1M~$}e7v0^kO0IxpA}=_x7Lg)H?k1`|4HmkTLqyR`Sz?rtN!YgX%*G^)3j=A{JfA;_T# zXkjm8g2Nc!e~>#}nd|oV`0maPJx9&n-zFYIsksSe_e!MI9X}!qYsqo6!U+SozfZEP z+hN98qcQkiiRYSXoIvYL5PJ@Ks<-MHLI0_C=`0Xn-#R)S(E8-Tf!!5R5scr%U0K}> z7>CA^BQQW}p2=BGuGyE25u?ut%@f0_=viS|trH2k z$06CbrhS3;E7O4m-|FDXS$LBJjkBir8o14*c}@BG59bFu`W2+lx478<%_J@|iOj=F z(VT~$Kw5JF)kf6cI5zo3+jB+8U>!2UL7~zXqu*q`RJ{KQk3uQcAan4aY^jW)nWGEN2KTKngHjo zsCRb9NA6L7Ujq|f~g@LB#sqCr!(So-Onq zfFf4yu>7f(>v-@VPxJqJ#oq~=5~4%mC>=Fm4=E_8SV536hmmoa{-5Dv!LV9tc^FXS zS*}SUQDPaSku}J-+3oL-_azZ+5F^Ub?09Zx@Sw1-u4e}_rqN_#szwYOt%n&3HFc)BuQnA0wb zZ4?XU%Md5;ZKC_(;2vI~OpO@45@F(~hqm0RnGZ+Be5?DAwk$3ImM+EDcK^IXKCOY5 zVhR`swBR$0!O|Sl9L|Rq!E)bE$pY%%UvSm^iK{VYq_Jmkd^p31-_CRi{h{)U!3HjS zJDUls;Mskb@mi!h+Y=pLK~v+DvcT1a)pq`s6OP1#W7qJWlwZLizq?+> z-4e9i!awdm-aK6+s&e>g30AcKh;K`j;#*oJfIP?CW{wky}C;GZxpF;>7WmKvQ+L9`$g4)W8C zug@B9uAr6Z87wxcWOvh~^;!p1aop&Q5JN~CFLj)xVRTO%xnx##eBwqQI{@uJ|LU?a z{#VH>IQ4e+JFLJSc$KiQqLGup0Uy@(1FDl|l%o@z@7pL3CQL07=|s%ADO3Q4?y1Y@Rsla&ng(K+ zTd6dK5&U^5xH6cbdXNTyfY^iNK+fucAbBhfPbCYF56dPlxXP&Rz#*tbmPIdYPfex( z{(J!h>An(Y+Z0ol)()+q7GA(6szK7|ck zPHx@cb(7)D56YU~0jL?qEtTSGWpho@+c*j7VfhmjrSYUF(LAIyi6s!MJ~;@$0K}nq z)DAA{l^V)lSryPOOEFa{=FWPCYKmGzF9lwf2;UEL^oHg<){7HlIY5Q9AtRX3ZA z(osguVkR4m#@qz-0e!Bd>Xld`W;|5Ou+sL()Tg=x5-#MTKZ4@lB1N%mR# zsBFZvV;zEqITAsS$N7@VAeynR&N*A$r0#)i?(l~ndGPDu*1T?ByaXpM?jy8}+?gYc z;CG~Ka0-NQwR*$D>K#4Y9xr4=zlz`C<(`fqKP~^?=4cd4*fEul1?a*nu$rrX7M_YC|0&T9GF(;&5m-@oX4SDrXRig##8}S|- zd8B;jdg|+#)41#ZL=(_g_hY`H4ycxtzt_m=RW(=2Bsy(_GBzPvAYw7o#3BUH>S(HX z5_gy4XHk(zqPvWB0&P;9WqB@n@@M#krX zb>2CMOcsi5In=5^mtiVWvg{3ux2670L z88|49v?&Z}j9?9qst%^^tx0~Gj7>`&H!&~xYGFNSCseY6R^@amvV+ci4mKY;TH`sLmxm5H>(MfnwX>Viva`0?8(K{ z3^cb;a>E*m9&uhk1ehgGaZE!7-Jr4DBzbT&)aa`*2|x5@cnWMjUld%a+ST;n)`{fS z<*YYd!9*-$G*{P;Xou5$`2cw^Gb!SybE5A8H2C>UF(!AxrNU#N+CZ7_ItdrI46uYK%BbE#yn%zihf~VI% zrf@(KF?15BUSI?!zKxqeAXHoi)o2D(!8~`@{(8WZWr+X{3XH^t@kp#D9u!n`i)$sL zZ=+1|(>ik9zupGt7BJ0lXkBbP0AcXB2Wc1(uZ|qsqfbv5t@R${ z4c1==8m<~dLX>VbN@CmG(=?RdRhk=V0(~?jff(K`4S2l9Vr*&b-4I_ex1?-`q^hKp zPKT6VBnc{PlpsZ$i zMxAKhZiGzRoF|+-U8e&p5i^6=dFwzS)}|??p&<29jQ(7lI-cb@fc4v{0DZfF&ION& zl$K5q>}fEcT`(J-sDL?Ad-HS$1mffl(p8nvDZhZ#b?Qe2X}=BTsB8bG4NkD-PwWpW zaaH48R`)1C(YXjeX9dwctK++Vt>1I+JZw|-hbUCQncII18V`#%4HbbfOmD>jeSw<% z{%RYoiI4WZl=jVB&N#6?R#v}2T;gP`zNUJZh+7LyFvf{4{vLrvnb#zSE-;XqU=!(b z-BOp&f-B_>@OI*{s15@t>M7rek>DXnzO-(BeAW~hQeNz0?T#zc*KHtMg>4pvxGTC% z>0dp$H zUipTQrN%5yv!nXN$0`wzAIO*{tI2(?I=^<(KcwUmN3Q|4dM zkxc$Mc~j0~_hi=?k@_2dQ4x7F`GBNOwkX|s4l+74gSVwjNEQl?PGj*tE20{kQvBW z7oA|?6)OEg>fx?7zoQ7ZyqET|PQZ|=Skt&2>A-&q?{&;3lhj>ET;Pp8(>Tu;IzM&x z&MajAcseh=O7?j_SF>Zt9meL`78Wmmt1+e(vtk(YPVsi>86h`-RG6a8U=l0%J^H)F z&F-Vk7X(s&NrP8%7b!}0PTEWP^QhpRk82fi6uL9_25!*WlJdmFVxH`O?puhz!-F(m zG_Uj5ZHNPGQ~y+2EsS^{;YJn1F@F7|JnS7#7uv!Pd^od>C z$#a!%{}C^MmJ1+uTKoAqS$}?TtnZIdzh75x*%=atq}2cva#v(ow+Wwgj*P1j-{iPqE0P-%iu^D-RqdXrBF3 zggAT@e|E9RiYK0BC>#E(M_x~kn@tH-G``ODHgR*QwH#?jMlqI0gTkYt3t&{R3)uZ! zsrXy?QOEZKr2KiA^JljFL;euJ85e3Z>|lkUM3uesSMaXOOgi&>?r%&S9@EkUn1Qkm zPW^UAK7PpX%7_ed97{mY9XsouoF1KOte#7h)yySeNXU(78NR7Q6T(T%hKp7=_20J` zmkNF?sjnY>X$sZAnebEIiZ#BXEg3WuU=7PNdqbtV`M>){Mv+RxGqd|y|LznHW-*JI}~_&iX`*gTf3=BZObwz~ciNs=L; zqX(E#+r<+iu-z>{hBJ;%{5T;wr}cayK!~*QG6Mo&S(J$kZu(WoY1?e0t6qaBm(T5b zfsMh9MD=a%#e`s#OeGs&e+ZP>DI&01Q{C0F+ETb}Kpn&laIipGo9@0q7Rc3=$By5? zD`*!hajBNbixn5xBPAm!ik#v}@*`Jxv^taL6MlhwTdclDVQR7?vfA!0J83-=ewWR2 zRBH5VwQXb#jd+Y)j^x7IWyRU9I4kT_?OsgU1*@IzRT{1Y5C?? zHn$+Koqd(zwVS8jR`-$x%0!Q>Y6LX+f5c6<1&&5d3;pU7yGbgaz?~+QgYVP#QopaX zd%2-`co<}a)cy8l;%0yJ%mffX`^bh=`x-CdSK`m~B#j?X4KpZ%ZoI7*$Ajh6Y(`uI zAZ=!B?Pgb_IJ)*DV`jAEVM!J0KY1#qw<&%r?Tml>>Ir_Ix{2h*Hjx#0JSPl%8F7La z&^L>yuv>hd;?$;io$tur!w-7EA|*skHbOnunxI26NPrTq<}eH> z5!<4na=sm6wF~CDK%sM3&rFk4FUG*Nj?JHfKWE@os+nbMyk)Bm$T|$1X2A(ijrRE* zkUTzQq5$V4`uEi`yA+}q09l03ww&*ANOR1;+flLsEnJ*pS^{HS6twdwIy!!U5;kF)#g1EfLCou+$apvq8JyAt>S2SuBueUl4$Nn@7P; zrk*8U50D?F);?1k1g1d;inkvwN`0c8QdYLGKdK%JJ%HnjGfFCLu9qnOYB0VKmyF?; z+SP2l`P>qKC1hPe+R~|I8}#@xxP}iAypN|x8cP}OP404>?&qbEaTADcd{?^Eqa>N< z&tf8N_%8F#FqUkjYKE9!E8jex;H8!;az_1{3WVp>W5n1JV6IbfiX%r3S|B1OM>{gc8nGU!A*)#dw<4{Z_N_12^I&s|#LWiL9SAF|=es zbsz}Jf5`k6jC`YhTk#x=F;C%Dg*JY;Jhk5q5bxMU(CEUee~2@*ji=Z9XTPmgUj4eG z6oVco!&!<`Pda1EiKdQPpzx=RZsog+?MLTdm&1rM0+2?@lODAb!*k+Y^~Y(R0!%h@ zIn@A{aatWHBCZ1nBWf!BC_3#yY^CYTb#$#G8_N9n9{N+%n6RT?GG`VQJ>SJA&jM>S zeU$6;+oq%D*!REUZzlS`xn07SlVpP8EcD@Ex(fVLFC-Bf*SbLK*`!M>rVhR$3m43^ zZ1SD(Uc0A3+0M3lg&Cc_SHVh^ZAllQNGB{?4+=2s9AD^VCEyk=&zy#H6J)d3Q)GR> z47eGcB*!$_gBI!`+7@36DhpC_mTPY5TMeQuk0;Ql3sbtG&xVAkJ z5d!$3bNT2aYCWaR*adKRJ=&MY;+D(OtEA4>{&b|~{m-K=Zmuq~EN`Xn%%6KZ_scwT zJ{nTS1P`4N~4KjiAIiHAEAz5Lu_g1h&M zFxB#6TH7a?wCa$@yQFXESE-XRL!8!>J{i_D{|!Em^0lWT&=Z$-2c&v(_ZfDbn@Hw!-$ zcxFZ4FUsz|8ja{XRDra(T9GDaB1=zAUwqpuz=3+@wVrtY*2i07{@X5h zRnV><32~2lAHafBnAMU9WR4r2;wgK%{uFX0VGw)viq~t^J4VR$LX-nsfkof6Qfy42 zem!_91?aiTL=nGSjL(ezHWgz1l3H*GR^;WPu=ca-kmbrLFs50|G-)9iCu75oD3|5GG*OqEB3=c?KZ*zHE}3oHfax&oIl-)= z#`Sli9lVNervO^ehhKO( z(mffV9>>n4K)8YjfOeU;^M1cu$a&lzFyV%Y=M^?GG2W|ct$Sn?kCkQ$CO@w*VB!2I z(5=sKC$=9=K*C$acvs18oPc-!3qQmk-$nhfifH6f{cLatz3YaFFhto=7d4DGg%uHf)~Gxow61gut+r@ z&U)WrlFIS#6oC7}!`RIHB*od22c(v@yZR@)QlReD>UTR??vbDIv&nuk%>c`=j_slx zS4JXWkvPa8Sj_2?$ZV2K92jU!Dea_~*SgGI&);1^scL##9YB>|MRvSJ=G{zN4QI@A z_zVSYYa7y@c>4liz>{_M(sdf#L>APMlKzz`x2c0Ee+H>EsEGHd)7p&ezihI~+4S)2 zML8_8PxmVXC8te7**I+#3*?d-VLTV670S-iS1*ihh6->h#ZEH&p0WeYR|W%9M`q`3 zF)THe*N}~$+DA0%rxelHo2@|TgIPcgC7F);)Qs<*AWHjt8neGRx7OSkWGG-6)ldUY^>p`$fci$WTgnyf9RBU}d5LVi39KXA z2wmy+^*rc9KaeXA!@JwYjn~Q_VZuE|*2?xEh&v5bf5I#v&ZoC^Y>i~u;9$eRNr%M+ zO(nSOm zT>)>L<6fTwP6Ud22Ea^xY0-RatLvaYRJ3h5gm^(hs#QxzNHBdax!wU3_>9Tqd{1SA zbtJ1;^b2tJr(+%m2#Nx!n9wwe5@~;VVDRj(TQ0t;deng<;Uy&i5o8ub&Yepw<7_dK zg$dP0b5f~MpH)f(o)ekO(ia6y0084BXFpObKHZrMX`FC{Q)vsE!$2_M{0;?b3vml4 z9+qT!-a*1GBs&%<3zd*%ZQb9Q`vz7A>#x(SRvx&)rItE|zEZ1>&T)Z~m|9&`fC%y>5Ul#e0dnbd4A+W zE>nya^qGqC+^JfyW|D+%%nsK(4&-2m+^2KL``;LacsAn!NrGmbm8luVrP_}{I;eAn7v*;O@odxqp zD(Qhv;Wy{Jh4>7U_m~0z!)+xsBfs_s5yBmFMg;)9SQR6a1da5V$tz-0%6vWQ4M3w- z;z+vPA8}Kod?N!(*n>94IS%%(mCXEI=A?NfdOsagfLxseJUWI33)&BL77UC6jB-0U zaow+&`lx~&i1i#pY@01?L;}BWJ!Bho5nZTc$&2Gip#GpTZ@r)L@P~zs5N56=Fahmk z=5eY{EiFcWDJ;}}8=6m&;2_#Ium!+~8Vzuq5{r&mwom5Uz6jxzpji$DQ^TB@H!Woz zUs{f;(;p6-A0E? z3an89G==Sx>j3bAda_fnFxDL@Z}wLlu4HQPk~OcIBQM>Y4heuxj12 zxxizHtK0fY=(0oX+r`<>d_3nX_7foUPCGt$5H^<^PUYx6ppO&9Pz_^=_qzRX$5(!* zGX9sL{=XiPY!&zeWdrcv`uz*_y9}l28KQuM1)djBaBA#v$~@u;3tDS=;{VCXTO|Ij z5?|C&)E6!s{?BE$0)iFQUKwj+vDeKUgQ)348w8%IwyGGV87P zi?KJ@K_{oMca|bWhyoi#Xiu(wx&k z-0v5pfOYbIHNV^?+hel`fW3A+ReLNOGpPcSSrNkEkzfOZZh??O%Oqx8bjv-I)F z*XZ<~XzC%RCMn z8o!*Jy&SVrh|Udwb+~qD~fln(KptJSCm;p^N6lxMjJ%I9S6M}C#jMw z@TZ^2>1z|Nm2}>s+?%DGK*re3Wg-YZU1$-3;WByq{SmWuUh{G$4tLEzP>|JY{ERS< zYq0Q|OpOLm5U$=;0N*c&yNO%tDcP3INN8X}-9%whV>5eG-WZfE$)}dw(8yMLPsVeZ z2Z^QvG|;q+T{r1HjHL@!Fa8z9e29pCgV9oVd{N0jv0M?YQB>Ap?nG>z)!a()-!<#T zDc2!qy7@(MwEYztzqVP2GtA}(d1>LWPNID04#T;P}1pP9S?HwGW(o*}F zGo%jNH>>!5A?p3gfA80#-ixfizqfSm+r8h6A{xe297cWktVrw?Pn`3$BZ)axmAP{* zBCA&vm{I9%uEXb+CmITH$i%#ZYm&xR26fxP0)TA71BAFvAnVTu92XBD!j9yIxBp{H zSVn)e>HBD@L@vxhZXZ43**9XsGUBR~SwAomu{wNOK>>hMWV}N+L}Ku6?Bhzz*qJ}w zF^xbRSj0A1g$)F@g3gsbOMWXD)YxK|hz2YJ>A@iIN#%f$)38Aw*^JWELiE&1-_+Xe z)KV##Fp>=0H+_6N{l$KI-+{{Bh34e;^C5;zDT0E`G57g@V?|32>s^>ppHGLpk*O&_ zsY>tQ%6I-%V79%ENHsb40YE2^7m7Sd?&x7jItSsvO4N0xvFFgLY;HbRl8ngIR znM|02%tLu8BxcEOZE+J;6QR6p!%7K2-ampIM^ZM1uQbcW^oen;%~aV1##%e(z^-5^ ztYF22!a&^NwCLk6uej!c6(n~YDb)}r-VFze#6%Z62dc%+8No1{Gf{; z%W%Ky8~U`i+5udn=Dd8jLoHmnUv{@&sd7*gd(hB-(0q5$rgGR7d)V-OsfX?G5)(+e ze)y^XXzK20R^@mh_IRcL_>)TOr@!gA+JEKqn2EbemYD+KEH%b{+da7Qkk0%0^my3( zKfL9b9izMN=a_ZI^3(fk7>;u6z5^wl${FyEg2jsBURWT+wyFGdlT!6!O?gL){Z#M6 zh3nmg8E)J1`K4a}&gPv+Sp-IWAwHx`fa2Wo2IWy+kG z4-cRzdVcGKrC|E+l|!mZ!$Zf{B903+A8?LkH^8cN3=&Mtq=Xh*S5vw?N;ij|!dT!4 zNIIjn`)3+97RAssC%rU$05{H{Sn2;$dh#+_J7Fa5BU7HogVo8B?o%%mqBc7BB|XOP zFH)h(DN+rS_xUJ)43V^;F@De8zlpcnjmD6d)f|+TsRhtxmx*HKRGDMO*FI%H223hz zzn`WPm2@$k8i_$T=bwMX;u$q^2x4YG>M1s9*(Bk#GD}Tm??a`;6W10&3~OhKBglAgUIh`*doDNB-kc7=hS_w>7u9vbZPJSLv?V^{&2}!_KtI20crIF`*|rb}zhI80`yO_xGHgl}8AdQA;lB z)z6Yx1fb3k5u3_fh9~>B`5ugs{FSeIZR|vGEO;2A(L#;S3Zn>9D#kU;Ihm|+R&b)s z(WK-wFR!aPnaY;SN2(V-8Ql=O5$+lG)bV=r3Bfn_N>BGRFMPhTged`G%>Xdtgu_C* zI24A$ASo)=aD+@Rt9EC9GgY~J3N5^8%tlVjWr=1_F{xJs8q078VlyPQ__IkB#rDq( z7}Zzj$X~mj#1T_{*puARZ@G%3BiOMHnWn(y3rsOQRZW8**R-I#@%IV>&^7mrT121qS#W2iD0*4owSe>J=@l9uUg->$uhSu2vv+DW70KhBy*D)z}`4Tx`FN6*QQWOYu9@SIAJ=~F}_h_XHIc+pJ@B#V>fKikY$dhJ@m|5_ zY_E5Sy``pqo_C)QX-2JlS(cnay0C|q9cglh(S2PTPh4up*5JF@I#!tPxzn+CZd#0g zVboKh$nag|##;}7Fpg!B2DxCkJqii<^atPPM1Kw{{EOJxs-re&tzi+`n-glSEZ4vU zB>jhSFg*%WMQ-^!=e8y(^R9nTqJ^k~SYYFz5RUJpL`WucET~zRjy(sT8i!4y$E}m& zVrLrv*PK7oy>HIbAh`e6oY!}PL?8yavrFu^D;}w^wNwi_3=bDu#|z!<1!l?2Ihi0B zhB=&s#s3*NITsdkf1t?XdN#yNd&&Dz;AgWOW*cr2yahMtb?E43T)MB|F^BVnr&iWdaXE3jdp;{M z^fIR*um5D&NMo?aLWW(G=zk7Ca(iAw>fQxP1LU}BE4lP|C$lpxKf1h#j3>4;UVbfs zpHpRspP?0qnqBam*HJ5;R;v}vQcms^%av-76)7^$OU$ncFXA@~V~7v4=3zIu3QPGr=< zet5i-$P)IfrL@fE@f6iU`+k?2dxwtj34wLI7%@eH7^79WTyw5OXpO_;qbijNgR$Za z;Ck!0V&_|F37?9N;maoH;}n)YCYR0yWZ9AFU$f*a9}1kmkg(4-@3*fhA^)vPPg(HQ z+D-FdNZOrT13#yJXI?K5uB2stR^IVJ`%d~DK4a0h9OvaD&c*H}A~N~Rv&YE^FT7m= zJE}gO?;wbEqJ7^Jyd~nM{{+K&8$=4EvZ0Ti&EnsUfBI$h+rW+@sW6;kaTCGU4fJir z@2L?QG-oB*tN>f{9xYZnHKhgil8vRrS-#upL!j~E$DQ^jZNP3VM+@P)g~0# z^I}m@K=Vg8=d|sjNjYBWk>zw|YS!0u+|N}YL0P?w-^hQ54HFtRIeoEkVv{Jc;@NAq z{0`NyI?=AO`6(Hgcgss?A~*DU^YznF`*jI}F?lv#TzhCL$-eFnx|#UW^Vg3s1^&T^ zB)#yqa@F)4k&fz#kAKb_XF|WS8h|BI-8!>~_x89{BNsc3B`idmYr#kJf}Sv!{5K?C zrm2xU)pP|7#1_N5jqm!KWK3V(d~@^AVV=%o<8JYl0z7X0NcCxQ_+=dF&o9G_f*)(Y zv;nD~#(Nmf5=P3Dyx!Xp8nOGH{{9kP0|DQECv4|C_5=YnuLFpqRvoA>DwJ)ziC_PH ze&qN2wLrrUX|9N`zosWz!$OX!XaNj9p4uPu2ndyg@2MScx*v|S);;^1@G64GZiqF* z?WnP6Bd6ecINke~(v=|dUpMhj&yB}Y>%iM8<`J5>tcA0kK9(IG<)$fbqx0gwDcG}# z9<&4p`QxU*7BC>PAR&XQ>etvF5u?`8QPzcwaM`{>F*wswXLB3uwlpyXd2{5 z+rf~!Pcv*(8sPdTx8-J0UA~!pqo)BzjJf z@YcTdH|^qP4Vk}Z-OI1}OMOv*pMNfb`ng{|px7fFJlhtovSATj+^_79{FL;ibge4# zwuvpOW2=&`108Z!q7aoc->>lYfo@hk^|Bl71}DSc_p5Q4ktb10*E@hv>X=%h)f!S;+V!A?pwzH?$Drtl0jX zQ8#XbAeycYQFD&u38#^Q5x))qDao1fjUlLa5WS-)8YDNF93$Ocu=L*ZfAk66JIGMJ z_?AHMlYj*Hi#XMX@#EWwrMF&`8@f)CaWZ2_i^6--nqx1F>~x0gt0{QfJ;AP?kzNcx zxq_$>;~v_hp;>58V3io?6ncpW#fL}6!#E7ll*W6Z9?*oL-+^wYPt{L_R_~Q|Sn#(B zvZ0!|ki8@~ASANTCaRtY&X973heM;}o(|^t;ZvHwmqpVuJkzL+%n48J8H4M1LGp0%2*V9Vtz6sf11hq}fpLI>eA0x|$T=wuhD^Nd8uzn2n~>M1n=Y zKp}B3jzX-OI_*;rl|^gP9}eQE<)ni#`H8WV1$Vx$Th7z!$SIG=6*O|SK6UW7Td=fB zUj-F@E9nolBn7@q(?DQUA(5kF3h7MN`Er5^5~XDB_!;SiCl1jcgK&kU|Jlv#_29{6 zkmN7QDWS zu8rm0OGMqw#7A4n-~qVkim_bXS;%prP}DWlNFgwqPcs08ax;d31u8Fz*keES9d zdR7aeBqt7#TPgMO!WW2r>e~9)S`TpXiV(^(K0bnh)tOZD#<{t+aCxkNqAoq1un4!C zw`t`oetAz!OM66EtPlvTwN8ujAoy=ZgFZs{DcY)n{^>GDYVzAc9>N!R0wptgCCz-L z>a*Z}&y-W^GF#4K2i@X?)3hrGqCeO4Y5Wvv@+Ic{WwK+5l7t%4goVqVDIBe3UUOxm zH)UNNutkSFgd^^yFXH84Zz4#c!krQ!1uBo!OIs#{T(0o^F4DbWq)dWA7ci=e)-S0J zyqY8KZJ8p&Z*$lpjepvNyxXr3AILasDB~04r1)dVltLjA&aEBqI0Sliyz(shFPcBg2s3s(=z=iN2FgmCIe)o>!f8(--+ z)_65m9pIn^SZJMBV-5nUvmu;>AkfY$xRb9&(7Z;Hc&?Z&3R5;(qw3 zuWtYhHiUhJP8~FTCTgA)Z2qF(JTne0z(5xin$g&rge+*D1A(pwLt62x+5P$h!Uj3r zs_>#F`D|z=7N6$-5O$YAZN5?e;6orJc#3QB;uJ6LR@_P{Qi8O&mQpAd9EubuR$Pm_ zdvJG$;uLo%#k2W6&+LC@XLfeai@eN>doq*jKG!+l&tiG1Xpz8VQ9@SPZE?l@*RsXt ziYP?cf(#^V0ul=-|JGdCU~58s7X^1l6_yFzQ*@?DkSj~{YKRci#ROK+B{L{ckgOUmfQDwz&TF;gvu zWXf^x!zznPY_MxSDWwY@))IWH;>$)>iK^C357jIm4{-qHDU#7N;cX zI3W7yRZpkFtF6k@eOK#bMEc4Il}cK+@U0FgRy|FLRRk4dO|2fasja}Oifyh9qH3^T z=5WMmh-j%N@*>t%ZE*9d8@+=_rZ&t_Vnyb~!i;FlRl{wUbF+-?>n>ki@ftP`)cqrJIH)}`adu6cF2!!E9q zs`Nkk^A5W!kgkiG%5>%sao&b{{sdmOT^{7YoMU_yXn@oSZD@68yMEfj_y)`4F`#1(tIf;aS z_eH@6#DBL(v{w9>KtglZ2hMN?Ro->7Q+MCp4^H~#nEGh*;hv0 zTop1R zkb0B}ZCu2tsd8xelDe#;w9H+nviqpFlwwS!WaMjWzwd)Vit$8R+VJ^9v6ao}6!zq7 z@hH*C=!@2I%as23*2&k#gRc8yCc53U5*74i6O5yV%no%6_TvJ@Q+LKAd|yWRqec*^ zGY7?E!p9?`ZOAGd^(p+aG8T!la2Gsg)yY-knfkEFOw}N#_XVf5n}TD)1&k!ie@ zR_VtIHi?<<_LH&RGrVP!u+cUPyi%|O<13#z*Oa+g_E`yu27Q_`84)bQwkbcc`O=5k ztCD#es>L{yIU18;Kbir5iC#PP%DBV1yA%tVmRZh~S%=#N!qyQFu8G8`MU1k=anXg= zk=78rG8sa=oVJDfrK!fdsln1E?}ugTGBw|oCA>lGeK^5Jj4r0hv}o)^{O}@%+Va@9 zg+}$6D2EZiBk`U%(eITNuGaa{Ho+c~--BTinOPX4XZW7|zwJg!mnfIhxmGgE%I@Xx z##6>!+mMN5c)ts|rrl|3N>Lp*Dtu90z)=hiN9^4BO5gMfzucz zUi-1WC568&!@VshxgD1UiId)z*C+a0DbF2|#K zjidhZBRD>Ww>ptfAV2BMro<(`48MQ^I-v9npB)H5XyL1L3ova6V18b7d0+ME{q7e> z!cBfjRMhY({wXTd^HSsVujA=iJ0yq>J8|sv@#Hk#7cav36kYQSzAP=z#H=<81*a>e?^g;Hkk{X@Bu|l-d{A`l zmw$CN|Gs(o*B$$>e#Kv-@xQu$KvRNiGe2M=6e!|!?VE9Am3e7XaXmD4?cjIhMDVY5 z^=OlZr2mKburA@~r8v_wiD_L4rcS)3JPafp0}vy-iY|HhT=&n(#j)XfeHA{|>Z+>4 zpzg_X=i^#R$88cdHKDxBSIr%YS{a%v8F~TPKvTkCKa}%%9AQc*h?M<4-k1VMvFaEH zqpPBh{{%KxQqfl9(>Kb!H>4;Zx}5qDoeJ-J2w+T#0BOaKdW1H$pB=6g8B7V8oGw@i z0PF<2wH=M6S@^eEzbAg*uSqOQoZn}-Jn*E=_nM9!pFWj5Qf6SNuRxrPMZ&fKUkDArM#Ai4|uI7qm*K8^_qzp)P8D6eHFu8mlJlC zHMUm=WI@_3l;gz%{{aCI_wjh^6mT)@r%&Uzv#AF8t)6c>e^34_&!3ti{PSf^mS!r< z+Qa^_zgH9Bu_%gR6gyEhaF#Cyj6H1qrcmw_SX*y9R1C@f;dC>%5s*A+Ea_?|wAp67 zeC_bN>GSEBbyJ~b0U{O~sZPP;l0D$ZZtCb=;k5eIMycTa%H3z=(ISqlQ~PD(W&4QB zH(CP8s@uL*WSr@s$^FRw>7Vfe)3tWxe}86a6)Tc_hLM0Hr|QQsjtNA^May{J4XN9i z41}>qT_y==IVhXJqxQNR4~#q3-6f5Cj>ur=-akFI^o0D z9Gc9d@vNO>CO4^NRiKX$xELS_963|U_{uam7@HLtH~2FTcW{WK$o}OECJ}~e)aiq` zMwD5MX;O*{B!1Z~xJZmUoV`TNE5qGS9mgPcIrB*qF(i*QCcLJ`uP9>0S=%S)L@c09 zces72D#@7OrW5}#nmgOl znz^rb(}$93vBq>jku!}@#2*2_6Br}q0XN*>U_ z8QM;G>Bn=07Y94e*c6g0Wk7g3X-+;7xQOepbXC>etC& z48>Btk%9b#260%L;h5aWlJ{wa@aLJ~Ie5rX?`R=I#kS1|d~W3EFtx+vn9QF=dB`)p z&<WEEdf>^7uO^3LcV@cokiM$<_gKG#Q54qMUV0|(d|tTVajf*D zeReb+MhNa6c|Z59d4QX6Ag+v7AoL*z=SwLX1eK^Fk)IP{3d>0aAVA`r8yF5*azJIY zB4s2bz|lGfVhITqPMeyFCB-1xf`uy4*gT80jn9pu1_-yygfIx8XM@m!Dd1-q4yCyq zxRaQ#l(67*Bi-c6Fp$&?T|$;)Z7zWIK>J6t9zfu4k#_n4*FqH*y>KTX=vLZrPL`m7 zletumxkNj*cqZuAY>`$1J3x3H--=iUYY_&PIVdJoUneQ0AmPw{{5ppq-6sA0U;!MM zjAALwrs-f+)^Avvtq}cCVZn8XG@UGdH%7Wm)XyUa6_z2;kJm3T{%afCb>0iCWF+%9 z>y#P+kpJiW{5;3uX?OYQAf89J=n-PtECO(UAjG(t2-0&Mg8rNwY4PKP;LT+Rx!qh9 zK*PD^3UL4o4{}%_Hfga7>}MO6&wa80{vf}FKQG4$ zu|M7GL|a(q(rh`Oy>~;#MoWlh)1+3O&<36n@RRloE8jZGOso@Na(~DJ?I|)&x2#5_ ziHzFqFbCmO<6FsFqW4Sp2cu#|Qo_#*0%p zK`R}umXeU#Isj?>fId_j(=RntWeSN5BuYW!0gTBw14=h&DV(wUKpM``UewzRR**sU z_BG?ZTxwf`k0RV7QKTFj&Z<>SeQ1m4-$T8(nWaSJ5}l)cuX3rSSRqpsIc`id)a$R- zglE1yZGBX3NF9Y&V?LeFCh^Pf2w2@Mq-R_fUK%IbB833!aZ8P4@;kD!uSn+cl0W7# zviqFNh-F~GzaA>kuEPd+S=Y$aOXY|()`P_E+L9a-H`Y&l8Z$aZ0S;k|`|6KFl9ls57c?hKaz0fB_j@raSXj5|t_I0zE#31^;cQmpkb|sv)f1kGh>mcww zcv~FNK!ywgJ>C@0;{dPo1=g-7<|R&jOrh&Ie)$xTQ29aBy%Xy6^!@$U8^P0uWu>(T zKxL1JuvSc+UCWVbdy_@`J(Uyy(RPvA{&X(|xG8702AjYjzy~mWEFZg(V7qY0X9y4h zW%Gq}`kjG&lZ)H5LP;$^?q?C72g(8_f^oMZ98-is!df#2*k-6gNn$#snn8rboxaN8 z#Y+J)3;=l$1PVg~+;BxW!#!a&E_>hXyc~9OZDF7&b;tW4da|KIaT0aqeY?fnjHP z^dkx(3knf*z>^vXWc?KY3Vh2c#|J4ykx{@O*w&m7n@EVQ8dq3jpWe5Z*ywPQLPh_^ z@IdEpE*Nmvps-K1iuP_LuXO;Z2jRgP=9#BtvaRr`RFOIxI)lFm7sVSEMGGo)>#s90;1#&TRh(QkS7^0* z!vS=Cd^+tD!m?muFyS{SFrJc5r1yZ1+q_IT6&u5c&loEYnbCVgcaw;R*9^67JRPZji$nD!`Wr}6a zaC6oeH3a);fv+&&6bm8l6QQ5sm{v^riPMoT17J7ESPtv>j$5sfmgcov?Z3$JTem)f z8DbQrjF7$tO=)ODCmbY3{< zu=wb(M(MDn>#&#UaJ1=gj_Po&=x`tFynNK*!PDiX(d8o|k%!P=*;@Exb3{f;HJV0UC(VEo`629Jt_}-Tg9NB~v}-%)TlwfGz~P=*IUlteogP4d zRAm59$SY2Wn2)sR=9nfcMExezeIyuH3@qf;X%wXY#pkU@FC_m5_-g{#2lmRrnpYLT z<5JlbP>JEgBjXe$M2I) z2{obvvfN<&l{Kt0G2*6y8==r0Yp|m*_mfzt%!gnGF?;r1x_y4PT|HpYh-Tgyp-Zv=D`~KhU-Ocs= z^#jWF{!jKk|4;V*udb1Q|Dtg3o2zT&)y~E31&Z~)y1qoo-j|n`7Z(=~=ldwu`{3`v z2}zySuwPD93wi>wb0ZU~Of0dE@DK z!_!>!(|9bh7xB~wd+JbIJ6l~oU0Ob#TRdKvJ(`_8n)!V=ws1JVvAMGTKfd?s|M=d^ z%gakk3zPekBYVRmyTkL_Bhy=xV}Hh`*2cQGx)v7}=jZ29==bdG3`+c7oNJz$oEk^f z(CF}B-@w2?Z*Ol`SJ(f--L0*y4XxFsizO)&$zg*bpAarPHGva#A;?A{Wc7=~8u{kt zy4ITVj)v66mI_p#x1q7Nrm4KHuCA)Cq^732vbF?8ZX-)QkflV(LdgFh-e~_h-pTN* z0?vO0#CHX_D9U@G^ut(|e`9HGeO5(5Q%+e;L2*q!is>$^C_zcxMJ4$;r5Qy-HVM(Oi)tyn>TO%7v)w_ zQBhJtvD}Jsa&pqr(kPmnMZpsJiXX}G0!d4QBz%U%#X(WqH`G**AW)=`;Qy-K0s;cO zyu2v5n~RH!gM$NQcQZ3HGcq#%AG@2H<~bD=6$J$a85tQVDJd~AF(Ki9iZ=@Jeuf9d z!^gwL#r;2&Hv|Ite?`1ezIO`Xzk(nEXb@`U%B;>n2objNdhbBw{~zUT(=+^kC~q}% zeznN|Z_1lpkBA?4;Wy>nexaDCZwgY(umUZW?gHUUTi+E3!1!8_vw)YR|V?w1*#qCEa@%6rX8>dE`@Xf|op2c3|W#t%Tu zy6z8QSI!JPmDw|aL-bi={763*{txAy9ZU|~`yGgT!jkR9l99yV$x&^Ptu_t+u5+qh}+S|^w=5t+q5`U!f@IjjWV}MF_K@wmI($Qi~b}UPr3c^ z(F10|L6(U&|54uIA0eNEvUXCP`zTma9fv%B0T*7|q-MmOFBbg3d~d~&br3896)|6# z`lDvbeXy4sqxcP$`xi?Dj;n83y#FiB{h+Aet+PvSL0+P5aZz^kSK9(U+=;v_9ztX@ zU1`FKYJ7LH$5+eF{l`hmR;ubX!&rw_b?Sz%koNAqQg0h; z)C2v%^$us)mOYZ5wNbghW0bgW_1$y}E>_-HL}`&D)7EL&R{$_+-T~*?e-6PBUxb_d zFO%-nDj4I10fkwYIs@M|%kNKGms7?1+;xvvR?$T)BBY6Wq+hycMK}f_ARyg4nS#@% zyE(r@Z;9(Nf)t5Q;Z$1DocH>x_qThDc9J)pTMjYjCxV*ZGE=XZlh`GWq5=D)2tcok<_iQY5q*xPf?}c@U zk*8<`z@J46K|dn8=oYo&rEAd!rW`hC>*$pq3qwU_%=pX`Eoq+B47NEuf99G`oiE&f zo8b)Hi7yI5QQj28@7hm28kn}kF$2Ci;WCl;1Egu5=#k%jhZt%50C1_mMSK<9Jkn8O zBK~zVT-7XTx@iFj6Thc=#@}(j-&f1}ZU}&bK0DlrpG8DTMQ10hRz&$|nYeCXD$#K= z9aP24&9#UBH3UB=pP!N>9-+(J0{}<_qXDqLP6PpA08{DUS2O+?0QsxfS=>zpbmqoy zuAz1eg_wel6Qh^`Gd3(-MF#ytoS41>`P#i>sFz0E4`WvWLTy(2g=Yjj2&SLtgCW}B z9QY>>AfOROB}i*6??icBSyzokcPE2~;r6$5U4Y{qi|XQT&}WVU>I|~2#wf;GXD&p4ZB(*T*T!eBh3gab?&!^bm@WA@ zld=|}D5bxledpn7nN(Kl#zwXBrS9dYS_}Y5waj-vEuN&D{1x?d(KgI1bLt!Ee%?xF zsBS6a^G@dtdsQpYhr;gX8+-BEH|9}ju($xa;^#gBV{o2h`DyT@C#CXj*!#bjb!JA zM!M^F(bEb<*vh%I#mYJ^W*5fjPX)co8W%F})wU09g<1qMs-mVT*J-|&6$80T)m&rN zLHr(X+1^wBNKo5Zi4vjb{iP9gSo1OXcQVphPTwT4#Qsn9s5~HGFH}IydlQrKnWGhV zP1YaMy}-O%5eHw*oMWXwDs%4?ToNyH-<@sg8M}@Nu~lzHi|=W?t)IXY5%@$}_FPA` zc9OW)t(X?i<_*r<7vg(LQr6DIX7D$W{jv;(>9yP}vG~XQk zrER_Kx#=+Zf_);N+N!sc?F33wb=r%R zn`yXT4W{ih*j%cuB-N!MQ+J)e-#V*9)Q{`>V6D3)ipg9XaqrljKMJK#)oq}bYlY$p=Y2jtk2{ap=M3qI|WWV zRrfe$d9-!A8%5SWEsMv(ijT;I?~h-DOVHOo*ROPECLTg;35Jy=rbF?E(IXV1AWp1 zaOUB{>^>C=S0vY&`|{k{is}+w(VQ5)GfwqmkfJRr;}Am$F8H6<4Knj?(ep;am4q7P z=og%rmEAV2tgx!kd?vnf7`RO&($d30ZegHhY1|`0;Nm(iZ49&mhVNnic^(bN2n;Yu zdfU@r`Pw5WveD)q>7s%bgBB+o9&Zqy=n)<_pkT+WYk5Ur8ivz$rP?W=ri>2gvxL&H zLMd6H7Oc>R7dAEvwg!n7!f@ZmETB`PFBMRVF$-@s2BU)z9aj$9z!_8kCx|>#p#1`h z# z=KZ!Nl2{8J1jwuWjLw4}Gye^6_N|i0W&$lnN+5t~;S)wBc&HZ}jvh)4luBbHRicBA zuH*mB!aI2Z-TvsfCj^a!;{Tg)Pmw2#F5N;{0IUgn5%4Xw7|x9wAV3}jh|Rpov~cd{nkU8lAT`%MKMt%JOC4x(ZZ8G z5)4GbQ^L#~n4wN2@ACwIxP5rbGl^U4j5EXoePE48_Y9F$j92iC2UKG2y~SgzjA_1! zS71%>reJ%q`27Qf+%6a={qH+o3QyM$hK2ctrJtdRaQs6aEZcn_tj@$#rkEtGBsq}? zv@gC`Y!SGgc3z7~d5g?`Ha~@`^p|H%))aL4MAUbJ-yih4f?R;t&~K&6KO+-;L|Kvw ztl~d~LdDL&QafKg_T%A-3HeQFQaNdf-JW5;QuAM=7xbk%g=#zACh97nd21yx08%`E zrsX0B)3yg03n-HPI=`ofI;~lyZ-CQ!F*B8Ipmh+u;rx(|@Sv@C84tJgyZae&*%_0A z842MTsT2|Y`>91rQ1I)tM_3xxfmLi>=Ht6;%8N|g!dEjQ_LRX{>P1;wN>CLFw|VF2 z_3*Sin{4)_G~yJ#i6S42gXeZOSq}TzFCaNLYzl5o*#Ca!vXX`p?4)ss=4mqK9o4{J zeG%jpHRut_yx7lk`Qqz+X7S!VM@lqXJ|&;RHG}I%-hJnHe)O!5s0*ghT>T+*zX{C9 zU^Mz~Ij|3ThLi;_Km}S?FR`IK6e+Y1jXdfHpFY~=cZxunC%}F@<}!1?-m<5-HW%I? z&yxa(d8Vqlrl+{#42zs)i`EFa^TUi67Yls9rK9tviA(3>9Q=}5%85)VZrmtLs%9_0 zV=KBSt`;rPhnCbXv72J%XQ}+MP6l|Lfxk+d(*ze178e$OE#2NI1oFN}WM^@kDxI)> zF<#7t`=cb2vaq!{9jF~)AA>D@of=-8G$2~OoLvg1%=EjRRq|dfiVhT>xQM9 zsAZAnVz+O?ilHI<#pQd=<&UEBDotQfY4hke#T)Dy|C%e~%*vnLRRE}}pkh_@ib=w- z!g=hE(#7VtLzVvyDxZo=S|}?YRH~OeeNn6s=xu&aah1VA6_1gAA*CRdS1ut^wd(R) zjYvd%cN02@0}msnYW`m}uTd>8TD4F~4aBQPmZRFAuh6d&$oSDl{V+$+j*r2nRwumn z!%*#;mRgnNY9LE7xisFzU7dhxtzk<&sI!jwuud$ZUQ)FBi4nLm2t+Lvx*ENDYsB|% zxPFOTV+vD~)EVc9j-dbShjo3$(ong}J?cDDAJbQchRD@xX&7H@$egKya}?y)I^&Tk z?a*Nw$KWkaSf<#Op@!X(sj4+vxTDTWgk#V?4p*1j)!8mL+2N=t7r6CX0B_bIKy8qC zV`I@_QA11fCyu7wX71oKuooO4HEcCB+|X3gqKKp7^Y2SPx?u(*^bZo?i6H}Lgn^LG z7wOjmmx8y^&Ggd_GdIGUI#N-v*HGdJ);RHB7V<(M~?nfr?}WdiPmVBWzpyKH?%A)B2pL z`|ZX1-9|dxn$Yno4JLWezSws-JoF!wboL*Hy)CU%*$&`A7839k5@-uUH%g#huVB%s zt>(+k<@e8bl_02`@=}zFJT}AN9)p?)@t2e8pFXP<2Hif)>Z#s z4if;j7?_;Zu+rDIyw=JcOVvg#{5-qn!iYf=oQ4|v!BOw$% z+?sB+#)b*}OJ`gu=E2I5qQ#}g7bVTLtu#68G?}>B?P`pFTBZ40Ml+T>0eS;FoWsNS z%|optr&VZQQo-yoz6;{DOZMYkk>jj?$M@342JS})k7>G_Fo|No5uZoFWkHwXPPk1z+$mfn$JBxG)Qh&U*ErJ+on^oYKqzd2 zDyjubeR|7w`q|3(Q|UCIZDwPm#1HWXZvuPHd(5AA@VUvjVq1G7=G@rVk|a|m4vPzJr)J?SB>3Gpx&K{+2UKJRKW zFPuKOsvR-O0nM2pz%H7*rCtc2DF`b25Mr_r<}tSsxNU`i&2KX4m>`yP(rcoyuCzSMsd`U60_ z*i-30ISruIFc0d|*|pKMjW*jjpM^Y!)wDFvig z8sFdPkM*nm)#;p2Z|_NL$4v!pD4QgZ1Ahty6p_@*12Y@og0b$6t)He5$P zAIx#y25;>0lYQ)ktpT)fG~1)}kWV{5$#zdgR(p^49#+=)HvXV%Pt;)UfzbBOHbJ*A zY!x1?OS+!|&)KpI_L{r*KsLWcGq#LZw}fJMF=8jNbapVa_Z7c@*I)$e(i@KLtkTYy zA7KY=fd>}F2W9PBDQz2mGW*%-bIBUeddELn_-qn9Abh$btmHkC`lVR>{gv{glCc9L zv_s4>gWa1W^k>KMQOERU$6x!8DJ6Fexlb&7c88z9Y^qRlu|o^T?b_(s>9G@1l_M9d zlMToJX5s{7PJr6=RuLz_?2}(B^rUb|E|dtQg=vjI1Ja6MAiqC8?bg0OWF$Cd&OBlH zej)Ga>wESGR&Mnb=llUFx#mRq=dTQ?WdbMl8`K(r{bAz#FnR(z^Y?}CkKrTL41D@mQR+(mI~8XK5TkRxX6`Dkd`T;l z(~*WKX#$6gfQSizoh1!4k{Xf$p1PhKz|#Mi($3Y>7lY0hVrkCVq%O1HRfxI*zu^#B ztzUX(<}gfMpP&4*_E{S|)|aLWD~T?Wu=b3w0pkxy`@t;wkiz)saV_|eg%za`4QYSzPvfBfT|Dx z7jo}; z9TfC5LIcwXONDs$w>tK>uI6e#pV`a>dGK$4lk!m^$C!C(2nZB);S=~;yFL)7k{)se zx!70aZE>|pPI+^vUvARoTSiX8say8CDMccc@JPD$!)!Td;+o;Rlo&2%*c`!xOq1^Y z923slGwG^88gBA>9PMs2$zS9l)bB1Vhlp^z@Q(g*Ep%v#aXfkp)b5Q^d)^5Y=F-;T zdaHWT(C~dieke<_A)~Id)9-$sCF#;gV|?ShDeUkm{aB!WZ{C zpVlqV19cjI(bBYX@RXpj4OO&9p0ubZn{e9{;%ZG)^2k3^BF615VlTCkjnp&dl^uNw z9PK5OYvvZqy7LcVoreW!DE`!9(q4L4zh=o4uu(36dxtATl(tSO zP1Me4@{kg!ot3v<2gE2Ln{x<gu% z%2mQU(M&y%-DH1h7?_+L)y<$uh^Yi8GSxeWr25AshmvxLPFh6^<}(lkYk%a0XG0_x zg9eSjFAUm^(HIBI%t@{Z4bP}|NH)XB5|sf*&cdw0w$yq9i=pBg%7*#U5G!0O20_+1 zFH!(J0+k`VNy`jyX3F$MYYe1Ku)Gb)GLLV1D@p9S7>u(@%qnb?A1HRypJa8VYYs%R zg``Lom-Ow0NL^>G(`h>!L$*VDB$c;w1ByWK9|YBw>He}XZ~~TSC5SpPwy__DuJe5S z=|A^;fY2i#(J9dc!%);>zkHD#o(*I1{U{bdGsQ|S0^?e*iMmQqBA2^faq z5bsii?htSuKo)(Dx7ABWUA+J#PwT`r1UY&1@oYDjSR-Vt^yq*vq(5zeRu^f!4E|Q9 zD(Rbb`8Eg(Ejq-4RA_G^RKH2Xois0j%JTz{|9*+VP<6(7OFkD{b)ZzK41mIJBJjF! zoah-5w;c{Th|Pl?5J^v!ZmviIX25bBkfRwW1QzQFM(aoEN-BR+j!T@;h%3HGrwnJ2 zz*@@ndM}?mno^*`RgEV3;17aesYLrOPLVP6XQ_y>xvc8xp_R$+w_I^E-v$3NIr<#x*!&zf z)X&54x#`A+R!idcd@fNkD+!x9Adx?kCCA%fZejgwv z9`G2z%vp$UzP&z>DyP#uAJoR0V)4eVZ%V_mHYp!9UC8v-;A1(1_<7*_Q;#U(+JyRx z2QInyMwxT2z0P4q4z3k%f8Ttb73uuU{!zl>-M`nb=-t?6Wb`}J_lD}T{M0xscXb!c zDkJITdC-aCTULd6$r!qi$vw@y(vaTZ;3Li-B;*(UC>6YT+tmuYO7@=tF{uK5S8~ zy)Ds8m6G~Nc~LEGYbl5&s&q&4d(w%-#B|L z6TpWj?`b#(`E)&n{S>$LyblXR?lDj`e_BADMu+7mSevVUykFefg-5R^3yDb@pS#}F z7#7xg{hapVg$O-JIRC4H{$j z6b~22k!P}(yNl04V)u`c==3zV%`#sQz*s}s>OS^cMm623n~nuY%6QtP>}TyaqwY=kq5t^0J^;ZuU?W;JS=8%+;%bgUM2Us zCE@X1Hnj-sv(bLa{<8W4v*z});k)u4*D=zerKIg&yC#Ij$*12&tL@~HTjbBOn3v#R zOyZetpDU`Ids`!#>%4xJi@#AZgfmyaAZ9+Jj80!Y*gMn{O~cW62m(VI!HZL&QnH0o zcB^)N|CSr100KBW0cx$ATgWy6LWuyGj)V!QxltJ1p8t)7^sR-Y32(>NVI4rN^`S&E zSU4&S9kuBLiI;246BFHFmHt8A&~1w#8fgRfG~Sm~*XJUpYk2X8xx){^-wqM;_tGUe zGQYGtH!IO*asomDBE*)6TRV}X;dU&&F4W&d**6Ppw~v_*=kHY@JU=zo4UWp-oaZe(3^wPJq8mWTCz#U;*=;G=z&1 zjpHVi(Hee=F@8ooe$F(0K|D?{5J|@Xh~k@()X6EMjRcpFDY0 zOAUXo0xT^ccTDi-M&LoM#*sK=J&#UxAdoy^k|KYSvTl;9canN`lIG9k^S_g{peZ_% zDSGB92Ei%DvPs#SKpEj6Dv2O@dk|B?6kEOyTU`*=afmR}*fSXn0uu;JOaeMY+wGqH zBO-XlcoaD|GPb=qb`mu4P&@t#GyzVSe$1N|4W7Q~(S2y0mPpXN;zXn9Lc9DOZ9M^y zdK{Bfm;psiD+p?0Nr>qsgWbqO%?HwPdxu#>;JUT}yl?6&Y(rqIBi$GPcCC^5QpKe- z#b&kHq3XK6`wFw|fqqU_4%oB+N0?|B23K;RJ!>cwF~ddDUwNtb#*X}uf=-Yt=gJnU%!e}0qL9l!x?qtxm4usCS z@)L(XiybqJF4Rj4{85W1tu@#^In*M|-zIp}KYm1kb0IPrF1^P?uw08Ap3^UzH8Kf9 z9_r1D+yYDJ#?X{&J>S$u{Z?2k)z{DOC>PEwY+)QRep83RDT40r?mRj)td}?w^LE=H zD)OBL^}=`J#f6@^1n6MU0ASK=z8c6A2CaV< z%dJ)Acz$@qzsZ?3%4Oy^5<$2DpEZBxZBbV>q%rFJY+N?Mskr`(tzLepzOu_@I^Y1KTA<1{ z^SI58+x!jYv1MVQa62l6JXQZz7^o?4>xqPqL!W3|0{bd!K*zO1NV4SBm^twa3&qvV z6bKw5DWbT*Z3A!JR5$BNkif@}OO%%mK8xv5*pAcLc5~ZS%CLAbMu~BY6=Vkzk28DY zX!#~cIbaa)i#kM}>VwX&%|Y~Sg}!aI7i)UH;hBQO3gUmJxwZ_SlaoVaL#69XJ{IWI zHysCCylXd1TW1kkulLXLm!ev-BwdvfvVbyh*f_G-N~&@xe%S5Z2{%A%y^{eczv3 zr)KQOmh+?JtU&#p6y-JxObmjDjj%)*&6UmOrp+c@#melyyzjw3+k*s)-9D0oEc|eX z9Sa)BR({4_!23m0UqTsoY#ilCpB35c)B`Ak^)oS>_*L7Z1gwlb{eX!z-vx`R#C8&6L@SRy-!>ZLt<3SRKjV}Jj=2ghpI|GcuY-=9Lyy*RbU)GT^VAzf5 z6ubR~aJ4bHeei;w)}CJ9Q&wa2S_kG)(68f2gVqWV9Iz0Lw6T8Qacy5c28)7WSRz8# zvwyL09ItD^d$QgIlPk@0TlpyN?f*J4D?g5CTno6NjQ?Z5HfC$O10g%Za2g1;bjB!p zj$iBhO|>y->qKnL8L(Gwoym9TjcMDGaTHh|ru>Bdyt0_7y?rgw&Q&N}qY~_^75dhI zDcmDo`DeUJQ@k2QnEHOaCVdzhU9fW_*o_AiWtb3sm$&`mnN|F0U%jkUx!psCUD+5U z;RS@o8p^A2Q1#q-Zv{e52XamZn?nO%-(YrxLu{)^lLr$WP$3#vNiJ+;NsS=q0d%JI z0H0to&ulU;EEf%pv|a9V4&w7*Nax9k<7xXThi^DC=XyuVC|LLC=v3bY*bh-s#`N9` z(J&ZgLWG9VQT*u4^w*+Dbou!!?B~y_0B?_-fb~588;b82#j1!8L3>f^(x+VWQ&k>E z1{Rk>nl5~%SQXD9Bv6|Fi>bSCin4tJzQ08*u`J!NgmiZZEZr&HE!`bTcXzimh;+N8 z2&f>4lnNr9QUZeeaR1(U=Xw5vo!M*7xpvRv_>$eFNKmNuw%>jCTBF=O2?01_%fYK>aNawP_~eNuBREM}#wut2 z6JD@?*GC_?TK@0096*KG8i{=ww8IS#26!Pt;wz%&v}}xMBrc!ZS-HJTT;z5V4I@S-9JkP#V@flUu${7zZLC{e|He)WVZfhB}de+tV0 zjfHV|Wu=XMRhC4EDB_{u6e=()R91Q!*jYq=Rm^*X%W|VLPC-~->720LO&;{O)**Q> zMr#@C+1}q_Wz4|D1SD0BoJ0+wN{uI0gi=V2N)fZ@O?(#yAd6sB9xFoO?fJn2Nd!s#-+_03OLh+udJ?=TuwL+Ctt~~f1-2)Zt&Z*49T}uL) zC6H#0eVX9E4=T=YWXmvlBu8_^v+X_wr z2Mp2?u>s=KYsg9sSvs+(a{+E}ujOy0$+!W~7Kd1x82UplXdj2!oK|I1OK06yjo{bH z-36l0&D)?P#2>4avw6Y|1tY@wu)CK<^BpWEoM}B@xqs=_UnexWzpZYxk};$Vn^tNn z-v6DGAt@pWtf0Kyo6|H?(EQen&rSFtLgJCOxjFkuT(z?sg&+-j-L%A0_I2m`FNy6R zHJ)%_vCMo#9b?7(usWcYc|&<7l{MENOTb^1w?hFkPN~Tz#t=(dG_l10?kHO$?j1rf zP2g|>^M~8XP&{QM(<^KM?4`~Efw07eeU+6^T2NjjUEv(a)l|2jB9`6xjXJLYB$zo% z)pUZ44|VoTBOA4$hm)?oT~M5w>d^26ojB>ox^i^9(^~3UZ;_vW=g*J>64rWOEh#Tk zD0My?rrD1{;F9FVphOD0CT!4_>U9xX8k1M$!@ArY_eXQHR;7+30W}4Oh$zf4QnOi7 zmm_mv#FK9naHv>eH!EMkpP%aIXm^&T8&3Qtfbs`=SL}_~gKYFkOe6H+y6J*-B|kN! zd<=|tConTz4&-RUKxzbvk`F?v_49TRz+?#sg|{?3WBFc0ueo>vMU~j6h61-#LqV9 zAjts|X1AxV`yF2~_MmQpJT<&y(Mu)QIqQ0PPuW$#IHe%=tBR8z#kX^)b=-^8Tqv_0(| z9Zl#Q^9J9_Ne=JzW8m45C$vogiX10ZubrbjX{Zt42GwhJB}fCZm}6D}4r<;ccv_(P z?_bAT`xZT>XtX&t|L|rk5D$g>13QkKFe$(5a=^#OT%g;4uKGe zHD}Dr*7O4PyW35^l;~sP>W`$B04VQ!-$`9Z;t~I9_cw<#b;CiA?f;I_uT+SqTjD77 zJC5S18D=c-^~lYKQ^b>vF`dPDZBm#^F^%ph?MX$?&=;>zOwQ?o0nB|$)o=AWvLX{^EFIB$-t6QqXY7}- zG~t0Myk8HI<*0;Zy5u&QDb||kSu4Bt+JXq700P^c^5M_^trqxhKYUh2x%ZqIFm6(a zDLB`LDr!ltdMB7!ypw}-qS_ak+0kld3hj`JLVeAVe2+7%X4~`j;u?etS~MO8h^X53 zE5%QM5GLZ-aCJPK#8Tlzs61}p9#1JTSE%dEO5|swK49Y)P{<6sIfKjox`ti^n`U-K zP~IcdEFRZ2it zrcjPEp?q&JBh3OkAsq#RxWn%`PobOG1A&~s{cG9w|MG5MZ@#!G^-cwHX8E}R0Z%Xi zM1xMtw9^r0-%YWhvm2#k&w^Qa%T!a;@4h<}l6Z__sCru|;3M6P5ig-?$aq})hZn}o zzvtF6`_3AkoX*+6)mJ|=n`}$P|C;7`@8k7#){$yJ0fRGEDGlp9|7YLgSd8VVAs{@% zo~COYlW!8fPcu>->&f7_Em$weWXV8((HAXprIKXJCBRg}dvy_={^fp8&r0z#=17!8 zjyHi_1QRXRq7X!PF4^48h(QZ`1}N8ZB$L|TzhuDMqMdqBcK`u50AN+5QTb>{LB{HB ztX~Ut3L$a9C`FElUXleCrhpP8v?AfSeT$axQ0FK0bz8hB3((yYmumep85F-_gdUR% z!u$AB@a^-`GnM2u+ZW#%0&BTW6X_wsWd-qE=NVWgv(?1IubkgjAD^bj6ut`j(j6Lf zfkl=uxQ$C7ngG>Hdb!NV@Dqt)mVS9wM~M>0-3PKsj{uX1OA+;ySWmF!61~F)lYY?k z&4^|JCEG##n)`ZCwAW~TvB)ne=d%AMT#J}$h}SmWiAWHFOGT-p{NYNxq&}E}ctd-N z%BfO5t&mV5+LsoF+j)I7H`!S+n196$3vn%J*!40G+sm%MQsYH=rJzSB?X|HMDQmVaRGk+V)CIPgw;cR2ir>C%(?s)8CFJAm1mqm3&+xh=QVF6#Q z_x~CA7>#CFS(2Ty@339aDI}) zYiE=Ak+Q>J1)M1(4k1%pRJ@Sl#$A`?>BDzy2)*oVgoKmwgH73vH{BEL>2p~)sgscc z&DsG;Mf>r(%5sq~ep&tyUHruN>hURj9LULSCZ=539Y0M1KYCPVFPi8dSY{7=MFNp= zl4otk%$loMpfDa7S+cA_aWE^+{K~|0#B~X(z>14_{^onSI|8fLN^Xj-keO-&2w*S# ztntQ%iijbFQXktINN+nL0v~(qtA8}GS#vjSFjg2pj-8qNUfnE5kz^zP@Ksua@kt(- z!_Sm%vLt$QlS-mY781cGmW|z(rD2a?m8&?Z+?1vG(Q9lo--+T%0kW{f5I`)xRbt>9 zN6Xxd>7q87&Y>0SCBxmOj^68rL3MIOAc~K!%(d98(0Du** z;He?A63ezJM+}SvQz(K#)f|bKtAu443Z4H_SzH_1rj}RShWP_CE2x9mkbg_Di~?Q- zF+_6NCvee>$mNWRj7Li##j*Z+hVsm?2?)&Ylv^vo?ql zn?Q-J*tqdX5b`_W`1db6*ZN2%#T;H|2GhOQ0cJts&QPKSzW; z&x1WrZ$H~5f))tMH*FxHmCH?IFXCv(uVpXhX~^qlFA+f%P44H>jkt1*@4xzf@PMtV z=Fl+9D96lb`UvzIzeRxud$(wqp`NJv6Z8#+l5Xn3Uw9D*~`%|IubwzYT0RQJ>htL-T3;h@yWWg zoQBm^>FAY%Rq%NRF5Vd1+>cL@AhtGplg=NNt@Y`1V0$`BqB9GH4UoA01hdWo@{xYN z**gU`WPEPO{n*f-#y-%E=FA`F9JFj0gzZDF$AtG#gD`fPBE6v#*PMTxsK)(b*ik=O z^9W-@>9xHAq5>pf-F}{78?N44fgyP>zoE~`FTD7etj)xrcrsosw>~NkDL}3}rJdAA z;<#1>*XTLgVPcmM9K;CmJ4HLzYYRLX%fpq;%RFE%HtDpYbvl~7Q(>PXdKxjpTn|oX z90#m}Bz~>G#AE~L03%zEK1v`y?liMZ94Q@)3$GqwNLL4nY?x+jVizzZ2w2h57|Zn* z!%GyU@8w(I+-tW}fP$!}XJDDdG2PT=$rxEYJRW}_fG20nM`YKxor^uoeT6Rjt5&pl z);P^{P8#>#k8kK^Cp~5r6~-r8RZl=1x>wGWvAR6=&2mDKomq;1_v^l$J4FsTHxI4$5(#R*hVA;Yc+p^s=R6O~W6~ms?qGx}y?9rm^R?kPYMN7dXz_Ar` z$+aj{zLtk6V}5+t${m!(;{RgTi<0-5d37Pb=Y_`!t%sdTJ(FzbmSoaVkTvgO#x$Qs zv)nqPQRk1zFwgNK_brLj>sN`l*N_*>4tFf|QAA!dRFx`EYvPrDDJ=2s=MiG3IC+#s z&Sl2h{2Mz3ohe$haddCrSlV0J0Eksjov@Cg{ zf7tBgQ^D^c_e#Uk7(LFVvQFL#0D)K=g2Pv)?X|R91We{;!Ze<0B-&eqF$jY5 zGoO~fKNp{z>fr8q%BkQ{QE)utLdhK2KQTL}JT1P-;?;>#b|E8ZgBkMSw z@!?Tf+zlVDKK$uZ&yMfp7E68)K3Q)M;`*&L=gr{jOnm51A5OjJAW|I`CAJNxxz7jm3G2 zBjkkKiORD!-VnF*Hx%?Ym-kYkX(4Am{w&f$Be(=w-@&Z{O7bgWchVoUcR54+B*)PH zVC7B)8AZ$^WuY2C^to~KiqOv8mF(=L^Vd$Ko749b_aFb<0R+!zdn@GX)4)#^h0$P# zm+=lVxQ_1_tg*Tc5CCHCN3l}aO19Hc#zQBLS7nOl`1`RNB?_NA1{4;@dJ0tssFIuv5OaSR- zHW4j3&MUS&CW_Z0cNy@*YlJJKLQW+m^m=@jGCHuwUoZd6yxfZ=UO{Zj;GemHp@n}a zmZ(=K|MQq{%Rm4b%@{3nBt?vTZ6rVv046mb;jaOQ386%o$0BgY$@jqQ#%LhdhJ2VI zO%U&rcBEXuCy3}h_*Os2nXOmR>w=&BGE{Iv?a!FpJ3iPy;=rWdP}gIhWJqox#W6s~N@6ZyU)EEtoUnWT)#EW(DqhE5gxjr0u8L@ThJc=LOj&=+^q97=Lj z3+-?G)kIVh9e{}?7yvOy5k7FaS(Jp|Dr8o^cVO((sXP(YRU?5yQ+`w5S|~&lPzL!e z3vgGXK>kgXoo>3P`E&Py_oPoKu=t~cqmX0Yv}1;?k6 zejo|sub`>uVG~*UBG6N7*^PoVq&>LoHO7)MoZJgnni{PDe8ldXJye`z|3+>s+r{N5 zD-^Q+t$Eg8MXktj-=#80H8T>vkNdja&fS@Uek@d;2+sqrO^bASjN5pG6do-JuSGiD zlmCil)dzCGZ<}6+NgjXZ%ej(`z}?J%aNm!WgiG%!|GOxX3Vrvl@)HCTPtpoJsG`yJ z;cv(~wO@fC|DWWT-?1adm<`AjS&>UoK@ulfr~9DTF)5lGxftpHQQp?F(O85m`n?%8 zW6@MG_1E?c#IycKd8gfog0`n9(T<&d%Lr|7A(Qj!AiKb> zRuoYGs<>9pMmrlAbZ--lsL?H_FO@Ded4_I$S8sqnoRXM(sFlk#5J$?Hg_{x!o{QjE zAR2%BQgw1NS2CaH>uY}um(duRsSzn(yS^BE0W6JEB;v2SEg<{wbmYhC}K6 z)Pu!^zB}v{B2p^1rU0CYng3~Do^EA*md5=|x$8v)#juBQ)F*lxvFGS7x5j~A ze@dIx)ee{jUu0s!Q`L;EvrSW2k{^nHm4pVKLJL1>dOYo2-!lL7l7ykskcj~yJSOA4_Ah>mq{MF3r z>#Mr&pJ18qzoCA#c$%rStJ)DG*u@+&8HRgX>C|fN0vhb^*Yw2tE9~`{X}{=e#hC|W zo*)DhI@v&3pKs#}MQ)FLHCcbF5i1Dp5-lhS$b8-`S`$#?2a5b#-W-yLa+B!7cw46D zQXp3y3?fp;M_Cp=l|L)!4)k4_Db@vq7maM5U@x{x#PTn&aSERr#t9_U(i@&E_|(wm zRH14#sb_K@M;;Z4YmMcLNKO0k_Poi!Fp27qnlQL(-pjK>Lvxu|T}LYpxv|_9{+>8$ zMI_C(WD(T=_M+d|ZGVHBWL(FhIeuih&>B_vV2~x_h>eJ`CFs{-I|E+)i+r__7|3kg z7~ya)y5(QD*o&aO+plX25*MkDkqWDxx64(Z>~zpHfuxoat!)F)M(RCMMl&Z_y= zC|qsmA`W*lpr94lAA%?s!F=N?B7lAzZZAE8Wxq&6vE6 zFMhMKqjgk_nhbG${ce`35@5WKMO9m%r16H#WGBVdCbxF2y0(`@H$YHcs)q;boob!T0Om(QB`Bix9sPucVmn^ zOUQaTS7{M6>nH>DR@;4nmb%JyHYVx$Y*h>ROlwYl@4J^B7|=A6O#iRiB^R?!qF%RD^-{^(it;3cK^+c=tv6+>;IbVtxWsR(V zl#cxHRXSKpM>xV3A83Jz0u(8b$T2)VGjhD4!CDap{ofbWj75*3pCU-~rzis6BukLQ zfXnN%GbwC=JyWBxQkSZ@SU1B0&TTyWjj2-^J=8f5aWPBkHbf>pa;w1kcudL(o;Vw_ zsJTQHa+@jkbx;jQ+B~!VJr$`A?-kQ<@CaNXn~D%#StU&v?FteG&O9 z7O9IpW&kjL;zSYwx4yTd|1`TJBRr;|`$Dhu@IK**47PF%HiF$v1xZzEJjVd@O9Ejy zsn}PbEX>sra@G`b>$Zu>X@1sZUoyD&r?he%Yw}YBD%*)V3h>l~vihIy7_U=u1f~5> z;$NS50*ONBP2Hv-N^jnYs;GS~SZ@_3iP?K7YmTSB8hGy zu-SW-CYPp?MV$aT`kijwd(~on>|)cDuhCx%aQU?0Dx0C#oaiFb7NB3d4Lcm8yIu4K zI3Y5__~6F96Bs!dPA&wDUt945dI+ynbgq})Ml(CcRC9C7s)l~nO~dcuaRZvfKTh(B zRfJWD(E}{ARMx&PwcE@e9{@tvqa*MVN4ckPLZS`oKX(-jV(@D5o3-uq!wIFo)gvu& zafr}(2>0u$-GB~ptEez?#mS@NXZ#zS4GsZ_^gA#C#Cq`Gc8^#2 z@zh=l3<#6{up%Y9xuYtW_30UpTJFrOQ*?xz9~WjsbgeO7KG*gaR6v z)f-=HH?a#{1!(cpOhT(nrZi7YK9gTuJZC*}iM5W9s+uzeJmw)6TE!;cdvuzuN8vDQ7SpPuXzV>r2y4;O))hF}nYJyG3VLmu_KT*mH;AnT%LU2z~ARN%CEkKUuSb zdj^y(61UwLtJUV!A=EI0d^qTx%#vyG@6qph&hv+1kl)Qk@ii3#v#nyK6e~zY)_6tI>h*jeQJbTN z$hrvYAD*(`1TXGEEgD|^xZYZxS)Zuwzf3i~q?p(FSK9E)Tv|NoiVc^K28i2^-cbHn z^x`U-3vqxBQsNy(`u1t_9g6G(zQu?FU{u$^uRe>epgq>B#>mG|h<8$pBY3^%Dl4{-ws2{ zV##DokD4Ct!pRjNrQ0}G!2rLnxIa!+;>`xxt%5OnCn(7P_IRO@`&j2M3b{R5FG)iJ z=Ig5H=QoP=DekajOTOQ}R2;l%it?uUU>R=YH6sEU#aMSO%TWCJLUBmDPr(z=r8U#b zSi2FiC9Mf0Z#(*T^f$uOcF!{?2gSV+i3s6{6ROl2+(X;H`;!H`kJx`eH-Fg8Ic14? zFN$>E^1%D|crt|W0@%}V*5&B4+z^P-Iv)mu+V|i>Tu3=D=tJ6Vktbpb_gBDAdq%~r zM_4;E6+2ZE8^aOAtBl*GnT!p>yY?iPvoWJVVW~o~9pwJOqM(8v7$#?|2g;;vjKDoR zd^ie^P!6^W$N!W8JcJWm$U%s;@V?>Tt%K0u zlVkSA$x0l7-z1+%^Iy-`WY7_NkC`Iq)~iUQ2GFL9&m~_hhs`M zrXIpwmo46hNg4ix*k_>|uy%rAHdJSvLDIRm6BrR)WAj~RG)2#9a}aG2xOg*P=njJtV}l0z4g)z2iQ5NyW4#{{9o%X3(;uLz|s zAL*OF2^zHMO^V!(pN&Mvdgsg%2!fIdnTHD*pb!$n4+#}Q-gY1fg=9%dkQWGCGDUnc zA-M-Z{C^uWMSNV(rbQ=w_%?}ATu93GQCjr)J6601$aKZU!9~-_g8BIZbEhCq3_{7l zPszDc=`j!Q?Wa_TASggQ>fFka`pOp-q?arzsrpJCDD}@3xgx)L6`#oq=E&=+3$Rb& zFdotuF?{j>;l_vwC08k=rs;EouDJvo3FTo{P{S@XrEGyQk>qYu!ixT?t5^onIJ7FV z2n`e+Geaxa7bX{B<1b&deEluH<3M_^uA`ho;*XOfQ$|LZfiuz2-zd_t;}e#FKoQlW%uRENH$L^F&5sA z!n(ZDmFln(^)q3=`jd5DHH@HN2T@GQ0b?rRJ)dmouT97qZQpLt*Qg^>Mkw&AK(_9X zgx}ay6_1p+bESyOs{ohECCE7fCjsHw72w*}?K*VrIuhU-iy(+WxP7>Gn>TdrK#6=t zxPQyT?kB=(&x4kr!07sJpfrL&dc)(k+w)<``69p*9pDB1;|%WcBK+e?AnHw-??T?= zP5lS^qp$|nl8=NnWm^l*FIyXf*yo&>w$Fr};>iF>O9&m{nj8m#e&GK@c?SkK_XN2A zd8E7p5{0OIdIG*6uW%{@V*`T{dxBE`1Z9c_=LQDHlB)`d2!waX?*MH70cqO2xbP6q zA3phpUNbWW*m4>oc&?ourE&&Q?-nxG9|7Ut0^DZu9w~3PtuLhCMPCdA=+e8n?k{=J z8hL*D^RoEb8%W`U5fnk(6M^6BMJN_|YUopLRL7CuR|H(6Y3CUS5Gv(_^46F=^9Rh0 z5Th~U%mqbw!~*Qyuk19%bR%c9B?F8Px3CU`95S!0fJ+YKzoqJgLI|cHZ7tMV$mm4P zcw7*q+nQa{2KVu0TBVZq9Dr*nY)EKps4f}L(xCtNTDI+ocS#dQNM(7GE%c_i1scn;9Q|Pqx zW?bdmS8ZlQ3$tTx+D`;o6?dj+ro}yw#+Q7A!-ydrh{_-o*QUJ9 zIlP2c)VlWtStL#ncmcHE1!ZM_NnyQ;n`xK->x7wbL4Op<2DK&YKT}uilT<0>L~EGj zu3Y67u4q{tVdV}Dxa`7P)eJ_T@Wa-7%`nzY6eWw1#X7tW&O%)2ez z^(!(6#%^XH3kQ^839B+GYQGM4=(q)XniL0$$G=a&5&21fAj_RA50oY)(Ge;wwJU9s zlY9lhVe7BrzN_Mws1^>X<~GGSx2_VGs8N)tk({DpS*?~0sS%`l84QSPG0A#!TMjHT z>FLv>UuIRnvoqTu8?B_9-6YenMhr$!u2<6LF@%i)DCcbG`fVgJ8HrFMbi=Y~4T-6C z+pxA&vQt-a5cbrgSepYOnbd)Fj8viO@788& zF1PI=jl?4f8=)K=p}ikrcsfdH4m(G}nD0mV%}2LUMy56+X!i9{!NHL&!~hl$);%y_ zVA%He7V5ex_5Lq^R3#YzFa#YXT9QS`MbPTlfFw|4C|Pw3Mrsl$U^bE#14P;%8D@9< zB&NW2G{W)mE}f$WCd5EEoPp9ELxqDzUy5;>X({LFP?r>%>WnDvW7aTL=hu{PD;G(qxGZd1@lgD$OyXh!;ov zbOYb!LmEV3I+hP#9#v#ZAX+!M3v8GOtVB-L=-B9a@l+LvWi&k!lZ*4g+{!+J`efIB= zX;A0y2wcbVgW!E2x&mKc>bpbu_tR1?^l|vf0HyGx=<*N))Ykg+q5xDSmH_ffl!-?UUu@{%L zB`PhlU*6Lm^O_&8Az&2i$5wPF`~MtV#ZKhUYQt^AE-3udk%&nIby5*!3Nawc=JP9a z1S12@iA`hI{>586fYw*;l73C03S5TD3;O6oGr3Dm`Z0C%U($R03MCSnr}wlpFbZL~ zwam3eS>A5RlJoG6yOo}MS^hgr=qfO6tVg@e@-Gk+@&8la3=xEACAKhZe#VH$zeQCB zv41PlDcVbf++z#WOl2~oWu_nVM>W&AjEYyqWURm5=WuLd-x0I1s7R()+}uEg>fx*e zB#%4%fNH&z{{}&E-mot=V87BEl9=OIdPTzR@qly9As=ruQ>0iA`1-c1hpZ&LDTjzn zhj3$cC|UIN_jbEKj7JCL5lU%XxYT)x=WVuyOLtvF;vGAhvJ!#Ucu6bo=Bl7wm^^#8 zf+KTPzzni*3Eqv*%?#J>_-mcrUB|8C-N}q3^$I_}|05 zg=kEvrRC(~lcX|@CN-wuOiT5%R`G`Dee++o=>Det&HviMZFj$m!IJj-m5mATI-fk0 zIqE7_%9X+Qr=cK{F9VPJqY9H7%L|d87GOqW>*%LhepA8^6r&Y>FgdY=7-AQr%~%5m zY_o&_)myUM=O+8Mio!qrxAN2?BQ(OggP{gsGh|gF3tz^2$6_1*eWSF1;~OR)=_N`% z&Ibkg&!zTHZVs6@qv5b96Y0oLr6buJ#Ok`c+9wav1gBNxP;ljJ_g_MPRZx zr>Vu&)s{78yb960BP$K!*x7BeALQ4RX}xr=QI3FBO{&F^9sH8bj1uO0liY52WcXfs zf}@eBA>;tMh8`zR?7*?eWZ|xi$#Q(L^um>+Gf3Dquc@7k?68SvB!*M7Urt5k^|0RZ zuSyD$q@y>tKh0L#jc%Jr`ZgGuPhN44=WAkv>1&WhuV;l1FmSbx97Y15G5>_emr+DtpG??R+Sy8I02qm{bjQzeH5W;0((-CBfcHwPvw zw{?&`%|$=Mlk0}pB?j)laiCk;HoAT2QKg-s`jx?<7$ElZ($W3(^oA6S@zl%vf#i&^ zL7MO2o)V!Rh6?lOsF#fvI3TLk<}LbdMJPjh*b=m##xE-uX$hT=~^BP=8C-AwUf+5^!FGCS7-bm4dvl6+-+r*RLjqU@IQpGO%~;(wP2^N^K|I?LE$Y^hMe?bl z%)4-vC~HWh;z&!&Cob9)6+(I+1%+ItxcVptFU&R;@(^2neZNTD*EhB3&bUO1%FQ2c zDhRYwjD|qu`6hvGtpYxNW`Zl8I?-v@I00xb(HH`otFKSg`{JGctdgnY7h6TD8*f-- zsKHT!g3=+J&AY&4-D%Z{3)fO7HLHY(xo&jA%Q-W>>@$dNVB)=w?RdI5klAwZMu?Ab zH*5eIn( z>V;4nvkQfSKTLOOf=`dFBg~$AC4R)r_DMeJF9%%J;Mq@N1nCOub&{TW8Z?D^%26~m z3-+<{v{?%HF(@dFWnF>0PhGJI;qF_!kU39FXyr48U4TFFq+Q;qFn=$%Tcy>;l{VQTOcJAj?T184kP1DQ=YcV*B9nHS6_6fGe z@=(Lu;4X6|sm4e^62dTv8RqWg!r;VcFq5O5XL!Y86bLm|D!hnsmf|$N#!BQNS!k=` za+4D)%Ixm{!W3Le3*NgxEiYG^<=u_c_qUhrN>X3onW!|v=koAwOi?qp!9~Ak!@_1G zTU&Jr9Kd+rD(lmf@vW?>hndn`rIC^WMJSq=%3O~uI5e6+Q6CN^EWrH-#60?*H*kN< zYjth*qbpBwu$}R>%69~_g3s%ke+ma7e^$Q_)8!BI$hWrV%#h%5#xNREM8-QO!=K!P zaqpfaztm3o*%H))*wDm|v~t+U=pCmzscL#wXaAHQ|>vP01kNVxL3+S5!7LRtCNki$Bdf3r)vcoofv4l;?4X zmq~$}XMnpVk_B>4!=7^zKxVM!eM)E{@tsXRtG<)n?HCZ*86#SNezH?6_L z7Oy&FJ-lJeHyWRUPK0cZpYi~oYqV!S0ar*?u{zx+j=bh7NzK<)aeX)|G z@My2Vit!1aKRM~#E^TbZ%5{^Qm1tzbhbr7w$+RnEOSr3rgy>hdoo?Bz!92B$wROlJ z-u_@IRz2orz|2!GicT0xd?kaSYcDQar|3`f)H0OMDTvmHgMMwx8EnS~$)U~~~B(h!N z(dQ?>GA{XALMhaeCU!u0()#h3t*B(qd26~2&l6rKhh4ROpm`zul5Nzt-@9psHre>= z%qOVAcQKNx@@Sq*Z|2rZr3Hy&7uLbQt1o=1w!= z_n#Ds(eS2uTMVrKSTqaU($=o($I9Y+Rm-(23ySZ@Y=m2WzhB-pxDG8Zed-?Au*u5) zsprRs%X;1y;rcJ9->(V23hCK-wux|(TPs_2x*yzACb+A`vf9!Y9sZ+^zG;V|xdN>| z3SPY+E}2qq-Ff+tMe%LRmEhl>A+yl9n;NW@{28s7ve`NUg_ z#WWhmEdDWxU`vSZO)Tx@NOR(LuTQAPCY8h{&j|8k=SL^L2gcbXB!+c`#*#;O*Tg6p zCaZMEjZP-iOeGK5Bq@H0eicB}G)1Iat=+mDf0iH9p^`k?tJ5=OTQTK3u$=s5it4S( z3%_NFabt>|2@jZC}`U_&YLk+Qz3O}FKuK#4bqurQIo3qEDBpCkz?Mi z{UX)&=EWDsG}QCRcCn0%{N!S?^wau`fXGxg(v)bw^q_hQv7GeGy>x=T_$bzw=b|q$ zg42YZ+@O6KOwf3MKstG3(p_&XmN9m!S0>$N>cdSEAz8-Nb8kBKjDw(zXUbVp`^k)n zs;uudu8dg;6ZJN3SQk<00);7nhQ#H-xWV|e?HsgsIa$1PV(wW`t_0LaArYbUUP@(! z=BV9G<(AN1C0DF4yX=vQrie9x=10zFfOm3dfO)Ndvh3m68htcQ`=Pq*xgXh{8SJZ@ zQRc@xllh9f5G1k&ikma%TbnuN(QW2`c$FstE%=3THEv0jz_(W1=u$n(nm`6ZWW13Xed7EeB zQisW3o34`Ms8$iyM|6Z`2UV-`xXU+RO=0DTE`|nLht!c2)nV48hPhNvO%dTvnMIja zEyvX-_BU*FmTbJMPn|9&nt=YYCRp7-W8Ch(3OT6BN~#U(CHlY+z7^XL<5K8#P$Ab? zSnd+7#?g3^pq1%GkmrTbI|p-&O}1b!Z4GHqDsZ7UXriQyd}dM~cb5{yp58>2G)ga-S0NC{zzJG+s`fAIdiW+eRK?)yy1jR^~ z^IC0_Bjl_0ms?EEnRf0+?i#m)f1o`c(ZO?Ab~s)AGU3&R$?KAk*DE+QmVB^pbFYoP z@B%X+ws6=x1RQ~ap^z9xUTD1i3=*ac*ti!)7LuR@0k^6ksIkUqiy&Y&bf6k|Q>~&V za7JLo2XC*y$Iu1RiGU2x2$bglfyq6=O+BGAJ>g9~0*}SX3hd}6>^N)9#~4atQ*ZK2 zZ|Y%h`ao|BvNv13FW0p%U$U1vvaeXOFBt&ULqRGz`>Uxjv^Ib*)&TSwSo9J7Er~;~7;rZb@W~83a3y|k2FD{mo>16dZ~3%^L1~XhTBSxS3o)`}Yll>nMm} z%-5`Eq-mg$6U>VoR|o?O=zvw5$JJ-YHIE+CALH?W2~8TXqT7T~%7jVtgaTf#{NRL@ z+XUMN&`x90;prspTt5nT9N9eSN;BwwG$}jS?>#%|tMRT&a`4Gt(yTLlGOv+oNjSF- ztnKl}90B{=MzCQG0lmTd&Iva^A0o+p>uR!1RJ`tF=EZ zM!&iYnXWCF_D-7ST%{JQfSDrT6i?xgMeFGe650yFT5Xo9;r{^8C>sk+};=9 z_4ufdm4?-fxDe!6V@xJB&)2`B8jmSjZTMRBVfDU4Sh3~y7M^lOaEJVeMiJaq03Ok@ z$JqA^E_hxAj0FN9<|D{89|cE_a?FnM;Eg%Vyq`_UCHey0_9CcnY;2sJZYi0=9-6~1 zZPE#%er$OYr~cRSW)}Hh%Nq$VjeuPO0k{Z)Yye>4kfbeQ2v9Ku&cshk(Lm$PN!`{9 zDYx__HJODhh_y6H;LoEXN4k&jRpB1|86OR-33{wCjF5OI2qqSkTr|!RNG;h9O*A4HDW0KEJ;;dUAL&>6f24mb?=4Uy#k zLfc+%C}+M{v}9O?zg)&)|GJ(jE>(v&)Z}Aa5aC`H<^I9Oy=u*TIV<(Uw?Ts(Zgye~ z7M_FUam*E=`jzh*%Y{;_?;Td+KjaeKt$czGyBK_^N?oZkc0l%6r#yKCgWY_xRx6 zx|XUC_aT#7_4}Cn_tA$BB^LY}$KO&O9lVzBq9$vT;cH(szmc1w>rP8^e_LdCTl^>s z`Ee7z4*9q|d;9gCd-xC84PpYb^k_SxpDVl zmEt7(pH#V%)Fx5uPa3UF&VP|Vzp;FC|9Kz#Q}Xa9Z`s!M!6sk+4|R?$H@Pk0VT&OvDsQ9J+@t5YwFKyVi<_k!k7ev=%+bC^YTYB4|Y}?{w+f-}Yif6}ac-zin$Jlb` zdFzf&*^cYUj@tJf&*2?!o?Xim40PKRt38O6q38cn-dcOH9(#|JcVg>a^2fc@lfC~- zc}wq;=(e?Z@4A2ZALR`@sN^}Q*82Y_@3e!4)`Q0k=_BR+8g}@G=dk1Bz8@`;ME0<+ z^>E;k@;*6y3p*O&IU1t-Mf3*n$YT4SZ2P%lOb_qOo*aFmdq4kTXHM(b&g1wi&(2Eg zvBk&ZZ)w{HQ|p{&>v?kMzhpOjd8P4^!&v*5#p%_5lsE6So%XeZ z=k@dS>qp1i_0zTc>Gh-I&2HFO=WLdGcLTWv8gBXBq7?N-J5+i!(>@g&}C*+8maJ&=ZT|@FIxF_}E zc?#CH<%IM*ifjnM5!8R4O#U0cgjVqINwm*7ntV-N>MG{RRXz5i zS@Ck3{F>lt6Y*qIz;)Bd*VnZvS3vRAsvR7!nBZI!r@7B;p2)Ax zxh0fB>%1Wl=tX2&rv`B6sFkj(eUf}3@HzR%ST*CTh9C$zw{_?4Vx5&N+1U0JjK*4- z${+l|87B6CSdLxi=T}u_&hM@kd*wdK4jJfne@NewsPj0$Yc*2GfZ}P%H3Hg-UOQt)pu9i+X?ue=9B3huCi-eQAq^fpC{pL~I<&B5FJYL>fW57f0AVV&? zKcJ0)^ncnoGuB1eE%F&eE1XgByY!CwILZ+;!^Xu%b(k8h(yM*C&dMP)MS)_Nei@nH zXDxoJIbdwvtj7Q6rK56yfT-5fC)LlU7)0fCG_!oz`PFk_nYw5-;8`dofLEH|q74`p zyO5;cc5{go><=>31;)gwwE1*O)A)t{y3tBPE~F5O)nPA5_yaM&ssLGSE*cb!!LLsCf# zD2r3(TP7OC^nS_6J4#Q@ zjo2!>$G)yw_@uA7CDOZe@z*V2Ae9j%^Jj0h|HYSNS+-HO?0o-8(f4vC#wQ>bGT|Ih z-1I%)_}zpjb-p42BNk8OPRDN+={|bg{7>!a9tCRU2|3G;VKc(wfK3NNfKKE0fLc%< zwua+uR!1@H{E$)cPrz2c0qvIX1qhS=$ znzGcN67qYTcvurZTmneD6L(jRIWFhyl+SmHiETxq80*$ZA9Sivot?x1BEyO&xUYD) zA-<>sJ&Ar_%sGLHmmDe~-3vo>3R+UX5`I-FRq?kD_Cx9^sn9BpTo&S%%h_ zzNLP}+gADVNB8k4{kCXKh^k-L);M!dLoh*OW%`sPjFjC)`>C2avMQjX z%aoKH2InK{?8_`-y|cP@+~p9VVX%zztN=!xMnZZ0}U=(DG z!_t4C)>e4o{cGFy22uNcMHvchUAF|PlWJ6{H3Tr1hqkyUY1;E07*EEwB=2L?uv%lp zmaW>0Pe{t5X}n8os6G!cJD`<(-qY1K`;EbVi^NcJi>A0T@X_y#5p%qo{RoS&hgmfp z(gv$0JlX`o+$?mW%5^^Ln`cMwEGhdqVX99;J6_E{)r8%L<)sKb?<2aD)9lso6?(|wV0RT6`}z;0sWR~bBEY%9_(>Gx+W?Ob z8ah>gdHaT?`hK}O?s$zQ6#<^xr&yV<5fAx}ewJZkfP;~0)!VEoqKS^XGR>mkf#B~s+aiNj>2CGYH0m)W* zd>$*`mnuLP(?`3-3l*3-K!oM~X8m@f@8+BX`F&)&Qjp{Wk>uhXu{ehrbc036(}jDQ zUsb0cvcwh4J|GLt7@PwzN@5EUDG#VsW+>QBP%2_%;)mG?;9jWnD|KKN?L=7?@bpL~4ZMS#NUi1dZ#3 z`)5>HZ{2hWnzZ@jpEGK`eXAu@ zhqDEL9#(7E?EloiSf~#VsB^J7kQGJpLFY&{REJW2x)N~x+(P>-M=>c0YH^+ErZqFk zP)=8mO76Fi2Jzz6`~k=11#}1W5!#+a3BMHEK}BmXsmyBj5eiltDhc{IuvQf-bG@=m zBb!-g>FmV#=6ry5XiXN-1vBGFGmiV3flH&dKU*IMLbfT80D$M)7!#9~ zpw#hSBMCr_>nyfhpPm9d#3)yGt_CsePa$M8;X z#(zJM18$3ZFtE?m;6FA*Kgq$z-T^O8D3VMeNtcl?pr8;Jqu*-7=Kf#Z+^zp7H}~S}(e?fT z_GlWrH~4333Hx~&yIzl7F8uTEHFiD*J2Hr!euy1)!1n2%d^`F2_3PI6EgX)E6L$Zj z>KAmUMtr?t;yRor>^Kqv(CO1~szkK?eW~n-NCOc*<3P*jXU{dYRo16xb^ z-{{=@d~BM{j~e#h)fAWIbjx+7FY9Xh^79(nt8s2F4$W<7XsB#1`7bxO_P^ZR%F4?B zoz5-GthDQ}{uj#4&dtuq$VkPcrX*oP^22eMZv4}D!-9LCqvH}{F|o0+k&%)A<>oqB zVNLX~YRWri`W27Sp<$soH#aCK>ha^p{sB)PJb3W0o9pfE{V$y>A6+hmYWs)I?NEJO zFB{V4gf6WoKtcAP_7pEKE#H|F3Q?+5aCm z_e5<@GEMA!e}=K7UK-CL%;@)M~Z6;3+?Y%z5Wo$Z&{^RBvzOKJb_?eS9qzz_XoD9^oBlL^0&Ov-|G2r2q^Yugl3HNEv>E@n zxi#C*++qzipq?XqJNfRfh)bjgQ(b7}{kU4` z_Q~o^1}s{XPdSs!LGHcZ9cr|KW=Wlx>MrBgCWYMhu7qAY&j@R#3kHN~!$TX=;_FR^LPiz12Y#27Qy)qb)^$LaGn%KR3 zIPckU^uo@gR-+VYZgAZ)X{J*zv2^(vJH`Co<~wP-w}@bK3X8k!#n1IbsouNG3u*-c zVWv;Ny(L*GSx-U^aNfZz5-s*TUMl}Zdiznh%j00ZlN-^*GQtscof~cMy}No^VbW4S z>79l*f?%ya_w7791l~4&|FX1l524U`Vy$rYt9{$Xn?Gj>82)Ox%Hfy4R#^|^GrOb| zi$Jfts)Cd!Lc%e>!_|d*u3qS2nXi9r_;~z?XxE=%#G;gc`P21+Z@}#~x{@}JITD-9 z*ZqN}XxS44SuoQEUM50A*1Nxncm~Y;eJQqy%#k=?h=aa`cjXjVMf)s7G0#9j`~zYG z5q$=RR~%+!8ax%ur|@8f%>*nqE2|Ih#y7MKzoQo|6a{du#v3MzZO(N>e*zd5?@48iE=Mr*>WfH&;Vz!hjnU zwugt>68VMXsrF+*z@fMNaTQhcUWjQ_j8a=OZ-ggD3a|=}|2Qhw6EqtBE5wVlLqj1E zgbJK%Va}x26hzfv0hhiF`h4?9Q&U&Cs=|CO;l2CA)ckNdk-lJFj^$6)L2nW)&*VR} zEl5Jvhxmif%1o)NkfsbukMmmt0dw2gav&y4*}+=qGYB}TF|Y^Q0}jYxsdsDIkt}mL zPn|hc!d^%u#P{7;vX3BZ?6{p^dsbr@X05(As5&8Cmd%;DsFTBy_<6xqQnAGlDm) zHU~1FID4ijflEL0f0Nt_?HAg zv)M-|gNcApHgK>EXtKH0^pONCsW6q!5R*NlNU^_u=&y9NW=M3;EdS*J{=3~cSh#HG zYs%TCVbUg)lfU&lwk-d^PvpA^L|-~qXghvXtc30zG<2J8B!od4o>UR7f3KM+*K>WU`cBuJ&&2NBbLerlf8csJ>W&nSlIVs;57L_D2sARS(Jl3SiJWZ%y* zd5M)bdttR=k~m0*Tk=hni%7hq6RA5!bTDxT?(b zLu6Dig99$+%E7XSQ9A^RV_cU8ncSE)IR_k4e0)vW3Rc?M?)`H9OoV=15&IyEs>_S< zen@W3AGYU3zrYNH>x+`_X6VM&NG+W}41vA_^h16m5w1837lmVSm7c<@%Kpp3g^TQ} zP@4oo6kg?FTn#SQ#{4^#6!Z!Wv4IPgw7)tzdi*pw5L21zkDo~3gZ(g|8*SLE4S8EI z%$o$C{09^S+@2*<0V8SG;A05F7E((|rWrW-s|`+DctTv2KRn~XZg0ViFYB!V$?^I? z^EU8`c9el3D_Wev90n9GBeKookggO-5rB^QurDjX;(-U`Y*1MVYC;0Va@=9p$6q*P zloF4b&ywy0o~=uc(7k#1LFUyY`l~;%WSA75Z?$=Ur6~+oCH5?=03pR2Cj>f)4bxQy zX`n|Gxk0G==S+YJJtJ_U6ddtTnYn@L>F00ymnC>%zVGj!J-Q0-=nu)8UR4O_%Kvl5 zQvkp-UWjkzbr*Bs=1bt0q3Dk0M4m7(%SBFH-Ms5XM0p``t&cnwu=T;b{91n8ZlHK{ z))1i5RTW_$;jP8zszlQVy?O>v=1 zapC82sLnX&Ecu#@yQ=5f&G~3>@*>cn2PHA>}%W zPJPd2Ck6g=LaM)dQ?5^>6oorxCO&V1g4yt}kN%pt_-2;B5yW>;#4tjyhpusbxA_9m z<_t);k-)^UoWu#&LxdH=HiuYycpLaSzJPRiX?{luqZpXV3&@ z9y@3sVfQfcAfX52X+RbSEqI;e*pU3wiRaJzo;w&%TqWbWFZn7eB}O8o-yEa){i#__ zNbsG+$t4V#mfIUNy!%%o7tP~E2yk=DSQr9`LZYtV>KBMRc)KBxvFO+;RKRvLO&J)4 zj5&fvxW-}#q|+_M5{Yvqg0b{ynV0F2V+v*x#+ZAllN)#KAyjXXu+AnDDYoP+r~~;U zGk&+2!BK*O^Z4z+m^2MBVa;@FEf&e&A$YCkNk7bIxiT^XEOOf|2>pn5o5(VnGB~A^ zZ~RI#)XbK52BVsicg8{oxYBKYXG@)Ca!HF!ZCRgI-Q^v-3-+`5&~8Iw2ET=41o5*) zW-|;KGP6yS^}%>3d+(6=%v^$;(sABMzUA(?Kd%c%IGpiEtMa2P6d2??&(Qm~K~ zvyy)Hiip0#EqAgc+H@r2c~CqrLukM_XFe}!Pi8#FFBklmc{2<-;WfzPDlb2Ve80WC zC*L!E-p$url6u-lSb*INoMK3rW+>Pl=jf5nUjXI5%YDWjgvzmS8Vy2t08ocmQVO^1 zP=@rkxrKl`+W|vS7frT(f5RfS|!Cng$%DsbHxjggIWR{fz>r|F_q#W=_1{cqH_w|4|bq0E*1{X zV}DR0kWf-VBm(9rBjiYir5E$=KO=dCs3m|t7ja^{QC?z!i;r*!y;AM^E&$>X{3KR+ ze@@UjxYEP15+~knte3Y-m!9Ra3Iot6U($Q0KwIR=q ztI?L#as2#)*o{gV;tJnj79vDpd9fKeq&(+;I0 z;>&6~FX|>8Yx5p@P3%|KPCS3NU%S$u7P<-!9yV)vRridzev?>gj+lNLTvu~Zjk!^` zugzle8+=#WY3YKlEg^5mvY}(Y#%I6bdcX1TdHqsEc6bwLY`?%HHYOvZ@#0m@)r}_L zQv*dv{bB-hJ`vuECFy;thTZ2)sNp8kPgUeMo29i|xOAGozG60pLb(kq>Sv0LvID?= zjVi<~Y}ncgj;Afy;1(HJ^T9sLgBy7CGlAtm>-eTi*j}AfSDW&hJ?{`rwF>)G zhx+vLdbWb=v40yk-d_z@6q0G=y6~(e}9{UvDvjhChNy5hXPuug_qA>D+}b{2nVY zRpRb_Gt~^2pf+_PoQb>KCl3)-aquGwHteSj?Z+u?H@f?omit+*`VmY6>~aH~)&tz3 z1HAbI{M`cr%L86_eR$vcwnnMm z!1}&jzSgzw#SuFDA-%>^y++oog6&J?hkqiw9MDU zSntM|BVSd*0AtK6udY|Ya_wPYtdMI_zI)L%zZ*A00YcJ0!T``c1tEU_9wQ8C+|On9f^>S%~a+lPD)*j z8q`kWR#);F@W4uADRC2{-R-tr6F-dmtUw^!;wjL(ww|fU!=DGI*?I@#mR52J_l7AOEeVI7L|9o~ccqVjeh6AfN_u*dL^M{EW_-30RnT=T@Ar*G-aOC5DS5v}17gi~J6FD$>f4vk|HWN;LLIl-y! zHxap@77QyE*sm90M+-35dF!?3_?Wp(x5cGy8kIK_*h7|zK3FT9O0|h7*B5XOGrIqI zMyLLrhu5399_I8eFnD&pP!ld-Gb>ck#zINZeFBTmffHkh@^D)KUPe(i^F;z5%aYy| z=u)*#60SbO-MwUt-YlWRtZ)w-0g|K@$tdDSkcT2DvN0<0`lxHO6kCwyX+t&SUdJ?S zbvNfNGHFb?eoP|dy{ROXL=(|70Mz59_qt#yPxs?zEa~!~Jk@frHh^iq9A7p|f?GYt zAO0r=5N0%OCC`e7A;`l_e@N2$bTt0u&FAYkUvBr%fP7!$^?y9O`1qz^;%$$EB$BNE z1fq9Bptk!K;Rrb3zw0Xaav}eP=wQ~6bVZMO-R0;@M}JxvF5wjc5L&@gnLnj_!CMR; z&62X`;8Ia=D)ChaL;YG-+n1rFC4glWA+#Lc9Edu>Md|9_0}ar^mB8h$HAC2FG1+I| zr>BCSk4x}h_rZ+%Hb#cmL{mqV_1E15*Q4dvZyA*`iogR8)`?iA9aSVbnwr55xx#ruBP%idpq2QVb-7lG%a z$R34p+-lmghEusB-c@)bt618R4ZAhdhfYFNi3;%ODHreKO{(`@BZv*0+?&VZXD`I? z#1@B?K*DW+Q5J=9p`uCK-8a+6Z^@_{72sT}^NT`z1TP%yFyxg0BtwMU=fjQ^m{5`> z8&*t|hrr(S2aXRr(8HE53tn$aq_q8E;6vJfCi6Xgk$$T0c0|d2ChGA$?K*?X zZsoeTNXq9c2f^p?Ne&q5fWQdIPx_+Z6H;(o!NT%wrDwm6WkrCM9^V6uFWTsPd`ACd zmN}BBcP5J1fxs2Ow|E`?C4AET>nXN=ze@fmD)meyq)P9}H=?}7mEIrUQ{RW!{E`p< zHJ|@$|Icaa>tFDMPF5gAHKK4-jgh+#ACw)rvQALuMrZt|{u%2NQ;aa$Y z)w)&HFX6Gm3dzC@Lw&Fu1eLVyh36A3uDDeX&paBY%>k zh=q#D{zQEBGDDud-{;B>`}N0X;j45ko!rD5{Qi#(1wW%%w`U9%WJ~d^3L!(iME6nG z(v8=xZ`;*&p-3X@u??X*fLBn(pqXE8Q$OfKXUS#KRp4nI1 z-Y_15H(j&UwymZx1Np?xwUr?~Mi+6=ZVFM%^NSkGS2<1FMXuMUkgMO^&-7eWi_{A& zf4HMdJ`>-cV)%;PC~NbWeB^OiOL9?Veg(XYaZ#>=T`%ZMD~8@#k*s_8e5 zIhv4ojgxPmA0=Pv*MIj7h7S;oC(Kkr!|w2++(?w&l?Ua9#(VMnv<=%Kp=(?4ME5{@ zRXV$9qejXS%Nf~=K0J!&#DY_^%`BP0BJzroyZf~yGTpQNtZtN|BN_K~>#1$;`?YA_ zY~+M#SGZ4kjh8$sCz=xJSx(X|nueiBk>Rz6Eh$5~MEdAwL#G^q1{;ytb`Qr~0q8!y zxS{R?px7RWGUwLH+xoQLt&}$H?#86ER zQbV(Q5+lm8H=o}*b}nc)CEzLG)kE3_j>)^NZ!DM=DR@bgm?;iM(>aQyIi%~k@=98| z)yTf+HIF%>G(#|MX-%hg)6~e(0L|iqq~yWrR^Jz{(dKToM>_Ggf$`unaY<1p%dlVa zq$>qvca1-N!vB-@IlqsT$N@7lpZT7>R$9y^ax$Nu>+xr?EmkX_2}I|&FSK{p9TvU2#9bJGVIToSU%hl;(&0VLZnQvCY*ggjUzc(%c|Re|gQBTlGP3lsk+I4c z5$w>L!qQ5fbH_klnb!-CeY@`@faxEM7afvTN5Gee)DvzdYmJt0A4Uul2^H_D7jtiy z#3bmSm23zb)z9~%5)suNeI?`?q1B}--C1s)6k7-T_RQp3fCTf1$$WI}wy0Zb%L`(B zzcJK(rx^B^E+C+HRTF{B^?(75QwkJ#k|fPN{I9AN`{D1 zQD&6R>hB&TX-glPqSQ$aOe?}U)*64x3F+Aq^^Hgwgn~Z;Xj(aZ5JZV?QBI=}d!#oM zqL(@(C4lI?BHAR_LP3<9M3TdBFA<_tQ8H)W$i1eJh;|&<{|00Hqjx_?1nOWc^D62N%B{cJA4G@htK72U=B1 zaJN*e3Wi%X7+Ro|6dH&&t1|+dCeNoePU%3KL<|Ic%jnI4K4=>#iJWtYY8Utj-c%w2 zW*ixzYyFBDd{2E&rXQC$ItQGd!5EFB30zLVk`gj)+RvjCo;`HwxBT!DV@$$HMPEUT zaLm1n63fqHtRb}GdG;;Ip7Dz>nEYYFB;OJqok^#%=yE?Ekcbm~QDC|prDT?sB-%Sm zR$ma72t3S$3AN}Tw@JGZF6ddt_j~t+WAJdcJ3QYh>5c^#K^h$pNeT|stc=|-Zkt=Y zbL)EQe5hDcjVzYrz-gC+NKgb%6KkGb+y@Ei)Ml& zZ?=ud(z)c*EqUTnNzXuVewvNO!+pK7H3`>ecXg-(XJK4RFuR;#!D{1lS+i(b)JC+@N z&l*8Y#dW{P#@pq=;U{KAd=~6mBI9XHrli^65bMcLF$cuWc#38N)l_%ka>%D>=?^2q} zhK$~T?jYSGITwbC@RXW7cI+OiZf@l}b3iX4VL(?TcIs%8~ zeXJ*~5MKB2K!^c=g{cfcACR%?*z)c5P$`YoPgn8 zQzZ=1OH7t1H_O`>bdmXZlMHnhy0i`7IGHZ<`r(*Vz$4)HP1PNU-jDtKmA6@TvY+vr z9@PrpGokL~PkC^g<~=t2C3vKK_@k9M`BwAC$s8Fmldm85@mnd$1g!tvmsT=$^Q#jR1Q zG7r=M@4_G-Nhgaq29gtF2Pntij=I$(Abr>^n5Z<*sH#1sShd%N?n8-*s|e%2RPLtC z+Qrx8RExl<@-4sCY8#S|rZy@?#Lsjz8OoYaOY$!W$~Y%!8fJau8y1io*4C8~I#hO` z<|Ezg=)91u`HnPD9c1=Yu(nR3IEUEM*YVtn{CzN7ayhJ1KJ36bQgM*RpjvM`$dcso z>ei;TA<1x7ACzqgU(dJ2Q}v~n^YGoa(GZdmp;=-{*MVqFkO$EIzG3Ft~sV18}CrWsEl<8l`AtIcoMl0%M>e?t7`=Tim z(f75Y_M;|Et(fGh@pw^S^S-#70LoeqIg+ zz|>w~^7@5t689TrA@P)cnet->OJAq?{+>@JTE(S&+qAZS!2MKO5E4Mh%_ zh11MZaLrOm%)+k$`EwN2y;<4-Be>oyO&HG2HKM;edt-Q(A!(LrYnJNsEDL0gpc+LK z8No_w^s6tH8aj7FVvY+k#~olyX%p$70`Z;UW9bBeNvRog)L-`Tx5XB1_DiS;ee*=3VB1Maz40R>O-_G!aIY5dw) zc?q4W>pu$^(kYE`XqW0P;d20shVt4j@YqdjeLml5E!dO-qwcDQUOu8B5f7+o8rQ4Q ze=qm+NpYk}JrGkJr8xtZnThp>g4}7SVJ9&bIq%|m#|aNj8LXHrpix}^0KM4TlQI4x zdJ86R9@0z&6d3HE5mBAvedmWwFAaeX_1m18dX*vZIiSE!{0N$iU$U8xuhL^On}&%9 z{5uH)d3k7dU}Lg~d{75445^%p%NzwU%s zd#eRfn-!}`t2$G9qPL$Gr_WmBen>hLkx+eeW3*s`F*i(r)F) zCw$Y@{b3@To4vKJF^#;pTCb%x7xg60zAWx8#G~SMT}#2+&+!y&vCCf|_rDbI@`!*% zQ6}nNW9(3u(|0Xe?v+3Zt6^-w8hm>7D$SOla)nC4g0+EYEva_!NQ3T0Uq_EUlESV6 zh|sKlmqs$r)XPmFHW zaHozVqTg>cqdQqVk@$nMa`IW|V=dbcf?4=6&{*pY{uKx2!!-d(2YlO2is^X#9K@87 zd=#=Z!`cAp9Tr$gvQ(rk*@Ls`8p9pcQj}Am2t@E~R6IVkz zw|*O6Kbo9&%jn%^qT1HiBO5`5dj$yL8zyLyCAcXPFxT&1429}8Y}u+O#S>51j0hSN zY^(P=3fyS;7PS8GfnvKLQ7;jY~?4;^oXPGV=B|CyIT(ETItL7u|{eqOfc)JnX8|V`! zOG#HZbi8^G#hyY;AAGM_V-YJht5}ezaSX z{G#;HCPLr6Vr4sJh6W7VL3G8QGJZ%J+0*IW*PY&X`zF&Q#FEjwW7pu4l`LJLX%*Ay z6ck|jvcdh;&)tGv54XM5wS|NClm{*=pId0Rdw+VME8|0M=|uRF`*PTLl-U=&NQ){= z5a^2zOoR?lyc&~qg47(gy*RY5^eUf*u75;E`+~4*o&7T`P6yV-XD2Kh_ z`{OSo?|Q#@Z^siH|13bC!7ZYBBO(pAUp_j15Suxy4!xV#G)_zU@XoR3x<`E0)@#!} z6Lq5X?#P|6&ss8osoo6cQndtJ-@uKVOu|K>mo*5qF zn-k|qkEaa~UV`H5|868bYhuW20ijxPjgoGR5uGu6~Y^x6WkhzG}Vy#w>MjS{<6ZV(?(od)NCBivf{_AwlQ~j`B6&=_ACzndkV}B9P3B z4h3z21xqE7p_s_H8RocwA8zsB+yW?T@drEMGa8MDKePNH1`qj*(6bQK!ARj%*duj= zz2G0dfnzbkfoL-G4=F&Alrb86DqVDDQS{TOK$;HXkBGBxinttSbvZ3Dp<(CUxBQ*{ zOE1iyw&Ssyk6Xm3XDaYvUnqi<&Bck(lk&hjPvpTfXbHuQqUhTt)c(x0{w4imkdUQV zksJn>&Jrd{H1mE*bl|)i1&*-sFX)crYW|P4_C;SFMndF`s2tdLio#Zx`d-2I` z)^X#GUFK5UYgIJkQrvqFj)>i$JBek|&&y;d%2*~KOB7I{^SB2*<&{$9(MvO!9XcTd z0e(BL__<{r*0r8avLVI4sUygx!zWYIfn79&Xxils&(FL@qHt75T}>PYU19Nz&1!(l zX1(G*m^%W_?Wi0RibP|{&IxZjaoepI)%Z8K)v1pQ`v$ZAByK#*ayelj1SoG;xcB+B zzy1~KbD4UAZ-DcAJHrjm@tvy~F&LiU7M{>Kp72v16eTo*y&C8DE zG}a+J@)~sutIfpJd16X~y2{ZMC3PTfh$Ov}ugk#h*u|+=8Fs%+P!HGUnJQF32QYXY zf0Tau@&wuvxEC2_%Uk)W$1h7{uIKR58DiJH>Z{tiH}!RMBKwvPS?4eR?rA}6;T%AeGSZ0XLA{Y#`S9g{sfc!a& zo@T`KPYScyKSXlp!6`UW}g}tXD8aZul!mRdx1tQ#?0$2F}f` z4_;st8#`>(tsCQ2A-ff)|K2UCTfKU>w2xoP5r#@M(?fWKeXM9iNFLm+wi!44q%676 z&V$?Kl|Uxjx?T!)*8QZ_6}h5U@fLZR;~&)kQ@FX_P(5=_&5m_;xGg{L$_>S@3 zYag}AMX>_$p>eUW`-}~m))|pR8uwit|GK${Wueu@fw__W$2WW*A>yw5H2DnEE3o|5 z3KznCoCgvorbmXeGt`H?B)h|64g)YzCO<%FS_wv46v`ahG(%a`4Kg2%e|7k6UjM-m zlK}>AQC0Bz2Nj~ zQcL})aV)9jYHQWubU(6Up>5{$%K?qTeJywSC>@nf)ub?@n|rM^g3V z72;+?MmVBzwB9p(+Mm5GJewABd!4$CtJ>!`K0S68mW_L8v6#%7? zGm5TrHkCAR9K*B?O2CLzWJefO9DN&NY*B2oxAytN!S>Bk$7v%up0fSP}Y)1IUhYB~YYi4dgXL$XRIvLkX<^V?y3FxV?QS;HV zO3uusfc>gJZ%&Y8^rwU@JF$*o`t`}_A+~4AAxL=-?C@^OSbIxA>X}@TCMn%}?pSf@ z((W=CEk)Dc;pffWMe99FlN@bPLBl>gmW!R&g2}0+c5P7nDGWhkX?u%&DeRje4*GRf zQTvF4epiU+`dL~Vez!3zYr8Rks>KO{^Y?XhK6TV)r8bK>+ujh2EYqX!Z|O}+4UPPk z5L@h6$Xvm1pZi;5!X81h(HyHt=a@?al#(0kHTbvlW#`yNtF3sY(#~_MFhemMnOB0r zSPs@e-bZXPlwNn8LJWQnY&FdJK7TknXof_=yUGiM9o!hxBq(z99Mo2~S*%iT9E$aj zg{OqhH8aMVD>I+`5DwG0wCgAr)_Ffxrh<>90wS8&?tFW55|5XNEQw8qxgKiDunKH! zjg8`Jm z)*^-nzr{onq9s4hl6k2{x~T^ED@84Dc9gH?2DXpcNuDSHcnohEO(se6`%}WiK|p`; zaK!jH1=Lkp!$#rkf#*S9C0pina=5tV?(M>GF_cIGdo!+#!jUiEr;hX-RuUVQ!){u*W^05y zAg+|Zc2ogkVmxr;ad{U_Q&cZizlZg#iWy5Mi;gG1Me!9C_h~!!VF>Z3%)m3B4|Yu- zT0`Qk+~+S1%(s_v9~9h|b!rvlLe`6idbt4z(fNGtpXr|mY?1|>I!h({M3Wu%@zS#C zoOd-zr~8V6A6Rq0`^o$wuKsJd%X{|qmp3}qN>ll-`%`w*A2*le(+X5OG5or%etYiQ zSm3V~1%;k5u>ZoRWUA}C2`_3K+y(u;s?N9A-Mq8FLg{E-l(8_q^!RT*_5hs&>QQq7 zfkd%yc$Ot}-D8nK-%ZZizsELb;&vYozmaO^NN*VJODAZh?)el z+Rh9bbc^9A!-^G^uV)Wooosf9IH~&vsRq7Ltjj0SOQU2af_Eg(J+o8fy~!aVoUczl zxb(W+Th9qM=h(6>sgz(?*{Qd+6rhHp@fe~<)Q}*4w2Feb%C~RU>RYC2hglt+MVsS< zx6kNR@&}|A?8Gve{$ws2+eGd8sUb--pvkM(@%UPX{m>zMh+(wI0vO;$XrPp&nBws- zC>f@da~+}?oChF|s~=~v7zL3i8c`Jm5ir#K%bXYMfdxLe9Neg9XNEv&zf}6}Hlf6} zKpcy&l`*3DFhxakKnfQ>O(;?ejSwszl%tQj_(uKK5TS-d(lR*A_K(p~535fwJ8?czE}W ze|ew8d6Xh1u8(iCV@!i9XYeNC-OU_4o_u9l-_>@l((gSRg2^0e_JF$}yHzNYg~d8f;$BF5FilT-Q8V-2MG!8A-KD{1qcM` z={(Q(etY)bvuCR2KDeva!KzvZOYe1E|KEJPd_A4Ox&db*F!r!JHe$*R46?oHLpi2v z8xH4%-;$D%%2o%ROzM9#vqVNUl@kboT$;@1SlA!oyon;yQZfTpS?;%49ujx62}yBl zhLAW&k?QKXP44QYh3k9LOV0*BlrXqp_kU zDO&|wbGk|vo+&`g;cRopSqvHahQozI2&IREgeq`E9Nrq?TC>V+wddwowT5c*$e3d0 z*!xi1XJI?!!B21HNi-%SmgLeu%b_%bY_(~fTW1K5dc?fo+P#9sVCb?-5XN*Vi&M7j z@`ixbaG0)zenGK4r2NgF0e_Iqd*f1_s)3b(wN)cME3+WZgl*YFO;Vu%Hzt5Bx{`O+ zyJfyWw*Dx#@pqW6(xMg8JPJT*T>wXYuqarXM_)#^j>c`@3LjA_t)@58&ywHht(_|4 z`(vhP<9G79l>4@n2S2Du=AcO2d}Y!y#%>9S62>;wY_z<(y#zKrJSlyHyFtP+Jw!Ia z0;V$2)8)}D<-?AaX_BP|lQc;fHi}h8S=TnQ;B{H-{3~h`CTska%OKiIWZT2yWIME& z5D3hPRa6IEyTD^U!37Ni#CI#zo`R)g`(2}KGv>>maRBmVz4k2#{?>MJLDn{5w7VYp z3jI`tlP0;=+KiX4KbXTKAqTo8$o;uJN_I-5os{NSl+J(Oi|GoF{{*)b(<70C2S|}V z5SBr(p(S{N!{-Au2~;*}ReF~uT1+-XKw>sH3>9e-Fv9^WTe=)9ZOJi;G zVQsRLyg>+RcVbnLg0gnBR)3YV|2k3K6?gJwy}E0@`kT@T?md&dgQ>I^I59~B896*i zOa{Y7ilJiE8Abssl+{cew|Gcjv6B(WV9OJC^LQ`=)O*GF-~|DUu8CU`hEn^bHKTQG zW34q~-`K_nYsM$oe$3bWSZ9MFxD&^LwB#ZD3B4184&=zQr0}&v<7w01OHAJYy8-?9p6q6j@XeAGpt>HHwL*ra zRBG#N84ZP8Mrs(rPDd^PwJe*%s+=OhK_83QvJO_#uV;*CI}16A8Y9dEsq{z_s|SgA z^~$0HI12jCm|2RI0*mMC!Uqk{gLXX0K^J9K+NiT8&-#~2<>i<(Mmp!!4zz+k#rqSB z7G*ty8gk-KebX||62@bIoS=U-V3(Gu zIr-ubRAZbk`y_lJSlJxzzRdVP8y@7Y@W%$+M>#80w<*7uJ$uR+2*4YDVmo<3CVBfa zm%%~WB_IhC(Kcg(>@E9nsf)cew}Aq;6c}W$I;!N#a%tQ^`THu4kW=4=q0pu59qF|v zXm0Lq{iFJ!1e+@z+z7REDEYz_-j17zX*Vyuj3@{km&HZ@w$WyNV8*!LSs=s(_kj5G zwVG?4U%!j=Z1)ZNAVvZr(@!^p*~Ztajd(Lxf-4B1MO7)^A1F_Os5({x23Mv^P!@w4 z7ukYxA4Is19gMyLO>c|d5H`meXv)AE>&=F{7wmXjg?^|DT)A-%mSSx zOG_m^?Tu9VF4c#SFgF`KBxJ$2YODq!==h}AhnEuA9*~1yre5xDd7ot;5i|9Jwccak z8sVY7y|E!|qWYWxfodaQ!!eA5t1Br?VJ0v>qf+OHd}jgTft!%Tt$~ZBi4z7@WuAx$ zU*L8#_d7m$KvlsfHZ0cnY7)HilahrG08`%{iBmgGi*a4Dck+EqNWo18!!{B(^nh{Y zxl{w46AxC~Th(&e+I73S#unY`W@lT#kwCxqEduY8bY)8m3+)}`pqc3ax^241Z+y@~ zjk>PLa3d}Aj_JG2+iqT2-I~T*y+I|OSFS+rr&a00q??;ip(kk$g*(e3SFM>A!&m$U zZ2@7Xc3G{m^?J7|kGD*;AL89^Wn&!ecvqIT-O~dhE7RIajyu;sw1|O4+HJWDCySKXceOY5AEt!YW@v?htH6k3W3$ z@bWKn>!Y>75;RTe9#IJ93l(6ET@2+i_f2l~8~q?S^FdaflUSGY&hFyn4AfFR+~TDEyv((sDaRVhb*G#Am8D;@-o?aZW5GKu2+46gk+5F2GD*W<0VMYCE_uS z_%dj~ww8#G$Dra?v0BK5;GPc7(=GjjEV!H3NLqEh?QQc1|1+;3i@}U!VV!JG*(Vq5 zKJFrt%C`anh912VAvGzT$kEbq(f%x9_O99{7>{)yzL=3-!SM6^_ORcwr*k0~n?XXe z!NRK`UG{z=p*}kJ9 zm2tuo9|kk2_pollT#;!hG9u0)_Fs1&c8kN+XCiFdf$8u zMY(yCaquVaSG)2>(dU%`AOo1}+nyMHguXi>A(OoeVKBY+D*$m{ol~EqL4U_k0;#wR zb^&Tt@qlD`r%$Me?0G9kyr}lcvR6eABdZ5tYuY)!$Y+bYZ;y|@vjq$y{q!|`Qh$ly zAb1!N9MVS@3nPLh`*=fy@mT={L4pAt)x|`}DZOl9+na=s!}9GzpM{3MHw~vhMRzv6 zg{=dNde!F35DfW@8{929^ZOPQlDh3-q` zss)l{W}x%pZ)c^EfmJdh2EM%#LMwB>Bpmoa6@7Z!?{Zgz&}rY@CycQ@R8~ zs?BSV&?m90w5$ASzTBX5=Hl?zD}CK9>EE}C3OBdU{Ds-iH@vss`$9QE#p1}c+#pG0 zn_ynUr=tpKQpIjj1rVSO?%|@3(-;IG7n5dsmhL`7#{OU3Tr z3|Gk&2_bzC-I~qej#u|11}VQ~Ta7XUa!HXjW5J6R&LEoxiYfsryu=W&qA>u2DHyY9 z%GAo~`amSr%08mcngK0dHQ)?ai=lXu$52tO{qYgFTJecfuV2IXbAL*&y?IMeCH++k zPRC&k!E`!8t9T@VfRs(^pwr`ih`cibplq>Ec29}>gD9%Ln;`aUaSbi?Exc@XH^-B> zk;`p_128-rSaUk9{bLX4I=9JUtk*shd&>dH8he){4HRB2t`rDCmLTXPuZpXotiZDWr#^9>QwE99>jJtM(VZC)l zmMXhVusFaLII6Qz+%m68Ev-#0`%2|##<)eaKb;Mkr&v=(2t1PEzYdyTdME#fzg}Hs zphewYxamDLZpG2NRDkZl9T>C-2*ChZ6Qs|cc+giGg?NPu=-=+jx)(+95l6tOu<%1I zN`RvJ)$4&M918l~6+hk>faVBZPXKg|!bx%El0L%8luhhR&L}fVyS5mHi)%3cO4G-)#)YuI7yhKLrV_ukcV4ijT|ZG`Oq3!e3qVX5O|lV)o3Lo)-uUkVmnKq= zld~$@olLD~r;It9;%3k?G+*a zZBmwhKP0+|+Pp;$=GF^TQ9}*PIvB*aXC{#?P-yO!-`9B})ibGM9I~y;&8ool(h!ee z>RI^NPr>*V;dl*dYVJ8YhZ=lBi2$8sOGN0QogzrH??I;!e=3fn!xlTQ$0p!>nbg{r8o%V5Ti1M~ZEpV=MSu@LtsjyInKHu~`t7yl=o}r79)P3I*M_6+#7mK5 zdDlza8$#EZfPjmF<{lgL`4SnkK1PM~;aVzp&k;n{rz`8P=}PCFOte=WMX`1 z^|NEr)tZr?2b;Jgf?)n_3yp_-qok@Y9OdOCVuS``Tb#f{_o?gn2O_q*#v@ZRJ8o}#q`tX?*A-WW1doUaG^{(dD&dv+Qq z6GMRWGcwBJ(r)ps?48BuZ?^<$&)Ez5;0ff$^GK5ftLI|8Td@bY-guq%$HqMj!H+e; z<`|i;5EK<{_iqS-pdp9;(1nFhgkqQgOKS8q0GeeWRU_ilG!{Unht>%Qz%D;RbpmeL zKTDQAW3oT!A_0#rPKvh8_n8HrIH6FvdT8SXbe*$9-yR$kNPZ5X$e{)ja6NT*)Al;D zq3-OW27n$$KtE96sL%Gqhx?hrSn$WE00B@;DHMz#lm}O| z3;o46mkybI>4motpNzqPp2a#HB&~1er;IC9pUW zf2<>3yTBG?n9^)ue0@S-+i*OqLHW@fwR#_OkC9u{9Eq?9|C1{oWhD8<6nQNU1@Gjn zt_4nvB7t?C;i4%{J`UkKZUl@5+&8_HrHE90jOd~uDiBwh@76A+Bp8W@tZ5h=d`V0Z zhTp-$(t&AF#zaWZL$i}eiE~|C2P=Hk9M0*c-3JB}gYf7Q=y;RBIPmmC^`sxA;OZcA z%NW>F*p$rI$7MX1$J~r#u8fRqc=Sg!=P|^57}$|XrZJzfZ;u(^`udZ8Fvnpd99&(j z<37Y4(7vDEL^rjDzHH$M(4g1bNxhK5NAa_0TT&kf}+b2P8{8YO(ex zLw4|Z78OaMG^WYKzvh;cA<3GOj!7cScw=@wv>nu0=mEq67_)r%x)FFHMCaV|KM>Zf z_>+U$akb^&&We`L;L@Ux6#ytEBN(`-U-O*G<6hJhp0ta4Qv?!IrvF5vembSf19DLi zM6@xXrvxeznSl{E2__3EbIja^V?;5uWEDYbzwqf_E0Y+_NY~=4$EIK-wa|4c1D&=Y zG(avW;wA>^mi8FK(ZBkx{u{7N55*{m?>(3|8#W z)>>#04d<8D<5N7T0@7?jUT?WpNTJ-*f9<4&}gjg$2Nx zJG%yf|8jF1?%-}D5k*ZMMq2-Ia|ImdS{UmPSCkK^SD9#+j+a5 zJGi?$XW)YUqks#_7Z);97Ysqy--NCNUtC+#TwyA0`X(fnpiBgyA!d#WrZthDwwWri zL@>8S>b1oPDh2Q2-hkh~`G0bA&At%)F(Y+J_gv_2Fjo(#dIPDb zrIC6|&_#c{C(c`H=ve8cfr|(aD+JtrEZD6GpoE$FEq(D@`weq*Kka?-ixVn)E&Sp zU6>0g%#aUJ;TVlT(=e2dY%_sG z6&xOS5^Yu#RO4N$<1O)@!FVh_cwGAE0?VQzq&(t2C3`}pi5-Z#*Q8IGCAAOX$pryx z0r^N-*|y&1-=HJ(Jjdurmm8wG} z6NqXI5h)7`W<`SU@1Y$G)UoPET-GD(?a!TBsvna2+|v?j;?;1_)&SARSVlo{(d{(q za6*J2+ufHok>;S07OFLu)%LZG1VB(}aL>)Ye3OiZ8M-MS!D$ei3v&`gb22w9Y8Ndz z7SpE}pma@0k#wL5mk(OW$4?cHV89I>K3S)VcVqf;hUQi;_evP_nHU?nr*n*~TJTlb zm*xIW{lqb8;v&>E(C5FH+Tz{MZ}4u4tW4u;Qx~ZK%*Uk}7(m!Y z90d|0g3tzGJ}x!6lFGLS48Wxs%&x_oE%czK>z#v#PuqfsQmbSEit}ILuM3YdT8xtQ zg(d?~*q*1k#b)^ZW`w(Dc#W_`#b#xnr!y-EWGH5(DVQ5c!hdwa!u=IYx*&S0!Jnll zR+oRso06pkGK!dzg>0d9ZxVOIs9baO{X$$QV$n~i=p>rCuYAGqI|VFCI`RNq75uL% z+#Sl`XKuP&ZU@P~=yJc`>PXk>kLT4Xv9&QHtl6%$HKSD=2orYC+LF;426aJY=A2^A zxLBux#hUqyFArfL*)4?XB@p&1B`75clWq+-Ar#H(p#3dV1SuG!TmSKC2nZeyHwY%r zq$1wZ00WB^^D@4yad#MTxk+M?Zebd}?3s!0TYcJx$*^YPST|rShffFIFPI*0Nxdi! z-skNvfD14n{myN356|Ng2Gv@=^PhuRzk=BMgV@GF?6XqfQ|Cv$~7mLZ+gC=D%=osUSZk}I>U)+AWc=&elEPinyiM79Zf%5$l z3+SX!cnRl!`S9`q*n>?8JaW`M@^0N2XdeIhF^ULY(9KWKCm87ytx#C8P#mmjlY&s3 zDmZILxG1>XDtyv*7kRXY_Ik^JDipLxStzTYQ8&)@$h zCEmD4_PNv-AyXICAc)jxk4l!9{lg)ze9mVF)%k5VYG5SUb`n0ba0s2#Dz&M>9o7* z9a0iD7)u^V>-XYBQ zqq#^qSvw*6Si%tP^}Cj>7S@W1I{TGxU1=Uitt~qfXK14LlD)l1CMOG3oUVbch!kfAenRPlD}z7+1BXQD>V{(nfmIIeBe3ogpFP^4a~LI(CbLc5+GZr&wf{a9(a*nYa= zxKJaac{X*AaKnOP%#wpcC5b5HX5MR4SgvK>tr-yL3z^vx(GVE>Wvm@g>!5}d>a)Xz z9BR=t1STn9GJQkd@p_$^mT&tAjIe+}_Y|;Mhk^1r}CE0wxe%o&&vWA|1;WQGvmbkw$7T$V*Iwseh{ zG0y#ZQAuJ3zI-9i@6QpqKuJl#AUQ@S%tp7}yro)Q#ybnYqB{!4?P|xm_tlSbjMZq` zM=?~{lt9y#H!6iFQ?RRjPM3yA(VruCYl7G9DBFqW?N~dat5yy_|2U>&tLJqo)~CBz zkG^QU$|G>Jnb9=JX#uk=xF9F7py2# zK_-iT&67ouK6haa1=XAx&#L~iaB%~lhJQgDBCRXHGVmoFRBjxjnA}4>OBtk3_i)QX zg)b&0k(a<|30I6y<*{aMawr&cMO7#m=Uegpm56b&n*6hQ-uiB7{mM6GN&}9oB@Hg8 zD2vj0Blb&-9c0DY*~OgVGH|vmi`<15PV<)$y4r!ul0$mx-Goej^xe*zj%>lzpP)|o zSK81XUhn;)_!sR}vo}Uda{(LlF0SFG?&Vt(@2hXW2*p1ywiU{^zuHYpCTQR3GQrf} zFDteQV5>sl6+N1eFqyeJ>#*I~s6Nnp6<1leO!UPb*?3`lc8|k*?+2rg_@DjkJF_wc*6d#?c7_F{$)se%`M1o8Y`vtR zT-zbxYQLy)ent#FWK1zB7)Il!3*|6?DpVVy&8hFTOIV`LqEN=SLCkb=#t1y-!8s@- z@vVb=EN+RViY02xUTK284e0c{V|SP483=o_acHiEa;6!5QVavpywq0AvXS_ll#P~g zmL;qvm1SL9^8Rx>8+1pSit`AU9QGN*;HX(_)n2>!oyR3A{*X~^1}(?DMDV&k%9xE3 zudZA_I^7Q%MWOv^4#wAJM)Q;52W&F&0jSzk(v`AOWliQMmIvGejY>%n_pFx z^e8x}zWcbUmHcuU$4aOYxZF{UyfOqx^QZlG+y5=;@OZ z$$~LKPvRydNnBKs0$-V^8zt)@#b?u+d1Ps4ha2fMUM_le%-WvCU7%E5EWJjj6`Nce zdU}KvW}2&oVKZRPgO_=xZEbWW@}}Z)5`Q%!TqKD))HiUhIz)EIbcsgCKe45zN0imL zgCub&u$E&t<&Cyc)Efi=zR%K~wpU8M=*or=v@sZZd-;B`x5_iP@`s)In^xVyKkn2a z1`3=He0rnb-W0MwZyO!_QJ>J{2+FrY!F<6%oZWVB8E1E}S1wX(ymSwNHqj5C94{sW zM!9o!#d~eMKR{_IAjvojUI(! zUTqPnWNQA2s7*_s%X;9|`sF%b*NKrL$FPQ>wWCmxv^(Oj!aG!OxJH|bBdJm=lY z3rx!GJ=%Sh3WxzP(!;FC@UAgG64@FMAb9#kr97~J@-z0>;1hBaVyTwVz2!*rT)`a8XA(<)ui zY|(j(*&}&RY}}iQ7{}vCl5JXBZ0+PSH$H7z6};*!ndP*?#uC=Gaq{o%li$u;(-dMi zW{*Bp%yrc%VgydVeYMg!DNY~5uYBV5vtwe}ld8Te_9AD!bD~#=t-n;^Q{k zmwMk?l5_01mEv~zdMdya*6HZcrn7ZJE!nw?w@Jskn4$L=G``NFSe|cRG3SAuwH@&Q z&?~=SnmPRT^|iOX--*P}yF;3|oBHUo?N5C|?Hg4#$*QjXItSi0ev~)K#pH(%v_2%M z9Cu$OqD~)K1)`2Xn=YDkn4sy035u~5IQf<3^R%W5LXNp`GOP=q&re^N^ChAW7Ebwy z%E*hHrXh=`6@X5W61?^I?d5qVXN|9DxSbys!y_(QZaVeQuDvVOa7rDVUu~m3DGmtc zo%hjy@}~YS{hH``uhIEs-3$sT>zq1DHdH;Ii*pJhCK)OH@Hjm7&KH4}YIMsv`}$(S z_n;bjedMoPS?FfBQBHE>JNgMS;b3!NLGdJIB6i|x1$ETlb32g_V1V-@r}0aa@mp?Y zzmZ42E2r%YvHSDE#|0^1=ZhC{Mqu1;g@fNdXKw?jE98)DK4mdF<$O@i{~&*x?u5|8 zzq;V}{kKief|Ep#mq10JkdT!yvKH_#utp|`hAHG7h6BZ@1HKA`=rK{r3ORg2GF3zlOra0NV+#IB7^t z&#<7jFioKk#^r9{iirFSGB=x0ln50xT^6t5px96-QG}eOTAO;Hu5VR&mRjV6`%ou0K6m63c z`FYcD#DlirT?M?OMYfaS#2*KV?-kgok0jm$k?MIh?~vo} zGu~&n#b@ZIOrq+7?%gvVCfK#>!e;^B0NUSy51nSBYD;v2kDc9^{J zWD-iroQmq(~Qt8}8l1(0& zrfDk_ijqa+oqqM~koWz;?=mbGzdea9vtVXFcwIQ) zAv6EcJHh%O|FAt9UBfHtApyR_A5kRK^r0|uBr+K(54$QFcQg}P7F+bLkecyziD1DT zO3ngF(KShajj+c@+oG+=B1$SJTvnPL`k z;U;4LgV%O*XI54;BB|gOU`2y*doStVcVt@hz=yfGqc$Rj1CUlmYuAozH&E-gNbABS z>(-UB@>q%yMqQ9lA;0wEm_Lx2NMf$nSLp_zdu_s7fH8-#abbRK4;U6KjDA#r3*&1C z{^4s)fdJD2tRhK-&jDDMdnqG6nUj3@reNIWdJH-Z;4wc)`w~li5ZVlviZ!rH1&)@otj%4X2|F1kh8rOFZr+LlC| ztgoWmDyzLhI1fUAp|LrWn7G)ujo6sfX6R#J+?510c1SWInH}*X7AYAnxiW4=f_-`c z(qA_>x;?YHJ$tM@jST6NI*nsfpxG=RA8?#meeFThaafxMZj+qa}t=Pn%ziK$<$EUAq zlWwc|@uy~r1$Tw4k+!<^=wl;eH}dPv|8jGGDSy9Z{SMP|MHAp2$DrSzPyTUppT3J0 zApK$Oezb?9Ecol@qOJmuvs;g=TXEQWtd)BRL|chsdW@@k$W{RkCk0m2C>y50o>yOJ zT;cWrXf%NcJM~zP*qBb!=;36zG@X?9TqrbCD97r!Nsp%Mu&kHiinxEY+9a0Rl&oAd zeaF{1B+HcrNy19%zHd~~@i6Sj#&^Iq_dD(CU&;dd< zeWIrg;FT`OYKo&BRw{P6yGW&G%-i!nb)RZfIZ=is2zo94$>NTD!g?yeLInV*3os_s zd#PPfjuRjNFz^=`1#tOw>Qxs&y=x)6i$HmZUlFR2tB(1*9wRQh-&eGZ#;16IWUO(# zZq4>DSlb?hu&R!J$q&m6!=U2A%?rR}1pNhTQ|iB*f${3G+hB>?yVV$cUvVQ1Mn&g~ z&-BM`n1`EU3f8{<_@O)ej`}NYJ;uf+eC{AzoG8Lw0GhT7!oVh`C;-6YQvVhkM%LDw zCSVnDAyjZRL`2st_SDMyVrbj<~(cH zyyEDBWA5U<-~=!8Tp+t$aPFi@>|(UanA7vTs>-kw#*#DB5_|1ZvdR)=)PkSmvckwx zZfn z-$GZ{>bT>gkL}73#<%t}eb3tYLX73*wdL-vm0pS|I;AyzVjHE&Hu-?{quTY8AM0ml z>ld}_$}T9%fQ?(njo-QJ*DBDB`yU(6xf{REHh>cwf7mw>FgM_xHc`H=B_S<&=Az_yqee%JKvGO+=X!LN~`Y5I_=8G?JCy&4>wn%Zs#qFh&1(IH&?H2 z&tT%On`?r(Z=kxWY6b^&LBP-36o}bJtlPKe*mOMK2Vx$$PHecV9{hGZ_~5kRU3YNt zNQ!xsjJX}BdX)ZcD=qGbi33jFWyIp$ z+8p^Y0}j;H^zCtR9A8D=@t`CAe2rO^Dq-FFas9XGW)8x}Ph{m2$B@DkA1$)3my^~y z;m&pYwuzJ8ID$d(gnr7?@pI;GC(=pEvtEv~Sedio39Zp}yyZN+)%CMQ@z`4}U`4la z9ryX36X}65+3~mY-SzWBW71Qn^K{mx=0D#qZqAvX#MgnGmvCx-SzM&} zOO(%-Xg@D8E-taKu5dW7@YJq28sK{*F>kprN1{oz^h>oVNqzU;23V0*`t-_cqo1l{ zZ2+#b3jv=Ku3&2I;1i))!C$p@f)w{(wRWQZoxRyFq0hfCz-Sv>ScmH97IApe`OshV ziKO!5e-9e|HrTlJ=Df3{!fo-XZttk>Qo0W{ zxsAxbjZ(vft4CL(!d0q=v9*}ZT!(=AJ4fi9GtO_G_y^C8+gBS8BA*ckO)+n=G4r@^ z%P;QarIC6r5mgG1icLtIP|Mwv%Cm9wi{I#%TajKXeJ(PC+r>sVnS^)VgfBHiJyl0i z-bB6%cudkjs_#b5!vYj-V)_&yjB;TnI}mP3yohkZ{lG@i1R$<-W7uy&Uv{Z*V>U4k z!MAIO*ky}zdfQBSi~zW1*+&}sx5C%}fD0<@FBZ(HrBiy{db)ugsj@#+G_6RL8_WEr z&T=WKR5Az=hsE*`yGSOAklPOa5`}`EQU6APJh5((K=DSX-Ew)Bemn>XkHg`fYr8*+ zh!+It;mAl~9h&9`sNdL3m#WUyg|fKYsZ=vdcpK7b^n9__KduQTaI+jqwnq?jWKFf6 z%O*Q`sYctJX6II6nmXA{FHuYh=6Bv-)hn%V&3onCM?VD+(JFdV-hah8ZZ`++PYkq1 z^L(c_<toaM|UL z6n=dXW&1u|$L`_4l9tiNLR={Y!Ks+rdh=~mIx@NB!!H0Axa)Qqt{c&3ST{1+ldgc1 z{8@7w3jhVksEMU6x^s5W()DgrF)`R(_8`;W)Jj~Bce>EBPi$?qi`*>%8NJABF1|e} zrP%bMzQIqBjMVpS;7)aM4HJK)>s6Cy5DpH_W}u%8S1?Ploi4quZ*!wJvjY~ivJ0Y? zr&-J%G1PL=^MvMLx2T6F@#WiZQ?UyK?WeKUDo4WjTAOJRxEzR0Cm$L=ek=cqFJ1uF zTJkWtnf714mK;6+)guMlLL5-kpi-o~Y0IMlSPf~Kg2sYVQ#6ri8_JVhCWOnR0a1$9 zv=0uGiP~Bu{FhS-T3OASfd52o<{;R0y(u!x+=Nd4PT(w%l^m@q@&2{8 z?Gjt+vI$U~0N~I<&r@n1mpD8VDZg4HTF~mZwl4%&H4AGeIkVksuCkvs zAQ5s1RhHvQVFuO5%OIQ z0ezV+s1%joNCK+8??`N*b5Eio{IkG`lB+!}~;lKZw|7Y>w+b(uJ8R|*5K*$vW7dafcru$|osJs~E4;J9C zsQ_>bj;rRHa7{=yJh}<*-Mzhl`U1X!0mj6ANoHmg<%`Hibmk&gJ%~tJrsjB=HkGsy z#l(nhNhuYU^wL|sO)_N2y<_7WAp_SH#Gu0t*lLtyRB2;^x6B zToJ*2WP*#+?&92XTrU<>y9(yi7XyQ_U%Badx`6n;;Vn&i z9QKi%5JP!lytX18qj#kLsVaqX13}$OVKuHFE+EQxgGpISNl`?OLK|L^E^|i7rYlLY zv80rVLXXq{z!UQrfCy;YtMw0vHZC}}WLps$QwIek4#7+E^t6pzi>p)kEe-PxSt&fr zOc7f-;4)*lV3xzWnA@O|@)4K>AhumRv{k0Cv|dZ}HH8wwK{UKqla{EiE;T|!)T3@y z;k=ds#fg3n;}|!Q2p+>ysE50UY3Lm|A$9Pmj|!$rERtBtfNqpOGW5jObkWY66^c}E zw4~nfOeZ<*mN2u&2Vu%+;v^yf>W9ld+1N>Dm%*2_E-?c{12NNqroig}yxCXhg5GmC?;OJI9s61S2`)@G7X8fYIF(>2$gat zJ7is6VtfoK?slHW58u@Km43L$_>^|tUq+FJv(^~8La>RadZ7w z+)4i9=JJvgtSuwMUX=dJ%@yvHU;mGrn}J?m=Hu0eL*`v5mZyQDDhwk34VJGG1nta~ zrU>cB$?zTbU@-Xxl3nW#%243NflZqB4Gw%3y7I0BrwdWi>gCh31F-ZJAh-t^KZ)*K zQJHi>r7TAP_HG>AO7>hEkAfh9wyPK}7YMlx9DsguD}q5tD%9ki?+yj@-v6yBr4Z)e z@U_V719344Kv`4CnDVs4hD18)eu#J$e#rIpbS!+R?}-uAXEFH^6`CM_wik#MNGG?ah3t@VF?_wnX6y85O#zDUW( zyx%Xs#qqx>MPUKDpmiN-E=T~+ODrW1DpdD@f8AU%7WlhK2PF<@)cA_%%8_V76!Rn; zfL%*M)l4E%5{YJ10y#z!B}Z~AAavgq#Bm89CHzV+AV`5L+&=*b*bMp-9Hf--DzyOK zdoqYjsQRY34#7cUr~pYV0L0b?e_kL-u?nGF?EzkfxO5}EHw|03q;|a&R=p2jz!eeT z70DF|^SnnYeI<@yNQ#((tTfr=8GtBv2;qE^;wtIZ;tJQlX$ydT7(c)Rm;e9(n*z6RZ@hOXqi%nv~4W1(YX(4KG5DL?3#BXqz3 z`c3}i?)dWZFNX_*aQ~rjPmlkO!=2-;+9FAU%ob0FIBbFxcY1nlOJ!|yIZVE-Z7Qp3DuwyCl?^2|wKe(GIr-Jum6es{<>mh^ z-&UklhnIzA3%yzjZHG@T}4^G11r8*U{0@($doShrm@*QiA!na&mIg z($fF>w}0_l*t#1H7)nYE#l?Z5qrnK=2V#O}c=$n1b}=!re-&I_US4i)Zca{4c6N3c zgv-Lh!o4 z32=FK~|97bS{h09K|M>vnpv5u{hFH{xe@P7?nb) zxninVA(_Q!w7GJoT)kK+SE+?Xn^Y18;bvj~e?z#@q17AT1D-+u3xq2Pg0f$$MJpx9 zF_HW?go|10%_l!q#{Un5Yad;w;=}$Agv<8={9hql+tpU##bLK@j6*)J7r{Rs$A+~Q zKRNs!bC8F9m4&Ep_l+7_-_c;E(nbDFNAB~fl{7@ z%BM@0^zmHK%G6(Kq5M-Ita}dz;lBAF5bjZ!X$K<%0PbnC|345e%Q3+}5N>G_%P|(5 zjF3&>XG$osebE0!)qQxg8L(jkj|{OBdlP%BRW*VjHmy}vdvB`tDnaZ~t3_=!YpYGw zs#R@6?a|uQE{aw)pZERtKag{hlXLRqzOVcGy%jaBDb)BD;G!&hzPeA3_xt}K+#Sm| z0u-z`fx{NIlhyu~c_(wH*13uW0*d>8SKaEd-~JSLZkU)>S;rhD;)FL^-UtIGKD!^k zyHYfJ5@aX13Z}SX)Q>g+lIWf&uWko(b{*AyWbJHJ5w00(F(jL}xqpHtP=Pl}j=#I! z{ttv3$Z#59XR?Zh62L4<`icEl(GYUUp2iOyZ`^$o{p z|1E@j+JD`jd<)@zua*3~<5N(dZmxRsUkEo%Vs!QYK)844{bw&8e=1rbw6%OY7aE5r zzxW<@`YGQ_jJ65J`hOwZu2h+{Z{rj!% z5uGuKoaq08aOH0yT!Bv1>$y2y5i@06bkDq}D4aZ(nfv5U5&Lv#Qq2g%P4ZWxos+;B zpwLUd)IMznst@_0xB+|j?~Yf5{w2_0 zP$>t|yPSKBAws_*7;KRTAipT|66tV@K{1*gsub%v8sbO*u}@1h9m#8eFpdM}Nwkl6 ztq(iSAciml|VeC5T26S15gzB_&DT7I?N7WQ`qJKiH244^y7Q!W%*^LtbFw6G0k-v!}_wtU^$^0-?NxYadqQomR zJQhM*{?ZdAF#7cNN-~;+-vWvZn;e*u<6zvYij$GxXk_CDvGoJpzI!a)U2LNVIPPjF zY4(}_lKIt+rL7OYWTsvRdcOAYf3SNhX~RnBUw?GNwD<32VmMN@B+@cJ;nv6S##f`NB0yu*bi?EYCX@G{bQ#~n*={ALYmJ9yX_-)|BZ zt`7q7w>3OjxLBuS&J9z$ubI5`cCBm1^xZGgr`*0h_lS|N*{gGWuyvj5T%nKOXjSkg zurS#0D&_V$OP|CA3U47alJO88(dd^(6I(;!zdy&3pWy*v_LA+ePZ1`*Sqr+mvf29t z&vr+oL~VA@SF%Sfhu@ant#;-*4R*VuBY8Zoi|$e(ZomLri;>UfXi%@&tN2@9#|al3 z{I#b8^bv>*DZ_kmDzd=eD$=Xz6sAKI0OLM&g^8a{ky4y2zpm6-Yz%*B$#-J{D!ycV z`MUW>>T#Qj?#U}=5h2E`dB~gk&DX!9AwGVfSwsF|mW)-%QyNvo!$zn;7B0pc``qdW zgE|e1I828KP5K8OLv8vLCeTy1@a29-Gh8vvHM4T@yi>Zey!uetS6(@CRMn6Xe#Dn* zuEY)>p?^iNA5}KXQ-_})Ms1^Dw*yb=LmO^@4JAb+98?d$#fnf5c*k6a87kbHE|=|j zNCK4Om_PFS5InyPx>=j9bmw!()b&x6n!e};0o_x8>UEF&UJW29E0Zs(w7*7x%xKR4o^;DqHGB^t4Ufar3kh9>S8{usE& z4#W^vwwW7N1{nvk$DhFd;4t_;*q<~$L>l==xN$D$fACv-D8Ml=!1dAs3JqVs7saU> z9%aIAd28Mp8#?-_ySAu%o~r}k8otIFfoQnFi8e4jTDvi#%{e?w!!4LLXr2pO;)IQ` z1qR!Y-{64wM;1em*bxYbF+XJKgp`mExPT*LOM}g=O#(+LIL*zO^O5I${JA~ zE)tv!2CDP`2C+Cl)3|`3xFDH0bM$?#4-e&JqMOk=ZCD)*5TM%u{+kbeK~Md+-LnTj zVob2hCQJvaQBx)L5 zuJ6q;AL1F5go|a@#}b^*B=ue;^)V#BBXS5c^|Qy`w`#o)oVFT&U`1FUv9pUib zDt2lnV*O-|`lMqB>XeR9&fKiDAa*KmDAObIHB+qJ+l=h#j61XaLLtbl;=?mSy>pxYbxi_n=ss)tb~2`|DH(4hieTkR=J zkrw0S;g%49HElXb!g9vn5^4bY1&?32N|#8;(vi(*jbR642!m~cqHMC)BeQd53~qxY z6=NJ`0y*;pPnm{aas=mUYh_%e1A}okpHbMrg_Pjjq{@XnvB$3x>2o}Pu+|FLXLY_P zB77xP@~EUbe=9Oi{3&6uw_^yP;G@7RW35+hyLrpiT-CDqO9uJj_=>>Q;76YYs3(F8 zb`scTbK#r2(9;;;VM5`2wcXOfE&uzfPd02I!L>Co|BWnmpP2f`?|jf7Do7$+TtCnB zW${6E-s|e@%iJQGajk0shGu8aw#pKKSt0PxOQH+x#}a}du>#)hVz60}ze$PkUM%$< ztDi5%JDq)#qvLtng4)d+S>M6xnd2$uj%6|j!J;Y5J#Wba-x#*1%VPP zv&t*VOu&ioWT{A42=DS#C1#vAVozk%FdmRok(==PV^eN09%rva2)ISseB6ox%&Ij) zN>-*(Ii&(sQ`LoC0&h;MO9kJQkO#AFL^CmG-zov_YlnK6U`EnFX3{*VnhFH|x}GD6RWBFHi+gnSs^I~Nz46<>7=ubFG0Ft#-_9tnzK_AKTmeD*`Zps$z4myyoq$ zW}1)eMsTwJVlm=1K;a3oSWAFuE(z$hOp?d)-pb+`1-?3GM?j z=-b^NZHw=2NF;3sW)QTeky^p2?N5m9Y&x^Av$q1gfCi-7tB^-&<`k3ChP zUHVLHb%F#xA11^lwNllz>JGL-I7m7XB;t5+a1o9;ZNFP1R*~bLPop~MvX}@s34TG@ z^>M$wY`vN~1t-L+HoexdiYD1%EG~Yx z945Oa+@qbkv>i;2`+p!@vH>;}luiG?5boc8zWf0ZmO+Vw0e3|0lRlY-L;zb80|IQ!FXv-GLWpaFma#>N33C%v1~sYx>D=u0Eb zxcvg1xPQ{MO_Pjy7!+gJ*Ly??uq%hm3zvRzfB(Dt)30t8(mW^+01$$MeMWRI=;{rU zjWKZ&cLKfgIo0}hLd{6mvGCwlVikF+l*{nLh#Qvc4UWN7%oQ72Hp`q1$U>B z8X>4b_&x&KL%TlW;JhV@Qya448i!Jy_n(BO@w(HO@}>7(Z!4F9im#@CH`cI~sm>7Q z{aRvi4sZdA@ZLM?kfnA^(pww7Hrr3M@*#xgS-8jB)B4?02JgI$JejG;$!^^>7O_tG z#+iYc8OQyZZxeH&OLGw%1jes`2AdTLLQ}>AQ(mlNn+BkcG*Tim>h7iPpaSP7a54(m?FsrvRzw)j7-JC@vAb$)9G-%#n`UX(=_M?^q24A?t z(OYo)$rk8+W&J*9IlXZ6t>_bN)W@fQ)wj6BdGfgB(Wyn~Q*ggGDYY5EP7K^)xk~51 zI9?-deHZxry``Ij5KeX=ye_Q1PWEkyuYP^K?o%5_$3|IO z|D$F1y2Z^pj#pxnaz_(;@1_ns*N^H}Pb}9J?^6pa!vD$FRO@Z*?r|8Uk#>7eh;e}J zFij6q^^jg$#;L0hQ`bo;sO#kJbJ+wn)HKtG!Zpr8gMAd|C*;pKW|9xt_Lo14;VB7= zif7!tYz@9mT8nNfAH7V!|D&~}>y8+l_=fCd{AOma^PUT66G!^k2J8mV!T#fT%1SMH zLR=&UO1ba){M(mdk)221HcoFgpvrlH2m;X4DZcHk*7{ANHUGum9E$L-lH}A5C&ae! z{oLv8wtw5Eh5Jt_HY1we2dDi2_D@fvtOp7=OLU|;ZKOez6wUf%dwt|tsEIed5ML4a zgT~!J(!*`8+g!;;M(_9Q`eU&2P_O8+sZ(*NsGo`v{Fgqg&Ia-l1-s7LOE#R#azEC_ z9(Ue5pucl;qqqYtITRCvgZpZ4<&9AFqis?6Wm*qVnN;xoe44}pO%aL?|NdwD(e`7C z9T_|oy2tpk!1%Yq8ut^|JyVL}IO1Kv|mot_Yi<4 zyZFa`8N>E0(_ycR!OsyeH{ze{rvMqYr6<+~hWJTkrKwDO$&12YAcJ=W6z7)5xH}xs z@A|Mc+>vGk*EeR;+XcR=&DirN^63%33hw-Ff?XTGzXX?j{Pg&wTdPm58PbU%bs9M+ zD&DSxg+9IG1c9ZF-AR4>;CFcB?-jP9PV3*ay^HkWe=}?WactCy_|y*{p8R!U&;NMm z#k7*!Mo}K7=?whyjcZ+D*ORrK=$nkmO&W6Qx+CJoe>W*-e?GHcwcN&F2vDo2Cq&10757c{5TOuG|vt$j@nfWw1FK&!MFPK81~Hy%e$RrQu&MBFed| zcAubP41ks>8kh$&8Sm{0y*e+`eWeYnkXp|wMOVYCP5gssg;eXz$pe0o_;7xt z2|jW`?3NZu5pws((q6SWjlb|dRB;H&-n^e^tC&8?Y;<-^S~9BtqiuCo)$bz3xf* zBTCY9z)E~uqP!nB@OG@Pk2UpW%1p}v8KwfovLX2=;ArI?v>O0H$z9>KX1A z>Y4e(S!r=$_-E6$_JktD`LV{}U@8y29)e0Gp5TwFm@D>y@&L__LN8Y5UWR0TVutC51IV-l!-O4LaLM_QE4O0&$uZ^ z;(#cw-l*wUgwd?@)Tcbuj(!Qlvl1OV*`kVq0Bw=>O+$Wx%w};-gs+E0vjm^~+h(cq z^_0OVX?eB5yUKY+QZKqZeti6j9#f-iS>|W8Q*njJ=@K;gK4-SML{Jsxz9M6(@nh$h)9F$=e;Q*+f3?g< zcb_>L8JGGQalqu|SmG706&+Y<; zQ8jYGXvr39--f!gN$*5n{kquN{R^yhtSnO3cFn=t{qx^utNTak9%niVA_tSGloV|W zOTF?aWmf4jul@xjC}lLxBXH~7X>;|=uA;c`_%+UE=B|FDs2NolAv&5BZdj6boEoDo zZ`M6%hM=>!AE22mwq7Cc`$;V%pQq=?bm%%xh>dk;%HJeRE75BA6())yt%9ANN~s{A zlnLgZ72$Ln=r9{98DTMVVIWF!Tz1vS6(lrNWe%DZ;1!JQS{*KY${Aec+km0;_C0^$yPcL-p8&mjh`&=MnH5F+nR+SuH`g`%<+?b@#^vgw!suoA)MKnZoiix3?D1qVc<_M~NOGk@h`sq(z;IM2SiH{VW>!(Zh z!ylSkld%J%k@*||!l&x*^dHGzCkQ!2|HjDl;>fQA`mtj0tj5>W30WtdLxvF1_iR?S4GV8a{@Sjrixy~JqQmO zg)2@bfbu7^M08$jnpBA@M%BL%-n9MhWID)9w@Gt@iuqwxJVEgOI#^4#|2= z3rZi5xoCRsE%r2I4>zLJYygUk$J^6@5(bsz^x-7&eR%>}C4tj@oFqszK||tVNr7!EmxdkZKF*3;c8eq z6hUEnJ0|{QIviP>pyx?fMuP_kXbvtEKut-_VUu+2vz>;m&%A|>{T?Ch_r6%H+#w83 z>sQWtsIxRVtp#W$<@{FyEB$vHw(+JUYHmulA;D7Zt&)N_Z>K?xcFY>rx5fULu}F_8 z#LC|a9c6xEc6huEp}nh_&dmM9zG=fIi+tuSrjdIRL*U>(RbsLMKx$A~k-sB@{u&S{ zKx0C(bQMDbKty>+4TA9CF|Zs37y}vFpafuIqzO->Ywe_yfQ*Fn%mXHaWC%w$HO~@F zdBM}M^Sb(0MvI5g`KUfVLTEbsjV5$yhe%p1nkG`ZCmqX1GpD9kr6H0JkFoC9fC5f{ zN}5ezA?|3Fr5=RvD-1D3K!(1qj%QG3%i_2C^m^a&$_FzV=22wMAVT6kNxu&B+opl` z5Jm@j6(++U)f~*D=CLM_bt11JRn`%g0aTT&qfN zy4)A(R0EWTSddG(Prl>p?I`aK7jC+-PW5HSKfqjfEBW{}c>6tML>c-{Kz{7IXpqGw zXEKa9nr{f97K+%xwDgfjmNg-Vp`NhU6=Ub58H-}NiI2H12KXYfwr!N<&ZQt0S?GCLXPla?>9{t3LI4sb86<66mYR;Mgyw5`SX* zq738re>T3a{7Oh|iYg^bH+8Q5bDV8*^d#m+&mDiVbtmk(mz(M^eZ=(wltiht=UfNw z%*7FFigAs853vyb-Oc)kRN?Z0@FH)|L0i=|w!Z}HOe-2reJdcHnqLd8ZM7LZrIfk-3E~i$u=biBK zpk^|PW*OB@ba&vl%x}&?iToi+sUd=Cs@|oTW}hKL?9hGgA&xTi{UH*jb&$(fS=Zuj zMvD(^DylOoL-QTT#2f-4;SbI7YRD|KE&79PRw7jgpCm&jDImS}<9jo3?gQgq3v9}K zC=pbjeD+H1Evfp$SpJOfDT#4KFUAwgoPU_oPOf2x~gtrDchln2Upl1OT%UR z!_T6JX?4|}ohPpGM^Z9I&OcT6KF~NjLjjTLzevjseBOt8bcR`sJUbu2i_*w;V6v}* zNC$&s|KyH(d%VMLQlS8`6e011K`$1gN8_;?(XTtAr8Mo&HFBg#lym`&D1yx#)+c3S zX%38c$;dpLMqXfL5|YR4(Asv!<7Gqym%kYs=aY@E?ma!w3hYu-A<%w@Q)c5H50=z^ zlQs6dc3e3t@rD`z*d=K#CVcRCJU0s&IHVR6mM(w;n>;0Y^b`EzKs)$)TpO%qvN_f$ zoR~6*YH^?dj+St{>okSwq;F=pbjmq!>yGzL=)Q(y=vj#B(u$_3bsKf1 zM>eSx6CmSZLoZtzvRU-rvwS2@{`89fr94sO7b#-0)%d9Ci4P7E_^-l&(eTXcC!l$B;JgSqhi8 z;;wxB!BqnI#oJa_sCIE=s6IH-CF--_9f}t`uq_4nvxM;LdkI8(%IBXBknM+?pUu4o zV}qg$+|W#)#LEo;8jVoClc)$&nOnA3&!+CT#nhj&FV|uB@ufL(&q2gg2+aVNDM|PE z=OoqMIm3{Gk8R?gvsw%VxfliG|0DMP3Im5Ch&(Yd(EuSz@7ouOBE(Eic!Jpz^vqnGKuiUkrGkpP~KC=*jCAOEzfo^f>X*R)cw z+{x?{$ecIr+*6)8pSyFuYIA-M=lmV#0{rI!W9EWh%mtS}^1g{i?t)YibNcW+{i?YL z$UKJJRGWX+t3w$XLkYT)kBe_L^f4hb&vR^y!HeEZi9IxaVrQ&DYht4|laexH^K0H1 zvXCY+lg{&4|L#KOjWlheF?$u^XPL+8hx0ii3%M(%c86VtX;43gI9up(nJJ^{L5&AX8`66PuO=ndp)tE!$3v(txR+V7&$!S`P3rp+4Etw(Kcz|Y1cn~3B zmCfP1)!I=Tz7N!T`XE!kcmeVUG>Sa5CYHY*+R!;I7t4q<1rY-%_Ht*$75y7X}Mn9 zF=VhoWL#A)J!~bkoyf+98;_yv8tT#C!ZXgLsh}ycC!U-E`9mse$ zqxFC?I9j8(==G-h-9l;8mM zTFnvKp&(C`BFr;fLjNOMmKXh`TJgg8F>MI)n>XFRYU2^I-xxEsaM{8`mw^RzZDYqOw*zP<_O%d#X7^DqE%hbL6oS#iG zZ6OLF&eQCYA&6|pOeWhz%+$z|JkB>gqhra+0C2%pve zX4q{xY#)2UQS>cC#EYCn$fmK7xyj085>7onQf;K8C3bKmfcj=s0Dm)Z-C9lDcnE)Gnkrn z>HFsK)+>GytpXsz;LS4#w-^r7MGrFqB<4kN(!Ph(>+bX!p1Bo=%}(rMNp^1YW8a*Soc?HoC+bli!O)R^2vEM80d5}u?=$cv_5iNM=mC5Br zzv1jevHP~|P$Gb6pmyt@gEOm%%a&8V)n_O4ER{30U92}ivF_Nh`&j7XlYdrDqGb8(c%-H@jO5YjK2l!3p zNeMk#==I9E!Z0-LH?D5S9$@4Ae$MG6%O4zHJUgXN^#L%rL?SSs;t9WB{M>VTvKF2Y zvIQZV5Fvp$VyL@uh)hW5_0ual0?b{NuegbmdeTBl> zcR<}k>cIl1bMW!ImvRhBs*FXxOmp6v+2QqdE=ol{+Wy#7}j0P4xNP2XnTV_w!o-KyLBV5muua0ZU` z+fUY2O15=Mq77xXEyj3)dGOOls2>6XsVUqaW0QzTfx=^K`0vN^10>+lV;;X`!UgVq zInj#nlgajp6?+otO|U5zQ(e1m8uzP{B9VL=GP<`}-m79aa+T<-gx%UA~ne&1*+bBuI}G*pcl z{Cvsoe1wP~Rzt;x?#Aj~O>uX`r4yBMF!4splyaMu@`iBU0#9K!!00|s5h{^b8UKbx z^>n4f&qBWgm3{}zg=EeVRUdts*NSO_Klv2kg{@5pY=j7l#Zv@XqyxBZIk{DV0JI^u zx(_#i0rGSn?1O-s>(ADWb2qH>CPON*=^6}o+^OO{7I~xQP4MYd zjIrl#!%q(U-v7zsySB>q9fxA5yxFf@2~xddAG3tg)BU50NO-nN5Y-p?3_%>p$={(= zg{6v*ajS|;X)3#-IQEJMy3i2tYK8)QF{J$bo9|h@9=j<9iR9TO_v{Rw*J57L#Ee3I=$_{Lm+HLyp zSX-i|cs4E2;~%Wag7a-}<=f%`jJf(S508a0FWAO(Vt$nl9}V#P3Cpp)fLKT$wY*KH z1KsG8A%C1l4WcZ)?Z3#RBZpq6iY5L`UT`TAL@?*wwrzO@`)}@m_vQ^lE z%cjZ%z&)+Ira5M_Ri>tdZga&&!@n?0uTb1Wd=4&rw-9dE8+t1XVH6H%G5@ftG~cVj z)wCySt48;T2cyn5c`m8PXtWpdt@+2@rHo2}u~Py-vuS8uYklmWH>O6L&7_ntS_GP4 z`BkWBm*86K13l1M?p;Q<9$yy>B3hg_mJK8+t%?UODHTV_-dV%T?Z93Qxi zgW|TBJxA6ImVLD|Hi5~8aMo1-PD`k6qidAm>|A_P>QQsgR;S0?8QJ3y{}*3giZk8~ z0XH_!PP{xkSilLg(2;w0<zjHzt>mC=Fb+^ zZ)8ecm-c0PKW1RGGp9Oi=6VGjy{109N53HB1=~hV40&JQ=nHqo+gZM;Df}mQ@O14V zNoyQO@7+zvPWZ`Dj^t;T&*0rj1EnujeW9~s??1fNK9o_`r#{GH>sEE!^hq+Hc)CiQ zG98M4ryJz&%?wcU7~q^a+g=PEKgg^@zPs1Hs*BH@agb^|K5DPUfAkhF%0O13;DQtO zA*({8z$k)bfwGtf&@cqJfD7n|ttZ?QgDR+GD_+$-kCusMC%Hda=9<4Q&WtO7Qjffk z`}>7^q8Os=7D*0LhXc_3i>k30*0Pz#IQS5$d?^5+?KcQWA=2oXzU*he5jE0Vo+jy@ zO@q%?vR9h+vz~e*X(YrGlg>(YkbKmlI1qC=KSX-hw#H=aQyf&FFS&4aST+Q9=Zqf+ zh&M<)rS*=s)a5t=j0scalqOcY-2Tfi<|aT>B==F5>6*Dv36X(VmUcf-S(94Nhl2X_ zLXJt>0fcB7L@aA^b8gsR66aA9jEca9#z@{`=3mvPs~f{R*r9Ss3yjj$=+28&zjfJ? zT_xK#G(jQ)A^@kPVVcE315}eF&weZXJnth>`=~-~*7=Eo!Y?83w^L>@$NeboA7n3q zy!S{K1p+G2#OrC$dmS9ly~*NIl=e&beJDwvWk>}K<$pY!nAH1yg${^p! zwYviO1U3oa^)uiLZK*VQS{*!q*f1st_co5+d_}eX^_$A67gbT+`<68!Gw+;Q8~l|q zY)%)+F+dEDmI??sn)r~mKC@E7RpS-mKukbOYb>V2YLJEV_0df0TZ~+_g<;~?X2F*Y zzQh>P!gQPjQc99WT)9lwX7wN!=-ZFQh!6yVm=osdw_~>ctymtKV z9>?4dbf>hi!|v(_x>|&$K#0LQ^Szw0)n`eh#gh*s6R;F?2otjV%bOw^hCQ_XbUAO; zrVW@7blrW<$)oVt$K;)#;`%?zOUS12q><%mw}@w#T(7*;t=F2gIketAi9*gR1I@yl zBf9^tW}s^)shH3BRpkut88IP)wBibyOH+Av7)#@3&rAWN(nhP5oa97U_R};VAs5q^ z#QL?=>cDBs^Ny*uZ)8^L$}ltJI%P}R2*1pV8(;LFuRPWD8dWSAL?;|D@jmO)Bv#KC zn>pOt`l?XCsvO?n!>f=dcNeKI0`{M_t07ZH)#Vq{Q`C32ItvQ}xGMADWMb9qQ#e(3 zRS6e)7n?7~0j-O41yn4;(d^eKARvT*^x^^+(mtP|s?THXV}ul5VN2@XIDC@wR*u`i zD-R1atUt@L2rCU#mmNuA^~@Q+uXqg|ixu3ACm^b3pnUI|l26u*s~#jLy}! zDf#1Q8oWYDm$4Rca}}`XEa~jk8FJ^O{xS}+F?u2vMG$X5mizVB$e9K5fOzUk6yNjJ z8QQhUH3bxS`)*ouB%X{7@F&9~^=gn$YX|H_B~Zo1c)@>5`%X@FJe$rX-5pSsUYefw zEz;;ApV;tsyI9@`M-0?FkP5_cHejs$Qvh6Rberi*^P|%AjIyLxm z(0^ak-%)=3W*P}=TB z;%%l=29$2gd6QKIMj4GCT1&D6_sw!mOyK_tl^ zmVOz+6C#m1iLEJn3`n00N_(iljB{wDGkM9#A;=*zVQRWqR;y`H%%{f+ z7>?g7#eTn;NpP?wo|mQ$#dPG@zy8IPOxAq8>{PSgq49(CehIhRVu5&7MSc)Hp_Sqc zO3Y?LwMxy0b^Y_&hkM{9R9ckJ)#TOM>L!7`atBJo^uDwjZPspBz96n4ro1NRspcX`ot6F|99kob8KvjRX&823q5U&b&$$f94& zV^EqbnzqG!LG7EIirqB}m{`A5z;xZzhLhBRo+W&fp~52P?;sl`nzAYyp!b@U2`u=A zQ;3f37wrqh6*zh~jnBIeoncN~VR6{%z>r}Z-HK__jsBCM#wn7a{m)K5#9`okLx~Q1 z{{*Xe1=eQ)E4hH!3qKl6O#)Ue{E`8JWgH~MDv`82Bdak=v*kn>0Jv)7A>oEq1;aC% z2TZ+?JCj_>9_vs!`wb}*mBv{2zE}?yFwLti_Pxwo)D*yk)u-BW(#NN&XfX_wV6>Fbj(#R&R>Gieax|AP2!I4q#mok( z7rQs}`jueZIFc;LD$tuwG4(qNb}ot++b~F_^fpj5C?ln~@9xQt@4rgFM1TT%n~Ell z@;p7T-icgpH(4>&=t5PBf607$JBD+ctJPU8`I}^LmE8R${p>~erVR}D%Of3)_jQp=d{_x9HyDAe2pu>vT|CAZA z_CMoAn>pp^R0DH*94*vcX%hQb=2h>_M~V2UDvS~UY@(zDtCB?>Q{>!ikQhO!v1bz> zkn0t(c7l1IS>vMAfTA`aH>&h-7qJruJ8JVC*wS2Fd8akm+*jzk^g#nE6zZg_m^; zg(8a;o(mxW)*#GcugLPS$U<}7e>&K{9WJ+td^KoC`YtKs>m}qa)Gdi~8e#q9=q6Clq&n(lz{KyK~Cha4OpHlSJh% ziw?io@lVbHw#|MvMAW%c!-dzK%YcT<@FypRQCo^w&a~IEr5oFF)CJ?~%qhwY4uSwo z!jIcumU&)OR?VTCSIRov1)c@>WOdi176~=yGd1pN~q<(%_lNp z$}=1++}u^FefvG8BC~FFs#v_Wb%<*(8zBk9$AmTxi!1<}1Lu=(9(LM4t&)$^+Pp0p zU3a3ON`FD6vtp#rfie#L^4|SiRjRx)Lx5?Z9NK9#RTv-^IY#mGU0cOC+rIhou4I}3 zbvFbEPf|bFsF+8SsdwgpYpQnXSIV7yJiAq47EdKHQUhPKh=ugZt|ni;$%YObUs7_$9;P-!V&0) zsWG<&t$ZP8@Q^bOc0AbMY=_0BGQfwgJ!Q{`5yNk~rcA^mv!_O1R4W;wEzYMaL@ylu zt;syux9HC}yZjR68(+$1-#c7b3>7+(jUN{AQh_vA0!o-O?SLXZSFhnkE1ip~VpS?# z%@6WQ%Fnc@Pj#42(dSq(rVLKq!0KcFbdg1irWn#;Hp*gzc0g*5vKvlWrJRk?aZ9sq53Erg4 zEH3;-jVcsvB>&6QsxIj z?q<_TJ!JN<7{PzAP*N>gY&B&uEvY-RioP(`K+CgZYo`Pq-;biMaWvD_%JKd1EH4YB zv;*~-ZQLWb%Lgv|trlsRtV8inQ8CGr3{M{Ya%A@#xbpvA+Xf^4l&cJ_@iOyVYIBfu z)9OBVi31Z?(Mg>&dBv)kKAl^Me5>tz$=thRYT+@=#y>La>mO>8yQLzA^Hx5=S(x@K zG3@$X6Z>Xf7;H2NEs0M~K9E9HRz!WU6=1MFZZl@S*DBbqD(v}H(Q~@%vTh9}yw0ag zhWbWRY=Ib5aySp)(2Ov0_bO_SejQ|v=quBVj${wgnV!~5x%7{=vrdBSZHobFz5WEu z(!~!*f$#v4DK(kD(IUw*zAJ5>H}^hrwisrD3F2{5yDr|9Lxl0Pl@c-ml`^cVK`Il` zH=Hd0F0RrJ0hd8C7Ndhoroarzlni^8Or_uE?{}cPf zhc7~c^wF~87LbB^sPsLA4tG(j8d8_JlCUJ)RP)ue1@$aP1-34i1uE*B>Uin?r;Qrh zM2`nc>GPLaDBas$NP?w{|=ll2vkVli+gDl*U^znmx z1bxs()jML!G&HJme(E3(kVJA1$|X`UK8m_=KmqAQ_oqA7GjatfVd*ibgoJ(i+O@bL z{n@$dd9zGv$mL57w5rk)4fDHB((rGe&MlJd1iqD_q@oli##?T)KKlJi!kj*T@haSy zXKZS9(k#JA^I?{rT(ix8%=NFALp932K5dJZTe}R_24k{}g1@U`o!k8exi0fbgESHE z%+as)n7}->(I^Z+J_`u;>l4O;@`C$i;`_E>SXqxlBfn^HWC1XKz>%$wAqXg$@&T3> z{=;|V2lf8Sqs~F0{d*)a6~SW7Kq-p0ENKq8-zURj?$CR>HrYi>)O(Q1V@L zIwq-b6d^z5$R2%{_>e8`JljLNV>^MoXAZ6j_S>FfGtk@*6zuz2%nlkFjpmJ|1q+(QIU;&vdyFBYM01E5z>StexE{?IU7_uG=2Jp#ou~MFD*37k6)(`3~#Ku6WucEoXM-*$%jrU!%i9G zw9WI-Yte8Ha*LA$5x51#(|AkX7mLhvhEQtF;-m;Uqcs;3+ejl?-ulaZfq2js#! zAAT8|YHiT+${c6DO&TECzrB)dep*@J*wW#mAI(HLQut(jRnu6%=})_Y_*QLmRgZRx*4HY4_I#ihE!?es7Pc{Gp541@%NI_^bM=go22%+*z| zVCO7Rqc+|KgN9EZxcvYPWZ9T*q_~>p)CO+xFrd;Q+>cA9P23M>fogW zZ*3ECGZ-juW~WtpVrkzW z$H^i&WL>&aPGGrP$^K}r_FfF~RIJ2d&{bOg>{|jJ@8UamC#oQLdApwZfADpeL2b7G zy08-xGz5Y>1SwFgP+Hs_3KZH>oZ?=jxRv0pMGKVR?poa4-P&Tsp=et)Z=V0N-o4kX z*|YNLp3Gz>bA7nynxC8pah@cjcD@phkI}7t)}pd|Sc5%!|*0)p@E7y^cRV zoblaRl^;`GWj@@}R*I%Ys8Qo)`KLKc0wqd(1g_~9)=~@V`4Dy!#$DIEOaQ7WJm8Vf zI}Def;@8k>uisn7P5{j&1JyuprCTLJoZeu<$|(uV@?jvvU2L%XmkPb^TI#?qjQsRa zn*0qMYonn1x@IbbODqyYE;Y({UCqE7q|BLODfc+EFq}UihmhY>I(FN^L#R~=cZjr( zat7ulg-=EGyjJW+%Q;d2*W??IN&T#!IbhXBp60BWQea>^vX`HEUPva;`m)#8$Q1_z zRmcRYz1ED9v}aM9Yi<|c;bX;8+T<>_YLCS~WO$yt%@+4mIqSYxC-#{IIlm0z&E*!A z(I_LpI38P6i69^jKbO0=R+>4IIEnjO=9?=JFHftSIcY=TNrDZDQDc7GC)usVFJEh8 z%5AB+oeE_?QnW1(!#?|SWx@)Y$IJu!65U7&o8#w*ddy8SkAowG6lcaZH;Ch@Y=Eyb zKd1%e$8r3~FOqy|BX3AN9dtrFLVgemdAVJ|9QPMn1fP03q3hH8{L3AIJmsp-WW@}{ zI_5vk<)sn1iTO>w8&cXznh};P5xaMNw1SB}$rJU=9N!}3Q4yMsJUrAa)$1KMTBu3H zm$O`+i2UF7Dz8J}Ne<0J+X~3Pgaztk%*t2cVo>2XIU>PPZ5MgCMyvw~pX>AGp2Jln zt>;Sy0v)=aQBysW0rnh)l)60+*LxoJx*~SIoS+-<>}}BVl5G=vKkmb~!yHqLh4n~x zKjr+rotc+uQ%w1Ad@!xPcAEpZtm>J)DbVSkoqiC=2e55>p*zpy-q0z-i7oizb>mJ? zi9*z*yoeN~uKC-#m@5@4#|Ca`NzF`aLZRG&VH_$DE}ifAjy{!4?c`FYP_cI zuXb9NrZ!=)_`ls;1G%QXk4*?2^EliIw z_cLK`sU^L(+u|qfG!N(Y=r?-%hs|Q zQsNKO5G5MdNvwVT47zdwEXqC7^yO4Km1@fv*3St!mDYKfOZ(vthp3)xIEWMHQ;=Hg z>xFEit8C}SQtM~{KP$ip&;AdIR@wDbguX!TB;Mie@Cq`qk?(4!#m-3bro6zQHqpav z@?#Q^|E^r6HsajgO0d=az(KGT=rp&hxr$sZJ!Ts_BlKohT-`dl@~0Tze$5zYN8hfh zG^ru&8fU(t-NIh34P&Lt(x!9;zg_Fy%DnXwm4-zdcgWJ+qxeOhCJ@+9+A7pfRwtW| z9mC2z%zwR`z8OW)yHvhdWjaO%Pkw!W`Sn{G$WhXJGlT0K5v0!_@K#l6TBCan+;NcE zDKc*LtH0R{^iXF<#P5); z&lrFIKE~qBy?+{r!RB<&0Rug8I+ZY`ayLiepE6+?)1YvAaaeK|!XJaFqEN8j#kBFi zt}^wR0T^PAQ<)tf2CzdH=nKma{}lJXahcDy9O z0r>bOUvn{LIZwY%C3b*QpS|Ok?_A7!0gz|}o?ZaMTo+D`6RGP9MwX5565S(6-UV2E zTw(k+_-MVkaIW}dXl)W(ln^Fa1qtH9=gXxS>ZYGFp_Q+*Y~~|H55n}<2;!KmKJ@>_{0DE$R=yR#|@H0y37`Wq; zRD#;g1-?4+L?I^xa|=2Re};vGn9~5Z0)EA+I`&zB@Dl4q0#*VoM3bd^3ckU0TaM)Q z>|!?E=rEcgQv69@#>?Qw1o(aW$67tmGAKo2hV5ky>uXJRW-iu?=ubzC8e*mpg9GA} zTDL~WZLV{631@2GkvnUGV(((MueG$Oa7up3`R8vHzIB#o3}&WnpPXc&`KafL7dYn*3ohODa(u z?*p03Fis;i?=9;{8;Gge6Ommrz4%?kILst^7^LL3#Htt1UOxRo{`&dV3@fkH^Yh{7 zHk%YAm46-hSuV~WQ^oK%RDgN{c)7YCeT2tKPgvwKkz^8U6((g3nZ9d2(J1^2k@{)(JN+BUw zIkH|mva9D(7N!iXN|Y8%zg|6)asDJReIeLVN$&Bfi8p|E#pIC{6AqRMF;9*PH$YKP zLDB1(To?wk4L@tXi+Ek7KtPiGB9z6SOPSAEnJ$VP$Bafqm9-0@QdY0NjQfI0;RV$7 zrA02LD>mEc+@mhd{_jvV?Ifj&Pb>{C18GupI3S2E20`hYG^rdFD&WftS1DOj*2y_l z{@fQDjBtI^uu}k>F;xPk`j`JaxY3CYSXRuP+|m z)iVH|YiMG~i;`(FUOsJ|kwCe*42VckWhT9K3sk2lRoAlCo-NRhbJc%`@urUWk@1B_ zGT9SCbHSxXx*7g)GZA$E zCkBPWT^vCmhIDuH@bLQM<|ydlBj~9w=ur;D^#0=!(galPA{2S*x`rVD4~Ez@x+NFbIM{FYA&=_2ZZA+@OaH^o(r!j0RMH#~%R z5AJ{E;eXxafB(lHD1^ZDMBp|fpnnk;+J9h_0n?m>zX3$#LV=Gw10OdBa{mqF6AF5c zem3znnW;o=B6)kH7kPu!m;b2$SXADm0Njx~&6+xK=ZeW0yLD^(bT)-%{RwSN^^E!B zS<>Y3+?Zpc3&W||&8<1ykJ2+iD9qn8;?tk-tY-I|X7B#gC-cN_e}!Rv&fz6^$2zZQGLHmDMRu7AbZfbB{>>V2fh_S;IBhep|6E#$qSxK6WiUiRNt%z>;Cc z>C%xMOp9KgW0dH^i~K-Rj>G{NldhN$=>4{sPt%G^W`&X4%WE+Yq=coAeYl`Z;^VjG z^eCY2s=cfra_$Wl6*R+JRxAzwgqMeN`<(8;gsM`@ZgI)Uikzio+j1j~S*hXfpxN%% zQkv|w0V-qxi3J$N$+Mj{Bf`2?cqc4bpByv)n>kSHlOPpy?J%<>Rh*)5#wRcS)UR2Q z>;9KeE&g1*!mpnzsG_P$o#MX6DE8=Y@iX@{WFCJ_y-v^EU5-qDnvM@|eds1%`igPr zN=(d%_ZRx**Vbn*stiR8%m-Ih!N6>DIAt$Y`e6FYdtu~sL+WP$J&r8>UWGfrWk0P9W3 zAr(^ebJB4TbP)sFTAFsRo7Nf_55<6_Nb4r$;Nj;&Vu5tqIW%`zdObPx#RV<|*Fm8{ zyePdKB?IbhV{hZxJghxqBFc>_plCIwPc?39HB`TvBBzSbrv`hKxIBm9Z9omKXw7{~ z^&dFl-!6N}8>id!Tw$LlXCU;rDb0cmUZe>@Vi%+@hZ27iw3I`U2FHtJqzg7B)scoI z8k776$^y{^VrkM$1Q}_F;-(%#0`c@gnl^sD@`|g9lS=%f2oa7+OG#@>#cfNCXlui2 z3nYL5&!n~cwnZx-xkt3M^|rNY74`rpyo19Wy6R-TOA9_5Bnyj6NYQpksdMEL9p&_* zQCwOoKvG{a9R}62aRsM7c)hes*~nMnLX5~9UU>4?jMipMmBO0MA_x#)sI3=;4xEq{ z>y!8Gle~lOtwWW>`Xy;$pLs~%81$*p_DlP=-*@3tZnWpzWJ^P;E%!Z&C*drUU_%e9^8o3y2 zjDK5?9(v#yc^?x9NA&Z(nva4GREFt!{GTGx6-?@|^TAwn@>$yPu$H-5IHKN5;)&fr>4r7ESo<NN-+XX%g^-JHT_&1{WxY0LpdW11J$>8ZI#KdBnLrE#8p4H8i-q&% z^n~D32`v5o#URQG<J?u0z1dt188546YC zex)a%_Uv!!xvX194+V;DeH~n5axH!oyr=t#ZSMHk5=9`<=9#dxyFwr1)9n4Z&80P9 z;pMzHzt{Plw5ss+;=b**{%?`b{v$x4S8iLVWUcQ3)WbC|>>0 z27U7Ie1g}bl6(hMVsa(Pd+<}*2(P1!fvo2xo{wydE#0iOB4iqhWlUSVh%%)(PDk~P zq#|t!Kc`p{zvKLd^*ZYSS1(Cp;!>9hX&f&?lJn%lbwTRb@BwYb)N;#oUIqut;}B5N zc?xYS!Hc7`c9}cDa%A^_|(kWQP(90rEhk&IkaPP>yMSbMP9yF+91!jtH~_v zFC;pao14Jc>3~!P4mKto8IC@Ekya<{N15p`SIPIOW0@)PP;cv_YqcV-M?Ej#=YZ%h zPrR=46z-FODCdD%d4u($y^u&phnr1sw(r;b(eDk{71q|>_g}|8Ab5)|33aJS`kXxn zt5^HRB~a126O8kAi|ve{=e25q2=+}g_M+%qH4vxBMHzRm2Dc*e+^J%mx zV9GLEoMI`*E0b|Zkpg`el1a~8n$^%Q$!^p-9B**-Az5qc_UGTeYPHoDlp?TxGU53) z%tOxAP@yyH^%_6WG^XCI2(MZV1Ep`%Fc#1$<~_zu(4n!hBk|qyuu^u!yV9O{U*KnJ ziGi);6pnVW99nm~4!0Ga-tlnkMw>4b#(2}`svatAyY~LX}>t1L>b;ayPa<|o@b_$P-jr@4ecS_^;wTvK?Y+t zZ&@e@=;vyWk6B9IC_4q_MHr`93Kp##SADo|jrg>OMJkAY%9cHu~Cc!1L0f-ro=R!1JqwNyxt_`()`fr7MSUewCm0#*h&!} zzXwMvr;i;sE^&Zgy${LZ&tptxPy9o47~y1}&rH-a6g;KL?Y?Hb_CV1k9;*4+=@3pi zVAb(E;6>6V(<7ys)PzuRd(u@zm`Lmfotpf4LcQxY7vWRox;G#Eoik`OR=UE(*1F@& zE?L-@6^Awo_}&hSF`g4AMk~qX;0>{deKvnQsAubv;W)CR_dz$s@a+?uw8KF{H`7q# z^Bia#qZuPn#DMGoe}df`C4z_U5VdcK8F!iM62oq?K0kS*JZ>X2kY^;46|c<)NLj8w z3oBu{1xmJsCck>KQrj=ztzLuxHXTBb(*$C`JhF+4TABG+ zP^}?sKXiE&%{I*vj`EM(FSadH_4=;W+U&TdmT$vqW#WrmxZmb_KKI?ZLzfEi( z*YQV1nZPkA-++0Xx^7Yx2NBZ2kM!7sY7W;|cT!t93wJ+qm#^WEQog5o&b|lquPnO|lX+9R@x?3R@Jrr`( zfoFEq^Mc3aKGA?|r?KzrU#4VJSt2SDW`QBHtEc<5D&`cjuyM;1ew&Qw1-5s5Bf2bP zoq;wChZw@O*{&#S_HHp1rPNn5MQdC)0%b!c3Cok25^6CQVP+s7Cw8y(UbEe?y+6CNKuvAUhO`Bqn+3Ux4h)Ea^@uu%tDqbK^#NEi)dd{U*RtD^t*ds;!0 z{%K*9T7zE+zh3`BzXrkKHV@HK6`s~ ztI#&jRYcH_f?7GJbAFpuez)4Ct?xwlyIIcvbH(e7w|k*4y;r3j&!+TGjtipb)_Gs@ z54!E2H3hUu_`nNGrYf#fwr*!!wBLPuZDZ5g`+3;xmyf5lg9BmJ{Yy&?-S7>E51$v7 z=U3Fd{Mb&;BU8WqN*aW$<9^rU?`t{`PQhg*B6JO}x;u=q^1Y1hXereGcoq9ve0zd^ zqMlRv;%cMKPHX3F5L?F~F+=;W5Qn4cx{rUIGuuGfmEVh_B7Z9{_u5NFQws7b^tBMS zj|9Z|RiTW^io>!GBM2WHsI%8-8?$KAsxEdZF8w1Hu1@5$@4pXb@5NJm{QE1r@z*H9 zwZ_{ArwInsyZu4w@C2XvFm7~gssXnDilD!7nE6(iKampajg{-2p!LHp{oWt!gCctwHs!QF(fGg)E6qWh|+dlv-ECTeE#i^ z6*qe@_gUbuHrrFm4>V~{-n>FErZM5{If)AeUN-r$Tl>p~hivXXCJ(oxq?Ey7`*5r% zBi@ZAL24^ZX&;+vs-+ZS_bITXDNvU^Oh`7MXfT9sH$*rfxToF){|ZYmJjhwl5zo_) zbt!c1Pw01wFc+aP`6d7M8Z6_bu=p!!fv`|^wvZ6dz%c6&!lCeN%ExZuM7E*CVPsn2 z3)r8QP&8ti>bs=jzltI<*`s<>A}Er=rT>9&X>vU!e`-?}=`i>rBVWj1cLr#ru!mnM zgvSkr))!lSK|{EnuvpK4U|@8CK=h(k#1Kx@*b<_kDM(@uQNtSZQz?x?CEs+Usn?}B- zE?I1WHJ)+fN{K>V-c7|eZJvo{sfjgW9W{TDyupej{;> z`t-s|G93-fA)&fm`X0rJ{L)EpQWI$UUP%-sF{C?sERxycl6!@D*xL|gJxXqPn~bEC zj4>umSO+&w5r|2d7(GrhhNakhB#B%yzI^`a*>x~pM8t+rh~R#F9!{`$M6BCa@3TB; z1005hAjmsSMLtan{*&l)%(wIvcggfi$plO^9GK{d(39 z+%FrCzicUg+4f2cH2!>|7*`@3B}|nbN0nR|fVn*dt$mEy&x@_Rj=8CUk8y?q9!)`1 zVVM2#1aBBI_IdF&*Ksb4aWQf*Z{T?9U3h=iHF0Zfri9I=Ew(SVU6G?~`H zsA@12k^8tbmvbbS`yls8Y3`GC?9&`Jv`H%%nI~MDCmNYo3LpsquB?UDtt{wguV;xoF!@XQV);AKT3R+zT5(WXg;!R? zQC6o?)?i!K6j@fOf@`No-U){Q07Y2RxQB2U8m%n=0O@!k8|yra!Z4##LID6^ry3We ziTBMI#uTZ^ah4gy;Xb3BwGfd7&Z%Ir&9#oKWWNEhB5~x_D}UitopDrMs8n51SBam3 zTu(tFT~+r7RVch_AZIn`w(7d23ak&>=P0x)t+o~^guW;wgwz;w)R2r8kY!ZbiliEB z;QY`4c2O6B0zf~f@IZ|JrLTJ60Y(tT7@E220KlJh98du6fiW!ch8(T(s)VK2SEuhf zWj2F-1opp_<0e;Je^Dr_4_Bg=M-se&qhQ@4FeW5)7(qsdgmxk@^)&E*NEz^m!uUk% zo^!$kGb)%zD#SBFJah@;t5c7sK+D7N>Ls6)qnb{a>r1J!^8#>CNWy^I|FT#AiGn_@ z!H`B1u;{}9o@>-iaKNTGD&}k}mTYq(M;b@mlYbf$>MtiV+BCh;kMnJ9I!4ca&?gY(%+;@T^VwFWR9AHZDZvZx5l$a07AUW;G4MhIO#!Ddgl71dsy#SA6pn5*^=sU5%@zfk*ne zSZuW|dIZ&$x0)pKH))o$Yvx7Q{Af!NQMn<&h&~T%c|BuvD#ueLQ|85gGMKwEC%$%a z|82watuOXzFNmrK9d(O(h0yr=(~W&8!|h>d>tV2O=dqWi$#_f=*;821!?f0edDl}0 z>E)vBB~NH~_3GV7?FINYJ&o=wTrT*I16!)}>_iRnYt zb*Q2AXoC#=kx<&X%e+*viH*zG1F8P(=_ALbjQ;S&>2SV8D_N^rV8Q~8w!V-F3#~8?&Fy! zP&7|F%da;3{Qaz8%&c(5tmycx`0=bHbWWOkjxz?+GLKj`W=^?c?#1|=+VR{=C~97F ze6HY#$ch*fbU(=#HGfw=uOBmMcszfJzhDBLG*eqRv0t#tny{%@*d1HAGXU#2@kyEi zq@+NP)TYe>7JVwFy~h{*vlb!Hr69WLk7`R{<5QtAOH^tgsncdT)3FS@aT1|rT9e*X zy5&**WtxEHjF{f^7&vmAOdy&$SA3-~i!Muzy429OEM`UPb_Jt*g;H^ag=n?lc-dcb z^>xy!$kWvpztzqxik|mg-F~Yv^{b2tYYa7OV}5Im-&O@>fCWg+Jic%9F;t6c)GP15 z&9#5~{_We+J;hqqxAhq3ZE==8I+la>?>kxFPt?ZGxPM%z{RhI0`Egx=`f-bfaF2hW zpzA=MbP0B z(gkibR>LsCH82Lhb;92`d> zf1&74GY|xE@!&VS*tIc8yb+|`+36Y2*`>p;zaP~ofBgcWRZ=P>NDm2cLgKa{&&tTz z7|uvK&&i*_GP>v>2v_7bEZh6r#R zFX6<*C2r>_6vdOvOW>A}p0SL+W4ye+q(HYL$c-qf5zwLl{B~YgKQF%5*&e9tgdNu+(40? z_d7FqKP4z;ueXwJDQLBFyf(_<87PVkIHVs*u(pm?%wgMUfa2T}B0w-M8ISqW)P^ho z1!I&upH%6wtcN>n?`fF!KDm=~Wl=t7mH~|k0O3uw+b`1iEGF`GUC>ceU?>Li{E4y* zy3P49{y71L4BK9$>$NtBu~8S7xxEgTWVb62+vh=!($#u8FXliR&m&fcD7Z8B(dGH1 zf>xroo9z|un_`(<1t7v$8&4)ocY_?DF}lFL)+}6iUcP!&8Rq25qz>*X)t6x=2TCQY zkU1-UjcQtv$I(3>4(W{)kBM|Tuv)62bTz zXtj>?wVH4PnYN*q{E)VBNXRb+0pO4cgFuWNp7KQsx<8`t@~vU5lTnJCka zuT%N}qi9WC-HeKcHEUp+Y$oAEe)&jn_1uga9(Vmq13#eWf`JhV>ZuZvuM?IO3_E#c zqGK|egBvf4bYQA%Tt;j_eMtx-&bBic;qbf0 zi^1TpY)FtM>KtSnx!De0e3hRRb(!MblU-%~4y?x7(wT8KVqhw^vwF zA9@yKaGYB^vEcUYqY^&kWscvA(nok?+3TW&T*m8ulcU<40R!Z8fSLCKbZ+@`Hu8*% zsL*!19aVZuE9nN46@*K3vk%xe z!AC>~x~==cO822hC69YIydO^mSim=LJzVe3vm6;;tdq;K^TsIw;JAyROma^EK*yJv zu{Zv$4?u_s$PtWKel-Ln84C9I1u_b;!&z6R0m1cw?(<*azE9KQq13Pdzz|qu2lP+q zB?`_e#|U`inN9vVj*;&O`0$W`o8E82KnO-W`YsK`QGqd%f|;&)h59ha&%70rr~tW0 z0v#@vKy+IgWo}k$afigVi~gho-vH~^=V8Z|hKROQ577ITn8kb`B|qoGdn6`9kL{fF zWP%Z!8E#5v5-o6=D_*65erUVR@trewChw=gFe$Awo5*%#;7f z()`g!{0Jrar?o_eQW$hYHPisO38^-FAbD&z0V`{t4uCgM%y=5Cx)&6*<7L4_5fQJu zaGpZCZ1Kc@xX;X27V=68OGra0$n}m1FD5?h(b4Rfj?AZ&#=Zg`ul*Os7)abJRB;GN z?kU7096NK9rATK4#HK%!jC(l|&aGKP<`8=nCm6lQch<5K$rcQLHFrzr_I?%cZ@fROD3gVklfv zW(OI|iyYM8Kcur2yPeBhs;q?k=1NxgP#)rt_tx6kb}bTrq{}+y9QUC*&|Fd~ROG}Y z)`UeXO^t|E@Q5!qbw#mE?CP;h8{XR*rr>f*dAnEgQ&H~Ky_9mBxB>^$ZMS2|W$yR3 zI)i!(b%oCvZHGcdS8Adq$$nQ)@W+`Rs`L)*G$4OH#(26@Gt>>whd6|AqCSeP&QCo& zV`O_QuiQ|mw=h6f*820kqu;ImI+k{G?;{827$1XeR_(8&77i|1w+4F(+AXsM4sI1b zhDVm#t*bvBJlby!PeZlawjMcpjr$l~7HYR2S~&WAyEXbdpxtp%;OKYk^X_g(yYu#^ zqyPQwI{>y$7l_p<0P1TDX4C10SULr*2C-r*>hzElI)zXf;LS7UV{6nqg^Aypz{1kn zDaoB9)O<}zi<<4Qx^Tr?a>9e}%IL=sV0|DG$7!jz6p!(77V+PNv1b@GmrGbA)zvYc zEI}UuNI4-}TX`}?-I3RYPs5`Mu~_7C={27Bi2vRVcd5R@yM<$tFroNlLtNp3c5SeD zl6)*Sb2FN;^+2*d;8#VYERli+xT5sVN(x(V>Y)H3_S6pYJDM-Vo-Q=m7)THr@7YK) zJf=o>M))L}-EqtF$8L|HwMLlUTpqb2=>rkro53ym4q=5Srekj%hM5GqZv^e~6u)xQv~OWkQ454-e=iqwm;cgIOOY{3hS3OJQTeIoNK zLc}KkDZ+=da2w8?sPTUx+|2+aeefF`uC@f&Ti%uFS8s;c|K7hJ2NLPKl#<$|D9jG zyZ-0%KloMDzxL|Y?}w`+)W!PMpR3O1sD>w~8m8W_T`dijebrr~4IkT^k^icz&0iZE|4~=# zYHDi!qpn(@%1HjBu7c3&>O~3TT>;i=g>Fk(IVv52itw9H@@vel{Qtex0<^bUS^E#U zT2WC^P@VJN$<=~?(A9h-5}BQyot2f9n^b7lZ0w)w|F-V6MwL1mSXHY~RW8y=O-)Ts zPEJfrMDwe05lLZTVQ6nPBqRhavwjTys2=Z&@_t|K6BZB<;P3ArAPLLh|CL{zFCH)BtGHVo zX((H)GVYC}d(l|FTxUI7YB<_hvD)OcHIntBsnW3dZS}#oQSGX@Rs;w_ui9L_(Hl+@ zc0B4iB+11oOY9}b@^ol8ncKgwe3^N7f=)7Mf!+Jrz)azjT>26>oUO%bv&p}^d8Nmz z%`S)E$6K3z{m?SIy;qbI`hn$4P5C3r;QB-Rc(z##&ppT0!Lur})Dl0Ru@hg^4eC_= zyJxsR<4D=N$&U8hKc`!xsn<<^eF5t~b{DhnB+xAL@!}W65s?lYQ5CWKBM^|8N*@GM zVBZKPeLH0A2V`Q;4mfny`4YxpOUV%aJwYcod}G=&$A_SDZ!?N_fSoy-^1Bt2yWnOx zlmEnWbDoc|3Pparq-nu=^lC%+cA~1l{`RNdWkoc#`o`vGvW{iR&lJ6nrvumqp^tac z^u2KlQ}FP0wgbc`1h+ppQd1OV+O4>lVLRC`Ry_|5?(!Jd1 zx7~Yr@d`J^dC|XlrNZ1w1&f?AdKUKWvI9RqR`Z~Cjn!_v^NRmc+IVnKR?Ui1qLmK* zUJXod-dX7;pxZt;tkODJu}h&@>yjf(YZTrrX5@gpEB2G7;jX(Z35OAgnUD5M>h-O_ zy}yTYo-}V_p)1USZB_s%*54+FRvfAf%Q`BNTdsyx>+>>=65RGz69qN3Dkt4I zY;ER9GTxeimZKILJ{cNb&49uOVw)#%SMEnO<*NUISeq}Do3S{{&quhP3|05TdPRS< z;y(A~YnO1qHy@bXhtN%mgWgZQGfWTEV7h}Jz8~QhJieS=YWH>VdG2GadraDN~f{rUjZmSXEx{U@PAnJ!`6m013g8gH2NWd+(=OS^=@o z$AnsOzZRR@-Pas7e6oEnQ&@gMJd)r7g)kqw6oI8yIp3ZZKTb)1mg31 z3(_Lp1YX;wWPYHoAK+K$OUD-7G2*g=6eg7(c2o9@9gpmr~VJR)Uxj zW}wOpQC#X1Pc)8~TiYU1kqQwbZtkK#G9!@-mtmDz2bu9Q>%-WGFlE!~pn)1@O?BUC zh@Q$M$Hawrjxm3VP6demJ&Qx&=fko02f^%MFF+R!4CNfmI@1fnu)*R1@CN5Yx2ZNb zhn~H91haJ_a?<)6W(S@T3ofq_iOo>v&>HTp8Yfb(a4o>`SgaR4I7?}+hcVy|j~YEp z$Ky)pGi@lw1t4W;LCcs=0jHtN=T`eu!q9+w+=CX?Y_) zU^mI{G+k+euIOVLB8eXoFw^Wmz|mVN7vNlgn|&ZwvoVeE`^ABT(#Kg5FJf_;r=fiL zqylblC||rAnXjZ~D?IA%e;(}=#EtWe9;}9x#;k?7kOtytpZ3v|S`%{FI%jDAl_Lv{ z5BF^gz{-{iBX&TRzwW6i32)~(K{u5gVNx~G!?rz*2lFF(3rc$+gh_iH*luo%;RM8_ z=Ulpgxrt4-GZiKhPZSd5n@e{-g^3Y@2Vg}#%cJ`P4`W?u09g$M>D%5FW063XEu`mP zJ0qk7T8JQ?rpYPXc}EsSFTMpM+{6Q;Ub^Gf>gv#^x;wZY1ZYTUkqc?RJukPwD;xd( zyJx%QVA)~JmeoMu%b$*caSg7P9H{@!pRfBdC*I#)tYd%x9X}JQzOgpW9o(ljGc_bo z*H1%}HU;H@mg%n0v5gd_G%>tF>Y!}xi47y69yY93^u;$5q-FxWoU2Y@R?(w`K5TtQ zxXvE)xF)0&6cSWv@`AOD-)p;JN zibznNm;eW3$cH6ny2i9_sb*fNSGgIAtP>KX`-pd1wM+Q3R1@*GC+y!%vh zvHe#ez4c1of{UWbTERb+uPj&@a55F+P`}i#efGfzjbPe`Q{fFEdWjmP&@uAnc-QQh z#Px6jZ5$Tx;Zi>dsV1Q+4j6K`2PVRd!G52T zrf*0+yEf?e-o9GK^3MQZ$e+_+Lo(VDtxj%@(DQJ2oIbJ{9eyWK4p`j+0Ia@--#yPC-%&rGz6PGqL6>r9)+nXBZ*y&~*fD4+^o67y5Cm^<@}c({ z!5H4~7=Lu=-Gryd`*AFQAFUxg-8k$YUA0pTXIqED)zZU&PA<066{7wnN!!RGR@g_J zM~8>|=Gf8phZW9|H8;TZ;lP$RPcb7NTXGL*$;#>nS2b>##U^$OO6%d&o^06+Yj;aB z!%lcR+GI&5DUd9>G;%E6McXzVqgQR{!_iL2_|P3UgX(3tQ<}vtJc}kKEHy<9LHdEl z&e3)T@Z$Amsp1ZjvL_FJGDyBUFAXM7^}PIeS;z2jIVgz&RtJJ~<)7mO#=KgSJ2!|s z*cBCW8LMN%eDWg{Mc+8-*EG2c(om8lEw6#R3qw#(?@7sMB*Z>TUKQRqYI+6ag%)^- zopn(lUNZakxNV;Crq z(b{W<2w+}qP%~v6cVYc}ksk8rD0!(&~NK1?O+#HeW2@C^k2xzG`hpE~(sE&ix{wc(R0a*xD zkTJn$MCg*D*UD}v>p5$MS-lvXONye|-&!Yr1Z;i(kvCnvzCwCEYlh|HzviKU2a zo!3^$Z$ULuI1L*3KQ-_$H6_*wwGei&hJee0&^ybhH|`ck8y`k7Aql_f+$p1#un_o9 z0cxkbBc5?R)4^|=5I<4<^@74ogiay5*sD=y}$96yYx?BVc(`O zj&VqGK7@6lS96yV{ACb5jBm{?-eM^0&F_i4zk2KZTpPcL;J6D1UpQ(z?Ss{yH#;~q z#3(83Cq+=OQvzN>!fCNq?;eBkZh}IIsH<$$-n<1u?;O)1B=wgNFp635Bd(Tflm*`vA z&B;SQW9NK+N#f`i0PKX}JK>TTYv8^^WXw?sw@|qg*QI_+O&^P6O9iBZqv&^EbQc%5eIMF5eoi5#2#La-WXJ7~8zd6jX!6oJMj`GrZ}-D~FLt z0kB9p^4x5A_G&ZEiA>Ko^E#LF?!VIG@?yL5;(dd^m-o)4ypD|&);+$aeFMYqK!RSO z8}vl%01eJ23@%UaM?Hx}z9Wx(RJaB(LJda>f~eD~fFCX3=3wnYFv`2IE3FVGFSDu} z(v24EIf`6G*b{3@GHuzDW=fEFrP-zIDVsULBRQcf6hSuFJOG!cgT?#8wDI1&i6fNp zF#I++$XS~TF zYbE$FV>Bn~3A}K8zWU&^jdV%jvI;#z7hZh403K1+Y)MTbYN$q^x|Ru&R`R*>yYv@# zByiM1i=DFyEL~Oos_c+4{nDoHMR*1=5%eofDxkS~srOV87Z3)Tg6DetHCejJahRWqdY1L_Xwz;*GKRfLNcVz*bR>sFp^@ zvby4xI?yexvUXx- z>{A$bA%Mh;S_Sf&KhuRB#-MCbN8`fxWX6zRyo5ur*afZTS3b@8t#!7dZPC&x7I1(o z1mY?BbuuFt!~H8{iqnt2NOl@yov<;yP zc=ingXXW@^Eh})q^oz~~;j-=A`f5#ZH!uDvF3CDaGtgcaSJ1;$ArTZn(4+`!qreDA z1w);Bg))0Z+Iq#-dL_zx>0sD&r@e9peF~ZXti>p{^{L|b$*lEhwDl>|_M>-VUK{l5 zwDoFd_KV{K&5f}+rvSIl@g&;%4aWK{GyCO?JL@Am=Qq+)@JMb|(jOmb38uQ34*Y)r zu0T=02>Cz|){sdAad=(v2yrmTgj~pme8`BL$cq2G$c)^`j{L}w9LbVA$&_5lmVC*W zoXMKJ$%C8*q&WzBAcv&D$)sG$iu?#{{K0N49gyG)kjc4~Pzl*v$1MeSa<_1L%*TE_ z5HnoEXMDzK{L4`s%)$)C#9Yi${KUvy#mBtNR; z9*jcNTOJ_*r!oPq;!4XcHF~AT52wcuKlH*e+&Kf;$dJtq=n+n}kI(G}`5Wdquz779u(e*6B`HayUJ-V+!o^_xB0I&yR>Zl{F zI|RLv5#pF=pszuIj4l0AI=8#;Ko7{!P&LiLkaoB8o4)M3(==hAFdz^lO4L}5w66lf z!jZYJ{M5gfw)T9y7tPUL?X$uGv?KrkCs1jxD$-?L(ghtMXb=p)07-1Ucy683avj$^ zebYM47!w%-0uim#O4b6Mn@7!_23;Ns&Xnr@h#F5u$c* z*8woJDB9PTU9Xvqxti;wl`sjOE7}G|+NOQarH$J3JluQn*aDHT+u(_m&DEAIyAVRV zl75aI`ZFmA9+39~HU)Ro<;ec$-~-NfzSHX#9E ziUIlGw6k-FAzzP-X0g>1xo);A&$A$a6V&J-qm=1=U6W35l$1z`{f{QY2g{*2vGy) zkPBBp1Z~hrv|S;3@S1TZ-9V7wjqXy9PLqJ{m$6=pN1nPVFc3mbrZCRw2eAqfr^>ax z9?TgGOAQk*8rrSSWOB~q`K{ku&gIOW5SK0x0idWWSmu|hn5}jU?SKtISn3s`)^VBJ zsh;fj^y*)!&LCId#&NKZk=Zn0x~NQ_izuZFa?-k57-3m6k-N~ zP1p%h0Ms3&=6>$W?(FN%?pHqPkZu!*>be3!wW-lRt0uS!E2r4gjto@@Kuu5^};&Z%^nh>*_x7 z67TkNjt~eym^zD8KNiO&kvaQ{E`qP#Ajc@00U-Rug`~#8o)c&rrg!vi<`s#tNGjRY3&HGvx^Kb9^ zt9TQuz0PqEqV7Ah~LcV|Xs}Fis5B~zIyp-?a z-Qc{*Z~L?T`N7U20P!o>6#xYd9xMo^(iemc9X^B@QQ}036)j%Gm{H?KjvYOI1R3(8 zkAFl&dTbD9Ye zF!~a1LAw~44n~YH>eR#&(FEgVK;nT(m4YP9jUPvzyzytmtC2c?ZriQk+SJoJ$E)`s zi*DRT%(i}AI>*Dxsq!{Y5lE#;4${AeA78#j=G8%upNqe){{7+e`-eyZpHM&umTqEc ziNCO*gQ&duSVB)Z1t5@UfJiE7;z12J~Q;l+=My!b)}9ET*b$gn;Xk4CUkRIxdf+ZZr}j9gpKA7*@hWGfg$0LUOwMq@1!jD5>%?q|{g>W6OhJla0$aZNzQOi^eq0 ziD3VH5kgQ!7iE;blKzwv&L|;`lv0T@uo6pyxbqIBIaT{qA}||mh*0Br2?mmh3J8KB zQeTC2!#4l36vR+-s?*L}Z946R76CiRKmr9>EphFa*xn+yM7 zF4*9i`L+4M;ff2oYp*{VddZ@7ts2*{sSdYn5|uo;4wVs#r5jktPW$T2I{D`n0B*2_ z9DCBSWd?(+fF>SzoSDL)HmH%O9c0h~K#ObgDaR3svYv0f_P*x4b4MW;xnz=)7Jcc6 z0*Jwm7aBT&n{G~^TWO6XCd&$Qu+bX|WZ*br3v!Mr$b)xsQR0bX)>(;&dsaE3ifFDW zhzNRIVL}sr+K34A%?vQ(6b~dSAd*Og^t^oY5ehp_($`P2?$Qe?!45h!XlRsfWHI_| zv_qm@EDy-xLNxS-kVNET0RX7NKZa0{DEtEn04T&hBm)3A_+urj2!}z8(TxA>Nd-O% z=tVGmBoP@5;Cv@MU-~BXK9I4meeVkZ8C2I03ur?|v16fO0@avZxB>tIY{(HBiSKh6akJ3{LqR8xdA#*VGt;kqaXbk#{vtY1$OY`AJd>g zLCE0=gSg=z8$gID{;|nTela~%IFt@3;sElM(Ucogp|RK~Gc}5Bm8?V~00>Y9JGh`B z0pQa~js_mP4Q2@Jh(bYtXpj(8gBdT`Ks9z@g)1B*9GK(*IaV=+EJXj~877=$B`=AP zEq2j^@j;cUBoc&4gyEFu+*c|I)=F2hQ+=UpNDAyQhXgc)JKOk9{$8m|{q^rFg!l(P z1o{tu@S`gqn8q{uSdd4sV}cN%hav!g3TqgIBm}9VL9p0CPo~FNyqL%bq*Y3Emh@HX zbjmJoqCbbR6lt++;XxQc%M~~zZgb=3KK0p4xO@N#KZSxdb^(QDQ6m~1IEW_JVL|{b zU>=MBfGetDkRJR43jkOJI5fyXh-i;9LZFuu?zIq;mX%Z}wb~uu`9ig-(jnPF0P9=_ zyPUc&VtK?25JNx>a2$aLf9=W=?r{qyJYg5{=m7w>;Ez%yp$h-aI0q)Bw~8fX;(8pN z4=Z|shKV#GV`c@dpwMbIo!SwmYqTpo4I-c`ImCYWgXL*;NVB}^O$(glBwDy2jd;8R z8ae}jBCauyb|_;B2GIgGC}%m$%0~xXnTP`_L#@zOH%z1Dl}mZ)PPcM*oe05`o(=+n zZQQV~-kpd)8RgXn;mf-3B@%Yq*w*gKww)m>*SQ?R2fqO8y!1^kUaiI6&OpFk<7CeP z;JaX1ol&)HweJc6oK}M%OkoW{fDOek-w8)Vy^A97W}MKAUj!#21@Hn%8NA~6$d_B% z4NPhw{NT|6;AAOt$Q-r701ijEA|F;%h&8i-5RQ<=M~?rmgJ)c08mFYSNy{-_e>^mC>$1L&PT8P1-* zGRfpQhdA1^J9G^-nr9bjczyFh&iXP$WH3@q*LpCV#-X5NT4pDUtTi>YsoW?`=m67p zz^B&hXm$AmqQE$TW>RbwpatWe5h~=PGltv zeD-+G?+QAXueIkRCppDaM`hNPcU>(<_{;aD@ytA?7Zj+F&ZWL{e(zi1fe!j}(qM-= zu(=^C_pjB7-S2QqI_B}AKnOWIb+()3;JyAi(35`O!BF51wS344j9&7%Q$)*aVtQu0 zOpy&V0h4VB zJJQ9%T42l7ycCbOyf2>le{X(120)dOA>#jqOOM|7W?cN`g+KgV_Z=xLxlz|#!*L$|G1H~T|8{IfXzd$HK#zV3sG z_;DNQFh9DJKr>oDQb9oY5IE{`zy~b7;v>L>%R1Hb3IULz7g&q9(KpL8JxKe&MhU^p z@Blv$D~SLDN~pgQY&!^CDGJQL4(zn6^N2U1gA7m#Zksp`TtW4Nz9O*-tRNxm6GELM z!lbA;FEqjubpe@A1F2o3x0>gPj z!4y2cyojrvfSPSUwE?WbEQ3QFltcNz0D)LLXu-p&(?gy3!acl1Obo*!^h2i*KYYUp z0f3E0`@=+BwHsWoMwE{$gqASaoJq{NO0)<*)Wl9~L+29-3j-FMm?Lk5#JZ(ixP{aRCiFVB@Pnav8N-}Fo;tRF}K5&7n*093ur#gnVFvE%=8>DhPDggnm=c_H@t(ea{H}h)>iMgkXS{IZNX_&WqH~ zB6*AwTgK1>&=ZP+dEke5s7yx4hl8+&Rd9%I3IQhgha_l#8nw|I#nBwq(H-Sc9PNNO z=zty-(jg_%8~xEBEz%@aQXd7()Mba-7 z(<&8HBJej&;-vp^cuLpg5D+>?iP)MEJs}7{f+|>rc3=V(Wl{`m0qGf(Bg> zPx1r+B{)w8^~`Hj%?)kHkH8C3dx$MPfxXO1fBn~ZBMBz(Rj4}%Q=kWRC%STuoc*UAXqLkScjkid3XfCdsz7Zt6=Czi1^Qvd;tml4xZFJz24hnaV>iZJ7{=hs^@!Ao0ht7V7I2-^RN^=G z-M)3n*h_#21fgqUMJVv2CE?_dQ!0CL)jd&xsVI3R#-5$Q;2n3tN&B!_45JMS; zM6u+$&0iUoD=*zEH>j> z)`<9o;(`!>DL%wR?qgs+WntD?Qu!!~@PbIF%4GJOW!7OGX690^Mvpi-{Xz)-+J-1R zV0G?8wQS@@nU{JQE9xcZ&N1igMPk2&=4XBg7o4&Ho=DrJ=b;Sd4iyx}#F+m`(3pNM z=U6^t2-RQe#Au0-r};q$7AUU{KHr7@%7(sYM}`aqYzUr#V2bu4(Sw zpI}Y^7y%o?;l3qlzqDs9eiaOW1gV^eICW{x`R61K=w@E$4n!CiIS31Yjcn*;h5qF- zK1GM-7ynG^uUTrRero^K=8T9R95Vw4A*8eW});4d~V>1@_&MwaVW@dNn#5il5Myyh6aersp`%I1A zlTK`Jeiq0sBgr;wxUOuChKMu<0FV|ohCXe|M(o5KVLA>g(hg&owru~hK5UxyZHJJu zK{kjJ;A!dn?ASKt+u-IjQOx&%=n4UX?!;|T&P?V8^0iXcsc0D+d_<*~M9+>Psw z2;vQC?(~4oJCrqAn{Ixo?(l}=)b8YnU_FCifJI~LMof;Fhg`@4^RDdECwnf^fLF0)PN8ka(7D2%l+i0|`P%27MrhPDm{IIPdfrJc&p* zWLEH4d2dcuN$bw=hB)i79PBoRZ5Y?@EdB@_*aUFchh-=P^)`o#X@D0~rz&41!aGBoD=qL9(RJI6BxCeh|2UI{RjKCYc;T!+I0UW_82*NQO#4(5g z*aUK5-%miU$*G*n8E{fj2(DRjWodHxe)0V-Yl&bHeFcCyij6>b@x$cskl2Av5C?kL zg)Lx&aG0WtupQh10Nvpo-vJ%~5FX+&9^@$qTNnp8Ac87jTIr!4>%pF`y7NX^4@w~7 zJwGW1pKt8O^6ZAZcE*wxC@)wbWWPpk@YZpTC}s zQltiYAST!cC1?l?+N$QN7AN3@xP6E)5NBFvaa;fML|;wM#%hU}M=JC612Jx5ck)~B z?~RZLT(E+M*nm>Fh#vBzAQ~b7D54`uq9p==P9TR(Fo*wh$c0q}fQ(|OEaE0#^`dKe z?t!#lbg%UZzVdZvcYCeiQKO%EmxcL6^m`Zit^SBG_lP~}qhT_LKpLciD5OJ5q=LYO zd!U9aNG@oQBuXj>OPX~6@Y7DZmJjtjkN=rI$8~%U`IbM3PXr2-&&T+VdaBQNjpzr? ztoeSxh+hh(fhQ(oLMCNmCTGGVT=)lWN1(R{fNU!IZ8``T&3J23fMN!p$98%(fqD&p z@TpgHDa#YACwalw_3`Eie*pV}=mC4c2!IkOM=Gd;N~ndpB8Msnh>|E&*aw5yfPdIn zioYU@e+VLf4`=BG6N88ih=f`F`$Y+S!f*G<&T;>Q_+%2;1J{X#tQT)TS9C{N?xfO$ ze)t4UQ2tFw26DX!p8_hOBC5SQs-#+~f^aIRYJ-1xUjUc_xzDO^cXd?`6AUOakCg7& zzb<5nm^|4PuLl4F*P>0SLe1GhBJ@@*$;7V>Lxdszg@|eMCeEBXck;9e zDHtyUIGa?8RG=r)q)L}EZR+$X)TmOYQbp+FACam{8^md#RVi1mUz3I%i?poSo@i~p zuu~>hw{Cm_XkD8&r`@|a^ESQe11hu{Qyu>T(DLsv;;aC;NQ?Iln!$rTkjYz@>jpwC z*z%QggmY$1y`rJ&=yl2iP6v}J1sU!7HSE~3XFt8FnD#-wvUTt7iW?#C*uepmuwy4% zw{3gI4tL$$x$mfce^XZox;l0M7xS)dM<#e5c4$4poB{D>KA%+=h)z1zI-O$f^ zShY7GZ2|g6;%p`|hay5QAlJ<-BM2zgd@S}xBY_4k1q}@VK=UJzKWexTghPsE1|&I! zQHd8uI{74&4EcjYLQ2RJ;%&I8SeO5e!gcxDmR#bPPz&C~H3|cFg-O+#Y<`Kbv=E=9 zUUurKRB<{r17--_5ZaS;1{xJB!JM)xtg(`pOD_HxLu)R$cv7la>`~XIRKNxcDW{Z@ z$iggfX=B1@!b0Wjv&8NsYE#T)k`N}#M5(H*Ora6XFFNS7fuG%)du~;wp!S-tHGT@F zwDrY1qp>uOFbbyI*pWh{jn*4#fl$4}L_$lvvn@^NHe~=W!Eln(7n8K6FvS%owLu35 z4Y3JKjQ%?BiSNQIa#uYHKSfUz2}My4!l+u@lOMtK zvaU_th4C}eNi*aOCIHaDPCE89omRVAn*0^CPi5WI)?CK{K?^TtBZnPyXfQI(AIm(g z%}zmMOG36t)3ee%LC{MuN!}y_C6xeCH{d_J^8^5oU}Hcc;&|+C+Kj7>9R#E#yWbuf z&|$|4uywuF)mV4V5VcHUVUIMWlp>8i>OskE;0!_1iyt|G;a%&spIgrm02osW07LLh zwTO=kKfKjzrxid8lY7I*2m!=k2N?ut{<)jRt4X~=p))mwG2&R0OA>OjZaYE?5PcI6 z6k13=`+$O@$q@2j0YLv1>nvV;25<{Xhu-Ji(0nA<%j!%ip6sI28dTFD~8~g&)KsfjMAqQU?qnz;xsk1r)+` zg}4aaCa91FK;l(52|^_%;Q$>HF+)6d{N zI%R=LK>|7GagA%xV;o1wVG#k~1YZOL4L2Ep7uJ`?IkK;69R#5hxp)@=h~Y&i3}9IX zScd{aQGZWViWiZx3}%$-2F%db>JmoBQvd}5bi5>nkWrIEaS|C#EaV;WsKvYV&xFiN zNLW^A2N#4=k9q&h5ma!NkSWXqjcF`R-o}N=UB)IC9{>QZf|-j?jtiZ-oSfDiiVMl3$Mmpr&70VQ4PA(OJwo+JSda6m$x8mPll zM8+l?Sk3>$fT~ufn64D7kOwssG!1#I;;2~FCqI?ClmPURW&P2~J@a|hekE0_ZEK%c zCE6XMthKRD$ptDBf{I}RFH3nvYGDa06=f<*3^2e$&TMIPZpND{78+0o7{tD1cZ2w)MHZSdg&J#m2@<^TfT$}6Q}ieXcNBwZn~ z7M+mrh2CPa)1%S0yE|EjXAt5DcG&f|m&NR0cf!||K~<_eAweDNkOt>gkGai-t^^aS z!=L=32sUv*6VB<~0pFw(_OJyb7-0)~bfUbZ^{sg=%99f;vm4pi6jBI420OqYfl=8U zSUmsyVG#pht2{wM8#Vxda#fd?3uqWCa7f@8BP9{jc*i@YkqEs|RId+)aBr2;RQ(WF znn+neaz#L5r+}C&OJ*{OO`MY(K*JyXFaj`LQPWF0;TO5Qi2~$E<1xdg$LPhYgd@xo z7Q9Fn?nMfG?SO(NpXJF+p>v(-o4vy_Wf#rxfjqF>2F115y5Q1NOn?vxbCS8yt}*jn z&l~A9$K(Q|=>L~MhDeIU500IpFBh<3cyi`D|c=6hWIKZJ0 zbu_Mb3*`ISmtIH-TU=nVT&5s-4jBM|sPSTF&gpq7(2_DvY@2E>1DaY8O2-2GsfDRD+YZk8S5W{;TO^~SGLmJwNb5WxV(IL4ND z`Ad*Gv`OMVc+JRN(S(>|XmCDjv6(e(4xA zUr-??MEMTYCAx`~cy$%@*o1?>Uh}Y@`yhNZlQ+Z=6^g$s?QBPBY299GhIIep9}kI1 zIZSceKgE5H28i``7IJ{U~P z=D^0~8L|m$_`@2T;6Yfi4OCn*wDgX>2Uu}?57u8#?epG!ULnp6K4cLpXt#at)e`!Sl{)T7EbJfmbG6_Tmd$KNc~9^CGo<*DTEA6!X$_p|D{nO@Iy10 zPBZL7Aq?OLd7a=noVvw@EHqP8)ZRkeo=xyzJ(b_6ogWi~01>X7LMZm-YcB|a%`UfPz4EG4!kjh z55gf3Dw_mq9KayPKbV3-3;{dj%o5tf`^De9{_v+ z6l5b5Si>$rK}>8OpctaSodPd}UP7dg-@pc3WCO&-f-i=LmG%FFJkBFJph6O91tiYk zBsSd0T!1{m0s?478}1A4abgfsV^utxH7W!KDvUT{k`Ulc^C5&S!Uh_C!#7yio4q4- zG(tL{f>)tJI$**lz{CH2MLwD#Kkno7pkZ<-o>pLD56&UR8Kh3cp&XvyY1u?WqRT^K z(zgUd?1Pu#jb0qNM}>eXe1T8tMJ^r&6~sa_Zf0!2 zK|Wvutzg4Fya51Uf|j9VX@cEW8sk@3fIQU#F@j}s`CMXZWej2`PQ0B>SRK}Bo%pCF zZTUejxRFArhHSaUVfZ0(QU?*N!l0~z!X<ku-xNJi!z! z13IkBEu_O1n8Y-cXLYV5U_Pi;xTL0l7y@isCvN{}1R~>7bm&5yUh1vhh<2B2B}A>w zr)ccMKez#lQb!i-!Zd&cBdjP+;J`nq#|-Gh3u44SlvOqMrvVP$b-Kn0tjt^@o4g^{ z97sTsX6TX5W{K72PC#EmB*FAO>1_GIFF+kac$>@V1wH%&fo3Uf6hb}V!aZP_CO}e7 zAi+O);}-lwj~oO#h-gAk05CGaKO{i|q^hc}Dyz1ttG+6%vT6s!K?lUDt==lGuIjAT zYOeOGugWT|{;IIPY75Be38d<-4(qL!Kzz+vuO_RqM(e9WtF%_Ds#2@9S}V3zD-rmq zPWT@H3Lv36*4)A8K}a2wjD|S;gAzjOY+(Nb>Z#fk*iTLvz%tAYRpvuNSc7LKgel$XI0~bsi05k%j z-GnWq!)39aFRP6sjT*N{^I^I+SmK_@DG>UFD&TZ{LrbJNz8)X-4 z#KS*K4dK3qCy2up$U_z|LOW=}8`*+7fMc1SsS>0q<+3SizFwPZh30m{D6Ap)0bK%! zR_N;K=t^(tLPanV;V@32cl`w2Ed-01g*?1&?83$Xe8N2VgFo0qWZlFq#Df-81P{FB zEuh1VPD73kFP{b-l2*ksDz5`Rpj1GURYfo6zNwGqgpw*mJkFy$*5f^D2L+feC7bJ^Vw=j<0J#025pRAu`7uMOXAe zh{2isuQ@M;<+PAR%kvG>a{?>GmUbysf@vB*a-(?wjOhgr{6lDp^hj6k@fNS~Dn$!m z$|$gOOD6>ZJWuqXvKPx{Rnw+D>x86Is-?94y|D0niB{G1XYDQ{6oJo_MbSmReQEV zD@B}kgDkWr0rSL=x(r?CHWkmdS#LgR2g+KfQbhcCp3eu@=eTc?cQ$gA~%_Fg3#zd5-%}SEWlytvvg+& zb;tBoSNBp}K(b`RaULX6+|wI|H+hfuZwoh6l<)bb@A~3xqfx+515wUKMG_pw1K&54 zd_f(D zynS|jf$4feLQ@AKa}Dl06@bd#KSjj(Q`XC zLGPy+YV2UJJUdSH1BgaLa!MHfkd`dSgUH zL&hM4CagobEWkW$9TRBdC&&X72!=5z142xLwwF5Y9~=hY%`fnNIx58x97YHV|L{-! z@&7nL01!BkU_pZi5e{q+r$NGlEx2{#&sKYgk7pM_RGpo|LAp9yOwQRw{O?RBmy@jL%JSa-nD4=;|XouUNd;5+U79qlu4lYIql|*zk~12 z((>`+vCXF^&MFwN-Iaoztk5}%di(eBw@qF={N4Wk$1^B^Sh~^X1h$q#!Hzmg01zYM z{(~z*2?Io_y!B1G?(h$idPgr|%(A!^hx-x1Acd@m zg@`5sa!LRQAj1wa2=Eb12bFshPOXmAk}DFf$KY!45h!2$R1>W#qKeMlF=7(5&zr)lMON0dcnxMM|VIQ(=vjq(i;) zl+rjs1wa5@37vncc~;wP1)_Df zWV-@4+!y)iW*ZhLEHZ(^V3^d+T#N0})?2e$mfNbXx_3zrfwBK&w`pU=!NVga1P#gkIlGVQ47XbwvIV8fEQKA3ge@*_yJjEEf2O>V`C2* z;jh3V9!Nn35uR7ki|5>w=a1}NIj4Mu#*j~G$C9C<0rvUFm7<|ev1J%_9;|As&m6GV zUuy|~j_G+#c&Z=y)$0jJ~m7R_HI2(THcQ-F8x}vii+|C=nspCa7ZHCXJksEa9 zBp`-0+sygrbYGTt@ru?~xoy3P`wHnuDiY@(aVYQHJiamZ8QJbm*hV5vEyc9f$K5)c zCf8s8yIYRkp4{`9OZgawJ_Q1x1>NYzji?3z>}cnF6^!2TwsO6W>Cb>|@xU*3w;LcJ1QoC9 z;0e2eKwvHKd@}3CC~}s91(5(|HMHOb>4ZP1aS(-SIYswGbPx!1=4m}N;{8BlLmVoQ zK-s7cbJRcw9&;6u}pyG?_p; z^9X^m(w#elr+)~+t63yYGA^*g95lejHfr>Z9A$|cKgvc87A%|#bqFhvHi>F&Vsj>4 zWkdC;NAJ|aTnEBT3GBcTkgjB>C+R6kehU9ok^WP10d*-#&>*+5G+_pvfxuB43Da@q zlWZPk$q432$;U`wM=tUh!g8lmHeaf*tHoJ-I`p%2gzgKw32J##l7cwXFSQOaliuo7B&nwjQ zhIYN|UG6WPd);1$w_0Mda4X*b)L{{oo7{A{s5nJW-DxFHEj zK!rY@aN+oVm>|oT$2$Bq2_AQ_zsj{NTxg_?5fB!*1{v;NR$P%MA7si@M(ju4p-^pM zc(shMhba6tmJtqle?{(SluKJ1tUj!>QO-bDt&HY0AGvtZ3{{K?q5wtYg9$qR7?}-% zgU+0Slw|?5_{_{*5vzqjvtS-x4Ts=3FWAn#q%+X|!GsWO+KdH>!aVp94-0R3#~&s_ zXD~s9l=7epN;q`z63x>B&l&$Sm?a!uQ#|QKLo${xo|R`hV+w;n00~uCMLYUT>Oa5Q z1Nr!eJ=V#J_kaQvhIsYuVvXKiYlQ)jf}wD6+hoYhn%0%>W+d;YX-+%j8MyHCwFP1T z&56ner6A=cKp_cucP`tXl{1uQQ!Z_At<7+GvmLw&@NGNv(&oD#o(lpEUA!CK%jnD- z1Tq0oAk7lg{=vTW)^GJLoF=8~h8PGE)JT&d!Q=k7!hIdOhC`01tH=ToqOb~oaDn2l zMx`7)N8H_Y|Yz;4VD-08g~v8Il7bnl(-D;X)lxNOp<{=*sp9LNne zzMGDN!UJoETH9G{ZncycFitkC2Ba7^DZd@=(DeN0$wO4^m0GeT`iC+MPY_A0g6LUr ze9<6pT&tsmM&4kbirJC?HN}9Ud7ph{V=nW`h<<~lm#f`^lMq3GBJGHHz0hL6d8%6; z%@_EKRu!z40AS~mk(Yd(``%zb!gty7okC~S;SeQ&!WD|ox1gTivFMi@^lceMul9<2 zwa5@>-mkxl{|^AY3F3;c{GO`{I^!NbfFdLT6vC_$Tmcl8ApSsR{(LX^wBiIJ0)nVd zErex?+-~|haOwYet=F;+t&Gp5vLFFzpdt`~`Njg@KtT{FQ2s)U1mEc{ny&L|;(gjh z>2Q$YFwo%!ko-QZ5IRF1@TMZLfZ9ZX+Ne$6YLH+okOxh$EilWbbWJNFje>x12uJMu zz%TR&kfc&jppefU8qXs*01Dj@6mVb)^`#1{E(l2?08H!xvm)v^>kGv&fxs{fPY{p{ zP_9<+AHdAQrV{7WJV#$5vqO;9oDcV%j^bu^6J_`eP$tktWYF)5#ju6BP|Ue z*T}d2PG17=h>)Q(n8CV;vVdN);9`;@H1L7^Pb9Rl_xe#MbMh#Wa{LC;rI7C*jNmJY z%qah8GuFv24Ja(DY#O_wEa?s(KO!Tw zODfOp9}BaUND(Vd(THdO96G}s8q+bs5-$UAGi!oCV!;nT0w*(*EfsAn>uMYcQJ}WK zA38%9QV%t^B@2{69sYq320}5{!5*F=2`BzrH<^h7-k~$XVFt=mWr|ZE24Eeo1OR5>9u&bL=#w@Dj2pD@EE56&)MOvuay$QL zQ$$DfFbQ;(DxefRqe2&yLDka;{$UCRLNn%5HN$TzwSre*;TJz*`z|U|LbNl3^hR-X zK)sWd7{N0lv_)N1Ah6&cl0qPiK{yJ60yZrKnBX6hpaHnFOTF|~Q zlwy$sSwT}-$LG{KLm4_vU^~VGrr`WGVG2&N6W{?3q97UKGhrKYVJmheGIT?!lOQ~l zVyaRzW7Z=lmJIh5g($!nI-?z`6=Xq%Gk|U4knwXQ7ryNi-_Y>O}uLC<^GIGuGiZ z%NE35wr2tNB&L>X2||XRhX^eeaRXOtf6Y<31yVr<0))0RK7nuh_AdXHal2L|PQZaG zGd~T&d9E`c6BiJLbVz*`G4}@x_@Oh>VN);Hh|YF9)#o+ak|0Q6M}AOo7nfmu_jfPW zaql7(apDGSfgJ219c)2C1;PrTAs*nt8LCwalwlp{0UOkDAQE95?g1P|4IvZ5;0QLMA22Rc`Joe-;Km3Dd_z-ZhQKqXVF~}u*K8HGcQ@A~?yoP| zSNCwXgjslgfj54M@i;ty9Jt_GwKpHu2?0+M0HWX@kia08q3n!d83uwH+$|x(S6gVn z8a!i%L%6m^SaV_cBWBVp1=DJOlzvHgieK1;N8&2)Vi%sqh6Umg+Cd;bz#U8h0yf|k z#NjjtLK=!F9hMXou)!d*H3VWpV}&M3JL8C-c(S5ciwW5y%4I3(761ZZV(1{3y4Z9B z)Qel#evd;Dz(JMB_y*7c6$Szd%Ap_nVH}+JhI0%6^npbIAQRZZQ$dxFL1qWSp)>q} zYy(-4W>-ip;4e@vku8NIwwQ}2nRM%y=I)m*hJYRF0|5VQI0UMJ88Bi4s$mzb;0lf* z95#R;wtyZQVIWReSOARd7oyb=QF0hP629x#C*=y)LP*ke3ra`V9o(mARI z`H|rkB?tggASN?Kw{-D&m^+$8!T2pc01A}-XH-*v)CYPVLVyq;2}O_|5UGLzM0&4E z5fB8C4kAsY_Y!*Vh*SxP^bXQXkY1#y^lqj1E|AIpK5L%2GqdiUHG7>`d6kuw{Bn}L z_xEGS0Ijf~D^cJo$R~s-P@g_S(wei>HRW3*<4+lSVoL_#0-2JbO^%5is*(}T(smNh zqhL>HSc|^e;;}#`ZnhLwUlu+wc#S$0e4xnX{h7-f;0_Dnjsx)k$ZP}oigyz{7zJLT zj1p19XSfVG7Ku=%VXxAcULO|39hgDz4bs=HX92lJ86VHz*GfcuQxs03ot0C3pw{yM ztUxCx!qD(e#F+5mpLsn7b5|UJ_pwA;R#qYDXDY$kc;Ypbp;P(wx5DeJ57dnrnIB6& z{en*DFsq0+yw0o+ZfSyt$a%W+31Jh4fmB0A$-k$biHv}*#I{5cVUGNxBcrA>-`u`C zB#y|oPkwDJZEYR@+Pbsb+>o#u$@Z=n63?;iQ+{o3a+)aU>tw%{xuzPce-0-viF0;X z`z=UHvh%&O1#FQp7y%`u9ZPYArIhNv<=+jzLV$C+>2hdWgK3fNpW%xM``F~)ew`)@ zDBQcYmbd(_jNQU4tzFj(ttXc46l-w9_CAxVJ`1V-m;U``Oo$%MSTm{lC=vQ-tLV4*eUPOV15ptj(@3XZ5PD1(Vd|3tx7>EnR$5dDTDH zK0$Fkf)9^?2TY3i|P2u_ZJ7xwKUgVQ%KsBy)yDrF)xRLZXgXPYD_nJ92Lr1=Nvi>u<#^a*a1fKZU>)|R9OW$6>Dh10NW#E?+B>N?HZXtl2>1NF#SFzTl zTyP1Q<=-eMBU>fMD)Ey+$`sSfJfbQyr@lNoY5ZF>pxTl4iiR zWY=~o%kkvkm*D%|l8Jn!SO)2sH12FM#}v=!sg*DIi&c(hYg1oQObMWW{92`V zVVkX?9$??LJw?tp5YJ?Rc~UADW4QIlI$}kumplCbZBDh!a7|Q(kujRgKd{SlS~$LK zYIUo8y3(X;)5DLh-uR27xEJjLRh3zXhibM=yu_!?DRY9YTaIF$j=frT9v@D;N2jDB z`1Ve6XwMDT%%kZ@a)mh@>Oa1d41!6w9(Pn7eNKkAyf;Bd3cl6jU&2`n)9b%lv>;)z8~n5I^5Ese zHJe+3&(eMAd^s2t-W%R|B00p}&8l?zHp()Fw@U0?kQV{Bd7S)fFFn1duRjup!Yt|X zBj|sem}<&@eZY~-==6O}{)^aQFU<(%CqXPxF89l~&rG9VDhrGeeTV~nHT-V5D5j#H z;5l)CO#J)k{7(35qjSy(|63Q6{_wT^C$xsTnJ@DKZ%TipyLxQA^fae>$>^l_Q9hE{ zt%TA%QI5rqHdpXDl)5NWH;YnDBMjgrqF_6K)A$vEZShTWiCl~$rBR7vB-A59bcH`A zlG#g+VIxasY>4McR_lX%wcYj?PwIxULXrqZ)Kc%}Rp7MLUw`sy$)c^OWq9bI9c!10 z(MdA#P;It1I_2|qA@;iGzg73IO67eBLr4k9lB<@n!DENlT{kym)QvWFZTuEXo)%WR zKXz<(TQ)(AdoGk@3sr3bck%1g8{0JeWk3+Q>mbujPpyaSEhh6OUw2_nU7Hkxl0qki zD^&J_NSk7L!r1~Xs=z}&*9nEld;5mq58HZ8#Ju)tnUek6TZPn5r9SmNoXN@QBwnIQ zq?PjT=q~l7(Da-G=qRQq)$WLFG0ZR8>oK(KwpNb1-CCep=G%BpwGv=(h3F^ZDX+L= znH}%_<6FU()OiPZ#;kU%kDH3l&&^?n3eO%Nx7PQ#Ac4H;DNv>NMp5ygm{x*p6-{u| z^0Tzel>GLV97FX0$z8EnE&h#S9L&F*gTzy4E1bEEMAVt=ZA60ISC*5}mKBQTWc?Sp zCtaN+;{j)-9|ON__K&Z(Y7?__(^$L7!lheV%_t;JW)=#YRy+K*18y#ZWUn0h6036$ ziSAm+>x4ROqasGxDn0i%7yq$9x>IJ~7%eR15#687y2*4z0UB9=!E~KKp#_X$IOgEC zVd>`cH@-PmYijtYEU2Y(!~^mSV%$*|tWFcH?)R8w6T^2Z4GZtlS<|>uq2fqTidKJM z8RYs<;%dq{MlX)^+>yQWU~=&FO0o$^QcVdLEw1f*kh;=`@$RbCcZql87`o+uzS|4PUi(oKWe!j)P1=(_)!jsNVd0H{K@+I zopjL9L{d)04@NsG)#=x&6w5poJ^iAOPQ?y%%l%2IMGqevHl`p^##5Y<(IfPMuAKS) zOs{|S-)`j>;x6r7zWY?H>((LVqu{tTq#NlMkzHNR4&wz~a@)wJ$scLv->t~5)%qbu zu6IA_P4Rz-*4ot+=A2T>x~wXYk|lTJ?kilm7yowj&T{JA+V5)DS#~3@irg@?##|cn zEtMj1NydM(xuiRyhpcD?^Mp2DsoV@n%9r7iF-%i=@@660_j%If6CU?4*s$G-gnoRl zFwZ4xaw!^9r&}Z}ZKaaiGMTXXz?;?Mks8s1ujQ+3@KE!f;Z}Lhw{?1%t4y!N`bY<} zi60b8R@!g)&Zp#Ak_d4~J!Sch&WI>W%RuZ{J?$c$ii*(k1AQucF%qGlZhIo=v%bl6 zsNEufj6hqNl*!n&@?d|sWezs*yePe#?j`20;>+B6*6jPXEy95((EPdXTchdERL|mG zDQ_8x%suOiId#P6C$lGeMo2vv*5PzCfe$=>b|&r7_}+u}^#|YC$<1fhaU#)Hi3Jf7 zDIll0J3F8^22T>D z`pO0um0W5;MPzPS)EDX3=UzKImB;-den%e36i4x}i3#&YS*zu-=kIuF%gLBune2Xl z>eW52xLAsPCW>3?RD3fd2-&rxX2o%bIbBj#460eBR6F0@70JyM9DKzi#?+Xyy>5Y3 zgd~TyB3N0LX2{(dN3B`h%4HYs%fIoR_TFevenzJ!`F$-mTp|x(`?6`EXfWH8KJ)Qo zj-3(T!u`gosCn0pEuDcul`bujj64lT$LiLvv;@cFMeWT1!ab%|V3IlDjRa&N zf=MRap_`PVv50+1J&_!Xe~WvaXI=1{eJ`_$oITF=dXqgI?^V0XeQCr0MoyI!cZlpR zL4bC65V<^3=bVHJK;uaF@PcD4^d}P0UqenPPtm-J7#Z+~&k*9!M1-}_DLghQcOUOZ zJ(>WR*MnK{0XWws1~Mt9{gXloq3r0U>I9e*yGtS9ow)c+~N9SVS2XV&$&YkOTwAez^akd zZL3fK6-0ah*+C*$S7Ai}0pmXOhjUO{5;{=LcC!8&ez= zQ(A(HDIbifT#qR}hnU+^#{jTfauLU(2vIbw1clJnhFwpNB>c=E+{qx6 zMuhEhCmyLKp4cXyc_;2e!dEiFjRzB-ttaAchZFE5X{aR;wSwy66cq$-BZxpc z5rmYWDJ(g4Ex}X`*)wON0R+tAX&hm2-0)x=Xf2M|B`QoYehLy5JL8?G8j!-}yV(?| z{w&q=kDC~=uXZCHK7Qc}NW-n-X-ELrC-}Bc-pGwe#6Ni?0wD(<<&Jc>#o?FCBSGDf z6KeOr4W^jPA)=k(@qmXeU8<;$vn8G9qDrcLOZqR4*arvr_QX4FbBZ=|UN$+3$q52* zKIs+;0M!CVSO{g=rVKnC?KF;QeJwmQGknx2 z#PK8G@9-hGW<7+;E#Na}GL3z38v-s30K!_B9u~jUhrW|VRUgJ5nF*K^uy6ce%dn(oLByh-QDxdk0XsA!IK}=HwyvY zk545&2t6)N_r&~jEwn4kqlXr4a22{46$d~|tRLr#loemJ6ft!dI$eGYk|+sbC`q!% z-1RLn%`5>;78$pe#4!}7OqW_p6rFk&zsf3pd+Gcx3x~)aE-Gs+d(&DF&s&_lS(0jB zQpAu`l2uv>Eq{MmO7=IC^>J?Pv$DprH;Tw$8Fa-^S;fe3#h1;B@zx5ZeTWiJIb~lt zQ&#cyapmlAPUcq1BuAM3-mxg%MQ8 z1=atC|4;m?dJU074M}VbX?YFVNDakS4c=a*bg1zTCYrUYrHielFRx`Bsb$`(WhJX) zkUO_Syb@lhHMZeLS%W%bmF8B%A{6&Y$FK6K`lo68ProJb3}DcWB_M+$q>`+0W@~&| zUSsXhXs2FdTi*DZtj2Mx(WR~0S+dqExah7+6Gw8BuVjT#Z4=jIli)!UqhNCwV>7dU zvs-erV{LPsUvtT1bI8AD0m>Fmp_VkimU}ua>9HSAl3Vy{TO!U{CTUuwbXrAST1zBb z{gYccCtIJ^wfZl#yq9bXWNfQzqpMa&w6?W1Ej(&>X#14SfaPoXEZN@aKuu!~Jx!q- z9%=VpYxk$@@D=R%-q!A?(=p-KG27O0C%xn9pyQIV^T$HRU7^n2n9hyz&aIKoovqG2 zvaSQZt|RrX6Nj#|*shE6u7BA$2BjpjKj!e?XeeO@?Y+OQE8=vlRP1*?)7eJGx=j+c z?ZZw1n7%U|6b%K8VITM3*(DPVV_-ORJb(g9YG9}P*llXut9q|rW4jk5@8uckGD=# zZ{)z?NO%^O)(H&_cOC>LNDmMsIvDcbm^9J+(b2eg;eGOG4A?-MVj4v|vp5RUfy`oH zm>l)b8l(Mjql9u4U(Jagqsg?{5gAEDO4>xjNibz`#83@64%r9Dfsa?A8W_^631X}K zu|EG%j;pZ)sqs&aD_s3^TfYp8Sr>n$q_Yj086C}A4=7L`-cE&iF zag*S+Z;@A!Y7CJI7IK0f1!+zY$4?YZlKxJj6(9u?X8OH@xqL(D_PK)KqqOA!{)0x2 zPlg<B&>lMh!dV^r$9L5O*Aotw&C?clF4+6G~y`+CgnWnGy$)PBRxc+vzO-bq!-=!=M!Ep5~CME z`HQ2{pYh=7gd93206o1!R|1S#xx`Pt%kYus9rB{H^p5prgH<`>^EYu6Z2WY2&M*!k zqHR=$o6DfeKHP^Z*(rcJm>*%h3h$Ss`r-&oU?QV)wQeX@K`@|Yu@K;V9FnNV1W4?M}s0a_!*As$KvZzeBqQDFbuH>lIvN?#(qM8RG=6OE%_gtt=$&f!B* z)IC+3q%PalH}G1glzP*xj`P@VvA8K1aEE6*QER(=d2<=I+l*d{j3Zm^{EgH0ZkIuH zv24$c?JhWN@4eqvliJHk$o^OJ{c?8;3!^P}uJs}Zq_ttQ(zJeBQNF?VKU`A5>61?a z=q^zdgcfAq5$hWmhz=IAhg}CJ#HTOMVPLa4%fPTR1%hR5){tmRyQhdnGsgUoyZR8M zLo~ae`lW_^6on8@0<-#4G_K>In5r!RvkzeR%-4>%@(%fAkClUtA9Wo+coUnq4_A*T zyiS@}ui6!LIgzVAQ5uJN}j!5PYY3GJx7Wu3*VRvGDHY!bi z4*nOd)xP%+%bG2Q@wV4MXb;8BPQc~n;Ic!pFFVsb#;CvEM|3?w2%BG9=U(fO0<|Ug zw-Nq$u~*FE27mv5^Qh})Ru(ajyU`>?0Dv5(7=o>`#`8B928wHnQIvPJ;xYtMKkNQv z8N(7_viO1OtAjfi)n*Uyhd&R;;TtGmS4|_6qB{9UGn-b>UT<*nj#@IuMWzx@5~-vf z+-j^M`rF30Z0SMzr@&O%w?q&{$(H-n))#`t?{_bZrvH#|+vOWB5cO@p2=6cCaTlQw zSoF%E@n!cq+mTfOkyI>jpn9c41M@-8W|7aE6Jk1qh@BPrX*|l))c!2a9leV3IXex{ zC^XBCqS+J&IV?+lCp)lsoLy1Xdx_ONK@*Hpmu%56XP@ zoSixl-Ik=m>_Y?56q$3U))L>S*b}^m(N@X%V`KR09T!zTi5!Gfn{!7dGe)jHr7NF)oV0DLPKw+F*e=>^uDZuoq$hJotI6tP=mVd*aYN(|AHcE(l ze(q!MVBEE^wji79FIJ~EqNmjEhoygF90}GNUrZ0{t0{Y|0DoCr9EpxX4JK-fne=KZ zD97DA2+RS!>6X8lUj%+Ny)ZG7IAi6PlgfAz#CoV}62li5W$Je@WsvHAEYD>Y>}wdo z9Pm}JXf<;G`;nI8ArF@cLa>w0dPm~M&@B1UL;Bwc*Wka*)-g2PP`lkVsB)$VZIo4_ z-B`=7)LTCkvb>jrBNp>xWf(SmUoFqtWU&>HquJ6+iWQ^+KJI7_TTBhH&{YCf9KC+qF2tn)CT@8{fu5$E`xX8`MVDDHC?%m3eWhvjY*ze zxlJh21-O4z7rl1>{?s7AWBP^Hwa2X0y8zF5ho)=KMYov%uVufpYp>N%xD4*BunLxrUc>g%gSmq)JLtB;2{Ww9zT{~Lc+LAg_mB80ro~;F?5=avQ#nJcBL!XC>u@}gMukKTV zbb4hQkx5$ng-p=|ay;8Vl*IaV65KSFsBZ+}Qe%p&Q-GY1Yp^WN#6)9xX`hLKLx_Qh7;TdL9k%<|cU&a896B>W}s+&Gt z@f*CAPkL8rjneGWMxMfV;tkB4`sakIWL7d!@UJ&P8Rx30_!Bab@|cZAj9BW%Le4-- zIDM-958}mXg6$$apYNredfP>`d$V4V@JBmMmlRUI+rg9vYB8DtmrpS)-*0U;lZZdg zZ^Urwm-dtWe|VHM;Qzlo%IouU-1!#nnmST*_1)j=n=4C)3pMN8|1XB}&;080*7E-Vlq)L>%gf74 zOG}H3iwg@2^Yim_|4)N*@yqnLm2dxRP)OV~7Cx1x_ z9}LBHbl^HXXPTl%o8IF(AK_ZWaSeR98svJ7LT_(xcXxMJS66#`TT63uM}0N6IjgC? zuBolI5q~v(!aJ08|0$F;HF#07vFv}8$?E$2%DQ6w169=@{JMNBo6U7=pWyjOT)8u@ z41p_w;EF(as&cQ4@2ZG+v^=D~qO82U{C_0Ml9H0*;^O?$^p77u;1?ie*?B z&c|gn(6zLn1e5f;>HaJv=;KyQktcNqO&T3I9(T9wmD2SvUt%+;iOz_O{N> z&Ul{k_3PJmc6K(eY^<%V%`IR4k4I^2Y;0&~sHd-|tE-E9tad3SekH_z#lv~chEEcv zyP?F#-jlg#YCd`LL`zFcU0war|H-42las@Hl+x1D5)u**CGZ^Oe;y@D5Ox3leE|W1 z|J5fsxj6CqcuSB_Rl31Ox>C-yS8hZy@3Smq)pw_`e>djRv8lal`+u zNBODjDV-$w>>}^e;jaH{k8-Ka`)KncUwHXS7aF%atKR&7c$9pmqs_HewUQup;?Zws3@?Ml3vI@7R7%|0nx->zJKnUa+gV68xmvLJg!d@1p=7LD z?ac>2RY=;fJ6`x;R5W9=9dKRkzBzSmIzHwh>6N|QHG?C+Z_0Ubh#LRK#6;imZ-M{j zllPOZ&g*~YM_VgTWN)sn#|}i3d@m>sSKUGQ?CbzCp(yhZifK9vh3&hx`EoZVC2J8( zp6hFor!OI^vg7jS7&P_QcLjcY1v3S)T!&``-oh|Fwy3k{sGkW^r|UoQcbFMwXim#W z%QzwSQnUC)!MVZ|5{AseG?67pp|^r5-lH`3-1sQ}d|8!49vWx zw}Izxj(g*UO^zKe;$yhhvzg*N?H^}cZdyhccl{5U|MMsxwwh&}#*<m+Yqh^=g+mH53{%HY_pJrR1(cb9C?*Se!t56TwmH&3tvNbn}4O3e{9~3F9oQC ze!aqy8Qnd1YA4bxFAkggF;a=S*o@ujoS#3gY=Pvf@8dnnioEXM@!}vV&StXe@FNy$ z5Y?SouJYH6Po`@Jt~<|M%o`euQ5n(i|MMu{4b*tUtnLYRTE4~%08>ZG!U^#YbCN-tHa*)wt+uvQQA*C7APeiPc$D|T_ zt0B-uV2~fdHb47eOqeH*>e;!jLtxwP+1^gu-}BfwNx)ok?jS}L3nGrTRbC0jVH)*_aBBg@1ln-a zG6)gH+Ix2uZchH;_JCTyP>3J_)Fqc-db;rsg*>t;N)-zJ8uvomhINW+P*~d{$!^vX zIW@7ih}ln^M_7B3;Ae_Y24uOlDBTljmT;hw8b14jl#H;1y97U#g?$fGEtISjz7O{Q z?XyCDSnZedJRk#V)>!wW?n)i6kpY8W6Sk9jI^j3anJ$jSbw z;I?Lza>s8?fcsE-Ozag;e$!ZR$v6auAk?@LL)h=TA)%;9P5>QiGcopoIG{k`)AZmK zDuksU2`CjmDv8dz=RGr8qWcb-5$|-@=eRpuBug$7)~J&UiZ+oX`W)+wV29|QgBfjX z6Cd5Spb?K-SS&(7xzEvvb3;NvK?lY$ihj)ckzL2?)6Daesp_#D4In~3(NIme=KBNQ zjg;Z<{Sps3wXRK~o#z`aZwE6RoU0yH8R>rFwWV1b91stj3=0ioXWpAo=JkyZvnl+^ zvV;wja|PnPa95#$WQ7ctv8^vUPp6wMCb3fM!Qnl;Zk%Zk7_FA5!zGp0Y9~JZ2|6a! zzx=K#JM*!^DRHEF1@ut12BRu?PfTwwWHfU~+0goxE|Ih`TkAf>g6qoDr88?f*|{%# z94#Z?UjBFm>cb4&AwHft0_~LC%6;SGi;0v0B55?bPx!k>~T9xW0JT z_2UBT%xb@w`Y208E{23x>Ade(7Rr?`=jlKDW*gD5on4u23zlzxV~>%sqx1>imd{EKpxb?W= z$1On|55RIfLFn7Yq;~pHsPlEe(=4u(m6qM3Dvz-o(kqK*dStT?MSwHGjwLN%-YkDF z85TUMz(BZRe(o(O8e9>d@hijbS$(q8?sv?say12w3JeKf`_;BojCi=sdkc46ff3O@ z56_5>TdkqRtHi9W8dCcX7PotMfAU-gBJ$(ocyf`#w(mZuKD5mgh^LY!G@njnu^;}vps5J)KY z-1Qyv2qA6uiPWU9^pu)Gr1ov}^Cxy*@bFKO2h5P<$E#jJ zkwG>Qrr-=#UM%?8Ab1)}wmuE|j-cR5LKMltd_!DjyIojFT=8ANcU}lyZv^=tbMD)b z=aUg&%AmPmd4^tj7O(=lk^*O#0X0wCcx@Q=!G^(O8skfXUGbzle9bdgR_%~0m~yS zNU+v*iz~7{ipAabjxZfSiHhqrjO+J~8x)IE^h6Z?l8=I@x+=Wj4F5c{7@<1_4pgrhi1UGmwv)9$MaLY1so{Es0cEFice}0hgYzxaOd7n;b&m{lLYR6i1sh+D%$MVMBV6N>-mV z6)XmOo~+`NMjM^%#1)$RNq>*#$&ucZGqBtZK=dQx$&$C*ig!@As-wwsFT51Gdq5B* zM}Ca5A+bmm4o>A$d{s6L6+uyx0BP>g+!Cbsx-;T@Ti*3H#}QNN(r0RE`sni9qMksJ zHDbvhbf*MPn=Oe%{}v<&Tn(btPPHIS*KJM!aike{JM9uv^EnfFqy0RdXFWWK1zAMS zvFYo*)Yr(=-!7B^CiKm2J;SLX(#>HTt3J<5{rE{!gQlPU==Q?O!5`RVn)!HTwitRv zGjc|{q6k1fSl6QGxi5mVfL_n^@aI`~GivN~^=AMK?ygax2jadne6l$u;XL~@X-+pO zGbxrN2pblggs`_`3E?vP;=^c0=V@i&IZcmQ`ZCj4$LxFZdCbIQkeM9( zNIP>dI?O{XJi8^YDcJXKF`^=p#El2TZiE8cBci9B@0gQq0`M;FCqe@ur)SI%--{&mY~jr?$irzt~W36)Vs%LKwI^4sjwH3pohL1)P3R zATjNET>RETqDbH(WuluXsD^~^YrD2kaDGOjS2xd z?}#Sb7&IJgK`}QSES2n|JOPZAfz+Hq#Hh;eMwQdPm9trucuwd(2AIFBTxFMGg5@^`TLX>}ts{QE6i>P*nqcy;{yN5~18mIKqW^Y)~4-i zG-&;6&}RIk8{6;-l^KuB4@G@4YWt+^KuT3^inXVf+DK)5(dc4SNF0U!hrwT^0JgNC zsRB1qF?NX(Mpk)eH+>(jTrO)0+-mZVtrSKJQoN`kd(j*vSp&~*j`nMgTc}C+*GwUo zZoCSqw69L)YXP!b&KPPHC2Efk(p^ZY@qj>^ZKE8Il)iWP^Fgp@Ofi7geTpq6WV_e< z^c{6KjLuybv3Z>B>D*T( zEUo}wF<3h;Nq13am%i(H#nZkQVNE(kq}Vc!d%g0Hd+RsZtY3NBjmA1KbsOUOON~LN z_MQinz;E0-0fBkCeB6LbPL^4=rK(iNQxt?~!?f^XpoVTxkvt)J^lcvbaO#>vz&>E= zpKLBQJVfF^+J5V04YUg5LMjNP4iCAk5BX>ehmQ7iY>%Y4)BxDBh`aq3?ZZs^y=nfe z>{w{IHgPi(rj=<}7o7P$$8aESv;?Yh3kldfH|`%DPK~p!Zog$Ei9hg0Ca-+IE%v`5 zAJ~l>+`mVkhS!GxJ(%<7xyAMyK9h4w;&Lps8A84D+j47h==Y*#h+|)*w0LAUW@^(Ou;7|_EQ8fM|4lKn6BI>57UnSdc zrbtIvk$z$RT1sLoHGA}I)*x;+x?|qy^(;!Ki?#ux8I}2iiS~o`e@)e33@yjS$Z}!x#7GKx3@6qtHjgmc#+SDARvc@~^;HRy3A> z8OslV(&CdSDFru!t!NQAJ- zH&dQ5kKJLy1V;Hv1RsXP*EuPW#mu(z*JIeG-SVHQZ8~R`sXnA$vesX}cGgE&QW<9I zdp6U#EGBuKf9zpvaMSe&0U&mlfKVrg@ZsMF%bQZ5*=*yj#~xd)GV5W1>l6uFD4ilW z5l2 ze+~jakhUhUtD(Hx-nm8aX173QlT?0(knLx=={7DKxoxuyN#4Fm&;iEr5x)ChZ?-2` zs0sGB2<3lwa&4Scv5t!$R6RRj3_73>+TDD=`__AyknJxUZhVvCKJuE!lgOu)vs#ne zY*TAY@JfA-fA>f@e{e?zkq8^R7}&pYWMj%2^1&=iJ~=>ZS%kdbrL8{XuRc(^PhDiZ z17gE#nqKT?M<5|c-BmATSK-qj9clPCMfjQQ6Ze0kNizkx_yCerEgvkVOp9FQ;JzvLDkS;#Xj#w~xBU|fy?)WrD_RNp< z4C~>qvbXE9Tt=*N6tH(jVv4YaUCwe`7C*VPeslRmrld%UfG`*!I2{xoKUVv_bJ_j3 zA@5OR*T0DOhlYDsyRVN~4S4It2a%N|z^v4Q`|K6@F zcI2ITEM3m6q(_Y3lEOkOQ6bPt!a#}}Vvd{LHy4DsD}X?5RW1bYQ8LY9H3|O@kCIy( zzwkoPdUYU&>XGuLXIIHN*ZHLu%JvAlc<^T6Q98d#C)4Z?GqMa3ID_}6m=w+T(g8PM z2EBFd0_FJr9G_#0Vb;g;0`AaBYrV*)r7R7;pUj_Cf?HU=?-!2~h9s;LZC!jSH;Uph z@C;|v;r!AJ5wFxeaRH)Q1Fmm~m<&<6tuC1$8$Xd+%aR~E)d2FAT15g=6cvYD+;Txf z>OU2kbKrq@_9H@z$>}(MJG7MqD%N>%nVuX+7xH78+=xeo_V^~S#?&H}y4dL-H!P12rJ6=&P5%TTF*}p2H z$0UUB2@-@LQ4uWnDy$Ei$rI&y$zL|;s4^<(@v!}@JNo#TpE<2W{l$FR zHyq^rMb7Vq(ZTaSmR;8un94fFy$t{+h1yoZ zc%$`=N(tEcj-55_+xB*&ck(J=w6D54c74@CSyrEihA?s42-nw|O1*ZVo|Y`j@$`+7 zl!9R;-M&1DY3J%Jm44BO4Pwqc4#A!(0JqAWSr;B(u0o2!#lYr1!*AMCxusfe6LC%yK%nmRexmMEA<4!gWp0y?yXajQ58+FJsiD78Lk_n z@4m%`S#H}%$pZ9aH=&E4Sg3a&Tw&E5Zc$6GBk>IFg zMm5vadt$N*4@6takFt}W=N?A!`!1RlA`%?WlS#X5dk}-G@n#SXqRokL%JltMHxvit zOs)@sLB=~ka2$|>3?eF2ZK9A^Sendp^zb|)8N_V?6ew|3b^3G(*QMxs_1=*(p%N?| zbbGH|3t^)8%+;qqnakR3si(V2A*9rkNW=z~p#=bLa0w|62?8MbiO)ZEvywmRdr15> z*2ep3Xw7qm-P^|v?&)bdTVTXpgBIQNPU^Sh{yZ84h;$hZEb^m-KEa#lB(%g!x_SUD zPhlDD4pAc7ysZq;kRx-t_W*KU69zI~C3^)?Vjv;Hax7XPC>yZlJUpY0i^QT)#`17| zl%3Id*w>E@^&bcRy=wJrRpB=IfcjrIdV2JNUvJ>*(>uW&iX1h(cZ6eUE;g2 z^erY%gNTE9^tY@f4MLBPjn{2M}jp^EsdY_7@DZN6N2T4UP4L$6)vK7n#cpJmJv>tsVeeiGn8<$yOl5aC~Lew zK5Y0T@S8u-Ouc>)y+a0R-f(3{wco0Lmgu5GKuA7XE91rf&{ohCTLUmz_=+ifFZfE;m9Q~^ZWHbU&7-xob5i|nOQAs>5Gd4zL~ zyjlOTLI=LYpd_`9j~dOEAgKG|;iw z>xBCKb{XQjtrAx4Z+7+jBaPRIwoFEnOd;53g7A^1jQaK|%s1I5L-RqMWP^W2bfi4Nv-0~CVQaql!W$N+_{0|@ z^^Y>O)M6u12}^r2Jd!}al;Wpq=4jYibltfe!MNJef@_n+*jCk1+js<3S`vX0EpU8z zvvg$qwRKdF#V1a2`8YCB9kluKZFAo8eshlhG+);pM9}i70O{2#>ln`c>-f@{j*B3u zh#mb(hxsJ@ufz76+r9)Y7pLQ_k9Jk}E+g*Tpr@-J9j23@OVfC#I!J>0BL}ar&1fnO zw?SZ6n+PYra@}Y8Z7y-#Z}YzNj)C3Ezh?Xzm2Ll*wLIA&#;&=aD2BECGevBAlFWr) z$L3QBVMUpI+k)2%vN3~|^#3|8Qy=~wVLv1zcT>kAtfPsHMPBfBJH*OiAZXE;JJIME zh+0njFcv6mBM3{97fTBFjUtK)S)%L)bI5Nyd>{dfT;73Z)$!0-L+Wo6-{$Ke){tTJ zN6?&$38ABm*jiYXut*LCYMRe_m!DHHbZxo{WMUD4z6vDm5;&M17o412;E+A?yan^^ zGrzlH-h}jtpaQpEEsaL|%Y&HkqyqDjj}IEU7~C_lq0zxS8Fdon68^FR$BOs26=)U} zG02?vb5PM$AmMhF`gV^<+GmnS^!od#$f%I7o04kn(vQH(kQ^oT_O1_dxwVg?MAskk z#wdTL?o(=4#3F(d0fI5BzQ1mL&vWD%G*m>Sps!;wm1yuqX^X)<1%hK`(01}XpUQ%y ziXyqPeW8+b1*xwjgj6jDN3CkwpdxhHhgAzPc7yCThuSQtbZzy&lu~*VrfkgwH3<0_ ziXyW_qfv$Y0~S37I=xv@VfxL?M3k+*S8Zc0VUFIBI4?|u2qKEIhR6dQX*L*~CL!xTE7a#yRBx)4`CR%qr?=(@hwM5$eIAbh$w+BtI44gpmneW z7sv-f5Qrn7u(o1AX4J=$#K&(O3f0rZ7?TG|NXmPV`+jN|;zkS2(R6 z$^#(!O0aB4flvTMzy~BCgMXkbffxr(P|Ky%!*pcIx2%calcU6W1bbo$dU}XFYKT$T z20Y7w834@1{0kQNI5D_FTS-i!qn##zhka-VHUI!czz6?=u!dAP2<~bDB>0CSXn^EY z&gEpz=5)^IgwEzX0XH~-=(Nu3#7^d%&g#t0?(|OSq|WaYPw(8$@ifotEYI`w&I$;G z<#Em_83q>!PxYiv?VQj0#Lx5;&mZ7RY*@aSqz*Xr7Cq1d9H>o`qn!{S0w_R*bU*^% z1Ww^Jh`#(ROK^h=#n24Z&<*9#4)xFv1ry`x7dbv6Nl23;UavjhMm zNK4jQ%X|btW&BjO{0X-M$mPg4(yR*6M3%k$QLhrxgLnaVumnZTm0_eqNkzBLK?O1R zfhIr&f9NJ#7>6-{f@vtq%cM%YR3**KOrUT|gW!ObR6@+WzUjfbfv^Ttpw%8R03CD) zZN$|{{Y6|52Yg6}XMi+~T!(n@NTaMok!;Iw97&tVM4urD2dL9pLe+-YSA;N4h)98T z$b@a(5lV0c%5jJupn??$*Jr!OQ1w)Zg-id=WQq3i0$UsivoMBf>{qN%Rg(DEgGhxj z_<=BRhIC-fMhQ%tu$_keyoV*pYMfU-bW5I?z-J@~EZ_*1?AVg{Sb5pYy6c5=zz1{a zg&}CoMWqfNph=gt$0Z%0=>yf6m060F*Ph5HlpF{O&jr!`uW*N>3P`@k(2s-r;U+f@z8t5jL21q|3+g(;&I+C*HpzhXblh8NMImcF$fVtpvu%hKAW;8?9o^JY+__y{)=k~3%|7K}o`Hw}`w9k(o!w;B zOM@)i9T@{v7=wtogGc;b)C%5+m0RKcUetYwH`2dm>6l`e#<8W{A?!tVRN5`66+DR4 z?M0{V72oi^-^DfFm+;3}%Gi6WT%WyMkoDWA09^MSmpOb$`mNv6Euzy^UHpw;{UzR( zKmg0oS^&^lH1ya32HMQM)((8%@JIqq$h@z+g9T>bP_o|%244x@-{EbDXB`L&NSs(G z#139xFtpw2-4UG7I|W(cv}$3-mEp}S-U>bm?Mq$&K!9!&1`Ooa0>%( z!05Rl#9UjQf-KQZ7PmZ>6&VCLs{9M7+gw22*aIZJ>Ft7f?y-QWJ~VjW@QN)1^}+566bAWL@r20_F*1@ z0UCkFhQPvB7NSZ<;y(stW^Lw{m;j!!R|3e7yuD&ku3|V2W*$)mRv3fu9@<206^PkdwO?b`!}Ni?Ye1cQj|4LfoEA98-?$35r#)ntbd z4xos}xrzQ~7shCczG#P_VGGa>Zt$h0!fSVB>VEd;y`E`<=m6s& z3s3f#90qBucJ2Q-8|^b`(nfrU>^TLu+`4%Zn>6} z%I53jR_?NfX@Up~SVDmOFa|c3ZuTZ`-hS_dnH$KyZ~X2R{f_Pb?(e?#Zvco~0qB@x zAnXGV?*!NC1#gt8OxQ7ba0pL1z0T@c=I`a6Z~$pl}0-~?BA z)NhRf%sFupw-5=h@UhGsi#c{uYsZ(Jnbz)a_nnOp@c3~oIb?oe;TK<9}?Z|_%!byLS=SLzcQxA0>R zc2-;DgGhlM`Dvr*Vq-3?`PFqf4jxhub7W8UY^P-c;Da+Xh8nN)NB?yNe+hWdg~mp& zHWv&c-~^&Z2ofO1Y8UnRGwiBdR!h%cM&JlyFmOk|^liuVny7pYDUE^Ge4!1kiI~uxf$V_!ghAWk-k^(1dKzhh-oHZyk?kcM6j~h);KTgj{$N zQ*lTq_i`U^R|kL$=(e-SX@Ea+jvsiR$b@_FhjcInB0Kq)4-6?#g>!3&JFo)ZZFxo> z^_ZvmMwj`3-^@iQ_9w!6o)>n(3*nE*fluIuc;JOGkc4fhs*~U&KLR8{A|$T^07OzG zMjD6#&;)NN+E55KOd_^O(-ks!o49d^Cyjb7=5?F!^>OcduSa!RqyRlH1~UA5pV#?!PU>c@k0)S&mre$g-fe55F2m&a8v}?+yM}xmy0b>8A zKm3hLeDT3{ZFl^~-*`R5g2b5zU?{cduKeIfcFZRTcen**D+m)1)R7pdg2JkSNT`Ks zsJD2ih(ZE=Fam?fs4KhuT){!$PS`3~#oaFxIY)DS?|J5*Ar6@IVORtw!rA%1`XhJ# zfdGgT00t5)Xz<{{U9$j0qjk_yx`8UxjS69c7PkceK6TR+P8=>71Eo0}ILRGCf-U~F zNa^w=%$PD~(j2(J)hbFbLFCaBr6$mzLWdG9YV;`5q)L}AUD=Xp&>jDNKqcD1O@pdK zuV&RMl&jaEV8hk~n*r85dh#Ac@bc#a*@I)_%A89VrrnxScOdOYqo9m_LJ|LI8^N$7 z!5QOB5oGeMU%zfX2Hv_?P0W~U&<1+@M3But69z@JC@uBr-PAQHtzuOJW)(em2B@xW z`!?>}x??)s4L~YY-vjgNCSDw?@ZrdlU$yW^9zA-oG63-KhtGrB#&K`I-5us$r2hUA z)L}0wx+Vh~7HmMtI2AqQ5X}276Ao}K^Y81qBOmx6-Fi-`3{GowuB&H_gT{IpPUQwB3 z(oZNlW}-Q@k3ah;0Dub9JY(2EmY`$6Kq16~2mqt#Ly-Ro|C9j$Nd%pA z5NW2dgrRC-P!d8+R_JjBnsLfGC!IlQs2hhNb|svRboEKrpISMvNHNg~gGB%X1;E80 zTqOG8o+FC5Tc88sNK`oC_(M*n;dIl?6hW!L1gT6|!wVAtv_MTX0uhwSIkW+=06dBS zP{uz)4CKUrsc1t`FU`DkXPvs?pobnk6uT_5&00t-Zh7)K>2Z-tYHhW<5wHj`(G|0Z z00n9AM;{Y-M{RDEYNhU_ML`1tQ|!5y%@8@*yW|n~*n-3oytJbO00vwm%@a^m%R}VG&Gp#yA3jT_6161pzjvEI7%7 z$HX&Gv!npPER8$fILB6#EfWejJ^0cAlWV^D*u?q;m|$eJovoe}#tqf!LuCL=bjLhG zfpU9Z@W&q)m~1%Cxa%ww;x$3@0sznmKfLgfpUF8;gRIhu#mGDVeAvYLGebc}yuybfF7>^g@TaxWy-^x4__du!u% zkK7~=Vv@!+a-sD2Oej@k?XA`G}HVi-rZeWjys1)ZoQKrXk(IXfun#old z)rG+QvziS(93qbr275?j6r+%aJ=V6d6yC4~svv_)6rjc`$g`w1Bvw2oBWXHw3ZJfRodu!b&*&@qnMkc_S%;X$HshY6Xq zs`DdOHZrjTcZ3QG=jbOj1sc}eB}D*>VB-Hg*b)?P{=oxd-CaPz6VXjFwT3Lf3I0+t z09jeJug)VDA@b1=gl*)DFO4f)5ev7v!6XBCqlYjK8Wg{I!IeLqsZ1f7MWZNy5TOV~ z9hS6CPKKd{gYYYARS2ydJb_98kirqbdRei~maIh~fFq!D3`a0DD6^}b=@=WA)GdWw zb1e!Hx)G0STq7Rc(A7reS4=XpBA6*5K@~`v+U;Jgu7`c7ZEKs@pm3mN^ZbFZI-3n=*#WT-P?1~Z-}17<8^w45A4gH++#gD61{c~}8=6CB-^{DQ#-e6Va4 z``+NfcewN&2yUTcj78*BC>ewqh2Q_W*a{cKzB18eL7V^&|8kOruCVSw25^UrDY(YW z>WwZ`001BISQiln?|6fXS(!LCMdd4s6kl{PpM%|s65@n?DVjEM~>lC!% z;|1Gz#u^JVqAxUNuauIuKn^lcVL}1co%hH_>A-a!P-moU+9;ha%ASw%0%iCEANc4; zGF*`5Vj6%FIzdPekfp3d(>gi5VJ@z7&DuVjR+u z{&_*LfFff&Q7LQ%C&@(&>~|Z)#Gm*FVhBRKsTa@XRaIUqs_c?X(!A?cA=WvlCMI;S z8|c37`N>m)fO!|x(nwj<9~MdweQ$-|oVNQ>Lj4jcgd-bK|EqLOYQLu5Ak6zjSPBY4-e2^4)gAD9> z2@%R58oo|!;9``4D_U{dgOs2r{98Qmivq1fOk*AEn8qRK(&&s|9`noxfUxOtj731@ z0qJwA=ueM&lP~>{syB#24&xFTJi{OT5Wrn(^;7I;aQ|O04zjDEPxzT{Fd!pQ0bW-0>T^00S!x)SbD6--xb6; zH~|1$AOHx#if#X(UnPMma2Wu&QwfA16b=jfg-n@g91h+f3KGQTiBGXH#d@iaT-4yc zrJ$aP;a33M0+xmY5(JSL$vz;7k|4x8C>0Sxfg>TIRT)5l4cI^wz(_?QARfdBDn$wI zU-OwD1aUy25S>?K&<2Ge8J1xrI@=`nTk5&QsFcd7qzXbX17o~H5Ey_j{KBfWUkklj zLBtRqWKJNq;vgnPAs(Os$|C!?89fX`05Zh|Oc9JA1l^rsCEi^ylHTb-n*<&N6QBb# z;Dax4!#P0L`h`(nu|_K(4M7Y56~I#~y5bb>RcgfI6`tUH4Wp;IK?pcPifmI=Ab?xI z1r(VfFk=7VI9{Sm9OFT_Kq&ZvCjv|gx+b=E4C5t-47oQ!~js$K!PB#Xu`rwTPnnZ zCX`*~ogG9*P|M5%^@T-}_2N5{V>trl7|LUPrJPWF!zkcfcTJ&RNkJ>T0+%VkjH%>G z1|PA6!$J~-B!mM^+GI_7rEOS1%N#?|d4-(e+e`c+M+#-#v1L4B5mIP^HTZ)yWI_&D z8&mpK7_4DIxXEl(rTh`gJycuH-9uMC-&Z1LZE!%hFd|uC8XwG(M!Mx&isQc(qfrip z5sd$WH|T>iWMwoa8rlp*g!lwtTBUStLnstPDEx}$nVn*SWomE$6Ac3;P$mEzn@>(= z$yw(1MMY*7#S~ma=!7Pii2x@ESV6=F;+^K=0oFb=gD8kXGw4Gd9H#!!qHijN(6t>r z5`Z8%3O9WuNRnq=nCEz6=JyeW6wtys#6vIiV-lWXLG&ImIj7e_3l#7IbMe9xz{Dq5 z!#kuyGVsShjDRhu13dh~UA_c3X5lP`<89a?FhsyF#!_USCvF0TT6*M$mZy3m#b$P9 zGf2W5;bDSNqZAaxCCw0icHJO0!z3($6D-3x%#kgS0~tU8HB5tCUEEDVXoNDwBBcLC zEI0rF(A}{iU3&JW6$+{MiAOcqW%T4_YW*V#b>JN^+>16Gu`nP5ssNkF#0>ny+PFYI z5W+wl!9Q4I0yboj&LdGK1v=6LEHIS5-J5u7sFOORcIriN)`U`4sWc{7Nh&94CSI4$ zob*73qe8|wjKWDC1QGm0s*u4y0M9^-!%U6_10umc6hQ-wDyf#Lsh%pTrmCu*>It~P z39Krt#;UBEYOB8LtllcFvZ|}*DzBz$ojyVckZP^=s;r7!1>EYe605SVYO*e?vzBVJ zKI^kaE3W=PpxV$#k`{gHhKZC#k1ivPv!3%Bt9oEv%O9s#@!Micz+5k^;aOL14_G(S-#N6g?1w+tDo95Q{ww zY7zL7!ni~<T~@1g2^#0C1{4L%IS7iMThbq+Z`|RDh1rh z9rJ!Dh|cM6Mk!JlBtk0WQkATNQCIWCTC&i^Dz$_6N=NvzZr}w0DhLoN0B=D6je&?A zg04e6FzAmmFaS62D}8945^w=0Mde;@0%vaUJ|sDftW3CMD!~7wOv1rttb{QPim;%&=0(Ok1@j4{NaxYZg*qWkGDE5i1zX ztwJdb#Ia;BT_nRlXkZn0PT+|FFH8f#NP^Z`91N>q87sviM8_9{@!K&9;E?ekOCke9 z8%zvlK@@>uqG+O(foTnd6)fCc(851_Lmuy~bP+;4;KDtiA0`-F`>@vg1N2pmr`zs3vQ=rg1tPbyb_9-i0Xq1D1`l*bvJ#EF=*=!B@Se89%P( z(gYTy#Us#iEguD2VV@(raszX5(*bcz5JGfLXLVjDCMW+|2)qI%*#;*3!yPiS6&FN2 zPz4bR!6moy|3dO3y95?M2P}jOpBe?+HS$mfG$lr|Img6)_UC`Lv5hS;LEwND%vxBC zz(0_KJrim{fCESop(Nljqh+yd?lLbY1#O;}MJjSpQ#3yjW6ud(iC_*}90(RDPHCwY$WI&+=0}LWmo_#Yh()1a}=HlYC2!d$~ zh$%&b84sv}fUSV6k%a>M13L&c^%lecgaSPHgFo1V#8GofJM~k~1O*HOWKps64#fe# zbY=cCvnlXF1E*KVg!w%xq)Mu@e6C5cP)-1Vn|S}5S4hD>?3`QUVF)0B6r3ntbG2UQ zbxlM-%Yg3=6NOA?HA7pXI7{+NkgK`20lKOyyGAwzCmMC}z#MCIRUAT*boN-EvF+_hQ2Y`I`SP`l>Jcx^J-zcvZc#E37D4@Ip|#_=~T1 zQ@?jw}fBwZ+N&%h%gDaH=Q8)%c)viOv68@6O;=$j2m}^ zyEcylK;0G;lG-3p7%M>E`C&WskN1z7qm~lf0S;6JIQ)Yx#JQYH`Dm;3jPtky;LR`q zb}r}mH}yE6e>pjq7@4O8ANw)S26Bndp8`-qDadVAxH%^}dYaFbdIhgahZ_2hym@+D>GAp0D{86?fAPbi!g@M5Ok;{5j(E2!w`L)x;APeyG=_dxm!x8A4EQ^#pydW<(c(92^0 ztWq&N_e{rxZce(muRY60eeKFMUEB2pi+#f>4=db36wG^${KFA~J%(t!P;tDZulxya zd$%LK+RfR>hdH)0{lJ&A+^7G%z2!6fyy!{#ez7sq-a{zSs z`>h`YMrMcGtGv^9e7PSJ>AxsCFuLdu{_PW@=~FrI2R{H%fXqI=x2MD|Qjy2Ye%Z&p z?c+Vo0Ra`}`~g>` zNV*kY-VK@YA(nac7OBl!@WP)z7w8Vwdr zU@hr3@*)B9M%@1`M7U;Tt44y_V{VsO0GQ7pOVSZY1$9OV!30{k!4Cj3z-eK?fymKh zpi#0hNQ4%!jOncnxzvh>Ry@%I4=Y;g=N}}xOjFG+JKXKVef~}I<5yInKu=f zsGA9Ec)_g&YN9!TpiIsw3xEaS5fur$LwSdZS`8d%8U>B6muh>bAZ1@YCM0QqvC5d- z^Uo2oS}&|aZhK?qq{D(9da#&wpbGlh@n?( zk0fIW;~Cim#$EkGfJ?;U6$fGgV-(A62?)=4tQf;yZIMv;;~yH2h{niJqJkIvNPqvh zAxK3!D3EGN;_2R~#{d9>9>UPr={E9(7v(XMZuBH&y12+jE|M-a=;2pN0FrV1V-2Kq zWpYM|mPe}alY1n{ohBkeKKZF*eC(qy&%!XR94eHGjO8oUq6#uvga~7K0WzT(nPZw| zmaeO1F9(tVVi}8e7El(mu&KvzUh^Y=JmWN@xs^y1@*}wT2RzalPr9H}E7c@hC*3$n zdIW<2(|JSuy3o&Yk`smmt%y0pNKbjzgaxP6LnbOL2-7mtMu5B*dpJ-CQ6L zvis>kk;>5;TE>+-&FM(Wz|Mz!;~&>}>Qy;}QOER@hDTNEiG(50$S}YQ^5c#{MTpXZ zf|9AEbShRW5(0;kKp{C8O9J7V*N?olC0x~_TG^($C-R1cE(B~^y}H(sAk>R|)hj|u zak-f$#1#MN$73-Y!RKf+v539j`r0>C!w90ITM_0k@#oRfqSlv;Euv#HOOPo@6(M60 zRcvv~Ev;USvuK6n{a}Hj6kg^5%KAWR8@5{39`?6vMJ8->YXFCW03kjwV{Wkv-Icac zrQH=&BUabC%Lw3NUXTECO^e?2Di_G;wN=yIHH@DgaC3lmW zQshV=JFwu5+0f?Rt0;KE>dgv+X+q4ligLdEElCn8*olJ>Vl0BQFlPO`*xq_qsmqB- zF(|Mb*clbVEorff9sFMQHn_F%J!geKJd&k-g}MY806hK?jT~n-#31pj?K8J;CiEO;%9n@$g2WPF|45k zjTjW*^+VwIhkydR*v2NYfQ@Y9Hn5=xMzGBipzUpL4@3@~sGui0k%^k>d*4kZ_*opS z+IFL5$*kivK??gqb|+bh@4j_8ZCsFb>{o)(&Z`kRfofIT;~$bJI95HbWpKlr<$BR4 zFy=h$hZKg226;GM&TVCx>wMu{M0PWrd z{*jHA?H#9^FG#|Z+jFg)SVb|v3xZ8*^RMT5_OuVX?Ntwen3x?)X-CL2Ag6hwbNd8H z|4K9d!4FX2hV(BrJ&ykFS;w!%0>lc8KsbGY*v$?hi+4%w_YD5J+&=uG{s=U5k?*)S z-yoQ%JISfh2|KXgqR;2z)LSn7#ROLv^m9F1v@XiNkNi4~01Ghp6b>cK2^GZP2busC z{GoH;j{X!v4MOf|)B)f$i~{A!{saQ`)(Zh?f&>4;YvR=6@H&F=D6Y9|P5y?J^r8*&q;!o8&0S$ss2#2qpijW15kS;)KY)lX>R*d^pP~2!~`rc5)U@)P=klSuS z8N`7LRSgrq5SoS%1ea?Hw*moljhoWYEbPdvaLxcN!uz055Zz4<`)vJkkPN~>7xa(| z>8cM6juJ;_4CAm2+2T%$q4f??D^O6*$WHtkkri8!5f?G{woHevaG}CLWipWq@rn~E z%oEE86sfQU(Sicz==zwj>&%9iUNH(o5EB2p>ewcc7iZ-kdZ7|>u@ek|7u~83u>ueu z%oSG=76AZkhT)QqQ4P260G;s};V>9qFdF-C1lr*r^q~dF;2MWW8(WGSc?uZs$qlo@ z0+>v^WKZUvOn&??7T58w7E;X=Fyk7FA3tmWtYIvQ003Yh6YYQrMo%B*%NIe&A0tr| z(;~Qn;j9YMECL|T%8wZX5g*gYX5$Vl=W+E2*-txDv_Ik|qBHOQaqVD*_ND)$uOv5-MY|(I9dvYjWRUU@V%! z!{X8p=aMD7QO20^A(D_D3`{Irf&j`Z@mlgMAI&qR5E`xUF*EB36tgiqkTf3>{{qhl z&*JLBF)LUIZFmkeLsKw=@*PL>Fiq_V#v*D^Go7}QHC-_OvZ69W3o}!K=BlVR0TV58 zQ!OQNH|fuN>_G*BQ!aV)+lbROTN5i(=NQmXIZMLV@W?r%Q#whqI0;iKxlA?T3JJzy zAD$^Yg%dviYclI>_5=W8l9N0~0s#QZ9KlXM_tPo&GCe=AFyC`Kb8HI60v}|+KDF~F zyORu!^D00p#T2q7Ho~w%%|QQ&%{E_hEw|A@ElkY*!5;LELhlnr5w0$wQz&VI0ER)R zIy5CNtvN%KL`#%L-BBjt@##$SAKn2wUGzmQR76?A&hEq*OffcDV#UB|M4$6Buk<#j zlP#al3C2PfWF|?$5JssrO+J!ug?D{29lVJs+0 zOe=J=E;JM~v?ZQ2N~N?UG?OD#(Mr+uOo8+tP1Gm%tp(0uEKJT%|I|awGy&r@A#4;! zmk}jqGxiRYNt+ZL0hCVTfD_ zO)bJr%e7HCm0=flOHb6)CSfejfnDVl2W!GY3hf+*$OY~}XH-sLA@xy5A^;#JT*dVx z$V*Y>bWjDAUF zwrQRAX_@u}+~5SDwrZ{RYL`}OsTOOwHasnWYm-)M!FDz;0BpHdY|S=p&vt6nwr#H# zZQV9*qn2&uwr>B!mTuGb2Uyiu@zj-`;L!d-2y%9z-il{$k$D8d7q+b+P6dE0!3`ic zawT_iDYtSh_i`~eb2WE!Ik$5?*A3p_Mq}Y~Nf&ZS>JJ2=bX9kCS+{jv_jO@6c4c>V zE!PtEwu6rKa|R$3P$eh^cV5L}S`T+16qjhR#Axj{dEqvB<92!N)@#+)d7l;oV&?;x zcW$@#dfirfwbyL9w|lYnd%@Rg#kXqpwpekuZw1K(xM3{Pp+$dJXIp}2eHLg1LTI&h zQ(G2hM?wkzb5|8YVI6f&RTV?|cVuo?{VXgDvh5#q0cYb^ep!NN2Y_Rn<74wzWCxQy zQ$o_l(=7iLLO@w|MhVz}Ik;(q`r{RW^~@8KDY zU{y6ZH(mB4NN^tXvWOAFY%ond%Xnl<*opHOiiOW&U+Dx=0ac#uiV0VJ33H6y_<$=S zxWe*O+eV7YGLTQWiQ)K-PcMO^Sg+Qgfm4BxozIVH4UhwKi4{U1>A@(6b!{rZxcriY z9hr;;S&^T3X5q>Oqybe3!ICf8j%#9DOBGnbCKwo%AP%w%2y~OTbIzChxb*o28$n7uhFjTxr~KpV!QA8wGDo0*nr z!j^YAm>(h{grSr}*&vRXHotkBxjCPQd6lUXtETZEm;qhTd6t(HU2nN193VT4(U1*- zjeQlL?-`;SIhB1boEK^bpkXZD0SX2>r-l=n5f&xxgcyEVjRD}&*f641nUN*Br5~A& z!zXvs!~kXiRXU}kJ=&Rn*r3~)Buo}m8TxgqSDsP1n^hW^Pr0J|*`kgB$cz+mak}($ zI%GjQWjmN2j^SY8bOOSI3*PjoO*yH<+Ncp2rmsh)HDm#F0aa3=Bcqz2ZI!3tG$sFr zSTX_NAYFu_$C|8*nx$XbqF*To;(=m=;H{x=~Lp3EbfF96TG7~kM#d?6DKpD;<9byC9~Sb(*pRdXX(4!lgRBYbdupJj4eA0Tgi}U< z={w1p9IWqrj+cXO>;`Z2hHw04AOJ^j2&H-LXms*FKAc+2<9SD5s^@`HXHC-*@TbryVj+mDmG3)=+UhP30#QB*^b*L6l z#T0Vf><>HSMU2?(UdhALP*EZPSg7XyZ|-}V>(BK$1%8D)r~$xXEYJa}{r>EmenADl z&QqC^{x>BOpAF;wC>g);jeX`Z8?YxQ1(5z9+Mw?<|L+U>^ex>YGT<-Lm?bv+6dm8L zwSJz@GV&uCblPCHXCJrF{@)+pBEZJCTjJ7=eDRqd_-%jdMIDmsSbSb!8&HJ|l3)2Z zp9nj@>kl}g;XC@L=mSc*^v^N)h5!0ZS~v0jbN*#4paDt4pUB3ao#&cl0b&uoVgvvf zJcux%LI4{2{P`e2VFNb}7FxWBF{4C^8asN_II-f#ktF{QhAfHF! zG;7+t*y3M{n>>30P|)q)KYwg|8a;|MsnVrPn>t09bLUfwF@H?W`10z)tQmpPbJX&J zLoNk3iqyK5BigiQ*CyoZ764qgb34YI88$X7W}_54|FU(ilTE4-Un@8Z-g8we2^4hrkpv}@bWyE<-T!V_u4 z_zgU`@ZrRZ8y`-?jql^YAJGHG{P>Nr2waNRYno|x?bq{eSNh!`>f2LullLg8&6M-( z+q-}7(fr!oeP6gKWGKJ>{rvm;{|{h)h1?gQeu@7WLys&40w_oznN??9Ti$gSS9nQT zcoc?4SvVeiNXh46LNCY=Vu>c6m>7s!(Wh5(cEkZ=j55whV~sZ6NTVEX$bn;wkkDhy zi#^uZ;2(g{fE9&wDY=%08!`zQlv;5p6N){lXl0gKZpo!lSWd-aUdhRUMww=wiDsH= zuE}PaYPg|Bn`Q<>Pb_k-StKBd#E_(f6-wC|pn>|iB%w_TN>!Czvh?Mmjy?+Mqm4Qh zW?W<5iD{;Hz8R;SgUmzE8Je1z=NyLciII~%smc?pts+_)tW8mgSEL_JYHO~#?s^-p zOjYXErK1izET?zILXR-S=9xwur}pWXtla+@dMLG1O1l)TylUj@w%&dVZh3s=1?*bF z5{vGpaLSoRG4wz(tRQ~;0Y(~VIE!k8(ONsGVXoTrZ%x{Ut5CNDAB=FqC>fkoxoDl6 zZp3OD+h!y59An0)^3rSXz0anKEqEbcI5NrnhIaB(11rq1!Y;oIGXO0g<*-%|ON?`w z6thVuFdF~Cv6=Wn%Uj7A8hv!iu_`@l$sH>6i8b$}lZ+9$&Kz^rTJwsvPc>h4bIua) ztmYu{(9=k!X@CKAy=M*$GSk!U>o3wi1x(Y*3N6~LP71bmy>;P+b4fT)Ur!ab z*y)m;=8wau&34dlf2?oOa%XGz-JSoxy1B@qi>GKtGyEgQ;Nu?7dh5C-e$(PlHSRdE zkfTY=yO^#Gv>g{G) zEYBc!rUA$we)#@7=9?vN{OCv(-x~YzyPtGQF(J`H{vudpz%tWZeZA@laDecEolUaW zl?LTXWtAiOSs zEv%vy38O-qAdo3EtYMoP_#^*gbPP`p;)AGys6Mt35j#jsVjEGSL^v)Fg$WrzEzD7b zU1jl#eC%UN_Q;YgE~SfJTvG$-WG6Ol3=n5T;|0|S!bnPzjYcHi94}&vc8nnhoHRl7 z{0PcWHU*F&lwn^8Sx7gnD@|rY+nRW1IXMXtl0{r2C2jd9_dP8kA{5FbJ}Jsz3X>4}OiD79sk2q0 zX&AaolLUWQL20IunvVI}u@oUNB}r39@>HnGRH`&}BSv55Q=V!S zt2(_3P>mwgLP8FF87tEnzF7IbPLew4JVdwbb5( zT$d-=UEt2la144lh+btCn|P7C+Vswpxv;(HbJ<(n_bNDR@kPjdZ&F|G?d(U#fae1L zOWq+C*uWcpEKItY)95aE#9C|cK^|IP*s31Yy@X9!~0(L5mB|6b4+nAgn)@XuzjOEN;`B%9;<&cT|#Wx7T zhkqDIl9kNZ88?}#=S6RuIk#SxZ8^(yzAX%cY^g7U8BgW=10RG@r&MBi&2%NST@8Kc zH;eATau)w_ogb~oIV%OlHBoWS&QQ5PfZ+^hQ*7-9t!R@GSjrVOW|b=|X-KO&OFsqx zrDkPI@L&dbxUGBs%9I>cbxiEsBm5F@ou}dQ?7R|yM5}} zl3U#TCQqx)%@TBDO5M-y7^ftM&RmoF-r3e5zJsl0aQA!S@A)^fg{*Ae5?rmzgcCcb zP3<%@x#1op`4Q*6Tww2*;w%r5#qk_0Jr{E0Nq*BA6q@jO1DM{W*0q~`F5i3$d*3ZD zIu`$l?zM~OIpZ@2!+r~HNH_dQSveQEwNYN)o-h2hTaWF^jSlu+A-yL6Pl>>p?Q~~z zoK0`a9mqq@bB1?apFoE*qZ2mluQ`4el4tP_`?w2R^Imx z`GSpIaY~Ol(*d9Mb)R`+hOK(s53hB@(;e}E6?()Yk9x!OUALE)Sl~6K1_Zqw?kOid zj_bZ?+>@^HT$_CAe}9wJd%5-Kdi|(=+h2HFUEU@K-Ka&+Va9(Q_|(6O@RN-*;}5H6 zL@s>ja6_I~d(fA7&xe1bM`gShY3CP!8Q2onhjGJ_faroq4XAvd zM}ZSqg8FxY9^q}MhJhOBf+WF#OQ$Ixh%W9%2_i^)S%-qr7k<0egQwAdz1M;-NQ447 zgiBF&C_zXxm@bkNS|j*?CK!RuXGw}zV zM|^sSGsq$g4OByan1YpPiBsr?4km|(n24Q-5sPSmm*WEL}*J#lQkK2{-jLDdgUT1#r7>(Z)0{c)02eAvv zkdI+_6*drzX26jh>5(4^k|8OQAUTfdgoA!~j#da|gt(B(=#n=Ti+1LaiTF)A@DJ-@ z5UEfN2_XXc(*j8F4@J-bLrIiHX_QBalu4DbfA@A36^0gmSahlUug%0Km$wJ04LxEC!m&Z372uXmTf7Qb!nGG$(C+;mwOqP zdC8Z5xs-khn1gAQf_axe5R;Mecr(dkHF=W;F+nZnybm0t?8Pt37fGgo3lxqwP~BTiJQ3@o0gE6DKw3Y8FmmU zkrZi>2+@=I1C&BZn9JD!7cdAm0G-h(ozqF3)oGpA8J#qsoiv~WZlD9(37+98p5sZL z;`st^X_(9jnCYpWe94~extH$=pLHpp^VyelxtEB9-Dgx&ZMfk54GAHkgdiXt0wRbM zgQ8NDF1;7&7!*(`5|l0_q4y$)AiYTMO7FcxDAIcoq@zev%;Y)GoH_5Dd1p;N=S$Yw z_sZV)eeM76dxX{zj37gx1dyOAJoO3Dky<7t=OP=y!*}sinizxzlKNB|e&&t{z*C=Q zP(L~fZGojI@B4NrH%H0?c z<4pLinRib;-$IRZ1^IoP6q)#!sjU#ygd{`&mWC1lv@>pK9MUKNz=v`;7aEa|r-rOh z4qy;pF_f$(pB{&KR*S*Uw5i4VA_Yudzw>;(OPra!X}hn?)PSM{4s$6iVc*e+n;GzI z1Sv1^_s`4ZHO5epi$Dkf2#|q)#2~U`s41LMgb;M0h50e$VdSB?FKr9%-YtIo3loHc z&Z3yo!w`2+@LUW+{g9dnwk|A#AS+bCwg{O}FtOMihCw7^;S?fC+?_>Dg>EepxjX%( z?WzUuFG_dv3)cPM8fe6zEka0}dJuVqSDU&4Nv3y5Ik&7bcZFmn8jfBC(qBPk-6p5|My~L(m8=1WgD46mJ)n z-z@rKi>MCEN0~JvcZcN4=2dBLCNb3lvT367Af6nlPnb z6gKh5TcfD=%HbnG0m75!Gz4)qjAkw)Q~#ni=51+(f2_P(ZnbHJLQ%EMK=qKAcSW+# z%ejVn$;N?@hB~{(h9bWve*Rd>#u(nlq`B%>MRmgU6@n&B4W|twYTl!2P2&x9Q#+V0 z3PZjyhm_wA^OV>{*5;Yyf>p_aL&`GNJ_J03@Lnc8=l40ajqcBu)H5iljfYoxbV;$9Ya+YNR* z?EaGlbrS4(qu%3U-{Th1<5Ar6cCg2Lx5t;N7dPJ{;*{Y*3uy}I4K3~sAMB0X?Tx1D zixupPQ}26k-}fP+FR8dMd9W{aw~rV!#a4t1)6r$x6Z-Qa`U{Htiw65kcKgdB`Z;&$ zZW9^0!!EPIlA6Y@y5a$&!GWd+T`g3DT7rWegPmRWgNhM@ed?V9W}Q+6>s& zsiSN|9JJJ<9D9LW4x_B*W4sz;{HfL~kz-`uV})E}Ds5wdT%_6M(g8Z-_ZJw&9he?O zj^EQ5mtmifC}EUp8kdW-R!qIF8p*Bh&8>M!m{6wf(9`&8;PBNj@~d&lSJR=d=6heC zP)}M4O+M3@w04-3`~|8-{G*cQ)?ckj49{j`)VXul;2F~;EYB$u)R+N3$)K)`Wu!n; z*ipl?uvI2pkO2&wfQp5P0J)fdz)}xUhR~+z$OWJvgZc=agZoXNFf>i!L`lGYUg4Pz zaF~X~g6c8wBRo|+HBbY;Sj73|Tw9ZnT?Qrb z9dHLMya0Rkt9#^3ZRD%A`^1>L-#DX)M79UXf2LqjU{6|#?N*4i4D=vl*`xxJdsq=k z4W#4Yukhf00Dg0a{;tm&WQBAX164$keMM92ajhSEBV4f5-?V3!CsuE9tWih-6G&=Z zG`I#K262KtJp^fIP_1iMlE+dV49x)u@DYkq84LTZ4KdW&Knbq_F&n0f8&8_^o@#!x zd4>3hhKHfRL{9WvwN|A*M@whZFly6ec*6p|YAN;2+M@E|MYgO&&h5CZ;DIgSSDQxg z?{DFRRh-l^BomljrqU{he8*BiM!z|7Y`&3Vi1gX?;P~$KYWvU}R)vDd5euzYSo!`p zjPNFTHf$Mt^`}vEp&Cfpy6srxSo{y?C{>=D{z%r^mjCj0+%NM|28TEX-JKm!yuaQREDw#kkLH= zbD$P;@H-802?tOJ8mkP1*LEIoSfv$v2$UaE6Au6Ur4e|Q=Z?$s3_J2=$!BZXqi{Sp zTH{?qGw3TdO1 zqyR=85#yY~3d`{42lV$~1+g=Xmp`RFV~YnUPE4F=PO%hP7y|4B3G=iB@|S5Y0K{J@ z5~LA+SvCO1Ak1@C25&P1i&WV#h ze{F7kmf7V`vM$P?YWbE!=v-{d2HaT#s+hg;z^a+>lFUx$GshJjaRm*Yg18CxYeZBP z_E@wm#;Og{Ut0AdJ%%U#&9=eh=92IJ>0!434RE9U{CT=fqGc|UF$^K!ObaA#T+2=I z+xuMj2c-Sr2lVD)E0~cdzm2>s6cz7l0YV4)Sja~pYu8sDw(TTaCXnTm|6USS_e9aT$mc{x^))C+hhLul*48nG*2%=jpzGW|VO9BuwODfUpSP zm|uTePKI`UTRacfUym&0OIzCGhlJ91eTqTyDr23aj|ktD*wpPJ_4PC#T4NwUVFg(x zV%3-;+2`usW~&YmlPlrJ>(rxR2HT!MGP?g_FtQ{`Tu=W7mFu|zxU1x5Ye>Fp^fSFblf6` z|3$*Ct-~sE326C(u;RmF3t9N8rcE|U&h;yXRYUuubPjg@8)JQ|^(z(vQ;AX~f@0MMjuAOorzNVSmtZ--_3KU zRM$Ko{?Po3_9>Md#$U`w7Qy93N+AXHzdf-c@!A*)$c8B0jKYR`pG8W;71A%D+_DrV z2!EFK403a&Diq3+z&x*=LOI+Pew~e*Bic0c+=QtO_V~~b=v{_Lp2-4iD;(7_?N{7K zqe9ORA#yxVy^Wx4jJ!HQP_9tYFT_Y`JQs173JTK*kz?>24MBqes`oF_`%^+0r$2vW z)k>6u{CI9!f8LXc5`lZ^XNy&FuS-v!+}-~gMm<|ge!taPfC2xM?F0zshi;|kZYeSX zOj!P5r|9SI)bRlmT{JA>L4N~o-_I5eAq9C16j{BFOD)#p?T?Lia({=EKtm*c=tNoM zk0CWYRGUk2G?)it()H^(D1p-f^kisaw?gi1Q!J%x{u<)~sSI6?6HP*0=*LE$kXyKy zLk=8wlE?`B9ip=pQO^Y{Q#RE%MeiC9Sv(#8NbV6$lSoVRO9*Q=67el<@}-8G4P7*t znT+e@hWZOtx(}=yFO(i$=)?r+=Ult~Qbog4H$GSY(?1@i`Gsy`_rD&cgQs4~H~l=x zjh9;gc$5%>eEI9PI+33GIYf_A&DvHkmALbzXi%v4$=0C6)1cVKpvZK?*0AZqpghQ+ z_}O(k;~~$-Uvdpf?5yof7cM6EGbl>me6lm&^E7O{YDEtdP=-JKVAu+IT<(9pSpU?- zsFU|`MYy#fi25)TGkuLU;082)pM+W^BnC0x8Z0E6n_T74`97GK7$~*`^BaLU2FqCp zfM8qXTW9|#k)Mdz;ak(rAU{@XL_5zu$pCWw8iS%tfVdzy&?lrF8kdnGs~!{PaAV|V z)@9GDSQ%p;yCKA!$oJ8lD0^Lzi~d}FbaMj@p{@% z`}AE1lbMS1ugFiz0x!N_$Ka^F(4T~f)E64{;0G?n3jagpYQ175bT!B;QN7H|JW}9O zOqs8d!<8LChT<=6G-L_H4z+O#H~+Jmq`AWR3@H~Gicf(WCbVCL06}-vb>ML@pp?xZ z@S}LBD}W>?Xa_`w5;Ytp<9@x|A3_Gp4+1i{S;<5Ky}qjgW1gZ7U<3eiTZ zGiAc!&?YHD-Y?akOK^dD74H9tjj{>BArk_-um8<#86y2W=KGsWlFisAh`DZ*OsDhC z6j$W!mnKsU-|pth6R%rx)9DUgS2YwD8JBVvJG+4E=hVwx^vG)bA|g;O)7!y*8Yuy$;nB=D4sA8Oc?bh482~M==ooC zDWRu_&}T>JH2Fsgnm} z=H}+=>iXu*8z(0xB0NfXZbLBCCTOY<6dqJtSP++{t*xz%jm@)X&(LV}|8hu8O-&6A z4Gjzo^z`(I8mW$s&VQ++DnxfwSxHGrQBm>Hqet@c@^W%=|MH^*NpZrRTLi(I1THQD z69a*khCoUAuNgYd&Q8QhB_$=r#l^+M#Qyb3MMOmY^+|<FDVGZ)hnD2K#STDH!z6=O3%|Ke$q&XBtRc2LJ#i z03=X0K0k83c){2K+zJ((x;z@acJ$p9B9- zwDkACXzAF0LrXhw`2w|Nqfa6{gJpiI!HnbNdQqF=o5pq4;lTX~=(|rK{m6ZX#N`B$AXG zr*+dKBlf?erL#&rvQ+y2g_fSCNl@{_R#99}fG1|3OQ) zw|p!o@ACqnUQFkIqNUp}=`2K7zUSv8T)fOr=|{DC;}$0iivr~c%GU2b3p3lv1xsxk z=G32T@07LP?A&=9XR_T+=E7TKPsY@UZL7p9&h37FVX@p!d%N7TC~WSv=}wxL>&|M8 z$OcQXdPiE(e*La(lCbBq+n4~#b9S`fW7urCqwLhS@lsJ030ryX?JH)ex>@exn7TcV z<5wLBCBX_Gn(+HJWJ+e*2TfPE-{Q%X^pSS86wzkufu!W!JRNi(ZKnZLkKkvkTW{Q) zdRY$!(t9A5f`AJ(4 zWAppjD?OJdYcapK#a_KxJEgpFs)*<)oY@o7hIw4;3=@)|5v?8N6YyDI3CVj!w}#PU zKi~cGS@PWB{gT`HVn<(j{2R=?SR1b- zK)TOoKdHj{Gx1*2miQq~_T55^vQ>R48JdJ?FavVGw+;Rj1;F@8?&#`(nG7a2r0Zg?W5@cNy651Y3BKBSMIy}U3;)hVst16 z5edOA*9X9S|t4foysu;)QxP%T#ao9bp-+2Fcci9|=uJ zD45~s5G(TJMpV5ny+6TJ%nF;v-Xr5%>4;uwCT6 zZWIwM#edI1-?-6Onp6>)ul|X3B}8023&jEI3%Cnu4>Ja2s0r9$;T5N7Lje83+e!%u z`2l-GiX~~pCrVduKJ@Y+im}`b-uk|vSiKY^HNTwHg~S`xv4;&}T}{hp-Qa}6yP{nJ@(`?2iW)y17Eex|_-I0>EBx7b!DNrH_lJ zDpvUU8T<6uAEB0-n|XCh;wQ!7HGl&wpGezHL&-H$J1D)AS)i3Gd;`P zp6-=6t%KVMdzYG|x9&x_k$l;eCzG6B_u&I_wvdO)p524hmOr)CYZ^#pU~)yQca=HRhFW|tJ#E!CKPb}TG%#TH4YN#~1^g??1yZ61i z%$~sLT-pQtDmAWZ2m7#HBXqEo9)3vwn4$6qL=U{c@mGq_U=p8-lZt@uEb2sQHYy-Z zv>^}MxnO>~B&^37iY(|=Yhlw1v-kI)E?Vl}xSvlo3qJlF9v%Gc;82F?5)mky_<%#u zbc=E!29lPF48IF*qnZr~l&RK^R)bnnO&x-R`d7kuk7YR`5XwwHxI(YJXy?#GOa|Z5 za5&Lyc#!Nv6Sgz?o#CKnLUH5P8&Yf_f7xt5Y<=tX`5K8s;>v4C-43xm6@e?ZqhX;*u>=%|1R4K`; zTCRmbMn^E9wE-DUkO`J~kQsqXDfccuOP1+BjJELuU8#rYVvjzpqm1fCSp>LQveJ#&D@TbC6nRC#=lhEvMVtMJ;{4eG-eI;r$Ka)r@WpnE1 z*4LJ3ZvMfyvY8;DQ|8~O%$WGE?Dr}?*j4YSqUqejeE2Q1-TX7{N%BFt+)KhXvi%#6aJXX>{}w7&>@GY zH#jS~O-Q;oVYjD6xCNAPGGE7GB*v513QT!PuGJNO&%#@oB8c6U<}IiF2~|NdwZ;2t!&YjwU(_1c)mp*8I}COF z7@G$}_M8%1~Zswzzx zqkrk1ywN)UqIG$!wb?^sUTzOC1k|1SCT_i5dCc(`O&)ZYZ1XH&*~v@fna_S=tkFBa zuR6irXR*l8U|)9x|NH2pbz>(6y*mta&C9SnETyPys6l58wMtw~Ch2p6l}_4O=;E21 zZtXp`f>=5Jhq8Ta0*UO#RR-oR?|z>d-&T5T6ZqKH8WE0yZvjw|x=0FU9pFV=H5ZvH z!s44)?6Og8*7P&^q=XRC=!QVf#81Y%Q@R>S?*N2Jwt-2WHG)@$#v}ec%s4chJkf%m znN^z{F++1jCE=lmkKxp9rh<|NFitwpdha*$-hbxpS6QqpisBNL5Z0F@WsKg< z|JYx^MGdyAnEfm85xye(j95X_8IOWU_BXfH46P`^h*#!!^OUI%WHu zYkd6GLD2K-XqvZ3gyJC$TIOj@QfdOTWkX#|^Jn0ejgS%EoTQ61IlIEGrx>W)`iqi?A$(^wJoyI9R4+Mp+B-M6?a6j8{ zoQrAjb02LQ@DWui-c!;EOhAEY4zoG&U?vQpV3MQgnWOwMN3}kO3QbB?o}+-qWHWtS3pe<<NgZgcP-e?lkVI z)$9FkxG~Ux6Uic4!TihN`~b21)j%Q8#;cB?_iAGPFKuSdIB zO1n@*+fGBr1N$}~T%1ce34ne^HQ$=IQ^iA7E#}oO@uyvys#D*zEq{lRaFYy(0ljiH z<4);RIBgYVY10@i*Lu(;)!43M)@3uua08>r0{}sInrw7Jia^7iWr}SS&BQX<8>8lD zjVabC-7#uiOJ}J8#Rzn07YPAHrD4=z;gtd%C0)#*Kp%phTmM#a^K<(FJ2N`g<(iuS0F$8#;UA11OjK&6qt`|p%g`j_ z$s$lR9bX13=Lg{zgSrs|b!6e=Z6tdaPlqCRZ6zh8tf;dKCpP8!K>H*!4QRI zogpB{ozbL>8SNl=A^j{o1XD&d*g+$iJ!$|<|Xa&O?Z)5aJv9Nn%SzP-lOG!u#=%a#!&Z1d^KUO ze`v0|x$|{waO^4jB;ODN96?+KAkxgPUPQa->Is3-BecvAb`m`H@$ z8H5apaC*?A899wEZZvM1w(a{$9XaJ;K9oN+1{GSb zJo5=fhuJ3c8Hm#i1rni$*6EmmM%2X$&=9;w^?iu0RWEY~4acfSq^j5c}fV{lzVfg|FU={EMi?BbLujR2yS{$UZNWh_hzc8+aQ07p;9w9hE~Qj77H8@ zmzPV%W@bU=D}4^1nKcK<_AR1Imd{I;&L7R7nn61c=RXSdWZzqknpqV{!>~%Nu?w$r z`Ychr0zlg!5DCfrgSi{~3+W}((topLrO*Vm)<^p*#+vK5E!Qy10H|Ul%h(Ad`1$m0 zt)AwF)PD85p$&&u8`iJBH5vjcnuspSO_$>Nmx~z&&1~*$SrZ5xe)DpQAa-Vl3vb^(~7-WMrhoL7I*O0lh5Bx9X(HM+5KlP{e>Cp4jO}uAYH|^7EhlLH zK(ri5HUh+H5O8KIz0aW#&3+Zf&zIsqwcv+>#Qkb`msKhmLrJni$7Tl$BnBXQzu+D`+~`oKlSaZ!HqD8u{Lqx4_CHNR}7Pn{iq5aDx;^cm2~ zVrbHdTbY^tt&LY@v5L|2U*X4QOTVfgkf@lSfVf&Zuo`-t$2iV?|AVMNt-0XnpMMq) z_#Epx)DR?C+n0NLE&coglLs*JI0XCTO$cWV35?Ms{d{{=(k%MXsR~&;N#1eD_xPC zN@-raM}>LcyQO~r7IMy*C{p8`cL`*dV5NXSCr9wwJ5mMYJ(Ax!ZvaB-*2(0<`k}Zd zo>kBC>;_~+hZZyAtod=h*xWP+aOeQ<##O6wS@P&-nm0GSc82cmR{q{;?+{hrEhHN2 z*C_mRw>A^$d)M%l^dfKg%Wl=j20i4nGQI}A^Ck2Vl4e5ZQwZ-<{+>+Etr?yWVIQ1g z2IuP0I#lV0tb8VvGpABjpp4#DHJA5GdHeUrR)vjeoosaK)1^<_qQrSoFXDaV#K#A| z4BH(E(|i$GV?3dl%}#>=hgrjXe`!gv4+;C?G8uQzobuyrA)eP6`58JZb=7Wl9dirC zuKrLH7a2Spr+&nKS0A8gZHHf{lFQ<>dL1%8@eW@U{$2~fk7qo>({A}Yqe7QSwM)-` z27A(5W`K=cX_b>6k|=kkszmpHF|jLadaaiwkvgtUuTl~=nA*ucWx5DVw?&EZpp@f% z6fCLD7&fd&iL)sgxuj<4484Jl_n3P_9gauISy>@09VuRaExWayf9dQZIHG^epNiWn5GOG(5w}r8BVVp3_;HX@N897B8 zv)Rr1R_4dez_kS1n^CgKn)Qe^MhgN20G@{O3q#|4s~0`jqFW%6yIOXn7=Qv}N$`>RS(gEk7l91(jHz7RZ zGVmsC2gDcTwwm-f1waPa__Sd&lzKB+u#n{=5TKR9tQ_Rq4rI{TBHxR0jjQmrc>Tmd z7QXm`cQ3!4Ot~(#U*B!b0{p4C1_T%R6+$N)UK=cm`XNB1SBIg;VqLT!@nNpL0ARD+ zb3F(jXy%^%RBbzeHjVx|;po$W7bke-y!(`H!ll>krvC!0EW4fIFBy$GdA{P#WZ_bM?rgYineK?2Pak{9K`2w zTX*@pKCzJ-+1YFib-klJx_qwlPd*%PJ(3@O6j5FGL^>$8TTb=$V@ayiYs})Rx{HtE z#c)=|H@^4Xt^OhOve5q-1u+UWjdJmhH}C($s7jMC_Mzp^Api4s{Zl1ldT)7VOrb#5 zP4}0A9m=gju>~>aVFZoD)=ryyYEx>k6336cDLDeh=U3UMW#OLrF=V#l%r9B!xW7`( z-K`SW@@!W~LvelU>-11}<9#C_^jZFj$;2$$G&#EhnJ@m&3r$W^ zt@2ODInt?lT29qt3C$B(kcT&QzPXW+6!W-MPw?vswU3v<81fB&eKN?~)<|@%%tv14 zYRdo}41x**XOs|<){puD+P|KeblI9QzznM~?@QdM^3)=Z?=O1V$F>bFt23*z+aW)~POFb-Kg088U+nUOZ)#G>N3h0% z_+%w@M=vJpXGDeW2F{sag6`Iv{|W_}C4l|30~E^qUh%kyEi61ftv?X5c75~PXzg`P zgWKi4UOb|vjyiyg7D|&cR@5*5POJIw5hfQt$bE6eu<2yz0P9kT6UU2Qb6`>v(ZoI> zebQONVT$p4lp?eoX5aAZkyDs~-5TW>lQ-)G|_%skhjmLW>mB=a0Wys5+S!>|*+rReol0 zFHkM|*VTsCE4M$qnpBya@BS8^^Af)JQcwEc&Vs;ZLX(y2K@wTyw|LQ~Ec+OxJ7PvS zy?hWyB^LMWeBKfkTsJ17BXd>XCFUnLSDE1Ce)^KhH`x#MCQ)YcEI~2>8q?V@K#WXm za5>OMP<~9>;&vimm|apUHJlO!1#{n_5bH@Ae)D)GSd!OT@BW-HrE1mTqILcoq)XZ<(3icSZ{`;Eh3km2>j|b7b|M79jYg3wBf;bZ6oCRvye56!A z9G!NYo}F<`(A@((uMh^OO8sugSU*zH{Oc3>C8WMf;VzU3#Hc;Lz^EkoT7j8_%N<9z z^@6nbk>+cEg%rE67xIh0n%$aD7Y=;My_U(O-P;)#4}+DwRvB8{yYDX^MHAj~Ory!~ zow3tiZwIa4ZSfeEx1dEwD>i^qUB?8J(i&yDntoDay+5!$HygJ&H-|o)PemVkQdkLbtStu#z->yxJ}mxz z5Sw@Fv53P%XbyCGzoy=;#Ln?Efjeo@x#5B~;zd6*-^mA9s!vF$Uxp=(i44f*EQn^g z`Sb5)&;+H@Dp;fz$F~gj5d#_h4!V6vYJ(0kebe$lx8-D~I=nakNdvWEK~l?wDA!tr zZ=zI0fm8sB#7#SZlrXqb;Z{0EWSA5SU>GfxZxgP> zx1-F;LJqMm?g4`H?GjYHpyF&gN-;IM4(LutJhBq;Ac!`io!eQyLlvsU1$J#N#2;0;$#3_{Aa%(Wjt(;o(euPXZfu2w#&$>Td=Jo^|1XmZP&9D zMO*t0`IJytK6@fR^p6O{2-bCF@V4~l3TylBH(vSAy?E3*J54&fe$6QaBytL(uzrbt zNnAOY#_s#s?XMMjeB&Rv42Hf~SCa4SR(DoPS`J~l8A6|bon(!|Xx>y#rVXrW#m6e~h<@Ik{<1Fvr zK0)Hw3s~asK;5B5#{<-6Du!PMdLm$re>zOPl;A1qAvZd3G95n1AUc)7W;6Bo>WZWO zgJXiQzT!dt;=Z6{6&&`u@s*GYrq0|mwKzayPQ7~6th!!QBSK+_kZYy7ynE+!JoL=7q)h}$WQ=@xAqg1qKQE+G}MR`Dd$lt6#SVpbNO6|_BN+r**=aJHPo)LJMrjTlX z^q^*cvF1)Ew2ci)35`Y@b!-$5g=-Ifi!VJA9Qn%w-8R#bY8eA1~&X#h3i#^IPKt;$Qtt+m5@M<9DWnGZ%_E`1c#BP;q^ z)Gng|s9{{9>ITm!ErSmEry;se1M~(uSgTP+hfyYLEh;kX9vBGrVm$bwbx1!}?Wvg% zkLRrFKsISJ3F!(BJqpEY0XGKEi$++#jy&S0injQuPiY!-5QC z0XKdKrgPHB<#E{hV~^CStl}vu_6a}gsb4ASf*35JUOWilFlFze77^Kdne#Q^vOlnE zs&QgKSLku5HZHG-)vCAW-StV_#x%#T>1g(^T3KB|krU=shJUsd_**&Of1M(^oMG9S zPBfTKV!!#W$;gj-LUxbjO(APEg~{u#@shA9y*nmZ-uGi7O;Uzt1{#fV(EImsvn3m| zF`s4?yJmeSW?wVR6p)!zGK7?&)UC>OsvS%}SXVyNm}6*~Eh!}0K{I7!^L!d{CK5sK z1Ls=Vr^X9s{kO30J9AC!U#i$=61wIZn&$nrv6A^*&&sDe+0BA4^#icv1_*!hmnwbN zh5B9QY|Kr9y^R1QxQ!d4WoqWMH+w%N^g#w0;VnK$1(QLhV*b@!aMId%P{U+E!y@3! zKZzOQ8fh-${rHB1S%5oEIWg#MIoZQAx~g!q)xg_pL-RFNrawx|{L8U<3=mp(^J#0N zqxDdw400c_VD%RqYfKi0kpf5N7VGSf34sOyl+ot{eJ6L9zXv`^!IG%d2DxJbZvz3g z=!AFLG$$CEvlyBS1oU?+%_T9P6a#k14|XaK;JX~wrwHk!*a5>ArK{_CS-Z=JNH;75-f8;ENdSvFdfTr9*d-f>a_;lJtMg_ z-FE%uJ8Fr3hM=yi@MSNdCsRXJ^oTivWk$N^pe6fNGk>N9e+;?)8L59QR;@KevX9P( zHbm+?PR1!*mOuVlZ7??qszj15eDc)#(t^utWy`=!DN2}>DS$-+B8QHsY+nI2FBrcM z{oMsKonbUzVdyx2k7iDgjt#Jn33zoFr2hhE<8gJkB5`UwQQ`0EBTeZI>SrRa%wyz8 zT~eial;2PHuiu+o50*3vz>_PpK^gJn@vV&B=SenyKVX>?{br=}GlFf1k2FVt!J$mJ z#KbTzXu}SRX_^8`Q$J^KNwGPK4H}pv5+o~wz4Y_9Fk2HT9ln1L>Vvky#o#;=8PblJ zePACmX+yHaKjs*-5R=2cNKyiB%g+~SRYd!|mh-hHvW_jl@uJBtp~@}*B9`X zDTMMY7&^g*i?I&qeG=t*!=+jeuy}5+2%|-TW6P6i=>d^KQeN-x&xXwvB0^tnL3{x6 zs{J5)e4zbj=n5Cdnk>hLCC4U?1DBY#E$;98;t?=S8nT~uKpUbgYgL#aTePSj`BkZ; zdAp<+kk9ARpcpl8yfgoB$6NE8|6!ovA`GyFkg!OCnD&A(oW@qe%thS|Zz@_z4+c$wMDzi<-o< zfS${M%Wnsl_Z~)n+g~M1wdRFBzb6uNZ|79V@pv*6z<@f|2W4;M$GL0Vu6F#XiH<)c z3qA^jpB};qjtuZazBMXeUMP1=!jU58na$DFp2JiuDO#9V64Z(`0zQaqQu;b2?%S&; zZPWG$lO+WjBVC5H;x0rUy@ZLF{vx`6^z~?+Bjif$ z{t3dV_RNWZBgb@ zhPN1@W*D&FivUxo(;b4;aBV=(UM@om2IA(VdMkAC#8w9}U1$%Y0BF@IoP{^-Ie0@{ z#7O;6q%KCzinksP*J6KHktk2giU-?ErvEISto*efe15I7xHn&{byLXk`TG8mUq~oEFKZFzFTenbU@9HN9!~N|I3FdP$N3zP06n~ zN2_3RK-itk&K+XFM7lzTiM+)>oEW5(LE^T|aq9-TkMH?AX-|=_q4by!C&Dm?h!*>) z6Z7{Ty+iJ42SUTsptty7ST5KMRXjgE*H1wM56i)7 zc>nfLw_?ZYu@Iavh7E zUtojWTZ3A=-J61I<`g~Oab5;$0rH4qX2#R-+9QP1l#{Rb^oKukgL)~oWM+T^fw7g$ zwD&DO-7GmVFj?%!N_t>9-zA&DtSTe4bLp4P@|%dn^!v-$>5=L6bmw4cSHEde_bu-w z={wolWTf^#j||DyIRE@)c>5|kWL(SpKGH7EnkqlrM>E}fHv0VOEth@f5R_5y{^{RC zvJhV`06|1ck?jE#j8}4w4j>&NSNJ%*@ZU(fB3NimI%|)zyQ7dws`Pat3ZIZF zc;Kp}E|BQ_avVLBEb(UBxi2nDo<+jg0CWcpFxeJ)-dg`=w4XpC*y^TTg}J_d{l+w3PL`= zw!dc^v^yH+$METu+Mg2}{JKqYJGbRE<2+~**3L^twASWwSHYvY-!RUDC`I0}v zlhINR#+3CArHuOO&;HsTJL&BcsbmpiyK$PVHdRo&>H;Fw&IlLj7rPeumtkud0ij-j z`_o;VW&6{9iqVzMG-{oIyqRtTXF3seb0^Om3wI+-CaAX4;V~a1_B!0%-3zMsk(4uXf=M&+<3;j{wXU` z;^Ib5xGJQT=Vu}*6q(z3r|+X|MI$Y;FafgRT|CrY{0|F^}^@YW1 zL+*+5HH|DP7_OTPph8^Bj%9f(SlOvb0dNi!e;&T=Wp(#s{#O$LE;;^~taq_G8i-(a z6^xaD<9dRCKnil@V+{Fh;*nYztPW2peF2bQZ>Bld*;ig({4RUl_4-js9vSO{87*Zh zz0Fiz70Vt5NJRMlV?Vg!09M;ItHq8-% z>gG}0>K3`AiYwF?oYo1Z@csJWeU}cy&_t+GK)EOx^p~s#8AngJwzw%Ea~qIp^?yBJ z{`S&E|CSxYogw-jmMuKv$n#9q>=4v@FlM?UKu+n@>U7~HYh;By;p~!zmwXf*brtMg zjF%LDx)&&6=6@-+9;?Q4@@2u?^xmw^)b=QB?&Mjor`{t=rK=PZC2o4|2LTdeUW9DX zaq^8LEvYI(hn5r-k29s;!5<7DSRp1Xe$*we>5+F^pyh#&_eObnszC`lm|Y;g%X9Ig zBRofOhvgVYw<39@E}(g1o!9}Hpc}Zm0TyXIIvSus5wexq?9T`FY@^?A-*XXtB;uUQ zRd@qQ=^8>Rf3ZooYaRWT`6x{eo)>e)i1cdBbO2TS`^s~ta{m}V9b~>Nji)*Y@!k&c z^Z0}K0TuW2RxGta0-9V*8HuB63?*f(l|HI1)uxSI&W_n^2wdco7lU0D%HlB|E9)G|iK zc`bBk&a%5(S@D4;8EMHm8%Z%KT~fS4G!N{WGNO()a)IZ{$a2peBrS-!WHd6NaovhS zA$pbG3VK|gO_A;1({F_~?PUT#KFs%wzfxjT`WWOY2}CJ zK~-F#4$R-kk0m3Xn9#3o@5@0lxyUKp=JWFtnhbgmkAF&Wo%DaOb{Aezy=~v{H#5XA z1I*A3Lr4kIT{Dz)C?F~w5&{AO(hdx%bV)aYfOJVHB_$~xN=XU`3ewEW^}Fu-UQfNx z^So=l`(N0z&Ncgc9>@2C&cxs`oMV;*yLm_6Q>nwx`olau+~M*}qK0R%VvC#^xHXC` z6%fMsFN>0^hWF&KuGp*5%~9TbrZXM-5J>gi+)9VLJT!MxwKp9Pi_~AG|0P8v@Jc@( znx({i5KlnDuGDDoiXz7z-R0{Y-p~2NPVnN$Ua|0lWO^f6+`^)|z_WL+Q9dXv$rZ0Y zM_p&k4<&@oY>2?ealDW$5Yv+z;4qc#-lg3{_OBr*aKRRx8fqX>Pt2p;sX38h{+wNM z3W8J2!i$O@iF|_&ylo1rum2Ff3?|R(hh4J~0?8dL{>Vu3Ydpg6=*gnliXEf3%Uw+a z5qx{TdI9D#(^ERBwRTfnuUr#*89q=~=GZv|?-a+4C;nwjmqMw89>D*kuds6Q^h;*> zAfQ9X5FA|>*rR;m+waDvk5>Y2{;z{2ERoH<@^?IZWfxbunm&wB-*L~q{cUNrg0+w? z*!7L9*^gR7GNfCjchhb2WZP71HO;-7MEak;*v! zRq~|f9xjE$Nb(gW`MlX4pEOdINBnE_6V1I6ABAJZDx!sXqq!!&OewF^3N=8v5Oqu1}-h>yVUt{iF7U-HD2bU+8ySxE0F(DNX zjFB$RCCIFPLZD43Hk4$UYR$ycVvZQY4)LDg*{!$A*GWOU-HxYxt(ln0`2{z)@1FkP z+flihwW8*=^o*oNu;Miuo=rc$*v~h{u)`K(Sj5h7WC8{l#)U((3Ycvo@j9>snEL^R zB<7ZcqHoWg^*FqZ7tPg6mC5HG7#RaD8xxI>U5p%CTe#VntcU}5T;E2re>+9~?!O=? zWOcKqsax*pf{R#v$|eSw%}A5C;QmT7jL16;4Cy&_Gr5z!E&rhZ zp=gN8t;*o2T5A1@`$6%PoNL}E!&TF9DPGxBH0gSJGe+#LdlNd|V2^5Lc-HlHjOb;s z9G3>urb(Y!s_ZT+F?Q)Pho3I0lX@sEIO)VMrFKGo-s_E~mvW7F;|Y#a&p+dm{l37% zXOc`iFIWe-ypA+J!i^4CeU+AVo>h1Za!?;Nzu|Bl*Nw<+xBhFmt4U$0lfApVRhf9v zH$<_r(F=P!LNl|1v{9@9noA>x=|*+^V4YgRW$mL>l5_c@i% z#1O1;a5iYZ=QL%BWYu!RafL=^<^68n{V^l6Zz;bCR#bp|`ozbBB$!(rV8w%OIV6Nq zfertwm7Xn1lj;#|q6%Qjw85KA`#X-*JdUh#NiCAbF(%b9p9T}1y=;bA60&9}Bmbm= zqQs!}vh|U_5wyLA_c=Rwh6qM|*fr?BFyfwo$ zz_4F%dA!=;Hoqp#A|28bhE(q6L)8Hd7m5Tz`B?*h9 z%!`c*>{KEDEy6&%vTq;vua=9rHS`~1*Z>+1A{@B#FQ}HnpkFxhsu)kN9tGmnU zb-v`KYprkze(cU|aLozi6gx0*Ifke}v-)^0*$!0k70}Z!EA5|aa@ncfB+~Z8BPH}? zm?Z>W(0pW&@#hz6Z(q(2-8DgJLb@Nfa4DB2YWbFiOc$$!=YAXBP(kFAv*%N2Iv^S` zOOVAdnHy)lC!FO;L|KU%osDobdlVlolqN7GPKn!x;R#j*pRt9FX)xb1X#MWFO{_v+ zY#Hoj8S;&{qmn+Oh&G--S172bN87D5vB1%vCS2!9=q>942EQlB%WgSS-qa^NMn?`I z*IQ{K_!K{)*??`Oegsq2R?b_;#7ak#`t9Wv-s`z8MK^5rPHCZLSWW>??wu`_>S8bQ zE$cfyM{WjI>^u2yQ8{N27w@ zadN(8?=AE2*WC%w=hR;QAyA=;TNzLN+gE%&O|!uiV`Wq3dtWlBhn)!e)Jc{2K{ALQ zq9QPtN(TX^OZP!9&ZeyYF; z0*>~U2rKu(f&E0gm1`_#*Dt&NsxI*=Uym#T^%YDkAE06<3;k6=R!wqW;K-cdG!lN6 zrUw!07PQ1+&~hN@Eo*QGc9$ji)Feb!3Js$Z_)38<%D>mk=Q{hLOL3POY7-9q!!+>7 zxSXCtxc>3GJDa4GZVa2%bNdIz0on*XWdvYKvK31{*3HX=rmRW-a%(|_~Msor1FM%*JkK? zv^5Hsv5Q=3fcAdW(*CM7_$xwIcl!^jQpl2=d2oy`uvQS~u|{(cB>m?Px?8b1MC@m+ zv>r~CbE!%yZX3;lJ?yn9^&W5c6OpobjuzYAF{t}+MoM2PY8N1UI4-F8=h?Snj49%I zi#BEvslTx!Dsua1L*kEq5JsOu>?I%;_vp{Mv1cMhMV78k{mTW&W;b zh^V7lM~&=OW#(ZLBemqX#qTw_X}@`{ZhphNQX1MP>h|%$-Z=A+qco#IGdpT5%@Nc- zWk#E#s+-5EUydH((&R6d_1-o-Qa>)ZcWlmmWCd!Vf1u4aWJmY1?5agv`efE(6!(Dg zbQp$^u%+`BW0#Q7JNo+rW9lGoQUQoJG|=7k_SiYN_sd%J5-jEBZEw-|E!bP+r*S@!~3**-Ho>N-i4QJ#JBrLTrPJTZtjI#A0KHgM7Ki4P2`4{-GI%o29sZ+ znJtGz@+Xg(2Nk!hpC^UczqInaU;ARgoD@Ia@ww`k)y`M7r4A8|u0MZ1Em@J7J@Tb( z^ck&k(vtA`f#x9upJsnP#r}MHTw!gh(FUI_W1xIg9=dD|``-J;YL;+D4-Q>7$3$lf2i9D&KKZv70AD zwatY^F9h?0!$waHksqE_NNP7V8Plx^xrshxa&!Sc1X4=-zphuj`zpyIQRY(FK}gyp z^i1}}iKi9;MH#RDlfu8S7v9vP%Mg8l-+v*P*tn~;?PryPq zn0%4g_T*EWIcay8ZxL%#&c!m&)2%4gotx_$!zxz9*kl1Tu=2EwQy&*TJH4+dQySM` zN7PagRvhRmlSjl|R=#GN1q8rXwZdWV0%an~&#UhHl@nQk54sg6Ln=mFUXb}&pBx#} z*$5e8NEx0}Yp=fp`Cj&nMhAa2kIs#HKDa$q`0=#;`?I!c(NMwUk6VgMfLpiX zB6dIR+NfE6qE+nYAtx_!zf%Cz<%J{+g~k$* za~U?rTPa7t+0>Gy60B8U(+WRvrdzdu#IQPEwjL(fb`rU;By;+T6l+Fd&&j`F;)}Jy zZtu*_9ag^`j+PI6gwIgFs$W16qeh~!=5W6Rkn#(VNx?Z8g@3uue`=ZX^g)$H=bdN< z8dQIREh!g4`Sf;_^%dbQ+s7VVjI#GY2P#p2mlrF8aQo{w-Ira(SaMpX%rs#e6o^PH zRW99Q=CkE6`yErSIvwS!P`3EnQl%I^?`nR`Y&zf1l1hstHCXHN%Aked()5*QTnBw? zFcIw?;ij1(tm92Pk8od2(0!^q5otXmOjP8>M8mGnWnawMCM~dB*Pr_Qp~;2}dFBLO zEUbTE*<3KYbrn@`p76*)kxe&S{S#QQqk)jKy7&z0sV;Zo91_<_1a}I~efeD)(FGGO z8tg3lktxvG!5;v96%>!Q{sb2;`&rpmt(BfJB&|o)HS91u0oYYE0>&i<|j|>A9nQXoe5qguy}pN%QTOq=2#}?U(~_p zk(2kdR-83;!Q%HP+3`cS`{KiGkDisNY*$R&-!rxopQ5Fv{_{0dBs+y)5Wlu(+N`f4 zrBvsWk|(o+@zmO`+e2rXY971m{$?h?Hm)%#{@;>6{k_g$DzU ziR$s)vA0@|=D91+3>hsld9D2(RJ_mWhX=RJmF>4v7Cz>9U#=SaBUHub3u%GkBLF5_ z!GqlEnN=8f2_mAEnNEWJ&HNRPB;U#ykc69Y3=4zW8U|$vv-3xll;sM6qH1s~v8I~5 zS2MX`pjys)V~XcETtpS=d_?%&r!vR__lR>b$$1Cg=3IKwE84HRkc`?pV)3ti!%VyP zcVSv7-(^N}2l}!&y-#I_Yv$%|zgQJ_>MTu|7&)jtcC2hq*GAj@H&Q4*y4O5=o`6v2 zU@uf4NQ`)#=AMiD{vw$Q1(&(jG^jhM{e)9RV6w{8e?3v{XlY-*i!+%38O&0V6CUs* zJoEK79w=TIahe;Q&;D)hLo@q90%8VD!T0GBIJCD|1t6>BfwfAJX|7sQOf)+=wC&t9 z0#F7HbYPa$XEMKoFbcet;^b2i1;`K9yQo$A*Z3-Ha`6$5FV#sJOcIzc`5jDt?}znzTi#gbT3g53LHIQ(>VW&#g(>*~)^*9k;e5+vo1G$O(9Jfwugvk1PZ zf}=`9a_X^8GEJYytWU!S-9;FDzfu=VUOGj zQ%S4}T4WwlNc9@9^Oc1Fy6M_?yxnyNpRNNIQEKLp9%|yYbxDrZCUcM_@FQLYt%-`$ zq<@|?mHbu>%B^asQxyL0;bR)*vk}Xc=YEuDHbq@hm1OY=@MSRvsXFNdchCx}sZhTl zDgglv#T5KAju&qbdVgWld{6}TuDZTZtJWy!u z$1?Y`_Ql@HtZ(Zn@8Is|kr@?n-r6yc4=$OB)F-iA6+~^NhSArEU>pgf5i{ z34=f1rU)SxfvS+Z2>pCGo?+ZjneyJn>*wPYh6f);QYu|$!AAkjZuaK-L!b38_q zPO{YMF!5b0@=TLPzJhn({B|le0n*^HuCf$6h%u~os*>hMIYqGpg#VR65xdd5!YfC| zs6iR%0aXKw86Izn<$OV{VWaX*U(J2L$BPAqO|7J51}_FDpUQ~mLrJg-_`jh?4^ux7 zcJc#sJ7XcJ$+*2NE^e(5QQwU*wxQZ?(Uk7dAnP|7Go;II%#Rn>X`F-h<11aWvPGJJ>{xK7RGnr9`G}+_+Me! z8+dozR#+33Lr4K3V(*F-;(FvpkP*F9B4?hNJH3#yrG12yTLo`IlIbg>Hp`b1G+jre zX3rjN48tU69Bt`-DjK6lw3D$cZO9O=Gc9vodwe~r?n33#`w`U0q|S2f1G(0U_?I$# zUCz*MY5YW}3K@O3g2JHi@$q^<5GRn&FqJ~TDk^)B7v+&t7mK&2OC(q^q*8|B@1G@* zsQWNBTf47tC1)P3&8FAiRi~scL?o-S;+c?I?@PeEb?bMtqiawG{ckpeE575nvg;9g z+0^E6zv3qUYxz@5zN+1K?2BC|5HEVK;c&lv7u<^E;CR%&^?;Fc8q!;%tmYXlfBXwc zphmhU^X;htj=`)`ZLXS{24Cb}cjUkmv1aDKTdomjY=xM6e-RXGQl`Rv3+9rozE|jb zqom)~_d zLT(`^{!ey3Hdk>|yb6j|!V-;(<}ybAPWmFZVZPY(OWpN0J?b~>-$+b&*69ON>qPfD~HIn4flQv+y`DA`H8Ya1ZuS=tTOZQ*098UMQbWKK>>~#@&`fF%Dr`5Z3S=tJ`kHH{E5dp-47oG&OXU+PM>%fk(|0zu&7$ zvX4eWxqW>GlD-ZV-#3w1w6p^07-+#3|$3(#iL|j z2BB6MUiBeUJ1LjI@NNJBB$H8`3goH!E!PT}5dJU}qB6UFDRoEBGU z@)FePT-e5d!SFSTLU?I@YHu~tbeU126Pabnc!XxH#_K_Zz<2VAp&7EoX?LKuk+7Tc^8ABKl0t%aA%wUgH0UfA^gA9mdU}#*kH-e02VmT21EmfU9I~V@Tvg|+acXm0s%OYPoaa@^DA*q zJ~e|7e#Q!|&@z%Gn2DkkZ#kcO0AOLlW5bLg(}E#_<($JDgaMuHLk^r89yFOZee}Y& ztoRL0qdB=O-K$Y>o*EY(vg7k{y7UceqpT ziVzM8+`L|jXn>Ngn&X8Xz!RKTPw{8jfC9H~p)mGUq3dSkm=pyZOp0)2lZxF=I;O+6 zMDO;Gtlr3%%+vX_x(?K_yR;oUh$*iZc%nkD|A5vJLH2s)uY5RqL0w+2N9-6=rK%m#me8jNs!B=)cYf3d>(6&4#&|@ za=VWDfD%Ci{*}-~w_Seym+;!#*H7DXU*OO$7bg9Hb2t2HbUnK~I9^KWe7dR8s zTN}}f!YAo>pr1_EhaKxJImrc+I=(Z#ultEg`*S0bIdIUOiKowD!6HS?!T)xBiCi0f`nvWFkv`ABX0r9ty` zorMJ&GX_d}xr z(0BH2E_RD@z?y^R;ca8PffPN#RGnl`8@tpq8HsNQam%^}lMXd8o-SJh2|M0KyXSv( zuBJ>AsGf*=KS^n1ucjtnN~UUyWA{XI7cJWd(^$GsJ4Q(uj6St|^Y`glfn&q51>AZi z-fEuH+UfXsG{oDwCe_^Ruc>h3lg=Bol#$c%&Eb<3342BCI#&o$5Et~(@kDs4bHlV- z-?T&fv@87#Uyt|GIvPNs{(z;6D2VW0r?#~uLhr^s6^*6HSz#Utra7lH+ir9>IALd@ zbvLLT^gdz(p;S_k_v|C>WSiVxr#>a{X7fPb)M~?=R~VICUGF#f&~JHat=jCB#x3qm zGlc+U{bY&DpPgSkPx10)t0%BnX6@OE6!{)4o%Weg$m=z?lLizvToV}BDm;X^OF zPc?5vLO8+r^G!6KwB#ox-zJlcvS@qC5I|((4i)nCW^+Wt>8pek$Jkv~{7!$cbP{z} z)Grf)%ol7l$iO6wH?dUc=i>xsX;X`7ZENGCyNOA9zJr4^E2*D5@S6h-KE!jJt#Cbb zO_+{0n{&1DwJWK3NgYD)m5dBmP4osvm-zf)qS4%&hjU@rbhU_w4zyJly|qXXlGtMv zT5;3c&G_@vf&*7g$&^qF5ChCe*XlAYt4c$nRnmYq(& za{d>oZ|S~;AyR+%CO7>}rgVyqZ;F3d#udF3UPi3_9bjJ74}>8S(@D=Y$vvUJaYSPA z!oxTi(zyMe+@4P#c&ZX@#l>lvQ;v*{noEA#@?e3!=;CNWU#3{nyO`N8gTa^pQAHMD z>1H$ccJE=yGnwF}uSHQsDS>{s|Io%HWxPgU4w8}F-!0RJeTy_&-esScO~A_{RLV*i z9S<&P;l~X>Gb&%m7LCs}ShPmn%20UkS62=qSe_@_?~oq*Q~$6f zpG~&r;bZq;+2#ws=B3(ZuM1u-0kzRemh zvBP;6Ls|)T%9d=Jl5MAc{OO{#W$2OmSWEl*&vva3d^8Wr zDf5MN7cbN2EB}_W^v{p8+%2-=N|k!|Fum{pa_&;++%j#Q4v|Q@|QLU+nR3>naTBD!J?`H|-Y>*pgagt8eQ)QHDcCBL?J#d;_w^TV-S~hF;1H z6F(f(C>VZkd6y)}S)Hpk+4iD8rgP|&x%7A4xmW## z+3YM?^VC;UlJX5FjH8a(3-6~E=KfB02YwM$Y73T%{3Q3yUv{DDs%d!fn@iyPTkbQ0 z1s9qt-!-UKZW*o6eqS8@HqRzgHo>$Ehkh4O|E?IYDBNX!hFPH&Te&?of04b!ab3Zk zv)VbZO8kHgqQG(PeedvUjNI%;)8nF-mrDlM-!#lxr&`xV+3_Io4Yc`4IrA*mtWL|k zLr-DTMPvQxoAphzHI0Hne$}T z(aV`%Gb{%e=D%?tBO1RQSUi+s?quBRq}Sznwi1451S*yQHam>dNFPZIxz-=>J#^W5LiBvY-tzKNP-*<@NTb z>pk4{p(1YE0-w-oYD(b;9thJBj1OawiyT|NSMSMa#137JvVFlr2)jEZ->(Vg_cH%mW(9xn++!4^p1AujzI50f{*$?vB5KB z0-@q%lkW`kD+8+bSjw09eo(={fY1h7gD@tRw#*4Hv6=Gz( z9Oa+yM+TD0N(ig?87_Q`k!{-l*5-e4{hw&*$$N)_Y6;=`gOirncX@pfLL5t^ zWeD_6za^F<`Pk43w0~>LLyUsl)SE#;ZlIE05-`>; zLk{U7mH@R|e?blBb=hhe>S{U`rK_@Ks5=3511MeR!Z?N5 zS>)KAc<5x0;$6Tpjuk9z9gDuprb^K;XCCd|%fQ{}V!c+Nb*G;_F5u3<&RfRuwv>NO ze}c9j6^l0Odj^YE1mLOhPniOkPVlWZw{G}dQ+@kfjTZN>nu5bes?5KRYRcKPTz(JS ze-quH%6C7tPw_0^3a)r21auG$9e7lsUZp+9pvZeBh=4w>R_D4=DAoI(YokTar664P z(S(d@w)oA4NUVtMAy;FwZj5YD^J;=({jn{pRPYDN(fV3j$T03Q1P>h-FN#5tcC5MO zQ@IrI0MTSUL!A&}GM~N1C0*993FNL`Q;`v?~-4pRLZ~-?oJ;Q~IN4(?p#R&1$Z_)`5%fV$v_{^s%4U^88sMC=uaq z*aPTH$bNt6y76bvfcv9wX~p=6p?iI5dr(REAvbbK>bslv~G9Dk7ZxmN~2`?suCx%V#9hUr6fz!^J*Jg$Ow<>=b^uM%Ol#FZj+~94kQwP z&vcbTPpX8fODG|0_eU{JdZOBQ;l$($PEJKBjm%SFuJQn4!~_Jb@8^+PZy3$5$3DpV zwl<=Of1NJVVer2BS7fN%D%aDfA=^8fsmK94X6$yqg>FrB2h#@9inqsx?|J58eX#`f znzqK@dnv6yZi(IX)isNq$YSK>+E1Gs_8I&WoKS<-cfgDW>^#rC+$~YW4U97KtP%nO zH&ePTdchP_`6Mn5D59OQND0GyiuYS+UZ?Tszc|W5hCK%b=^cZZkmP)eQ=(2|laRzy z`(l2VcUl(EiL^n_w_@+#={$Qik+tJlBDeQW?{9-C2|CkUCY}`M z*r}L-xEIH_4)NXFGQZe)5QZmF_>#Fo74~#Cl3k*P%#7cLe8(hoei;_{Xa&zfA5_q2 zsGG4@p)37!ZtN>neSv_0w#L)>$$g#TvTu&W4r3An9hA4~2|T>9@~Hh&X4ZX!(G>pi1cw&@G`x#0nC`!lmW?-!aY z$NN6ThUR?5O~{|O)cwEtn`gG2gwbRU1rT^FUDO(UN`EDod^&xRwJ zy0>o0G63;6Q96;ww)V3OWJnsJ{D}LjU!nGLF&bVOGmASK4;X-&X|WQ5#OyuKyECh7 zdR3zpPL_8c&EE96-60V`FwQEmY#ylC;R)^B%Y7vL(cG)rLI?5G#vfJ%>65F>cW_IZ zpKMmf@{ItY;%VKKaVyI56yx~%?Uo`R5Gs_7mam_AT1xXiBDZ_AOlpK#A+m>b+43cj zi7#5hfBE3sj#U%OTQUMk4tE*r^I^0NF-z=?am;x0Z$%v1d%_9Ym;4LvvP4->*^SBV>m?&?Z~}BO~gx zP;t%TT${7P+cq8wV0W=jMupMpKly@z?2ATPn1O$@7~CSgD2*jN|2Ykm^p~^oW2jDV=~k zlCwm}{(+a-X_yrR@RvdaK_WwZc(N!UGf1*(H}>Zoh`}y?S@(#9(g->pM5;Otar58Z z4$R-B#DCM8m~SE(LlosJ6;(PL@e%^ixskd6z-%hJQS`H^hFHQIeG3{}6HX0~emx0PP$zEHm+|tkKK6+_<3Yd=NUO&{C?2=*XhtIR7C%ahL?q3WQ-G0VGWP7end*5Vm1R zBUVKrg+jcJakuFcC?6)!rr#{aM&Kxf!1sk}!D6rS6A^Pba<#KW;V7thq)RCxsr?jg zE}00nO5}M*d4C|$I4Zg4ZHj^vV&yp@h&=U{Z=yywv9^~pAOv2}$Hw5rX4Ej1ER%X3 z)A6r~+?S&N+d%@hf({GO2O`J<5AZR0WPhZ>-KXQgc=4ctRAvL%*g?1(oxQm}8MZf` zYa=b5H$8cqV0>BpgBz?_2ysgY-+CB z7)UvQKO+VN^Wf$uNdO{6_Av7uZ&pP*yplK*#Fkl4OnP!pR5D3ac0yF2J~_%DyK|d+ z_FXnmO}Ma(2dYUii^8)Y23qGbC(qJ4-ev4Q#AW@W&+TkZzX8cog%GFGZy5i8)H?D= z2lI5f!1Eo@nv~GfeAY`eeF=h0QJ>!IkN6ov!iIx>srpTf5LpsASsgbb^&mJN9sVRT ze4vC<`UI#)lHNhw{Dz6G!4l`oq}-_m;LZYk0}!~+pYTwEjFR;HK>U1JJRK8L(G(p; zUUYlDKottyeT2|}0#R;q8$z6UH!VHt#e7genIThc-XFiS_$lS%XOxoGns4p+iXN1` z1pufVwBY;z1_(ue_K7x_FTP(!Y2^3TJEQnRY6UfP_25WHzGGE3LThp2Tze3`ER zA6AsS4I+Us4-E#FPZUV!zXv+r4?0z<;k^fhWS)AzCmU zAWSVG9|s}(7|R*W&{s8;d-GKr(CT!KY9_wyjWJ?^{OZd4p{XsTZ9?E-O7PV*Z!QI2 zk~?%yh!Cljno<)Re@JkmPpq^|bchU3sDZBLx%*+rXfNnkItWY;;0YZB_@czS)r5K| z7~dN@1z5e(Q!rc~wo;8FK>oCq?W{-3))N?H-14rIZmk2=5ZMCwF3Y5~NCXN+Y;Fm* z(ueIVmlt@yG?^h*L-@svH%R8y$uTzCJZ`klY<#-V_)!x!g&@?mgiVhj=IZ3Xt;I;W zH~GREt+g7TzyOExM(3Z603iQWS$-NTKi@6?-KI(Eb&~}Q@R$8S6zuY5hS|Z5EStN@ z)89Ypu=(xlmcXZo*$w>7F(~q9dClXdMh=K30sXh%0t8~=SE8<8#%tqi2q#hSnX%^B zL%h5LQmsZ}qXoLl=VC9V?AKB7w&k#>&i33IXvDapZ64kFPx>|~#A7Y%DgXAx_;%1C zWW^G`lt+y4!@)Kz;Va9~&zgux9;c#S(l42GzhAfOdVe}={RCnIUtN5{Grje$gKS3# z_S^%NlhHBV+VS`Gr}HnLu3;S@5)?=UHPqY5Ecfa7cGXRU^x-E~!VUHtL-yUcoA7Z7kTkUO+)=-bmZjTeBLZ?#LNu)p|Gw;8?=4pH#37=SXix|~io)Sr9FQDfV9#11Gbs41 z<=bffFLl~q=B$ZlFoY;1oCf}pHSG~yCA>pKED#UH8z7z(LS$NcRaV24tw;%j z`<1d-Bl01jaUvY5GHFa^LBB3_tZdzRj3{O-HbLm1W9+~Zu8M}02@Mz%k-iZ^xLCq7 z_z)-jxo4MfJMp);rz*UmQ1oplPUQt*cz-^HD;sW?w_lBok_NIYq;%x*3Jw^~G6sKqj&qm!8kdxuun9VGQR1lCs zZA1_NH(drnXogjEI_zU6fojO_1Bl82eiVZESA%;VaOc1O3wXLZ{fj&O58w%R!#n-` zdwhI+13X7bCIP zU0v6Wjkuo2xK9SSb`@NUJg!*+SI38|;rROX>;FJIefjd`Mt2$*80hQky8)hhdU`rL zJ8yue_V)JH*47)~=|*>|tE;Q2skyF}`IqigUXCkQ!BtS>$`H7Bu>Yi;@NRS`ToG_w z!qNIZ^?w08ESOQ$Nw^(-n@B}l9G~?l$4N=aAQ10 zM@L6RMg5oY6cQ4G!C?M(#*>p1&gK#Bp)pSXE>2aY*2?PN%#*#n{r{WvWN2vk|ABdu zk-&)x;{^C|9BepxS{wyA?&j(QN{k~Qz=1%Q6ci6-Wd3LANk~ZO-`LatU(ypC4ksfc zBOxJy!C+7*^nYfa{=;~}!@B{VYJh(|5Zr$YJlQV)-vCeDu>S;}xc)DIC%(yl15XqG zXW;4QKfu$~{{TGI{sTP0{{=kJd~1$=C~6;{F8T7B?jPVuwm`StUHobEe*sUouE(nf zTbq6@bzotvx^2zwMOdvxn#*6kzdPWwaz12cGRL3BODs+@17&CSzc+>8;1Vo%T}xuHbw z`<3-u}PSi-H30ao_Sc{k~zBAIVj=RdB+r$(jZt zMJkgg8#`_P8+g)m%kO!c7tY65njPf#js&c7%AKRK@$N@bc^PiUNn1kX{7qrw#=pj1 zyF$zT<3U32V6^>?yEW972Oz?JiJ#83Us8R8VXFPe+ZA;RbUz#3dq2JZzJ28AY4eZN zr*~4e#YJa1XTdIjkh|ibi|wrz zOA$4dduQvRwR#nrmdc>>BTzUi{2Bz`<-}q|0^+;5N-BO2HsvD8+auSJ-oJ}DVl0;kJ&?1v~&pk z!a%eQ|8QcP0iNYxM06fLw|XZLA(HKu58>@_Bv@4c8RB&7Gfi&?nR&kwv12n4D}EQ$ zK6-^HvHC88q>IR(-x`vIiMUwi#s;XY5ESO= zy{92e1&_Q@! zor((RB*w~dP=kYe$(91rWX$aB}XSL}{!3~N>&N-QBJxUGN&Q14d!f!6Z9~N1E)Pn*8*ud#61m9L4@lZMlAvWM( zEI)}29@-ClwuV&*2SWWoH~Z_=n=qgQr)2@61i%O^S4Dm-OPgRi;fe)EHg7HOMhW7I zju2f*oc7ga0<$z!sHeYGq{&&-MyvuW^i)T(-V_p$P;MHM#|roN5bk{g8ELZ z2=suM{I)u2`4R{jrj^N+#zM&!{x%Al6u=~AyXD6KKr6BvCfJ{3n7P%j{&z}V%0x}E zOd9dZdb2dN#o=ql;B4=A&36{(TO!IbtZXPO3ogx^u>lHHeteJ40EiTZ3|`-6>Y?}< z8F5<Gui~T!Ep+QF+1na|9OJ8q`Z8x5DLH z5ebu6o9rVS9iVE}kudw^GyOLT@ZPw<7qV8cifllFbG=z+sHgi?QDL7MhmBn7H zr`}rV^+M9>+ilNUg>O~LR&80bM>g~TS@mnIw&k_{Dr-J~g6Vh0_(g-M2gxJpbI9SI zKC8EG3g<+3(Xlt>VL13gb)WcF83K86I+DsSTpdcX;>-N-qo3$6-}LCEvr-J*mC$Fj z%w;y*rXRLkt(KaOdM$RDNAfK#3{~p}*9NRe=1)UWN|;y^{(Sh6Lnx{%FHVEXit^M_ zDf>8j^O4}_2voWT8)v$ts3kSFKw>G9ekQe+s``t2nap5I~&Hiz#)gI)%6(OQqy~X%o za-77E;6`BB3lXwr2Aze960UasXYjxhX4~3Cm0ijaGz z)I_(wGJyV=!Uk%%xTyZZqR(=jANLi9Wj$}6Aj(;J9k0n}^Z&4Q-{EZifBf*X5IgoJ zQG4$_WACl@R@$N{YE^@nMa|lK6s0w5*PgYhq9|(b)+kEz%jbKKKkn=PKl$UFD_73@ zyvFl^+56Iu$La$xT-h|tyxpXj`YXp0HpTKTG;rR%el+uLFiYcKP(|Hubj>Qqmx(F7 zETxwmnqcY%5};T_csSbKiSfnqCrp48&nGLZ_SG-&}0}I!M zUyI;Btb=5tNQ2S|b<&2z7yd#dza`dhw@~DDW&CNB`(v1TZiP;VG*T5c~?=o(Yguk0}cj2(XY# z%mn^xj;~pa|8O1uJ_}ee;O|+c4eHhY0MThM)%k?hX@>yPiiiO?B#oEoF^GGHq-$0y z$~qhpAmj|A4ac|8@^1|(4@|W2jR%KIRYPB|T_^ryf4%Rg%`s?MfCKogYH)=%xP<`3 zdPuF|*k_5s5Upb$jU2gDcxG$D#sv_A|R$43uCbyR)g2H27EhdxT#}Wt| zH;w3XiNntNjRkNhdd~2xiU`Gx;wH)x`Xr*h^@9C{i0;?pK-q7KGM%aRLZEbMuS=3o z76Y%8&Hf7?%r#5#V29aLnLC@APW&lDd3jwe*;5n$eAGyI8(6!Lcn-2vX{fo zi6YqGxbX`$X^I=^AeIKo$T>2S-dj4y)7dv2$sz8 z*jtRmwFhUq&b#eV+Jiq{JQX?GqglSvsVzVp|8?AZZz7msF5hUBza`vb#J-|MV6@6jAoeVo4#K}sC+C;XQsi2VS z6oMcwNDh%Tf?!|}QdlWV(SMecL~yB8PN__LsoZiYp#z9;x)do>rpi;MNM9x$57a&b z3NM%G-~JDHqA#cI!KD={x5z2CiZ3?{F1Nldci<_vrLSM9>&8wo-Vpk(^0 zRGF%DtE#ubRarUz1D<%QgnDou*H!*sz*9wVb!AR<_5TNWs;)LN#CzdD5NG~B;He!N zOpq2PQ*+rXQ~EIY);suiT{#^LfR2?Q)=PxwOR0(=f`(;_Ikl3(Wy{O8Yr%k(oKnFe zh>z8~M>6kray|&he>kvuceMP$@Akt15Ac~Go?ddXJcZWv_^@t#fN z4n+Yn+6s$fb4#V_gmjo~Oueh&B>k8hqA9~17%z9}Y@>oTclqx|q->KKtmz$j5L~DD zbyX9J3}9x6r-3RgG0fo8X%;vv6wYn_CfrzH39MQtIX5J{E-S!AaM0`2`}ux)qQmj{ zDdz*7LW+Z&@LrHV438c~6zPifee$iow?xn8#(?W}3G>m`t*jkQsT*0EsD>dWKrln* z5p@moK}$L>oeg)Z@9Wl_j<%_#Hfvz6ZxOI;n$+ZPt9M9DDnlL0x~(P`@&3C^*56Oq za(?zuWMv@~FWA|*V3B@mZ2 zQFvuxcSvrpwNk%zXKhGZ0cO5)@@Z>KN9Q;Lt(GC45de@J1ij1dI_>Df-S4`_J}lwHchr4r z{aN9zU(_+x91h?hG)qD0Lon~VZf+n03h3^r#l469e$P4iOC(BsOo%b zGl**hFgL`L0|3-9MbGZ8di{xpm}J29(uCHaFXLo< zh&ExIfNN%SgvyTrj{*RoMzwV1j^!t`JEq{{gp*41!YYO0x*8^l6TL|FMyT#*x)|p~ zUc!tqhIm?V*w@3>`-LTPW=ov3EoNY>&*XkN}U~1hUoHLr3H?WJe{W@vv_ZF7$NTuki(jCi?{7%(H-1*#tzoesj_cKZ?8 zzZf5I?pmHc`es<(M@B!{K>Quemw)(viu=a5)3g2aL{Fc5UG2nDetzH3u`RwP=sEWK zdEhWua`Cih|BCghaLDS%+Lfi+Rm$TvvECJMZ!1s8vLW&4eBxSI^;)Ff;^@R$Zr2*V zW8nrr?D)OMj(qp6e9hhckAL^Gjl@6X`16g0VBRl#paowYZ3K9_){nlf!@_=$Fn>po ztb>);!M%e?`5S)s-zOMXn8T9c0vlwX`$qJB8s>kd5`YcpI)75mUgYg=qx)%~yK-i> zz^bt6Ub}Vd`BON26Erh10#Dkm-4K}EP}kowm;9;!Z%N8)bCG{aMjuvc-Ofj{#PDI# z^27FV=Zw0$$N(=oa|{PL%*-OtFdc4v$N_VydS zT-$s_ve$C7BSW}LYPZSewJ&hLjf2I|6L!lymlKnA9)8#nBH0(?+UuX|_Osj7N!kae z>=~_*woR-ieORtw-b>a0gtpuB5m?WjJj`9&hlCfVY8{sR+iUrdQR#JLM{<;LaYV^Nj zt&;;veOUSN&yBF7rL~i>f#t8e6`!1W`B>X%vuf4C>E=3apuq$MRR+ZLnUNaolq_lRudq& zRmn-!S=Il*u_~;j!1y0uTZvu2HCd*5zSZTEg&G5UvpX6;%-)AIwY2J=f>kLTsL~`xa`N&*<069O%GI}jzYu!Y1SR2H&0ZHL zcs=4Ci43r!bBeQ^9<9U+k-Bkw?NGs8855+yja_G+bg%q;<24|x!St|ExcaZhdt%M4 zh=Jqojs!W82W$tGNC4Vcvx0?_R@Ju}4?{*EMA|O=AZr)4{F50Mum}1Q@!=W|3b-2C zMMcc6b3QPr6V`ld`-IV5L;lZJqru#7qQhabQO|q|% z1*mip(@KV~98wtq&O{LE3*39)0Fk)$2*W12#+VRl%ObR8FgMqH1Z6lUf&jUGi72~+ zNLV<=Y*%VjLikN*)MAK;jPmndQkSwFWNpqysw!0!O7NIa&*@Fvy?^tR2XLtqX#Oov=U;|JB&qtMfpa19)6Am|`6SCF zI7uQ}`oIE#K;9yv0bZh>2~IIRtFNQ|>MF65qR3eF%r^qDJ5+)_Sva|`ocD&(_=liF znLxmFru{3j<>rS<6zVdM%U7)ztD=FF*^igWB1FnNuRs>)cG zFm<~7Fl6O>cUBomLN0bPObZ<<==7-3)unIWfJ@!@Z@tbRO}%f?4WCYJrFZoYoi{b z>{LQgI5N!jDaFSx-I`D@^p(;O?s>w zoyz{ErhvJ&Vr)z~CCzR|iIIpcTWM!2BZ$!+sHdfEcO}Bpp^DG*M@mclLw%ZKHZ>J1 zoKCMIC3ToF5kZ5eYj2L3%TX!j&_cJ33D8sIw6eV(6dJ-x0ts0JDNdUWL3#n78Z8vi z#HuzyI?oHzUb`$=eG8l&4-PYtp3P>a`A9;Bd|V!ShD(uhu{i^*Il3Wj~|D3v!6q z%v(d}a#YFN$#SNqA{O>ajioHZ=;iaIHOQ_xNGVE&O_@)ycU@RD**Ho9U8+sNt?B<{ zB2PW7OssZaH1c4&YRe(PmG6r--@1G~@M{(3u8aYv-K5&QInX3yOd=Ch`_}s_=K^p1 zLnBu6!~wQAT)NSr1jq1H5~_TF8K-%z%)|Fr>8w_sLpikSa^!Q4HzFN~k@YB%GCRQHpRY?5hHfq`%3AB&X+j|@sIG@XQcARg!} zMdOk+g=CC1Rj=3gAhoPRU28f0Etlu6KIK$3SIJ!xd>`GpYE~h8S0?c#8baJ}6_eqC z(2&(z!vasG5HCCQYwMp#$@U9BZG~yxYQ@+HWNF zmeX=OcNX9cWD6)fxuWps2va!KaWWpi17L}q;>ECnowtz`fP0(Oh4P*@nt9A)N8t_M zXuPdRF1y~UrU4tVJ2V0&75;`DphWeP3rthAL8M?$+pj_5myppQ&Mo&1?qeBEQSGs9 z`NF@HUSBkZv+HRjaE|FU7f|8K5XO3^616;0Url$n8`9Ux30oCJ!lzY@Jm}aK)vea$&C^0(W5l1rr?_z z!nnn*5j3X9?3>Xdx6R_#_QiG0Cu>S>+X)?sEAk$r5c0L9y zQRm61I{}QjHKV5k!o7A=tMq{nC-USuqXosVK+??FWA3WXN?R(KgGRF8?Ku5vqXDOPmYFY#$ zcDMm`L0LZ;>SJkI@dQGzTC%Tk_XlXbyrcBbBGs#58kL2=5{zYK*T(dlG0ynr&&2^y zfU#23R516!Yiiu17HfuLT_vd4BA8Dq(hU|vYS?}Cvqw6(JHjE#yA@l+!J!8NWS_?b zRYuY7b(4iiJ`$~WJ;c9XW<c?dZCrgn)q-XyT)u2k1BNz$mWL z2Bt0L7al1)s7`KG790f|wM?CVTL zD$d1q2fvPl0w&?nQ@zR$B3owgRRCvz7bvudT)(my5xb3w)lX#VxoK%g?)fH4t~3Z<}VT8o*B8jvl{rG!6ny{*qT zPIX>HZwva$8fqzo{gL8XUWX4^E1Iwk*=wt4Xb;LK^aA__T~+a^iogjepK^twEXMma z*cxq&nc4Ypb6l;qLMQZDLAP!#txGi0=g(jr#PMb&y-P5(~vS(8S!(xA&z zbvHKry6*YFru-+QitF@xa4bMZG~$@y#4 zeAAWL-Veu6j#k8K#@7g@<&8+z#4hNdB1cdhA~-mq8a8_RV=pnBdSXIf{dpN3WG}lj3OocvXW%R+37EJ=OIzb`#NCA(nCvq{%LT99We5_)i z`5k1qQcMS(rTuzkxDcYPn%5g!-5cQzaxGFT9~i3>6Mv^mTPde=rK962rt#`dqq!^= zl8nzT0_8ixGv?~a?)(yOI1*Vl?8*1#v)q?%K8;UJWATvj=riIT9w-!so3vCEcro%E z-B7>sWvpqua$x+8s@}xPc)BY7p)4#?GugRLXpU05WebWOg`xfIF){RPI!6h8glt>I?5$#GLCeW-Z*)<`};XM}I+!iOs zu8OB-P=D0_)y9C*U+-|f!sTMJI(_QKWhMe(0Lao&ZdapcH(<{gzwppx{%V9YH9|1W zrX@_$u;cg3@d8FZ4>k?m`57_I4{=V+a1H8nsa0ZxsOESFjrXj{d&t8%=y5;!s*1nt z+wYt?;4=|@Il_HB$+A68L_8mNW(Zj)D$Dy!%w)KJVW5Cxs3<-S#+ijD&POedL9}pn zbWLSz=g8SjG+vsD)|%?v#iHSDd z!cLlb-_N;;n@4F1FadJ2E+#Cx<}5R+<+sgEY|P#G4IgcrNt8i@f96o06*zL~k$W!K zQVF>ve*2vFF#N08a_2Yye5i0dn904wNmCmWZEJy|s`ccz$d|K-DxbFzH%qdGjz5Xu z5Q&C0FD5mA3%{RFI5rQgeZa#0&3D_-r*=L91>$InOI2HZb8Pm4oj=pnl5J(NfY>5= z+cMM>8ruLqozV-?! z*t$i0rBV++$Q?&`nymZYdXB&*UTtZ}^SduGKow5n=*>|nZ#5BRlRg5r?uqd#Lf>YS ze(ACq8ndb8w_Q%Oe9ngb*obk_946=3CMVIb%QKcH8S-=l&t^JOSgWr((N-dNRl@aQ z4bw`18kB6E21M z>QWb3vSn9)xjIj27c~vG>4|v~2>J3C7`hnCzfYdQ9Vv?L#z@3(%qTH}0R zWWpjfY`C1s>{=eqy=s%VcCjyM2cIv+{E*95{WSeHC_5`VJLe|T>>3Zj70Z8($4^3U z&72c?CKIuNJ%6}}3fQ>4-BP6sSBWKem4Xl^gPzoz8<6Zc?o1h~L&LImB9g;{*JGP3 zbAx>tT2mO>g<~-tqq$xC40?w?oYkf zaqX@_=|U_QMl4rAz@KoIn_?D#6zVZFnjh9o_^%K^4_E*EB$jdi1n1GK=%ehg22Cu5&)?j4wDV+#+8qGE`HT~F6>xg>mUJ=dBmhbDSOH2?xij2*a*T}} zv0E<}ia0dGHPS3i3!Ia_@HmM+%8`IN^w2n<&Y&@8*I_3&6}$uRy+~Mu+9LuV^je^V z?RG^hB`waT1+J09N{Z%(T7^^nM`sQx&j@#`*a;cis6-tWQ|Kry!mt*%I=M?S-j|t|w5*FNF z6>ttb!6)Y&aT#$->&bJMee4!vDErLYR4UdK-aPXD%;7~%sbh@3Gvq1Oa+;1lRJb$~ ze6C`Dl8gc%9nOs$Y~rR-AZ1eF=v6>1wGTiapVPfWTUanLi<(!{;Z@;_Y5mj4X^`az?ql~Tc;Kqfv+HCT`ll!e zJu0Sm1LWuZ=MkPsD#ja2Evp@n+V#5z`}3W z3GW<}g&w*53rq?$k%NZ}i~Ys1zl{KZys}~*XGI4s;=Z$6t9bKwX!f}FTksyy;>U_F zF4G>VaG>UB_<4;{nWO=yTAa-^&TIhCwg;#6dN z_S8H+=a|fsdGY&b|D1EW2#FXglNNItVbBl`vw2cqWfE&xs*p!73@CQFPbMR95JjcS zm_R7yG@DDlHWJQN^XsHIkEBTIt!%zHT~n}TU*6;!`y;sC6M=`J5YTPrYJMC~Bg&kU zF7*9V%9MVE$CXpO@%?SKcKCA*CTTWu^9n1OgZ=UonR>%v#!~5P z>Q|!L9A&ObPUtnA9xxhjaVaXY4(iJ+L%c=A#v&?CVrgElI^v+HkS*-$c6Jb zg{<_MI+Lc$Mfqdz5{`FI{2CrPW{4|ia~8h5z2Q_pG%_aT3A+v-lS}ubE6WmCmNre0 zF2_+0zlZ)@($|`IR0BPe7<*VI74^g<%GXSFRI%6;GC)TI5bB8u0m<;zHtX*rSSDM4 zCW(eJUS?$$l5q27IZ9xW-CQQ@8J2h6XqbRmo?yRemW*MynFN8KLbGmBdY~e3*Egl0 z0GJ-*G?;Yb?Kp1#TTo*J{NnCdy5Mr!MXKPVt2kUXY63Q&PeH4Gjdv3Yg8t3)RQWEm zr7Zaf0{)=#@d%suxl@pm*sk97S9k}G zXfE|0X7cEI^fizPp-5+_#$>2DC}F_Yu@$62g)1+nB32fuhSXF{fBo{;g?A5MBP>bk zxcU29@usIR3C}L&mB9XKk7C_vwm!gLmFbyoUE5DjjkV5GTiH%SX3XC6d&RrGMwE(f zS?L$~M)$}`(#9WQ3b%;UY~#@}y1xoteB|Wk7$MO=su7I-TQIV{Vm!eEjOL}Nob(o0 zR|-y11|;NADucYuQWKCuL|SYMyrk}2uaTpSeY)7syZ{~exPm8ronIqFHm$3uo>E!} zbs+Fhj(C{$r;{!TCIG34J^1G*PV~DjhRrySZD#{tyt0?#Ja(W&TN7DJHU#35Qzd%U z7b!CUgt+4u0g7q5*zH_`Nk<)3I#c2(;@o2t!IBYB4pOTsQr<;n&S2pt5^%yZYStLs^Ut&_|me+za=@J(k^eWc*C#XubXRnC% z-XR+CZ!eiTK8i1Fev88-sElD*6`F(DQ&$L{QNPY2Oa0WjZMhIhti!iO{;h|N$tYW^ zM=IQYa2iNWBQhxEz0P|7b3{~-u<>oojWNn&zNmk#W8*|~GYuAs zVIOz+w~cQ_HiU2SX*gVnJzFT7LtHIet*w5R!yY;)y@Pn|8QfTedl?tg3L_jGa3Z9t zLW^w{lUNfeBd9dhWVf&h`=%~04)T6#e4mZZ%3#&t0qbxdR!zN(Fy$}ri{o`1#i~xI zh(tLq{pU~8tQ1^mA}x^A-iRa;Hr4;Tu$GX7Wuo*mO0A&vbjCto_!WVP?q!ds-qwoQ z+ivqH*4~hZse;KFiODbq{?!Z30xt5%kf%@u7%&05N9+tx!au8zLBlp!9F(+8%<#>6 znYUdfXGtEXjxwDpJ%3;LoKNd4NIUsrj@^aP$ZDy2Deps!&EIQ2_rc;gaLoY=5nsQe zZV}7}o`RqZeEPp?+VrPSpSt+Ho@0ThO=@g44e%_IcV*-1s$~ERJiR7d*%F~?A*-B6 zusT@(5NK)ZNK~?@gs=WI{?@)m?De9X*KRwhrL&1x(D#|4WwL8P~y#&yb1rlwfE%OyLd$ z2wzlJH6utWDZ$Zx1>I}XeuD>FRWHlU4vf9RN ze^xKGKlTz0T*_Oc>wZ6^ursn4zX35w-JE2#Hjoz}M8T)Q0C}zp6=UTjW-dr`wI1{- zu!E(q;k-&&xhL~HwlN=~q--jrnx!FsGPkovpz63dYUm$6yCF#Uc9e&$c9(^Yo_v>$bT<226cT9zS-7x`50qC+eqscI^tf-*xs4PWg3 zk)Kyz$!Y9S2d*C)`pg3y=RTp5=2ZS&MgGA*RFOM==k2B8>Q;4L`0Vj$3)6!QMmOmx z?iZWZE-V->@XdV_b1+x=V};gG!@8u~yk{YtF^js}vvw3i8Y{oX3SQm&8~t%aBZbpd z676r5A*-EApx>jxp^3T=4QrkAJDw)M;O}ZCFd`#V$d#n3#7jt zEG}_u2EW?etm*X@f&PK1j7Nj9iqi;K@k~X2ahT+Q2seI1Un*SWB9cor1uqqX0nTE? z?GMDq0aj?Y@CCOx>c?#wJ3tn>yT}P!#3M692v;x7yeYKa25?}*=!GWB!Z#z%*YV3a zYTF8ylfa{|s1o#6Tivk?|X0oJLz6cURV?iv_bJDO}v zlhpVJKM#VJXJE@yHJKlhLPwXnU(A)ms(7bDljTH5^%L=V1INxuEf2*>90{E+(BU)3 z01X9xlP)i<32>+iI;j>FYZfzEag~&afB>sp$}-X4?JGA$k(kovbqEBiQZtb==!0ep zTc(ySW%pt+aotp3Sw`;Bf4rd=E-4k6B`$4#0Fo$`n{-x{Pz59qi@-;qUJ!Ff26j*x zK8KUi=0JP%_l`lV;$$6iRJ`L4SPey~D7esm+N2#T(_8r=f@Wg#8gP24vFle#s=sB> zNvWS_Ggg~7+~tC-{HEALU|jIPq35S!unWGID#LoA#DQ~wxTb+uDbdXXJrd)MN|&`D z;Hnrqzp%5e?}TnOyKYu7ETBxyW9uit)$q1VV24@%EdK|PS=ZRnRyom#-#z3a>k>s}G2Xo7no6FBU)YG=8h(1o?Zp^B3p_9_v#aH}+8{e>}wE$g}Bd{!VA5 zP$Vyx-)=zek}O1f$J4mN)d~W+;=qY;1C8}7?l}Zi&jf+geAjk^C%4t*l*j!XLd_w- z)?~^oAfnnm zzIqq`U;s{CBKw(*Vw%{5gxiafTbGf0ad9`>PE~EqIZ8$q6pv0_u7g3&xZR~ zDt8b`#APgZ%0ZPu7Wea#{USTGDK}VsVIMg^&ft#nwc0mTf8w?IxHfqoJ7RZwv+rq9 ztph#CLq3r+M_bEqrHc#@Oe-&Qap%9S&W|p0EQ+sg0`PdN$R~h#j?|EWy@H*QvS)p> zd=S_`zbxMXvqz-74Vc~(@(vpscBj(reoz5=Vh~teQnJURph{qY$33ziC4vS+6LuQCd4E~)YFn?V2&idNVIkSc(#u;`u8JQ_%S`aZzgQ7K{ILJxV= zE8porvp!072WAJNID7iwci7@HNPr6>R*6*Q7T86QPZ4Cz>Ay@20_LMR} zJxSBbO{&|~0Z-eUoE$qNW>7{*p*|V50lYeu{}d;5ghVGCklrha?iuG9kZPg^xJQVK z4Lrry)0E>QGRK~T`=>yjeRivH*9t&rP0_S)KuW zi(#(HYPRV0X4Vg7%pcz4M(-Dq{Ae;0+XJcDD2a7O(4czx93tOW+93S|0HI!cNhinw zPv|(maZVv?-3Q0k6P{kL(_612kP^ThSJ(wry|8&Qc5?JqP<3n9&~)l@Pvy#k6cE}Y zdfm5%RZYuOnALm!Q=B?g?sEzi{7#p7(BDsv)^=8jrV|MRpE;sF0^**S0mL9+T)u$^d0-O}lpM;744#a2`6!x{Ce}QVa*>m) zNBbNYINKdq!O$B=(Och;_xJcF7VL7) zlQSweVSED~n)d{Bt$EP=aM7~^!8t#SN~T?1r0~P0K|*{H^o!nAXGnwRN6$V3X?n)zieyx-(b*sXPb_aQr6W ziuk0KDK?dNVf}lst6xEgo+g@4^Z~ zUgzSo1F9M4Ov`azS%%ZSs0_{VuHa|x~}{s zg}on0m4l?<75$3d35g7?(e~ac;6^JrDlsd<{{vw8$iRvH&l|o!NxV|2e=n&Nek(eh zqzU3A_5TTcC}p5YB?ks^ebDdAD#PZoQ=Y3H6pI_;iCaW@( zISdr2!#cd&miatTT6o1jN{oU3=MMLzWZv)Csj3aJ7D4N@2xH!@!Z`-O=I z%r!jkUk5Xm?t99-`+K8T*Y=tvSPyot!dc8q(U#kCYb|)KE35jz0xSoO;T#Tp7n0`v zFH&dr*03fhg7>NpgT@J*g=w3Ed$?Oj+I$a#Ls_JyCN1cTlwnXH=Q>73U$mpPn`X7H zwh0fX`B19-VX(nUp>X9#m&ftH>jDdQ+p9C_E$q;;e8}kTzmI&|3)7QBUZ5qm)pZW%t8t|*FjkCO0$2gQ7+b?vj+di=^#*n;xK%ojkc;{7Q|JD$Fwf4CXuLBX5oK0Nu$?Fq#)V>zjuk+jswVzL!+xOz0)H zQRY1Br(;w2RRvmw(jRs_UwPnnV*S935-RK=xksrK|9U;_h5Wk7zpK{@s&z=Il}MRu zY=F(}VozW}>vMPfJHg&vcak7bbQT|Q{8+t!KVJD49u)c+57a)Qv$V}U1% zM0Lvl0Z&YdG8z8?PpZ0@E2^6I{{c^&NSvpJY@_wiv?RTd3oS)g8TSgg>J7boHqGq< z`PM65`;TF5AiGx6XB%iIVovkC>6z|VOw<~0Rc%Z*Q%G;Ku-6n!do8oJ?S#0 z*Hffw@&#`cnldRf08erfhGnfPg8==GyJ+^zGNs&Qkn;auNyj&uosX4I3liXsLw z_*3N(x=qgC$*J0xO-9sJ#9yRi$W2+`8u#HoKd9 zx<=oW0G)jJsH*D2rb-*#lguA)eJ4EKg*8!vVg0qk^q4O7 z)fb%AwJrpbjHQb2b8UaOY&`nx^RBU(G3ckx@?D`&k6_{ZA8nHF^^fdX*Bezn_^-@^ zngw(2Ne@q3eNi*Rp+v*~egV&klX>n-V}HL*SG?!;mY#@XQP0}0*>OD$i)pu03m)bL z&w7$4J;nnnb7c@~L&9}T*1JNaNtI51Ub{7R)WYp8eB(i~d@IUTq zgsJ3l)<@~}V%VtK^D809g7-N42;E#=O*(5YQNN;#ce3RO5|Irka;EOZ;1-i)RH}&|7^UQx zmJ4K5>G>a+6z9ZDrGu)?*q<<;7~)B-_g33p9z5)&H?L31sBsm4`mnoM@5f9!%4t2u zc@}QchJ<8!Kzj6^KS|F2ELwoba+BB6HcrF6Dvi8%w@x>TOr(EXIGfT>0PQdsQkN(t zE$7qV46%%SWZnqg=2JAPHYaXq4kdCJ6xhvKj-LMt-?!leELZ71eKf-+jITEbZx}Pr z@&44;x6>b(IcuG|5U6}Tqd4FQ`YO<3J`klT6l19iKm)QH%D2UJM5J7cL~@7`%8YE4 z?BDB8+M7Hd@o(>}OdSsi&$^z35J!lRx+@c6V$swd0F)M{RfYIr9S&D*h}}^H+Q~(w zSOxYFk9+ZT%l4(`v+(zW7wYV2u=l>=$_)70E3o~*7D^X(OZpIMLa|pDBZyWSHX>N; zq@U@X434&rX6q3%&+7RNXWU>6(d%0)Jp<6e2?1V?@{ErJ1i<6E?9MKfRMrkELKR;R z*uAm2o+A4Zyvx>zB|V3p7-zeBz=P*mUx=zo109!EIikjF4IXJu@AQCr>aTlA7JNvW zb>EA;sRAJbh&bZqb{>S#TJYNaMu|qeb6I+Z;LB2B3UqLlahsbI|MD9>;THW;3YSrt zTr3;^I8Bu1poL6YS>*N?`j~sGBfxPbk92j@!Xy~OO1I)$Nr6iM5ZRn_UTZ|E+fMLG zqE-6?n{&xh*MlvC7p1Vt6~7YpH#6YONxkZX!N*T+y4e=P`7TvNyotChNfBbvtBKjR z`+n~k7T72SBwuw((kS%{U&JbZ!nr?0`-NCN{+zE4HDZM%e}@}I_ouVVKegfwU2P8g zWA!t?8Mrkj9NzQi-Q|R)%2etq5kg7$LPZ6j$vNr&D6rpP&FkWp_PK}@HpAK5C*fI# zBZG$D7~L$jiwi1Rb|j8hZ}OMc54v6Ysm5{w3{<0r^o=*Glt* zs)!h0^3UzJ_sjuQEM2@QzHa|dCIUM~DwZbf7s-n=Rzh4vKmVlgn!%ymrUvMGhCzKMnvu`*auY9T-Z`tHw*jN@&9f zp|6H3Y1rd206c{2WM%E3uSTFs_M@)MZ$PS1a8OAga1M;WN>rN4xsu1JPiduOi=DNH_%7Bx8usNgG4uxvL>P%X z3nW~u0{!Hr_v>XBfYaOc681Py*KHuN)Y4AxW>YdDu!k^&XJ9DVTn0r0s3ZgN6E}NO zl(Pc%-AJ+56z{lhhm_eL`3ji5Wu=MEoDt?lY*VxBVCW3Is@K35H%nQ+g4Q4xx7hMHE4#D$<+MG4$RP z=|~aj2m;be=tV$^^kV2pQJP54&hL4i|DOHdGkecDXU_d%y<2bAthHwD>%OkglLN3k{}lCLdO-B7-!Tw&OC`SM9rMFE69!7$lUGBd%4`II+R zvE0lRlna<2_q3Rus$jMUM_inBhhvO^NMfUVLy;KPdwGx)fOd(!h${(Ubep(p@6(~u zjYuRS)P<-gY~?zLN)E+wtD0S`lUhv(!n;wYYqhftkRD<<2fnhfB(ezJ%hVpvMhSEe zt&nFa{R#wG0vL-xK6*+kSi>@FmC`=C`k@uT3`A1L-Du;v!H=uC$8it+#EP7YgNKyI zqNVf(*P_90uVJ$Dm|pa60bQAh<(x#S)U@ zab`2YcXWfp=+=(7GDvroqHsu3%U1Tchj?R+ERl$u;gKOLiU!amj~A8CbC!o5-KJB1 zUWX4B#=i7-72X$9JgZTBe#FNjBpMKQ+ijKXSBEIN1BJ7NE2+J?L#KR>$_EN~C;_P8 z&E&hsZ(2*LdR|%>VM`g2cSL^AD_ zSW-rf{C5ETX_?61Q`PM_vGcR){AYH8k(qrSXeco)!b;1KOFg|-3p&E$RC|whg4Yp* z77*2$^w9Ar)(H{kLaeMR3vm*lb$?=wl8@CUlJy?$$+n8AeALs_1<<)2d%H$DMYW^H z;uj~>0P*up;DOAm9qI3$dicPMS%e(J138aw*vvB9R^HW335p=<`?i0O@jbkP9Dtm} zI3Z~*Q zEgPLID<3Rp3}JF3bz)W3S+j*%%fEUiOK#(!Z?^Z+L=Bi!590s>wjUqZ z222{6PALcdQD6F_?v(N@eJXZ^CdxI%3?_z+T%O^`2W~&3L_3Qloai)9If%W3FnxJ3 zaN_@-mLvI%?Pu6ioDl~(DtZHL&^V>@`i}!nOTxOf@-P@Y(fgv`>Kuvw-XoA4 z*sXJ>2v*AG;b25XuVHi*4_%{--ET=c{vEz}WeHC~lDR4|heukFdASnRn}1BXdth_U zVMU<3>SpU`Cz|3+BZh;r}BK68d*6V+32-wuFF9CkewM7J>F|in1=pF7n(2==k%Ffd6$hC&^g&8cUw6>K49}laXR6`5Zer}`53L{9qCHMS zmc0}DzC?$8Nm4o!6t?!0PM^B-N0r)&WVDbJIDIK8{fcZhQIg@={nL1rMn^V=lou5P zj+01o!1hCK_!H@rE~)1_bg!R3Ou|KlCb^{F%Y=DzH;jbWYf>o_>T){W77mzAOO%z) zh?{-;u{OOY-PK8&SBv4z@K?W%X{2$k5EgKMnUmt z2o}OxK??tr153~RX_B&j#`40;I^t1|<=dQ9=}ex6=i=Cx`S(Cer|&3a-byrPhDcGp?rq%FbJ>kHdk4#-%+MY=s9b>i<}9uC#vZKAcB-#wzFk=H8skn=B6F)7rmC1`bFTapUf6MrZ?X+xOO6g86 ze1U-S6)J9`=@Z*UB;Qohn%QCdF)u8w?605n zh2N7B0*r?;ChQD^(vQNyGTQcJyHicOS0Aa&@@$r^vd?Qx%*b#Vp=`HNq0mJOd&)+PAUtQ^bcrxd=s8+T(MH?#r%dTtDJ%d&;n~Cdnc8rDpv>;GCqwOj!1hi0h8|46~u; z4eRX)GVa?+m2^h4-KE5M&MRWa3gPVf830SuY&|Y z7({*$`&st z@ka|py}?sU02G`k$QwkAnBUsXp9?j^OA_L0 z3C8~m@YM3^VHwr&`oP)tls+kY2HhDQSK)CK-*Ie1ynOS?-a@lqg2lnQXWB|%y?_fV z_xUmRbPe0j>(;(gI)^3lUlU|f4(aKm+D9r3i$lS0N%nBHx4UoD7H+TZHZg7a8z%3Z85ITxKT8)!l(aevN zi{APWrSwa4?cVJrjeL^DG%DR^vU_eYLcmjr0eE;x2nOOB5Fq_*$B?%I4Qt>yKGwNc zRvGr62A*X)Z=|d|@Sow-q$+D5REZU%o&69Wa1ANQ;iNn(N(?3@-7?U~I3?u)#0LvHibqf9FgM>(ryW&p) zZqB%{!>HoCs1=Q^+z8@}vU@RaX8I&(aEwTKc-)HQyBGXVCYB%hn3I71aQA z0-Ln-8_K)S^1?RCf3=ahv>ft1;CF2$h$;Wvb;C~}vS*`AxGmb4mxJP`MG&GuIt(5s zBxMdC<~K)+lHH*Lu!0RMZybd5w+iRXAmt-E?gKY-cAvGjFJ?Mo1PPf}+C~5F2oHA* z2z;;R*f>Z~P{4I1D3AgB9b#>AF%uj=nbG&bN5>#kQBJsweTh`I@3S%4nOdP=5vs{O-s118%icgV~OZASn7XO=Z=a%+CURjz$z++&7w?mKv)FG6Ur2r&6v{&x<AhJvrN$@hVi;M5TM{|f220CqL zzhM}{un@N`^{8jT%EV6+Im8H@k4v`gzDzQV^(|RydlFX{=Y!)&HOXp`$WQ?r?!Q|a0Q0^0 zD4T*?ico$HeWEu`)HYmtCfX9j_ufg*a$T!J2OkaIldOs*<$X9XsCZ~7iT=JK6p%hJ ze|#@B-E;j4fAVa@_m;2UKbiug9Ac;Kk@3B}P@*zw*nY`^O0vIDvK^}Lk$I3+Bwu9m&2LUDXYIICv4Oku#tfGY_#faYdNh>J6AwHU ztFV!dMQVHIQ&$wL2}h5`+T%PwFi#f8;-92wq)P#pV2Re<=<(!I&;JAPWOvXBvF)Dt z2Y6ByEHzAs{$9ZMrC1ECPj>wo9I$jGt(LfL)MGp8b5Ek|aSz|a#m33X;K?#8z2}d< zJ|3xgGeK;g_yz()h1~Ew&eg~$dvfdXbo2IPp3h?0Q>wY?cG8sGAQnee9TZ_Y+PoHD5j9w(C8!J%P05c>%k2O5Tr`l2gn}7KiQM9?s=; z8`o95baG-V{xb5|wyt%#!rp~R8%r!%&vopy7V5{edal~|Rqc~;+B{g*LIt4wMWOu&6Z*ypP(zT%y#y78bgYHr8;r0`+ANzm`9-I&{#8M^Hk z*}?%hGAuymjR6Z)1;JvmV1Dloa_6cLHu7bNj&~>Zr>ZdF*ky7D?=I$FRS}BhR*)ZP z8f@VfKK3~8;x1YhsWIF9upEZ&e3m~A>U65LXuaf9rc`=n*IqQ4 z$K|S&6a)I^h#~ALI8Rd3`1V^iY?Q-L7jq?+<=xvBoA<>lY{m%J#0WE+EDVNbBezee zF!t>O{|~G?4MbG0R)XCxyTH=yUE;r%`r?k4@2#qom$WuY@xFG1H)LjC=KhWdH_qxHvDfUo72Jg%c2OIDUvt+Cn^^?$VlE z>+ze;{R!yvEC^kBKUC0)io*nkWqyOvg6@JOei)dE8ibM*hU;TUB_qXSY+bt#9Bb2!6>;-hL`89oS-uf{E?h=n#=+(IX*B71iLnmgH;(Sv0auA_->oJc8xlJ67_#*MvV*=QdL;o?!fX#=#QzZUp zUcf~J;_B~f-8w`GKrZEmwtRy=>w;4KW$IB18c^au?Za4ZbHot{vgiLNxov@tBLz;W z3;-sHlq?}^)fwu+8}8f#B)}S$RCeqi zo`km$ylFwWJmH^H1ldpY5PK9NX~+F50%2qq_GpIN;|65TfU?Gw?Oq5XmxHf)EYubf zW+#OoVnaMk3sbe`P0Q!aTH$@EDPgM-e%CwvUU4{p2F+oJ0i;8Q0fqD!A+CyuHxgkf z6|Qd=ZkUEhppSY>9}2+9z@4}#02_5i2;K)mS`TP`uKL@sbC96P@+CQj4+Rt<%qJGG ztSX{716Z(YOg08~hJn39a#Yh2t(Rc%DfFio=j?a=>s^6ayNdDGMRCXvQc1bJ6ZwMQch|gY#Xaz}I%K3V|mBMGlOhCE0?eRd< zQWd&gG{(vj7sH-Ux;$#sVJQNsiS7u3eM>|X0~8$NBx|E258;qKi&*4J>}VQd;!&K6 zNqoHsg_>QcZZFXm*7gUFg{@D@i^dc)0}A;Xvc_C8X+r`f5n|6Xfm~Ev6R`*2nta}$ z(7K#zSCS&do)-EdEwUsn77C>7!+ie|T%bMhVpOwRI=Uo1qy!e`llJLv`oz8foKuwA zT9p1s5YZ^w@;M_N3S^#TWS0;xVL?(x?+X(9bfRxCnjL3Ye87BV04?5@h$r}YHXD~xjp`Qj`P=p}w zxt!Q2MK#9#O&`a*zZ}ThK#2wA`hTiN3mZz7?Cu zD!NqZj@%in6FeFrn1J+OSxT3S5}ZcZ{@Cbd`+8m)TQrwva8R%xFY* z6C$V7OGXKlA02>024;XtBSR3;6HMj!5b;t(6=P{It(3a4RKzM}luB;Xav3HA(aA{o z?i`jVk^`bIi34D3?@AdPN<;07D@jYod?hDja)2uEPb^gSb46@T(8y78n+Rbwf^bIt z)~n!K$Ty_FMTiee-*TIDX0Ssj8-^w;m$hITox>lJi$!dVnTHAR<^~tLuH{xvrFBQ{T zjjv3vzSi1Y)XK3t=;l&ZAuE&k8q}G}M#LbTVQlqp_?tUZRwf*Nyv@ZV{VVAa9&>sC z%0p7#?1kRkVOs7Idaz})WdUnLg|sX;*)5Ywuq)V%GS&Oh1~yc;{C!%K+4Q5TNeTpA zL&H|8pquGrKhdx?I9d9fV^WF3cURbt(Z&{~meNeCf##Os7{u-U7JN7)Sr_TAQOYl9 zuAK>mwz1aUi`K!fEhA*D<2tSD9tyQvxVDns*5aMkex3G}vIc59!bTKq2kj6L-a2=| zbl}$l0BwJo>vijd>@4%7l!z%>TG=-`*vLEC1v)u(JGmV@Z^d@2gB2S6Dj_}DWlKrb~)@UjS>D>@;^ul zWh_2|0@ei7#^zF-R8hpkdn01|qvWJh@KV_w$O*4bOrW9C9mJ=jg;HZZ(uRWyVIOetl4$I|cqSBV#S!*%d>AA+N?1Yjw8{sC9!0q# zHeyHo3rBW$M{M(kW}$$@SV-cmf5<*%#0e}gaTI0n2`o6ysW+~506Kv~B-kwlM4<&8;MQZAZ|D^h${8b)McD1-M2P4^+aJOl5MV1E=P4j#>D znmeG3guE|D1R`ONu>@-m2I-sdn4$n$=#0 zm}3cp_9<W;LcC*Fw^zfKkNGR5cl^#Fw^z_0yE)`j?RycuK#TOcbjPw zZ!=x*WB;Qv?e1RheY@V=#O(~=w(zz{{r{#iZES4(TV>k+FO}(fxe@oH=z4A%w~&pS zOTkSi{NG@v(NWxJI&ReOde{SRGtK;$&4ladz~N!09&=oqHLgVk*Ch83%=ASVSAFw; z!b~G0BSS+&|5lm$`}^@EQ&(5lze%RHwl;jQE}mqnudm0eOtrPO|Av`xRkHtrnc{Ju z7;)v)xKh~v1~Z)&Gd5Se!>df6K7A@HD=RK8E-EVe`0*ny&$H=6YJPtHe^jQF6kLq= zd}8#!RHml~0Wbf*sZ4%;em*`vUS3|WUcK`4^mKD`b9HrfadE*pI^v#L;GP)c?%&7h z%i&ZN6KyQ*?d|`6wV6b4{Jc00b{st|4i3XX@h}s9fC+R>MOAt0mb|>Ytc;Abw6v6z zl%%BOojZ5L#l=NMMgMIx2?`4SKjE3Uz+e^@7G`EKiw1P*G9+zv7v^fPdD1=b5q&Ds^Hb;GEi7nxFG~qQ&834gH@#Xhbte1~O~iDCm8| zV;HVGaJV{{A|lupt0lHFlp*1wuyE)S-kF06A!X4%E{c3DisE@PSX(ktWbi>dTl-7t zWZ9z{`^CX8Wz&@wUC}JEUy4m~MX$%Cz8c#RN>I!VJ~+kCxi=H-tSs^y2tREJ#Eno0 zGzcztK8F!%G7)}W?ITvYBm^~9uYXMwb66T`tl12CF&(H->@AKS|6usqcrX3s^XV*0 z7vrIs+P#oByg!zP|IIVODE3V2o~@=QSsMqYH`;E#%TpF&vrIUND7N+4|RMImMv>ZN}N$z23D`s2@yz9wE#%I&fLZ1vkp=PgMfXHY)c{kF4 zK!#^T{Nx9niQ3gK=pvmmdJ8Pw3a6eq8Pn3(zV|=*c`N6NSEQS?kU=CE)W#59jCx^g zx0$J>++>qoW;mDev2xL5F$c9b@Utj4{QSvl1i7J7Uc}9eQWOojXi!#KFOGJ{v4-`b zgL}PDQHg)P`W=%>3^D(%b3s$|c76-5j6q4I!eCy3vjTrb#OR8&0Pxnk*zO0Z=ck6}mtvjPDF&Pd{9nKiezm=; z%iM2Dx-IwOOQyN(?^f!Eyuq`(bMt`{B={_Pih7K~|+U~9yyvacl*C+9(c7lu~#R7MgKrfHTE*T5q z-23!Zn~ck&N?d2}boIiJ1x1kj(D`gV?YX`W0FA=N@(H!%_D-R(U1YRRYio1_RI=Re zvJzB`$I{8mS$%^MuUo=6lxzs@E)umTCUA-yebyvl>3$PKCZr2*7}U5$DYo)mSZ{O% zbBFTmWWht@C4on%@b&3hs!QN0l&7`^bahSEuP6^m9+YE&6zK5bqieop5d6uHQW`<^ zpmITSfJNRdBIx76+qA9Q@P84neBsoJ;j8j1OBQ zQ~P^SW=dp0+A`Z=WS-n16&cVEfBkE}3#DL)B045ut=0@B#St5eSg zTFB+`u!?!h^{j*Z@j-NJQr1RYf6t(s5c`e;+w_uXVh$A*;4`WL_s6KSH2{E<4G3^= z=pv}@CrhpBm3f8FsZoGMRdbjj*=JDQ$s7zHklNIUnlh&su$aVHE}P zsG*s@V9+v~`KcB_a!4*qsS4Wg1_MTJWXV@|s0$gv~RRMi0uP{VfY3yEqq`+{YgJv;z%Nvi=K&-!%hyh(? zW~E0#U~?ZS6a8=5{>v(gi9tbTq;HJjtM4W}5xAkia}VL<1#uw&@<&gh5g3LEo%5MP5K%pI)^CZq}xTS=nS7qCDYTZGFG zf}p`zOQw?sb%wy(Q>{%W!2y#)PZM5tcj8E=>KuE>z-yxkR{mq}Ek5Qt)dBJLu8zW?dSMz35N=B3yM9d&YdQEu(d8; zVHD;PweC01SFc9;cepa}iLSuQM@mR*VkL3+gF+3A3fqyl!0w9NrpyoNZ@^5A()mU` z3U)rpBIGG*%in9m%a{|I>~1>m9xPov12$dyEp*|)h##e7>%S&ZJT_#9NqwNxbTllx z{!D}~9U_%j-IIviqd4ihziETS%ljz4+*EuPz=n8J5%FwG?XJmmh*J!r%8^tC%2e3R z8b^|X`OU4lO0z-KA%?aL3N;I6rm?SjBF=6J7%G{qpfluW?-sl*`G%AyY}5iXzzP!wt2l+x@GHTh*EC5RbH5 zP<^4+s*GpPE%xUpRgYr4z7sO8gDdQY4d;TeK}>%!z4i&8jypZbR>KaMw^TJ`Ci3)O zmV4l5W0A6Rvy@(VvHB96@52__x*B^W^-0f>7Sdu#e}z_G6ST5Cp)>VrV3Lp{B>e3 zg#ZC1>mQ%pI}UjozSH$+6+^%=@l_vyKlIkelJKo)1kx9?ZEOZI&jkIv6$GL3PY*R9 zbi4hcR^91X-L01X5=~^D3v;(Ye_6L9mwLrTOMOR#q&QWx%**9Tic4jLCxcYzJr3zs zuTafMzxLn$DCWcZ*JRrC4X?|bW)GcZr5t5dVC zJh$#U;!Y#)278Bz8W0h^v{ns%?#W2LZUBD?=d^$we+UbbatujBhtX3Th>$#@B~|P6 zU0e2j!4sM&6?4KK6@Oq8@e2LaF8cSg5LH8hWe@VJ#7D6+uR3XBYSUut4<0dF3l)!2 z9*U3&?j!0V=^G-An>0hri{sj)sP#oi!bV};D4@bFyfQM}>SOp|Lwt&oSueNZ8j{## zpL`e<=M1rB(l9+Acb=S%xuSPh$^*HHkQAbyGFruNfMR~~#O%%_h8;Ww^@?(!Vctl% z@;=Ng7e4ujetPTShe(%?JdsaM5q7D>Dr#Vo*+`%DL;)y+=pAcjPGVC|_)3)%!^MsJ1 z>K&^HnAQTYU`Vl&PO&jbdFGR1Q37!00(P@0&SxpMB`J>36j~85Yt=jN^i| zU{oq?E-~$XYN$zC_&{oqbXr7XT5MEWFuo58njXcFZu$c3Awoo?1xap9ecPD+{%2}- zdaAf<>6uN9nJu%KZD*MnhOAEM ztnQLb!9=2GBAJ7YSwpi~BWGEo4B6w-+22jFr+l(!(zE9pvlq^?ys*R`A`m{@6v?8= z`;FP`NK}S)Nqo`ldz7VPe<5tJ5O&+-Hem4fVF|TKRO-i00@t$~AS1&}oO zfaS|+%*|`erJMsO&U14Z@@_PxQ~Rb#i;y^?AXjkm8@_ooeCY`#sUOa)l(ydUJf^;w za>3Ps5hh6h986!5!~_ORs=006d?2*CDKqy0()qzI|EA5u5S&y2R0%K=A(5%Nck_8N zB#M=^@jZEZz7b>aa2n|foY(|QK4Ov3)y*L^&S@o6D169i<6HRLzR*73dErq(GtV2f zq!4Em*q($<1Nu>mA#m5^qrWzs;0~x5?+KyETvR_i<%8pvKgjd3N8{#-2|A0ZR}w;b zN?LfREu~1*F?prWi|&@P8kQE_pDW5Aq~#|_oR17x)GT;wAL#**Fd`r7Z5QyFDCNnN z*2yqS*q4_0mX~bA@H36%*$O3_S@G zob(D4k|k4iYpxt?Py123qV2p;(Ir&&f8Be1^*O@~)Y-?RvLamDN1odTS$V3)x3YBjE)WiJPa*bNkThD$0pO zNI-S_Wm)XCECw;(g1e|<5`Z%d5}Vr+s7%(C`!%XmQQt6t<4=1s&_vM&u-C3FVWu6w zd^%)J>vrZlEMq#rZUC_WT$PDj(!Vj#`X5v12_HOnpZs=tqqt+n9cGN&*S7q!uA=h} zbBV?)gGTPG2QS<@wUavWo=}+xJld5~@3MP{v4>2q$JnvisHIXtj)Ww(sk^DkX`u;9 zMRrC8suNXvYW6^+abPP=zXzBeeYkj{cCA z@UVp*YuRpwtp0ofxJNl5!B}+{{Xj5L;B!}slU#}$S-sf;r8&FJ&O?K;W`m(U{irNk z^_Z`|x()hfUnzXPrpOLPwhXzL6%@(AJF0qyKcJRjZ`_r9V)J~6z>V-Kk$h9& zyIkxH;EI&}8F?U0Y^?+yHJ`Fg)%NSosOhldzXIXFEg z;Bml&nf#c{)ue@BH83=0^JLPywWe|BLAzYMll&B7t;vmlS`Rweb2@>3G9A7k0u^bU z<(y3lbl zSI9E>K7f}IQ(r_jeuX6Oz{xGNHO&Vt%#T)#rw=b+v*)W8XDcILCCS3UKv~A#)X3Gh z^?;$xCp~zTX}{&ih9QanPCXu>>_zu=3l0&oFJxG z6PaR`n&Rf9_a-SmdBT>gs78KRIjv+<5fDawAyg{T3|N`0z#0XQv$t7tUO(VA$4CES z>n%UG|LwmRT22;Ry|26~@!njL(oEWX;VOG6<)HGR4t%h6P=s<&Rftl9LTiyp(JugA=IuqjrR6`1laEIx&H}Ilj*FI`ek6=JxZ`=c72t1AkLRb2l*NtE z%MGTA)m^=<7w_*G;zUUF_t_7dBO_Q>S(m<}^+U~m(URzl>Wr+q3(@nAma^}&j|sd; za9&RunMW%83^D$xw7jlOxe;!@?#B+?7a`HW(skL7$g*xeyyh~A-}dL;+P>OGC~Ue0 z(z!E&0+TSF?{?DSYaA%2i+=5B7jC0Ewx0z4q}Q9&kEbU|EKql4WO66u3x6~8ey`|i zw}fSH+<6saK1IE>*{!hUmz3v}sNf4)>)hMyZu!Naxu^z{AuquB?EN73%dl| ztXjy_-`=`jz8sm``}ISYa>vd5*B=QIBh2*6j=YZj#eK@3FyWt6E=!(IwrCW0JB2p9 zs6by9>FiMij=1dKD(2fM9kBq?B-z#^jT>%?CHsw~Y<49gR3aXQ!*)f;y1>K}uCOHl zQr?5*ZeK^V?-@VcKm7DFV|l5c;z(7NoHOn~Asc%K#_-GAY~YL8FgKiKl(HNS)<%;3 zgwx65O)xYOMudXkGvN^ys)B)>Cwd`n{kdQH@LHd4W@P-+`$GX?Iwp%R1WR;YRhu!D zKbx=V;L^_slq`T;qRe|lIINF%A}q$8_!3T+g{B~+B5Oi#Wz2s+4zAwUEGJA)Fe z;7-oNyiTE@{j&F`)_0Hif78D*C-_18BK_9|Cye1P^exe60^2)q9W2E~6>J`hAUGh} zM&5X^9IP4f-6-h0*bd+T_f z$@=oc*tiY8X^6sxj_slf5`2gsDYv_ePkf>d9AfksIax>BE3pB zO)v%}0j3g69U&bvb6VygV^X18l(9S`D4#|LlR)`wW()`*ZNj&#{=+j-u&H0(zPS=^ z#2~9qepY4El^jx-M);gijiBqC%4&h$&Mr8yBE0VC?vL%)m&d#Sw!;Kh358IVh@tj7 zyvZOpV2v{H)8{;Ug5x%wt*g zm2?s0QL5U|1^LPo)m_kj#ev^Gl!+|5_o3VYoIpx-*cqt)ov(>{Ds zCKK)!QK1m69+BR!IyWeV=P)J}-?%$y8Gi?f)lCc394nDOQTBkfZMF=;7#)0F^E75c zt4Q9lCws4F(*f|19PL1ia;hu+oaKA{&_}9lw{JQ+s|ePwRqF^p+&1W?f01?Y`8KDl zN40o>c5a-srwFW7p;!E^zWAOTg$#2?Bu{=%uiXZVmp?;1QXW^B^qj>s6a|TW@#~Bj z9+&dUogT@j0fIz-C)|22>+hFqM_N--XGth6rBFYM zS_%+u`fC|=t1zuLP=)5sRP6J`hMD+;D=BWC4Rn4!fgEAn@;f8rf#qmu^r>z7^TNiD zF%c9db6F*evkUL_8Ide~+Jb%~*Wa;yKa$lG$dUvaR`LPQ2z9 zbX$~LuE*$RYk=k0^P5+mKVH{Myu`@$@%{~ud&+Q@@~+*EP-;UnkK;z{teJSHN;|8U zT*bP)8@8QG#EvHCdwlXl#)Xypr5xhO&+WLT9+DD{$f0Urfe^`8FTNCw3u(y_`dFf4ZjXbdP5G~_8Q)eeFyaCVy$#jVekQr; z6J=y)J(E#18D=)G$)2^z)(+hwrjXhpUh&*uJenQ4wKV>A8(d62+ove7rJmLxgvejkY=zdV9z*lV z?OpT2DsgJ#w*VpcJlQ9!+Nn+TVHofDTvHq8Pfa7O&fb}sW(O(LbyGcp6pkemV|A&f zuze+3@s4=*^13gT75ysbp%97V>2@5EE1F2of`D!YL!#~)Ow(dPEIHEw3wI6Wma_yD zEh#-42+_Z>43;xNoovKzk!rD#f9|Qa!)Mj&`L@kz9ZKm+d3G&9iH~LuiNG}#6+Xi; z<}4AZee#9B5`xH|u*1?D)t=#;At_;mi&j(gk_JL=;x3;Y>Pt6a^<1Kute}p^{Y3l* zZck0+o|#_d(^w1g1HtGi7tyH-Z`B`}EGBOr)V)D2u4n0SlJ)D^Gq9)Rs<#>IK2x^V zL_Ez^q7m;%5T$;=Y}p?ymepZ2a{Jy$Qkkb3abp#mEiz-NR8`Dsnz@b5y|Ob9iV?6V2Zi1~(-f|^;dDXQ zQHrj4mF=%)Qz23|6pRh+awV-L6Vm)-UO@QEF0@BX!2|8Gu~P^Q{|%f9Hr`*>xdT+fKvMg^I!Z zVK=%#HmcGKu-`K;a95T=Z2lVz_q_*h1%7`|_ew)m-yHy>sIR=Mmz7{{!Tu@vS5yAG z*emiRDV{u0z>^8guXs=DL>$9l~hW)D4fJ2yy-@wY!cv;`MIt0~Ofe3|? zwiIkfu=xTF*Qaz315X2NJrem@&m(^XsvSS`0@6?nSM)^1nXdx}BUqwW`fwWql}Cq& zcHBZAq_>$FXaMM_h%tFGn=0HFM@5$&7{)opBc1lG3&p9gkz<^Z06kIri#tJn&2uqQ z^aSlBTuLHQDBNm0buxxjHFEJnIv68hW0C8AALCIbM`%JE)Wn!2dEVR_o7U#c z5qYz?RPKWka;SBsrX`?5jwQ4+0ju)ZN|TGqnhw)(IW?M!#-08)fE#?)%BgI<*+x z7F9h@HGFICfo9zgvbHuRHG#D*V%44};5yTVt~=%J7Ao&(Kmcbss~NZ#DbS;^*7M90 z`k(-1Y}SLnanq6(KoSU16A9~f+L$SeIw}YFC_j(wL~%7J?W&8As~abk0S%zxMitHP zDu!n2Pq_O0sJq@Cs`(me*a|2z^~X{mLEj?fd=@lJ%QdvR`<{twWSwKqj@0jPK_CDp z4qvsr%@eJl?HiedLCocwdwdQ(1_c_c{`f%3!1LtYKbl)A61dyx6Nw*SgtfsM9JsF-bfi1HRmP2<2rxv!$N zgZXA(NgTi0j+a&(YxCLg{^1R49%_3T`}JwE*0am6TI549kvyH^1K?P(AmM$a5 zQT=^j`M7Y_BV*F z3VDpjbs|GK58jY|F(~dbpr9H0TW(0O9!ZEEv_djc>SmkpuUr;&m{g#BqWcUqX(7D#l9*aR6#X-8rVA>d97 z^Bjd5%n*y?qe}X}@EnA)TY&jRC&X;OiW3b=Jh;Ej6@4?8)tV<%T2qxxen3)oEY=RB zi6?o`VIup4j@Yn-EwnS7kU0+`*AT%qN${&A`1L*rpbz$k1V>}Rj%YZv142*qAU4x* zqh;(gRI@`Q2(cYu!9!rRE&s4bmxSV8d_#yShQ!_i%&-IUKZQKRpAiC6;hNxANC?c1 zM8_LV3J^JI-qXZ}Yv662M?^Hp$Q2Z1?ex1nk*=Yj&V7~#xF{zm0R+6QM6BHZNm`ST z>7%aW)uRM?y>=C-w?UX-aU^LmIAJuzp*YT$JCX(-5zQINy&oPh6XE3gCBK@)Zl6Ho zj3`(H5{e;<{vWK}g;P~;-!J~P1K4z@#HNw%hP^i>At~ZUkVaZSk&@VSNvnX;s5BDN z9nvDDAR*n|Df@7L?=$y#&NJuyX3orS{RwMkU9+z1dVk)pNCC2a!U)cGC+gobT_Z_U zL|m8$mg;PimLYQXQ!9g0yP-c{%)$_F^GeqVmN4`caKb7iVYLP9mfL~DVf^P2Pno6~ z(J;!qnkmD_^kL{I{*g$5AMffwt_tBuG;l92`wt{dHu% z2bh8QH+C{iYlI&^z}qy~JIEKnzsM%NY9swSPl^S|g6R^#^dW&rIiN1M#w7udH4^54 zo*+g{W<2RMG>xqbnrha1;HCk^I@pa${qC4U zsRiMXG!gUMbDSRuaInF?g#oaTbcf!EccJv9?%b?)JV%r{Y*8!6h=WUv^HvStna0L@ zFE;um9=pI;D@*u(EfTLtcQ?Nirm^0?2GCri!5%VH$920Jh%op60=n`orUsI^UL z?2@fc}9H-AXCIFrT&QpK>B^H6FR%+I+3M)3hB4GvUkJJ{xVXJa0F!FON zKo8W!8SC(Q^_wM*(R>7Y(#}W^M+2zJKDXAVS#A9md1taM0Ew%QT#MCX!SW&jPfweR zYiadok*4U-a6PDLo9(Niwd=yr8%Bg1jg5i4L;W_45{82l+#2zj-`&N=?nX&Y72k_4 zIGill^L#zw<|D!W7`PpD{c^J@?TDAF8R{qu$Pb6>8g13+Y+5qg##jXZVhrb^8;L=JvSOH<%$%CJhU|x6 zLIrqF3qmz5!hKWq1l!lz1Mc{`Nf@Jl)2(lQ4Osc(vi5?*+*KkRi)>R)Kw=IG6pMzo zuCJZFS7H2-Va^G-M(07a-)(>4GCSFa(qZs$`+_|zwx?E|d!9OlS~yM^kMdyeU{b(h(#WIaIs z_6DsEGD+rqmdQrj2L7=ER?FGBdN&Kg_J_k}8aZ$WB=Kiw7mJ=Qf`#x|=EHqb!yQs1 zTnhdO7`xzQeGXoI_Tv_eEOks=Ey*TkkJE!3Xbva>C z!>io+I9J_n2h<04xBwTR^8n+JRIWxrakiIxukXa@6%<*)LI-wXAZY@gx^1IptGrmH*J>~?3$oCCuov=3{I*i<-d@jBrkfTm zeKJ?7v=Awt_d5?`$$Z4Cx(NRQ9A53`2|6c*8VA<*PN^bZpeFWYCNj7pxAfFy-bNP7M1nzW zu21ovi|9tNNQa228?AAjTE)K~ErV*$^JseFdT0N3{q=0&&+)rnz%9D4UI$-l=y)#H z>zw%cFxwg7W1Rc;ky_qI1X+hvf4ttp!MEfblX(ioXYGv>_I=*^a7xarG6urst$J8~}@-QHUy2?NEEtZ^c+x}_((l1&a zPaw=6m=6+5xtd}rofi5zgotWGn8z~eIhwDe)&{804fsNWUgg1jK20pUMta-tu1
b@$!_0qw36#Vx4^KH0}4Df&POkJUb#NFq1 zBe|R*zGd0~KxC+FnhJDHTO!|;MDjkW^n)$3M7|TX8~txQ6Di*)nd}2ra6-X&YV<^S z;K=rV>pwh`^SQ8976cc=`5tXG+G9_wi^~8rZncyeQvAMQGxP>xCdXZNfAZMkE48)w z*CSn)?SGw}B6+Nm_)XKyr1s}KA}EF8hJQ%BIxV?y*sPOsY#;fn^J4>U*c$Lr zSh|FHq&r=j^O-N63G?Q~=OS!{+PWqFKPRRlWk;(tC)CSnC8RKv9&yN8X1D7~Z`k3g1AFspd5F2`~r&LhYI_!`dHUW-uR z>b!vb1(5_}sc@LW-<+V)k>s<&w{8&{M?V4VPs0#_$XvB?)YFVuaO6$%PGBG1XV=EE z3wBNBzP5~(;Yt(xy#zraCX<)q2-J+;zZw7LKuOtutV~4C%ZYEs$i4i=Mi+C)v980u z3+>{ZUGCJ1a*EjL2rt|fW^_vZR?%wNpgq&~IlYTJ0Kdjrd%#@6B)&Y?v&GJx{Q!U#W!iP7C zH*L4(Yt-l)C~32^#dP^=JG%H9Hj13kH0Afji22d-98uy2B@eX7AlevBxx>NH4n5gt zQ>78m5PLUelGjO3!gNF$4G0!4qINoUjTl$HJzz88)QRM6h+$!Bi`;79{NPuKHE#fN zyQu3TJA;sg3G8Y#Kg22BKDa&QUmJSr6CD)V3w{2koxEJ6hdhMsI=OOLU}vmW>VQ(4 z9T-p-?KgI6K0!JA5C`Lt7IbwW%x|}9irz4eE`+J{o9rRTnLJHC7wo}uqNqQ5r#eiL zX?;%f$IfPV<>JT1RP>8x=_SsiD$?b|J@z3^T>0fr#7We_4;Uosg$0VjTcHbq5OLzUsauSVL9~1fcoWh`Z)c$t$Cg}Y?VyZ1^IQxIyqZx?5KpJG z=~Ja)&BX;EJZ&I~aty9K986izh9g=YMB)dBvh%blP8QPnC%|zb-gr`jti<%!aF{Yr z2YFI?C`hI2jE+|E@FD{Gk>@SGItok^_k-34uFmWS0uauftc9?9ueKu)f5V=6d>Uh> zsE<(Dxa%I(@3eT3YVkS%)(IU8vDzuZ0dY$LF{U#aw5|4y!qJJI+Q-aMhTeh<;Zamx zRvr85?cLo!A@1M{kOEL1BF_e;UYTr1N>0cG`R%%Z<=)Lu_)u~&S{u%|PtD_YWe?jv8@o-gTq0&`9@RNx0Y2j2m(!yPgtqJUv~XPlkZ2W0TD zr1I+Phwu3(g-B`c2Z`q-ey+n5Jzho^%Q5A{v1Wj@%)2>x^trc9H*K$L!WRQqqb2Bokv0iNEA zTekpgufqP_UN$-B?R7p4Prqk5{^MaK%4TtOEI$|) zv^~IdlpU7hjXz?eEtZy}sfJKP4F?xN<=yDwBOMz`(k=_!GCtyCpek@k8lNzHCH{`g zV@(;w>LT%=4?wMg!!0f;ZrC5Jl?%ObyDX2WV~>b zc!>SRG6rvJ^Ntm~&;DW#e^gW-V5(eT)_>?j+b73DWA&C5BEvY zZQce+y|}dV3t@pLo6(jMQfjLnT^x#$FDv+#;l-0R4t=HfTe{zsC)ReyvvwlX ztZdbZEhrA>@erFiwt0iJy*iRd%8|ppK|{Y-p^+Vo*>DVJmQV4?$_8@$adM9a$@4c= zrh#TnE1!{zEX8ylA8&(Yf{}wV5us%-9!`_7P4-cZI=)c$a9gArqaS7Rtju(%kGT9Qbg?`ODdI*6~)_X||8lDzCy z#uhOALezI7o-a7p^)r;dtdUewNlU}hOa6xABq*f|bS*j|XvVvrYA}tx=}{29svTpF zk-Q0t_Igx3wZeQ_LLMB{=;JYiJM#68IC9>C^zF>dH-TW2Tuq|}ig!Dn!p-fYae+2$ zi}32R_Ji1+U}>b%x5?M7_y)n!=kM*l{;B@R?z{UoVJv;!kXvq+-rmb(hUe%!g4t0} z=k zJL_UAv9nx}dvYE-XAzx?mYsMjj>pRZ9Oq&E|74k7zGbBC1kk&i=2^+0ICKsmmF1FC>h(sJhQPJ5)b-qA2}}R)xe^?vhZx4koHWVfEc+<<4Xc^T3_5NH9e=?B zs_c@yWkj6kf6-Z3zhsKpc{2Hu&bjZ`Uky0nrP)n|N{YX6YHV8GFe9uCs(9VWJY(@I zG8>baonUJ=NBuC#_7U_F`-h+bj#CtxD>9Wb2`5#AF8@`gR$1sfx6mU`4?2L6PcrW+ z^g-I_F|2Tk8u&tDW(+Eanhi>d4y7r}akt1Z2Ict9gA&m!>2&R%-LvKr7w8Gh-Bdad zw+3f6SZW+1g9(Nabpysr>GXb?rO zlB|jvL>(fC&P93zDIz<_EWnE6_mrESPz~MIhe7VXTg>~JyF%Yx1y`0T;}D zm={=DvdulPNU6y7w?t6pnNDz1(t=?-B0CD{*1-pW#lcAanGPgUnO8bg@(?a|4Jq

zWn=@h1J5Yj= zw(mgl2T37^BnL6b5(0H7E?BBhm;b~zkcR>0^`bAP*!p?2*nPxZz#S3zyB%2bl*QIX86emYuy zG^=AEyeAky9IZ?`m`pexPBsbQB?_Ww>X6&VMR`1>UG8Lu1#z0@DIH>$xqX9Fn>fPX zMTI|OjkpPglvoLq8Ad6ofFfBzhIgYg3kp9LM3vdQ4&%^$9A}M1iOJ^*)oG(VxPbY8 zWEnTBM4ffr)eb~LXVO!9>6)i<@4q=^CcTplWo|%4;}m6j-}RreeLyq4pEjuUY~EE- zDN{)^nPk;vRmJC2`48PDDjnz(;EZJ3d}p@F$ZVGPZZPj=juZ_I(cw)qEP55~nDV?3 zMP-W!1*6;?Q5?YN-3;XVX4tSJx_2{&fG-LD`TV2frDX@AEu>g;=*^mnFL}a&DwK#s|T3}Jae*41&f!y#`&_Ivu=W2O* zpG9whlsM1nHW<2B8v0=+{oHj!P;!fIvejbq*VKPS_*(^evqstKeJR@1a$ehZw#8|* z7ZtSpg5r?j-}SSsAqWq=`%Ve9-KF@c(KD;{U9qR=93r8;J6fYBV54Ug>Pe-1z2ewR z5c)YM6$LnXT|1XEm*|N)GQ8(wjN3qnKmOj``<-huc~RwabjA+`C;a2bB#h9J=ixOp zE|b9msgL=`$}A@(&nk$LUu#-rz#N`%JfYCt_E?&>6tvB;GP|X>Hkk zu*+3swvBrkq&iNy8(g;AvNgRMx@c9rBKhrYF8@Bmmo81dZQi|x!QEx;+i7*{;|BHh zq0JRZ6(6?F4Vo|d>p8=ou3fuZ{hO;4MT8fl8Bmz>;Nu;LNaw?K;&&^+$^eSs$>Oiz%g}=&u1Xd$1x;yOgWQ ztVjofh(l&8f^PbYkg|$Te{s)YSN8MA+}y`!R+V=lN2odo+jW&N9}6uSI!JX)Xi~|4 zw0mFtU~h3-XIZo$S6m{?O@XiSv3INqV<>pNU4bY_t#bk5Jysm#q24K~addD$RfIuT zOlNRzjlM*NTTGNs0%fRzwNXJC{$tkk-u;59s=}W@d@a&l>p=~CQDIleH5CpWw6{TAdobd4yHm*g>a}v-aLrT5 zOBP)zEi#F_KcFD^o5xq4ZY-{Lk34Qlm854nWsifO3!ULUhKeC;QLZ&?a;K;n;FgZG z8c?yy^Yqd^_9B!bJK8fFn--uF$*%D7AoR2!3%!#D4yaWzcz0@vl~m|FJB$7j=<4yy zCs@@&GKez5#coet3`87q`iyVPh~p%9uht9i<+-G&ZwkxWO$f&`ZpW=`Rom>a zfY%olkp0=?y}H;XtZM+FOqkqZVCQ=VG&HvF{I%8@ZgHLRc8190q4AF{|3-<>M`CZL zk6ItseKQVHy&n=TR`2HF{l{oGZ8}s#>L^5ckdf!py9c#;KQ5xrY7<|{G@~Ts2gTE9 zBhqNQCjLlj%MS=!xPEv5_cu!aFLK z@k*gmD)^?4jH9r!8S%$;FJuNQGjXyZ#Q}{KKg1eYx~`(76Ih^7ct$$@#aFGXG84I& zJlQRGj2t>tYWk{J&ZqH3&4(4~_GGzQHNk4q>v~t2`z-S1EcL!VZL;XDFd4rfmRJ6W z&^Hf!s%S$$w}Uus{n}lx8@-w`?lpXCZu|aMnJ)FZS?=;BA{0Ut|E%#C#lO$!QCb%- zJ9e+>J62%kJK%BC8FqQyY1g3tN|KN5!8g)ST*lZhg3V(S(mf%yJ=Su)UPkkeRm{&m}#_y%$ zc!a2`@T|8g47128$;SxO(QjrUzm&?&ncPfbn<@Utcidwn8V)g^Q$$BJ1}Mwmi;r&f zG@Ii#b=9^UI0d#^-Fzfcyz^4LQ?Av(uU&wwf{CaLFa^twD+^7IqON^@`OsQQJTAUpPhOxG!4-GnB>L52B=p{D)7^GMY|eus z+ETO9)Q4NjWl!z|;FQ0BqpR3B4dff&33MtmPej?vr96Am=wwO3h}k7ak)Ix~FZ)bn zPd0>;hi}sIw>_+oTpg@vr#YDEcM*C(qFJ}G8e${!Lg&u=ubPlH`DX@t?_WAiq#uFj z4@k987TIK)K*g)xRu*Cm9<5@!xBF60tcjjA$mhk{j~G6?Ki6ubT*DRI=8D%{A7t)T zMz{(-@w?bw{+`d$`o#ZgeS5YCFV0MwIOxlCTz4x=E>ry31)*LWNF%y5CeVyW{T-UD zav2d%rmx(Af45|~gHU8puaj72d$^PIuK1@c%WYt!i+C^FI!;_ue&idi#n}6>exBtO_VT_-&44QJO z7bt}Am!J2L^FO`4dG#7D$fZelv;Asp9c!R2q7j4xgh{UsxBvFqc#M6=8<+<6F0k|3 zKFx6;e##qv3zonaB3PfnUgKdMRDWrWR^-#d8KxZcwJ*Mjn}sGA^p9mr+FO%wGlWP@ zB#49AE792{H`MjyJ!Jf2yq=?acy9atOtk^7MC0W1NJ2FAHttGRV7w7v z>nZM}Q>#e7@ga&!eXU%iXg&qI&0(@rO({AxTdZmn3Eh&eR=zJO4!>`ab!t}V`u0XA zYW`~<^9PrRq4PZk7gE=2w^~%V+-h+eP4~u=tW-!GB^zSus1_jw+b$>eVq_)PJK`Z9 zGk$dEd2?eKEi2J$kqiFb)i%)atlS#Y=@&vlzuaF;1`DkY%WPP)iwyHxS&xuZ=FgZa z&HdfTwTv@`t3Rrwna2w$y7myMPN372j9ky?S^U9f=a0 zJpj>Fkj6{1*{_SiYsVuHyVM+Hf8pVf!6cwidx0eB!|%W4Pf?`~2~KV7GiT$^Tj;Vo z+4sfAzX?2ElK?gUA#}-eG2jTf2G6m+mgV38!>UOu2Tdc;R8V% zNv=)DAHMskrwCy380w5W_=koeA|A>#(2d*uFgcX7myJm&4a(Ip9HO?pLe7xyp&-Kjz^Tc;sgr`k>|#b6Ii#trMePm2wo{QZQTj^EbxdFlOYbEFZP- z8d$?sn4qL*(m6DMVOZcfz*=X4gR*ju2}ZJ0uM({+aFNAe-EuH{;v0#J_3gvtw>jN9 z)FW{uf`>6%%zr#j`=YM%;puSp3-@o_Ksi<~gd>;EQTZQrF$4u2$bWbO{`55@%bKCNfC8i09Q2~_?T+J*>8axu z&*qA68v+hawAl5K7VLb4qR|q_4tvbT4Ml~@5+M`t2HAz77s2w54)9_b3F@BQwEj2Pi%8`PGO$TZq&MFVQ$>{4^&ivjT0v%XM@$Ml_R$+k=no(q zho}SQ0d)Z#M)K1ww?~H9e1#9K7la^q#p$l?XfZ|m$pVmgDbR$b+G{pHv z##)imxcydGZh64!sfZl~4%i-@hbQQErkOwf*_Q!h0zWIAD2_|9>H%we%d|jR(n(Q-ZxgoABx#K{+cQ_cTG2X>f zQy?O~l-M#4MmE0UEL^qoO{?$};i92d7BSofX7<=7ze zOQEd41NK)hrT~ExQsRtqmhw*aqe-RmcJ23;YsW5ZmD~?jr6SUT8-AOX)gb4zhrN4V z{&~@SI?Q~Z7l-J;?laL@>yGHN^Oo121Z_2;1;P<`k;rk`xB12=cTXu~d8+#*BQUqC*>vkWfrdLXCk>pQU6fSr>Ek#bWQ zH0^wdH-Lj=e-R;!&Ay!WBAMDDe+u4|0aS#!GGm$lh}mZ~NG9jF0F@+KLt=gSRmLcXMf z3bg0#I$X42plOa>`}Ct$`u<0$rcA$m7ISaR$v2khtx~4!`dZ*&{dKRV6{MU9FG-tSmNO#7}y9xM0xRUU=g^YL$48iQWYPJ!Nmpa~#N4?l1n06z(M@kao zMnZmIxS2q(l^gW6%vA?Nng<8jlab}`-3|{E5|Uf33y~|hH!eRTn_vTY1OiUEDAp_} zWQHlGb;*7w5KA3c${tWURNN>XQ2)q%8wdIg#if4ePAwvW^ThoODndi~l*UPfK5U03 zszLy(mcybF1P4A71(MT69Q;+OpvMG4a_tVFUX)y=SaXlPfl>{#=J8^ zFrjzHQvU|P;M^<_HmJh!E7`wy!1G)M)hk9F`#wJ(W@V3O))i*^>2@aqUL38$8vG@_ zE{t8_kgE{Pq3kM%-lS8vVCBmNuJ$(#E7zivczpIy{3uqUd7Af@j7wzPpOOSU4o_E= zMAQ~aU-RIN{=ok%%xNr2#!YdD?~v1ror|1}x?_PD=Nni4p} zn5I-D7QbG8K-X?{2!|oabD`@I#Dd=tKPiy{hR9FJ3Z!ESq+gYp*ravi1hAP0GmPVK zgEqO(aM#@t8R}zs5f8Cga$cEnWrwdW6dtP8VA7pR6%ZWo0L-&73y+Tx<{s*NRB952 zYEB*+LSU6UyZl9iqE(B4DJA~UusVcFOUO_w@eNYyjYj)1Yx{fr&{`*8ZpoQt*xJjY_ZNPexgWAzn7HklWM2VeCY z*Q~`Ka5C`Fr3>JkClGLr>rqqdkUo51BC7V~g&NaOe+r(%C|}i zC)(BIhE5c6_f8bFsI?nk;|ChBiX$CcmiS~|J|M4tP)l{s;jNVFi4nG1>=EQAztS^S zxHxaWm_cl{`j?Z3-^GjzzX_zBaAmx`SC|WIi?R9{LO0+KjKxiUzeQVD%k;2mD4&=d zh?~Y&@zGJSj*E+C&qG9xPHs*_|58XURqL$1HR~KV+dJe{qhi&=1kA(nn6qa+s_)-< zVX-yxnEI_r-Zv9+PdK%tXrt1-kfE^GfVprrhjzJ;1dUPrOY4Kb|jcp#y(*^gamtRFqMUwDZ|NIZReVxJ=J zFkP&Rr2-@^}BNclCo`Q2j!43N$X0RGpHEK}qXziBNXXbXgw<1Crq zM(tCdM;?6OKp)RQeLmLG=a{RSSHzS4OI|LkQbDo90U}BO))_$0&BJp z=mLyWJ<=vT?B0dE9SPwJ1~5{hf7)PHw7|PB_}tQA@m^u{bkFgPoLSvT{ub7QV_MJL71rqN#mDppR zm3omr&z<`&`juGPD}4Gmb99`wcOqp)A}bQl@F~e89FNEN8Agyps-D8!7{8YGUA11o z8u|_SNDO-$?A-0X+q~wT4sy9io)c(HOd6(GIuaXO_b`DjB_=-Ht3IW$4L9^BYiJM$ zUVUuxS#0y856xa_x}VZAd``9>LE_rvsD^Oilx*H7aO(@wx!)x5^}($Z@05Mgnc~Si z+L?0~e$s$_B>;RC;f#wzw%nf?YsSfx?~|J^g4@#!yXdoWURRJ4l-%K(LU9anVgSF@<7zE4q%9t;>IWFqyU-@m>Y;7ZKrwWo41n-9fkij`iLuRQLK?&+k_gcoi1AzO+KM8DHtZ2x-S{Ik-74IX?>~;AN+;11I5gtFK18Sss z4KLB`wqt}GwK3nc<<92de17l#v!PU|E~hm06MIUhe(;y;&0Y|^95)6|uvJbG1NTNz z6XZ%M<<@h=R34fXugVQ{#*%j}FkjX`iIgpvc%S)QKJrepKg)X#XTsXoGjQ*LS{S%4 zG^Xw~A+Rg|18ez%oe;=$suj>0POeA{X&M}9>Us2cFy>TnwYX)Mul2OJ6_{`R_^b`Q z)R*Vi56bQb&G%zX8}ypvurHfFm^}GipZ4*y`Np1ddXJ0qhfEn{|KwuiJ{m7R%m)cO0=_ICh2v|2K>O9ZIEnM_gm zhZf9JcZQ*{!wIizMrIET6=IfV7oIRJPB&{AFO3&G_=*0`WU5_lJk4nK;g>V<#M4&` z3Ka`Mri*ibe=_<1W_tX+Q)XBrbMt;n7|YGFOXe!OV#rUfTx;h3r#C(B0gDdg zd%~P+*|PRxcg;z0{Q>hz4$~h6IMZp@0QK#t<5mz%||Wk zQGaG1o^PFSY=8Sx)qAsnb!A@PXxZ2b*nD!iBZr=?{eo#mz1Ru@&30pLnxRj+mjsZvSLH0-5i!vW&(D=*_eoYHuE51GauQZ0TmLOxzqz zi*BgSjXcdRv$i;OXgzhop1LE>ULwvM0CIbavmnHI7|Yo!>{$f%JTdFsA90bEbrI8g zkrQ~Hg}5vP-p$hvilSf}Bp0rTSkTe^zqJS`P$gd2CHJzZyjn zk;5-9|Ng@>!7aMs|K^#r-tskG^i=Qe5KuNPhYo{sMn{#xp*IvExjsi>Xw)nUBg zVb!xImnRMrmC9pf{%4ZA4Gmt{?H#$g{RN&NN|tBWb^FWxUSh6sS2D+$qxp{_0-Ak1 zSEl2=xNn$zwl{b?lM(UEn2Te-y)qJ zBRtBv^cwNgK2J+}b#gRL{sv}~phTi!lc>fVWs{^S*k_Zhqlj<&#z05I_N|dwl3oUN1#v+_fyao6lA~+%I#yo?E0|&hhDpV;}F5p1$u(FfKms~V2}8YZ+? zS2aMr+rcMPo96qY%J$^LP7MLxv|Gzk64gQ1qb>s-g(-0* zik_)o_i*{F_c7tJ8QHhfxDiA-(Q^Dv`Gjyy)1Vk>M*cb+>7VkKnFI^v9p6Z-kKuD1 zJEoiE zB?ch!or5%}0;{j;(S9fhO-(``piw=qRH`mFxYS4XdR54e(wB`2UhMl>UsRhOfGWz%@HATj6bF z$gM#jx+_NWE1dEc*8yqjbD)JI2)We4{l6mJ_xB%=$ESA5jt)op4Cc^-hI$#oNeam@JTkxy=jApk zq-?PrQ7%kjloS!lMh-y`Kr_ne=V|$0SrTa*44AAwPkDCD3iOXeC%Mg2&do294U0g8 zi4y6_E28K7}~@C;V3xJ!;&K-GCYXLE#@hmI_ZS^2jSn=q_6D3 zgwX{(EX&py?R|EZ>x580u3uq+lbRfrk*WmRqCpNe`z36NP$AisLAxZ5Vw0UBbp|+z zalt$&;k-vstrF&QZG8vv1}Sk30PaSF!0djJdjEbr0Z&Ak=}UgIlm17oV59O-Y7LJ4 z3Sv>W9NOu9N+ClLiemAIN>BfXW@op+Q#40;NcAd3Q$@VLGb9XbDk&UXg^UecSEjA&{id$6A0nh8?UE_%WEDYY2B<%hVHDgC zQUzO)Cr@^<+&_p02}cF`(E|LF_tyOQD1MH5w@Kc(Mcy-Aq`dNGa41HKn^xcm_JZ#u zsfq$`?x!=nqU+K9BLWQ1$C5;<)DKo;UeIr$>F?FZSha`%&xvd)^Nhc<&hAo7qM{PJ z=qmdygUCo?*Ogx!;LN&V!$8AFeR^>QiUmA9Bt$lNHBmvz^3nHF>P4 z;)nm{U2=Yp%!zuqzm+v%0!QDU71m$U6fd{ka@h{Jk#DVc48L54OsUmWf-ta`@(e&9 z4QoBf;+Y5Do#}1dwhB~^lg=K54xn?;&@FlZlzf%hpgC;-={X1163&01xxIcaAvuiY zSRf1}C2Ali)XQ3%gosCgev94axvk9)585cqTA&V1i*L50zCl$Fqi$OAnd+UKq`dD^ zkof8;uzKv5U@H!)Od1_=gv~o-Br6KckNh~2&V4ij%Hvs`BAKT*L4&QcVOie@62GT4 z{Ll`5SsJebHnroRDNa3+mL&z=-_kCFB$%Q+gqg05Kmjxd8@EC~SBIpqs$;vSk z6wW&ib{USkIcC!LhovkLG_U18Z_@Su6UWiXV5E4IAw(gM3Bq%P_3*27Ks0PDai5f{ z$|XI+3MhNXWWb>@7{&gD0P$hJA9%pwy};9mz{{S%n-q^~4Dpk4Xl=r6f*QOrPoSBA zca-hjlZYXt3p{!hc!mdD)CS%{P5>NwiXl+WhJM*6sTmDop$lf0X5@qg5=RD;*;7z1 zDc~sMZe_be&=|Z(%s@T{v5vXxO+i@&-P$K;PVvyR$K1wKF>RFV?XX2R(vZW4xCI9qN%*T$OpAtOzYTdeEJ&N(w1$Hspd$q0Ze$ifByPL@7M?N# zO~i|H;+H%Wv3exuaFWz=`?_qBb3KxBvX=s4Dp6qqb8g{1Bat4xs!8fm?|85jLYS!c zy;1BSaPd6J4wCTrMDWyt{2S0dzM3qLF~(kboDJfM1wE*q1=OkwA){NPahwQX`St zA(1vJk^Z(WvoDe9f=gm0k@ap8yGD|}6+VXqg<`ybjwIYJPpLZDtL(x>fTvI_Qvb1RxcRy4WT59f-9%4QmVo22<5|+#-zZD~XD@@^tA!Wk@ z^6H;{x*%l@a>XWiMBM5oZ6GX?wBCVq6ZzqHVaD_ZmuUi05y(_*Q)|BX@RK6F(>R?o zDBT|y2!-7jszGD+N#+kpUy)@h>iNzTW?l7VnJ)H&j%_GDSP-)Z;b&Z=?b)huir~N3 zc)zpZ7|ls>c$Z?0%>J)K4sCSKgCu;sUl4Q~?9tnI=>XJ6j|2+`Cs3sz_win8P`rYZ zqRYWd9VvVGIRHEdNPry=!;pG75tujh1RqhnA0?Pp4 zI_7&t=c^v#uife1K$J~=r#K0ZD=IyyWzf% z3Mbcld)WP-|3*%3c6M&Ir?IQ6*zE!AMhAAK=KqGA>@EE3nVXx#&JAMc3$VZcK~5%< z{y&71h5wKyL(SN+5bV%PY@Z#rqXS!Cf6&x~?L=dnY_LrzY^@~rD<8Ik<3GH~j~_q2 zfB*jfE}X#s5l)J+rIOfET5K^nwvZTGfRD|`#eN23KLO|Y+%2UE{}E0K3k&~)oXqFM z{x9L=%^U1%o6SToECz#p>2m1f^Z&DOVrPXl(Z%X&VO12%&CQ&ho&PIuVrgk+0%iYinz1X=!L^+`D&AO-)TzRaIG88Hq$95D2WS z6jodqD=3KN<-~HZW8sY0JM>s8%6|zb#Kc$vd@KwPi-Us&gGb>k|3XgW2n>5~j z2mhTnF>U+Q{l9pV7&nOokZCmyaG&8SiNu`ikDK@rqAWB?o{Y~7!(QT15~BBmZX z*;keS`vjW;o*5F?tLVMrcm{f9Tvsww$hWj|K*WT2*Wy4G!}KSQgw zY_`$+X!FxRSn*sdrhaHrtFC;ZGm?_eY_P7vx=IYJRd(=WKr=~_;&{gF>@+6*?l-g{7c-M z zKw26klvG4?-ub@gtaW}lYwbT_uV=64-q(G7%46?^3(Di}YP%R>z&|y1;;9@Pb`t39 zoOhzoQbEkfUs=xO$+wl7`pEM-lgiX#qd zm_}JXTZm2qCu_#hZ=C;l6PJTrajj>JnP6_Ap?pLFhBvX#b2$VvmRt@Mx_5qaEOcpU zglADnd@C(o-w7!#Ta-_(4ZHZueO!U0=&8)R@xes_gkd|!)tTx%-)eG9?;9xc9Gkw? z<=LG$6JXJCvBifgJU#KP-^y$9h@`ovtZErU^PD!n^@Y3&Pmx#~hIsuv;l*SMwoh9} zV{!SQlyBjx1XYi;P8vSa;CjS<7U)h06a1j0hSsBWNy6+$+%NUubL2J;o97?^%IBSc&K^Git6E04^iX&5&Oual;jjBhb##3C zD0EWKQBaIDKhBicS315$Pj@+dYJDt(Da}X|?x$R*6&(;gweU;+<47wq$@1&$`jhBo zc&2Df|UR?A{xIUMNb02hD^^~#j5RpJL4fM|7LG-tlzI9 z@Tq6WQqEp|P(=8j(wo5N)5vak3Z& zf0Hf$?%Njx3b%l4Oz4N3FJ9=sSI|rt?py;%g}`mais_;apD)^$z9$JnGUuHkk7G~% z=`NO-$(ERjN|pGhCK4tF%s46K$Nn9RBy2+AVA|d(x}$*v41j^l*WcrJSQ$5Fk9ua> zek4ehloFm-cY)`265#|@Fm$5kC?f})xl|POWtbu<>JHA-Sda(>XQvtiDzNVndGO#i z+&DNEIaXEz6qp&mN@nk0W|6;UNu@&7ewqH$b#r_pe?(?2OTizkOPo3}t^m4B!qwV+ z6e5`sgHWc$@`3OJyc41(_Oh-fH244jE#96zVl3bXDsmKl@Psl6AJ_V-X8v1ok(O{z zxmu4*81PJ!-_>{DjNymow7H>E-VE+Me3?q|;rCVkZxy?*Ib5h90yh6DFpA-Z8ObPh z4HW{QM6CePI*z_+srMj`mMkL7vVS_iaV^1kp>_)lMKy&`L71A9nh_D?cc#_LdAu9p z|7OTkSMy0ge+S*A^z(Z`+@HhMSj>sd?o7m&bPNnsd-$5+cqc&as|{W5oo z6KB3+T+x4A^*J865X2ATK*bRI%~jz+E0Hq0^C|jiSvc=C6Xm<-abmg=l$Uqozqnjw ziW>#0P5w^f_N}2yf=2nETbenZHu|KB|;SPC*z3pZEo?zUk&GI8yc!rITwg%vTtRZ{@ zU8in;s%Qxq7rzfgKC2jlK0i+21N+8@8Sg?7a|xW_N3njWVVv-aaTf3{BtkV7rw}zx z^6>5%R5qkpZ){0EcX{RBfXd;n`Pikg$^6wU7&^%hekHeIySgxrh3Sqx!pmOFcaKHW zU@57{D*&R^-tGZGJEIcdN2wOb`4q17tCvs@9UROy!P$G?NItoZ@w&k2C>IsQ`>Z%& zzZI=dgqgf>V6-@?D#;0Kg0n<8Q<#ea&_cxy7`@0ac(F&4(3haZhI%=qnm^b5qP~(i z_V}7>%{eXJJwKk%rKJH*^~{94P}sxq_XUvl(e+!nInxUPP&C1x<2aE0c3RX85YUT( zSCTG>SupU*R|*`~Ior(d@dwNAUv$w2d1P9@Jo@s>*55}kqTbL`0kH|*z9O|S8x|(wsIcFwv#u%Y>3pYD=HN&?r)=dbS ztoOXiD(5`dVy@fKradbN`gJhUlKd!B56>7^Zs()pC+G{*Pga9HavdTivGAc7q`e)T zUwcQOM4J;}RJjTigIz)5>)S;8?{PdM&T{!nRa88li|gW**O0Zl9it@C|?l< ziGn(|&z%u6YXmD6A_V&o=C+da|FT+i;&FN! zfiD#i=>zc0w5&o!6F0cK{Nf+_k2hhal?v~kS45M-byeZmNI2dooCpknu_=++D}imn z`fM5`- zX@|qC2@;C~z|@Su026<;XJRl*d)TsfG@uoC0Y#46ZJQ$*G7TjK3PG6F3BZULDX5iZ zL1Gbmz;&f0xsXdVRZ^@}5)vngoJsdD8$ABTKZy;Nf*#d;0oKY^)yl9}%Zk>-0uaRq z#7#JbOpQCpP?7S&p|*$7L0ppR4T(+8T-sbL#vHIHv!r&Z)R%!tF=D#^_DunRr%4^U zA8&LqoC=0De#nH_R1hzYCO^vym%B@-qzV)!f%u~cavW1sqzoIoQ`VA#SEa;sjz#n| z<9DTAm^5JeRgyf!jV4tMupy-V7q|`4_>pZ1)PXU1%L(P0q}*^QD${-0*=}Vbaa}5N zXCZwN7~45-C`fMf?amZvVkDVsBpU!rF(5jL)^bgXo9oW{w33B$39fPWMmsC0-sxj& zWpWj=zV6n^{=(o~Yx?WgVP3K`$H;LER$eSM)AyHlyx3}cLfGao!cP}@ zEmBdYj^X_dxhh)ue-bjlm*D|(=F~86?QhyqtNgT51vS5)#Yn@P>l`CgKzEr?kT4iM z2f>TUoNn{YT20RT<{S8|5GMxU35Ql!SfVNN#P@S*LrTbfi(X8)lsuJ$3GDb)NTi-Zb^TGWGuE^?{-F!A*66aH#hM{$Ds=2u(vQ zPebx{bqAzIxv1e?jHC>D-0yxH^ORr#ORuOwH`0|jdm#Lt#uDuc?6t-UnkK@YasimI zOlT8XN_9g|6KPXZb5B#teN#QnE2?{dZvz<4^@>9KRnJG6`+9APV?3L0nk8qYF;`Y9#hVESBMq41ln$KyKZA$7~c+hxKw2N2F}7l4PjN*3Py3*|=Bw1Q5#%G&ud@{9433IlLS4dGDj zXcM~xm-63FDjWH$f47VmYPew}m%0BWmwB?+EfWUoJ+FNX+qrl-IPnFyds=sk;y{%k ze~& zMyKukVTE|YAb%lD(2{^9x#N^4PhYk(74Kar+iR25cdJ_OaHbRRfZ2~TvHlwPY0-9m z(CQ4vr&0)e*Ym#9w74@O3`T2^!)<^Qb}C5or>#OI&kO{ zIAHQaKBBn$Y^uA0R?P7aWhQ=yQdoX;ajRDn&=(HnL4p596D)APXQR%n4C_6smv*Lo zPcPB-b*DFKNT2;@hb1=z$b|RTASTJ8Hzl=qRu&dk+%rAh)g=2qMh8X$gZj6Es53*9 zGCM4}<@7-eX;cW1tq_upFp6Ke+`j{tSxl7^TcR zM4~&ifdAi`N@y|`0MT8G!1Onuwy%bmHX>R221xscq%Hf+U4}pv?~9-#KA3^D=76|v zkz{y}Ho*`p->6j{zzYuLBj{~E9lc)|daFF55gx2HGb&{{EJH9RM*#Sw0SQRzo1z_i zsyiB;JZRC}V5K{(*F0t;H!gQp>|cQenCm}gA2%8qt8y9jlFRdP{}2#9p>sC=8@*EM ziosl9gV(9U!tR420Q@rp;+0ki1@A=MLr%Qzc(VIMCBf86@^~l#Ad;r7YQscf>OULC z3Wa5Vp~^5bS(=tzE;q)x(TmqRg+Dz31puhia#CidhNf_9Bt|;Jr?CpBKle`G;D0>V zQGmj#Wtm_J-rd#&ItOE<81Q8cfY+W$v{Zp9ZyB3OE1Bh+lzo^1G`ILKlzK)30Na4= z$@evMmM0_>`TwiK6h}i+4Tz&#Cyz^JYv0fI^%bvg%zfB!4i5haXnpblHbZ1(d7=c~ zvV`4bz5)5*%_HV;-FBvnf}*r^84pL({FUrGdNf#-iCh~ruVKvZz|0H-7wByD|xy(qPKFO z#{`3Y7}uMpc)ii(F}QcSvD=@rACZCiRt)rgJ+CYb=72S(Z9V_F+2*@^d;aX#YwO=1 zzrK#x{O~$Iu!7#Vmtgd4d+Xyyt=?BC(b5jR?V!hw+sDrZe^<_ia*e#9YcYM(?Ator zU-33}Xv^Gi75Z58H($N}dK3d(OT}7d25sqVENN`F*li0ln2P>;g5qT$bY7L5-QMwe zZ+HP%wrv@LO?vci2(--5Sno3v?DhTJx$xMujojLdprx7X;mM>23lZ2@94fuo+3r8E z^c=Ca_Co0I5-J=TZtm{`v!4I}tMlNt^+Nb;wDN3909xUQFmQixeHybv$GXK}t^?%; z94}n1R$A@NU>`xsj#Ct@(ir-5TGop651FiKy)BsBGO^xSoluq?sPP?@dj?mw>}y#w zRF`eFFzo(p%kUEdHNEJwd4K9fbm}2@8u#q9JMz?mxli-^amW_K!W|fE9uS%tvO9Ss z^zoa@_iqy~wzmYrgCY+k^v`rXzeh25_*MXyJTa%&!QtPN&Ohf!y6+=W-(txkyR#xG32FcsmokzOrQekotG?o8enIBNa_WKd%8S0iVE7 z|7W1h@2ag!_440|gTGmOe>n|a$CY1;`@DaW*+OmL?Ot(5^yWVK)9t-a9sp)@ZDR8a zlYK<}XSVcU%$6tE3ozmnA^a99>?MrZf`;MXb6mGFUTF-Hv%Wd%^Zb)Hco`!MLR!Es zbpWXHTkTZFgh@LA?B^mJFa{J+GZR>y2_N9o0t7Jpl=wZd`-%n-d#ym?QuBrY!B86TE**C3P9d7l?>(Qz> zyT4$d^NGK`>1*bQwL8gbH%;Qru{*qX!k_vffKH@?*}+$0K*$v}A}Qf3N`IAWZ0fe{ z&}=v!!<&?tUE0;eksfVK7O*@W%b~O|O_OdrEao|$Sw&>&4cd{l{>!ng=SB}q@%>>5xYj2bxl-zGsAy%|M?ipzh6Bww~RmJ;IWlWHw_R_loi-wMx<1?(psm8p6z!T3VqI}QK<9nwHKRp2-0 zjF2d}O;_}js;FL`s#x0SqGccMY~g-R@@&BwxDmi}tjW@kSSfZNmxScHD~zGP-)S(a zp?5SGF}Nsz#`@wp7m5D`Xgen44!}g}$~D!956G-`exJ_MHzzIr)Zv}UQziQjAxV7p zx9#SFz2Y5~lItdQ^vB+;K$Ob2!P8k)4xvT;yW0XWZuA_APKr?um z0^rV`CdKY<93LPvl)z#Jy5?Gb`ZZqCI)v7UT(;C-cX>J7XY=Wo$dJF195@>l&!MRx z0Jg#N>XB=9mC9m%uuID&5F69ZH_Tw1B($3wWCuVHMDhSxQZ0uIF&wEJbu3A85v!l| zf4s?I<_5i+X$1B6+;?T~|E%^_SQy5>;Kr*EF0`W@%Rh2p*5@SpCs%1NNQnN`mJexsq952iIGq>&@;s_PZHDS{u>MFz8OZ-`)89+}{T;cFAlNguM%*X-;Om{un~{PBn4D}g>7ySt zss;XYT)NGg;B7dR-dz>;S4bUO22;)gpZAszrzeS*QWx>mOcNAl`EI5uOZokbL#HB+ z42&SbGd|$4xMA773YHgQ5OQy(C!R<@OA zZN|A96L-Ay%xHlxdxL5jUw*?3NBctDjDG>;(~H76Gjt8?FKi6x|80g-`8pLFe8`wA zt?%plp@2upk>!h-yl3EiaVU}lSOj1WQU}&amHlI47fMk-RsyaR~(CqWQ$vAcyU37OlsDGV_W-uIe@+ zWF3d}ex8`)fwcCMf6>)2w_(}OMK(71WUZy3&z?>G@qBu?boFq+_N@xpUw2N<>JzQ# zSi=g14?LzZu8%5PvKzjOosbOjm^f%(c~KKs{dT8WUIgSV`iXWB!( zEV-pUR&F|WRL$vWRg8n(4NmE&qFXYvU8oP9UK+f;I|JT5y!@WQCb2Qxrk8$y5$Z&E z>uV;aT|QqvdWNrK+ho*8Bu{J}8GB7{O|;wl`Ie**LJBPYUCs5URKE!)m+JugjSfun zT|}@F?Bv!&6Zvb#IBNM--$p)lh6Y;1QOfNGC9kj$dvZhy%j}SKnF0o z(4iBD&7A@d4hFv}dHb0_wpj4p1eOZMgn7O6WtNEDv+lb2TQ*rbo@kD+07TYVes5~d zP33Ks3H^JKC{o3-(8trb-S}`sGmegkDtUXI%LK{!LR7c#-ZeR$ZWuXU)isX zBSmQFT)cvR73Jo!aMy^_nUJ6Sb~c$tV(4P6!fgR(>|Pb&@9}pGg3qs%$vaxa0iN`p z`02eHR2qNYvzPr$eN%c)ia7*u8G_#9Z|wd_KtXa_J&%Y~z}|yln@0@6L+cTHXZY94 zw%4V;SweJETS{&=6;M^=#ITSe>N&gFNxNmsG*)h8?X?dDCByR$HkE%vBY6>46Gz!CDZ;ZROl*$Y{xws^chCFkclu4PpCu81`yNQ(kYW9|LR=mo zV4Dsb`FD>lCvwIDSXm7GdCrgJ&!64h>{^w?i}%**xq^c4K!{MHS9CncRt}AYBGe@W zvcc0+;D4SgUf|*4S8-x`%N-`zaa2)1@1ZPQvbe2DA`@7=Tv*PqMB)k5*&d1^oQU{s z-wgi1G_5i-IGM^2%eFF!pq1HhTZDv9IS`cE_#T|W1q{|i(%%g6pTU^G3cI8OyQCvR zXE=mOSTb;h6dVBhh$W%cc8KJml`?H8qXHXUL5;Bl<#cHYk;%kJWg#|YxR`RrO37?v z60bS-d{{e7m67f`I?x-;zc`{*BEe8o&a}}-aV99$+@4ubCw)hsqB%rsuBs>2`f!b0 zy#`quKq)g-wUHk_Tqqmm2$|Qkk|1A`*5HseU>19tEYg%urUo(T*)Xm|vkTx!>IVlt z4h2rSKX0qJf}d-Wro+4Pwl6uikPuV ziU_vSD>Z-jPH)v#AHMN$wq!p7^+yk5&S}cOL{$^ISsa}~Z|qcweLJ5njwkftMm}gn z(T%`MG|>ssB+@u)0B4Y+*^u7ZxRh$&3%`l19NeVl3Ei6Un~^^7oNUTO%yaK1&YQ89 zWMi45GTEb(`9fMEHJW8~s^w>L2BJXPd&p-^RL(|Oe4k4Aj8@6UWEpa*JWV_2El!6> zC)S*Zox!W>hY40gZS3b$b##;UIaBR5Q%Q0>sljax6*wu{*dhDcZ*R22&J=aXrh5sp zT2(onb2Q84bc)WVd0&#mstQJ!54Jpr6oaMv>}Rr=rU!3yqI0HQ(yH=BsM7Z*o)~cj z@X3F8E70$*>lm&(37&bYI^*ArQ)}0hpElXQJ9Ah)P1i9!=dV4-$2}nSaZ>f;XMeqv z<5ILX&D7CU&DOr&{_iQ$cD=Ql(fPCKMz)U=Y(t;|&YOzp?Ro7fzS)|zk19I)2a76) zGanbuRBJYL6Ul+(AA%ma@KFkBs=jb+hrK&Ld zObL+}Y7_qY71FaILn@3WVoV;N2tRxxy5+&=rLyFKREN)Ukk1L7JmG$)z$35Ao34Xq zQDeX_sOM@(u{j z2&?61xh4+jxLojMZIjQU2PSy0b(}wHxs+F)~vX&f5}B)k+WgbUDQ8ZJzdINd1yBaLBtCN)5dMCsGhC_5Iif6 zSj@$VcI&B`m0l&^Gm0lL!$>RtQ8bz0%qO^7cZqKiF-F@7p;U=ROu&?FkaaLLXfB?& zA_*9c^b}IprYdfiE|#ZTDGcZ@iWn)jS})PV#q$<$Pl=nkU**zyR_F4i@*IaU8tFEX zXn~6B6v7n%B)Vy)vKBzZE@J*uW)L{U2&gFx#F`0-K_nTiB#3PT`2mW#AxTMG?Jwrc z-a7ET<40xCKkbrFrn`IT(A_%Syl!prMWEd*)%icX#(x6oMxBgqm%{&Bk@U_vwX1^o zeFZ+t1eAFtY2Xe&ki@ExeN#Vv>jmOT37&bN!+I7Xj!itl5Yqa&+ky_)=Her_7ke^g z64;{vY6go_oWS0r!d;mlUTY=PoJ_|UE1gMT&uFkWPNE4SW^azz=vhfe`qpdFO-ePZ z(09g#6M&S^7MmE@?EvPHN(#G)->*b}nSC&%-Wr+bS1Mrlyst9+IP3NS4w{raMojKZFdgNW#B^ zZm^OcAc*j|W$6R=%+7WwtPmL=x6+vaN+|aFg{sFhLW-ulM5OllE6}GK84+B`jv;x@ zg?X@sJZ0=?_tiYl-xMNuiT2=VUf7^l?cJfFh3 zgQWS0!}lqN=?&Irgu9)8cQPgpx4$Jmhau7Tq6?o!)(wB!8hy4%@dj(GK($w#HG;wB zW=S~(gpGwXz3nv3^F=-wNJa{y8X*#xXgic>ofwX_2pmr79ZIa6U*G^FGz;d0kxGB{ z@FNcdQV((gQ19(TA2V0)ZEULsF*EMtVvg4(>c?gJR6&1FcKO?Oi_zitp`i+h`3lrh)62XS;_bav zk#zo+;zx7c-dSg5;`i^FR55!htJP&9@2qhjIlBQ6Kq&!&MTsA_Gz6vyNMsTO>I5+< zKz@t!IO#kz@tAdU#Ca&=#-LDAw>Ti7jF`6;0Ah(NPh3j`GQ|vRY2XRA@rLvg>7dM@ z!xucI9%a}jZ)UwRI#=#hfqXBv_){0wK}6}tC@l^G^03-o774DI&g zlk}}=@mf`&l2~#4PUM>j1H>0sClmVLoBHj1PqLPZPk}?6GOwitKZia`lrTcN2}NTB znz4V^0IwU?4DLh;{~W5T8STrj1J1fuehGK6q2Aa!tzf4HXn{B>Wc&u+LlnxDX;!gI zo#dye;kO+a@Tnz3?+4ucMbp=`w8n}$z2ZI5{07d}deL*h1}Kg$>mV=1v+HZCfq>~osEcH$6V*4Ij)A8jug>(8UM`cahTv(Viow_NB_S6x=m{h z&;carT~tNfg9*1d0C@tAbx#PKETSUSB@HeaJb&14R_Xwu1- zPgKQFIuiu~So{kz5YLl^Gu*8DPZcyyc>F!{V}sOc`6BGpyEaL6hV_Q8U2l1oo6Wm? zJ?_MshD{2o?Cb(eSU$8+#5DcYdi#1k%e#=kk9!IX=u`-p%My*Pv+gFqLgOp^?!4F* z*UW9=JHGQ#8s#3;ZgKxDayU~YX;ae-V}K>Vw@XWt3cYO?V@+&cBPQ6}I8+YqM=uie zv&)*-zniZ2p3c{Zg^>t)_E8?q8oU(s`u>2~q9l;VlA=tqWx{|C=Knq}{V~1J{kHZo zvq0h_;ITKwTts*KUGrrdwi91J&+VW8c#|Jrzxm>68Gho9dhnT&%XSZ13(Ni(v=k>V zePOQHCQVkUB6V|{A9gIg!emEfXkzn3F~+@0ys4GE|*)|EJ5Gh(}61PMNzeZ~Sbhqp7LQ-wo+vlrNEFR?$B zwZ=X$bfzJ*_HV`TOi?f=k4+1PM!Q zuK#!w85cEsPY1`K$oo2O?-FbW5Vt^9?67&6dCd+T_nAwRY53t}Q+V{+QxeK;OCv7T zBTHa(72t*`qZ;u8bsO$KFOhm+vduBgRm zuv{HHEfQ30^vjVuN+Tm-#^H}q2}g(yeK?Wv2g`JCu%=2J-NAe(O)Me;o>*ZTRR*}7 zXfA^kM0LqYKXZ&=Yf{+(60@b_=*w0%9Vs>x1JHh2Dxww7o@dB^d594SnjYA6-H5RM_XGeUb@yJITSI<+_xxHa=hM_nLy9#P&seY656klu$Ui#b^Tcxdkels2s8{aKN3#Ln8IeKGQ@R98rZOo z+8Atzwc2F5#33U!)MK!O$CeaWsSEM0XK}7-a;!9sdC-XcszzBa>nsp=^`byKpGT_cB%A-he7%A>N?iIYXP!a~f9e$^Cr|{MH6_aYRgf zs%|XJrKScyvNaR8B9{KD-~+xuwxA46cCI{Hcu4SmhydMx;>%y7LI%!6$=dz!Pr6~y z3tUmLdKkh=AYEpA**G(WGtc}U2T9Trjql?RXKth#r+N!ZcWPL0W4U3+b;*wFp;OU+ z2gaq?sfanhT=3s9e#T-noZ%wHlKao)P~^JtQ>{T_K=U6ImfUV^R5TF4hSFdl6G2A# z53#%g8_FJF>%SD*L5=`Q4;3CwD4EwL07`Z=Sl8-cBqAD3=KUMc?zq(K9&u{CiTC9_k4cMvzuS{?JTT$~ zK`rlJUIeppsbVH8sWV)KW2_BFyPGwcTo}dQjT^175y!lEj8qY@?doB-BP{#N=d8lJ zHlN-3woabk)#%mQQhVpSmVk45-JNWk{hfE6^!&{2&WY<+om~Te`Mu+KHx@Z!-}K8` zBDz34hLzD|!CC^l4I`;^{Hnx#02E`VZI&@IPB`ZspJNowV&(3;zCivTmY-6$x|)KT zC|0VOmwUE;a)?8GE8>Wj-IiKTC|hpM1x?ZTh^CXJ?%OL~|FB0*wwZ}!xMMT{C$@$F zKnw$B(>R{l7ti+s!7RPms2qwuG4NuzDm8e(fhdblD_hq9T+)Zp1z)t2s$SIGC||@G z#m3s+jj)e2*uBtEFZJ|}WiHvq26P&{NF>-MJ1DqNBE6NJ7dB?euQ4X|0|NMoAsKItaS82<&11)ykSPpsIb zM??dwo`9o`lT--Iqp`($LL8nJ-4#b#^kq@B&&=0pXVr{+8h0>G=f+;9kc}>5S*5T*lgK1x04_5pO>eNu$V) zFOXEcpB5iLE?PB4omEP({s)cxbJsIYN4bF&7%zJj`I`3Krn{_d07m^N87`Q}~`F zE#2>d8P@=dK5ve@+=+I5(J%D)-(M0oo~-2iA>kR`*o$V`RGFm$%QvmwM5Q*x-yTbb z9se|$j|A+!Uy7V~bX(+{Eu2 z-(jzCNHdvDNsiHfn0fEI@fd8b+V>(%#oE|7#8*#-x*iyNS>zuWZqtP?@N}Y_7k5`9 ze1f`)nX`UqaMww?CaR(c{SAgUB^kqm5BpC~)aA8K5*`-u-5#wSgX9M068*(u&qnJ1 zo>BV#F}!QLBG94&wUnP-MrocfT-MJ4?tdLPss272->k-lp4MBq)q z&z3pQPB`zmk_Nb{478YzZMdC3gLo{&aD z{{A_b9l9L%Q8`}GsJ}2Wz&1ZnY5Q^qp_T*R1e1}6CKD}yi7B>$hUR1MtRC5AQ8<(X ziz)}%5$c)+&Sq2zTH_QTYeHQFh36bu;Kvqr=0`u7@L+Ls@2xI8$e6z||BhhJEU;0B z6=pFPW)JPqFEgvq0qK=@wdC#oRc`-l%f^KzH_uZ6`w9dqE4d!AfCOx{_E*bpSIZ%5 z6_XY0hAdRNEbKkhB8`}Wu5Ie?bdXU)VKLgHWNNycLgwsUA!}L|N960BqL%b6KGRXg zQGL-KO}e^Ke!E?Uf5{N!l<=M1YJ_?hv(dA*qJCN*x9VRsNYjV#OIVDo? zIdO${z=~CXf)(DxtUhD;ano|vs#JEFnePFsf}c&aGhXF;8L?+PQ}<|oKq7s(<%DgG z_|Ix#-+i@kt5aa~3iUqUz=$FrK)bGnf2vH8!@;6;2t}ss$dfu1&4&U6E zeH!ba!ovRS-<~O$nR^?!76NXv-?Atw+|x?aH%DG8mESyJw05+moUpT5o7U7vf6x{= zv@?vy#lc!n1}r)t0rNm+I>(PWhptVBL#>By*fnYsjDJ@d|0Ua-mF=-SsL0#b+2E-= z4Om$^#$!$B3RgsHM1X4_g&+A3b9Rb3u9zK}5NKDnqPV?PuQ%`jbVGaIs55WYk@iYeVk3ihEO=e?wZ)3v*&<j)i@W{iC=40am{2s1!<^3Uf z*Z~DtoBSaT%B{-Tr_4ma4HzBf=R=CsfcC_=|3H*BVYNA~bqUsXa%(l2C7E0X#RbEg z{Rb8`W1NMis}! zAa_nvwQAXxk7uh=zp+9fJ~uEY+^#7+CEEF4ELI8B&XQq*daQOfxe)KPgJzOYD`B2V zj|d3IPf}6l8YKxH(eY3r zAUQf9{#heGA6N{)^D^-K55}ypH(QySctfGKDubpq(N{y?#xcWRnd7jahuALpr)Z;}LH4t9B4fTfTxE-;3Ux66J9^xeBE*w=`HFUiN&)pvjDVa&v z*14*InKnr^e;hj2ge-IZQpdxGJ|p~xj-zW70_V3r?rxQJd81_yx5@;)`_^i*sAZw; zLtM|LKgEu#B5-xEsMt_TVxbOuj(ns;Mo_N`SY#CjRFNA&Y-;e@BE7K_y=Pdwm(nid z0)`bWpHijrKl;HGa&<9)_W_de&D5Q&>#Yxh$TzWW$C3h{fwO?{XB(s6@;LE<}c75n&A}9Dg_eHI1d_V35*AH(F(RN}* zkv3IdUzZWZU=XhjwvYyxLy(92m#WUgX|f%pW7%FH|3IL)o#N{yBV~!|0~QHc2bEKY zc8-sFzpq*ie^MR2DS^B3vWWB`T8Px^(}pXvRN^|1Zi{482RoLV$n!RVQ?t2{E77MP zj&+spB79{9FGYTd@M!FT7WHm7JM8H&Xq{+LX`2QZ-T)XGuIMm9kjzqDDHUJJavI2u zC#k+#6#W->3ir1y@!vWV{lwv~)mJ0pU9DvF0cYb2)7Fiqn}9g4n8cCj3?V#zjZ3HN zM(!!MZn@{<5n6L!m(S@N`MZW>9UW?^-kKSU#3SVf9VJwYdTsRY5Zz)b2L6o>w?KPy z?ztLXpCHDo zK`OB!)48z~0O1J8B!q7^qu<&T6F7YRVaVvM7zHLJ(A8DHHFidM0KTryUp|+-oy~bm z9~dyS)bYfr({Uv5QP9ua_MgfIaI3UogdpTrdq`cf)3dij_fNBZ94_LqA;n@k9pkMp zzQm+bph};*aI252WPE?)=TGyu&y0fHID?2h17k^kWY7OJd)WovlQ50zQbqdrLWHz&RZ3c_N``&8bh1HWCDm~)1{ffsf4shq=!$=f0ek3f@E};5tN$hpNsF7_LL<7`b_IzT$NJDQ&{joUi&~K_#+KgU}~@dfjd!HNCE9#7HgLv z=~ng+qfN_(qF0dOy_(Bk&yHwSz71gNiso zXwHaQ66x>MsPY-OaE8r%g7fd1KW{mnN=aA6Py>`;?jQxKm>Rwyk_e^E8tDcvwaOn- z1us?CIO6meL$x!H^^bxYyME=n1(bKGuy!NZ<4VxoKSCK;zI}dR*#P$2#{_*IzjFo!|co@MrKNk{=!f&*=WZ&b< zzIr2D`%7A|0rbx6!G;?p^AIO57nF$K|GD>GEl28rL|$t{s7EjYr4l-lDy{KTnO9f- z&(gI4Fk-@}-!QCKWKasP;-IRxPi^B7`CRELam03z{Al?GM|2FK@es!a7InA$l}88r z#NUn6yH!!Ntoq`fV2$jE4YFVo2qcP}k(Jv?l$37AI6Nvc7s`9G3g4dnR4j?ze>{-0 zE{6I4K^Uwk*fQ{Mbz|$<$JG)GgCjPZ}aDWiR~pbBQ46=F5WR?UnIN?xpLO$CUiJ zw?%;->yj2x0ep92%Ui(6TT;lopcpRyIwpV>skc|tY`t=R(Y?gt#!}lW`!@fz=(Ddw zQG+i6B=_gS!#cj@6F@GnadYQlI)>!^=6{@OXEc57*I(L+q9H~B2^UTnoyeFBh9E#v z@20Dwk;g5cxtQw8m4Ci$WujYleKjz0XF;S&sAn;vi0$DE`*1d8cJh)O!YrDH$T_^M;@MC7D07vix7Xm$eOALW@T7kR>ja4;%iIQhta! z#+g}5XEtfWVDecjar!nR9XltW&_^{Cq7c9HtLbmAnpu$!XLJ^%t?WUp`T5DMRc-!zx zNQy1Gx{j6mUP?gUexv!z1^)8i;_}?87g7R&Rn*$5w2BEB_ZJ1X)*ELOXVj;@H?pN! z3p+|+7mm6)A443SnB>9&EM*llu;5AbL!fIyw)u6?V?(3aA#=NxtU?24rjvzpI~E$# z;q%Ry0E+(ZEN@Q`Pu}O3PYCajoZ-$W*R?Hdfc|9i{icgTQ^yOpMdbw5ojVP%_KK9D zQ8L&vb;SBRnX;;lObGL>zfW7C*H+T5J>p`eO&o1&BP6n!v1zsj6BcsDsRI+39F?vr49G>Ap%xe0RJqsLG=KASNLx zkMGXSAm>p1iiBi$Pg0H@thV7uLP~AThPZRO&Xey6sjZh*Jbyh!m^*hty%&9Oy7asG zVst>XFP|z;IGl$S5$-ejjI&&!Pw5+)<&VuR*{ObzQkXpz0@!4$_8O6S|M1;2s~0y` zZ0>kge2VR$nUb7%9_)2@BxLZo=ziK<7Z)907_%?UpX>4|`uGiy1CrGb&ibIj;Xoyt z-Wtg?i+Q9ePDePlxu3?;0m&W;p!mi0OK()yWZ*faYZ@tp-%dGVFv*Qz!J^(%1UQLp zuz$JSx^F&CxCTRms0p5AjCKGU|oi;9v3wOJF&~z;6D{W_wTC@%`H)#)~h(@Hd;0p-PGJ?;rHBs{gZ5t zbffvd^_PC~N|CO^(=M%iQM@z77vTNxyiGwB-HtJTXmLM8GCo-Z`_eA)y z+AQNCfi<<|lKhA63ER?Ns@ax+h^xs@kupzR@vYFm4BoA3PcoJ^o6Hn=SB|csftRxa zprwPiH-=Zz*-zgW7iN+vA>^dw(|RBZP6j_RxKw-(+YIJ#qB%%Oz*D{($yputymO7~ zw|sx$ACVvySwLG;93k$0r24ca?z{r7R&*I0Q|&SrpKRZUdJ`TOd3XJ)&m2FR^R+)^ z@Vdu2nnTAz<6}1a=IamVLJukSEn2odSFWefzQW-&`djFvQx!%(+*TX z@Z>EE5rvxygH+X@9ARDgXmq;B+~+IUp1WImyxx-`_pa+`m)r1Cs?!m0bkz4cqP?Tm z2n>8eU?$H)T92(;{s5Tt$2W^;6=puzLKUU#u-+9#*bvom*ut=Y_@=ht`gr%1yAPope(%;hdpj92Sf=2OZ2!Qfz=HhNBD~fUt6=4b$VHe|q50 zd*V-_zQaqW)=#DqgNw5be9@?r8)TfnzaISJPUk}?O>Be(sKSQ2Ye~gTqpf_$De!WQ z38J7g%6`hIeTyX^(H&DQkLnr#_9ddn+gD%Nt_-p>sxv0V!bu zwU46Qebh$mE;zVxLzUQFpv$lh{twM3ell=tg;SlV`Gn}g)v?bK?4iC*qevMquBY3# z1P539O5H->_?H1fjVVQdevj&e<>nv_vAZCEDjvz5Mj>&_#ox9e zfciA3%zxY0x>|$2KuVG)*m)yUg zjk`#3T&xq&&>s>0j^{eIAR+j39doOy0IZ&%H((ybC}@Ne%_$LvB;Zh-xFY1iy&q@a zJ6<^wXGetp6+AfZ09?Fsg-(Jj zuY*Y*hh*(wUwjT)=RWB~ak8!;Ejt*gNLVp3jh2M2a=;FTVZVH7EHn?(=5 zuD)8B9Si#TzUg2T^f_9TN`$Onh1D0JAd^xJ!Ex&OgQM_QmR91Y9qGvs6h@f%BM@B( zo(?XtWitAZ0!LZU%P4<9b9$AYcZd+CCvneK{#MNGEi`2(Ey!Q5O53^fc(mp$4?7)E z&KXFPy}~i?&(wrLn)sLd<|2?idxn%Q{QrZHLt z4ffzTc3Wr6h?GtYI_EElGYHG^)tOZ^grP59^eD=ZLidOkyW29hCNVC7J7klln=}wW zf^3n`3qVn}^!U5nV{zP$B%Gl%S3TDUcMgSk(7Fj%ch97}E~`P+lzdmU`7G2x)4N=Q zs=xFSPM5~G2?$Xk9P@#oKqL=HO&$7oSRhbO@ZCK|kE4Fy1XWHvO~HFQWQEY}Y6+uj z!#e?vA-NBNXuOwzyy9zuKj5O3*F?=V`KtqI2vpl#W<)9FPzWXhE8+oyxLutBx{$$q zZw|ym54go?B{J7R^?cC605V^Yze(iPFQZpWkA#lMS^mD4R25U%f-k;uc>}zb=pnn7 z-XrlcA9gg(Y7do`PL%mXAzXe<w?6*p(A5$g0>lst>8V4l{Bl& zgj6^Qn+#n`gLtVXRNi*?dT63Ve5CA^HE=-)3i`SyN!?J7oB8p+0`JV(0;@RH5 zmj3N5m8gG1M@*d+cO~T(=bHyg>4`Uf^eU~r7OB$xGCd(6KeE$X#;ZD^xUHk2P{@9& zb}cf1w827nIPT^`wE{kK#I zZ%INvq0Cn~xA73A8bz(i>%r2D+lganD-hrQo!{d(ALohDCy6Tlly-3CSH~ykVTOi3 zY6O0g(oHh+9IrB%)NH*jX?d&>%OltIfL|6XU4R75#;JZ7)~=+#Q~yb)-Su7{rIrjO zO6R%=Hj($qEmG~GET>UjHUo7QX&G*Y`+Q0Ft~{DsuOa-^zZ=P;Y(B<&$)NDwMVGu* z_uYg>pn(so+XK}p#l2&`q+{hmOJPXT{rh?PAMpB8ZVxLNWIj#k)gQO0$QU@grK?Zz zYA0(H-ck;;&|sS6l|<{BOwC{WHIi^;f{L_!j!!0?Be(-#oGL^Yv{>;r#*zlg12op&M_#Y0)zhflX1SV^h zOJgP2X>#YD$Tbvi2G*j{O?MF|o-SiXc}3rG!g6Sg{4aG{{0&F#=JbONtdSa=exKFL0*XLKOE&AXNYvcbu6k6iaQld&AAwcdAknmVzK6tbfy zl0Y5Cg6gj}WleVLY?-D_PMo>bvC{AHj-XWQFNwC~j~!nAV(9m$gikqhF+JuzeeJ;W z-0`I&l!si>!~00a;Zgl-TMsQUJK$a}dsLBY<%#R2teeA(;Aq0cYBJIQqgjA*e{pKh zKjZcCR4Nd1Wr^5WC8d;4_Qan_I`~vAlE<`NLemNDl!rPGNp;GXyRY!r+bf~`FE`xX z-Dl&Jr|Gd@&cro*Ep3mrX*NcCf9Ca zK_0*zZ94ea`iEzNGjoh;VC1LN5Gi9Zne(S_EyY6Ccxcf!N`axthEckW;nkjz8x4`h zjmZy=l36N+)Q~JDk9i1^D64N6_+L9?3opL~=H#!plAm`+278T%DV#+GI0jh+U*RFw z-h>*Wd8HC`5elg~EP>BwJwAE8saMbo?|dmtLdot$C5zehPD`3la3VF>?zeGgx!H6{g1?wHcwB8};izMT1x+nDBLI^HCMt$ zQ(9Uh*x$f4%*;)2!YAXg5nsH@8jUMA&dY*D%Pp+R=jK}%y|oS-xEQIp>2N89fUU!P z<>&bv(eoU?^pZ`_DxbP4-6;Vu?v}Q^({zER&<{@!<5ahd)I!DNw_eFG=16dY{a8z~>IxLhTdky2@Vy+00(Ie?!tzYwj=9_;?i+ zofnYKHxyoJyniCFIv>T2OZke9ej-=0oc8g9PoC)Srs^AyYfTql1!ype08UtGrM1Ss z=9(F=rU%U}UW)f-exnymrOa0ghpb53GN`(L=khl<2{w1IWaa(&-M-COoPMwP@Hf)c z2tuJjn}94MTxlsd&CK|Dqqfwmwlckwf3bsvJ;EW+1Y;qdhpRTetpDxZG4{Kq$fWh5 z*@MTvIZsHE#Cg39fvguw4b=0!&Pv_o%|#yUZVwhIROJV#c>n_>6-6SmJGus%*&EB= zU6|SZ(57K+V<7Xg(fhJXmqIWgC zNXSzyeODlrnxxJD_e84lV(vxf80!qF>CDid{E^nX5E9ZPjAq(OpMTJI;>xuT4r>dpq$y}qb?bf>9^m?)m(3iDY)f;o*(<-B$ILlzhuX5< z^GDKP+4)ui#TT8_@ep4XDg#VEl*c?lm5k@ciu3%^kjlo7){Xm0tC>$%)qjDGEkX$Z z?n;Z^T4nb2J$&h$6}brZ$DhAH{-}_;U`^s$w?4nwi&hycR2n{fCuFieW$7?&w?FOT zFyjpc%5W@u{_Kho%+b&}=Gy&tZw#K{xmvJDB@5P&{vR1iGfrn2-P>tvsZ+_4(2RD9SrO3gg*oV z$TAxDf8-92`s!2H9TT!OC^^v7}%nxYS{>^#f%p$6;+8mb4|xd6smpQ`wYy6Eax z&PgeDR>V$F^?&gucQY0JsAPz|i9xAJYlKYcSni!_l~Iq-d{I+Q{vdgsb*?xH`-LVy zYPpKVMi5+rB>fl6)d&96DjRWd9X^9yre}}INJ^D=Cf+6?s!4d_on9`ztyM9 z`3TUEy*DhXK!H%_58|7mxu&0ZJ8>t~rBv8CGyIGt$2iBzTQ&(KZEdY|N3z|FQEEKe z7%p;|Qrw?ZC*9x+Cw2;`|BNT5XlF;h-tdh7+8#@3{8!2Qa7X#Qwc^zg>Y3;DxkSGi%oVjiP|O*D`GQ%~{)`+?a)dIrewMbB*lT zgWKusIsJ#l@!lSn`S)`P2l=rifG+^O`r9E1tVm&hj8pOj^cEZ%_oo-s+aGxvf|*ma z>^{8Dj<9?5;?=2jYMNs9=P!nb|7lNcqrT(;O>lj8epz-XaKrsB!&g-oSI(O&7K_5%m^dAmwKk@?@KAdt}`CtAjY)jL>x!7s?@y6?WS7Y|kl24~n z%Yh%=+m^$(Jnbz<-v=*Cx08O}^ZV6$|E)x1-poCpy#=3T<%&X`@6Ery<@|6yHvu`y z?S&7G_+8>B6ji>@=Eo8>qGj{ilNArz_H)RA-!lF3K1GqrA7Lkdv^LUkHdO8uRE43x zT;4@`pgI)d{Mq-=KC(7fz&pCc-dr?9oVg`&3g&J+#@)TM97BaU8xMaBdjkKX|~71P-Jw6 za5dsV6q-GsrO~KYxl(;09 z*%ykMLxzk7^;67n?C#d#LuNZJsV#ejSKmU0(Nv!j$6nG>|Fs}f5c#A!XeN-HA*^A2 zYa)6)>pg3!t**4Cbf)E^fLwDLBd=2~f2uT&MiZrlvV1|YZC}JQvpwR;N|$|9R;2jL z=8Nx1eD;L_AH-Vn!y(4$Iw`*pBK@IWIp1|r>K^Uel}CD|YS-V=M|0zQAC18{2{i^R z8%7$rM-Sp&xrQ-4y04kzqF+={BP{w{TgUBme4{(5fP?t5><7o60H3Gc7xAmA?C><^%$se-5^V%3$#A5e3K60DMfy>1|}APgD5a=Mui z@zzz_zy9<7E4iZp!?ZxoM$PZ)1}o9t#a)cI4>YL<4`b<^_-LjYLgh$0vcA7MX$HVQ zJcou5$0ez)9FT6Ay?9y!CqA1Kq{diMzWLXq>GpM*s{mQc(#fkJ>J}m$?&=&&PW`## zyl4N7px6=>@u@a6d{?)_PsMniZNUDke6 zRM3sE>=8Y55;POQWU$^HY+r$JT&QP#0e#)7QCAXrR96OSv3zNl$NtCl4RNTy} zjGJe)pWZO)7iqZjmCJOUF$dHa8)wdw6XnNLtaA+R(|0vC1Yk zl9ITCu_x|e8YbO&J|iS%55IMO4Wk*f2y!w~d@F43HAD!+3~v|QMsQVk-dt3&GmqkK zW7}4fm8Xj|6D!(cvrr)34UiQ|f91XBAx*s{6%sq!{Ymiw?F&%9f;iIO8jASLJb`UQZXdqGKDd1!}#d8_q z`{ObKe?~|7bKMdj$%c+b@>0L^Z`y4A!OKTqOp0MIKhUH^9YVj*b+F4+rI)^2F;T;< zO*jAe^8*y;7vr@28{ZesxpzqEki^UAKRBuGluuymf8h5$)X%LR@pA^T%=9L5m9>hS zt;T|lP%k_&{bq*pEk%RhS4w~#3w;Ry5-E^r96|}@3t--`=f2r{;rD~-EoHGk` zD%d#=mI!c37-~!gi&q1j19G4#;ze{HBC(44%QZi0gW$($!N=UR)i@Fu974cS)A7Iv zRZu-a(98j)thyU83N>j!SRcUj64)KWf`euOXZcV!&rr4wuvbGU8#m;v3i^DMyrl{% z&&|&^h77j}js%CgXok9ng?bkg{78xEvIHbGNrXWjd&F4?FdFtA9KKmg#kOKu0uN_9 zgVo7~v0H?Ng|XN4hsAhC#1~UFpZRAoNu8r8*rcL@J;S)VAnyt+03_)WK5F4G@F_g# zwmjDdIBm~5FN%kckCO8YfU*;t=m0KX6s@lw`CA>@lk zko7q|qh0tN0H?|iPy3Ch2H*j_Mgek0St>;-wELl{H*`epK^#SA-&QZ2F)1Q|p zsu8G5Qk=&Tp6o@Oq)t>DXo~}cSeL$7g&b#c=eS9`;q@C{#kwOj7W*wf^gj z0Yp|h)R-cJZH%PLg=_-{DJeuTdWW#=AW&5>sW}843U;O-cmGNr zn}04BcmDN3glvSlW~w`YBat?t-`5jQwq?If1>9lH*E3-x+9sbnO~o*~$Ke8J} z6mmEh5RomR3s?*)EnFin5`YmWZzL2iyx{seq?#;7)sFFdid?<5JFoEUN= z>=PplG9FKBt4Cgov>DDVDZ2ny%mZ~O+Q+!!>}2-(`4W$A1l5O|`6eYrO$aYIg>n_e ziX=7L7-=GwTn0~Ghoj|FH1`L;%$6jJ0-Of@%Vg0d#Ztae^)9Q3IZ zSsfO-oGVGQCb{FzzGhM}G+*|GwH%NvpYkrBqXIzElH{+6gJ((TPsyQ<%0cf6LP-VJ ziscD~?8w~UW3ssiqax_;41H}+`t!bWr zkD}`tZ;je6RJ|DygZhU@O2-f{%V^I~v{kq~O~x=;Lv!sqc5~C3>^pVVk#%ecQoEtL zS2}!Uc-lP_b$cgT?P2|GpZaH}buTjOUM|!*mJ$av(mb-)Vei@9+3GwO8hl<>D^or@ z#?oGwHGduXX@I!Mr3Soq8~8=dOkAYjHzKs$n^K-P*GD!tmNqvJHMj0Iw^O$ev!`7; zEj=$=`XXBfN?V48T0ZZ#e4%a~6K$Q)X`Oo6IuqGCSK7KT)cSR|b(y+tMYK(WJ8C!^FDc$gO!dJ3oI zFhR=&n$JAv^2XErLP1q=xOOg@PHq~RBrNfJmDC>%L-vuL;UTwh zln4CgCRMOxIGI0=_|XMr$3g#+@Y7zx`0tX9p`fh?p0~%45bo=^1g8AeVU#J zcLnGqVXF;@(ovTz43s?=Vn9jV3=f(=K>Qj)sAPfJIw%RF1qn{#OYo9pRIa{Q-|M@5 zI~HUFB+N?;b|x8ABk5(WY{_mY%#r4L}=?GJ201pD>_as9ToTs@Rw6^!5?qvnKB%DhWb%=|#} z@K9?D0~h8kR|f=FjY!A$pj!}%mx!dQp6Be0l}gS2@d7(PHqV z#-ree4V~}cWZo!Rf|Hi9WS1%cmRm&l5f!9S5~Gc-s=atX@-u)1ALGHQdgNhP+`QN* zscs)B9=w2oZO2g~U!*J{aghhGSWBEW+o+bvKLir=ayZTF%Q+3;r)R#8r}jjR@;i*T z+=Z+=jf;LB7yrxb0WZ-kw0!d4q${eSe22rDZatE)r;36IDB zqadw(B+N|{7BUGlvHu?g5@B?dFrG;G;z<~MIs0!8iAW$dG@P`z6MD@F?av5p+W#m> zjS7U?tAvjN|Cb6&aQc{wW zlarE?;^X6EV`GVZeZ(IlAt52b!NGxnffx+t?c28mFE4_l4dMB7!jlJthYtz&R0+3L z2ue4C-n{Yk_4V=b@$&NW@bHMYf9dM#>g??7jWt-f-paUi;KX>K!C#uP~wUe zLZBcgkdhKeKz|SjBN-VvIXPKb+3VM@OG!yxy?RwbLPA_z{J#@OJUl%A-9KVwW&Kb8 zh=GCO{}DeTBPAszAt3>QKm-6F>XpO?m;ivl?3z{BjzBOyl^MS0|KC5d?HURQTKPMW z)To{NIaB`ij+zacA{>qiq~g&2Klw*frAD9ZzG_>B_`gHH_DkcI>*QCFG*jNIFc$-bH&7Ux3icgikgqKH2&Ni&DY6Msg;7PhO@2V?zMDe zP%MV}5Gc9Yex4nDYtJX%wzRIEd`EP}R#qKaXTl~Q8sLeIp*S+a#*&dJVB<*WjGsQUdJ+(KwP{$>Ec%|h@IU^MF@F-}t+ae^(}c~u z_)CASoV3IE?dA1|%`Dex+s${*B*oa2f1IQo428%){*j#!mJ55> zksBquQ=H3Lu<|_8ChxJWS87PAut%ndb&hUo)=#=@xdE-655@0GM55l)^$P-|-2}bv zvYKhT-SUQSC8gzNdpo<8xQm@0nhw8#!s^75SzC`j{dxP8K4B}2d_h@+Ug@-T>3-d! zOGr7Ua&Z0@d2Gtd?>USO=#Iv{x*MvL(hTuDA0;J3mp(DAX6Ck4sAtBp5Wr*QsAXFF zgAVWuQ^~i!B6@1n2v)t$$5*xYZXu{f7oN9Xy3Zbla)oX=cFyc*9SsN--QDawK2%Ue zTv1b!ilXz->n3B}+_V39e$-O=<O(a0e@Ia$U~ z(qfiZ3S05agvC)=_f#WZxL70RSKYj`qjLR*+p{QBWSH<1YT%~}o(z1RXeilg{7&H+h!a|Dl7yi~S z{n>&to=g$HLZvTH3rwxumffn3F?Yq&SrHeu6@ATn7WaK_n!=acHnE4qOUgb{t{NvY z;2VSwfN17YJ?`&hY?2HHX@VhPV-X#3{(eCXp;v2=6mDmEjCW9h%7nkjI72uu&CM`1 zLM+4!U|x({8f8>UPKE_J zMLmmL>QA5K$I*HY=X0JC{i9VW5S14v0559z^#_G4iz8x6S<3x5U+hJ?21-CJF33JdiNXcq zK*Pt_0069i5wVuNq+GQCMv7yOR+WbAN(LE*AegmBw5Jkx#-Nm$WgKMjY0Y_2nf^3H2*VOl7?@WBAjsB8J0w}q>4}!I@9muy>4elVP zaA9kDz#OZ_WIsyjlLZ2j;C*lte4$=O^#`+NI|T(QjO=kf3rm&AbL!Mb3I0>1Sm^!> z51t7S#Gm=+S>MHU#zZ>_7L*F~DG&QciW1m^=(aJ$ZvC?vo?{-4Ut1x(WUD0RxGqUc zD-i>(=Edj$exP?tLr}m+`-d=b%!uZoHW-6?N8P?Mg8;LHfns0BSsDPiPRSirS}k}1 zY_V8FmUakR9&*xlMm}WYraw=5r_z!ocyA+{^){CPNKBLy&+1Rd^l*=`99Ae(j^*ytuojKgVQd`K~D7 zFIz1jHzZBZ}Fst_g93ksCzzpU$uG=VN&E1sQ;uT6H)Nu zrT@6hnmHHvyjSZjwEJ28c>@8r6!a<1;aY&zF)96XV#x=qJ=O?I0_bvvagTGyJ*0Vt z3|5E|tASwHEMK$7;WuO~eZOg&Dt?wTe(gVB#?z-L*Pp{EshT$$`(_mRC3EARHk2&P z9xpZu*!ar}K>+DJUN}{pzvN#87&x;W2823qMgSO}V-sXFDpZvZp48hvJ3iWb^}R!$ zEs1l+t!#>q#c~?xU^Qe@4%oJ&dTw`D<}fuPP=10+ zaDamoHs;1?Js%f6$ze~NYL_Oha@k3Y2&f6<`VcMoPyv&el>LyouNAgEXDbFSYy( zkv3b9ol|v{IUIAQe=!B|ehMz|kLIGGpg520zLKIB?z83Zz8Tj;_ZJCcAO&d7!pIO3 zhnCv0e~zxbRp_Frcpxj-(x>o4VR8AdQzjS%{k)|?zw^|YN*U(-yaOS*s0y{G z*HBoz5vStX#W~;LH!v7;z8ZOTkMe`pTNf?qy2!R;+E}q~hJdRT9P{fAW#+f&FMb`| z%g90VSOW41W%IYtrF{o3zYEAU@*8U`zrX6tpElortMoYsxuS7DajNavWE@rGHz}m3CQ$Gh zG$bP4VN}B#1hyjsk&kUaIG%g>2)td`#K>-`%k*E*dV!QSxGjk_+|R$Qw0;}Kr=}KU zppm4eV*uAVfQ6C)x?nQFt+zXr7}DMVk`9oY2*QAD(n9PS zLhNTlY;3H+{yOsOL16`&QR|v<*RKMSS`-%0WF$Nv361m*5N&XH$BQBJCqwnou;PQ~ z2s3gDLLmvW;#O&j%zAcdY2g_S;aOqfw>@-zyFP55G;HI8JjH%x*2v@QDG1N7C)S4c>IrZ^c)_7rrpNhtpUf>*#xHth5=Qi?(io+2y*eG z`md}~<5eKBxUP6g7n2Xq{dpk3t4GRJ{H8U}O(`Cb{6dFb^>SKgPF%A|2I-M|9MJs1 zl7^mzq0bU6KZvk3Dj77|=4@I^hDVB|#eJ?Nk(-09oFwmp!w=G}lAUR(X^qT|$7qBAyi}6b3P;|J zq6rpGdKsGbvOXnxAWfRZN*GNUIUAPPn0VbYHQg(->|-iLuGQUMMLs8(FA}bH05jKf zdheC?tthQjIB}8DN*_)64y9jioN5uCInBbqvGxMft0-r6gM^zlUj20lA>G|}&bGE8 zZCD{wQI4eQ0}Vv>UD7~ec46j>aSmyKQu&Ep89n#}1)tOtC-1OFaoeko0u&dZJ7}Vd zgr%9s(q3TUthsda*#B^m{_&4kMRKp$NpqpGME{6KF^|tAPrxpZv5JDxDNk%ZPa+~u z{mnn<=jr zAi(8z4xkPHD@z|zMPU{}VRk^m4}Wi|_}f!Fkc+gL=l25Anhu+XY!%zwKGc*jI9XvRRNBlb0NKe zk=tRfu92{LmlSK~GG>&N&6iN<n&$sTP{j0E1S? zmtLDM?cK@K63L;~%t^i|Ta;4LNOjfeBWq{L0wl@0ZL`R@CDvCZ@FGInA0<{yDndxE z9t8w%c_lY6gIv&*;mFioyH^R?;UiS#XY(wTe43?5+FXTmyqmb~z zM+}`XO}KEI&?l)1QT&Ocq13BYHO+MLY3SmvM-%O&((LWVI6x0DL{lo^ zARcu!nI5$|^R;2r^$`mx7QY)5h3i6X5*<;b;BU!6qSrERe8^g8H2K|FK;5Xt)&$Q~ zAd_rV!hrwi(bThXU71U)y3um+tLZ@PR#n zJa==RPQA>_`ej07y~mK)%8(dLkK7$YrtV}caL}wc+jL@=IiK0OxZ5_k(6XeHi2T{& z3*9}R*I|+;slVGvEwMi zab5Cyp($P9AWS4pplL^zTgUuS9V>eXyIE^YDbbT`IX(nDY} z2Qq1z-_i7+{qDD*85B9{<*lL!9feIZ4O!avO|N#A+xu3E4dt|;W$z9#+!|aug#5vP z`+Pl~`Su;L4WBCx$43ox?{!5-AsvT7P%QWlo<`_kSURnLaNUzx!jo#ijV#u#F0ITF9hP^NCLOItYsdrJZxlwX5rOy}k zA3U=#{R<;|WrKgB#uh!ZBx`ST`V&m7@2Gt0Q zT$Kux>`3_VVi)_95lU66(2!d3{qbLr38-<~X~1M>b$xipFQPU)OB<`3A5`Rc*>Et%|3`Cv>^?--$0qmC~ zl}Q!&SQ3m-o;Ed|me-khWHu41%cU<4r$xVrK+SklPgx}Mkvqc*gyAJlb7JDN)uv;Y zziO5JCPTjV_K30Dw|0{_clrQxzC-hNvi2`;!BE^A)CxZQ^7jwJWknml?F3okP#Xat& zoX?3*F|Z_n%pVEstD75Zt!@@?tN1hdlY{Y|!}9vqd2m9qq8OaW(VjvXK@!|1%T7UW1xy3#NCl@7_BIySF-Y9HnG)yZSZvHex=3a{2_w`P*Zvv5DTf{enC04># z>cNumluXE#)wQ!H%j6zktd`cTW8(ExmOR_&EhMOPYj< zjYKw6`IuDn=uG+UjoeS}Rivbbhg5aDDn{gE_8w{d9_O3gPc363ZM)Ou^hBS{J&u%=yYI8oPQ@Gg#fr^piSKw? zhm4A4`|Poe?A>GT>PJYxgwu7udH-k3I;3*_>l=~f>>uK_Ka@vyuC*PYUmb#T_j{JO z*bXX0QSjHCJIwdD81Ao~eBVE#J$xZ>cysB;x4%EW+~ZOvXp=h`O+67l;;%eV_;Mil z<3PCbNT&D5Lt_8$_iuB$T)ZgavmqfnY)@1)89K%TpCJv4B9o91}_^v>D4S7%Reo^LIkL%18o?%nTkYAhz4XMen4ox7;`@~CQg z=i}8MeLqfXew=SuG|`~orXw_zZ_kEcI=FUbKM1fe^<kb?ccP^yB~u0OU|s`>OXHsv%Gg zl_2J7i_Ty=@ux}hYs)lI9Lm>@Nxqwi0C!*Io~!m|mIrW7x3Yfho^A|Q-if}bzGGAy zpuGN0WK}aKJ&gNr@L8I{w*GtFcPhcGk9G`79+f}sF*&xGj%0OqdZLXe)31JZGeu?r z;V>Whvh=7bpQ1yR_fOUsW-G-(tJLAl_=WZ;1qWBForv1Oo#qXEY3I zU5?zs4ivV(#v=?4Y{m<9bJX9N)T-s@Y56>f*0Uh&1^C@xkd1Dxc~yj1ot^85dw5gV z_r=6FWk$&zqhf&lm5tDo4%m)_a&ep;+ZyKyjWF`T&|_7LFc5<`Q^tw+$^O^&P*`29 z?QDN+-#rQW_T@i5zXf$WV?@a0HA7!qNOd+u95nx^?Ym3LmkG(1uEa8Sv-BVZ+U8zx zy?Q07N#lBa9-2l+b!1H!IC54*62b@OR*yD|tW;-n?3U7)`X*YgLcwIV-(C}RJ+i+# zswFH?Vb92)TlZpHjfbx>L%(FhTa7X@04psNWb65%IKbBOaFyD$#u-83cz5hp6#5Md zfMIxSAD^r9w}bvZtK0gg`!@+>47{8imxC%u!lP2UQngBx$r5#rfX*0U=3BYxZ!+RO zs;bFc+0!0BChABJ{-q;f(#!?K`r)n;qne*{Z;(Zb?Wg8<+`3ZyR6l4@obK@d6~9%HMT1*yrAkx zZshS|qrf|n3HrCKZX2mDI7`<*N4z`v6gpGsDN_DLWFCwMVz?1W=j{1|iL5vC)(~&o zynfBRXwN^M_**o}RaCS*dXZ066@iDXo}~TJ?aj_30Vn_D`0lrV8%?s{fh$w{;(q#! z@fT81b>P7$4=*;5!vIIz&tPD#t8Cc(TU$vatTFynY8F(FJUUC|;U4fLW*Uwcs^OX) zwE8w+o(tzF(&FbqqZix{wZSrsC8J>)_C^RDrkgB-72)HbxD1H@P`>L0Z3&3`jd{T^uhu)(SA%X;-Dc+*Z9H(Ojwfm11D*FbsZxw5=G@g4%+c@Pd9EMy zzD%1ZxTr4%iG#Z1{Wy*^1H8RcK38^;fJbiyBRhN5%%s5=#fTTKYoE1s8hYx9F z528pBnKK>-UwL$m&>ea2_w%c@jh{bQeTuwW^PDWyw%=Jhh}5O(HZAKBpJTjZhLBIu zpi^V#r1M1fsa2$0GTks$%EPpkD2sbKGMRIwFJ&88QuNS17UW$?WlZA8+A8vOj+{BDX7P34kV81yH z=VcdC-0A5xJn0Yf43xm=%d)Y|Ww`f$gHvS;Lb4~FKG(`98! zK+0vh$$580@nc8=rM&u0NsHPVlcVdf=ksXNW@84sy3)IM$}H}%nT%ViY2CH!=e~%i zLFm<$SG1NrhMqkhnV!zhmNB=`+3jv^tEz`r=Q2=H0Z_htt}v&U&tG~CwYenJ)dfpj zb*7I0)O7gX#?Qg9k{WYGZ!E&{MhIy_=9AWI9$pjCue^;f%qk3+V%Ev+EWJdR!x(T> zuJ--XqL77U5sf+lt4eQjcJ*V$?$$7a3ZDAkOS_#L&_srNHD%8k6&z|O9kr0{3I{$Kwr=HQkPXfLhWfXU!Cdv`A15P z=TR_;WH%_DpU@w9$G(^4nRK6A$dOl$z0y~als4F&qwo!v0L58uas{(;3YGb19Q!Pu%kSjHYwAWH9_e>+fxM%;1vHJ>Y>JQ&Vp9Tp%^bVm*@4W>Gz4t1FDk{%$Qnb{ZTdQGm@tR(CCKJWWMlx2P= zA25-qpPMrCKFue1qoOJSV*V8Z75`w8PE_l{dfYKWBGlw+Ad)whU3aEg$s`k(OA``4 z+QK_+FpZ>GS%?%q*PQW9Cnm%{Uhe|fD-zf9n{k+uo7=<7BjHKODuFUgY9umefSScdIjI ziTam+s_S2#YX;x!$FPNc`dxUzm)0+s(SY}76^S8i>Wer?`xmhB)nUKP<8&vB;!y%K zgrT9htraMS_4=#0e$%aDWIM6!!GwZxeLm&K3lC3<3Y|`B_nqb|6N|5}6PK-PGr9?< z+I>~{=(8qW*mLvH#}(cRmB$#TH{gLCQKzEYTs3w2eFU|Xs{XOQ4e^1O1Xo~;mMip0 zKLJBW-!ZuL=TIFVF^0c`L+rH2KoWVW)?aUiBy=0NkW+QoX!H5p=X;9W_lMQzfyvP@ z)`rX@*G$N%0CmC{vpX^h4}U$tqo>w3MD6V>D{?ldKtn2Kq0XeF76q2|cfm#f zRgLkC245BHKhzKi(|DB5$lw_z-!i1_K&CX@=lxJ!FL2PixtUT4MvZLWWN4J=zEj@? zc{nbnfE_lUBG!eB9NTIBQ>Zmm!~qymT}|XA~(DqbIhqY8m)T#ou~YuA~K1WKWvBx?_K(TRRW1#UqEX@;z% zUOz1!WoXpG6~~bdbmRSgjwN~Fp3>+Lf_139YCySMN`g2r9A<|aOF<1M9RY$uuo1)K zImyH+nOZ7^Y5`sX(3pnkbvh5<#^;5)4p^AEr>fXxY@jbN2Rl*jMx0lxE4)7*+fqb! znX)bhli7{G`O{xz(MD5F5YQ0sUmVMRsae52S&n|^>M-bLpugA1A%IAa7K_fv6Us;F z@6M_>G>w)R@whsH7#E;1s>2XW9xq_x?0|Ju{0mvK~y)ocHwD8JiwVx)NpB2nU)taMv z%L^vN5Dc2)&1RN0+g-k3_hCoSUsk-s>v-?EFN^*)eV0Pi+us}5QgDi>qH)W#1mY9 zw5GMzyZiALS`_R6yY52W@K~Euu7!k@_QV_Wu)8+#J=VDqw(%O#sR!}y z{WPC^KgF$n%832+{B~xzM<;t^Icjww`B5TugRRH7?F;wulbQt{+7&eSieR9X+uM~S zfNq+*-OGp-VskpR13+~;_9=ph&Lq~mINr~MfJzJ|dPxxM33VC=#V}xWjtIlV;`NT0 z`zculGnQYicGn#AC$-uQ9l*GcmOX4fJj=4Z9mq9V_=v+ntzj{@mF3D0#BvOE)V za0z+UFw6Bgsa>E*F|r6iT!KifCUO|KQ5YPt8-B5hu}q{svJramsb07dznt%Yn~8Dg zfcm6EUS7cl#gd8nVIyeLF&AuiTlA*040#L3K9er{c^PD!Ls z$39Arw?%-}X5x;;iiAErBR-}Q?qw!CR*W_PqD9FR)7M`f(+lH5wtMu)wAWg%DL0aO5Ub3@hBXjs!+O{|pa}q4Q;rNX`78@t+8AG2 zn+#gJPDr>Ij`$LKwUreuhh`B`W{q>z$#iWy*N+WO?}+(DY^^9_#}knlj3yBE z#1S_@66A6MZF7R2qqg!03}XXzy`p^XrX5W+QzBRBez^e5{#r@QN9-DqpfgKwbru3kbV9d0fR>-Wq=M_xkz4#yb$aw}Nl1?Zn!&Gj{1WEN! z6mlmua>w-U#EC^2b-Xj`0CSQIM%AtQ#U)0_y~9(jK`YSAp^&PMyn?Rd9D7WBKnMXy z1lLDYI1sfHDKq%AZO7NqB`XrgiHx)&FM{m)d&{h^J4III(~T-`605h#hX%TE0UJ;d?i zgf{yzI*rkXW%oEN6i^^7Y}kk4;xa@K|BwW#G<4O)h700;L&Fx zhxy(Qe#v~Rm;o9htMAQVrKNB)Yg4n8K2d}|Qu;pUYYkWZ1P;qkM;%{>83JE1hOFqr zJuNc?n@hYWXg|AwivaWGgVzrgyRjf*Dx4Pp9R-pl>6P*I&QG%rA&4v{pnpnWm5bF% z_L=JSnv2}W!2o=4oXZx3{JV(PhBx5*!Jza(<$A1^987DS;LP#(jG0EC;j_#OU(KvX z19iS2H28B6p<#nz-13sbiXR?cbO3ZB4!RQ^gNS~NIl1H1tM&>2?*;03t}=f-rl>z! zmTA(Ed+0HaWsId!wAr6iIf?l*0+;#>>W^4rDPoq5n6Q1P!eYRH8Vl`fxI; z0wYC20{_|=0N&%4y^Uo9gpEmx-C<~x*ch8wXUv&S+TB;C@ivnGVM!{>aUZjPt$KJx z3B#!SA=5^LsA^3dLjaIH$j>OS5(W;1|K}w+7spS2`?1ybc;H$7lcN#4@o$VFfkvul zzalTP2mv&=AKZhw$w7$waek+)mS0bI+a{}nV8X@!kxAAt5Uc62H@;kLAWl0sDj3Ef zA_ql}`Qf>Ye`i0gG-$|dbOsZo;P~f?|9m)QG4==XUD^kesdU6gG;HdI_y?q2HunCm z?f#XBhwwER$9o2){tDDc3#v2$s8nP1mSfCcou~hv9*hDCW3ohdnX~YLE>4fx=A#Vd z;6x9j^Pb`WrZLMcR{_(13ayC|yM+IdN$F5;6GVZb>KIon)q*`^i@&~W5J)jEMAV2^J3Z?X1Y^M_;($V5Wfa0lPZRHwg{eZ(~Vzh0C2SHd1iw1A#if1dlHN(~?BT32l}m*3u+e ze|f(N4(gM`XdupAe50ZLFVWPGzSBppe6_5+1H8Kq4Qq&x=qG4j4WjuN=|d6K@E!k; zB5VN)1Aw4ZLY_y6K`bG2?fv2-j$s@Tqe7S*??*n->UBJnn~}QM7~? zPT4f_7{v0r&MCvD{9K9b=+|*q+Vg-@vI7b&sOf*H`IUadH}}nZ!=!{ zs=db1OM3sj6yF{frzP>COb zS!$af6nlGexN6y?{;ofsTGabm?xa*3+DoD?Hvabg3-+x_yNDm>`4Dm*@Puys`z1QC zj;SrWEoAglS)FmsTb_o?lkZ@C5tELa>;L?tujZHXSU3u%FsHe+W)4%RKxk`)gXYAI zI)-P-gQmm>%}6CGoa6Sg&R;&2+o0!6;K>gu^&8YxPZNlSl_n}ZW7y4$$NAyb^o{b; zCnRsgB(3e_^@i10f{q%TQ;K=`SDu+h=}^NxZrfUbKPfoQY}*H&6?pT@D>YKZpYScH zg)8f_+au4lN)H2I!|Ywv!Wn>R5YWIGN(({omxp@UedjYbZd(|<#gn$cfV#qGU$Yz( z{@f|g;9c0Y@R%F_?jn0aa7SCp7gU0!bhj>HVK{ukTPfpTlUd9+F*iwigt+~AP8Q+g zuj~9#!&6~qtG8NXa$j$uf$&kgf$Dp-dX6o|9}%BHLRhfgGFNH0XC(dNIRT&vw63Al z#@Q;^`7OV|q29=?9ZsA%wUov43kun zd@n8f?I@XA|EJBwQK&4Rc1Ma>JgXwi{*gJ~$8sqxerE0o)mPlZ5QXk#*GZZ0*NEo# zcf)R4HLb}_D!S&6lh0l$j9)~g>S=sWUk4R&se0wAJ7NM-7Kk!TbcMTd zR54lY(LHio$yn6m*I})?U2xbkGCg=X)hAEqN+t$n@dw^^kOmu_{Nlc+6~*L1X-N7L_ zGC=5MyvoTXMdYpq5PqdDeK8;{MAei&PD##wHk+hpQA&Tg3}&!AA1X66b7K()I&8M& zOY>rZ4;sKU@1FH^WMl+XWa_Z0_G2w2qL`ZS=s}I%^u&Pi7`hlKZjpd1hHGDEy2a{I zp_Zd`T@x_d-uMWdP$J5*mW!=DWI!X5K%+bMINlH$m$nvHhAl^tk;1?6>)KAdrQCT; z;k>C<2-D;bMfh#a@hELEGEg#=(_?Q__z;d%a+n+K76MF-`d~eKjX;CQEU~ZtfPS&XV+=xBVqz}Eo`Qy}BNB7o068QciZUt)9 zERd?tu+D+JgbGa@rBRWhScV00cnHqse?l$q2tkJ}fsdVYt#v`Ix1kpLW6w!z{o|3> zjyD3!1OKG!BeOUjz>fig5_Apz5y&Ss0N|)uP+jU9A&k1BpJp9lf0yMK~ zDwPkAx1+oMSkRpkhA~coS#lBHVZd94I3&oKBHAQ|hOiR_;qb&s!`nMXl|}rYzy9(~ zqP_D&gh*hS;Od^4byuP%vlNZ#>H)7T#ghqe@Q~oz@w4{s9p(B!GI6_rEV|aitQy}) zwaTc=4SE0^B1_Yh=*yth-hD1?xA@L#hKixCNZ9utMe_QTfLt9#KLl{UVSSMB;tkgw zDk@&3Wx|KK4J?NZXjMF^OJ`!X57EP4Va_ffd0@YJfr0oCRwJ$Ij~g3cH!6j)iP--P zjd0<4jhqUdj~0=xqGg2QNdSI>)j1C2FXvDet3};r$>!grf^{YJol?x{C3eql4*ZF zVj#8{186Y72aSX25w*?rx})eG`Lq;{czxQ0DfPaS4L}=W@aOW>fV!=lTW@qFFukNYBBCtOHHTMfRh%6 zG|q6vjz4KBWyASHM9s*5W&O58FkCK3!o@uaZGf5bqH-VjM0}FH8k3wL3T4lYs9}R< z2LNjaX@T#;!i5??HhIq~k3Q%Eety#SN_YG3(8Fh~`-erlzadrUxR#2iGiL>-#rig##d9;GVXs{$L(fruQgS48qBp zwyQjpC3?tvr;L3BspiUNf)s4PUIpWCJPP|Vo=1vSq}KPM5V)rzME3w$IH>9oSlNN_ zGV1x-@pOmZ)Z>XHn4DJZ)PN(d=vPlc*EqYDgQb=8qSfO?KP3CX-q(Kv6z9rF%5XJB zTk>m0v|Gc#{Xh_b+-Nh3gutj6GU{YlYxS^X;Ni%U7pvJy?7Bt>00!bn3_%$9;@N&g zu)4CSr}=`K#YVp@1KFwi2oaJl)xM@PX!(^VasyVeBu*{Hpg*eZ0R{sfPBPvZO+|Wgoyt}($(ZVsc zr^Y%8d4FqqFX{8x4c|Gp;8sXyvm4H(#O9Ucn7_xt3aBXI!cCEOH+OL zA&aFh#5LW(t!u&t}Zw!r3)YB&?B*O6^=>#r@Bxf~}i9E)Tce*Oybe3e`5 z7OxMv?dQ5}ioci#0v1Zj`PFC0TFUi_X9YvoII{^1R}8iPxT%L2yh3y9$k>u~ebCWE zefh=)m|-BNmo^@bw%Hqi zLLNJjGG)+|om~l&76Hjc4Da|ihd%^BM!4k(w>^MI-DXFd7|&z)<)zJ`BRYUuRx6(!~ zFD+{&YSUfED3-E?j8E*7I%JD@IqJ6i7I;`G`rw}N4<6IvEsaZd05JmS0$I=@BdJ!G zof(p=1`&~B>93;|TW--B61Cg(wgaqo29#aUkSQF{=;j)49a6Ob`M=!J59O2Bj3p0@ z=TmYHs?&t9IGt$T3GjEf_hxg_gAnB-v@gll0RZYRAf{^oV~EBS0CP(T36c&_Ef30f zqrfI$(cLN}CQ1dRPKg~e(EIH{f78 zel5VByox*3k1Z3=er*=;pGUlwN@$4P?t`6gv4`KR)kiMT>1qt>3b0{l^(}RTBq$%0 z!SVyrfpS<(KKZa*AuYgRP=g{UFQiQ)%SAY!Lz~e#-L7C8;BI zO^bf1;b{8sC}Gc`%ykgPRuF)G-R3Xo;lSLH%>fy)?F2z-t84`gnQ zT6tFcOF=mKj%qk^lzePd9W^%UR{9dl^^es@PxG-O-^AL(lDopMf4(-WrV{L=5{dIOi;k3l3{qtJ+WK5o5GQ+wfo*Lv!sF7nq6{#fcW z+|ov+u{Xxl(zBtic2VSTSq5KYamyy@fMu@xUkzZ`DbIO2#va^O`R_hfdOe$~ z@6Qm%vwEK=EUI3bUgg*S`|)s7=KF~jga9Hi_vnrJg8TXK>t!>uKcyu*OOAl~mr~c@ zUpJzFU*5&zHDed|4I%wi+~8xfdUI~%$JPQceZxE6`Z%MbvO=FkqCHiE3_{sBQa;pT zQ^mKJs6qLm@qAzN5WMRn0Wp$~zrg!~q~?wU#%uJ*nfGgARni7cJdFbIs5Ehe%H-Lyx}s zOQ4VplKuOvq9fcgzPzvfx%iGva>c2io!pnyIj+IVo|3M<0cs)5n@j=fGXSanLSa75OgrF)X_G?QmYNep zdZ<}S000q=R)z*B8B2Dm|R%YMG)T_PF-^^F6KcO`+R&1wxm9jqSm zH{_$~j)Y>x?@PGSFg**EV^}X_F>pPK_mRF*M{{2U7XTyGq;hoxOZ; zu3OJ3cPn3E&rR8HcZ`T@oAi@Di4N3yY-j;vHCV7uYGHrsMG$%-u=Gl7uhnV2SuFe9 zB?jMsx;B>RZgLuf)cd=+{BHS^*alH-Jf(4R-)uhzY(j|?3P&8&h z-e%c2CpnMTF9&zqITC=7tJhfb*vQjh1HKv<`Z;gQk>M!t`&~JV|(ZR2w;NJo!7<*pdX9&X0X!%l#xzHrT!t87$Twrj4Sh!xoHP z70@>?-|u8x>a<7@RPn8OsZUV!yTgbN3oBsPX75rT_fP$M6-W_U>RKYA_(w+?0NGe8 zPm+)Q8(3s5AJ^_Id8au=6|!e4UnQvU{MTtI{^DQWkm}4*jd|Cr7<;FrklVS8CMEBu z+9)=zqH3jMK-PFHoJ(%FAo2ucSSAyM$; zL1iH|>0eIJqaoGh>0au;t$i&ORROA^f1hz-L&q*txy~8`N_U#ThihTywBJ=*`bPu8 z`-;Ln=~00G5x(uV2|-BIuj796w{>ZMJVGcg5m*o)S{c?pIlsn@gmb?Sx3CC(S9Yx? z_gE4ZKFu}k79G+os#Htevk&G64d{$^1X^1_|2~yq=QYAPsIAZ%5HGO z4hSq{q4aZgRuv<^A3X7e9g+;~DNRBaQ}iIkkid<$1Ck!iUn-CJhVS5ji<`<%~|DV#yPVwe%{+p@5X zHU#G}-e2Kf-nQ-Im8IV?7#|{kL4zbC*0eL-n@cc!A%kVg!mm#PbSyy zi|E^dJIG3QgWb*D~_1apcID9WKV^ke)x9FCK*J5 zFoWc>GUKNo5c0~k(?j#t+V{?x=-(4C|h6PMVUJk@_0*zuuO%bW2g5z}PErdPI3o^rU}& zmbsWYq@23P_gv9X4zD4PetttnW3;xYa_)0E^(M@ag#Rne#yNdD)+2bN;M%Bxxe>D z_`SP3I(!cEe3JC!_=I}+rdc#5UV)T4A2fm*88u0rh=I6c9MWU-b6l6l_^Ta7LimMrK9|pPn&zVoW}ie9uA9o#4Y2XUY_cR}FH5Ys?ha$IAk%6f*h$X15u? z3M+BeUhpZ3SeGYVo$WISO85YGr&xzR8-5|(FhjuNLTT3fb~i@>B1Ll-nfj|EDxq ztYany?d@*hmf}tz(~j22*lpm1D=l0qTo42XZd1n1ty6|^4?-8Sw81bY9K9}O7J^~^maDBS z14s)y<6`=IsjU_%o*pArPKPIXGOo0V2v@amIpl62d6@x7$TA>;#y|mL*Ib0)SDM14 zR6;LrhTspyzVVyp=~>?TM{feZ2|6?C+rBiToH892^2?jFI0RAz^$)QHG8#COKhGVJ z+7ZvlGjJD~&y4eQE5_J}i2p3(`fQTM(`ZX&K)hlBu2{U{Dud zBr*UD_ew^b;Pz&u@}o)P7jxK1B@L*~w|CEerb9-a1o8@M65aK4`S^Ujl|wkhPe@Owt3TrzDo_e=a9_|LvuC6Bm_YZy91}LQz2n=d z=;cje&0M)e_yCZ)o+rv}Zhs)-))n!l)+~n#(AB-){&rCZ@NAtO!1JvWAzz1D6U@3; zTI}Y%trd9-HZbCC4%z=+4h8|I(hnuL+qvI}>MYMtc;G6#Z8?bN;Z#m>I&ybT-|t8L zdf@zvPRc)awcxShCNU|Lp#WU@(^mL%cM!)!2a}A>N@^&aSkP^h=#?M#uE7e+@64gb zQ?ZYvNU}Ads9{YbT*CXVu4--@MzV*;IKDxk-1y|EV&!;>yO;a6dS{%S3eL&4;H!&p zKaJA7Mo>zjM>N8=^$y`LLvl1X$}Mk_Gyy~V6G;G>S)M$3BN>4I`2`ujJ&Mk*%e8DJ zcoMixr)6su*=* zf*ssa=PX;L^%Mz+>mtEkjPmGWtnu9qcI0hS$l>_?T~gHTLeq{G@W{_pvCPex zwh%S3RI?QN?UjHJGG+#D@vQyyUuYe>?$<|ttBFyt_edZR0QCFEFmSSht}qHB#~9*r z7v|jC{g+|}9O-^o14K^8==9SmQHqYT{EtF^n$sL<^`0}`VX1HGaAo)?oW|nrDJ|b? z#7c{F8e9I_lU4(QNsAee&%VxK39PK34FU`SrdAOE7E zxJEv!o2vyE?>XcULD$ew{_Xf5Z$(wM*o!vDG#xc|`=gOU?0ff*)cI(0wS>Bl2<$z} zKoE`?C5U+XJO%2!#O>#P62azEY~O`uUk}p%m$ESPzaxpxfMMRC>vAi_D<18{5_fe9 zZWKErmHkXjLIuMR34BTlWKG@$ZkJ#o>ZF?+T!b!%goB4Rq7VmTv`aBd_jcdP^bH+7%)>CbId7cBY$iUW zn*)@@rF4PL2;9K;)LMwU8$c-Po)_?`*351>+>6lXm0k3|9~3+t?>{^G;!V=GFMr`@ z$oPjvAmu>jNC4rsi3F~g&8h^Jjimch^1RoFW*bgeM?`wWL4{kVq9Ok^?hY6&;o1d~ zHZ@$VQ2;hYhw45&X?Xv`4781UxIZ{^>@q_-opRNn{*x}Laix?rZh&=pgB}H^V-RE@ zET!lgU~Ab}hR@n~)^T|Z9I%;^%!<0+E|E8lo{&Or8@XUyYDty-2-PUb@HzE1oU_8& z#Y}@EJE4?R?P6TKe)awa-KoRVMlJ*wgSw+B)J1iS%*I#hluXTyN^HfnAzB~n8gDrL zm`w%8kXXh-QfmE8NG^mJvOef`6p&28GAr(i5}%5sH0bSTb4jY)$zc0@%=xo%GCS3G ze3C&s8f@fBoUVnSIHAtTK-@QRqI;$-v`!zgLkZ&LY&^d0hLXHE=3b~_44*`3ZvNvQ z?U~B>Km52k}UyU&8 zo#H^inzW-vb7}Bid_?m0onIB3m%s0m= zVAk1^LReVB{*pjMvQ+g4LKE;tLXuo2>rg_G)PN8`6|zHbcOt1KDLJbttSP}GQNpgE z#wZSA{J0~n@r<$4|7i==@1=C@Qc8Yr00ck4){T*^ZxnNX&S8L&mrE2EFRjksW-Dr@ zUOW~nqw?(qI=7WiEqZLu3z$*X zm=`8QGby;R;fhthAFGgLazfeX|9x_jWGTH?e>y$B1@ zEh!z2U#Ouoqe%_jc{rECz}oNX}PmAQfYPQmlIR-^bp17>N95wOKwkX&9fH;sq5tf?;pz-6siO%DQAg2~4ltlR^IIcRM^9-HG$rL12_C*)^U7-Vr9x)@$i+fajm zJ58UrGp%ILZDN{Vtpw=np4+~sZ7f}cxLYDbq|8u;9K>jmZwQG!8VBRYx~~?ku1*}T zEXCht^;fnE>T?b}i_*5X^mqd-gYhMUyA$9E|> zo!KR~ndqFj=v<_&OnUiQblh>~miMd>4=z0XmfQ+tY=^RxsY~f$&O}WZ`r#6A`KePz zwu^m`vZOlLYLo~Ps8=cTu<^q2_nGrZD+k_ToqZVXmDT2TMF;p`Wh*-PG&Sl{$qGT- ze@h(u&SqQFw)-tMz=m}}RGUh4hc@GFKJU+cHZC~xEhNgoey_5dw`3B2RoozN3R9KDtK*`!)X7M)}c>mq2L(eRA4e3Vw(34?^-cta;4s+2=#w zfAo9tJ9z8k0+kEEYJer3FMKTcDNkv*EXhZM8ekn> zr+7Ql%2Iic}i6#Q%{`Yr>9*yRI3 z5Gu1|3zkB$y-k*Qj+M-fcV~z)Wq87W8JiID-Ys~J)I5xDP({Lw8(Ez51z;7?VgDvO zQNP_1Yondnj%yZ+d$Y{xS_AVLo7So*= zG6Xw0VM}O97wCmLF#?S&`kCgF^Q^DcThjKqaPD*K+pF;-A6~1PlmW&MGK1Sp06? z4CYBsKBLYnRAhYavzVVlUr?3DxzNVGEW?FF8f{}9jK~)nUgcFV>YFllHFapU*}M>} zOBYSO|EYuH8p;U!$Z6D{tl3d^@}y9^Jzjemn#fGOZpUXgHVz*w`!Yd{K5SIXp* z(x)~FlvKHrc4b6Nd!&D!F_!Yq2XcZicd(-PGuy0$Plc{|+8Zm~e(I`SD#|Nh_SfAc8qr=`sVOU4*=DU{MNFO|xyyDns@A zii-L_Jjy%?^tp)IMNYg0;&Kh+JUd_enemPON)?$$Ixzpu=X{7DL)W@p6xrqqLnp_B zP*HWeJLmaj6Lzml7+n`v)Ulxr?Sijwa&PZ|77r&dmx=g-wCUmFE zVc%t5(E28{<8N!n=WI^1Rt^TttBQ3)OUb6mKP_QhU4A4DF?J1&_U~KlLzxGyha@?S z`rDqYYb>@DZ76o}6!dk%J6KU2pWoK3z4fKvluQM-S7bxo#yk02n}p8p=KpF( z`1vH4%%!u+i#!BfBCj+)Z9ihpQn8pmLKN529NxUzZIHsu(e)M~hrZ1!;(r$mR3}NZ?vLim%fk69lBUw$jkNZ+hFNv#=%A;|j~ z{tPgPxI?*DKW>Gtvi~dRiW~tuuJ1ozFZsM444_#0K^{`vQkB1|5xF^ExJ~e6S+{ao zm~C|Hx?-|();K0sA!=BktubnK+m!k90QB2)>u=V*!=nq7gC%U0YLE;DYfkhR<85+v z?oREs9esw)l7A~N)b;Iew--p||LbQXE`iyVuqw@0P=pc60*G>l$rsSjpRUxEjz4^Q z4|v!P@%)aT8zaTa?lW1bAxQgKxSfMaAdqLp8eDN3(!|o=dUw969G9saGG7XrJzD(V z1QMWl$y@j%A&4Zdgl)X!mutpyGTEnw?n59cjt$8!K?HCqAxcvbH^LAfA}(Gdpi)S% zCqg{w^vL?|Hs#afqTb_4_0?rEz!$Q$?UXe@|9{lc<$IrLXS!?vd}jbO(7z5pgg?(d zUh5l?=v`l5Jkff-%DhG=g^BIB_mbinVtTefP$+9s&Tq3z-@6 zjU5h1URF-mNh}z)d&{fmS|L8%2WJZVb4?^wJyU{8`v3Sx)kZIkU9Z8CvkNVWIscxV zKk!UhZgiW>S5A_7w4xNGa2`g|UexSXxUkZbB>SI#^!LvViCn|_0G5PV#bJ47qFTeX z1avf8S`tX5TK)E{SiR;ExBItzogH=(z!t)=J5cz$(P*vx+ek9Swx6F`9xA>dK95pS zrgq({xx;}y;>1TwDWxi1sl)g#8sI?XKj3c*ubF9dX1Xp8mfOSX*KXckZf%Se7~A~o z{zJI;(f%pJtc)h|6EBibw=uTElsYf`b328stj;!x5fz@&8UpwYkuc@jwV^5Wm8|7; ziluYJImg}lMuf5hZr!2G78SMj9#=uklP-C11sat|V9w!+#!TRd6u=QZbRlntr5aRSZxY>M(q z;Vkty8+%INoF1Qhix+3RebYO>d%J>*{PsO3UKb(<=JO6u$%2-(!^l3*b8Dnre0os8 z^0-GhDT4Bo@3dj?s`I;p{7+t0J-=7X+Ebhth47y3@q2WsA)ATTxZsDO`1i8gk*>;* z*R3gfL$;E9K0NuZiNF70c`FkfS+ZW?6dAfim*1=K!>I4B-0sV1qp*Vsw!^l2&SswDPMT>R*Ge zo)t`ooh>+ZJic7-qj(RQDB8vQ6- zhqAnY*c3O!ay#In@4P|E*rA5#HNmM~TatYr)nL8#kMwn2%)ETF7cjA8(()xtvpF1zllDC!i6O6UiB#W-4wpIQTnGlgl6lZb|kn*c;@-&&b#3yH2%z$t_Q7c*g8uZ+v3Wlsi&LfZ&p@*7QmkMUN7Nfu4GuM z%;4euR~`z?g`-+kimk86BDyq+yW*DqtA9xll%E;%fRxz}!5< zvQBrMiYjE*>TOMFeQ4HeSAvJ}!%S99m5a5;1k`ql7gnhwmaYL6ukAkn|M!pFMUy^F zi4Z{R08r)LC`M9wPL^}rVjQm;Sx7k-y~gD;?tfA2WD{t*{bFsIt_BVQ>|pcPYE+95 zH{spfE%xq=ae%rXdFVAK?1bphH|aCL%uRz0zmq;PAo1FM?T;0wC?-~ZXO?6~4@>*C zSX<%tU@ozxm<4}l05xht78V`@Z=E>2*G_^tjFj!B=BR%%t52zpE@RuX89@bEQTXS2 z%3K^A_?(kC9)tS(z8lt~x{pYLTZZUu<;13G9KNou{T^6L@zo^kC)qR_ChX4DRxlVa z0`yz=o>dse9FsWzGlPr>5F+V3)yPA=%FL8W;;;eHAp!bpS{32)2Fq%@>8_#$W zsRa^sAr6vmxHi;c`!;vvYGZIwlXEBE z_uN)sm5fXw+Pg!fEq;N8-$?(K)Sj0l7J}}B24bsklWS+ zow3lltlqPnM?HH+PniJ!PY$Zd0heh^S^Xi~r!Y5FdEU$eN}!>)27bDXrTdUh{x9>- z!Yjwe9qeQeZDrps?OL^?h)amYFOl$5Uo6TX<$-0hf?oz;EVj}aeS46?Lb8)i@{c2q z+;5o6tryN8cU*C|!-cawH#RO*2@`-)=j5&)s}RV%mv~8;o=Yn~VJL$2OufSz*8rpY zH{g*V#>r5^AloT z%=&BO&A0#tNL{Xv+DoJ+C=)C%82ziIiM$*ek=f4u>*dK@-Jq#Z-M*#&<5kn76K%|IB6#?nJ3Za7_U8G5qE-D}*O39P|UT3efp6BdyPG00? zW-^nRB-edk-;V;&4~mVs2QV*fKBOPEhomQ2vQZAr{ zPE=cJC0Q&w+(otu)OHyCBp^C4n}6`mS>Czi7a#7eU)Ww`s;)Ut4w_?q(w7zl*n#FM zsen<(Tsu0(F-R>On7m9s74^8|a?rfU6IdVt$#$1fnx-C0&v10-QN0JH#pTzzg|(CD&Z`N*_t8iO&O7E2IGHHRBeZq8kS!webdMJ#gT1ydWwsKDM?{$s zBVziArK8jgV~%AcBGnOEGc1y^D$?7WOiT|X`ZY%T%h_ia5t`xBN0mN>MUh_Vvajv* zSf~J*UAk&>KJj#Bs}8;r3~G2%KwVvs+m-J(o|Z9}daQ_#fJYI0V4;;L<#awRVmPA- zjehzg<}skzn6B-z#S}4qwm;sQf*Fm|w328T)xc^P>yLK4g?O4PE|CBs7D$Y#$$dK0 z7|*c$bXPQif*-BB@jl;0(`ARapNlyin698oPSfpW~P^W^ARjAPEyBZ1=B>X0ND5`YgRA=#5J$j35wK(~yM zjC%>7XxVdksEJsL$qda05g+Z--=!n`gBfM`2i-vezPj{+KF%0d`jk%WR3$p18XfM3q&I&o zD9U+To<3AJA%fkPDI^^*Mo5LB(8<9-WpFYwJ$1k@{XzOZ37Zu94`4*8TfVk<;isDp z*rgZ$7m(Be0JNI~jA&@4*o!K)7e2Z#i=tmT{Xw@_2yJ5T@UguJ5P&S;X>tyI8nyYE z@AE+_sn@agocxmA4wBjT`D!s?l9c|;N#bm;wOpPO1%}ftvK=S>>-%`a(zCu#n6t)S`<~$Xn|KUy#YW88`13{_%$vOTMu?XxT#SkJ@ zvz!9}xqx^M$v$^v-)h2CYR5;)56Q`=kjKQAOW}&TJE7!VgnjY-<0cBFa)Uk7y+2Sx^vmVnN)QIxw6tO;1rbE=B$5O z&zsxSg$!eG$0dj-2GxM2SHU5z?I3nJG+!&Te|$`M<3g=Dia5N)85;w+!$B?tc8ih} zic=mIzi2K#enB$}P#NUV%r5c&gAj#XluKyu_k?&;^@kL4E$HU%NDAuADT- z%$2(s=?hdZu2fPT(;+126Y!|tlp3mWN-F{N8;`0PwPfad{Db+HwiYMnqe>fiHNSo} z13g4Iwp!d%uzVEtl|Z8!YNv96Q)aG8ma|&Gs#@e_wFC_y>v%!#3)x;d|5cTJEe{QF zv7~luHt_PO!+91*tv40bzI8gDHAqFu8xy)kk2sQ2m1wxD-{9}ra6h);K}o}- z!G_0Q8=lZKhDbDq={H7rHb%uZMwc|k4mQSrZA_qPq73Ph^_x;Wo6=&NUX(Pwv|=*s zZ_1`=&Q-KX8znG;AYMYv#U;%pR_3nj5j^Sh<}v0OcQIjFE*h}AAaS+4Ch78*>E zh%kCqm2K)c#1DP?5DeOK6l^2p-+vO=>rM+q;?N0L=uKlp*I<8*!CbZZAo`^fko{|IS~TuuD&dFR7o z5Pkd-46=dB1BN%^hCjtouN$KmjFHl*!+QpUAkhCV5p6^Mf}+Tj$JrVA?DUNCeEJ^} z(aG=skcbZdEfJkjB%MH$apR{3^WETAD%uh|0>!DEd%QQBh%G;hQ&a z3JMDTQy(Iyr<0SC$Z@{p(9ll_p_!SPFJHd=w?UMgocwQtC^|YiDk|!KV2J!Y$)28M z2UD_{8QEBqtc545C{+8nQy8L$4Tzu3x`yYHDg?Vq#=uboJ_00|NtHU0od=9c^vxe=$Vr>gsqrUR71~UlI}d z(j~HtFj-85jO8V>v5@I8WE9;$3=s@Q27?EAxG7YToSfXh86p`O85|DxFNx^?$q)$$ z2=M<;5)nH)`@bY2W@hI9#E8&nGzx{HrKP2zp`oUxMk0|21cDh1hQr}hR8%k+3<~|< zB%)B@pU3|p5#<#8|4T#`8iU{noa6gU-5Oza$OWD7>4BQUk?j8$iHN!QLy2_V$=v(8 zl1~+OT`}DH|C2;y(`Z?_{dw@ydRz+uLc?RwSh?IqWK8%r*x1{CPQqkX&Pkx!>3yo< z)$+`y)%9UP)i55hhxhu&MeC;QhMF%rGLT)azcOs8|2Efn_v^w33WE3UiT4T50@g5W zxjSCqzRk(e{?v!;ny2SpN&ngos%SY=gtYu#q$EJeM_1cg|NPvXD7iI~<-dDKUDtJ4 z^vN0N?;&iZp*_2O|K#BGH|Kqzo^>G*CS0@>N_%P3?$Hma>BS(%`kT2CVBtW%N1WxK z>Ba@7=QE*OrTniQ@d)4heWFvDHM)(4zz& z7zGk~W^ie1HQ888tRR^;eXrxWxl6J0bLx3*0fIs>t8jqhvp+)Vu7^F2NkOOm>o0wJ z#au%q!8ih~#%l3KR?y+rMmFJZ^p$@kBDWkFS^)oITzb|mgGrsE_%4GUwYAq>hc%Zs znE~5dg+U*qU1?ao+_#Gj{dU3dqWalwm=rCUuPZOr&%C7Uxkq40RLk29Q8mxdjL|op zES@`6nbk!kjMSxVU?pP z3uUF1?x-JfE-8C=dFADg2DkkZm&Q#n{x%89>Q(t*`~BD3wa9YCini4;tBUsIOQO>E zFh3BuW(e=jULTemD+r*@m*#Y_TBTK`OT5(e?V-KRS=z)M<@NJ}9Ov_0=x)d!y7mXk zHTojB$&bcNw87fuy?A?E?u3z5Y3(p)w$=VU_fH;K!?dTrz^TTVcLx6$2fD=NmQIoKB6! zH4**rYxpR{ku55@)3Izc!p%T{U`On_)a)CnV1PhBCMrCj?Pi!^>zD8X0T)gLcnERY zDlQ-bUbu?;2^&$Y6am1FR=8_*pfoW7vb_VI;g33;g!SdPuLe|unCv>);IA)#*fWeT zGAIb`ysYx8X+P!b-14V~I;!{QO#-_VGk6Z@p}a@qaA|;a{uTgeia$#V*bfydPkPF| zTJ4>7;B-s2nAO9!C*zYWitn!pEynUZpR?=~`wiV;KRuD4%`KQXRK0KVvme$A(y7`C zFp8m|9Q|BG@cTV70x0EY9SxekY$M!zUZI@rbSeC@iMie{%@y8Tjv(%x-nQNbumBuoc zn3OGnzKd-x;g;#SaQjUvDX2rlqwAgUThmlxP=?UE-Fb*d>Dv6zaoA(L10shMMb9*D znyzqIC8M_SfB?ilIO)2lT3di;_&s#R0?c)Ui;^nxNz^TZ@RYN`1foc>_ol-*<1qa+ z4?zh}$g)On!2Z^1b$>q=6ofF&bFBpod+?y|Y0xUkZYkR`#JJOT(;gfF0Mpo06d2Dm zhv}CD#1q{Fea#EQO9T5JF%Q&l_|V0=+{q3zd|8_&{3D`*`}tUc8lvIivfzk>0f?}Q zg3@nebi^W)Oy``_g<|(Dk2;s2+ygEOyaz0zC8x9AL`SnI z%JCTZH|*y9*&4Xl?od166C#&`AV}|oq5li^>3{N2s$vw#!_IP)K4kY zjz5ek%>2^RawV|}*e(WpuoP07hc<&D4 zbrp@C@(TCg#6Ats(HAVbsb8B4|4cw>c~||<=x6<}mQiv~adse%k|?m+ImKMDfg+Day(M>`AK%-8jO@Zj5PpS$rvm2@JpG}d(IxnW zsZk;-U@d$qxzo24n-=BZ7O}TZ>Qv^#uoG;s-242iys}H1ylh}NE$QHm;^~%gLi1!H${+R| z54t|mJk_A$kD^_MaOptcPp=+UzdYS>GisUrboH<@;ng>vgqHcS?}trur{6s)6c>I! z{S7yuoae8#Ed40|-I4v7icQsMIcS|(@U)ZrfEall&S3iJdH!q20Oa!br1+FsrHveN z`pacnAK-{L;@l&6FhGQLIVlTt^`CNfx3|p$qE}7 zMQ85@poj!IIRX)W+YI8h{wbu7|MsfOZ7mU`=Ds`KO*0JZMPwd$ zwwLx{j{6|rg%!B?>PCnPLPY5`^~#dl2*zEEO#$i3qr`N{aU%3E#2v>N)|iJiBDiEl zGAk5?Ji2>VbvmN6Q{(y+YTu5g<6b!DB~SLt`Vf0}qoYtNp$NZgSV}#9a1`y~6EPDW z2JWEjtAyAdMde*~*VW;9-Nl?9q42g#p&X)Et)W;?4pVG)#N=Y>puTh|qpZdVUS}%C zm+6>S<`}~q?*Thd;HK?#S5)?R7@;vHyV`kiS!Gv1^}tc}C|~vDiz)yGz?yifaLQZ@ zN@2A~n~?O)$W~`xbQ&)Q298KUW)m?M=D4^0F_Us4rPo2z>G89T@$=L1)BP%bvijec z;sCs+78KBVt!W^OF>=C8;gMi^>M;`A3(+v2z{?N&*>v&n+JSJ1qBKJ#f^1nW7D@(tdoP9U`j}0oBokB4;iFOBk!3bgSRQgas;I z`X#Da7h2G60_a&n(WV&0BJmQtAe_9FsL+&*7Sm^VVWIfTpk-3OoynlDL~x1_5!1WgHyDZ2)x7}QT4*cu;R_A%krt&VLml1z(RVe$BXzSB4+y_ znaK8hPu55pL|c$Z-9qB{B^Mzk@9?t&@WR6hQDE!nxLk0mtXQg3Q@YPe%%aJ)%R)ZB zO%{!{aw@Rvl8DmW*tcQXxl6iI&>j#xwfHA!(eOtEy+v+hr?bWaQ=Mke2| zNGrJZ9BGs?31l-{=KEuW?9f-B8N!s2-h;TGCcrg3+(HadJd+}P-DA8cy~^U1@=E$v zN950{G~d8y&mDO$X5eJS8M{w#1~nU16j~!{u+0gts9wr(V4x)Jj;Km7)A8fbhF9h8FLqMU>Ui{m8=a= z_BX!l#4p*|nz`%rfC&!nS?LWQ&0c>X#`0F3?QO2iY!=*um*+hX_U|jfx6y}U7zrHw zP9=pcL7Ix?8Fm?;_t277$TxV)!{xzqxtT}aLtg5A+71YIcL|!SWhU92e@@|5#msAm z_dLjnbC_P96bD&u{DKOt6;$LsO?ZVV%p1e-Uf)(*haiO=J;;%T~nt~;&P1B>_ z7I|Cph+qq~N6{bf>G!t_%tNvsHNQ@KSkiS-CLmNKYP_UvRwQh{q*I}^I#2YOc=4Nz zx2t2&yQ9#EQS>WJa^N=W!wj*Yn38F6_hxa79{<~gX2BbNLW>IJ`s#`U%{h4kZ#JaC zemJ;@9c_SUS#?ICuK3mZjIyJQ!nus{?e`UD8F8B(rAC#|(@I(ldr4u8{6__mPZ<@c zmMD(M^4kg(pT(*cszAOtxY$2#Q1*UCwZbC|WjZGwTg^yQ{Wt{VgM*9bP@VeFem1LNd6Y#XAtKmP(>PnB zCQ-W(Qrf4GqKku@V1QRZF))*#*`JXjUgzQ|cx+jB$+N)Is%kX^bO#5QAb`uMOAKgg zqr|Geq}8~#)Lf^jH1tgHR?J?nsrzUR9TIU*)%y1=b{ogn-Ue9QuV9SOPUodc_KLhgHiMV9+dm2Nmi|7>V3l-&uV(B zreej$aL&fA+$ISCP|rZd%~jh*ymoGB8Gfn!?rTlEM61`=mae^KVdE(4w~g=T-1FvI zN64PdMG}pZoULmu&5LTS02bjtn`%Gz&V0HN!3U`#p$-Ui7TBBu&Nc0>!H!Kdxt?!bf-#H$QnYE*?O+yJwi_)RW6VCHjY@}9aY$ftlsZ2e3@aVi`kIbX zDW@VHE7QKq;5{8?vAI0XR|yFj1i$L~F-U@bc+Y8=!~JfwMREc~wi)j4DE}^w88`UA z|7zqDZQFU}x_+;b$JUcthLdp}rG_}n&S0+?_qcNWEjBt44(>@P`^3$X@%xV^b(G(g z(-->Uz+id+?sdyZd4l~?v;ChBW@WkN-V-XXMg`uv+YA)xOJSfbw5t!MEtoQ7*3tXzya1I=1BqpPP`_tb1cu3joRP@ZtvKjfJk4bv- zHnSYU3UFN<28Hv@dO1gYH^=p5yv;C`q&y$V-BZauS9zMlM#f=uVrfyB_8FTN#i6;6 z+{2}YZRM{%u9bB)KgPT-o`>#@tbUjYrkmVS&j0k`^W3+TAMeKByn@^%QTalFviG!1 zpGP~Tny#G+-*~sEGQBuCvBZ3~I5xmWkcTT!(gH6BM?WthLRw1Z=NN8({`#TA`oqF+ z$xn}SA$M^w3Kk?hnlR|OJQ_Q@5VTUBxx$k+c;R@RQ~%nLFtS=rLv}>OWfAkc^1FNuTOtq8<|f90TnKfzmRP<*vXGK0?(ozwyn#xZH%4HJ_L<@ zRl-!2&_43s3{qJ^4-3<`ZOVPx6!^ROw0u3kjaAqXb1Syh8n)hZ`fi_g+thYMBX~`9 z;iH)fqpvvJK^epN`1QSott+kOPxUO8Qe=v&zS6TJTV+&9@Iz>BmD z+biuQt+DX#V6rzERQDLOzW+7YooV|ng=V}d_615-1KHYcPuOCJDqNEDA1=kj9%Ua`C!P*m1=%;I)*vDN;;6E3{(_h7 zN5A{^;?<6`5o5?z3_LLX>p4zQlXBcncF?LjmKAiSx(jp0uP@uqxhs z2<3B>r2@2;=#DGVb2(RlUD#$$@CeQa7&Bx5LY>cSu<4`Ys*$uBg5hi?E1EIPQnuac zCSSCkaw`Wz*-ck4!)iH$>D|=YexGL7Mg?HfN3rTe z2K9O8KR(;GZI4gSU|i zkBx#_*O)eA+c~+GfS02UkbdbxLukHE%DHdfm6a!-n8Kgn7#90w&9#7V0!ti3Q)^=Z zY>v%R0YtB4ggYG-(g0c=!h9BiYFC@KgkM*x)12=%&fA`xh}QTzb@zKqd%Zp(UjE*6 z=>-E@2478#zPMC%>G#<63?2v4*hRh_U1uV{ov$_((79CjjJJGAh$}oGF^Y+gWz01W zkv3SVCsENYqn~^!sQgNM>nhC?Y95W~r&qV=phK$EDvcwM-xsjkR}#6ip#Cc0}ovY%_a^p(p*Locm2 z^7RCp-D8|w@2+*bs;BCAaKpm2pl+&7(k5l1!`wUOldV6Uq@vJzqB`N?oWTuB#KG^Q zS)7CaB}@0hf_i@I7ghmM??E7rYtzcqpxseu^zjKob*mqeRS8Ub_pzip75k#Y{vFKg0d9{>Jzb0+qf<6ETs zk|;I*@ZSN=xp;Y%7vhmZk@p?aZbi-%##}f}TaUZ*o#7hvO}apIXp*|za;B%S_Zrda zsl0nZ+M%0E_asbet(csnm9S|e{m~wEiGfH29F=}Xdps|?ec$%=3oS+OI*?EEwfM4i z)b~c;RGmqAzeJt*;AisZZHf!e9tq|1sXX%TLZ>x;D_KKb@=0cgfAVc7bJtH3QF3px z)q^9rzC?Uh{A=H>E%Mm5XXB0Hr{VVJ^H#w|Yz^~7=ob71wcHb{g6cJ?)_aRj(taKE z-qe0^^sc*nAds|27ibqvsR3lGrH-8bjD7@HdGxJ;6k;p!qQ#AF~1{<8j z`ed+!vp4wBpN;JDMUfxEwel9jS9cWqmS?Z$_hyT8ZrMcOjIT2JaPsAl^$)C5ivS zF6T7>`zg{JTvy@O8-oz}+kxbMW^xrFYsHu=r>&s(nmY;$QrX92_)fkUO;HP+^@{e( z?Bn>v5+O~3)#1Ui5V*JCDyJ?&ReoyhnbCC;&v)r?+(|wZNgpL3?2y(%yUeTVh8Mrl zq-Rz?o>CF+EO~7pMAiqN+R*KM?v}2;)%JK=`@FMMh`fQrB|=({rpvj67w_Sk_I71K zcvqPu1G{tN!1otQAQoRy7_(O_0Ei7~6qi`sQ*WfHym z^z1uGg%m0}DGl|no_NK;=Zr9je(zmBncjKNUB8Zf!fE*VoBrA@!>FbqL^=XlCaZQp zoqNrE{drNlthh{z`~WnxCg12|)_JqB0V4*%=i-WSd;))Jk*2#Yy7&o@U}$tOo8x25 zPVR9!N1wLZ$FiB@2#I|nJQUiIVD6v)q5l0x!G|}j@0y2b5~tC^f#=I`?~7V4{Wa?q zH)JB;ssu4>cA%x5Ot`FrdRh0HZ#MV__?}Ud7}s~9(a;=5Pp$=fn&fE@srsr4e|CvZ z--LTddDTFoz2d5UEE_?(MCHKCiI9N;@B`hR=;iZb8wVGKF8RHh36El@ zo!_%fXlK-to)wqu_-f|e`0DXf;}sk@nl_L3JtD*Y*1YVL>0q50)&8KFR|j`gTKAAV z85ogeq-TN}V}gWy#&}v65%8J!(wx~Ldmb8Z)XCxRt|5Y0Fy>{tM>AJY`@V*?JE-HTU=M@vH5UY$QWePW(3 zaYrRSXz*0=-<;{>U zrPTAC*b}Lbj@a2af!WXfs9_>}c8plp@_Cmf^w?-M*uQz?@fQ_$9(TUbFlR#9qNbMa zU0u-3xg&M%^P(rqSMK}_5_q?BeCgdSr9-MOV7txJ-SC#v;WdV9PAuz<+VU=AWJpZH z!tXohPq$3&_^kYdfmN6-ij$MROzJBv2ss`9C}>aXjuqU9`yuZSzfdZM1^6$yP-XFw ze}62`SeVdOwSW8Lc~9TFJxYv77lSmXY<{qhd$zAEqRB(q%9a<5+5yedMUS@SyKRGz zXfTO3R2RXOSZ@$WIH^%VI<>Qu$l{X~K$G|y0sOMY#pDYOZAUWuSOjA~mqQNW>)rOf zIU>z-7GR#l=2X5Up#rJx;G9R&`GmFTBB(dx9F3`&CskPvF8u5wZ6 zQ_jvKPUKh&Se74Ho4X)Visv6fu%5KjUhl+tF>@%9W;7(kXpspos>tCv=Up~iD)LFf zaa{>mPV!e}>F%z}+a!(?5_qSpSd^a3hnS_u5=YhL!#hQHR0V?6a6?_%PMk8`9hg-O zy@Tj-0mSjk`W*dkkyUk^L-%=2bsfPg!mqpJ4~QBDSFZ0MZa{(QTvdP+0#H{GeR|BC zt~@R3q8#Cw9`t;W>AFDM>--Z5HphqJLx%RkuYKt@nryowTV--`MM<{j#!k1CCSLAk z%z2s%ypknVo?5a_RrE2v?y}l0N!_Xkq_RP+xKTBp*3NhKDv2#xn)iC8S9?Yk`yR)2 zD@$r%RvZ15qOX*w16Ya6265K&M61aj-=CeftJ-%HCozhXeZ0#@ZT%DN5L%s- z&1NCdJOi9UOp$J8>p)z;uJE&7O7iG=t!_%DUh1S)MtVE54=H#WI&<6~cOY9gu3L0) zrTDtuTP6JxS=kgh0!%Yxa}RplNqp_}z93USN^rn3M6LR{N=>PL?TLQfs%(bOC8i?| zN1(5Q$-uAV-RJ|owoH}wR((?DP!ChXDQ5^|FyyXUCi_0>%Q=z#pIz; zs9}cnhmqF?AA?juK5s;cckWLikmW9o+yfE&1cC076PZG*ZhF z_e06(;NI{!m(l(~pRTNt>Va-jBj|7ko=~e*$)!E+B|cGV)R27j6VqsF+=#J#*x^o; zNR9TowHnyD1VYyZeT5hcH>AGN9pW|Ok~oSqH2O?y)Yok+G-=%HW(boqSy75+MvT!5 zjZx7JGCm$=O6g#(>tXq9%=>L@DRcN4CS=n+@^^PHtM~9{u4t5Kw9XN{%no#YiRvL6 z{5m!yd^GgdQnGDjXgC`|do%J84z4H188OOi7o0Q-_GzRl!-ZPn!gvs2w{u{jyFh?j1XdJmDMwN6BfRCpxJjXN4$n;4 zz*Iki8jbT=#sM|y+-xdPBNhO`0MC=cH zWDWrRp((kcPj*27TWAmh9L*Ntr9-qJB*sh+8rLFr-= z392Qs28Mg~M_H4?>^>52;$Xn$4I&=uk0qkb;rf9D8abFZ!c1o=Qk&x7*ijrD;<66n z3tlW@kjCR9-m{<&_U^q>9gz&lshDL)`=nfxql=E3L}*pQgLUA>(+RQD5U=$3Kp_Mx zCdya`A+Q_ycsj~Ey-~6{%54{{`3DwCj183|Mz%0&J575$zUCW0k#})64j*!NE6O1! ztToKUyQlRJ6OxSprHDA@2#9Kbq-_p$35j|Iizwfv4h3kcurxIQ;l>dhizP}NMLB=A z0McWLI>ixmvj=z0<(N!aBP^-DA%qhzIZs!L$myAXnb=bLiX6%vHrsMq-@0bJ+&$&>89|LL zLHU9A5H*A0=HzbfPtO9QZj6GX8wq-ih@(XG-%9k!DEe#{9g0WueIK z_=s@OjZfbOa|@Ke(%y=WAPOC2T$2ZV;4;|bUhL+MP7;b{M}}}TC2@fW+*?V!NCp50 zcwizWNTF^^mVh0DNC<kv%F`LkQYbd?wQEN|`qT8{rP zNOTJ)YfVS#%6-xD3AZYu61{CBmgTT}#o>^-*H$CMK$PF5F`O2Q0AbQmKR@#>7~Nt- z{!7Zyq=Mhxj8Lsk6iszh%U@Zb`!X>|&@XBY-VC3kMPGJP-c?#rbTLf=BH4QxbhDf; zm8@PXGqKbN(NC;LZ4ZY}6S$#{0^gUVFF7&UtQGzR2ShBKcZ)G=bBHx4Q974bZ5q~j z+7NnRC0*`F*|#zE88;=Zd-b}=nJwK~;GvHsGMsZ!5O#JK*3wiAHEe80nTE;4BEHbB z=`XCg2P`H4kw)Oipea|oehXR?=R0Swgd!1G^Utqv>s=|XU#S6Mxia!g*~l@Sp!jS7v22Y+|;M03!5MpH{-Ns!{;QW#P4mm)o;2Q zI3!>}*Qo%OO&8LUYrIybnHwxP9hQ4L;s%9)N@h>4cUM$#@6I8p5qVzsLr21iy95YF z$>xJ|8xK*@Hs(;GG1O+sB?ncg=VRI~=T>;zqYoFNPT9H;4e!oGU^5_siAMFeJu9f9 z1K7Ys3^+j4v!?zv4ciQd4-{&<&3$gQ_v%(V4rF*X;&=pA9VR|W4h8pn-VNTiWkEj3 z0TXjVAFz3KzR9;W{%<8m=UY#}+RgHw;(bcP~8&$LL+~LrkPz(LX?r z>aPtsmG5IOqN4L*UtWR6BX5Uab>mr&-G1Yo-}2OTYUjJwR^Pg`UjafQF~Tb+((EWi z{Lj|m)t8=b;p~BMSV!nxHrL*%Yd_Auy(=Q9BXUmb9b%`yl~3)`HC)=e=OgkSLg9Wv zso^$_yVI$+kEbYBV0dxccOp-Gv=%)B+9yxQ5uA;Hksx|GP$eI_FIRn;VnQU2=B04Y z{~mr@$ns9a0v8c0j&2)#@$OnL-5L9gK({(~pCZV-OH>bXs5}y*yo(lS+;@dsOY7FX za5tlc+}xcoP?wXjj1X7b059omHNFId&2$9&?GPL6*I(b=o_IC=h#0)H#)~0{-h=Eu?XHJ0^Y>R&_H89t;H-eqI`bjFSGP}92+)XA6EH2 zA`Nmp+u{*;7g^c74TeI$r9)zXaboyxXn?uD*_{jW75kt9Bxm;a)$)Vz&AZsXA2{^E zGeU&d5=F)V&XK5Yng_VF%eb-zP-3O2mm)1~b)$D3c%TQy*}wTEqZvrB;Kry&(@|Fa zrdKZi{!<(&D{>TC7-^BcUp5u+6bC}hz9g&dzP}%ZxD^GqE4=ST{^@-=nimJTAZJG9 z`h)O<{bxDU#D~u-IP$)+qFBR$J@2nLETER|Y*T1Mn*lK%K8pSH;E}d((jt!;03%jH zEnNS&-u#`)Dp_!mYAt9jaKt%|^;g8kgT&GGw~H=>-w*ygh=Lgrc||v0;(w=+Z^suc z9a~Wm?_8y$YV>kF&dh%JXknxAhwEkZpVIp;?l#&30Q4R{@U`m0d^qs)bi}Z78!$xh zr#|F03Nq%>Z-Hm&a+73Gun)P1vZiqCV zNG3h(8{tt7j0|v#avcpTMjZDP{v^lRg<{|Qagrd=Ed&95kAozmS&m@A({LVuU?v*j zcmMRP`E-2oPdF~5QlIyJg?~5tY+mH?uF7dR0cM*H3N${G_L-V`63i4E+`xN$<$b30 z#(@*^w9u7&81-=CeDvKT(|tI=W9)zMpAr!@tBlv?KN1mxh-sjTnoV*vtLolN z!181}MPi~krxUnL@2Gm=2J!8M0j^7I)Qn077CCE!FQm-8*|rvo!<+H$pX~`OWrOIR zXE(n6y|^=7?fNBX?*|RQaI}wL+E0k>Og-;-=bZJ)kG&8$we;7hI9-bu;wwWT8a;FAIn)}y@<@4aJRDW&Z&s$|r4EUMG$xjW4p~4@*=O%jcLMb;c4XAN& znKucM(`>Fr7o^(8$giha+#Z0+oJtDxL!6qo1mXUgksUAn1CVcCJ@AVz%zB*4{wCXS zc6S7$6N&9mt4Id}l!c~)y!<3R1+fA~W&ROS*G#n-C5X&xJvm+~d8Z_p#XkCN5zjNK zlCtK%;-yvZ6(q{)W*u6C|`(UHD1VK0O4M+mhq_k_0oyjDDM(3oLXLyc9oX^M!LPu)stZtZKvCv zxsyW%mll$Y$MHiB?6h9aP_Lof?#{<7TzfAWuNl1Qd4RGMeMV%Eg(%!WOp2;MHRu{4 z%RcP}1e!LRPh^H_X1+kwRHyStfueMQa(weLpE0JLUT!{ugXP1rzZPS+rp&2mey^pW zW-2IDuO*Vt()_~eXSMq$`RHl#Zhit739{F{{O6$h++(S}lS}iy`6(X+p(dg6>cx#e zuh2feWtS%RK)LJF=na8a2g`4{weWnZ^kJQrmxuVGxT8H?>Q>Tk-TrgMn)4upK9^IP zPVz*$`^v@R$&LE?vX(OiEy`GqM(FwOvyl;`MXWd${9^K{QhllQQDluf_p5PXpXzjo z=S3xLh73-T(}T=w0ZJjfGMd%uR+)ZJm1;^=Sa#N4J~`7c?^dU~SY-`L^@-#(QYQOp z@%qMP7*{Y8CQZ%pPXYio{MQ?3;jC+j-?V=9wPhb5QV!gI`9(XB3PQm>$%`;hPNXxi zhVV|Z=DJEy?nC$}3Rw>#=>709yA){MTsID@)4@JoX&osu3FpBu)9`o)LrZxLQA^3e z_rU62V|dPW0u*@dBW8GS1^IEmJG9h?Ux}0Tk4I6DlxYkli^$LRn-8VWW+$qonTe)L z3t9X1g#qrS4`fm1Nlb)jlOc-Xe58Tppp;#o^RYt2`VUV+xN>k|?0D&?n#OtD{#^s? z6{&qS235i`9U%^>x$X6brzcAVyb@NoGQ`yQlk?CoHZ;F8c1f<(6hUWXZ#b>La(uJJWO2hA^7O5)MqSMb~m!KIW6f>N4o#R8~!2%w8|-{ghGE zCTyvvhZWW@i$FK_5)k?XDM|CJf9Hl zn+A5!`D;Uu78dpD`R~$y~(`TD#kou-{FOn&qiWuF!p0 z)>QvEz=C;;<=c$!kM}KID6G8sh}DGmcs}a-ml!!I1H(R5Jm@3;$R?-5DD};=96C_R z#TIXR%?nO{wQ9;?5R`tXy59*#I^jWIe2UM7$JT8RWgdwBID!k#8VKk*h0*-jRp%Y= zK!|TtzjtBpcBmg(tL^qhnPOybe;BfoZMilU`#nEH%uhpbEwRhbELQ2PA?m2#yQ8KU&?<-3OdQB z?MxkmL{`G!o#*S!4r{KNo+hhLA5DSTLvVM+zmhFQlIK3VNNY(BC93ntB*l8I3M@13 zIJ!b_XxKGiZv-iOex05}B?YKb(YtuEE{PiHY}CU~c2w?Y&eJ?_mUOky|5M7jz@nDY z1rhrJrVbJVvE{Y>_P!H|f0Ikc_p@({jy^Fe=nK_Nor|84hTbw}9?Sfhb?aK0BWiPKF@1}#H z?}vW)(Ix2a$dK?C9qV`Ez*0#@-q{Z~NU(ZpmlK8u74%-)}Wq z_(kqpbcs|XYMy-Iew$#oCh;)vsqDG00yk^Za&P_^TYPuGB>z}lQ{U1u%dD-Uk0^Pz z7ysqj!i>}J$6CN=w8x^#&xlkoH~@XRz}VUuorbtqpl|b)Bl{0?Rj;a#{n>txZ45u_ zsVQ_XSzjl->Qy*Iv~KbA+8tGXk}Bef+RPJ}`Jb|EO-dzSG!)c!_1IZwT{q%kv0AD< zxTIsz7&?Jlwj>Ym{P?r@`wBD~xfE?N3)X_ZWx9pzHH4gfq|$>j%4!Q=&w)*Ko98A| zeP1NKuxxyc)s%Yy=&>W;*ilTgx3vV!TXN1%y3acn-Sj@A!dS~+Qa$$alXTllKbP$` zc9%3pU%Xm=kp)|(KNr3lkvmw5^;BNU?|`CY4Mp(wOe>n+pINSi+tlSQb5Ytrzs$7) zDJ~F4F*BB(KinHr@_2Lm`iJm~jnD~ddRz#(8 zHJ$L%2Vv5J)7%W)H*zUjUf#7S?UToIK6IiM|j@7ST$_uKPpXWn2-_)mKl1< z+UZG<27<7Pj|(dV2twA7Hmt6GtBt-N=uoc#dsQ1wag9tQ44N=-~`oJz$Zw)$xCQTgVws8S|3BpU;&7TvdmKjqQSfG;8 zsT#g&o~m#0jEvEkTD)2uGW;j?oj(`zf|JdZHGe>s>=~?|NNa-9MCf##+v$esbV;~@ zSVz?_oy6ZjhC6@(M+IRgmhL1UXT87tiYE|pr}ZW;mwf*>XBOQIvhdSrVec81(SbGh zXA1$~HJfu0p9t|PM7kM(1Xl_>?-PsX0xO)%Li)QXe=`(`8!8m)i!upAX`1B;IZ>b+6cS`Y~?%jzLCyDlE!7rXH@h!Ex1os`cEg`|nabl(Y3Q&9@Vn1?FuyFNYZ zPz}_0>LDEBSNQB)I3zICRoSeJT~M9h9VJ|x_1!Mw?Uj5&$9EXOJ!Vh1Clgk+7&AEpF8 z8|uy~EMc*EQ^2!0v%8jwFTYh*a8%YdQaZ1AAHaDeOt@bAFeqN!q|2bJoyX<^YV8}c zDtDCEe^A!^&{7lYrHCk1?6dycC9A=^(uNPb!D%+;7eJ}Y_Q*K&b7|R-wDo`-r*c%c zItf|5u(jX^8x&3F3$zf2o6^DLt8VJ1ON#HY@RKc8(CR4mu{ z`ikWF?|c8mci@`Gfa48Qjm1*|sk1@=3m_Ej?pan&mKuGderpPc3~&ZaRD<~*d(rR_*$=TQW<+PWM?{A=77}w3W(3`gwuLTs7Y_)rZgD}?4rIURYZdqeiIVj?@ z!lDJJX$X|gA?j(XV2Rpexu46x&2oM48P{&weD~__VNFf%+{za2v?@difnVgHXj(3W zUyei9kLu~cJ9Ai5K?~x@tbhN&jCn{{p2=r(!mQvF7<3Y)$iG}IY1voWvxE@7tiO@*>Rg%mQCMr6?vwn`d zGI8W8tQfW5)lthb?Zp3sok6CGVS0%=XG9iD#5=`N`0eu|Mr@c!9g>fAIc8Uc)mg;X z=_+qj!0iS047y0ru#W9ih(m#i>`ZAatx_?BQF2*WDp^FJ=(MH0&LA}iua*5H zvXF{Q)3snR`BBW{!g5o0UrB_O4sp=CpvZc5$yiQIr*yhrE}XnC|D*PSrVFJ?-POyZ z^=PGCk|UMr5OE1MfB#S9n>jO4byBC!53-rGsjt=H17Umi#ox;d%seU(^|_E z8+Dq`&ooZYSe`rJk*+GFY&~Iphx+4kj`K*UnR#3Bj8wVdxn_gjVfj-!!`Q#r%ytcr zImK?xi7mzZ$X^*_U8W-@L>?BMa}>FtxO&Cf`(%*VG-@J`9x)K2v2}aj>ARi3d85fF z>LReeZ>ohpXEt#)pKwH_DAN1|;6YgOn07e2oanp0H`1RJ*!#s>m&$PQ{6l@SaQQ2-}GSVeR$EwWmvKinMY2 zN&W4UPswvoa8>QQFGOHJOTH&8@kh|tZHSUSmpWn)j!|VWrc7TxZv8tZI{uu8ysk}d z_Ck+e2n!p0VGvAVPM2_=cC|&MzNXQMB89mTz6Y!Y@r|oSz zXBoQIUq-}GqW@kqR+IwcGhX*-i)Q_`duBkI@FX&puK!dNG=F_=zAXOcl_)B#mueoM z2*Xm4)qAJeTupMWprw>hb&-HAV92fXt%G-IBwpjx?Q?*8-nNJFHZ!UkCAp|1eHoCN zeYM`vEqAAs-X>*A=J5)LK!_g5BnztVRQ%m<9r5U0vcjL2eGGVr6$SE*ydRh86XkE| zn;`0~$Z|j1-^h=LQl6VqpCs-Js77dMl0mwap2S}JK(4g4fICAJ*KrH3Bw>HMXZGn; z&T30}a^^$2)|q!mSG1DfiFAp?byCr1MUT_!vH?&E*+q$G*=Ok~0k>h-*0J*w1#)z2 z1I(?Ys@gCI>1^}0;N~@*cUAMfwwCPXr2NymN6j;Gf!B>*Rfk@xIFC51X)_;<)9Y3S z#Csi%x5iO<5X?0>i*?^i6z-vF4|lsSC!)0O>Scr!O$nE+OBP7BmPQ+#)m$Op-vx%+ z{cTY4zAx!#3~lSI1ACml?HrvS&X;}Z`Duu6<(>BXbJ{~rpO5| z`_O-HuCG1n1Up`~8%UkZ>GFJSlWDYQ)yeV8D6^ZbQ!a!!j=RZb(Ea^UMWLn1KV|U^ z*vor0_kLcrpK2ZDy4-^#1h_J=dg#+G zh}fKOA_%}P)e5Zb6Qc>jV*HD}LV&~8tVF8|67UZ66rY~gY}c!HQdn#lF8hqjHpLbr z^MzG#F}?L$)xw5XqCn0=KAb;4VZqx3{Xj+^>sgdszr_rP&wLgbgcuXzlzFv&P9Oem zV!89jV8_?#>qWAIqvZswV(ij&jg!F7C)mKjh6DiZyN`u*4DsvKkIFQSx|6`O9Jz-S zg-dE7LPhDJ|42keeL=9aF(d4NT*V+_A@iBAsb4CwOd_s0QXkfl@$64LWmAQ7qkTny z{zRz+bMGCG@Q|!Ph=~GQtnIbeye=b_cak7a31HY@M6HVS^HuTbsJ-5 zsn+H?K;gKtmGZvY%`u@r`p-tD>~E(H_RJy|JZG18nTZt^6F(JyXxr1*hf*nIwaf&`E$mdm2eAfYV%Ur zu#j?j^Kre+VjjlY-^Kq*e}1~X;sRyGK?8HOJ4?4qvqHXay)F8={X4_#=K{CvP}(P) ziXP%0->8?s>Ty1CB{^F@6)0n3No@qr+tQ7sQoFXY@uYorCTtn&noy^8^KQI*-k-8= zmu`6Q_h^IG+k;z;Vx*k7b`FXKe0iL|FjF<3rdMWN+4ngL2bAkivcEpBCQ;CKEW_>j z;y?H%bSFq+L#?;?OXjazu4P~JVr{WfsK?o?*#~q_df}KA{?+C?yUb^+UL%N99~`5! z>vR_2Djdso+2Hqg5aqJfX$4ECeMRh>_kh|E5BU1ZIVnr?%(1nA$%J?^>u)|j5G?hW z8LQ`pX_T0&42S0kwR1}O%@5U;w&%z2Xn4?*Eu|-T!T!}{9UgvC4O5GUAb@$Zrc?1F zUkSGN*R{?ipbP8zrC$C%n9h%9C?LYnDlT;A7b3^NGLe?V~U~F&usD#u{>0htkm3`V(S0T?KfiAcNPaU7 zA+2MXXUu`r`t( zHw&BI!oxD%6On(;-WN^&Ss z)=3LX?lJvz@D~@l=CTtO6wXi7;m$QKlB#D8PVvfrVDz9VAqmrWS+LGmvF2|V#!P*X z`+)I)q@3?88XtY6sO~a_jz}3}p%M-c;X$;v!qfu!JcqV)h#H`YOP)@QieY5 z5y}kTEq(sxx_hdJkNmG*^kJ^r3%1Ke9Q`Fx%w(+YCQLW; zDk+wEpOz@0P5svSk3pQ9`;AebOHv<4G)E!k)QV(zBkMG3{EoJ6=73h5 z8Kr{jacVA>$;23c*R|L~(1!tBqIS}522qh{ud%vK^UZSRumLeoIA&Gz0(ybrtResc zH+Qr4T(}G2i|UWwvM6YhgQa!@ZV>(*E29$fw1~C9T-*Rmc6)>q7pvV%mWBM_k@Yik zsr?21{sLOsB9q*9jxEFpdP=1q7S3x)M`-S}#<&o+kxWET$G;Bm%W)NNBi}VCOF;yg zxmZ1^ZG9@;Cf)t6vCjGPTUkL(LfnNH_!3$-Ht%9pXK?zm@4~`%^41NVK1N1K-45>C z?b30ho+XDfzXQFFGlT4kOSa_`eJgpP8Fa!Jfxi+bBjqU*H4@!WFSOg_$oiO&JbIu< zkul3vGlQo|2seiQCz&#_8o<_7UTzd~tQVS&S=u~@eo~}F24!r1qiGo)81K`J zfXWe-D6|d{Cdw1a|$;GR{^eDP8aSasb_I{o0=VCFun_4M< zPvb*Q>5Y&4e!!oOJqv@+)0}UCM8qS@H`(4pY6gSaMgarD4mTMEJhg4AZ8TNc_I23| zi@mDedEPnKzAJ(FBNAQC3S#a>E_qBTm-ZT4{1wYFceCW1J_8F9fB71WxeMHnu0UEm zDTlXNzo1EAFm#e5j~$N|?+678+tZ9|)m-bG(9$=gbjPG1v?jhD{)sTw70~3g+*&S{I1TVSZxY2M2 zQ}}5P%D0>cVu8X&s^F6%5`(JK-C;K@aa@1*H_i^B9fG(fRd*RI*k^s;Nd-Bg>@q^& z&=NRUM+;aOKjS$f*glHvJtB%^an-OpF=oLUup9rTb?X;P^y6szp}moQH8I8U!w(LJ z5iFJ=F)*?m)gx2z(j+O~6n-EdF-Z*p)iD`aA&CbeH_zb-2MqM#6VVGIGVl|^d+`(x zCT@_9l%Q?mF8k081~CG>j55g?%hYZBhfZI;Lh-ChxK1N;IQEOR9VjJ+!SS zqJCXNQ8q=JX-x2$og}`7F1G?Z{0Wyzut8%bNSB{Daf>!Mo;LIe!`uO!B!sTRk+DIE zrYf52Z8cMx*)AjE&jx~FNeE$oOmP?sJ+&v^7GfspXFM+FN^x*M=w{mIrw4yvfC!TX zqv*Pn87XR6cgHFDNjbSzJTLo9zvcWCbSkaXx`7JABaabs!W>FOYy?hRt>ciYUfXpT z-90A;rCN?vIOAL}t644A8+>}+6Aml{6@TD$Tn@e%36G{Ay9bIjJeVt5n0Jnt`-c!` z+A$4t;Pp4e4ZMUsUz_Kt6It-dvg{MyC8sOPuk3Ed^z5v69}L;iqaS!o#`q?_B3@PV zFAEE1$MAYNah^CbRrLxm0r%!O2#P*%`qpxlJH4pZ7UZwf`Be+|K>2F$^KpiPjw^(w zzFyOx3cac2U^DuMiLqmbHp7|kiHP6ui`;zRB<>b?SZga^heXwxs5sv{CzT8&<#Y$Z zBf9Zj6zQc6=|DQ-na(y)5n;2u6Z0Y-EF@>V;Tz9sy@#g|W-=~KGERdPrcOU8qf@D= z>9>~CqRs)g0zH^6c&6+VMe1pZD`Eb&X_<2y=(kZ1n_kG>YOZ*#)N~!vDuDT(0H?zW zP%+IkZOPH-tT7~f?>(t3w=kX6D5+g9-~=)rn?@??5}@bE6uk0g9tQK^bO)8fP`e2- zzSE~1x}t~9HkS!ve-k)#nd!fsJme9%k4>hisL82P%QPm)1ZAs5M?M%l8MwA=AeBdjKmIaowhPjn=Cbp;4uoVWnR*eWFC1G4T+ z%D?`PLjZRn3kYY6=#!9QiY{tG^kMD{DD;#=yN983WvbU2IpM4^U8hmwz)2WK0~h4^ z>rkNE{W$aNL7U?B(3?O`f$D;z6ep)#cZP39xN1+K4^kR*Lg9}x?W?6kdqHKTJMCF1a zQQ#9Ze1JqtVOGcfsmQeMeYXbPqIVi)PgOqFUYw0{+aZ4C`DNHN=vz-4EQoO91(U5k z(U?BxpPQAp|HYe)f~*@N{eoT}f4u)uY#ZxiMAY${_o9Zo4IEpf+&JA#AA#TG-}GAQ z_0B0U(N;=!S7TLO1&dys6&y%x0EmS}vR+JY@Z3P|nQ7s)*`=5UU4tp;!c=OO!!D3I z4h!28hZrDzK}Biid~SY9p)_&MbNkUE@`G{DEC&>6Sv$z3fke(DboNC}hbe5V8qL3a zG%ajImOL}J`gQd|(Kg~2uEXXFGF_YWBr7ycqY)8@#e$Q?#5b<#q-PYNWE+KCmCjCC zh`|k4D}`@%AD=n0>)2P-+cV8tOo?(3CvcIjm?ij`1d3Yuesktcwj12A;ud+!{+t<| z^w{DzbEq-49UpO`sH5UH$H8YVbZ(}s7cOQZ?`(V3=mCjPWAI6#HAB3OwVP{vvg2%m zOa83OJ2ys;CXT3r69-aG8~~449KZ7&jqM-j=q9_5RJva-Jno5j-qv#@eZ6pJ!TMlM zoM>p8D5#&@;H8x8>X_u=ru=gFIms8d2i5_GZY*FVF0rv2`7!0zovy9obA18|jz3M_ z+{yl+6=P=<-~vc~TA{LV@ZX&C>2Y(!G|@VFocn|8e78?u3rKLzyE&x+j+t?R49|Q_ zUWA-d`Z_B6KA0y^Pf^?|m`Q_k>LQUp5fI~Veij#jeMvs-mkfgvp$$%<>;>vPE1nUF z9B>34G3Ivj{2=Di&S?HO@g-83`gP_!f3CaAS)8*4%8yeO?-M+#i`pOZE~M|$VSxJW zRby1_aa4TJ#r5iIi##9>kepw!{GAd4Yl*q4jx0Ngc_a~g?oN62LN!a1CNGvlWn}<2 z$Y5JCX4Elebv|K#K7;-aqlDNrGP05mTrBV#Z>}HYC6SL zurke4h87QIy|i7ykE(bOJOl)%|GgAVvMpuMnnzZ`yjA*q2AS~3NBc9n$b_P9>s_hj zRJ|M-sSFdWm#1?c$EgR@%=CMTw2er01h>M)n%NH|q+2x$J1vLoDt$swmbo~CD(yg* z7an3r@qHESVEn;;joLw#IB_LYA}uR6IbS9%KKW0U>NU6!L}AZi) z!APcYp;stNkLT@nl9N@k=XP>{Rf-@KC^e+s^QT7`aindh#(d%Y{=IgtqO?l7%%Zmn z)h%X-U8~3fK3c(!>26j0RnwA=XuoNTU1RB&VPk7+XH9RP@{*kKsvT_MS;Wf%kXc*9 zSw{~ZU6f?sZOfxp=#6us7lw?OsaGp9mwM-GTy%?3b&+o?eGsinm~^83Liq%324_a^ zpN7V4)F;c4Pv|I_BEYbyIKRl}A<6gLa{x)+XjB}*!x4i&O|Fl9-pzQoQt$(WTTh#4 zf8Cqe+RN{q%Bqj!agMZMqHxa#_C$9LWVi8zw} zRmOszIj8pYDcT|S_HwVq!P)DMLR6jP=n!b7F3!I5!Dzi!8PzjI4*kCAab6B%>qai+ zf(HGoV!bin#W8}kL5OrvaE4YvWNVZxP9<+!V_91#Z~Gqo1X^+8P2|KhZ)=Tr3-;|X z?o$3*@}vUo6zsiv9d-}-Vn8bE<%8huupVPIfH(rkRB+e2g+r8lo-fWJ4(o2 z=UdZ$K}%2Dv_=#syV_h0p3M3XHp` ztVJS&^~ky3Z{$neJbu4xUKw0mboN=bFxYhKTt#dDw$0jn`E!#%&cli}+~V4iis6y0 z&(>7=mdD+u`p>Wjo$Dg)wYiKyA>(%P-R{S``RH4p2A|z8Rl8+bUeR|mb6NZQdZl0F z0rZs5-mvG6mEJ~){O+p!K@rX7VduUk<6*4){_Nepb=G0a&qGM|!K&0Y9n)T)JnL+G zq9VhwVg>FmPh3&oQ>m^~IrOQb!kO}$Q`;4|jp5l7h4ZIOXOGZl&(Y^b+2`sC7gk*t z7CGm(3V)t5{dw2*M>+e?dxc9Grpw?r7)oHtH3Y}NxFeX`dUVn%P^dE^Re;}G(#`7;!xL_!r4gDxhHe9%H z`Fwl0NYQwvtk-qD)cSH9=Q2EfkfqEiwo~~&c91Uy$!n(7>URSL?$0~S-sjH zMYs8SPoiQy5K};!64hda37g7rF78Q*ZcS#XCJfkIpRLc7PS@J~BN2T~viMQeqeny^jHkNwoOSFq0VRgCUbx z`8%j-9E$jXX}k(!xao(70>h>W8uEB%iP{BI^U-Hb`WEgu% zh%`p-tBp_=+jMurIKQGH^{_%w3a1j^-ejOUE|Lww%j!?D+}i=|Ad1$o=^me#e$HPqS8CuIys!2IRbU(H zwJ|i}>mW_m@9`w~j1X)fT*gY*e^i2u4N^au^kF5EQPF{!NG#hmqz=<-BMXT3T9Wkh za4{tgQHkrvk4oaRxkL&yFxCgk783S^$(sPl=i_qNljn0ru|&uPi=qw;J)SbH3VWKN zxFA(SUNa~gzLHt@Q{RiIah@AuC;t5{8hZsKQ-Nu3rW;oP9gQH zu@K*IEt0~tm<)f>Y1-CpH|aF`YB_zv;6~9u;{*)z8S4u>be^+iWLvi6B;tY47;3Ox zcN|SnU3*MMQ};A4W^(lzrV#K#XGurhAuxw=R!F?z1miqWW*jAY#zAbX{_y=VHkNv0 zGVy)B0(^A!f+9Idlwdm%kUxZrGVdW+Av{7HVf%q1{g7auAb)X_9@+kCxN?2pV*vhH zTy#sGnDWRE5JX~8%_9NRRVEQhD8=0>Hc%WFED*#Dl2cQni+~&b4(sU|s)kX^9x<4g zu7E}6(}}Qh0+|SzQRS2O(Ra*j6kU>G6fj|e)1cnB^B#Wkd|`6M%xy-oY#l>RsgdM=had`UMp=RHR++M-q5NN8WIoXFqpj^;H&uE0 zHG#1J^eYEUzzBrbOnzTI_&U#QBfciBwKIO9i zQu1u``_r~cmJrCR;MWsZFk$4=QXr@F>AS$EnFjbZ?_N`wtcJx2tgqQ6D67%fu|`Ds z5n#v=6~daj$q>f%-0dgIl0i~gn08Nm$gri`(J^6A4i@dk0=Coz60A_oTCnnj`w_{> z*IWM!ZFEb{0K2UxTLma)$PVwmBl!Im)0 zVQxLV1}8rc+h<>YXS-AUPPMmY7a$k*>Yd1&gYSRZRvGL)uF?$veI#wwBo>urJW&}X zH2~>U57;H}yAe-mw>S!c5PzK?bVAe?X1?_%@z%d~P42k@BQXsU`E#69TK!}su$#k9Cu@2!p809EW8545~?K8>5n zqfc+o#x{d4X(s(wm{F5LQg)2%DIG?lz=6Jj+C9^+fFzD|5+R_lt2qsF$yQAqhf?V>~PJvn1S?G#cd!!7X;K&WJ<~B{q9V%;jPUkZMr4}8#MlgVRo|Qt0 z3yW`Ym3vd^&Gk%E^tsaE%^t*;8Pb;7G7uMIIsNmZdG5=N7aHyLeGm>Y!Py1~93T!i zZe9x@D3v3}F9+DyZt#f-$(^uUd;!D16}IgcF)%sc{}SZL?e>_hd5FXOFxrXuVuc_i zk)Bf$UTKI;1;WjIPKn?OSVjgwrl9M7uwMYa>L-FNKiE2gz&Q`T-*9i%0k&-D-|8R8 zI)swD3{-T73kwD*y9Yr@u*xTi_Y4V|!Tc9m#4}j*Pl^L|wgQn{LH8|#)S!T|AmRE6 z0hv1-^I6{KA0h(?AVIzf=2alMfIsgeYT7m42v2rj*>Xh9NmhVfJRRhvm~u(KuNISEYS98<2L#7l90dBr_yQpG6;yPOBl-g;zDnZ5>ES&U4)hcxJQE~B=74A5 zur|0?STzxSGjuI14zDDx($bs)8+w6|m+^xYz;V2gyo~|i8zdeQfD#nJsgU>!TCUH6 zV^zg)l>nj{fY87J{4)n1G6mW2gUI+n5RGvX;R#YD;TTM$77UbY>E!tlK}qoKSqWk( zJ`fy7L!W#Ib%1*v!Hf{kEH=O{fqd#{_;5M5+TwdNUMSfDr%pDp~laTOjY(3SKTyBi%%gSU3dt3<5b0C6(@KwSSDGT5U zf{Bm0liz;RB}+_&7!k{1iMFSb4e=T2R)sHB9UN!WNdeM)^`MY+>VeJ-yqs6hN7!Q z0U%bvJqyaL0;-=RMmxkdEM#haOcxvu!f4v=)mcP4IWTF)L?ki%VJ^knT(Mf{%N5xJ zxGmLAE)#wpjWPa)A#4eWcTJkdU7D9k0{=g>hzplj)Dy}G*ge{_*1^a3UapM#$N@W1FH z=;`U%{{Tk5V1SW;e+NeT`_Wxp{}>~E&(Upm=nfThn>@Nn6kX5%AI8Y!6E|Wr6P@&7o(PfxrHPL@JMlOojI?CfP#z=X2`Tu5&BqX52 zY${Vy{;#@7OiaxGNQ*dHqRq|Gub-fGbkOQ5Xk}%zoMe-;{eP!L?CtIUCs*Y4>(~ER zSLA<3MPy`T&=L}8A$~L$2O2?-rlUhskfY&nG$8>R3Pt1Kph2K1CdU8liinAciHL{@ z2?_ldT7-v(hnt(5larH!gM*!&9ixjdGczL)2qq>bMn*;k1_pY1dOA9~|DubKl9G~; zkig;a|En(YKhYvO|D6`WGMxPU|4)lpztbWOrL)5jsDMJjiGVkqvz z_vDTS$IuUlNG%76%b0@jC%~OYJlkxqfDmHJW&gTW5s-K>-MM-^YH2H@X z`JJdcerD<|M_Lbn^-d8t)_5TPJEYubM&qj=_a zEB{>)*1&p>FvZADS@i&#$NG6?satU#|BLR8%61@-j2l3}4X zhSE_U>)foZFA-W5-^|PQ8~u%C43Y@oQ@#GUan&D#23oH&>M5jm8QMr&WzySMdt~Ob z7D?A_JO5tn-plpzgt7qSa3fI5#xqM02|2>@ULZ_{y2kem|Cx{n8E^gD&YQbk3@y?% zSL3QjxhUxWJIgC)m{>{1c7VOtJ8z8pYkS@ouZ_t?t{@3hsV$bb=kh`fn zPwW19{PgC>`8V%BXxn$)XYbXQ?|p*efC#hFGU>l#MI*&g)~xHU(9rgx9UPP(pOGN?Baek2r=rcL)1H6+A{|AZZewYQg1S|)_zoN7eMaGW_N3b zczRcai4DyIa4b#QrAd)dOdHACIQNbQazyI%z6i!4DIlBR$txfN_Ph*rU^4BPHoX_i zWNd9AZlk)skN@-~qJ2A_kJ=yi5##{2INjYj0sy{R4i?o=H?FjxKS*r|nvsi7-JL@? z#)>2Fo(mSLHleB&#G*Zzg7}xSP#YhC*!Dm;foDC8VQ>`Jic#m#X9QDha}NdeDhM{j zLPZ&bR77t;3YLBkhvlMv6(_zZU053RrN>?biqw>UJ$NEttmDVfIP_V-^ElFQF%OG8 zPZ|h|wh6jaB>=@mc(@}Gt!iMvCI@DU7etjS7$%}61h<@tvwd|LY6HcR34{whRd!+N zC+8MY(JuGB3-4FJ9}LiO$!A=b1Uunq<687%GvvF6BdY;IuS9H8oK z0l6k<`3`D1U|Me^ z8rOadh0tqOW%ogZ*v6p{%t#1d%nHPl3xzP8gs_DH_}&O+=IV?>6^ZYeQ9PSTSPy8i znAE<0KpiDxNtv9kC_X;TjJ16~84CA7PBV1_fY>__Q0no;hJ}YPsX0X2{YZN_-q{yV zkq4FN2`_vbK$F2WDYFTFaO2)hXU1j1b9nqg>#+&KvUm^zREN1jNr1eS5TvPNr2NS7 z%ZBx0{mqw5v1yP39M&RlSI3A%^SDAR$Jb8+k6=RGrm@%_A)1g{z*!axD7D;`)Ev+S zsW%uLN9mc*I{TTN^})55Y`)yLj+^Kiq$tGH1wcN8y@M8zcT+=gyZ+!iqOtr4(Ez6u zBi+0;xha+`^O(=p!^K~{gO%b^2Hv{N(RB4dlO+xxfI}ejBFF?LdlbMnxzg(iXMrZ= z7)gRwf*&~a;CeTQ@^T6hGuL;Ug+@_Yy>iiuoOR=PvIP;*fWLGe|D$}G7|T>WRXvN9 z16~_q1;(ml75I?2-Is$*KsCWr!hR?kfdw218TkvcFn~R>UxZjMlBUl~4ON6Yt&#;< zOs+AFM%q1sV97vUu+U#hs`6K2u#|FE#tLd>@$ejick}sl(eN+=SCUxYeps?<$Gw>X zJ~1AhFC%z(ew^2PN+Uhh>x`{q92 z^2k1rZjS8cYC`;hkoq%krfZ(N3fn5F~YzAwSy$iqZj1)@6iTLBWV40&!0Mo5(I>%@hHl0 z{?(l47q?!ve*5q2^qC6JIel`fqkJSmt4VjGDQo%CHPPVv9qy`fIjbZ7abFoXkiU_a zlhIzL`8%}+E%UZS?PcZ-4y@gSj5xwLqeEnyg#)pj$J5SWBRxB}qE|ohdi`b2)~LZq z>AH_GR+EL^dtuqUM_OgydllUfYwqWYP}}U5<)VYg$I>kOeL(>xc_m(hub%q4UG}H@ zBz>ZD@F#$TdBN|~<_kg{+)y}T(kmBCg1unE?tjrD-LTH1P^Q1&I73kXKeWibzXa5) z*iBvCv;qz{|Ii|s61|kx)fI%J|0ZppiOdh%q_mT1CyRrR9?*DlwsAlgkiX^RF52)wy<9L;Sx#)u)PT2a1Y>03E*iC;F}K+xC{`a4iuIQ6nzoM1qJ(95PBL0 z%FbhMh@dyg{I`F6?_VkuCd1PPtgctAuKg5av4MC_FWDzvNUirRO8S2p>>HT#7_I z(TyldiSkZ}I1Itx7lbu9=-5+524X+PQ4Bvf3XdgsIqHu*%*A$H(F+!gT2y-)-sn=O z6E@NugAfUtrq-7F!#GSvDb%Pv$tpKvA~(+p|K2C}6XT!2|K*<`sJ~0H^cO4O4J-Uk zF?+h=Hro9rXFl%YU5uh7|G`iUEjK$&I6NN8NT#bum8eKJqsT;#V%0?f4k+$=l(i^a z^#~@9fD2t=H$Mgxk@YXA(or@hT4zFC3B7)rpT65;d+8wOSHM z65(bA+E(={wr45;T-8}u7297G*N7+)0nY`95**{w*b`GFm~ip*UktFphYB8#tv{Y*Q~$!I8dpse zMoRp^H6gJf&M`GXhK7mT5aLrrNCQvIN!6!HjZqFyt_+Xgac3xAOAgjcZ?sAYv-QJEg`hLM6Ef(v`j)g<|_}F_%Dpl)pGY9nEWy|k^E#LYYt~K zgxQhjWiDhptfi9a9sekmDV|M=U0yBIj zPHFImZ#d81e)0;>M5W~DOBd1pDm3I_GL~jC^%Qwt>h}Jvgzklps}}TDix6k>6Tft# zCu@-l`g<{jagjuXaFe^`gPl)j=S6u<*^dk%IvC}|0WUACB)8Qe@_Sm0XQ^~=af4&g zaeUE9O;PgO5)D=}QaHpl2V40$PJUXkuwt?x#?GWIuQx4S=_x&0EjuN#`x) z;VU^bzl^^<-ALW)CnpY(2WD*&c@m8CyHJ6R=D{ z_m5PZNtZtuPKL0SsFEQFbV}Mi!_jH1ooWtV)}L=>-N8U}9&g`Ct?3DG4_2KhFUM!J z6W?%eIUi50H6EjkA>^4B&^=#yK%3^)Pz`-q%h^`Xl~fzx$Q548tu51#Xw0qa)$rm6 zx0H2d#6W|nBVgxHraTE7)xz>Ctt-BIqIOgEaJ1e|h7N8Gf2CdL@`K$xfa6_y6M2rn ztFju4k-CQCIy(m-c@j45(WoC;QI%I=KU(2P(EMe)$$O_k_zCdL5F&#Fz>s8S>-y4` z#)X~wXqnb3w$@~EK{osrXn13GNoxQo#y$>E$LJzCHetLi%XqDk)~y9U+OB)sn1Wkx zRazSRTGb=k#En{9b8vt-Jl%-G@SD8cAB~-_Itm|k7}VAFMYjJQ>Dc_vu!4p{i2Q&o zu^b=Tj@D70DC-WF>*lPsj>^dF{&e`rXuIZ-8x-jHc~khct!;j^6Nu94_IlpC>wNmi z1~Mk2NYzOM09n@_*K}P8b6q+YLT%Q;0Ld9 zd+*Y9S6OKXJzr14kDeG;20}u>W)jx#kk!Q7*HTu~s8X-{=ng zqp^12sOE2Yr$y8Ns(ipzbzpR3U}<+y(6JAMB)mn|bC&mHdkwmy$9g^6KZj*}j%^>P zBN@aJY8)|a)Up}WZ6A8NIP`jKpe()r5srfdArS1y-p+flHSbh7*6#dxrV&{5>^+HttHoXHLVH*)4KvVtc+rlW1{y3HXmpZ=D zleY2v$8->QFLr#NjO@fjM(5h%$i-gs=3-gj-ca1%$q$56ubG?i1mPNlr8o@ZlZ%A} znUe$&6E}}X8OJ6D_^9#VjWU98@F=12*eJMSh*7;2aoco_emoujcr1ar86pS|CP>8O zatEoW_hhC;_`Zrg{)&{KA)2g_&goB&)I)ZNF!0Y*J(#J9m_b?0sPIuw($-_I;@tWX zHl|OB-G0Jn#;)!rKKCQicbL?D-SO;p;Kfq3vu#Ykld`6VaGjThTDM;@4$ZG_e1mRm zbHN1q=t=vfV#nJ-v-h(vqsRPfN}eJB>?c@kHoXe_a}Z|yn$L~lOKp+29q*RrVxzzK z`p@wq;X%@q1xxdQ3XZH02wX!{C`hoQMa1kjpUpq5a~o6nWnN-`lH@g6`a`fRA7Sw0 zIa+?oBrW)bAuKls9H9mKhWVW=HRrw_Ev)#GpSkcF&0Jg}2REUMAG!S@j{if3`3H_a ztcnX>bVO+Pe#t(4iM3;C$7Xr&FO}6uUs1;F#+NP!Y2q?Lc%%dIG5<34;t$-H-ICGE zw~I@rugU1)g*-_3dfVu4hDB$Zpqj}AKns6=i61{^Wms)lb$^BZcKO_vY?2!cj_(_c z>!J~uA|xt$9S2LmY>)+Eehw>acC{Rxvs_s-@Pn`7LTRpXSYXGg`;}A25xDb)upeViZ=y8Fcnl#f z-5~JPH22Tn_yp570_Aq&ORwbD`j%EiNB~{5A>^?ZyhYZ^D`w;3)5g=gO{R)?;%-Bz=gXtJ{#d&mtC*dV%K40xLEI6GY#1;M%Cm#FS zY=b!V=sn{xY1QsCJ0#`3Lk`Wud-jKT=$d6*f4p1xQ@Yq=VB^r2?0K4?0}h0A=&3((1x)cysYC$v+DFo_TJMs zv*h;q#{zq_3KuUiF_ozVXTMD_37|x%`N@x?F`>z97W)%A>@$*+%S_cCF9f{-FLC-bXlPJ zcU==}6|~olk8;4N^CSM+gFU&A{R$wQLBM4NVTDMX=p2~2Lq~GgUXm}DN7a(;o0D`H zu*wU9td@B5A81wmc^3Q>7mW*SpOfkz!Nd^o=SMK{7RZ%@fMqxAs}TNzAiOq*U?}_V ztF)_$gT0E(+wnJWe7~;{e=MM;{0#{JCStswqLqunOcwe6MT>+HF=^{ct}PQrG00&# zJjL(6r-MgU!F%bS$quD_Y-1CA;lfHOriDyQjgYkyMD zlnPrcKc}*o<|E;S~JzFL7 z<@wuh>NOt(mKwy+O0{)l2My6)jR)Ua#fEC~l~w~yZs!*(Y;O>U;qTSw)Itjp!-33s zzgsPt)5-+in46sv_R(?k8~Ys70tn1778*$WrBwgU`}%x;8GS?BU~@h8{N_1P_YBT` zbqS8W92OvWeru2#C$6oyYdy-TQdI74inGu6a>@b($UB52_u!-07_jjJ3>g&wz>GFf z^cu@AlkkL_<@TsgNR`2DeX5gAea&7TOOx(vJ3%LeNX}e~#ASbc=`NCHI0U{+FKUR*Cbo&KRyPx7rdI6gJ)&y} zw(izzN96R-;JU|1SWGX%!Aa)O4XoW-1_40ksvd+DkER`$<=VNk5_Hd{pPMa#`8({r z9*)k=yhBB|eOayeM!B+9?Gw_(cvyx;rz-3T(i_zOqh7_r)N^{I5%l7-GN^>QC$64i z6V!oQ7ULyQ3byBulloZ^JU;nEO71BnxBLIKmt9z|5->{SdGK&5v|0cgn!PeoBi(DC zarC>iE$9AO!MbNsFm-zun(20{Xr>_A`t_CnT`iYAf0D408`DfkMauNPn%fkT$})+g z=26^6=_{z*(IP)-16pWGmitTb(4xd$QNiE=O4V5V7Z~sB2;lDHm+dMa@*Z(T`Lr$i z_8u))+>!-8e#xb}+CwPjbcilN8cC#*?fJ0~Dc7pjSLLLA4H;$j<7gOpUGQ~h$YrWL z{5|homz%1s{Vsu5wo}mlYYp}Cy>WIu^_cn8Z%sZrf)D;hE>$*rWe(DN&XkeBn>c)j zjohx!=hFrIBfi&VRvh*+yY_$I;l8i2k!9VC&ShZAjC}v{IrHPBsua8HtBr9%&3o;o zF;6UxJJVhM4H4mns01L1RnNQ?wv+$eJox?L{MQE(cfdczSABfbp+~=1fb^F%6{8-0 zi)KNDxf`T(cwv$bXR=$Ov-#tkR{$ zwjkwzSGB*UQ-c3Ko$gG^EbK)iI`VYD0t=?@#J~G9R z6o5N3CEX+2K*~pKq<#4B7@Eo~sa+*4&&-I2%=flsMwLxdKZesTB1zPqMx>$40gQ)v zB;u~PaX-VT;`Bp-psTcWQrH&AEeXzktlStTB3-eC*j4hwrpW@J;L3q!9oueV4F}+S}mkXWmOkQ)XL#&rBp=Hkip^?SCtJ^%N*6}tm-OICvVTSsy&5z*gEQK^6#=xqXXIS@Qg?+A36$wn1{|io7$<<5F?$;4L!$<` z6Yc{NZF9EEfN+fLo=yO;xOyj27xXCr{$OR{ z9>v8M-McF^etEX8^2t$2VFizOHl)wD?G--jz)8_5=83LwmdBG|w=b;nb8oodb3+;T zS0h&5neMOPj)Ege0#^%Hf00!`g{;)!=SKp663d^K!j``fLIP&iGX?wMbQdmtQf zr0BMgvbschRNIKZeXTIJKa~ON_l&a*P#o5RoYLeAZAsF#)?V5j{180x@V&ZDd z$c03b`d$!s?dRvf0E6;mN_FOLx@YuhM02UD7(rgkGfE(VaDvnEBT2Ot*m1&2@6HLDL4C`_41b+d z>eIZE2}T!r91p(vyA?_jb5#65d&)>>z4lH___x+L0u={`hYnncM zw;11Xe7l=pN=8Euq3z+|C1jgQntw}u|626+(kS8nN9iW~qGYN8LoU|vAl*!g=fC`J z6Ql0GFW(VW@DshNIg%atSKi%v`7_F1c6E2y7#PV4IjE$a8`<4#)N3j6Exkl!~RV}()<>7TGw z4>mLp{`op6B*sF5sif!YgL1t6^@ePv9tF(9K82={*~0~c;SKTd<>zo=>tTGP;c(#_ z_@-!oN+Iky?x{-GQ>;GJgH2mjY`9)YJIiSpmYqolLf(`QC}H~dvdCJq6tOP=p5aPt zn**#B2my*pY7h&Y0kOi1(B9HOY-yUyk@b7MBOZLFem<;Gl&KkA!?ikMhrpWN44w_c zq1GdH13Ul>mWKvRQHZ$e9lD2x+w+Y*%o|lK8opH>VK62m05`Cru_XR)ziN%zSdYGN zAFUA?3+c;LFqZQ+Mu@-Cfn;YAuOKbehzqQgz=s1roxoqnC`0vOc3ZkyYPzx22zQKj z{S1J&2rDqb;?~w0gvksX8S69PF`7uTN=acV8&AaOFDO%*WyA13Hwa%fvXx4pBnC`@ zM3{6@qVC4;!`{G#@P&ql;Fb@hm*{?$@5o!zoWy8}Vt^m)g z^{VHzYO)P#Dd3U8Wc?X!SXl4<0nodHN$XceK{p1`Eg&p}ARY#4l{2bFe5j=u7nA!~ z4G?y*2H$<~SbEYhatE6{dBu?V+8G-_Lo`6~v6$myd-bSOn@&x*E_pV%N1u43u(MZ9 ze_m|z8A5~FpG0rw<0s6-6vy~9gWil9nQJCG3IoOqf+w($$$SQbx`{C~Bo#_X=xR^G zTxPPerTcZxWL3?$!6od+qN!EP z^nSJJb1)!>K`r$KGL4dHZ{2t?nP$vnCa@f2wDxd_L!PF{uVuZ_I$^$qkq&%|&0E zGZT&Qew%ro-7&E>38fsZHV3E$jbJ9G@dMw@GQpN_n#~pGKih6u+8bLE5zX?CT4jcR z=r_UwkmjWGS&Al^3Y^vi$+OBwmMo+19NNCHy?xJ~gT+7Z!$?^$_*iL~kQ=LKZh9*q z+Vvza1j0G2^xJ1asn|GPlhk-1w-32Vh>aMdB}#+Qcr->8 z%c0+EjQf0yu~B0D0vG#i46<>$P;?fb-wU>OO~pDpw__#%`V49E7hw3OIWO@!rFmUH z8*Tq&Ypa|E)l}>(Mi(Ol2$dy{xi{}!JQ;43qkolN;GSZ&o0bSkw_+hc@1k7eN#d4L z#iXzVNKjZ;dK3^4JI9uA}zYgEB4PQ z#ggjprs;u6BJ7EnW-^9ead$gN-d_rM!l@1ZYieHg* zx=?S2JVYbMXOU~PeBTm}zDCE)z5Avw7t-aKXXicY*gNM~7oMWmm3FTyRUJ!;?aHI5 zq@X&bp`oQk3+2-jAQ>EJjV4IY&BzC^R@S|YXW`T*iE9MD13-yoLJb!^n{OBhAXJNZ zPHq)E_JK4l^M5pqIf=Oved;=$BmuoNlwMYgUS1fhkU%ecm3{$2igo>`I$4NXDtzAV zaWd?IKb`l;w)u>nSUXY&_t>Wy^?n|H?HU)H$&AE=l#$p&(6EWLiZZYTl+j9y5n#?} z8^LIQS3*@r>^_4MM-s!*Lb~Dv%dY5R{B1vp^QJCgC{Drz#-nRt4Bc;B*fO!}Ac@1N4(=E1O5;Ons#5R`6 zuG)V?^K>Un_eJ>BN`$M$)#ebVI932GU=r^Vu;7Q%t@5$KCWo62FQs$T`z6`FzfBADOtHZ12gvdRVtym(c zP9-SPH0Weo`BCnBRQSPty|mIx>!M8PE{{3q8ru)G7Aq~N3sEow za%5Qd@U6|^%)uT;D0Ngkb3pw;P8m!%$7AA&KhPuo< zd8p0(=%0V}BGqw;#99B?u{kvy=XAg{|C#aVbjsw@&LNKwl_%gQ2h-10fuFT31bufD zi~j!Wc>iDh)r;;#w(BGg{^7RfL^j_7P0fJ?t$= zfsPctW^ZzQQ2bNh9tp7df(5`G?Y@usT^>Q%bUNyrnb3tocLDKN8pt`>t*u@EJb`$HpAc)82 zi^I|lAD$(Ai;a6qL+pdzfDs#AoOvkz_SD<;G6?q%t72ci6Ie)KB^c+KSXI5Cq~AdR z?276PCYzNQD)HNx`RW*Yfw4!b<3NTpgwz(%v2h)E?i2!XDG$jmX6I)IbyFAjm;l0E z=!yd-P3o&Wk{BQHEA&-LXc|7Meyo|keeDOQGDXL!5Q$b(V8h9!%5S!0^QA_g+JpoMc zkFUYEEwX$7>m}J@ud|*dc6918>_+0x7=>Cs?xEK5?W+rFP(oDp@H z#qU4!6G*eJYtI*x*BbYR$N!?^Q-e?Luoa}_z#UqXG{F4kk)nUYySQx#K;f$5zEYZM z*TM)@jIrQVErh^nJw2%_J-Im*X_7d_{SE)h{Li-^$$|ENT^`(9(0nVHNB3nMt?F+# zPksNj;87g_CnCWHr*HO$+rOz0c`&s+ufcp-=0e18;HO@Wro!_FTK0%#s7~MA>(`%0r?*- zLL=-rw|nY^$b~RYT`7814_S)XwTh*l@&6AA8F&@&OJJ%(CGPBS@0Z{V4$l6*niRm5 zmkL`a6;JTmHOe=)FnmJR+AyC+P!YesXtquYAZ=Jmp@SUgz4DiCa1m{JJysy-cHI#4 zJ5;ihH*5ds;J4)Z0Ez@pze5iAhD$|%mjCy==mg${<|nVEkRK>)bdyds=^8QRpv+@+ zBzC?&4!}n0`N@C$KeWh~u>d8@w^k{@Cy$xyPrVlE|57bFRS5cexDHBKdyJbt&24(v zRFk`)Vo<33pseL?5E%k!94?d$yH&fcZ~O}iT9mMVR%zTJXiH;_)@E!pJ1hCP(Mke8p@_4 z*ihfl5Lm#xCo@6our8BJLRtf-Vs%oZH?GXh!0uLMnhLx!y)!1}iwockNQPMJ2te%! z@q)1F+}e4)Nf)v}fSUNDOjiBNOjU_)wvL8;ay*t`0DN_rKSP7RN1I=n0aQJFTWkD*xjMQON2{sIv1HaM4GUk&rYd zPGa1`Nd3aBkrb7qe(6lFuS>i-Bnm*TzR8n&E+?l24xm4!rlIQkcSnnSP*?mG^Yz~) zQIK=E;(y71UErsp8enXN@$~FXo-x`naA!HW{VU^|@0yBex>d|J>0c8rOR-&D42nhtG5P4IZVd z;14dohQ0In4sOkZe0PpERF22d6jq8sMefF2@aB$=)W(#^zZHbMy8y6Za|*-OYDS+W zg@X0ZFyXRct&P}0ve-}z-^U74Gi(>b+3RQ@)Ff~1;KKkVAn{h^fBzz1Xy>wyacP=o zs`JPottzzdlLjpI-sO%GTEvvn6CL_%ZRD^s18)Cdx=^l@{Fb6^vHV9HF#~0cX*xRD zq!u$KD0kAZEidN3&-0$d3XLlpev(=)8-WX@eIHsXWvwg-_LXUNy!CI(*Wck_po;-w79;hrfbF=jO8P7e=cFV5* z43(bnvgJao6KDcwid(Iv(hS^zngD|J^VZsTbNaMgIv*eV*Heisf%OwS%^p(N@IFIi z(EeZ^FOg}l&y&tZUqa{WbBF1OuQK4L#Z!X5)xc8wF-CF%vm*2NmQd0LeC^D8;r2ws zYBsBSt4$HRXDqrj+W;cA830+N5Q^^SfERpva=yIb7mq28ucksvRjJemhZ&%VwilDb zI|g}PJr_pj9}UZ&#zsuvVjse<^GadigfCGp)h6WR`4rw&Pl5*~slX+u&gOQ<_O}Zm z^g9dLJ|%DZ{~hU2SUs!;rf>n)Qz8goPNar1w$ntwrTYpp3>GkiktfSKA|FatC9-=d zzaH(Ckgc8;{N_zNO%r0`$qWS`$$v;4MYca)8C0kSmNh#_SL77}%?Iyz4p{74r?E-0 zoB@PvxOQzo;lmp1zU^cw45w$A-0CLVOZ!y$!xUnGm?vC)vZ0>_@61UMbmnRR3l(PF4<8`I0ZU%LVzOTVChIsTuPxjh^;>qme&e#<~ zbz2W=uso2t!uEBYMOMnfr8Z07+T=jj)(_jbq80A;SbdUj)A)4626ruTg7a6`IN~>( zQ2JH6#`P>F^6!e!{L-_>ZOB|NLDeYWScV>zQV5L!mDNfPEO~qx5=Itq!K0D`|SfC#3XAo2?7`+zN zpWt)pKB|i6>xf*36_QB&XUcx>D@8=A(Y?^>HHCjre*J63xz$T+R$aQ46QJ4<030JX zw6E|^#XHkITR-zckb5L_DM;fIHNMS_&|e3!ZIA?;;{kxc2Vmnb0#+H*oP6C^dI~Dj z5zi@*bZ6@%n)@x{?r;MCNyRv?K`ov% zSiel1Uut$aCx0}i*}8X6C5Hs4dxC;FG$oDVw+YHl-b9kP zxL$Ds{40%w$6G^#b&uh$Vv7G=@wrqOD3Urb+%G z5TPa0`;byvPXw_&t-#6GK^)^Wz?rtOau&0Z^%lW?ACX7tkWc$fz!Ssd?c8iU+kJM8zVdvax$ng*Z?7=kQ$etTIylIooyW`o*yH z$2I0h99ba)G(8(w9bV$95wS!>jSJqfHiWG^U{f1Aq*;bm_nnaJ@se7>Dc+9I8#74z zJIh$I$_QJj5O0az;ol~kCV=v0+VYn9O$`~)`Sz#|7lY#cCCyu?_Swk$i@TQhqV_)! z_2m+6fi)>IUj05V-M;cU0%TvrQ-%IvP1ulbr1xyXgq{S?CZ!G}F;&1n-(Uy9>dWxA z-YZ+$C)RvZFMicHt-|DT0|1z2I`mFF-_*aiq1eG^4gtJz89K@*)}#E$0jV-n*)Dj^ z_bJAQl91@CtJ@7*39#F5QS4^fg5Y) z41?0hO07hH6C59nFMC>#W2J4qCcMTR^xsMQE*t}s+k)%a!{oZ)%=ZSxywPzq4)8u< zz{p<3LOuLuN^GxQK9k_Y{`)h>Ek}y|lE6JZhQUjUVb6@J`*KE%70~Llz`)4*8sgNO zS+{@R+-{SRvL|pKAb_WO_)Kd+?TP@P4RsTf5{Hf!P$PN1CT_;o( zKD9B_p;{L~AN){ieL21g5nSWb{^_7y_@(PTcW^Fb5;GusGejhY;H@B>xYJevKmd&v z*b=A)As}ZFLJ44G#e{Z<8h$MgYg(gvH>zAmf?9b*b>#*T38>7s{Q6}8@S~k~Rj(4y zM3SgdS5g6T&S+`?9mUpvG)sgcG=sE#L#j$So(w`PTf@8*Dg1Zciths@asemcnTh_F zW^Al5jQ|s+K|~DvL(eO{Iah~Vp+z|F05EMOXHbk_+N(%Qs_%{>8tRj}qm}{O(RY9g zp||c`ycQMXDo$<~LW$a1t{S12G8ME&%H@J|9q3;EIcVXMV2>5PNC^I+g?}awmRJb< zVOAynNdvKQNhl~4x_N)3ctLDCvhI`P&k8xA*96mP5uu!PjZA^BzZ3f`%1jBcZ0`jk z99%N@_kS+Xg*AyC9C(I)b=lUu>(C^|9RX7($sTV3k?#u{k8dS(X#g!6wp(e9)wLn< zI!zR}RKjXuM>2aq?$?~6?wXe0f}-}z=^ZiHN5G1L&Cg= zOP_D>av#{wyZYaDu>Rp$=K_TSG>gv`M$W042$C>OmxLcAd~|Wu4ig9e zrh-9|BcG<+iKy4*ZwT|ePl8S)b)!#yH=by3!K%o#msB=&_-g8p@C{V-5q}%f4t^dJ zn^h12rh8_Z`6Z;K=%jX;q_rzx(UgS!0vkGqFCF10v~P|{cw27AGAMs9@hts!rqx3H z?j-;9vG3<#QXE(sbO6*I`93K|<|NJX@Kn3)gsZ1z_ijt38OVN@lsEuUrAxlIh1s#7 zS)Mw33lFF*KP^m);BbOuzmcnFIP&vev6|Ih|r z_|^*uwy+k;yfzrt%tH%39Ag!Vv-ji@GRi|I7g;7*VBlJtg(4sf+icMks6GW5;uVu4>Es&VG z&Fw};5-P`=grJi$6(|yykwon4%IVa#8TksRkVH$$08U<^bg7B;cw2=1WHbo@lzbwB zI8V4J!a-fcu&GU%S<;A5PSA;$4`6or>D+DZoO?JzlQ~Aa2q{H5Oda$FPJ`SsPx-yk zrfGJ8cqVHZ#Ut^T1q7HDRcbeSB5(9xoBhjZZMA_G7Bpv24E$pl$6OfWk8}QXdF|j< z2e+th3*ZT#m=htfwVi~sY!nL#EQnuQR5c22y-diAm$LD?w2yLkpr7;%S|9>Yi}1y| z--~rOYWMnkswRt8M7I#%KrF&ye*zWAJEJYbJVgLz?FF%JWw9ZOmu`Lv05t-8`8F{@ zkezB)%Tz}=b-P8Wiyw7Hm@4D1OU^LOcBfL#aBjuLoq@~jw!;1P!I2JU+0NiM#?fKC z9!4v?H`>b1ot}Pin<1UF?9DccPM1|DWRNdDn!gi%%ZEJk@7=4U1U&pTq*ySaI8_-N z9;N`CyKu2O4yyA`2#QT5REl;wXOw`c-Dr>T#D|GqDS!FRMc)K5yi8$4ZZQN!p<}Yf zulsSts~o|r#3(6rRGj(F z0Kx?*^z*mYm3$FNe6rsa@&iukW?22zX+hIy^t0K*ux^AOQYryu#%{u8ooW6qKJY^V zS~5PdoIE$kHVKbr&Q8E8b_+gD$Pjb_TxGf7M?vc;kx6o{UlK~9{#^CAr{ISj|0)-9 z%aw%vQIi~&?j7|zlvgWld;Yxp33vA|qG8RC+PRJ@kA5WR`Ca2wwIT@9ihp;OP+z~; zOw@_{a~`3U^QOnCNEzV$OYzGhDaBKPyf&L68+PM{=Cq#Wp&s|7j+ct_XZz1KrJ z!1ElgN~-y$UXc^jMridR=}uU*K2Y+BvY|)XsP~Q*2io-yUH25mWp^fhp+rhNq!qec6)X0J5EKaF=LPL!TaPDIF9rExf8W;g$IL<%-&mziyy`%^v&Nteq*smbR~#?$h7s z{te45HO#$C|0rnRDVp4@c2AR~(@p4?*8P99RY?Qys+X*irluKxJsobSduszudOQ9r z`Y=T*WN1=*^m|5>2$%W?r@pVu%3uG(D{D6XQ?RI%#l2nECi>p_R@-dMk8POADHUWb zgPc$P@b&KlYUM;~wb!G7u8yD|)EYbZj&H*w^zk}Dy+j|o^~E$b)|z~N1|5HXX!PYr z9ywA>bx~u=D!Gw*l$1|I05EoQ_R;~~KTD10e0Q@pe(yh78;VuJ6PlD?nwp)m_jU<& zD-YOa{B#K2lm-6$y<~o%O4c_f=}3t@(DeTM=Q$A!bHxmVX`xAI|3`~Jk*xSoxgw?f z4a8mQ)OxNf!n5-Jdn%tTCCe&e#n>{CdAtRmK`F08e^Iyej&V6%(AwN1sUH*Rva!UB zDi)BzO1*r6ZwX%iy?dZh^#9T#vRSS=S5j5BIqGj^KIXr2gJye>GnIMP8KP3%XJs(# zaoY|(N=IwO<%>TwafzG0L~8LTfMnAY8r#0I2(L`kaAXXH`%f3p&~?n?0lNb_)d;1- zkmatk_0LGN1CwtjKfD|AT*kRXPM)c=wnqF|c+JpZJDF>jbb-y*4X;)?TymJ5QCivY zc$SpY7}GPj(CbG%(w|(-RQF%k9W8R-MVuL2Z0%jJCsQYd%q_39)&Ksf<{}Zhfd%z7#c$lNPodqEfcRflVscC`6{7?9A;=O0Ztj znf2W78W+~Nq_8$GJ@?kncAEO5M~x;1Y*!@48)VC41zr~NlKpKt`6!U;2vz13X`K_W z@Z+%&uyX5(GDnlSw2N?6T>DYj1-zE8v}IJ`Wl(332N%RG3=A=a3zfCKJU_|G8b_NG zA<;_a*O_0s9`n~bmes~ce8m8r8SR|%$%g9_Jpqf(j_+Jv*xi9DBn2ql=5cB-(QkL* zGIA~OJaI!a-YXMWZDMPjRL^_W5TtB5KOa5)b`oV-p)!g}6Q(Nqj#)VR&Mi&>94o>I zfVI4NZV84`3N1_>wu>D?m$yqT`rUKL-5ZyE%b~k`vS90yM?2*yp{zim!*D_jE}6=4 zug1yr@m}4dShoH8u#(67FI_qu_t?!5aqly0dcJek4FSFeOGxVayGY#%cj6qp4JHcg zpTNCydQYdEj^F)QS9FN+K^@MR{?Gg2PiXSHK>;(C7`8HObGo614i-a)M{cIuld(3S74VSI>^U5o2h>yYpBX^g1 z1?|(>3sJ4X3~DfxYm)feOMDZ)p21iBIWkN@8<%d?Y#|1eFjw0Uo#f`;|DfbYYOuTN$u0@ z6lVKsIHF@UIQiOLM&fgLs)ukmbWhd8S?X@h*BvfrND7!;Z6+vvCFu^i#%1)E6#;la zlzsp>4Ls!`@9IgSMg^82{5wO`+(1suoXP$etn)z|$^{2YSC6L!WhhCfMsy=I@tOH4 zA_6)lQRZ3=Ls$lhG?4!ujR&A(x-+vRNw7*bf9N2*+d6ZoyR|gMhy;c#=R>bhJQe&6zH9vFKyG1IWQu3oLFUnT3h*fRQ zzUD(8t-W;nw;$e&wv+jb@;GKs+47K>=svW3NnaSQ4`^fzd|MVYb?CUrFUi0V*}H`b z90{ZzlRpm9y@nXNg!hs?3NR6NSOS@Q=u^)8j9Jcd^Tx|}*sj-n2C&e+baP(sBg)Nu zK+?VT&vrY{{;0~N(Vs*Kv(vvcFKH}!&#vme;@hP!sa7YaM1&8Qj5z!AQPRf69DOn+ z)K4=W@1E$pcPzeS&zSY>x=iGN_oI(>?dBaV*Pcd&`n^{jaeHv3##3p&86c$w z1g+?6K||e)W`rvZiOuBa8z6xc8sQ@vGv+i>yM%Z;1b|2*FHew5F`J+f%Qz0;JS+$I zWMI;wi)f{?g=H@JzZ4H?2dM5{X?(xY}||JCm{q3q&}FT1=wAUQ`4cy zZ5a?uol;;qI_sw{7Rx&R}*c5Q?>F=a*_|x z>}%Tk+&^1%0qdL8#2yG08X3i&w|yQo`0yRgvF{z_)0{v4>As)3NZ%wLmfU3zsLrO% zI>*UyPNEbK?A|&RvsDw46V)rdtjZ_Pw}-Gb?hY~g=I3OvVkmymV6-MeW81hf+tBcY z-RoxUo~Hhv!F6P7gKWi&e{EVc7!SoMUq;)~_0QOjiQB~2P=EiQTyye^q+*a0 zi@#;N{b#L#1pVXnU~8I)0YCK^psJ#sf<9(}ajjDT#$a6WyO5PnkP7J9&yPP(FhtFR z!dI0yV_}3*xlU7IdwEr)3U@7IOHDjV>wGv|4}$MDIO~?HNt=A zdX`^9=?hGG`EYIxfbX_5CxK?an++&QOo(4sZJg;p?5Uzaedk=MWJXW`9JLegA=(8z`_uv9ON?ocxfrT;p#&W zN4`-j#MU#Vj76G}nunYkNH;0cONL~*{!UjN%)=u_wSu8PX!;#HOP?GzuA6UYKPbFA zNN#<~;!s1AI>b0lBaEjaVGmsx^{o zZJJG$_Mdz6NrwfJmy{wN9W3rz>3+ z<^urk3QtZ;GTuoGUQQqcM1kQ)OA%KXyHq%h z)*FH6mV#@aXIb7fset9lJxK~SCv9bAM+@Zfbi&G3x&u?fu_+mm^t?KSlJZr_N*-f0 zo_CYh00Emy45sXUG6H>Z&cjg@LV-;>o*UP!HITx`TJ#+^WVr1%C=QB z8u?lYQ^06u%+*!1)JLs&izwQ+zJS(|+KDoPd-*?jilE~%Ql#hbVL!#ND#hoN&6(~X z)iwyeHVAVftM==c#)WM6HGPO2gSJc2UGE`69!1|XIXf1vA1k60!=RH8t@cM&;rW)P zTeQ9#kFH5{lY-E!iX4HAMb_mT#ItCg#q-79bM2*#@0#KWNvNnUxsbsx2w5Zeh8f{K(Y;I#9 zE&hd{PEHttqhzaN`_N|gHAfrF3|6l{*a2 z7-DHPZ&zb&Qf_5m-!6iccVr!s%SWjmXj7NjeC{v)Y<wIy_@MUFxiPOmXTJ?n0IT$Le*!I-whLuHEl;`{fI>>3L5FTOGhc4bK9E%7A6x zQc$BrTmOXzbG`HAyf=RdKYy!FYKOjC$DS{v6Dh_r&R|dP)POOp7u+Mbxx=A zC)qYkk5!S5HRB)R#eUbi6HE5f$v%dAb6+xk>0tHhVEkvJkQE!0+8)H;&V%Pda;BIH zn$A$YfaoQUxW<(PHZ275&vAXQ3Z=C(?1>QSveppYz-2>Uo?r4c420or1D$9btuDRu zJKP)?yXX|7Cm*^$jEy2d0=%WeLQsSX)sdTiAw+bsss(=EE~BgvK{}->njzsAt$~cY3$Z5c1O4Lc8$k*;rOkT$G(6a~vyqM<73{+&?1TtSX+cG+ekS;oV|V z*yjY<=)~uW?t2|}tZ-22cTiiLe)b|-YSANK@t*u*9DVjZMo{9k9pjhMD0=whKzNL> z;{9#A*!tG{aW?np!_2NaAF!T2c+dfjgcyVjfrJ(#AKE1xmAVOD-N)BlghQ30`Ii!z zhZKwk*}lKG}ll!P^oZHWo9kvNYxJ zIGeV(^ec#(Cre-~-{X=n`L3h~EXdTZP}Zvuv~@;4i*`tS0yB`{#8$u>;8=^xe7%G= zQNorhW!c20z3cKB?n2XU;Bp5cE^t?6P~aeA%6H2Y7nXbDaXvq~JP%mX=z+4WrF_va zXeCT&^deKUEGKNKpnNfpnl<@tJP(_l5SLI;I> z5(g+~i9fuU)Vldts5{5*QK^X?`9&uzm!%}kv}C>nYQA2KhuiRi24wenGx7F$5C5e4 zC6or)6=png%y|^TypgBo!AFJkKZKFulpoh8JSOdaY}K8&tyDf6Q|=W96>$$xtRlc* zs0`=nY95t;VSUo6R7T`o_RV2wJt3BUh&S_l5i6Wm+Ls_e*s^sTkG-O#=o_ZLkDfU#JrjKV#Etd&%XS>SQjsPPn=lVi$KvkcS@q_h z3X8;=tR+qPm709oT0&*$iXT$glV}%BMxj(^)l;|V@We?u*U9k(y7)yhJ=Ao)IIkTF zgpp$O$fi2RE)(ivR&aRM^4E#xEh-3lPha6G03SU+o`J3Exns>STSMJS)O_OW<+j(o z=MXYjCcG8OxBfKe%j<-dSI-`|BtOo2E%)Nz3il^Fk(a;IQtTeGdRB9))K0IwVP}8M z&5oPY#tHTg0KP_$!~NJ2ptd-zZ@6m4zi+Z0cf5I=_u#RP=-;+(+t#d{=VtAwzbU5l zJb+jj^wCPoFURiRkBgI*t6o0t{3_R;`YX@W3Q7m7cmyj5Qf<>ps;Rl|mi<#z!){bx z-c05BG(Zxnfb8FOCwZUH@wT^jkiDs#z3gvK-{4Z`U&b!_3mlyz)Eakx4Py4lsZW?K zx8*8FTgm^T+&`#h@zN$bU@Yqd1#~YDTmN1Hjtp{D4YH6>E+ zU0mu-9>I|vf(OCYgPck)-?bd%Wmb;OE3IfJuhnxd*1W}D>~a$ie)#(YRw=?}S_z?8 z=isSaJ=g|KY*4MPS8}^Hg>i11-45Ih%DVq;NVe5LVBAbK5a&TA7?;u+Qn!$RjOq4U zNb>eewQUED2NygaI$nL~7yCH&>f@ByCo&*8a**qNN*5V?YL`OMF8@D|wLV7?;#(;7 zU6Q`aW7}OX7Dp0PwoVmGLjRd7;pvYf{P$bGt@{ZZ{Xd`SCZ62-oZmk#-}zaZmMBK~ zMK0%y8s!`!XU>>%UWNxWL%@_fK)pM7?fZHm^z{@;$AR>%&!Fq!q{h+tM5uyZ)EV-q zw31r)juv@v;qdOl<&GB7y!3exrb06B#`Co!WWVwD>rlul+0g1t2<-}V;*PQDO8K_> z8nS*wD(|N5^K^%DW9QR-Z^N*CtuZcU#){9iMHo6%=C@BX{#=Kg1) zd$I}NsGi!8q5{a}ZmLmj0oEDA`yqGr`FS*d%}uufKqL%64`-=3l^hvJrTD+JNCt!G z|DP6trs>}v;@fGX_)RFi{mv3b0fSi`e5bl|Di?1pH`^0 zK2+C2Sa&B8{Cf7WpQczQcK1qpc%p#BvXNpv(&tlwvYB^7r>=?^uwH_KR=m`VeAYSU zkBn$J5x{fuvCd0dh*KI7b=3%kTGz? zbjyOC*iCCDZ{bhBbOHuQ{Q9cN5Jgi+82Hx>Al@ek^5}sWATLQSkAJc3ygY&!&xLhI zkqKZcTxTeMd~=~)k@s+6{2Wth#mW-{jgL=8BCz_#zsTqSn3Io^%wlsB%7ow%q#6>? ztgot(I+O!zU6sj`t)~Gmq5cmok~!z@N=?@3VPQgcv1MlQQ;y%%W@_%crirw#BY4Jn zlaRu*RuQBAf+k`_^mqg?0N(A3L~#ES;-O*rqb7slzbd;jFVMRs^~a&8_I|h+5y$x$ zWE8adn`&t3GgLp6VGYpbI`dg!i5P9SXC3UjLqOapFho+9WrUOPd(ly53VsOdU0myw zVbJT?QOCu~0r~eeO)+r70kTwSVcf-=gVX|J5^H@yEg^mlk1?PiUno7n>8N_mKaq2?_>1c$y`29X_J4GoL^=Y z=U=c64B=n2=gEoaHCHu>T_%30UNC1v@+mgjRrFfnd4%eFi;q95LSokvwX@>%1KmR8 zM^cQ`lt!a|JH}7`KaAanTT@}1Ch$WNNC+jNcL;*?5)h?J=m;o95TqHJf)oJ(X+j{7 zgd!aQ>Am+NC`#y6KvYCfx_}f7D2j?^`M#NNc4qe4ojw1;x$>Tq=REiQi!bWw!UUTv z{#Z&k`|SH9_>XMJV*2eXp6k-o@TJzR6hl7MkCjD@*iVAaS5&roWBw}c=}$x|?O#tU z3>x&-?yfFfB*i0Apfe6$3gg)soQVk zqHu9ok(qRD!PBGD*e`~?zL-{?)W>++56{0>4Ap}5BNO~$MP*7(_e}fQuONj*=1sUS z&<=2q`w^7tOPKDE2KaaUh#Gq(h$z?~3hqzRlPP6MA?b+*mtbL+O4*8FLlVaR30C!` z98IJlLBhVA%&86zhZ#`6u=L3|%dB(9n-8N46&_$6MEK~phm}F-VGTEaC|Key>)35#06gcj^L z+)_&%xDxXGRlz?06^&2vmW#^PToS*Bw~j3nTyBOyq+Y@N=gU<4(gu~* zN|^0oeJW|khSo76VB6+0!TA*(KTaSaD-zEtAC|=J>z^F8?Ti8gL#jJ{45)7(Yb*+G z-!zDR5SqWv;q4+}nKf<|-BZl5RZNs?mqJ=clnL%O46hHMRHaVq!{p+g840g0hPzLLl_Slh859!z*g5DY|mL} zSTtLh-l15>{?Cprv@cP{!te}lOkC7^8&u-)P~>+w&ce+V)jBieh?7Oyg0b_465m^R z()WJ1;so72j2<|_0gH`Mxp_KVXZOC3n=~KbaBRo~35bh2!5Qph9zQvl{d|v&51>PT z$FyUaxkZ04{>CsqSUIrtyt=rs7aY_Xr%8#4;sandD$!gq2~IG*HMP=^J{^DOVGKqH z609Fd_==CBNUAhS3|TGN=lW#2aPCyo6k1;3dK!DMa6kP&({NKp!Qg6@=w%4KdxP!9;rw zmX^%Fz4(K64d*`@LyN=>Y6Z7&hMwU0CJM>tK{QmrLmas@b02j2DuCt-dKtNBgF8@; zI=UD2^KsM!C;c&*=_ZA?hs-2z%?GmJyj6mGH-e*xM}4~$bzH^wYb469kHe`2BLD-0 zLbw=?BXccckffMetp8XATw*?yN|A!7AfY+9Ky5rz2wt4qM*Y}7C>?a+`6JDlBmHQj$;@;20-b0h z*9;>!-^McgF}%hEL1>8qM#SJQ+Bvk~6C6V~8Yu!m%+51eTEIVY;pFK63mBm1ar%oU z21y`^Ii$pSQc4Iz8VtywAn==1&~HCiv;;n=FFx)#o>YxU7$qSM5-LY|8)^7jwfS6E zqaU}#`_IP{j1oIxfG35?ei(l-ga#85Pn#2e6_z+Ckq7_@9TExSqe+)ZkX;NtI6D53 zt+X5(vPDYXBKaz;Fg5vIk{SsBuLkt{!#|S21Hz~N5n?l1Fh_yez6-X6Dm@=nh_fK{%$x41Yw zQ(^DKc*oKhR@0tltAE0XXNn`Ev(ry&khtEF+^cAMoP3v|#lz5C+ga=P&D%09W zbNuxj;usP`PGC}?`G&N;h&mJ7thq*e4a~wIX2_K(i6p#3=BRowwB$yg_x^agmY-4rJyL%DT!2x;d(Nb$I$l(0KjKrAk-Duk5Rw$8W^Sc zN|_|GB9v>~Gj}pKcUtnyY-kGL2U!?GF3Tf}2RgUrk|lK^Ez& z@K4!LdH$n)&Vb0%fMxz&0o_Hz(^qNiifO47m>s~Gy29+~M++auh8`5NsFhp*(mtlr z9>n{?kQZn#oUfUYNF`vv0$tp!yYO(!aZKW0Io}hW#8ly4+AqS6a&qr zvcF0d)XL6>m8H|?o}vPei5x09B@RyG#WRxCe-Nwu<>2 ziuo&whm=%E-Y$21RL+#<5JIrKS`>qblDXl(${K3q z@JL;B2fxx;FEqqqaJ48a`k(E2xQdhmno2aY3uoHe2OSvUTCXkn3VVKZsr@M_^oY~iVE z;hSg?*liJFXcd-j6)|Z&>(wfr*eY4qDm~FEyW1+y(54{WcFv^jyjPoYVw-ARoBD6_ zt&uh@hSMoZ>qAT!m^dWPn{>H zZldSKZqKkkgo;AEl13b3BRa|O>%U!Io700^=#FO|f?hraId_}5Wu{+(?E^Qd7{qHY zgwH|GfpqWJIxZ*FZ7p1{mfxNEy6tD-L(i5Np8Hy~Z>U?hJ_*c%`QRzcgd+qlwO7l$ z@SAiWn`xiO0nK*+$0!U3pFtM;J?&QaVN{@R-+fBklR8>U2Kh6u+V;ur^~=|@l$aAQ zHq$=9-p8xMwP&CoDG1r}t|Vz#%2Ol`g|M3e?YMPAllmDLfp`oe840n$z+4#yti6Zi zHGpI?({VBL6ZGw|VcU=+Pr;S{juUMU9A{203>mB~iV+sLs|u z+-#{fHdG67)TqM}qm0V*dum4$`M#7KogsbKI4AFr>Gk+HF{k&%(1p`n3+ zfxf=JuCA_*jt&Nc(bCe=)YLrHf&R1nqokyC%Kpg9%gf2h$;!&g$jC@bOaGtj59)t1 zf7saA{{Pt@2>2ft2n0Hnh)(lPr2s%fLjwQ+j0(`e_>G#2`|vO}xI=LqA&H0-G0rz? zDIH4WK6m^5X&vN93Q9MD|59uDScb&aTF52c3DCdeKVsTo#s3-qDHd@%#edFMKKvi? zADe&TKNFe%75};G4l6WW7s}4c@q*O;6aSGu#eWJcl{_;m&5BGLo|J!TQWBde{Bv(m zi^t~f?*GPr8Z#-dg(&*Bn5ld$UWw_E36!GoD{%7^{~`Vp|7knLe~R)8nl}!%pAwF_ z&OH15FZ}0z?C#<#n@Fw7P|HuA36kwx;}LDTxB}11;QAsV6m%==L};!QbBBkl3V$K zbDmoTA!|Rid4x7To#H=JHGrwbtj%@=aX7oW^s1e0MYcmU{ipKGYqvjzq|a^8C_77h zU59-i6*fmwy-SekASM8htnb|UH~eR}z8xN|-_W&LD_w_XL}JU>nh_Vn zBu#VWcK6z54D8L@&eeea@e~J!wL}>qS469xsLs?%TOqf*x0gJ%892*#eTzBjQ4q#n zsY_>D8F>>6pZ{JnSxaO!R+kM2ad}hvoGkg+1m{d~`zfKXb+4oIqzx#vs}JyxU%ImOJ;o(D(=bgMrE_ji`P(4LKW$ z@85lCth^sMW2z;4^qNWU^3j`1=Nxs(Q0XMfTP*QI(Odd4>=h1>JKw<|2Up;jZFITt zJs#UGO#g?Ft%e^#2rvKQ}UMe1Cq-xz+e{ zGymS_pIhnB{*FGkM4w-us?BVEY5SdIOz%>UGt9W(hcWnSbA8D?80L>c#nLK3<$K0u z5O;bgoUntw>1(e08n4x~{ZcmE7OsjcN8sZ6S%0=d3U5 zOCi<%Fo<5wDglNYVHWoQ=+Of81qg|4r zj1##px|yQM89`=6E zQ=m!!Mr5{i5>)9qF7;B*xxX!!;(^&xmV!^E7KFImunxebEzEx!zS9#Cn_5z|S z)kc?VEwjg8m(ihwMLY~ zpw0H#wi@p2mtyo92T!KppbiR*wKrdt?unWkz4|(`AMx!5QC}v5Q$mQK>irPpOrvr^ z7^$!=f`F6y6#u3{0q!z(@K_EKz@|*W2U#|oxy@j&t`7tvVH!R%*@6g^n zO4D?YP8xIgP`L%pFA9F;dZE1_5G9NoMrX3q-`fxo)MVYgrTaVO<-=f9_4!e~fmyqG z-eWRPdIQ#j0a*P0y$|_a)^9@80XPvB1mD4!%V>@8XZ8<{aD`fP1_2tWLj|$YBqpfVIg*;+3V!ocP98-2Ijt|NuHD`}X z#qaNWElcXIFuL2KgmYmd#f_c?m;Km)#^NE&BjKso%+SfMsquw2u%ns%a&_jOKrRSMHyHYU^?!x?cEQG!!VsyX{c7!d zMcQsg15%@mSEG1`;g=-6lxQF8cbqQ&L`#C`q_AKS1mOBC9FKD7&(wI+(a)7E=yWfx zkD{QjbekOGcJ`*%YSs0}F%UQQW45ifk9fgtW{NLt> zMb3C7-Rof=Sr8;mKX^W0)?1arGDEAys^B)FRoDXK3!hg`@p|#Ld=IFtpt4SzOe8Al zCL&CQvdupWTRlH0`1@!})hrx59Vu4)C1v|d#@+cc!R^%#N}$hV1eU$vp!deTx1-m8 zZ>kre9t$Nk$=eluSgiUn_T$ep)09+xqvy!=kCD{g%w;l2i+a+Y5@{L`CA9k%`rBkY z@+3_cP;0+<(rl)7oRjkRFW&KwJ4Cenme6NIAKCSbB+X%Aw*S>V3<EL3JR&S2Z~#(bR^rg!OwsURal1WtJydqdHM5+;*wNDm32+uRAIFw3(f(ql4$g!HYE2yfm_ z7|w|vQW4CS5ctf_>2=HbtCiVl@!{{+W>j`_usbpjV1j5fJw$PLk0uu9$ZuBA1f`Nr z$dLZ|IKyL^tdJy1m+%)AOM%zX3oO=Gt*s9-t?l1f-{83BYJKfi)-~ER$lzHd-8=A# z1ZmwU89(aT>U@f;Kr6eF?;0i5bEojerycp<(z%>5a1kT8h=^TDPi2bTWWqmAZLInDa)bF&3fW11LVV8r!E`88Oo{D$+AYf%2m_k!*rMKK83+>Fnv*-yBO9MZtSWV+iF90W+?>MpwU zsp!nFvnQ$o6ELC2+(ILg+3fHlM+@MpdC@dal3>E4+U;y%wNkZlVL%G^o<0s}EluUj zPQMw-G)l+fSM=5*Gs-{n8_{CM@3vC<39;NTfLB&L## zt-QsX;3<`ZudQia@M}rn-?gG)JgoVw?S9>^MpL5TXJ{3=BqkLOL@ZQY7*A_^QV%Fr zz)=wC)H)kup~G3T{w0aA3nl?#pZ=u2pV- zt?|%U{6JCuD5l}Vg<5(Rzyb?30D#)@+6JlQrZCC6(8h^JjkT@PjEl{!0n*HTEl*~p zf7CYVO4ZZ%HShpHJW#N@Q@eh2He;h>vMW(GslD*DUGabrR7?ZdSBg~^McK7q3l}i- zs^SiBvCnHbm(~XIuh-nHGl&nh4)5@g4%St-mrQIo-R<<-Emc@;=WA}uQ0r9kvTcEu zdM-Y0OX~>WdmLTYaVN1Ycm)DtY2MQBFxz>Y{M1Wi7xrd_`SS|n)hb383$G*BmW1(c zC+RMz_G9PWmXL|AoL^nlUTlqSbZ#qPt!Db~sgU{f6nSK6wPhDR@9Ai6J1tEofT6i( z|70(u?9KJYn(!X?PUdKeQ`g(h*uo}ikwo@UTWw-1N+R7=~#sW|8n z+HM@j{K=0g&+j%gOVCxb`*!XU}z)I%tFCPFde5qSWWPx55?bqMx$TUpN)#Q6urWYp+Q8yO=8j{RE^Gp8R^>9^5#kQP~u=I7jH3UnI1v=M{f z^9GIcdrjXDUVhbU-lJr8a!%Fj9A7O1!f()0V@MNE9#0r>NxJ04;8?7W6rdnnkhod( zXVVN%988``F?N)hl&#--V%kl1_3m&dFxHqO9Vv*<9ns&x&x{#H{F6oj>dMnzzMiY< zJH<=G_drx=HOd1OcTwKQ*}>?C&QKe&q~xsz-dE|FV%!D#w_w# zxyy{T?HE^4n2!9IN04+Q?TkAZ#D^97PWAEX`cYrg@q#>Ll6QUi)2`IX$L$(pZH(NH zy(WL|bid7SzhW}-pof(GWBizFA~T@*C4UOeezGcQYBXXJKmrq!?k~KiyPqRXwnu zp=%hKw0QBUei~IUTIF5)!5E1rBf7Ar;DVRDAIQ)@euMn8WABGgBbkpOlxlr*WG5LB zTRh9{gH#~HchHErRN4%kDOt_V}{r&utJ zdoTz1mG|l+dsSd}U(7^=#=ZmKO@7R?NI%y{IrqSsNq_pTaEO_gVB#STuj|;?4fd+Yi`pxnN`g!wI#RZumuV%`>*T%g7Z!IB8~#C3FLfk@a_4tr1WPA ziGHMlMUu#fMBIwBBhtWLxRyl zTS~fT#$)y0+TVU#^>lM{VUz3fn&ID%I|d2CSP+!j@=B9wYk{x5HDWz->JhGR%h9(c zY^fsKm(9tT?ae_i)E{KwxscRoyVkRmHdUVyIihiK`{Kp7I=0XtFJy(}TP$@#g!7rvB#-d;c1`yNR=mh1WD`!PmPh#pf^;<&|M`!0$1^Myi6?i0$pywAIh zpTGCz2U5O3g)?a`Q&xN_m5m2J;|GoTE4_02hg24tvY&K9L7H=IRH+{<^WAiM0H6weDaRco5@ zsY3wGZ@St_dO$I)*$DFxmKH2bH%(#Q1{l77rJXfLe4s#WtUg=F$Lk2yGc9j4d=|Xx zgj!tMzl?a}D$hswCKBIn^x&HjutKwggJV)5P3FumOTdjUz&6c{vnZq*5>bSLq@*Ie zyuGece{gXhpSM4by>s;CfIxIYStlRrE*!^{n5LdZqJOYnN20AL2)HEl$Bfp^6~xPz z^l#C~Mhv6V)-U0uU*3~ne#`y#m_o5oA9R6qUS53qHHrGI-Py7i0Z5)j3Z*h?iPH=I`d-lS^S=BK2( ztryP3%b@W*2Ikctb&#Mhqgj7lZ*xucM(k66PE-M8;?0p#PDZyWOds@s0*s3C;vowl zoO`tt40(_Dwy!EwC>E_luj++vjxvvF>{)L-mo(6)Q7;{HVUOHb+>czn#qvo>>2uGw zonIJwo-EQ$jIRsYNJWfMXLUO?NATQodn4q05R^DnX-848` z3O@*&(%?)4r!}E}@UlsY?4_0hY|qMYT#=7#(<&M5e|a~}>V#DC3OcP^eU94Z(I<&s z^Muj?R5E3RRj3iQnb#Re8p%NMj~Oyb#!o0-y{!C^y<1lMsd=~JS6+@L%P(qgDwuYf zMdI+umUtmY80oGm*H5Ya#ICh|G~>;M>(E>fL%%L>$W+N$82))`Wufn1zwK97swz6| zyd2Xz8|9QwTCZ6=J!>}Am){JAm(FFr;*5mTusQ5%=zdx7sLFio6#ivMxy1X^LZ|*c zHj|D<+$UacQTDy&f!N^-;4j&13mn<@YU?lFDuqc8tGGU>d;hp5Qn>SInOXmDs#`gT z)Xyx=`ioxQ;N$`KO<-rTYyH8UVbxpDz2$aX?`$!u-b{tQiWh(A++Uon?EW`+jZ0zk z`mGvjRi#>aHBUe}@4ff_Hu>PyUMFUJ~`;|~#RO?u>uVl4@hXAj~qmt)c zx1askm1QrjtQhr|=V3|PGRLo5@?M5{O^okR{w29ND?Oom?g;d^6%y($r2t=F++mRfVL=~9F4A5=-~Uy`}V>cC1nUAOAodr}j))X_Pmp+JbKhf`;%|hN5)k#fD zcr#Rj!r&aw3fuII9k6Bvd*-?E&*F3`Wv2&b#iW&_{R&ia!mhn8w^hiPsQPjs1sh_8}PkS|+^G&sio#Yj_ z1uiqriW-&B+m}nFSTbuE&uG&OgZWDpz|EJErQ-YaO`Yt>L~USPk(o%c24eU5WVl! z(nUi3IP(P@OgG9Oya=!Fg19yeyD`{rru%lYlr%Uh+b@1He%vM*tsF#-n^nf&0R2uzq)|h`@fb_?QKYFN_-NK+!wjG?W z$#V3SEN3iXk?+p{$A4h4KIslKpE$@|o%KKIz5%1L9 zD5pH`=O!qGozG`wZn7O3ex?v`x90|@t{%8Y`lYpd5RM(6)40A*ZHja4+4x9ro4v{? zpgC4w^xEkv@x9>pYl6C2 z{aDVsg?Sq5={eU&JT~hesapb)^Q$nHm+zm<(0c6fBAO!b;ZiW^HRBG;~ z@3jkqSZE661;uU|*ekcbt^HPREn8wGJvgmV*miYS=FRmHNdK8uU1rgK*sJHYbKQTA ze81$swdTsZ-Ed{J?i0V4`nkNhsm`EgL;ytT<-YLByAfS3+3mbSUVOxb;I5iD?^p@@ zxf!|(PvROrr>|tc(0DLPW4+-OjOS{V6p-o~dUoe>+HcgRZ*UFu-GomP5|zT*-FNX= zAvW%fdhe-{*ev|wPJ)?(JP_4M)-t6e20jsIxukb*wbGwY{ZUU^W61cqk6&mUAC2cM z1!iicN3(oVJEMF|tCfQeNYRUiadfq}^T&=l# zeT|~`bEZSEq|{Yo!TLvQ`+h@Ue2@JZ@#d!2mm)WdQtX%QiQ!6ZrzJ*J;rmfy>UuDr z?fBwR&czQGqVWlLnx1QZCJLFpb!_}p&hY#|uqD6htR<+T@6vwgtvicV)`6$^j|t(6 z(TBJ9@7ZPu3Ts{4j^SfGCYyv(Qih*wx%cu93H|x__*PH2))^{>CSM@_VQKBi<)7SlED$OuR~Q zwlE_nqdLbV4BW0FveBPH!H6;TA=>*ARM=iVf~~wG3PE(JhriFQt+TK1_ILg6hdSt} z4fZ9XX-VB5O3cwkYP6ylRZa()@hX6WdAn)EU?OSovgja~amX%-WWld%Y1+nb z1$)h)7!QLxaSM`2Lsug76KDG8+lJipvyaOZ&i3dk)ayE$!j|$#3;^M3I>{wg|H|I* z_4hhA*$rdKL!OgEca;o@B>9~T7~LycXb#L*&)`nJp`X>T|KLcB#E1uEz;aMSB7$#O zU7@UaBq7xh|7|eh?r?-s|9x*A&kaL$2a+PcELHNPcb9?es%P{-)F}K!k1#l5P#WtI zLcE(pi$cTP=Q%7x6fekVW;=8yj1F8Yfhk!H_{fYVPh!qM#{9iSU5@dh%^+uh$c$pT zx{|>~YS-sicXCh@*Mk|ClfbrBVM;?ucLy#<4-{IR&vA*4qJU;G$fKBH;@*g3>^R}QKoHUXjVUnCQAsnII=wOhu6CKsXQiCA|b`dVGq$$9Y6%PxwEm7Kvrhl|22iuE= z+$N9xCl6U@md0p)OGZ0(CH;w?9C1MXS~VSVD~5$>#hn(fO-g`IXA+VyZ6sJ~1@BLy zWn0LKG7=VVeX%(B;{EFvA2u%Y*?~`4Kd{PZiNOjKOTsVdO>J0Rk>GvNZ$CP#M@~8u zcL%4rvr5yqQP_Vn`TO1EzD)7?!>M1NrYKe-(}6`n?LuPaU1BRm2cpvy|LGszI33;> zY%vTz^F4a8Q&VLU7D%XoEs6OUYSPmFQFnw?K5T%8!BpyTNwC@tsFu=j-HF;0Q<6y+ zq1-L{Bx35%$#Vl3@A7tXm&4Doi{DK~%0R%?<&XZ6Yq zk)=Dp7Z*&4Dfea&Y=+2GN1xj!xO-fxvN9LzXe46WG&R&KR`coIE$Rm!n~M=zpqoIJL4)SzObFD14@W&*7-Q597RTrY{qS z-_eWdThs+SddUU46&^TEIF>+PXdem65(7zD+7Y1?7Mn(XM}K z`{8*E1s8;aSiG>7dvC4!;FXv=xg!&1GGryK`3AuzWmYXFho%dhpRsp*eM_^)qhikK zy!G2evO^i^ntL{<#x;Y}|BrsO0o6o*zqsANYj+=L2i~9c5zqoL0IYk@;<>NE$r#%T z8-@z~sE-(&{u^rhhPA1yv|#;f%6xYmhi#|H+#P8f(i^q-`xg_k<`xIepD8A>`DKKB zw9W8ouRkGOI)>Jo(^$+CLSaygQ&(sPX;}90H>C9<|#MUMThr`lW-F zDoam2B^qkDP4GxapacnFL^KJ(!C`UUGY*&L=`K+ScT{LOBuHQd7%k2Fxq{xe_s9D8 zm;A$CCX~xN8l}AqfBzk9{~#oxy4eBW47aBR8dl&<5-`hR;;n7aO>IJ(QDTg3Vy6mB zk(YV@!4-$|@yd=iK@IbL3A6Di-0V25+wJ+U`wQRB!^-kyUm{IjVVK@vncm_abfV*; zj-z9`VxlmYmMAxtRbam}89+-;;6ho5(+Z?wfn0lah^f%~{&m_-83s96h)SGXD(T20 zr3HuhS&aCNCY{V9fbA42IW`q+bMs|Q$Z?cL@!X(C) zcEyPlLG{-c&SlvQTE;T%)fvjxZ1Erj2VbzkK1EiUG;67#gKQ zG=)tPMza+6vu@BooR6ll4Iu_#Xm?~`H~l$1Jl$@5*TDK(e8{p3c=Y-gmDiyuD_{D_vPlg4VmWP3aH&vxUt zZ5lq$`J>eZJJ5cy6^RU7U05*k{dBotn^b+Xaq(0B#irE4t-`-cOrhXwKZl4Y!0A;S zkK>Ea=+VBziNDUB8_b=%t%WmjIH{bwiM)>1i{?dTbT#Jn2ej9Tf zEnE2%YW9}tp3g8zgQ+W-jXbGOHX3_)aACu%LFs@^+#{V7XFCIRmN>L6roChSfeZ0@ zmD9IPDe1MGBB252+uMMM2hLEw87@$5sjFL$1+;4%ayN4P;1o<5g}hpQ7o zu|{+jDkKZ@7aPcJ?2U5xCE@@J^3*b+ifYpge_UweCP(CJ*guS#rJK;$Ux55vz5C%QOkJ%T0JZG}fd!;_H&XXF+KH$m6%c<4q)FNrqB=|8h zhfaTzx_*s8f%E2FUL&ECUk-caNmNHIm^2RB&h_VpAk50>^#$=rtJGg3MQ$5J%h)u_ zE(?6VZmfV%SQFxB^9@pvE$bhx)C)an5YoM^n=~|7zkZ1z3bq@)O)1glq29*Sd;A0c z;T67M^a?97ntDb)_(bJUbUf+o)z-m~L1sRf6yoRF<891D{u!H{J)ZQc>0)jhg^r}?C%^&&sSg7HInxFUf-TH_*b;$45I@SU)~?x zx0aM^5YIkP2^s%UzTB&>NreaJ^d}dv^Fsf$#@HoxF;`Bd7%1$bxl!PQK(cTG z|LvSJiJXn|XOiHzZ3lu?hk`|tTjGg@p_;#rMN+jB^s{t7A5&5hpK)$DbO=qVp(aBA z)g}Gxle-_YqRU&(QnMYyexA*7PEZxgb$=8p_Q}fBme=i+(+CsTju_CZVX#Dk)m_KUP%G5#6X9FstOUAG9LVN~irs6m>{t zCt5x|>^82l)VQ{`P7tPZ*8mmLFMD!aYEakMnp4*(dALxQz;pp4axXQev%2N9wMwSV zxkPzPqm1#z3B0&q{Vk%+K>Os>0Pg37_ z$vdyRT&OnFBw3t3VUtE&+i3YB(EY*(D$sMg^#haqyiBNZ6+^Xldwx0^8i%g%pnG?m zQ4C@MW-6ne{ZxJY>&yuzx-|Z|3G^02VersqJ4o^GcAIWkk%XOfzczzrU?1ePyGY%s zr&);%q=K$EzEH}@?oygQIe7EN{X-U=@4R-bK0At4K!jU`{i}^f)wA=r&;M?RD=791 zv~ka$m?|xW?*1uzdB!>ZYz2U7zoOC7gXtKt%X2$gvsGTo0?g-GXlXb;;25-iBQ1Zv z^A_Lwxs_728Ep2^mWKQu*aN0Ngg^bOwpV_{H0PI;Sk-CMm6C}U@bv~P0I9ESCTtv^ zp1(O5#XIqSQhRpSZRdLRtFXN{_ECSXwMAJ!U4JYe_2Gv_?n)3dvVd$9*pZL5IK1BR zCGz;=XRo_dlm7Z2$;@`&2e#!D-)#G$7~M6>BfvO*fYi4 z9lpBawnXG$a;gYbwTMwASftpvmGNtA-vF*w_j7>A9$+LlP2HU4ePN0U_ueIzy%_?d z$_CxNwGmlDaXKF%iKJieybYxC6eSh2HX;dPSTx$Lr8(hRyklq!3?i0Rj75C7Fa6vx;;P;k*_9=Buj}Gj0sSC)_9L& z5#Cgl_w3Ph6Q`Q_!_iXWE&erd*oq~Au6&iIJAhk#yX4vdZ!Fm0aI$bRqj17)^Cb2V zZ0ffzI9%)=V)yPvG%Nf0?QVm!f|m4Nndkgn_A1#st` z^Y_|{hPLt0R>?Qrvv00jotVgFR9|f}_(+#Xn!4z%J(thUf!2)^vP-GhVjPvT<)?7%IQFZM8c_;yaiB281+j=Muf|pQfjPZS3Hd zezTKqxN{~1!^HIwDwj%+JG*TTE~~%uxtPyUU^%2EY|)R1@3H*mhi5~q4qgCKn;mtyz3oR)77l@Pq=D|7jy@3A`!tZ z;^N%nW`bk%tSkaI*!#WdYBtVhd@>b$Wz*;IN71-_R9}9)V=}o?CMA#@Z#(G17T5_7 zI~%{wf9Hwx(QQBZ(hO1`@5Whg63)6@J?F}L#+x%o{$?;wBR#3Znv~~3+R^-3re9}g zg6J->C4?r1YP%IATsmKJzjVjCE~{K7*Io7w&&=4`lZ6i(7F@P3lc?MP4&g|V$^O#g zl$5{H^d-Mc`wX&f?g?+p^DAdc4MA5#)9x;~c3yb?_>*O5PK=;Ncr2Q%`B|=M{!H;E z(N@`xCFotW<6h_2re}M5nJB9g#*TZ>!!1Du^oA$|0XheXD{ zf==X`zUeh+rl!VwmXR-m7KgJrb}p6YX;T`tKO?_=jG^apkDbwNyc}x&zeu~!s3zKW zU*JO$NC+jNcL=>p?=7JVBE2Yxp@>uk1O;gcy-Du^(i8-gDov1H1*J(>X(CuK^dgYM zv){G%dG}doo&Dj=nstAe&-Yq0_chn`|MB^&R5V)!{C@xNE!!%y$+n6xWh&KBcE#{( z$-b3>2N@Ozl{en_Pb&C^GqI&lyWP(c>%}P-9&ob>-98z!{sIY@@B58Rm85Tc=TzC5 zMTojD??lJA-zZbeMcjneeZ8XZY)S;N*?Q|S9eXF~E!|oYJ_;rueU-547CG=P=*^h9 z*iPRw?S``zu?7CH)HiR}c3KHN2yH zzk2rK>TP2jb6TQJ9C;D>>t!t=VppbqD$Nxv&49^i-B&XELGCWY-5V(Vil-dR_z)cj zM2UHOoOUY5jWlrm5rMBcvLAS+qb50K7(U;`VRsXD8h(g#6gK&H)v3v$8>xMnf)@8gsmL@)Zh+ZQMD8pG> zw}dOakMB%N2pg#|bnD0TE&XeEEGuzBp1rD(5kjg_7*`VMMz9Kf@0O}I;?g`(jbwKP ztJ#2ATp=dvH`&j$)Q{JV(@Krh9GGaoSyf<+fL@NaYiC33@b(f_G66OBNX7uLoW(aC zi!a~qeA&QjJ6|UX074{UIV1=ii2?xu1mKj5KuErB(Tv_zS+p#y*OnE+v>w3+!wAep z1Y`SdDd$O@MKtc*N&fXhANI{>40|JFfFxxoh#&i1ds6&EwmDqDNnJoU08og;OPjpV zAr$^0c}8%H^miPiy+ogWBZEbXCVt!w~XtXTD5@UbTmc?qwp(BejJCXMk}sI$FoMN zt>d*6d!C~sGta1=yk5S42B!Qb6zKYlX&j_<24+{(7CEDmLS0X${&pMrLTUx|SIk&T z`I$DEyU)ma(Ua+~b|BWgUJU~`lOfnWIgLju3I}W^C_~1FnfNvj7>w zK)zev>n$yu0c^BFF}_>F4qWhK^Qn6uv#X~4_Df7zkEGZbMFmh~P@Wu3N+NVuT=IJ{ zkEu@UdI?We(dts#u3ox2gnjdl`g*U%v6gzZgR!Sa^JCGL*DFxjUMcOD7)ZDhmiQIi z2j&FODj8MkoBSvMNN5vE{IQW_z$tzPW?rw%If*RX-4de|#3&0yxR8?OJjIKcQ;FX( zAK)t;;Ptoag9?!hieO}`HSZnv4LtlcIHCtrjF7hJ(ozK}b&Z3%zw~4Gih2j8;#54G`ee84_{FO;cBq84M zx>q!eV)itCHdH*`;?>+pY%S7I-_zaVnk!6IOO624y>>v3_X@!nj`Zcsb?B1 z#@C;kk}C%GqG!EIHj)bUkx;vChBGZbI})k@oS-L$DiSa2P1I_#hxj;p_MY~UBvNV6 zYo2F%uQfV@1-IZqtKfv&knfAYaj%9Vi0bDb3R}qU3nLK=v{ZhCT5yE0Hlr^44!|a8 zvcpVT^ihHmM0JI_|9TzgAD{gRKE@cI$rC-susUnlUHz6F#>bNS8C?a(pe>Ga4B^A5 zsSmu$`|-(6J+p7v)gBE=7Vc~m%4wnJ(7~yxj~tuSj{AJP%)_7VOMApB(6EfMUCcb| z5{%e&M(qk@`5G(%?VI6(!^?Uo9KB)+U{f!;RxtO5z?JO?W#1NOn-)`87Wz{HyrqzA zyj7gbir{XL6WwLAcK+g8|L|Z#NPCa_dIN=3L%%)ofevLiWCgU{?*pC#9NC{LG|MP1 zT8qgz2z_7lIs-EnHOLZWEH>-QyX#DKNa-RM#MveF!do-qd z^JyD@RXn(kY9zC7)RM&*&GqnW(y=H0!COgP8{Fr=?IVyNn=5|#x&`S!BU9q?(6RM1 zF4_+=MOUg}{+xX<=5kZF_0-ieFrH=PvLk=H?WfPyXp+(>Dh4t&(?s5mD!I=<3--^Qg(J*;f~KV1(@#q3d=lZMvH5FL%Lw^MOs*<8V*J zLkIe%^VByONsQ62LrZ{_UbXAKmX!VXH{hCwx7k)MH|<^iX4mm19mz*yrXE^hw{QK0 zkX>0cwmS;Seh6{-<I-Wqf8`1%Q_1?S8Urjf?{PabN4Q?kk1-oP9R+$pdWhOp7c> zuP;4JlARMc-48F;?I&rG)#GdFQ-2&C#C`kkgJbSqjoO~)e*+7X_h0bV6@bw|;u8t> z7nXKPW-`htKO0i4XDdA#f4wZvA2@Y(KIMEKm?9{}?VObIu2oCjqjvD%Rj+TI%0ZbP z1Et;7eUTss$)KY9H|Q%desgtJu0&kPlxeBfZf(qih}om+#Tmd)OYdn#i?L<%Bky*> zdL3De6Mc`Bz72iR3~7goT4`I6-ktc_ATK3N__oT6BbB=8T)@lUL z-UK~t`csk(U0+oDqtOTIw^r>-c7F9Jp9{CP?N@foeVcsdwYO8C5xgLW4qc4s zX;v-28SLex+O)<+I&E;pqSe?L{XlgvWjFXq_L=8v()_cAO-qz0xt#oANWtB!(h^rNOHC^H$sY|P688+ zZhma4lU@?5S~NYm>8gIZ0A}P^aLw5;TY}^tGRVc~se(^@_5Po)FY-0;m-tVH>qNM; z8>>!5eY9Bye?byNDVF%PMnFrUvCgTFcc_A=BlI`3)i1q@J7d=^hH1SPb7VdbWZLe~ zd~|%Uv+?O|Gw)>6wG&o8HfEfzK<6KnU7a$Zu!kyWE{6>SXoSch{t|07Jpi zEwg|dFE=fJebOqn{2}{9x4kamYYCv0Jm*%*&G)P0-5v;0sPu67P38T1-FK?aq=iF_ zlG*A7ZM!wE1t|s>Q6I!Zn}sO*yCq3&Ry#i;z8))gJO&0|K5OKBrrs^0>h@{2^Vy%^ z@;UOUd#}k@S7Mm(k<#5%D)A|m9ltp<4AJDgW!^GP$7@5Kl-b~jawkPf)4mFMSvY!3 z(>#JJ^fj#rUicS|7!E*Z-@n#u7DyD;V}G*d*%xncR@a~yAo87rJN25cT+6s}T?;Gt zZ81|QoJ9l>{DtKWFE7$g?YQ!cQk0xTmz>AeDF zB99*FPEs~ebQ^3U6R$GSy1%}oc}ei3Pt;4UxIN|NdbMw=$F&>I=zD>WC?b*OzFX)N zToHS{gW6vNr*llQL8am$T}-VK>ni-I=AOTZ^({L7Mm@@}ebZ*8H&@(PNTZErj2viK zwdi=%I9$^nPF937-WMp^v^av5{$LV#OeG9rE@&|t_oj(r(Da{W*qb%XwP<=}5|Gy~ z8@R)eHXozRL39Ot`7X~7j|t<4&tAOa^Mu`|U3|ksQdH{{FYcvdEf$l|qv(|26Oug< zviHgja1K!BT~F76uoQ=q%&j~Vh20d$xI7+oyKrCZ6ypm5x97hYTjh_ouAFz;tg_u>4{+To_hzv?HfPJcDdZ=Y_Gxuay} z0!#(qvB3eX#oHZ6<|nAE)?+AHxSh|pBEtX!)f8Fg`%626|BnBtJ^=*=YVCbw3yUb$ zLQ8z!pE5PRb@1uN{m%!pya?^>J6jun%VlY6x(+{ARfX_%kqRz(N4URJ`rec(K|KAv zK5ymoOyHsYTQ8bMpX~B}IZpOi8$%WD z5)N^g?*uW@g>NBbDT9Ye+MOuCW-r1xTg|cp%<1SZoTC+A7E^HyRq2F`K4RO~r})sF zZo2e7MrY|gM9n)&^o*C*`f?OYpgT#%#DQ^+$DwD}3&9CIGTLNB=mepZQ0BE0vRC>An6KJrst-p15@wk8V8&0<5@di=y{wJ&R_LT z&$rN24Und0KxI7FG_BBQZZm9#6fu7F0j?_Eylk=H&pz*4H9ip}PQtRbo}a90t)eh} zSy$wg`1uX4y=7slJa&X3e3&6vNEB#4BSlGvSD$<9Q_bOS@LC2?ej%0AEtUDoh-x#8 zjNF1~bXCe~jJvO1yDl;QlhEI?RAahBQiR{-&}DPW%sr?#HR%xp1zg zoYY$#Hz7feX*Fy=#qN@@S#)P*W?;J(HMHw&KJ}EvpsA9(;)EB?n6($HXJ{qq{c+Pa>34=`n&&o2&C{`8?nezp9O75M zR$_Q|)>%c>wgYu0ZzhQ~JAI}iClRuxcyKklWG#Ne>eWyC*F>_+=8}U~Y10WW9M5~X zT+n~;TC~dvwaulczhgaVEK;>-aCwi%UfK0df4z(&tJO(lGmf1QfFv{X!kb_b{))4G z*maXU|6aAfZJ*Yg?xK3TbBS_#916H+={{M*mO#Ng4sHoOnZ5|cF=!QCYQ^nU&kl~fDq!IxgW^6 zceUQJJF%IsL;N@lOMX>-lFoZ z*lU>{1nqAMI#O_TwVCtH&GP83nZ=hDd(Fd@^ayWW%8{I0%(_YPrgOKR#qnT06;Gl$ zWgkNiYDh-k$J;=rl47^Z*pGeNJC;p*RdYgs=eU@{)p3dENnb;j#_}?0i`%EQq zC2$jaUZ*Nx3$o$B>aNbP`W63S7u5Os z$0Qn;!zfk2b0ha#@S^As&9Egk8zwksb?U3vOp&C^gkf~XI914|7Mro`5c`kRNc?pL-m_q##*K8nMvp{VR&_o&{^O@=;*3oa zp>*DT5PPZj=AXg$|W z;IUme6i}o8U`FOVa(u_&))PhfHzv!=T)PecxfoZbloraWjy)&3)EvTA&+mB(oqF~M{6X1?nd~M{PhKN4T|W+8 z1!th3nJ8AP?q$s`mW*x?e3fQs#hwx1G(Z6F0M7U-lpVJQSqY2pHutp@NuF<9``ncJ z-shDjWrufrj}d?k|M1OPR1RgcBa$+qrugimc-s|7VKHmKGU+DrMmUaB7XwSfGAuZF zH{GY(B#@3KP;6sp!gBsbfTq*?|-IXJGv?u8L=lnEBY8hN~r zpm#GF@f{UvqfXuxdfkI#S#aP;aiAdMVK6ggfoW1V6?4AE&(ZtXxC0ykJsc=0TK>9o z&v4qe;zHCYV>{s`N=-1)d6*o6CDJ3-U!<~nd26?sT%p8;1ccM~m@rSd(XP4EdxeVx z6hmA*ajaVK>Z`1?CdZl+#|EaiV@)+G0nSj1E*ORERU3~QyH%Ev&<`DFJ8yDw^n8!62v@`Q)- zx<^2*H0|FyJ|fpBdYndxqzlp*o)w)YI5o);^pgnFBq0=WMlOp>naOFQSZN1mf0!}< z*%ebMf$$ih?vB30)rf*0OhcwRBhd%a6{re;bGMkok4A)zPVN-tlfykDFm=UtFQbK4 z)&aET?Jy-m1}a&e(v(s3d7y|8XOLJyaTY;qv2^1OQa8*+%S)MQ@5_moq?WVCwBk+sU*b<+J)ywa~2hlCuvhNO+s zG?ZRTN`Y7oHOrqKC=MZ&Iz;cssFZVGoCT)vyD zF$GQ3;iJ_hnPr^jVarg}SrxtCvsGE8Nr%vdQlaTq>E9J|epq4Fw9wYlCIM|}n>Na) zZ^>)y@mZ|1d-X{C#!?CC=oVC~Go{f}rE|{H>Az~!h-@r~ZB(@dfnBv^Yc zD<|Q3zzRww^CZZ2XxeJYhqBN#>LDAd zPdK))Z1z`uYso3cz;?&q?!Zz@@ql&}&)#0l;8~A~7le50-tCL=>WOjV#MRT|y_9{j zIE(Hw$~&~aa1?KHmy~z<6c(& zfD`*;+1C9E@W9)eau|`tWqAVmZE0e*|UQ zEA^1r#3AiKBs{uiKJNBPM`nSRti0KJ!p;7v3HRxGF7XzML=uiN%Lk9-Zit49;J8(< zmjINs0|Fy{^R+%4*}5bn{+ZTy9GJN6@a#Vv*zNGp7Yw=*%Z9eA77n$3Tt`<^8T=Eb z?m4{)%zosHVF(rvM;>!C1<3GePjYW21eDT;FumdKxAuLn5O$Io93%T^>xf$tRl@m+ zFBZo=j%-+G694%oAho%7{|Nu6PEI}>uc8?;f5eybE0s^oK0yvIwI4*xWU%87i2O}? zpUE@)dp3_`Iv1G@-;%$mL1xgCN2`pAQCf5S@xZ*S6)kJ21G z{QtV7Dzqx^&81NFq-ybivCfX|%o)9N(H|9qe+Oh`HfIUjM7^@HBeH^hSY|WD{gQnC zSQ;MQQ_0O)na;uIqNc55)p$Ux5q?iw;|^>d4c^Gnnag|6^fZi_8dobJTmJb!ervc ztV^>B6p~$|;{k=zRVGUni%#Tv+@#uRRo_>titw!JI6@`)Z4pJ9Q0o|^X>OJMx zw#pTV8|nOPcZB~=(w4mF+U1tVX0P2S*08Ppp8Nc{Uyh-zo$=dD3P)IF_$?})G=70- zWL}*@TBiTsO5VRsgL2JoIVhVuG$K6^=c{m9g}gXh6{olLpYkehShxDHy(BqG|2StY zN5gG`7QNousb#^ZB@ytQhFy$ z*Ph)I^Qz4>?10-FYgL3z+p^76nQIXYP7(KewN?6x%I*zu<7tu)3%BeCa!^|*hsvwj zr!}N!p>N;zsvY#c3PSNM6d-s2+4s~*%dw_^+v*Z}gmVW^%zD=%dT+JA!UnfM9bYb5 z1HKU$&fFyPvpQqDnpC!T2}>r)>`h>laTh&FZ6CES&|hjdT7I)%?`d&OuvNoS1L7r< zG#kK!)WLkFZ#OcSKjOhwb(H^+LY1$+ zVUT>4Owwnx>}mP@+YX}26hdt$vi%Wf$3(8z*n8Hk*O@3!ET)3(JH#SW4$mYo|x7ZlV#zEWNPSzm`nAS1iz z=T<^`o~9_GN-mt2911>^FKs5MPuCVGHGbaMs;DdCegkv?0}ixiUv#INnP43sqCz(4 z3Rk{9Z7jIhP&y#l<-Q4^8Hyyk`-84tuV2!?EfeJbLbZ4pVK66V)V&o>=X70>K{93Og#tB*~cA82AYd} zqD&M1N9A@z{K&5f``;8qtjsf4#bqj&WwOdJSFuj7x3|4IZ+rCKK9dUjyLIR_0u>(` zTLOU3(@#DxQ31-aQ5!7&4C1|h(d39hL?&}uV8h(wOK_Mj7h3l0#8J4dhU$KF#rVn;Jr_ezM@a&qitbr zEU`{W%G*P0dN3D7n+P>>7F3iUi!f8#)tj4a(LUWf#_DDlYsTtufPj%1#3`7dHkc*H z!8^+&IQQySvZtQli2+7UwRhxq^LG`K=-X|x5&)Sv9XQ2k{mD;jZ zF#2$r5gU_n-gQdJaS&k%YGwR1gA^y)h@2k1N&QLb?#ma2@jpz<-uZtod~7dNai>mG zLDc`v!l`?@lCZz^U2au#Due`O&>iG{B9At0RU;S-@Mbg^&^{nu*1geoOT1T+*>k+( z7584i@3pKZc}!H^djt1)9rEQdbJ6|Q_w?;M^$7(=?F*mgnJ!Ld?U+X!8>pp6s4Pfj z_G>Lt*cYcCP_ZC$4e#~Q8nX-b=@nO926|7jaSuKmHl!co4zerm$T3w-=@+UQ^?jfI zlAV6wr@NTwSmS~i$MAzVcKVO%GzLX zm5n8G>Z0$jJChDJ9+Cwr7dFinD*s@q`XIeoOQa6QzYF7gJfFpN^~5yIIP@%SOr`VD za$PfL@WITUV!K{{^Q*t3FTRHc{g^b&KR?)bW^8@JK0!b*Nw*`y&UQZzGg9rEAs zpGxm2G0$R(+pzzJ{}dAVd20=s4oUwF|LNls@rk?U`G4R)I%4klI}*bsOr5X+qGY^J zqO({j%g5LO!PnQXh#c$DUV#ms4C}#ss(H^gT=i5|rILM?c)7$k2Q{usri2HhINgd! ztExue%^HT_6-{(vm=W!V=I z%M)pvfyvBvhvzGvO7AUJXrn`$tCdU#Zr#u=*pL-9?zrD{2E4b!xSJeOI^{lJQw6w?%sz2R~ zACqks{++(-eSBFGy_kBo83aQc`I|)2Hd>J1+0>-?AMqdK_{oe)zvp6JFAZ&H-bm^AKMiWBD`0q@wf@Tmq=L{d%ry#*M_Eb{sIFK@JaMG`R;5NbrUMAf=um$6g-?hk#jW# za*HSEQ?=E@nh;X73#s88-j#&qH&#!o8g(-wld;}1v)X-cb}>^=e8n;3oj?JIHfpl(4MpdXt=bLNds0>)d#OKQsg19>P#*x1$ZOq6 zjK|T;Vfx_=kt9jf5Iu@7MFVDmrQ!FB94VBMU__{SoL@#UnQy@0BL*2Vqdt9_&3J-3UaQtv^DA6Evw_qZ7RC;!q7p zGDm1hL_n}6EO{t~c|FaMOobT`5A{jBONnFssyL{U)Tg-H6(N$(edilihn9d!cIUp) zZQxRu;2`F7t~)=VI3oq97ExOO+~hSvF-Dr>-y~uJM@8&?(cBhP@D8W!OUYUKneSlc1NP7_5in2T& z#NR1PoZ({x3R=i8b{NW5$sklaSyw|k^0!;U%mQG7SM8}q*8a*6d%&UqjD&3aNt7)> z2jZ<-Rv7}5qs+bQ6y6n60bu>7C~M|Hidq%25Xgq;Hqx-UljEMx&%C7%x-C8Bp9wKl zmfWT20rZu7S&472(Fxug1@B7vS_X?KsvYY!2bbm&&IH(s0{WH8itl}~SY^`~daXn} zUiNsiz075e8j^Mm$#$aSqr4CjoQ<~k6J-w({lyupXjYs;jq71kVE`$)7S(uZ6rgb4 z(6qRFeq|57Eda-l=LWB2b?kGqt$9aTjmoCXvj52W=4?0OQc*m@n@0wQCV5WvntV^V+SsQ|+hiGZhT&*OQNiA*kwrezXY! z*MxWl-G-gs!j7wl2Y^_+rErq>&e{Ip2DLhhp=$Czq?plOM5h!Wc;Bx&*ZR!efun{3iIQZ%co>8P2WkobaTmu?fqN|%!K;UyrFBy|4kO7C z$(PiwBL$?!sn}+jy9P;n^n$xE@UOMHDaG9EB@f;?AjZ(hl4Z(aLF$0ZJiQ|7=~=eV zM_g)O%)-`N)V>u(g18)v|=hlD^hHW{{^3bGi|yIIg?yq zdQDDxF$3IEn*X$j5MVD)PO*k^?5mg>&boS|MpoayJeUgqeHk zxx(N&;RiH%IN_W!rCc~ZFPUHX#vS3Ddg?sdlzUQ7OK%{blLHbsAp-&;1xTh5yluKc zebAQ+UdgRL$?m&~9Ei)0taoAkF7`7duW3rPyLhs?0b zB1!`=6`EodOZubLJc_Oee6tA54ZU3pzO>-it;)mz*V>woa^@88YpH(L{(s>= zi)IZm4Jz*&)NJdsB_Bg}K%j38Iv$OB33cd%M#J}wM(<6@(Buj_L@Hl2vPT~=ybP6N zh0d8EzM?$y-$*1|+SMvUM$=j8nHmgzHZp;@6jw~PCk#d4?`nr zUw{vn$4B~zp~^^T zM?iC_VcT;RL0TljS`k_99h#4&f)tZ$%v|Qo1<%!TVQdp`lUCs+kpTn*RuY-sCHxu5 zD?gn5BB6b_s+}YaLIe;WDG-O~;Cgh_U4qjjmK>5wc8JRY7dJwx-V$qdq)!luj;G;#bA*RDJ=tsxA3UYC=10Zy?QUJ9#Q<9FMztJ~{ zUC`r2@E4^{8nJFVRa!1If_MX&Z$br0C9gMp3tnlVFeR^{ct`5_c+9etTot*t+)00l z|4{a_6q9c)Lsh*=lhGkzi{u)T&{YCL&5tzZFF3Teg)|jP@Fo>AF-{BW60Ytt6+omA zz!m^371?W@*neZxIi-l|(3`ps@R*#Vvi=DpcJbT3t-2kQSJOpJL^Z7}_AS2X0jEL} z-%!6tLT^?N22~GcqNsx@hwx%Us1?}FWw+l&>vJz^MCU{7Z(@A^Rx5wbK==4@$dfG+1cN}e=kqTm+H^O@$tps;rZbq z@%Yyz|8snNe0ucHb$Iz?f1kLwcfPlGyt{j`_wC@|;9um=rT25Xy?ycfGl4+(^XJdM zjGyz3jf?M{KmSpFHot%W{_WehwY9bXGJd{&`SSVm=cT2kvzbrCh3v(}#f621`T6jKUeEj3bkC#Ny$jAuc?c2e@!Al~jr>Cc@tE;oK zv!kPFqWVooHx_AybsVq3J z=AEgGs;;g+E-pUJdwQ0hewOaKo0hhd_+%#`aUw14JR;&e@cwTc?(F{ki#x_Y-P~Tj ze0gaIy?F7WtgP(+(1V^neVUV#bLj)6rKKe&C&$OfU&=sHQBmRH;W!-b-*KRTfPnui z4&>_U>f++!MI=8ZbpBs}frDkqh(*JCAjx<^$mJ z8SXz`R=lYEQCZz|^9Pml5^?!Qb>n1wI3UHL{OtA4&VolV{prH3l2k@nx4I#Ls$cbz z94hIOl>kl{@H_+epjSOXl`){y%YPL?(W2Y=EIBFNEt?xkc$j=qifCi7KJG_;y_1VSkvxeik}cHYx%_$gI&spg3O^t_hr z%!_YS(M>~OKIJ|Le*xCeY3Kva9 zpr`T@>qkhVq_g;a%c!9&0=VVVpS6Qm{{Cv5z4!Nb%lFqRzXVc9^nP?fCC&(aO!v=r zh6HQQc1IQdob8S4Nu2LbTi*}a&FcDX|2#WX*hgI=(`*dwz0^Pg5Ng z${LAg+|55ZKmMM)yaAioL1+MHF&f9FuRO^4Y(+ih-)A-9*_^vvk%_2@aCuqso3*Yi zE!||VFUM;GYdszQ7Qw1!x@q!K-1t?C$uFm}8#=~Rf8!a4DShMoV0;V{%=&B>bz}e~ zFAMmk)g}KWN$o|hO+Qz0J9K}rPe55p^YG^gnJ>DZ-NK1kX`H?sKt~w+T(JOBa8$Zv z+#noQ^niw!g@msr@C^;-Skst&P)2WKvr2`VZN3r41M*4HM0ssO`KWQ>u4iCcz%^Qw z%r_!z4ggNkWoT)95@b74(lEG0Kw)@TNXJw%$TLcDfR9SX%LCO0u{m z8XZoe{kqJI+aF?l0W8NtCA~Knj#<+)sQcfjbZ5}4!6kT=c zG;nbl=9*yEwTHV;mnj9MHCS@g4qZ78&;#Tj`d-<-yPJ$qBzX;A9U1O3LvcwiV_f5i z$Vb$h*rUv21Cl7!$3qQ?%UTBn z`mau=-AfDWgOqA4HVj5in@b)gl4~I9&AtQs+6qRd*Zq~p0}e7Y$TL6CR|WJB`(Rne zhtQh3Qc3F1KPo@><^q-#kZ$7=+(L3Mt(sY1RvX0VJFxQxhjTL;)TYt?#%U@1!c)>) z@UZ{F>O8x&+AMNPIj1*QFv|F(!1f;cdPvtbV#<@Cie47hWdWQ0c!RoC-||DH&4(z% zif3&T^#|nck6!psd$un_iV8#p{csV+n-SEu&t!fz) zZ)jg&ul*tokilMi#~3cHvMRKY=np~5R^a1|NFZZePi7#6%wM&aSplb|UPg|y*5{>? zSca&(V3B&uy|l8ZepS$WWBOlCbYkNe0ofuFCrNPQPhNc^D(xGm`ZFr$pDl4=Q8%D& z2=%F(-)vO(6CW-)u`;pg_YzE#VyXIQJ`csn^CVjO{y6MKHPPPxU12uJx=bx}y)NE* zbd|Am4uH?EiPYSgVS@EB91J03Hk(1AErzHMLQ$A%5sgDoDkU+N3ghCQaxQRLOlEXV zxJY0Z5&Yiu_P{%~dGrqR6K17%a&-xV*EZ;T6}hF=J=DmgAR(G z*Mm;g@(Yb}hG9!UvTU-6g z2D#5T8Uogl_eb9Q9jcf0y)CjH9J-T)VPE>bJ<(X&bxwGp!r???eA>6772!6w#^v(7 zu1ewEy&th4_ESlyw4XQ9xXg*OTamQLt1HoOxs)vrsZX9Kh2Z22`U)j)!R}KtzdPa> zu?iSe(e?I&33r%Y3u{|tLg4zqF4J_6g+u&4po$(1{<+m1yaDwDY}?lueH+^=7z)J( zWiIxq6hdBfmZt%-PI%ol*NT#i)y_x!@uvgUJpaKzEjyL9<;T<~I#dmDh zmeCZ_Ny!_rbKJJkiI#FW%B;6$vFdH-$n7KDCq4`sAR?+Q@t?iO}|4Xy5mQ| zrwV~*gSRiBTw{WCY(w~S9nd2r;tv4ceiTBm7Na@FiBwz_zU*H2#h>AWcQB#mjJWhn zeA)nmT~}ypiXFLYI7NjQWplXprknV&&TmM>A$J4;6R`!wDQBMLNN_ zs&$PSjvpJeJa}*%VPX@Z|D8nWkh*<2BAO_4%^xNlloOK?8~#XR|~ZL*c^}9F21v&J2t0G{jCGFs{X?M05{QA%#gDZl9_DDgRz!ZR;CTPZPB6u1Qs>r8)UAd7TVF`+ zS9RLc-Z`f-DbZ15p^wnsl{Sef%#jqcxFegiYZ=KPl28&f ziP(JFm6J3{mUOYLSZJz?>`aORG0O>5=LC#9X^;UJ7vwB~9ApZgl4SYjD&(%uMo&&B z)B}DrPOANgl(i+JN-*uYb+SNfCR;=r0EE(`0vwgHoNr{g2xrk3xqpA*;<@1hBDo8o z?)tmj4R~=E=ptVvcq}6y(JI|LkBNQmnk4N2JobiKN_tV4WHJl0*$O${9L`M1&EyN@ z#0F+%1?IZG%mQ%tY@tBUjDLfbM{|}(lK`LaGQxRWQFAi;x?AS^rkuHzym|+opWjIn z2-J0iFz&0#=`6YLgd;nY63m;^q;KR8D5b+q?|HoR|1seEo00Bg3j9?UWqoRfIzx_u zk{c-w`smUpi6w0lMq!9ipuQsNqZBGDrrtu5e^N@V7xu0VjKGo8{fvR?6Q~JYz{&|1IRj_~pt#co@>))T)EUSE zHw6g>d3!lKH%cs|pAF1%T0Zihs_-cs_KDr_#|l1lzKcZR5C=shq(8EmTZ%ez3M5T| zknw^z0(Cu#%P2QZ&=sy!h78-hb6FiTQ|1-Qi&SNeC{&Cf%PWG%M~A;e{>+AwnMC1m zWzf?Q!4|4YEafHQlI@MGqNm?T^yiKc16H0ruWd zRRH{FnVNx!ePMSRkkm(qG(jHY5YHvaa=a1gSfnhD{3SWX-;}~_mgj*tD;es`CFaTx z@Cm;i3h2_x&IBsRXkL)vV1FbjHjY9aY2c*Ah!+r`+B*YIL)DwY{m8v?=zjsGKv};k z8>kvqs!AWMiXN_dS=f1<2tj~|3ILuL2)Sy4HXx}5Ar7yQP38a-s35Eta;(XkuAUT} z!;+!`@~r0(tqTIHd3UCPp&%fr2M#a-?+_0iu&u_3l>$KwO$q?2@T&;n40|)G?5eH~ zTOi9ydGi6U;~}q(_NYv0uYYG**2)6_APDb33($wLSD6rHun(Rf1CdY<1PTD9P^IR3c|Qe$c7OpN z`wq5HSyQVq=nA-iE4ZUlE2LYxvjQu!V!EnpEA#YNNvpK4yLXc-d+=hn0znH0$hmy$ zxqb_}zN@UgD;Qu!Z;V^Ka$+ZVV!Vs{wyhbvvg^DX8@HB=xg8*aB)GQ$%bUNuy=EJ{ zS_npi{~EsHE4M#ty8r+P?Weoh+qYxOz3vOV?Tc;PGQN@vz0o_j^;-}ixCb5}5VMfG z>bsll`@RIMA>IqA^9!W-E3FGWuZ7ZvcMAX&@PjlcGmu{TfCJLvk0%hE!#l$C`@=rW#V4G?3jh!AfCNaqyD-ee zXxtTvw+@zYOf!+iA{@tZ9K^c_!2^K>j2MprES?!0i}9PrX$)=$@Cf;E1JaTX>Yxp! z|DaR{!7@AHGBDFZC&WUM+%}Y4$!v4Un0z*xyvbyw0DAjXG) z%+L(Y*(0!)_{Xm-!=d&7GC&5UkPe1S5Y@t=1mVaW0LiLs$su&kXp_q7j5X}s&Lou1 z@H{qV6Us|-1@9OE^E@^049~1Qz}Fnm2a$NrKurUo0sr6z>;%LPe8H5<&7cb9~oFUB(~c2X}C}1o5Eokd{zw#!4*M0ZrIvZP$jq#q%5kstqCQrw4NoOp5BS?rk59StXyF-mkdcNZs5PeA4`3sEGO} zwkopsUEF_-jBw50gN@v18p7|r+Z1lz@O=k)-~fLDwH3}G3$DQp?%)pV-_D)e?ET#Q zv7O!d9eG=Q77kR#&4myy;w4Jr0S@4MT-g87pb79DAX^I)uHfiR;~qWZ_czu$zTGe0 z;q_qvdC;AqI1sh)4pGbG@sZyrYUD)jn>L=~L7w1C{vS};2L%x2cuRd>?%_ke3CY{6T0VxuIll@j$Yu1+419< zE^#03$ENo?xs^Kpt?fPtW1 z?6kh-%Ko>^E{~T!=+2HFig*XXF6_1n zQdjGwz3%M(o9_OI=kD$JejYB(U-j+ctbXkP-S45B>^)5AB_8mpJ|DgP+n#>l@Gk25 ze%$=d@R0fMqX_X4pYQ~K2YR5^{59U%D)RZR5ael|=n1FR|Bw&gKnZs0@E)IsAm4Ml zF7GT49t7^Od3Ol?`maBa?$m6d7^e%-a z59aP+0NiQk2=M?0Sl&lZnQ6MFZJMA(kL%>V$1w(1~&O6?Xt zT*%=c2Z$9dUc{JD<3^4hJ$?ikQshXIB~6}0nNsCSmM0}rZ22+8KNc}LlVwn$9UbVo6C>lIce9GBB>EKO%zst?g@UM0+Co;-Dtha*@Xfyo8Xsko005f8 zha$w0TA1Tozkb|SEL4Mz-#=*}4uTa+79s==g=fN)npp8-#*H06h8(%%%g8fpO70jH zvqsIEGj{fD5wv3}cf16^IDpr?ETK8)biHt<|Bb>NAV3uNYGEdG6%#IOs4)e)9tYPx zo3g&6xlIfDeu>`!JN%s)%EsN1tB(diIeiL$=)h;Ar&p z>%*3BU$F-}cSvM>;vIM{kPiU;;QJ>9jEIS5Ayu}5=#*?0B8C}_==g^p4gc|np928c zKpJP#I>-`q2sr40dL98_lxk%A=M03{V#uMvYCEhz9e3ohM<3C9@3Hvu!>_#qT|3gV zB#YYO4lXo`WB?GWPLAhDhp(p_*ZG z0DyyOpvmANP0ZmA00ig>GZktULg61Y{{WDXLJKhp@<&G>g)~x0L29(IA*-a4y(Kr> zRI*NOBH@lZJjiGPVBR?-)Ac@049kq*$OfNnE?FoTXck)IntZ;Y1f=8a%;tp?hW)Sx zd|I&qhhf@50RT4q0c8dYrF5pJG8om>X_ZQmHZoUub&P)CI|9JY9m_SL4@q09A8OloA=JU za?3COiSnqqCUS7NJ^#Gx$4c{J0F6d?=baHC|B3aKB(GU>%x9;)_K#$bsc)A-7hFfz zZz`N6{`}hrk#}k_F!;!RKM8i3ako8s>7$39CEbVa+;`<6V_u^spWNt{cLYhEcTTsL z%K40|pT2$f?`B`6>%T@n z0|2yQ9Bd%NG$51_9EJ{rXN=%t5@0l>Z3GMN_(cJds6*~C(Rw1p85F0uM?M0{fhJjp zB|e~!KOCe6F%k~ve1^s}GO{Q)9Kq6zP)lh})0@fc<~PM@OBUd9YJUu6I@PJ31nPhu{AkAu zBax4XRO1vD84r0ZAqRf;)1UtYXg~!zP=XfJpa(^0LKV7DhBnlp4~1w%CHl`U+@TM1 zIA|l@p^J%j)T1Abs3pufIdrbmq$ib30v{j)GL#}6H<)KV?^%&oav+wo9A{2<8BU${ zl$Jd8X-|O~)Nu}#sQn`WF>NtETN;(9-gN3yiCNAp<*}qF#cEci;z?(?0+p%+04oy- zL614oZ*+VNCN-#qjsQ@A57FdF;wqDo#_pl+OV~~Xe01XgHMnyJqk!HnS zQG|#xjwGTf{}7pLNg~@3PFBp5dc|yJ<5!9_us{c;@JAcEC=M`6V~iLnV`wHjlGU=- zjzYm;0`PFOjui2TkbQ0Ia{IcvHqbno1#WO}cUO+QA{_ZhhciSAfEcc$9>_Ss4GUY= z!&aBNKY^qqJMzXj;ufv=Lr-PHby?w-cb()FNosqC*u)xkC)G?`M=Dv7)`q0Mgstj1 ze`{X;_7}aIobFi*$le?lMGH0k9YWhzPkn9cZ(ukaQ(Nx7mlKZ=}J}s6S%-0 zJ_%AiVmw=j2Esf!u}LWWEe&JX#R_aOWdpps0b94jHqoHGIud|fydw}MmT(V){F4=X zE5MZs|9C_YY)kNiF}=i5H*wAgtTUul4dYZ3nbIHbv!9`y5)E$Q zBLNT}`3`;N3-Wp-jFyz7S3T?}wt918b~2x5Eo+s8$_}LR2oeG~z+IR6alTIPsf)c| zVt3np!nTNd&u4AeVmp)OmTPX;NZXG@DHfkWw@DNoZf$qc*xtr>-oRZEaqBPMlKnTp z|H-Y}foFG;9jO33-q8ej4}2%{=6Ag_5~@8w+apa75VbJ^@r`i(Aw++a(vd!P&nTVgb%Z)pgznn3pS#or@WKW` zB8!!EeeL$WJAUa#akBT_$b7#e&0)Rln-{)pXLA5Z7TjRFw;d&3hf#h>%5A?_e%qCK zwHZ}j^Eht=z9jz$i8%uKt>=BxlD8}6Ex&pe13q$@H?!l@E&JI^9VDgU!p@1f{~ADy z-t-b!ADsnA_fV)ez5@G(_Y}=9e#z2e|+vIefuamds=^= znemg~`Xqtc0OGD=kSs0{=C?h9Q19FB*FV_bZ=UkU9e>Re{v&3~gTw;~7)YHFfWOXL z46w@@{IkCX6eR{MiSPq21l&0O(}>R#i4Fq3@@qWoo4fwFil7AYz=s_XI|o$3 zkVrnk>p$l+JkBEtoePNyI29y1K<1O14+MZv(1u|-0TCdLJCAX|BrjZihw)0 z1Bn6XFff* zUeG#5^fE`x!WXo|=JSZ*0loHnhxbb~4*WUnBM+>&2oPuoOW3+^7zIPb8Cvj#-owQ& z)5TuoMVyPlj0gZ43<&^=2Lmj|O%#dXn~mB4#fzwhQpgBnFa~M78A9*{54y%A%SLWY zHhq-Ak8rjrY`1ri1-vsyg7iR+(13N&1dKQUZb$`rw3!j`1z#Y?|9gC~eC)<;%*faa z2{mK4kjSQmGe|XLG9E+)HDCcWaE5d!0RR{VcLV@XXag4@17o;{8-Pfgkp*8M1dBv6 zjNHed6iQ#*2!k6564Sj7B+0GeL1Qq7d?*KFcmd-GhJ#QAama^rScWk`K_t|XEbxU| z=o6p3Fre&5ZPduK+z1cY1L6^h1u!CO1c~5Fxhu)O);q+Cv4CChg&!bG3^Plj97@4d zOK*f1TN{bB;RWg&$w(xZyZpPnte8gd1x5JFvh>Pqb3u+=$_aE#05F?p8;JoBA4K59 z&g2`&}@iIY!oDFk15HweWn{gg!V+|P{!#*&B< zdpyn0UBvbven^^D#Lnu^3Ek0(T1RM~9We^7qFb-D$!n~Bg3KG-0WKlV_2=o+* z4p2B84AV~4#7~_(yTO9jM3GW8DLpEIe@Fx4pb;?(Qt<=UU_~qdHHl2!R8EanrW8)Q zX#idDg(N`MWMx1Z_y;;si*!&2Z7792p{d%qDX9`FV3JpzimG~DrhCO#W}??zqC^as zraNVgqUzUug{p!z*r{UDmTS`jp-jshS9O9S{{mQs1~~{!a04BPgmORzd;*w#0;!M{ z*^wpLk~P_rEhtB5OFxJxy6XjuLfM#=*^?Ei5G6h{1(zo91zljwhy^7mYK3r^KUA8^ z8-XQRO4x%%rlfr)ePvo+a@wcOC7^l$c;SKvn5GUm6+pcQ@iC)+k8O`ED5cB2f6IqX{|nCO+CEXf%?3~!>Jyp_@BwM=?0BYo1)6KBr1DJp4l@y2u zb-;&jKm}QyTPqD-X{|A;>r%y2xCd1`+&xCX9bUVk$ALuNDXLN-y zjk-xSwZO&8ypc$XJm1r8SZJl+YXjf#JuK1@w2}x(U;SR&O-=ia%*xrxp4{IPO5Zj7 zUjQy3T^)%p%~k?cU=ST&yFpW07|RG=pb5s_3NE(*E6MK5)5z!mz9du< zF5&)_)b$mzN=>8e%21Ms5;X<6{|??923CnO00(SPh#Wu$ICudz@P>{B01Z$FSfBwM zK!$Vh30B~SIA8%XSS~Y31sl+WHKAfI){%$RVg@o{_Kj2PjUcvk%aQ<~LhCpb<}Ecw z2@UXuHaHH5aD;q7001BZ5z>KwkO2U&fqiJy2+@XxFos3Bh$@bZV#S5uePrp0R~hc*_W9*6X68+4@ua0|FN z2)UpOyEuqez=vr_gIsxr|Gx-}?+}cKsHq&WoWhOgZ)4=zt>+mA<5h8lkvoY35FcW+ z=en&?PmVz1a8~3{4(4zU=#Y-GaD{(}Zq3LsitbFz5u1J>a5o4t={UZUTUre>#*)>qbX98SQ}s{-TC!m4^9jW z(U869kPiuw5m^WmIaU>65mDHOg_wYU5G{1Bk#{wWjxG=aFir$EYT7|+#kguPfP%+{ z?8uhv$)@bew(QHUY%q`m$Hwf=_UzC0Y|Z9u&?fED_G~M-1JN{z3NRu%OzBBpQkEtO zH-Qs5p%Xj76FuRR|AY9GFlmE-C|WVVX+)WjgQ$>2W@n2@M8i$&+F9(xxau!Rg6XF2 z>bCCd#_sIa?(NQQCXfRr;O_7i@9`dQ?*?!3M(^|%?C zgscdESzdu57=u9=06+m`n1^$K1#>=#T#@35k?;aBUI8Cuw2w+rUnab}R92Uuv<&A?^Mphp>{^2&K`snGH= z7xWMx^FcTC4lndWH*_ax@6E39k+_0)h=(jDxHzw0si1>o&AHK0EcIs_mWmSCglyP{W%z?rc8om7j0YZd z%lY%CK=oH2bXR9~GI#c8ckwgd11T8sH6Mvj`-QZo?~Qbf9tR0czz2Uwhf#3X#UOUc zKvS_ic6}>#1jTa5SaxX-^Ju5{Ew}f34{;|z94**^YkzdbI~6It^?rscF$H&yFab{3 zhI$|d|2B{WZ8&grfA{s+OJCT5cE_7!FN%5BcYG)DkB9b<7x@-%l0F!Mf1h=ch!R`i z@yWx1D@c5EX@q9OWLMQp85Ai8Lb1A@Z zfES5Kj|U{B)Q^t9Isb@uaD_6chzS6Np0D`zaLru~daN1xpD22!S9%s_`xZxfrYC}a z&v2;+2@2@3H%km$KX@8GAfO(>if{yOz=v#jp^P|pJRf`YaA#kD=d<6=aogOrc@mH!CG;sxKl`n67DjPOAq6heqV1AgEH8yE$BK-Y`t2O~TP z{}Jei2b6q_(P+s3;K!tVdAEGc-~7xseh}yUl6U$$m;w#Adynt|21D$E*YUrNjlb_g zj4*~}ScqweRE+Qk+&A)j;Csh=m8nl>f7hVkY@4*xjd?CJ9-P=N$+`N9(PDAJ@#mojbY^eI%FI(bHYsF6k0 zq!;8c+2Qpo*sx;9k}YeNtPnXu&a!Rm)@|CgZ|BktyX6iZB4N{lX>d`{J9s0q{~Dx7 z_^9E-7d8HC{4Z3&H;#I^ktS|KL4A-0WoNP*0N{Q zu5J7F#nrU0;*PkrYu(_&_o^Lke0bdB%EeB(b7zWJzJ4XbfcH+2?8LntYTph(BS()3 zLA0}!d9%RI4xfeCuG_o!9lmy1fN%dk{`~mg%jT_r;BU(b$X0R#8i-bL2O38N9(Qap zmUI#gV9PtS1dts={|(gLb{eH1Q8lF$gpx`uX($kXC$c6$Exu%-B8)N0I3q;wrGWrJ z2&7S!e;Nj;Adov07^H$j5;@mhc|j;gUlJkm4lsjZSdoSt_U2(k8myy9|3StqGmtc` z9F&R%0HksznrG6MB8^oM;!7-T$~h;U_Py7S2?UAI50C#~b>fdl4rrvH%Mn_rSZ6!n)>8 zbyhWkFTF@ePGwfI1Kj^Yre5Hl(l{9-Nv(p8`THx4HN=ZvdznH|4)JVG7HKryR7eO zu)yMvF*3vAN+%*945+dZ2M4Xs1VS9NqR>^#q{Rp|5zjmLYMkMT9ryRohgmU`2|<{A zIoruETQov1zU=BX*=5UHt3aTXnOcwkDI7FhL&Mz`(9RN(2eoEdi%0nRemR|&jFSQ6DJo3r6_FglX0006y^>j(w%jypySj{ASME2g_s&#*#J|0~f1ulz$6?BWXy`1}8V zQ{JNv901@F*dTx-wz0Eh0f&3!^PU5>2RA3^;SO4$Tlox9op&IjH}0Dh`#MB5!l27u3{ZRrc-8Y$!g>}#2@dgS5RBFjx^Rcp zVX#pJS->qSGyo5VFh3t84E&rj24ZZ(8nBo_ZMp_PEcgN!$Fm_C(}}?=e|9HncjIy08PU$|4WXb{l@QF{* z;Q(QDp&Da2LrW6VhWt6f7ziMcGSq;Mp|c|?g@igiqVhmVyn`257s#XmUCEdvla$po-9HBeK05%Cl^F!U z0BG@!TP#4Fi@Z-cp>j*5EQ1*$69F@}W-?%=u>eGY0zN~kys03ACj&bvGWLld?A5Hzf#sFh5DFLcpRrP7sb`UGVV zM;T45MvSk)vBDkf5QVx}%bS0z)I+_MSa6LnE5p#n83Z7JGh}03@hs+0ic;6jy6mn9 z=|nZ=k&a~0U?37`g*xbgj67uoh&F-6Pyz>HScW*(){1ekfeh1-hE-h4 zz-WTSuM2bUTZZ6;J9MF|gmv9ba|+Sn&XT`VJ7-pA00%h8z&4)spM2;u-39w2Y{;{JE=;IFpslh)`|C12wt+b!ir0o#l>lQ8CK@Wq~ZC|bsR-XEI zeZgg9aqY@cHL}P>4E}MQ-t&r45JVJFjff2Xu_`wF!&L$iM@k9;fsSy%2LG6W0&UUtQoacP!J*!y?d%!K9 z(Hv(pz~GyU5Hq3^t>`dkKn@vLG^8WF=te(U(w3Gq3v%3)G;vx@m%V2p-~{ARx9L6Y z0OLSr(2j@@U>WuUKqT@(kZPR5Afa$fV=N(uUGuuvzWz0^gDvb~6T8^PJ~pzGt?Xqp zyV=h6^&A@1g*iN14u8CNGrlowOG%()>5Xjm9c#3fe)O_Ob9f>6RzewE4<+fXSl=be3v{pq2Xbe zgF=A;1A=oL(vsW_09PtnVu)-Xu76^wu3;-I0Sm=3WZz)k6K^2$fZh12fAeh#{sNZVb?C zq<852Ec$GZp8YxS%fH9<$1zJ)p_(CCY zAP_=@2QCE&+6Pso|JeTlR1(g`Ko!(*1On46LMyo-;n|W5E=3NY12g1J#*z|%&_ zQ!!;h@o-%bo*`1OiDWsTdWjMV24JDUp;y?}9nh3oCbETm(U*M*M-$}2LM4GT zC14*`q3&HFb>$y136mqnqEEcXCe*_z#6cXOLOn#8L}B9fX`%@tVK4>>Y-x!sbcQ1Vp4oVD7>A4xuPYJ5iTf`EOw(syazZ~;y_FSI7pQdilF}uW9zBo zT=*Go6<}aw|3Th4qv84CDgvTYY(h2oLp5vy^&O&8Er28?fj1Upjkpj#6j-X^gE_*- z5$;_lUR6Yr#k6$64;V)xz>*-eR|}?Ml{6q0NuyHGfGBvwJ~V?kh9O=HBV10C4pcHkuU$l;Ojoze{lAVA72TqH*hW$u0CQ5KF!Dn%Krf;rTK zF(_X#d6X}J6je?oe~a>ZFSK-GdAV9=<~@XwzDfUp+#jcO<1x zkfceX|K!>@B{4-;U%KQFDn$`GBswN0FfPY6DT#1Af#2N15-bT@GT>Vx(jO9rKTyLa zu+}vq;yoQfT>VyP8svLW8I^6o19)X`fF%GC>wgGBVl7Pf#!L3<9kQ~IgG-9jlwu!f+w(pOq!K1@?UCp=x}@@R|!WD z#Ev@v0{IB2QF7;H#^tYw=l`&qf;FftzQ;4D9lJaO07wEi_|%3TribF4Ulrqv)x{4O z|6n|9ps0rD508WnC7IR zBFP=(flt0gn!-{dY*VB@V|PYGC;Y=I7z8EY8bdlnBu-)_0wia#oLFfp5b_5Ln8Lr5 zLaHW(e10W;va0G?Raw$S5U6QT+NxzzVXi(z8Gr*e^lCv+LOXok3Gn7Y)Z#7X|Kcv< zWk{(E*eUC>DrjNe-L*pJdv)Rf2FDP@PNN!>n@(Mm*3vybga&v+8$g4(*4wH@L^u)z zIm#0Iz3t}>|= zh6e|Hgh2>{Dgc1P`YJz&134%I0VPC262uGyt4c~&aF`0T?D#2HA!7^uNAv;%_1Sv>_DUd zI`lxg#BE`G1Cb%bRc7TUY-LyW?LA>2{{XK2y@x$uh5NaH(qe7mYVG23B7P1*AJCVg zw#5%10@LIIfWp|L4(P33iVV`hKkx(e{)0d8gD)Y3G2CTB0H$CPrp1O-4;q4gbigbO z#t6)UyTLB6fTQQQpCk<5$Y$-KZtb%C(_I+jTr7dW(n4%9%;gs7@*QH3;tp_nZi+ib#S1%yf{98jo*VkrL6X;NK58BNiBAaP^(LM}9MA)k#Y z=WFi9@9x5lDM@Er7{MYy3Opb}3qMT%g3!T|6G&d-3?oI25`-h*sE(F0g9)TBECGJZ zLOe8v-&}Ak&j=s?#I!DFwVv!POXM)pp&gz@7FcpET!Dd{|M7OlF!Lt!QD7<3ZfTe9 zF}{kFAHzon;6h`R@A+=?6X!D{|KcOt@>zUheVs)U!~)X*127+mJ1;5P#wlU!X`lXS zph7c)H9=g>m3>6QKj?!%XD~s(Z!PbY{31%}2q`2Z!Z%e2c1pA+zjGRQa#eKdr-tgN zmMR0|^DK+h0F)uw1rikX@PAW+CV@B-NuNljCQU`TGbLc^8fDHakUv@C-UGq)VGF&DEr5e7JT4nA~)1V}xzH84X(OaL_qLm8X_GH8R=Ap@TR z0H}+4dXV}+pg9MqIjJckBlZT}{R8L1|9S({xwP8(e44C||7aIeOBVE2U1KsX8@a*$ zFLe_}6yt+q_=EIPF92+SG&sZC3WOz~12;ZEJv;&cv;*|=Lm=}*B>(`K1Av+Tu)AB* zKHCN={KM_CJIsCjQP8?=*gEg-cqC(iH9MUwR5m9D`=R@Lk}HM?$N?mjK>;5y0C2!G zK!fHCgeI8786f~YL;?WV00Dc#Jmf%ooVY-Q$$g`GNTD(=sPb)?!#@y%$;Ud%2ZhSl z2FvfeaX;tw0M;HbLUYr?@hYLsvqo7FM%{nlq%OtJ3Vk-bfV%op4d6p7*Z>X;LpvBE z#KO0!po)EaJl5lrG=BkZNI+wN|8Cf~`{NTt8Z3j?uPy)t1Fn72h{1cw;(0oHg*ztr zEmZEw&V6d!eO17Iohx}#{OlSqpKG;2G_=DyJj1IG1gK}YyTD6MjJ+C_HEl52KbYa= z@5jf#0Vz1I=LZ8bsH@0~zHrxiju-b+4?!LzxK$H*&A;%G54)t&evlb|8Ud#+kbhKg z!apQK^JD%|{KNFizeJQhZJa$hm+%!>GC;svWMoG{g9i~NRJf2~!yQ88fN21LVnvG= zF=o`bk)uWhaujqFIg;eak0DE@RGBfwzZ5HB#*|5t!#@r)apu&ylcWG#zOwL~iSOSE zp+}J>Rl1aE(~LE5=KM#e|6;Iq>AJNNkr4t1uQvY8P%xHkS+i%+rd7K(?FTtbgv6CQ zmu_9Vck$-E8%9nTy?+4*4jkrBBX{rK(E=lwapSyv&0JtRnQ~>y8RTTJyqU9Q%$hrg z?##laQ`0b^o>skjWg%a)SZ5^g?_X@&w{hoQomwhYijU&xptG&o0gRz&C$}Vrd2{E_ zp+}cKoqBca*Rf~UzMXq_=!bqG{#D0&dGqJdr&qt8ef#K^O6$JOTYi0~BYOFQp&Qme zZ1w>RP{0A{n`x?yT=<6#jJoLxva-)`5 zIFh0Z-g3ywE3v#1A|bNu(n~9cSOlJT;;H2hJEHhf%{32#NFpf#I0;TUZ*0j%IC)AE z&piQX!k1kvz-HMhJ}Q!4?<1+iNM+2f8X zHZ9d5Hz$&k&LdY9&`v~gQWRDq1*pXrKyZuZA8=;v)mPkP9Z7>R2Hj+g6*NHQ3>Mh1 z#v2GC{U=H(DK*vFg)+U?)FosA5fLKrxTA|7v@Q3ch*D)0q&e5EGrnI_3Kre~0r904 z0c?YSHb~~}|JPrn5MB_Q<%u1(xFZiI zD!vv~c2QEdWLMw)m!p7H#?69Vd}+eAOK3B$<(qM)$tK+%KC;@7O{EyOLyIOTL<@J&Lz0}gR8bf77i5FadYxtmwAhLQoYy3gang+r}SegceKj- zv~p{b%w zNksrY(`tjP<}Ss#lJ4n(mP)ZDKm(dknUGT^=CltwgQ!kRA!1Cx5JW?)z%(iFQIGh9 zqCQb+y#P**q1PmUHVd(oc6?KzEkzPSPvg+~K(vGsRnrlS_6}QIp&?Qbl@&~R|4)y8 zG+iOJ;z$!$(rXU1phu}e&0HGQnJ9H7GL;WaEof6OT>*~oSVRyS0xofR(w-gls54a= z$h1Opn*PKZRdGoGTcz|U0`R5{q?%XMz|=HW)eTmgDO7C*0vPYGsFgaFhk6FptoTH0 zG}Q`Ow#tW^Z{@3AGcwRX356N|SO;c7t1~U$#;>^nEc>*2r5_ma9mTZL()N%)Yzg+P zeO#+Z1t~yRjyAL%8NghH(gWJ~rnkk#2wYQATHKsgdZ~2?=rYDUhu}?b4RNmD9;+j1 z-e|i#bL&Mq@sCwx#1Y)UM>gJoC*m`YDZ^PW;|6O+>?0kni zItixJbpZ(0rLALaD_PvK@VgZ$130iT-ix4tADpnkDD;s72wrx+zx4$ncCrcD=$5{{ zweLvqYa9Kpj=u>ZEE4I5SUZBuz>O_scDWl_?dq7a4F-S)ywL_|NZ2CASVl#r(TWZ8 zw!|38f-iKj*_niZHm_)MiBBw&6vt-8o@?}Nn93EpIU@}C^H5>?Q~-NvmrM&!L3dSf@uSpr01f02bQnOU~c zmiD=*eOqfYn8Xy>Kn`%8gK7*z!$od40HmShKy#SB1(1a=kp4B5i1;5{>9~oBemP-7 ztWqz(t|sM2W=(UtOJ5!ujtRbCR{FRit{z4yD1wH4aH0mG|HyE;pH7iQARX!IF3GO{ z@rk%YoyokMI;5*EZRaKeF}1K;mYfZ3R87w&QI zfG+4xivf^C1N~s&!}qS&k2mV?Ya_O#wHkz2WbBDu;b-IBChQvej>~ zUUbKmNCaRF+B7WnpdJ3UTc5et57nkd2;H*1#PToYK4iNOP^kd~e%n+wXV1@J0kny9 zf{G*Xf1aP2&QghMBIwQ-C4HY;VR`=ifwd07b0?z3T*9CIug81Yic~W&vL^f;OZ9 z0c6nmXfSx9Z+ND!wuG=C?hT1l?n|^U2wx87imKZ7iRMV^3QLR-7%(UuK2fr=^cOVN2ix-Tk|G4gN{4lFV@cVjC5r1#|g0FJekiHIx?r=fMehj{9 z!w#(w4^=}Cn}QE@F9c6cem159o9F{M=MV#n2*VEY3~&uO@#(IB0TT%T9w2P~q31MF z^&(M%vQT}t5W)Tp5XR&d=15I$&r-OrV!SW>{}$018!4*`2|z62l^=&l#`LjkgZ zHq>AjH_^Ku&GiDW*hq*Nb?O+!@P1m(5W5f&S&;-?(F9>p6Ja1fkS-P;z#C{I62LJW z;p`VFC>Yg@(gI;jY~k>}L<;hz(==rnC8ineL;UK4BK-~tg|8avt83_P4*x+C{t+Mz zZXBhr9APib4pOH&NKJ^K55xr(-LVWMvLc^xB5P6_AJJcwP=_qwCy>q_{=pwZaso9{ zCp?iUK(YG{Ob`yE7BWpueju^>&23Z>wGt5;jW8fF5)xx^?=BAM@N6iFvMZh9D3>BB znUS^v;V@|7ozw)j+L0>XaTU){=F%|o|LSoUO+X&#ZWl66ETxJ91@eao@{$A#9c#fY z7xJg91tQI5CgsB-bwe^cF(>kNfHzypH>pl0NeK{jN+H#xj_hEglyfevG9DQ*D-CWd zb+RZ!%M@s19X@~}iVx`m!8;YojM88k%z;q^U=+;Z9-LtY9A+@ns4zk8X~^>y%=1e? zX;jL^F)y?^W%D_6gEC`kI^m@{|H+3Gq_AWLApM}Msr>Vr%;*hB0pW;?6WT!zdO#V# zL5zY;G=UK~g>eV4AUurGQjjTxm@R0Qlf^U?Iyn?KJhZPs^mph}uaJQ@i~$NOA_+Qk zMa9XQmP7!|ffFd=1MuMy9PKy7QwW{_V{$-pw3J1obV(9q3@RcTh^!(Sgag1rEM{a<&0<1Kk|CzNp{y-ND>k!Vv5AMegn)O<-HCwfHTe+24;X_ZUlTQ;$ z09@fd^OGao(D-;2mV7nsf^}Gn^&%cMQe$;eE!9-2`_E9dbDY1P)qfRX+I6iNaLXt84r>0`YVOwVRa%QQTtZT8~9 z5H2Mufe>cJb7o-^K7kKhLv&(u=>?KwK~e%6kxmIX0Du$NAvluZMvoTo zqzw@eqY+{jA>gtP|D4@dR1*)wE&K^336PLbr1##WC{>D~C|wZgf`EX4i1Z>VgpSmJ zARR&#klvMI=p6y+0)o5?cNe=~`8gQ8;+@mX#e8%1v0}i(qsYHDNv1bN>=?v8&iRy(K$T&x;6)%Vo zZSjuu)9r)bzYebP9=rZ2rEb~ewpR(?5DlWG5669Vi6Ccn;Pn3G0}1z%Qk~w~NYdP; z_4{2Xk~3kVM(d!1dyLOz4W|c~aQv+fUbc0(eH=4tP#O89Q?`nu+8 zx`e#Sc+7Mk>D;IR;5OJ}l)u^Ky~M=PU3vKTzxUT3&rioan3|ZujK%E>K;%B6h*s3IXQ;sEwJXt09H76alOmwa+hg1`RJM<>9@f)krIeJ4PwKHT7bjO|XH4T-yT0aLOqy zCnl?ey9I${XOjyL<8`Gmmrnv8Qb@%zXbUBUKA81oKD~!G`FLZ2!FcIJe;jvo6~q#1 zB$e%(;W6u`aOx4_2tC@P*Q&-;@>pAXCTPp1h54r4CNu|D(@qPnC34d^eiW=|3aFi} z(Kp%hV~l+L(d9{HB;&T0#qsRGN$9W{dhA7*v!B#V6FB;B*vlC=X_P~CF3EG^c-!Ud zS`C)riQuKo~6L0DCT;`@k>PC_lFvlQqnr*AFJS6)nB5<$hrMR*ES{j>&13 zpQ49{?&*-$4WS02!2(sP!mp`eZ_NuInx}ATQYVJc?&Lc^mwP{mD7wEB@kKCFwTMi- zhYlxHaC_I2YOFY!x@6k49Pd~3(L-BoyleFLUT=_ z7>5XOp0a>oUdu@Ip>#*qn=TTCM0WpSCI4~yje*j)$Pe{8AK0Tl@bW>A;^}83v5Z{S z(X^Vwx2}(+=T4f}&z=eNiP6;9u&voJ(Kd4l1X=HM^0J9^02~kui1HB{-U4D2P$8ZG z(K!MT%rc8g2hCj&{E;=y8HjScqC<3NmyWp>ANKmKDx(`MYHPMeOg@LzKd13ij_?zz zt3imvV2^ns)_EZGOWK>&u{SQp+)D&51r63vW_MfS63At}XN@B>;X&*4-K7IqIN6K! z!(G$}^bPkrP$q!u!-x>ohPMo=zc>d4;~^yRiVs@;8g_o0Yms4Y9lnD^hTtz;IDe2O z+}W?=rjDI9&pJ%vnQEs7T3D@rj2wuxi*d3(yT_`s4C1rC*3cezor_5y^y4gs>ncWh zt&CTr#dn57&LX!yp6hKqs%yP=;PqISLsV@&Z_;;Vx+)%j9XU~L^JM3Sw)^038#>&S zOH>ETU?7vdD~Kg&`Lp`tNplywJ1CZdbS{r2=CfS(rgj0*$L*IE^LDXQqC|2~@DR;9 zxFJY76GReIpq@QC*f}}=MWeQtrMq$!y0k$@d$ahqQz-ky@GkQRDcPjB3S=XQeJ-~_ z@CS^?1~y^MI0qv8IQ%VOo=XT-gV5qC;rV7rqVolpTSNuM|w89b~_yc5zhG}uK z?$2|#+0d#HEz^!ou+@6r;c*}-TL#2snG^IUY@=U%6* zH4~PTSVVigmG<+e?y7F| z>h$J&Ww$`eQ(JQCsaT;Y{Li;M+3g1#nal>tyhmjlwacX73zC?8@IC>u10dnKtf9$s z+RJ;Y9J^B$yHyXl8JJ~wti8K)ald(xc_ur(Y}q*SnzxuP2vVIi_0FHx<`Y zKIQOK(vG7^y|ATS*!-uKFYxe23r9qMT$-fwT+5rA4!X*Fi)7x<_Ft^lyCA8KBsnRGVPV{2w?WI#O-lY3zq}ZUKW05e{UHdt zG%}+uI$!(-)t$gg%lAvc9;Q+`zU!Jz-~5ilLcfP`CWGj2ARM7%lx-)}B$0gCO%KCg zZu+tX!pBK86!tjs()5kzt9xn19``QAO}MPHg?%U6Ob-)yTJR%*o(vg_I$Ocosm7jg zMFaOAy(u))TEIQlf22i#_?CJkN>LK#yd%?(fh6}ch&T(@K!!{Q<2}o zoYI*+Z34%BC}28=@{EvO4G2YlCU+pKGHIst74^P7ad1ym-RlXKHDL7Np2L7o3uCDA zFL{f)V%=!x?5aE>6F!Rg(P%Mw5uL*XxWk_+S1RU+KKWmEV`kTU=Owy(IkdYs$Fvqc z?A7X?haZ&4I5#QF6S>o<3_ln!@tkJ5w`(xcx;xKEx8G8$;qU-ka%Wr%Vt@2aTSmU- z>wKDp`NW%GT>^}Q<29M)T3hp8KKdP-IMb4lHH+w9pbmZV?(tT`{9L!oM{lnPbD4=t z{8@C<%RDIUn`NNSBW1JHlm3%N)LxIQog$<-ji!r_3-*UBkhyY$2x{R)uy<8Unhriy}!*>d7IZO2F4&l zXv@$Rz0Zzc1CRV&s`bL=ixJFIbEB?Pb6{`*u0P+2@iBg+xmo^k`fz zqTZ|X!m#qr^oM)Lj!BHU3%TUd64<@W)Q_Y^l|d~ptlgeMMJcbUB!l+vT!&V5%^6=@gbw$z0D&oX<`;W;|&ht%4ax#46-~Sq6iczP`^l} zx|s)#)!s~#*C-q(PSVFwlVwk(J}_cb!42e7RnO}`SY7*I);$m$Y2cj4xC-A| zo1QXC{0)!W2x2bajDrhwC0EvkvRskR;K+TdLa&$EAfjiw_@oU!pM*Rn+m6URU9L_l zFS8emo*jDXQ=7S4=5U*0ZuIFC^;6w6^B)7OC_ndy#n-qMlt(GG1=I?7q&Cf5qrauy zuql=84whfM4_zd;aq)G0Xpkc`zarFFtZrH1nQuP%;fK#BybZ6gcjX78?Z>{&0=nB0 z)BbZ)$2~-$LJ59&s2*ULPfNM%U~}O_6E(~A;6d6v-G=jMsF2}jC@GtSJb(7MR&4qD z_2Hy_gC+5f2gKW>YA>rd1zd!{SWFVRy@+So$F#%Di{x)A)3f>$3Wj38S|0e*%u}sx z5`_pHb28q~1=C^M88-#mL&#Lsx&+psik8!cUN0h)j>ZL9kKGcIk8L8tne18vWx~KQt z%CFLb$;=)8<&V5X>M*ZOiN*3Wjie}G&pIObZsD-2E&gaMQRD}2bWwjyX)Q_q(0Yq$ z9sQRry zh`#MiJ~esY{HQY9tBm-jv*rEstf@sG<6Fp^3^U){79K&XE`R7{D|iS!@1p&b)@l{{ z_iva7-6NN$v4sJ9=N$VIU0tnwze6vY#p+ptQ(w&|^;`BlAXj(nXI2~v$ES>Zm)h+< z4JNf(B8m~SGVP(Nac`Tball~>4fFIF=MyqBS9$z@;WMvyJ_a|f61RB{f2jeKrI$C! zn?G8&!K>Yf?a4lmW{17uwR@7qvT7UXHIP&8_0FVq(Gc+_``dHX_o|XZRBZJISDh5D zH^QI`H0z_WzZ|`}Uq_AKb6BqI^AZ?j{beera%ehqQlyvhYpJ36UOH-{82uJ~c*CEs zfA+cA=Wk-al_UW%orx!#6-OM3!(FS8aX9!11`hU< zeU=iyNaf9QfIjMZmAv-qR=&54JL%_ZB0BEeP95AQDS=!Yd}ok=i}&# zikGLf0(~`QO&GGL3I>sYmsf=-Z%|X`x&YQ77$ltDAmC0heRT-w4TEP|HqXJ+q0Q>S z&X0pHBZ6P#2CJPQq{R(b01(U_h{qsgFvy=(WDrjBnf)*aS?ZHD3Nrv2wxkmW<#LMj zW|#?(Y}c*F(RO)TQ4)pSmyJ5`h!7<7J zVXFqj(WLUU6k+<%=Beo8pf~ig(u^83E+>?(#WbYqn&cfX3!r`m8h%ddLIJV{L8(Xt z2eF+#`KEPbLu52KH@d|yh8aZK1!ZqS#f0I2ZBzDshL@L$f`O4Ga)Lqxu8!Q&h-Z)>>Jkw4RgO73#{9C0-+|DMKx1V&HCv9jt{kJhH@M#y zN0ju@eVC!j7?sRED z%U0jEf|4E=(J-IHplsxo*L)|Mk~GLLeUB4MBNLr-6W<)#RU#=*F_a_NWP({F>V%9N zg`Z;K^^plrPBHSRmOTLVgp%P(HePxqry zeCsQ7zd${zV7jE1-DaRu8ry?=)u+UG%umsXbb7;_h zNs!HZ?x%Q~#w7;nWs-MVMSp#ZUX_%H50q33<`EDyfQ%gVl|c35zVveUykFN0nYv88)IypRxGG&GMC$YEkXFs2g?mb=4Bl40uqWJO^pA zP3H3keC_9nGQG1hEBE^GttuMxI?Lwruz`rB({g!n5=(XN2X2CoFe%*f_34K7qv`dg zROJ)3^$)h{eKRW6KTyTrqVH~}!MTx;u9K=h@o zG>W=63sTj6EopqeU02pe3T|=|<*XD`snt&DPsXm#^68Vlb(dTz{ z$>(@>91t84-QrnXvEE#jOQF0Q%{4*xxo%T^0!I#32G&N&&V(Dz4j~S;kUlVORT!6@ zQBfN1Hj9&~Uy?;ywT(h6696 zVc=ZQ7C<41Chl{iv}^~hqhPZ8&|@?i_ja z-+;f{GPcZs4GppEh3cUC3H(n=On+Kgf5uRMItxt}Y#>);ApfF2{~3PZz0QE~YTt(# zgSqa3*qs4_PrcYp&$LA7vJtKWc^C}sb4a{|`n)g*wp6Vfu0f9kx~ zkGU`86*4>%`HGZ2fY)@w z4a&6|)s@l5W8l={U&uI#exS%93B=z=5tleP2PrU&!DGPg#IK=1V`_A>-*EZND5Yf` z`~nA{fK~DKMdS8i=8oW~8lm@7&jtiGMv1`*gV1)+1P*2+0h-`|*}H-JuyC6FiTiNi zfeW$G>$t9%NoYbJY7C1z!)3PidwQ>Z#04;iUm~0Z zm^t7h91~z0vJI3cLLU)dl}zM=U1;fkKu zvmv+WnK8t}S;Uj#F#QhDR{&n;j!d_vtPBQ@^lx>u&=q2bhG4*r)1l_!8C-KyYSyfC ztWRI7I+TUlU2$P{pJ>912yH-oGKwdcMiY0AQhNLbt&78Cm!N;#dLNO!d#w3xY^8T? zA!p;dzj;gqwbJrdY#ZHTRS?y*^JvuMSMb;<<@P?T<8|kWKBfFCBt|gpwhlF6>2#iK zc`JI^MB(S=?xI0Sjo4MM#IM)10f|aiKc(1~RYuzOUU89^{Z#JzX{NKHxVWMd@N<{s zJ74gMrc#i0Krm`C)4Xj}FMIWoXuyMjH=@s1mENpgV_PN7T$5~Di+%aQp7OIpT$IJH zGOtJL)=KMsZNYc%t=dtp9|^20FRrO7ZQOXYanQ4FTk$RMS8fnxst;u&hHcaTY9nbR z>dlo@z{p1H#)f6UhJM9tch(eDI^Hi!AAX3T>_-t(D3eu&A}Bv@j+bp-HGF=`w$-b+ zRX?{lP>vizk;!s^2RSH76Oc)xl*hWW$saeW7c;UJ3lg6th(C6!Ja+zaY+Xq$YQf+*y6ma<*W2~4Z~WgEm49D;`TKhBZy@3%NbDp;?Hb~B^Ps*zL_9w)uZ zKkmdZN*EAyr=RK=7Ueh|#`|`fNrH%M!`X5Bz9=#KnxvA%C&NiH?uip0J?->z*n+^U zr(ZViYmw%X3Kwfxw0REpAPdht9E~zfsz+iz)|VPrUT+WQ{pR*;HraA4-LRSNhgqZB z&jxSjch4wU&C+;i#$zl$R z^QWF0V}*L}A1$1D<9B8Wy8w#|=f3;P-SPZZY;w^iOTS*z{IPZ`ayuzbPM9y5Yw_xL zME^Q+HL|CTyuY6Ptj}!+eShM7jRpkPwq^9Z%I)L;-IZ8pb9f?NDME71u8M;uSfZEh ziKIwhvg@yZraO_;xtW0|aYwlG!6{!!)h&xXRX~NMS}jE1Frhm{pdXy$WiC-1;keHk zK~v*pQPs|Nhi6QU5OS&R4j%9;V)aR zldHm4RjG240}h#G5){m~@1sM8E@j@>U6y!H;&;*(k;JTqfG1Cm)^oQoRvH%DaB7w= z)4MEiabaQ>{Ie@hkx(~l!H_WNM{Ywj-b>cY@h>D9ci;vaNLt|DTtYs?9+zO;%N z&BT&4l`s8W{A}9>Zf{{}P0kS7DOFm2&-WS7nxaGm`l2`J-Z78=6mfF)TXe#NFd^?^V) zWrX7c-TZE4X;W`4vzt*2kT6N(NSA0`U^l|ks(y$@J_87eRDfuID#H~}sfvgVy&uDAr*x0%pu>Tnr`n zvYd7FhTggz(-3EA3@Ocq1r`YjFjch13LVw5Uja*>+CXR)9l1!bA&7Eh0mmY28nOg9 zVzlbG&HgYafv6lYq+DG=ND?&nKIa>kq)vu1Vw`xQ4F(s66DHZQzEU#9Af@;5LBD3v zw^V+k$;uux`+9J~@SL6Hqx%8U1uT?|sX;D%ARw5jTME_@d<9wxR`|LElWXcCmcAdP z7xRO*&=>ib<7c47Acv>jDCOxgDJfnyL|I=MK1ApxTfH6Pu5mB>BL`+b5$I+RcaPVU z4F`($dzCIYr7o|L!11V{nMh4SyhtQbmrV>(0ZoH<3|GFP93SYG?~26Ty%G}O z2K^lN1VQI%ye})^KEvLS*LMzz%MmioN^^Ayv7?1Z;6>%^deE6I< zC6fdYt2`YP`FI$UIIqr3&ZQl)R4Y>?tEGx>=LN7!%magiEZe3S`Nu`qmaT0b8=&LZ z1bERQV-b?DjwmPDHL4ZAP)eTMI5obz`ftm4jz!;SmX_5Oip2^tR{TZ;h}$yuJ^Th6 z$HJUhgs;iGURB<6(yrW?C=|aQsTU+n)LROtQin;fdljUvLp2$Rvfd-d;Kx`lur`>|oIH?t4R_*E$KM(e;n z;GLn_~yE=ozr=1HhBi?(+0K@o`*hl`Wupd78AEdvP)d#Q*iu-aS^faKJ74<$UlfED3-OPedM|{ZT}~^hU4C zImqz7V?wOue3U1}a7hnc3P}9 zu{3*I!+=6JH=`LCTI4ff#Wby!Z%CP!WRyEF{p-z~&VzLnJIM$j3&MErBXmdU{5m?- z*)teIWaZl9WH&e%drCd@^AvZV z(sxlgy9KdyJLXMu26R$@5SD-uqWErvHg1Q-Xy?YUIn5IAB)p^r0|n@ z@5C7V$jzHObA^n`aG+}ioYFq@9Z*jnz8&Y8z;D4BJhvkru4oy6P+aQC4OPWUFz70T zG0`WNs4^R++46%a)#vWAKx%`GB5f55mMpA)GCvcGSO{&WW^IKI^t0cv{`czwf=}!E3A5)fb|Qa%27XZhEw2cLe*l5u*>v ztj_vXmPg%?_}{+o1OAi;zTR=bTb+Mf5BS@Pf4v`Jb@7uw@N_sZ;OM>8<+elM`2s%R zgn&97z7M?I4Gg?kx5A&V2jVaBfdC9en1&+~K@lsUNEG6%G*RGZD99_^PbjJIjYyhE z7_Z>x)C>Mj?#E=({43>ILy6=a6E;5C=LnunJ<(1@SsjvthaW z_*KTu6NnTBWS<0@Qodu9L}l!C$5buStVLPmAm?>H3H(M-U}UI$Qjn4GU3V6BkCr&N zY;GunS_ng!s!msjGE|R4%{&w1JR#FQ))OoqF(RZMu%jO6MQMO8A#9QAYVgpFMm)fR z)HxyoPk?~~6{b`Y357@vY=i_dsK-z3Sxc|zCz9M;5NmO$+NpY?i00cNIB16C`Dlcf zHTZ)>nX9p>vd&3_EeK6d(!!Vtv$Ku})F6+oQ#bAC4UQz~eHh`$Q2bU$tI$GgcAvz< zTB|rlt0Xi|M}U|f6Y67HT{5p#u`}>ppVSivaXkr@|E*Q4pxq0F{_oT<=l_u!KK_Rq zCiudqr&lLO1Z0>X4F4B9{AZg$4HInPf3)F)ga6Wof3Nkceud0pSOBlHXEMS)t{7C zTr^l+)T-m_#I7o@UzYRX%jot82L7iu+}GFlA8L51KAWHox3xC6w6uKs*wonA_-}By zrmEs!;BW;294;>}$CrrVi-`X*hfC4U_#|Cqy3(L+f|m%+i8zK{2Vf>*qKE}uTVv^Lp!;!s#vn3tD_#bR@Ear!`$t{lL`D8U{?^rv8~;$lLj0>jB6v>rJ#L;A4lX=1(+V@|Kj82+ z+AB)9rMbC@iHVVs(Q|F>e>=mvy1E2sSW{DzKn<&@s{Y3rzIE%CtgP(6onZ+HiT`J3 zn3k6Ie^SGgl#~Qs_=*gAMM82#M1%(bHUc#Ke@P8n^L4-ZKT*SJ9sf-Yd-4U*u*z=C z|9?`$LSHHQp%e4Bz7Bn^wC;>z)ov)8t#$lbYB|_Y{*CZ-Igq8@Sh3LTceqvP9RA_^ zXS7ZBjCNDia%Uus@S~xoYTHhJB5k_VA32QIQVh%HVN|tGMuZhZ7DfE)2F8o-=iPJh zkaCWG^gw5EZqrH#;52k^=D%kY5%fH-^`^sCA&Px;KXzM9d{p|?%n#ho{$A+h_Drqw z_mS4-zk5raCV1A1m(ok^{IsL@t=kj{!tlbN7&Nf$GU(6Vw=b1eO8BeYO9<9_60U(^ z{BGfyLD}0!6~eqg%RS0)islMon#<%uLe^k!LpYA@xR6X2ULKtSXB$`~1n*|O^xxF5 zl+?rEm1-Jx8iw_eDFfk?;#gb(!?*?1^PEJ zEPtN?D86lR4t>FIP{WuT#G17OQP*z~s9~=ur}Zp9$^z~<#flXEfPgEq)x;1kGslDo z@-)XlgElCI5Mbei>;}4Z=BP(#MSK07Suhuk~c@!(Q9P@wRIlb6<7)XA=6M zJ&*;de16A`8!Y*q;wlQWRWaE=Lr{rZa>F+cJ$_K${xd<>S3gT$=hFC{lBYsBH!`fE zS-e-|aA>>ZVSWn$weElusNuseD9H7rQ8nUNRYqCb@}qIp3=WhoH8aB>^aEm3??99D zJJkU`7oA_G@h6>#4raBlL)9dk3hnTB?pq}&Y?M}MNim&a#l7|MvcHS3{^BhQh9!Tr zcoMM0XD7?x2Ph)aNSTp663%&RqKVcYX@6d)?3tWqrA^oUdCk1R@riN*m&XMeS5Q?} z$%_mTPy3ya$Om-u+|-wJZ~v_yoEkvHeu5l*-uj=pw?T z%8i?S7DIV;(%V7zN&LxGGFG}%6K2+D)B0p zI;F3Rmv;;Wv;@JoLsgk~_g~z}{EBR>xic_4XkvDebNuRW7hn4C7{?twMi6bc;5gKf zO<&{MB{jJ-bmf}sw}ERk40rjx6Cz&o7;?a+`arDiuFg97T=e~Y={yFvUCQqFFz5%r z=e3KoD6u{J5s6gbvWrIv738U%=HGt&JNg|rFHi4Gv%2&_a@DIs;awU{CVL&e)cGhr z+aLWQ=mW*lmIT4mNUagl2PWMujKVKu22F1rrfEMbs(Mn4wrbnBW>eC2`-kZppS~dG zV*xO!0Ep73ic5)7_Kw_^M651r0nNIfy0DgwI&gGAInxwzD?Jw<^e(77i@16X6GtWz zJnop9tMer5%1@(JlO`P*yRpYMmu(Kl0Sv>%cVz~~;vP!^WSb~SQ;?F(Ga4Y7K=Aev z2ww4g23f4C5^gfev49hth3kdEsG+Yc^1uat>WYd^!KWqGkn~YBII0@9pZ11>NGeg8 zUV1Xz=#Py_tf?`7gU;vshI!WT4?}IYGR&D!2uIxy=FGpib(FmLzBU|#-3~1p5-=wtw^8QB`SuO(V}I zfi&cK_h{HpT|%5w=;c~9M}qFSaiO$jsnPV)0v;7G#;hQGe5W=KUg@_BuF|Q@#GuAuaD( z4|7A&mFmb~71Qv9Gy$jH!DY(#A6nLPpLm^rjp-!fXxNQ(Ra~b4m@c^C;u0c{_f9PQ z6Y>qqsl;`wiujbzhBD_s%&!$vB@sbZ=M}*zJ*9HMlzw zK;4k<;9@h<>>nZmu&;5(fI>6$qJ11cj_K|PLtK|0OS(vT>c02w6<7pD8@#qJ_YBED zk$z-oXcbh-aqmPfgApJ5ydekl${A7P_$kg#spjo>l~46S`$P(BxnZ&Va-DV}r+vOk z9^PM9R^WQ4F&v`qXY=R&EVmsw)UgpSaKuE?GCsJ^A3U=kW-Te@kc}=}_wuW}Xct{K z8mGGcR>V$$Zkp}oo%eA&rB;`_gCn1G8btXcIwLpKt*jTBoBl$MC5ZizJqqB2;|yZG zUv7E|B2;=DVX7B*eFCW#C*zC;oF@;&f)lT$i^d~pA8pCH7Jj>?cSd>h5vP~0!3tdR zv?_$^a3ZXV+YO5Zr}Z%R;f zL{Qzz>zl#4*40h|tGY`(_g3ugZ4}(wA<-vRCjW{;P6OnLROm_>bdRAK2mt%*Qyl8s z9PmGn1`{nUkvr@Yxmuf$f(RR&O1v0V@5DeRhOn6M*JKd(_-Qt-I|jTMdx1g&kyQh6 z-UpKQ4`d4;kR}j&^CBGuh;K%|qHzfMnjfHKs0QwX-26*SE*l8FPoA2G?E1^EFAx@d z;%+EFlSZgItSU3m(0vT?XTvi9*N|@#W#1&3zIn&+Cc+2#t6SFz3iuV8yh^?vc+GTL z#gxPbP8i58;DEnX4k7Ui7@2lRUM2O%K@Y1a(oEfd*Er6h$-B{%lV~ysNN7o)au^MM zK^+;=6eHCcM8XMi|927zL!6Ko#;YGmd|&&TIAZZ6c8MYGhiu%UDX5ZEW>4xN5hrvOhAHFR8heZ4E+Ntneuul~&XBvVLN5rEAJRFfB?!@xT0BI27 z1VwI#A^VFW{QFFtrVn;pB0uK{qA!jeVo206e6;OG)>rd9uF-lyBaT1~ulmLDA3u5s z1}yJd9Vc6z;k&I)R;~D#5KR4utL}I-ZFC?Q^Da!$3=1(v!VZ^6pqfeBbac7;$TK9I zIG4Pv7&!`1_~pfLohG91@*!`@es4~jEa_=Vgh1cZtG{HsXAi~+qgJ6H(~r6zKDl$=m=@I!(}OTK3k*?48-{UmvsAPqPo?a*k%Rf1Bl;q~+|r$XWgP!fYSfS(HQcDW_fz z3ogwTs&ecajR4T(#!e{}rwLfOT&*J`7zeREA!z0Hj>N`5!xVW%LYIPq@CZTdQABK* zJfTl{B6E47XL(}g;I9~`bet(0mh2ZcuMiCv(t-_Q@_4Mtm&Kpq-FR3UOWh!gb@O9tc?WI!egasx|TGKzRUnw+PZ8@?sFI%z^ez)JD^$}2TAH7~LW zNa=!E$vgj&`4<428<09zl5&={ESGcf0$U(dN@`wOtcBf3D=j0>d9RhNh=n}TC%N|* zRQ?p3@BiUX8aCGf>4AoyVBsBp>R&jJSxfM<6_^M^I>(FR5iRfGTQnp44OCrWEX?&M}j2!W|X$?dU3 zUQ2Ko(yT1cs8-&T0i-ds(g2ER;=F z17dc$x8eQmEF7O&MtTqNcC?c`^bkX_Qrbk`-y}{`7oYKI zn6J^I&eTb|mrd|dx@ zt5b61yyeSFNloI`iEolWrfoCMqqH-Ui~#`2;irxlZ=u<)=zG}a@wl-<82QJedB<5C zbW?nHTXv+jdDb}<-{6kd^zm^D=mi$S4FJTrBqMYxMN4c^bn!q&yZDZVn27zv z1n$L2``o$zl^{|Z=SqR?09YD{SUS~SxvB23$v*ge-MLc+c9+quh!+L`Q9dYzw(gf* zcQU(gR<{f5eCD|5mdn)2m?kAoaDRwwP;Rj^E$e=!zc$xTtW3Cd=yrvH#>~N?ogUW@0|!&xu$}?@IsaHA8k5Xnxrtdi zo$4cnFF&7+b00qv7IG7oQRbw7vSaT^vbmY*Ino%U6n^2wS}D~G%q z1;#SnL#HPhjwizxdLk`{*;{AQuk$-(G#oVazHXU))H;-+*q64@{Gxm&=91f60EGV0 zcWN;Qemz%weOiEQ*hzP|v~^DQVD{y4m5cVQYwLtd<9LJabkn7$yTZ3t%c=6$+?B&T zXdrOJa{gV`yjtcQ<*S7S{O-aHqIsPk(B7eM!7lU7?-x>A=gp_*3ohr&7G@oGXR3yI znyQBPVi$_a7w-%$#FH)R>dfD`0c1NP!{rfsu%(zAGsBVd7p#?6tV?aI3kTPEyrHwC zpiji*OCLfPW6zf^hZjB97l}ldX&x=h8cbp>ku)xStl0}3N;s;k5Z>oMMisdoEs;Ez zE}{YKY`&kk*nV=!{fw~qDfxT_FqkxPL7p?i^tzXoMwYe=W>gkms$Pn5ciHlEYv2h)%H0@y*u;AYUbAaY=AYGxr=g0 z983&?jPFx!y1^LnBr=m2#G*c#xbmufg`Y#5oqpV!)5xkn66|J=)Wx~_im#I;_Ye`1 za|}V9O&hUnG|)T_0LMW|#7RvA5Qy9gePTI%*cy&a44ELI4<6Nr6a6Oo<3=u1MRu`N z3?sN zdwEg`N!UAI+#~xfz;A|3;`$elivwsde%*+ zy{PB0^(V~~k1f9I4K3^bDw{|QMAc-g)|x=jQWg*J zz6gYJ{K3uy6jgDOpkf%+qL6YIKlShbyc@@=7(nvBQ^VIS+d>&1taZl-taha-ha|PJ z0LE`TAKW#U#PDBb>7&$xbc&E~MO}mroeYZ}l=Rg3Pv(;-`I~!LNV?LY%gi6XllnHc z@g}YdtE_gXE>AU*T2)D#6dfY@OhW5I5x{}ljAT4;PaTNR%z@Y^NjBi;L}>ayIt__ccLdvsW9Cg33-! zIZ|sO%d~!iMM*H_-`Ud`U*y}rF}_pUIc2Gzp!px{ekuy5aWOV zFDpxSjE7dNit=8I_6ADI$jHRL-pIr%Ov>2Ip|IZgp=-C4iKXvqy@{1GX%|8f2ueH1yvqT&3ENKYk_qBf_DGKn>d;7bi&?&g9YtF76Am zNDoBb6^(!D`4N?<{xE&Bfb5xn;Y)n&iGZAn@pG#7Vw>Pun@kt5{IhDo%k+F>Tt6g> zP+wmH8BLX}r&33K+TR2)GqRKVlF3$2pQ62j7%wDE%lDwJALY(8#Bq=k(5xq-GJ9JfTljc}*OVPwyRd zHsO-2dhfYoQDf++ETQqwhVY=&UzvtSsNk$z;hpe}F!fE5Rfc+}d*2=<-_(8WX<<2^ zX@0GI|6@#%{(~aW3D-py?9uqi2xcd)ZkMW3E&A7|WEXKmmzJA*2iKQsJAZXHA3mnP z*h+wC+w^W-WXbH)O#W$E8Mu<2$7FlB8u%xxfm5Lv@t!IJDHs|LLL+bQT*?Y@l=|Ns z38lBG>wnq1HR!d)<5Qn;5E$Y5m=@>b9))1ohh5QGRShoOecJ)FKFtg-=5adZ)>Kwf zLzyeV59m7Kw5U8J7>lG31Efr$1yCPJ+wJu=-5JLecqCfHl8koTnHLmTRngS|4kCnD zer*m}M_r~LvihB+g0|Y_Y1#u)GMX;Fv3|wVl%&2{f}YQG*?-|$^i|xPBY!9gQPUln$M?$|a`8Mx@4&nK&)4%C6Cp(BXdQxF zrqLw@8vB)UFQpYl>Ttf3^y&>hxi3sKgG9&NS-QJ{aqB&?V(q!j315|Nso~{iY#fWl zSKzfComXjHHSae2)hJ;u@XDRte%@Q7qJE*cc**>b$4B=ak$Ep?e))Sx5B;(;b+xr6 zZlmI43Ht1XyuvrN1ze4~5%$yN?1vQs1b(IwJ*KIoTO=H`L~5K1Imx+ojeu^!bx^Ox zQ|kh5)v;Q=Z+63_Il(_^D4|Xe8A+yLQ)_Ix{=C)maj#;pG8ICl5{)d}3 z$aBk_la^E)+DZDa+iAc$tJXZ)&*~-eR{BJ)1o+UzrrN!yRIj{_+XhGPI=}iu{khwW zr@eTbTV?oNw#rI#Zs~#dZIgscv3N)8KT|(JbGw$OmJMh5deGjpg6tSL`}x(7k91nW zcJH~XpiD!TComl~xY|RQE2`=9s^_y`TkmSWh}UxmD)oqM1y0UUl~7FCkIKh=YN{>l zc@E7;Kmz^S#A9?#TK2xzUY`)>Vc1ccOHFBdF=ykL3O#c3&~L0W^$v#z|4)oFAc5dC zF*xWe$;zYXh-Y100R|v|(n1P0rseT|qDir{LCZ_~9Dp`ASD*WmVfTRCj6~ozQy!im zh{sKm4I?jHx}@zl?6m-r2sX2&XJC>MYr(gri;B2k(|0H6(&@2&Yw+NE@_0Pg>ZFdo zio{iBXu`#qB)5y%WBRCjMq+ZCTqhI~tdTqANzN0`P`sM|`$eQ^ z@b^nWpzxVo#3ac|T24^J%p(LEzQ&yG^M z+7vlypO!v7T^)TuHvlRnu6no7vvjFqpv&voM)d*l`D@OFVU_q(ZOdbO;b(k{SxdPv z*NOPmw*&bpRu!HI7Ui7Edwb%q^r+`kUv#b|33TuO*i+YkWiJePBW?`|xcB_|is609 z)@Icy%e=Zuo>S4_YoVhY*5XlsY-AVS2blh>>%$iQe&k_8>{q4{rV*hWpJW}4UWbda zPuFu@vXgAnSmmev$Er~iG^-)sGkUfkdRKr*y+rtz#a$Qnh|BJiy z6LnjpT#I?7oE7@Lrt`52?Wt*%X&W@F0ecUvbX7}F4@h#hmH+cf=6Xc^?W@3QLR@NDg95qBT{EgC&RPCRLu~d}GPQkRXUUWrz)XevGJ% zUYF%bQstqs^M7Regph zeV)FRqj8WEIHeSkps<3nr52;0GMR0%(H;)GmSh3YDq9D+wh;i~W8%_U9GwW#gP~M7 zx$K9*;xhzr=5_85oP{Zv4w2xcOZY2+!1&hsjRG?YfZe+ZS@*_Dd(cpDyql%wqjQK~ z1BGV;5EqqXZby&-lpRTZ(=Vl=4o>O)p&rPsaXPJ2WD0i|NRELMy5oS@s3aQ%%o3Iy zBawUuo`C;F!a{2y8R6M}>6WBFfswRL3Z4ffc@kWB^h?#fv@@Kv^XxkoN{Jy6!&pvI zio6PA9^p&@ah@w>q_=W${l~&4&5(TQ9j8=&!xpZY2`Gol5T(BAH?ZtBjOo0slotg< z1-2$(!d$m9ESu{@xM{M#0Ksj)Uo2@C#-I23=y-Ni$0j$CZH#^=ma|brzCA}>WqPWz zPX%NOt(}A@tO51l$sVvG;mO=vOi>v*Gg?Q3cAG)j&5Uc(j;rL|$wwZ9tO1d`$DD-G4IdMOiu{AW_N`sC1I_ zQg@!nX};ETv<{2=Sk{my@XVvMPYJ8dV`%(5tb8|Bi#+4mrQYzvlPntatqpq{`%TPq z>}Jr?W{faT-5SVe#154T5{)fT7&ftWP40FUW`WHogtQsM7A(RQKDyW8^K~N`cIZa|XZ6 zzwulFfX5#*kq8Ul851+!T)yH?;n-D7>T3156*9pp{R2+TifD)!x|a7UT$WobW68d& z5STp>%G(eYV0!0cLre60J`63JNJK!kdg`${-eV9aYZGk6VJ`ay?_021!l7CP64suvE2X>>9b-~2|CzheY7bWM4n6)*u&X1Ws-=D^QeX>6`@UYY zv@y#@W<-}_e3je>16pk*J)k7C+5_Mu!2hAVu1S(;7;q1Z51dF2y~46>Q{cDKpOaCO z__RIl+Ath;j1~FVwedlZ8RJ%JncraU0=KD;b>548|5hR)s5_}|9^;Xnz!;nmC;-LI z10sSGnI|yr5`+z=i2+p!3b`1;3~SjiG2gBTQ~@JE z(cQu+&6z0PF>f9n7z{pZz#%3GApo>gR3Y0HArk=2vX&fGp61_>ma+#kR?X<-mIZ$0 z1{qHu2AF}ZM_7sBg_KR?qq5@#t_@B^wg>{iplj+NHXQLkD6cD;NS7dBYs+{GYJ3F^ z_96HQ2KX@Q1KJ>w^SHwuK<(A1r#n*O3EOzJT(?8!5A5}D87(E8w5?p`R*xYGaxjSy z{#jHTM+qY|N5j}olH&G~16+}h1_^z2!T*Ax*gdET8mDlTJXwYNg36L?q4!q(!YH@d zL~Z}2dK>HX-d8N6@ht&W^VHjhbL1^S^0S~t?X;Rd)hY-occ29A@zB3xrl za0$dEBVey=-Qvlqy+#Z$>^=sU{M}l6s==DNC^W#(>zqw^1ZKAWav;oBHLB{l9 zh4j%|_OJo!0|!_8K#$uRHoAt_RV&}Q)S*%sC3mG9r$hg#*hd~U2#pgHvwd*B=a6@?~! zBmb9ts2b8z$E?#YR95Q?cQqhuaqxBHUDKp3kevxMyJoQvHLrbyBlw)psOJ~& z%lUiEmFEa5bri7aTSS+QpG=@yE8VdEvRAM8Jc`f;HbwvH2(GB(x`jE+d~`&AXUvOg zDl_FZsJg)oxRo|JsePP{aLQ@}d(I~Z?m@;F$>^b(fcoQK?Z-PeM>TAeZ;jA@jfv(L z1AtEsqyLdoZ$bRm2=8=*$<;c3kyA5do~&7i>`VDn#4YOdk?A@4XW0J${0i=fTiOpy z`H$U25Sm@>Njx~EXxFz1IQ>=<+`k)8z?*GZu}}{bHAp<7;CJ9KA)?-c1T-YOxhCjM zBt5+(#S;>e8#;%6^9?;@JGoDn?Z);a*Ht>U%pV!;Nj9lmZBF8}bX z1De_L(;_z{p0;sG_*+QON0|Oi^3DAvH?knr zHc8#Aj-7cg{qeIGQUmALX|I!DGF!>U-59fZ!qx*^T(CM0hKZxhKpvCjYR$T3mAk)Q z_7LCNw5^lRJRbx-c~^Pp!?9v0GiYoH#bqZ&AHW{Meqpvnb)zsB7n1IHrq z#IMQBo$urb00`L~Ba2*Bb^xj(>a>3EG;+;NHW_8g z!0*uTM>9~xVL}!HJus~f4B`_6N)I`yJY8WRV|g-vnu1Dv>!@6G$=0RiSck*A>q2oj zD7qDA!8mC_d9%%MQ=IjPA~@hSjrBh%uu6s{B;{82>f4l*NK1OF-A8=3>67lRjQZs()fD~wl&g5Jn+T@_EG zYo*iK)7{stA5bQYM7=*)Iw}1(x$1!iaggM=u4@8-@@{d2{gjl97P zWoR(p=gHNjPVvY!;#1V%i0-7!3C^0yn+Ac-2%Yd5mTWjHRb|S~1XXg4dN(J^J&+-_ zPw#KO^0xu+4EX?2!E*|~mYJxC@O3~0;hzo8Y%+X#b@l`LJ35}UrV4)q>T>jz1RodJ z>-*A%%R~!4sfd2>TVEEZB-G%#x1d#cEton_aW-Q?fN@ZJw`=L*yqhirX#{1IgbeVq zMGO!ti?rJWJTWE*xQ3DeF+SWmr1-ttmp?vA!c?Igu3y{KLiJmddOKBFtY^3MfmrW; zfGskG0(6pH!Sap#$p&jy%Gpb8Q8_EAoV zZIhKLpw<9Ld$&(=oF>5Agcv{zCI;~56H(!TQxh;W&u>bZ3_+;kAaGXxZ!L%*+_Vbt zR`vR?^gNP8Rb~MdIe$c{C)_WyWTgC0X4y<#6w2nV8!NkN=WW!rV*enci`LAYiU6v0 zUVc7@V)$GJ^Lq8~-h$7Fs{F^WX(#zjuV+=o)}EBLWU?(YRUb#$#JdJdO&A9hzOV)* z&+_qiCqMyrifI;vwq`~Fmteq$O|p^pDY(f%5LRwS;biy`t1`|vRy znsR@G3v~XV>Mb>Fh=|%Ko_6%Zrd&}0cw?L9QTGTC7Rh(e$V0@C03fnx(AYz?LOdHN z0dub4L>Pi@mvI9Dk`(|f51M{3Pa9G}@$j8g;j~q_sPh^|d8OJ@3|K*INn4|W=IyCg z*c#gA1}*+1BMRFsBz4uixD}@+2{%&1+lQA?R*JyQDhDY4-7Ldz*@HzXXANc(MFrXd zG1|{_!@+ipdv2a|ho&eZYDFNXiHp@=03~Bxn5}8&gLCNP;VZ$78HRS`sjSuUi!))x z_l8IifLg|XS`rxBK?XFQ$(VA9ak{BHM`+qM$xkDA+L`E#E2GL;JVDT~1-{GZ%tRtZ zC)K-Pr2+qDr=yx_7S99>DOhRu6nL(uW$O35tTeqw{+R+okXAC?V}s;jQ)e3S;9{v` zDX)EbWPt>gC+YFlt^~(0$o1kg==WcKgvlbEjXwZTuh<~`*=|<X5!DwjOR_j#N? zZHm)hcSQ@mH}RHkJjPd~EW6a^kC#J*epGEB=G(|)pv!Pj8-c`&`Nfh&T25>}2`?vh zHZ?l0MrF3%E?x~qLU>a_3-^{)zgAJ|AIY*EFWVldd&*@VlvCq-jZCoG4SMxj@sD*g=aYW zvAYvcBJLE^E_M0Hsf62;TUjSDGhb9W;2Hm?)OArmxpD@r&yMm!lsSEV*2XL5&J=tr z&t?$hq1i)l5_xNTfCptpe}KfRMG4dVVYbEF&1B7Xrn%{5XI{^Nm-PDjP9RNr0NYbR z*RUpN}6n|`72}KU5 zXFLnfO3fXyon(ldZAla|pdFwm=!U9E1d|C{Q~d=o4swcP+h4LpZkfWRgLOhaPBUFC z{z|<(Y@;v2m(9NAlk8k(JJh|oGA5%)f5lvvD(x=vg-IDTrZ?fkvvi>LDHf8$)0n~v=lODPW;+^O?S zwN#amo)z_0lkCPFWo0DZ-QUy7^<^Z@*%m+H&6zYnaYUFhF0g`#xscq^cS5n}APMPG z_jwXcnbr18A4q)Rp=fCNr*dDT^Ze1s%D_rxd;1@M6@?!=>s1v{gZ@)gF(A$GzQld7G30u-CEL;-T`Sl{qT!+$W`o63LN737i zU+3c+HhMp-FLl_7&w6oR|0xR-i=m=s>_Nf~#Bu^sgK3p2b~zZDzIW+b5iOBR4c zxA%*XyG*VpgCC&drY&jQft|T5ANRdFMlu?XM2(UD#xcK;v{kqq8BXQP`l)fr_~W8J zkKlh|s02`^gDYF#?z&$0V+N%ooN&lz{TKJ?(p;a4soYOtl%F8HN%(mG`BkHs8hP}m zQxJ%@ma*gLDOOih$qd3M8m&Omc}@F|D|_~>BKm`!U)uf9x`2d!6SjJzoZqJHb%+8*+W+4AO69Yq`3bb57A-yHCeW zfu`s-r!RWBa7=anCnbHuChCbVjacE+MQQb|@`hwVL+{jRpR|5k{+JOmm+PHCjuh8V z2~?pJehIghgH12$#{3wn zwvKV@NvyVy;2{4FWN@T@BZ_&pM$flc(@4c_9nOV}snLU1Q%jBTG~uRl7~FpjyEoU! zx{sc6e*P)wei`wRd-JorwHZV3DAg4gvwq1S3?k(|s^qMxTsU(riceHGyajX#-90^w z778Vtxz#mB@3m1}`vbt?)e¬=peX0$g~EYZTS0)=$@!^))pY3%mq8v}Zo4s=0Yk zX%zje)e#!K*J-bw&ZC!UcqyizYRt2ye`+`DZg4}pyY0CPDPo{%}5J0 zihoZ`YJw)!{?qu;ZZ*;5jYm6#*J#_8i}kT1Xz-o_>hW*Q45MK=%dwV_T2gjr1*n6o zl-a-q5aphmB09+Im2PKkXW#M3qxVyqXr{y5vc*<>_3UGvK>WDs%qP zb{^{+Ue`cg20K>%lHvl$NP=wruA^1mCsk5KplC?cZhtDyrr??$z%P( zuT}#)u5Xw=Q#tS_7BbByq|%LQrqVC0)LTQ?|4EjHr?UrLez`Y~RC7cLcgD+ZC9vKG zn{JUN>u)H=I@hOPkz)MR?JU6ii;gMi`5^~Sd$@`9n7whmRaNEp_Dxuv-P!)|S?o6< zjkhHE!#4Tx#53*>0|{chm^IGw-$_<}Nz7FgMTknw$4}Ld|Kp!1X_#o|1%wZ)*To|( zho$;mHB?+K7KSdY9?`6FV95|1M*Im+-S2d;`D%OH~2Va@)abcNaMr6Bvke2bvJmy4e+!|LLNJy2SoHfx+gRF)LGbu_YW|K!VUC!E9 zgSN5kj*r$hD^qE8vIfTJlJnu>SAT0y6+eW0_mFh3AktDpS$C9}8cR|s=y7Nveo|6u zU46NRx>a?b1!!E&?B`1*R&X`Oy!pl}>Y6OK5C7|GcVv_3M^FJ3swVb94uXULh?)Tb zb?k@&52}L)Lhr}Pp#3G22(9M)og+|3w$u4_&d{!{OB4HO13Oct{_^OdySN_>t%#MV zMEx^jzm$Qe2BV{7ZCPMOEZlVjy!EuEewim5k74FXP@aE^*ucQ4YdH0VJQ8heIfd(u z(^U<9UJs$u|FD&0l+bK^edL1g0lw~k&*NG)_Ai0+l}2zz)nvkCO?9HX6R^V zUhRW=zVK|hFmmmd=}lPrkLg9hI5j2nYa$@Nw=2A@vuWBmo!@7KsSm}h3sUk2A-VYd zKKm;WmC;V@(1p`*c298|a!w=(LEkrwHO%LnE9CD=zQRE3Am=-DGOt0aB9`L(WXu>k zuqy-@1O>+rvkW4bC`VMc5E?ihz06yr+tb=r)QAdTc*wm|$j&JVATI~X_ysOlYkgZR zdVgu@`q@T6bjW;HgQluFU+p+0`q*+WKyy&c1O^epqST5A!1b8i`Fcun*Ezdp$ zBH@ff1vk%SvbmSMM zR3QZkH6Gn{JYg}Gu)yKPt;6~1;_GimbbzdP7sXrNxIwY*DU}1zSWDZfXnP3xewe2C zVQkB{r(b`iILX;@p&9A4oc(`ry)khf4Wh;dQ}h4(zE^a(ByK6`eT%xzj~Lmv1E$-z zeA{1+wprJF3f(-h4^|ApSMHwiY6VmE1LJ3oE-yL}jV<{c~< z#?~h1yDE0%x__f13PW;-1%1@-pfvB`Gk=b3I@Rg}h%6^4n-r z%fLa(LN#$B0EmVf9I<;cOa2#3 z0zwN8f@;Y%B?U$hx+6mKQWD2&pp$Kyv`mUCaRA3f89JDm2c`HofsJ%jSY*lWuW2VU zL^A9VDze?+$X||a$mL3d4q-Q+`(E1{Lghgq?SqohMG1`xB3(6hCbg`yR~IL{@D-vGlQyl^=^<_an}=aO&Ipp#Kn?FjpzoVCIAQ+ zZsgIHEMPBz=hlZMwL{L3&W=Ldb&6q*+Cvd<`2T_jnJ(REv^+>gh2h}S{u6o^_&<&XgDHeI|?xbixdwr(W2x; z79|1vLDzD@B=Sh?oD^FmHsXmltE>n@UPJf_Whf8m(@?&3Z=2%%Nae4)vk06hap#8r zAe1RVMl1OWsRm>KNwPI6$`l78v`PlBAY(ly3g?oY@#zY(+nq^c1ieGBq=pw=K1-PP zN65&G^b(KqmV-$p5vni{pfh3V45cp9%nLv}Q$So=O+xrD0<<_~? z^F!oo7&*g{W%etnf2e&Cii&qV6`vF`HX^JHnFzB}J+!vk|V*8EnIJH!}nZ z#Lblz{T4TfG-rX3{sqs3M$K-JX8r2^n;w-)sJztF-NvBYPJxtqeWk0Su{@&y8p>)- zh-%eQ-ZWJ1`Zbf~J@zgsKvn{*6do_*iXuh(!qx$5O~Yh60Fh4o$T!jNDz!su!SQ6+ zc(v<@X(v7e$s2u}gr@P7r(i%LgQn7f9xusrN?&<}xwf3)l94lC{-G;wM@Jw0i4Ngu zGy_!5V06bia48eSGWvTKHp-%jQf^9+X4Nm63)2H9nyQSxen$(r$T{UolK%_7zEm## z`(SVct3HphcqprFDd**MPe3c*DocL!i-gaUU)(M+5m;Gk0rB&|C(|KJVpa2=QRqEg zg}LdJA_^=t8_4t*%%6=U_8Al`#}IcTWy2E|>Hm7tVCT~~BMl;QyPDbi0{H1Lzk$#l zqrT`T?KU-l zba)XK`;t99ke?Ijef{r~bnJ#j-_kp+Hx3iq@A6kXV%=g!)O8oXcuyRBV!1~c8cH6D z@-|ERV8>OndzgfMZUMMa{HM+OqLRWXK&(*>6 zOc%rp(n=y1gwiQ>Zkg2R#3=I@VS`AfA6O7roz9r613wAqnJ;|t zp4#MY|2kV1p?U1_h%87rk^Nuw;Y?ZMql$`(2g{%rgI-Ce;x3W5)UeLSxt`1Li=Kz$ zzt$Y${$-#5rwd_sS_>V|ckV-Q{pD#h{pU@!VndT{1}0B`vZkMKE*d@;DSNn?Z8}26 zhMn)YL`NTUUF+6mjsD38pt8i{=bvSlVma|Utsq|e6FC--k@jY&BG1$aJNI9)zDY~) z;sm$Tb-NfP8}@kg$}r|kUhHBEmD-ny=IL?l1f*;4YiOPz&ci*^ba;5psb`M_I;&dl z+_ZbmD(+hv%(8uBey+^_ctdnb4Olx&q1rGp{dx!PHfK;-Ns?!%+9Mp+Ed4`dZ%*Hh z1)!q&xdzdtEJ0>vd7CfFn7p`xT(qiNt)$_KdL{Jg8NN}~Q+^u2>MpL{qieS56rlUL zXr@(rlJG*!ECb+P5^!1VwxVRE*=O(6)#^vVLYl7VskPs|6X;87qfHjx`N{=}vT1Tf zC9c{{!vNw`FJOD$IIK2j-`PcCX7NjoN9JR4{MH28L?o(zia)>4Bd_3JxC(71Up!de zZTj52HkR)a`(Y7O?5t@kOt~VrwYGE5;PLDyJ{=KT@pvbwZ>rkGAjm6|9y89zw3~KS zl_m;~ma1-_>R!w+F*X3$p;J7YBX8XJ_8Y%xmJ0j6B~kdA7q}VC&24!A!nNE-fO_r^ zcfIvaz-2x=e6g81wWrivUnz@(dgh~5L9 z6{QMvjs0YtrSs`)Nfcp?3J1!e(EAzSp7{oLEQ>AkPz zk#UQm@d`G=SDi^ZQ|C`DyzsFd6yZRx?B_63BfxH>{M(<6#GfqgeL$J3cnMy7(cq3R zDkgB`ulpNY_4%#4i^#8JrMTH2&(u@17c+PDOCB0Fe!}nV@yo9nr9E(b<^)VTNu=x2 zjU?Ow?(pdJT;x2{E`60l5QasnAn&+LUO%#@2UKbYCz5IX*&=eF8Jr`NxcfnPD~8oa zS;%f*jc~_FB5IZYClMshVZYisPM7L;wO*n?x-Jd+l!V?#3-IeIStgxPYmQb@a2;Gs z;xa*XOk`+^UHm*eb8o=X_faW}js}E3^#*|D%j7h)K zRw_9lD24>x5QccHf|Vyu&jHgZ$}hL~x+wM;Ny3Aslp=E-p23O|?tQ zck#oGBHjw;e<8;v3U|A&R5Vwb&d@zb>s5VsPmkuLeE{WHT`Ge#)x%Q@ZSfj~Nci9k?hF zXe?%?2|;6M+6a|*;&En(<*2~~c5gHN=GB$Vm!$M<(in`5Xw%fCS-WqvL;jR#G^0n^ zRa&pOmNv5F^n(#W_n?-6U#zH5-o z<~O%!5i;WvG&Pc$pRtFfg>mwIHH`B1-hRDt@3yuLBudGPeXv?ErT#q3tIZK9Oz|7a z8r%sc<%0REY)y-?K7jFC za)YfntltB!j_#hME2tjty7nyT(s40xGsZ=gC3=;${mAv9O5@|qhzmy^1pCFEeBrp+ z8VAC-zGCuwmOiM#AOpizPCKn|A=3=vTRfK2WNM`&@u$cA01nqzY348p+4UBdOyjmVlCU2hf+szo zhJ}Jx5DAB#hnFw2;zHhgsi<}G#cO-^6!V2=9S?;4+I=Cm(bB5b>XHR}{^&Fn1Bqw( zJ&_dl&N&i;tGe&lrKJg^1jQYLOG~UFFj)aCSj!7ZS&~c>JP6kZ6?Md^d;T<&&YoLIFG#^ zzz>`hEuIbq4Ll)4qzzui6Kt81-7S3kxBB7U@B89U%?dK9)x3A8aNolYi4MO%O@BC`!D#wsL#Zd^$OT6e|C(##{5gj{JcKpf-xm7 z*A#~~0e%bmJ?HyxLlY{V3JN&k43_W;KjH4hJxbm34>y7Zw7%=jN-jJ}pOeT~49+N} zyi+-U0UKmAyo+s^uW1SDt9Q=I^}7=8hjExd4!+11Lj8A48KUK0G6xhEZ^*&PBv)c znB%?gGtl(2Xvq>sezM%57)5vNlz{VJJB$-Ggr^!#5 z9JmQ&Jqi91Lb54nAnw5BtY-)>7OlyMEi`Sk2rEGi&3g=a44i3zb7iLn)ovK;%Dw=PC=*s&CJ!>(0U& za+@Hobekevq3O@|g5@(BLc9bZO&5+N%#&ium*7n! z`4hxWzm3E%B1L6T(qYn8&qc{DP$qc@JThGK*j!UjM%E>-eDnMXEr8k5gNa9DHrFTR zgeLJqT4cOK#G-?VES`-(n=t6EM#8*&u{m#fXqf4l0JDkKouwh&DmKenIswo!=@!=ea3&ER{la_UuKb}z>g}|LpLSdFyf2u7ZM?($ErC`^j@Z^TX8SN$G`8M zdf&4A&`}3GfhKLrAvFg8lrU_2u7ufcT>Ub7DZ@JLyx_(<3ir2eHzx9_GQ4Xt35L0% zh54$We-cF1FvSN*acl8cBoLncPO)tIb8} zY`n2dOc4SDGQZ>^5?#ZDc4^!3TL{@VL*PtM3MlQHsjQU^?E@bx8P+cQ{7h~#q_-F6 z^Xjc$g(M&`53D*NULy9x>c2N<`op;5^krC$v_ zh*%%JB0fV`G%wq_OlSPr48!1+`*IPR1yF;pO;w(n~2ODN{@`xkRF zF1I0HH!?|~ycN}-KWiA#jHwxrI(N$Adbsqx2st?cW$U+7qMBL^d%CZIcAb4FJ6 zcfMS_c~ix1S<5WrDg>#jZ; z7+tAT186$$3QG|&cAJMiNebK7yQ_L2!8lHl>p}TwCmhKYK}PATJQAY36Y)=n?CQ{Y zm8)3IBr-24GG!|A!LtoHQfkYwD0R?%WsjiQ;0UvMx0H$djmea{?$s7TfQi{@7*&lJqxqPEY;;L*z|zZrPkUs4k+QwjL+|6Sgs^cxY+`>4 zIG}2SUPoRlEY@kS2I0qEC{9@4H<&}q632d+hzCCbJ6g)}xk&-;jtdm)ead%Hwt4X6 z7)CqsB?eh`BadbCz#fO->PSDmY?hG!_2NJD`#&?A8*H;x0;`^9)3Rn%>C_d zS6hkX&yt7DMGiR?{EdaN`-K&}U6x=vz>%CLJczuf%;{e7M@7M5MgQ?^{Tps}{dbu? z#W0)I+?4Jl{x995LJ&&~%Mp^*(k+Exn6&&>_Qf#0LBQ9xSbhvKA6UZk(|RN*xZpM@ z)+*+=z|S4rnNJHJ(X2hfnBAR(veP9*eW0o^v92&sD1A$ec``h3LIMciV%&j4H>y~$ zGyoX{n`1RJw2EtB}? zb8}VUldY$&BH5#@3~89%(WQ{Y=mDIPkY)NU)4UnFRW$s*tnYW|5>g@9{dyGnd3_FONma4`t;_HBVLjBOU<;< zEL?(<4dM=7=A>nG1(_pRC||*AwrL?6TN5)g#9RnPIH$(7r=07Mr3VeGCz0A$OLd3( zsXyqUo=!!x>~sX?2E{mdY3=a9(fNa|hl87U+1z`LMS+ZUC>LZHLkra)?5pPZ7ZcWyYt!WLt7@=28ro z_%^FhD)9RdKY<3>CMT2-)B{9sO+*iuX#qA2Wy?AJy@bE+`#bx6LGghRap6?!kbY zL&ob{Y%JU>jF~E6f@R8e@(DB(K&-M~GG_;@H zoL%olD!u0KE$OTq`hf|?`^UY!eMBg4F1sngH~`u6O zOEPmlCIpf3VMv$ZOdH5)(JviZC_ocZc4Mf0-?Qv3`{A89o!vjs{#Q@#@S4x+Fvi&K z?Z)wls)cmT>{mO(84=K_D%!>B@9S?^w6}Zs9w|{G+(SaXE$rMomOXnF*YHYtFXzVf z0!@{hFjDgG+^y^=f%!{94U;V=S1N|l)n#n~LUyprQE6|f?Oh+ifp%A)e(-7S6^_JE zh+bm;N!p94obdMyO1=rhOgzV&f$bS9v z|4$7QCC`@(>zEWdoQJZx-BQEaSn_25TWXjn9|pkdm#X-h1K9`!9C~Ajr0ZvjgzV;S zsbT(^Ql$r%DyPSg8FOFD1A*ORGJx%4{rG5bEou7$g&6z(=-bvja@$wY|5DB8UbnAm zpjFf8>j4gf(8sYP@+})Z;XkI9r&a8S%!-F1Pm*VEZUDP{6L9}h{mg8P~ix9}m3U6dCIv zr)x(%i+ZL?&$|ypzvHcMq)xV`mL-LNwS+TOQRnnl__$!HtKp&`wdBn+l|Omk?`Aoh z6e<4g<&3uYAo02d=Q60dgQsvs`%V^>g$d({d~(CTi0YbBI_(XO)4rOqAfY6U=if|Z zE+|^Zz(DitF`Utto5?OzKJGTKHmO3@z`CnKkwG}fBSVfDSMvawfvb#Xjvr5Ck2M5N zsthTddPFes^-v~Dox<4ir}TVnQsgi5zZ6Il0rZ0+eTY`+2iLd&#a@+m4uw2Ndz|rV zQhH4E(Ru<`=Y#&1aDH=4Ym7Yki}?)CAltW$6jpRT6pb z#SWOYJ=m-AH#P#)l0Z&3%bI#46t6iuH^g|fG@T$h6DntG86rhMdIKlu6g z(fe?{K)MgSVSbTIodA^X*GfDgF4F#Qypq!=gbE`kg)syrJ(ub++FhCX1adzve>&pY z1i8)f=bI}zh*Wfd;ABI#KJA)jB->IdQdxtI2Y&dFYsN4rXzZlC$P^?&}ypQ1{+5~#L`G5~sm2DF;R zV>yJZxfx+Y^CFbI)f3u8Vm^ia@SwQI&zb1Hh9_cVFcGrX9BYOR)c|%%5#gN~04fim zX(SPkUl=Z)(i~x(yOYF6lqeg@^%~H8;8M2;W)K-ou$%E}LhFjerFZmXlCFq2L&J;~fYl>z&#*M3d56Ox- zsO7j`0}he8Wn=#zU-uae*ZcMje~%fAK7&MO^b!&^N`%pS4MLP?Nz~{i2&0caN_5dX z2|{!ky+;j#APG^UgoJ4G%{KyB$^z3E z{2($rl}()jxgohXte4|X%&@jo117C;ok#w!29Gib9Mbq5Z&QpIRe8R8Da(E9G0CV= zn`nCDNinIf-&>(r5ouAGzS|+6Z&>!Q!{ks(;ys~kq-_Um83o~D`6S~GnqJwnHDwZS zW5!*a9^|0VP}ZHbv3qs8HJ+wB5??Q33BRL=asl8gIdj^&XNj z!=W6I*x4S0-iC?g2O47$a8mynX+9Ka(>$&iL>bHp_RPR=hr3gxk3n2O>W%Ez-PwM#ULRZ{(yP# zP73|T5V15G9)9Mkk3OOKw2Baq3>%7n`j!8u1DWUiPVP+wT=lqyk9l?J{EwSL22v0X zZ&1AYf{FdoRjF@eoJl2RQ%itAPk59)Y-^(kIq=jJ1Sge`L{1jmy$Z=m=w=3yM{LY={!IdY2{t%8h0jN9CQ)nzQx|9 zmr<#6t@pMuS3Y~zFB2qulk+lvRFn^DR#&HxjuB87=lXC;=9Q2Tw>dfRu-_xtTb3088OF~eK<&cng(w518d>HJ)W>@5&HEXo=2b)* zT56u;!g}7jBuBb_NqGkS_W7+9K4|3w=MU*u43(O-IM(ERXZsOEYaiG9FS%dCzTBda znG^{Piwg~nqvuVZ*;;DUh{(44m9HO<6qjgWW{r4GwQ>muTHB(Vd_mmeJR0WNO)`fpSkozam@LRnq# zcduMi2>j{bh+{F1p}75tJf=^NO@4>%(e;EIfmp|0{eEBh(76{MMzvb@ttDxG_nwmU z%4-o}4tsktLb1%RzB$eB=D|OQtP73QWQXQ{c#xf+-&?|5H}ADwm4t(JHbN@BdS;s3 zV|PpY(e9Aj%R+Wp4`qLhxA`aSUFC83ULsy63`XJTp8c99%$4OMrX8L5bJD2t($zQW z?^_?%Z2m$2U9*9<8Nt^pl{)mYDq{rH6rw%BoO$cTmNGU(l>1>1eRdx5Hz$15IlAw5 zHDQI5nE)~W=}hR9c|xVAm^RcG-(sm0hl4It+&<-->hv^jURb@L%;4LzoXzBASg4Lm zjSnw5B$;CCq0RTkm9nCAGK|-+F3#6ma{V$6WFJLzzEI{``qNtTGF2gjX38z%1gg=F zk(l-;;to-&rFytWDDh%h<+0zL=F3kn^fCz7ufHrDT>bW;JzGzRK4Xnuxs8Fn|CFzP z#qZM9TlV4pnV;VEYPIZC(CXD2sh|V0k00LN+rW7_5qd`%D1(b(Dt-Y&gTZ=@D1-H2 z+2bIso1p_Dfh(IKJ_=r!84u|ELsp5EKo!hAgD^q|f09B%u?J#o^+Dh3!|0Fvy(B|D zZ-yH@c*!yp>Q(3yG6&%h1|%I`0`$SmwBEC}C=vq*E!|rDdgvzF2B;E9hg~B>#cZ7yudeFcCiAbn@h--L=g+p}L z@e2>=O&fn0R}0K{n&nGTl&=KZ|2OJMarAB4$QFZ8v5inaXv}tMbet(ukSQ#<0#;ot z5Y-)}X^5WoK_@B2P^Y3zjAA8C!oAOM=;WbTf79qpqOf6`7;wGEC&MVHM}$_|Q^%Hw zk(n6MuTc$tv8GdKz4x)T=y)Ho7~66WuN1;&G)#qnN{tuYS>c^eZ(FE-uXu~$ai-@o z^rliO$-*J!0fNGPjXJcB;tWOMfkHgYj6XuNj`I0qY~+>7VUgjywP6WGzv4*X@sq@f zLXz=CHX)ucVlgDRq<~5qMeTs4%5w)77f>A%$h_rCVyKL@GR2s5N1yuplGGDk`UYW+ zlF~dG>LA&+o+3z&@o($TBlq%!w@u*kN8(;Bt1ETswr5H+U zN9x$&%)}ST4h&hXS(XYh?srIN82qwk-osR=sUp^53e6+}%wWa*;lVM?BD3T*C~7s6w?kxE08|cBmS=x~q$=$i$zS(n4uSM3$Yi&}8t*NK#Qs=Ys zPDxB#Uf3$ATZBKu!DQ#0zP{k)SAV@R3?6Z0xW$i5lcww14hnG$QMRE~FQnBrpmwOE z%C!a;>L(|~^?)2SIs6@BsYgHrp~c!9#j=>!hMC1j&80~3 z=#1igb%C;>!V<*_m?|JOo(hk|vNR$*=?zOYJWI_+(7Q1-{bwO|RpoyT%C26NW%m>7 zJqlPhAfu~CJgf@yIQJEIDtDhNbqp;hr7H{6tb9FHPMr>OeI-L*5A{#9^SDU^Tnt$GHpw5+K4E}+06kjh2M zeEq8?w+W_$g#S8(&d1gg1r#ie1a$ZPmso)l+D*pgOZ;gFJ zT2DwrK&8c9{ztR)GpTV|)mzT@Ro9GlOiXNGEuYJnN-zli`N*WX4SIQ#Jnt_jIy;z_ zjP;9V>}3_2!8w%K`JG#L4beS%BN$w`7p7I9OdH14$Wwn@C3Z9JQKi7E3C9}J^?J#` zchVO)mqO8~SQ`kr0ko3f?St$Ll?xWH*v3AAcV$xVD=O;s>BnwTqnS`w4-cn^ZKGBNrAE_G5ejgrq!!XXnTR+aSuA0aLk|Zql3m|FVO0qI9 zAOXMoQqkBm(ipnih|_F|aBjIz&Gp_PA`T;P!=|~Wr-2mRT+q^dH=thQM>ElIt7zl< z{OTH93CS9YYQ~)??NzJr6xfS815yu(6J}R!fW}p~rD?GQ>{irkIg0P1Tbw(^JoG{_ zROu*i4VE%BGFBph8YJAI<_JU95!MTf9V5t-P{D%l+A8MTKA*M0_&QruJ5yeCUhLwi zPsJ&!^r<2GlzD)SYdb5*ny~L4ixv`!ac}$F08Oc`J-*jUE9hv`{`QnCxNwRDham-E z1XWmyQv_wzB#6g`=;I{i9+uqBnpzH^I1{FXkeBQ(B>H)@U$&RG^#PaG#5^FfUkqK{ zfz)6O_OuupQwOcbkS#0J9wEshupKnoZzrp(URHOrnYKT(AzF2(V5bc22flS?C@e=sC;jL9^g3rACWWn|0R>6yM4A{FCn=sElC#BAFWwS-g3`KoNF@pYS#^};`qZU>Jm8)x zZI&KmZ`~xDC={JjWNvi)8nD zk%E0Zp+m8`qixJult>64f`AW6%z^^psbQg?)A;OC5uq6|mYL9!Y4L;^>Dn1-*O_}i zXXHEaR^uo~ry;w}Y@_|GT7p_f4P6+Df@%#n!3QV!iX`PJ1h3#ne(NZlA;6R)wbUV% zBtFj9j5-;9Lzb==hY&If=TfFLQwm!A-6yPLYq+vfCRGCo9kQp)L5cjw-isUyED zf>(dZp1KqDV<>1QKTVraTMNzEQvgqEwfBqXob%eHnW1M$ymZ~Uc5nV$9QxgEiZXe- zUtV{`c)I!W4c~tV;-!BGVi-RYjA9)4#O*<{iM9SG%dw7@!jhVbWr~IZxbbqx;pJ3j zULLNIr0#1wR%@~J{udec#iGo4;mj`~29Z+rAQ@mq21!u|++jvgOdvtL_|!&}67-NV zZg}jj0_l_mIg3vI&6l6Ye&VVM$s((S+Lx}Pt}PMgxi?X+D+@3%oe@E@E%>aCR1yQO zo229c02XV?It(~epURIMpsy-qc1oVhT|L*SykuFcOqeG~{2eLp{r*?x; z{H&w=c-YPj>OF(a^TJD%9+hzDers|5)?@l*@5Q=0<(g{O`o)X)N^&hKw=sgOemW}| zMqNBLdHMR3ZKFcb-j*Buw}0^I{-AGf)%&=ie{18R)el_4#^TkFWt}y%jSa{BRA=36 z4c1PN;BT&SozJY^`LZ_o-2P&+k{k4K9WA$kvg!d0?)i_j{U7OaYmfFH zMeJ`4qc@}XH*Y0w7qQ}YgjTlly6W@aybcKNFSeSG{rCfk{!#I9E?2IvW@YD<)sD^n zPRH%tP~F`o%56@8ZTGI-)Ro<#;JuuwFZ={a-H9)&-jvq8-i)H$8NI!k-Idcz`4hwc z(IvL;~(40`3IIx(C0XADkv0{C#t9@#f(0_Q543 zepKcVI5+^~2j$%k36l=VCJs;E98ypnk>L*EdPfBEM>kdvpB_?Ku-svR(VCI`4>io~ z_KP>^7yo~#VWERxcc_l>)UcS|u>_tPPCAyBKSp}=bQd0tLQWL!;7gt-DsCrgNhca_ zPqZdZbPjMQdQ`s+?)?5QHEd@?bViVA_P?lMowq+7LxHCl0(WmP{hiZG%2O}5(^IQc zzqhByuTKL*{?UfL@Y-2D6( zU$%+A`Hz2PQ=Q*g1@Q`d?7Z7|8vPk^v?n=rzL0ZH(0*RSc9Hw%+|%R2J^4b){9;4q zqI|!w`_84R%q7rp5$khlcXDx@eEDqZ^5g0Sd)uYY(WQ;V6-(gNJ=!ZdgR42VtS@iR zQv|NR=POadNULKIKa#FNMb|vj*KEJ8w?nS?<#8AWT$?8jmz9FcY`|SU#%)u=00HkR$bL*CvPW?j-OFUm+_=g&1S4reDn_kCL!^UsyKTmIHWr{rcSYkHwLnl|-XMg?k z%%)y}LL?>kquDKk5{*~4pDfO9Kd3M$)h&JWX~($6tm*m2;-}q*bvFHp+~y`K)o!O9 zF}9coG*Uq`9}iEIf3nEfON9BJXH=EP*zD}v+V$c9NK3tWDAS=yV?p2xXsOXDT1k)I?CQ z$ryuQB6}s@%#1F_G8|LhZxcu1)~d|N#J|_D+-t|4{ir)gC=K^vFqH0MVQ;j3*9+u3 z2K;Ec8UVo%F^V}^M=FPkYA8jDrocDxynx4@yMR^2W*XDouf&Pz4vp|ZNM3}YrU0mp zT1%)Ef=cz|is>enfqcW}+IYhHUTa$zdJW&rkM|s*-slh=6#`8nSspqK71Ddr0&D;1 zNol1@pIrg}p;5EP{n;o3!tqxb$79Cd>)8SU}@tTs-(=kS985)42H1?*F z=S1qnj~qjV7Xb^qzPf1%f4V83Y&|kb$V`#%CEH1_`%C?J=M)?st+nKf8D51 zO7C6uLZ%$2hb^?hdT}W{G^W31w?jB|M9!DB9k6n`0T$PEC=V-sb+A#_SNdpALu)&0 zfPig?+Hbm%$*uDSTgA~Jr`s)95YJRpuB|B%aMRxYf*3MEp=RM7s?H1b90n~Q^YrO6 z5jR}-!YzFl9||y^^zncE;sNkYmg#|1>Yo*0uyN&2BQ#~==5mO~IVB!{!!mG=xw%s+&Q3Dmdch44kn|M^O#cc_eX zIEyABG9>>^vCl*9jermqq1de<7pmcXU zH7pJ(gle2o(G=-N;&vkB-h-mW#O;_|9f@ucg@uPK7jVm*Ab=#6{ljqfJ`R|UofxRTCxZ5jIQyv-jOiOJfn}YYDI`L?La_>Wl=4 zB*D+zf=~D{kBPi8`|asOQwz0$pl@u^>pJq2MyjDmgVbZ;M$ zRc5>jgC*kR-d2}>8ulC;21xyVv@kG0V;ujTP_AA{_-}X8KXR{ckA{?BR*dJKJ##ia zUhY-Z>T+~@88%v~9rb9oxS?8ULKF(#DU@_R`CfJfE#rINEPYzLUP&M#pdce`>;Uhp z3V7EyLgbnFl4T<6o%671FM~0Vdjl{M8hQkBkMXLZ1x#LMSlFmPtfzie|uGuKfNVP(h%N@t);)tO+3dr%Wnuk7k1X7S`iV&0__AoQQt_O&2wad3GcQ zFfvHoJ+ueQtkqIhfa2b5N6>$zh6?Cs(f9jH3s^Gu0M^t2BGJom8hd&>-UWqd7DTW5Y^g?CInH7OS*M`5CKZLWUW*Ye0Vsy` z2a`5Qc|@{$h_dx>YK;YP3XpM)J3ki#R+u-X=gkm9Lqv?;7;;yKD)0}K3MGL7)yA9k z2|uVfK%_%_x1HgmXPH;D3o6NY89`j<5KYKyxvlj~hC65fq+H1r2C5g3bw?6A9d~TX zU6_raRNrMQSZ;+u)rq%Igvrr=oaI(`ZoNX4aC$YwxUVbSrmpb~PaHGK9qN`^#H{Mv z#l*T-MA9<98{R-{OO0fL*~VL#vYvVFdk5NmA^6-UbplT`$n|E}oE(&jD$Ky+;8|x! ze>4wkpC|slSOw9cNrJ;`wbs!xiATe@jWxUXcV4t~aqhdJ$a2?+)TDqFSb}d& zFM}6ceMoI3CFP(U%U3S-ru-&bU`esusSRv+iozrKIQI(#uFqFRL0PmpxbmPp;8Sg| zPt7ySUGvR=`Oa&fx@gNiJKn(0x2Z%rbYs<)kh`vg<%ojdKuEN%Pft_RPM^nh}qzE*OlV15C{R|X#o+%n03aJ zOM03`?BHFQoB+H+bv~n)dUp*7*IdIXQP@lm@;f2W^L=IHR{$Y}z|og5?KRrZSP{w) z9M$eBl5y6Zh;e8w!5FGcy@5Bx_J#F#$o@kO=R%1qqO}Q7CJtqWQg=cTk)aGxPg~er zg`v|-=+kycC@dnR;H|EdfZHTfgUlNOK?NFF1<+V%h(GboAmW!pZ1(Pi3rv|#0O7(+ z^gIEIj23+=7T(IpsAWp5@s~KzK_N(rm{wbn+oEUkUU-N;m;tTGV4X#u+r3cH%{11{ z0zsW#lE%XD=P{re|XJFXcikPx&R>z0KF6@WQ0a|oJCV2_|FcE%;aM)Sh z?GCZfGbI2Eu`3K^se^nGQ#Nr?d8m93v=HGsNsMQEU0V6vFr9d{mlFgmT}UqOys^cr zy@#FmjRfRrm9B~td{9yIfhrF1s*d9Adi2qb9jY#4s@NHb7$V&lDdbA7hNp&`l_EW{ z(a!=J%d4v^+~o!C;^gx3^5WtGcYgK{*?V^O zFVlPe_Y80Mp5x`-v$J!&-Fx;EFZkl&UfjQM@A2`~$;sKTU)Lw!@s#hscJKAk&e74) z)xnQ{1>b}H{j0sbgWdJZ%}w0S!1a31&!0bcc6PS5w*E``Uf~hnPjk4bslQWG*DK|? z*_dztk$wNS=KH@X->Io7+{DD+$;rR?>%`c}#Kig7_}_o+-jCyd$NT=}d;bm$od1vD z`(M7d^t`+Byc>-hbH@!>Uv|0TK4_jbH($IDx@^+HHH%-@-(H;fXN`}KkByCujEpSz z_YV#Z_Vx93cXwm4*niaCuC9O7-nO>p|ERr=B!M~O*z z%6B|1a6dBY%HQ$I$?m}a#jcC%^<#tU2Rb{}HrqzV|MI<=nVD&6Y01gS2?+`R^1WeU zVgG--*U!(-$H&LR!vhcZy1KeLIXOLj`qa+O&f3}<5BFMGS>f&8NB>cHjf{*84GsTQ zczT!q@;vIBIV`f<>cgKWo4zMrT^b*FE=+g7Z(=?2L}RyU}IxrWo2byVPR%w7Kg!@ zn3(A4>2Kb=i6?t$XlU?iFAN5wqN4hj>?I>3`!CargMjgH?+zGDj9&miL_|bLNC<&I zz+f-|0Raf#kA^28aR3O)tX@~p9S)@tuo$YtZy{iunz`!rMg4K~Vou9L^~Hlp2>z(^ zW>UP)_2ox`9k=ZoljFh1Qbl2mdSl?aBK)%Vr`26)_Ha@b&BltUV)ax3%aJtpFtNK< z>Uo+?RiCO&-#L95X{w(8zscU8rcBQq81I8A%{ADYx3>Ie#?z4;e^q~4zY}_egl#$y zg1FwMA|);ruY^nW)MrLB#hh2hTHkF>P)uAh>9jR&&s039wi<71+MTbn8-1f^5z3GOJPaP)dz z9eFm-5e^=f-t9$ zgW7~qzqw%(>0pWeYR357)Fk?0%+qj#h6)0d2a!igBC<;P`?S0(Agpy8+pzy zkfqjk`jGXj!zGOJO~>_Qb)L%g6z#ia>tq?7hZAI^vxR^I#P|hwI)UTxlMIt!5>$po zirLf5$JsHMG<|A9^}DpW{>#W)Xs=kL`w7hu=(h5)9s&^lo`*zU9)p2%KmfzLMXwy| zc;}LLyCluTX}dJ@Y1MXF?m6!hEuH#G9*5#!ld5OszUezps~ci}WSR5e`gjcP7AQp^ z`6wX-5+i-2vG*?f#HQIoDM^uq(L6G+V)+zaZm6y5t)GpvCeF1=h)b|*#e?@%Sl4}1%ej+P)zr@>GuTbeLnpp(kJad zo5&^i4trr#rS558s#1=B-?$Hkbrj7FsX z=r(WgFM#yP5(qTx_7rH;1o31qovS#YAjZ8@O{~9mGNZ31^n2Fmp{oQT>)6-sPZoaT zO`W8L?P&{|$q8wnpT%9)E^;$PetYwIYqDqAI$Bg2R=hP6jpWG1iD|(?`o7ZxPJ7^3 zsuH90y7y|5`)A)V&gmzHT8}>;P-Q-Q^A|tsxBqvuz>YG40U7c9e7n3IfmFmNLbe&a zrMc0*=M+8qCrzVpVZc!mx~_fiSf7Si;qDi^L|yRJl#bjY&~(<5taj(>WY%1~)$kQ~ zt%pj$Xzlmun)!G)DRYFI-29D-!*H^idAT#qo#SgwA5Iz7PQX1}u; z3itv0HZcGvJ?!Z$@!jyT=X_MOnh+&X1=10>V6I+EfPolG8E_b`OtWSnpccwzw1y%X z8~gBQ151`T9{D8PX7O-dgwZp~k}>x+RAH!>^}J5(o**d+E(EJMfzS`l;J1Ol8R2I!7(J&M*{);0if{QsWtoN3tUXuS< z36EsVFy_#Jzcm0!X7Uh&d}NOay5LkKkHILvpN!(vn&D!X(t6b6>DoN|cwMG-*y{XO zbjRfoua_imL}mj=g+25Z)whu_=h0zC^C?G_$g z)mKml1ZSu|XAa6_Plc)_4-|ksHj!2Q@I=+VVk(fM`dfxH&5t5+E83Ns_o2F*L!rd? zr6T3R+&LbO)e_*?;4e>t3(=x^`+yYLx5@w8XBg_kL!)?z5Vk@vi+DHX&?%gh%)zB%Z1exSSq z>$=-lvS@)vfCHy<4eeQSFf__?jwl7GKlPY|8hhSdQ!pRb!(jUzd2a;lVV|A(=wTwo zS+`uM_;+2xWYt?OUM7sMzOr?44vA7I&WqrZXTt)%?7Eg`nv;)+W=MB%X_9Cye~WT& zp^*jP*#0Zlw{4{^}cr6-(hwNU_oDx z1V3^+mZUSH?k{Yf30mtM535VT3sk#p$tDT8@hq#GX<1Q6>2&=hB@c66}nAT z565>*+Rs0g{sD_(;3TF?=W}%{${0Usdwe9?e7-^hlC=&jR=~kB&W$#dUJ~5xnd@Et z{XDW<=ckkTQpdOhVIc17icVv1N9mC2OWqD^w##sed6U`~<)PM|#ScM0078&eA-U6I zsa}phB1xw&zcCzNtcqR>V~HtkU()3EB~}oNy4To-vt6!IZVF?B`0aZMF22#b#nzEc zll%Ctv2CW^xaWM2_My>tqFXq9f%{9{#V&mAS&cw6o4Y%a!5DkZvA!~urp+9_Eu5lA zIGiFyOx6HhOnj^0vFp_ctn5zT_Rrl~)gS{Z?RcXd5yQ-hY?5< zY`h<~0-?1k3M@5lR>W%|szNL#&lUY#SNgH`D%=48C|MuU1d?8%xGk8ti6|`dN-b zRG^qL;LF6JD;dha%hj2O)NgI63-M_{_~3l*MgqF#L~#EaH9&t2M%z>Oa|plT2+V88~*YtHh_^I3Cr&= z;Ya+_CJg8#YxeA;3Zeti15plZ|8|5S4U^J7)J5I(dx8W#+tn75dJgG#51%NA1$AC zaH6$N2wI1=B|JwePI)c{eiVa%YZgP)i~R#jx3r%^b-MXxvK{|_sEeMm+btgy~#jj_^vKxTK9m0uYFfu+dPU;D}Qpu}a z$*vej*SUG}0wBHdHY-i8OxHZ)`-QRrOXG?g*^-0~+X>^) zeBmC882G1Ye-OmSug{BKjQD6a>PIgmg;^TxUCf|1OV-=1i&G|wLU)6 zB=^o=)caTIh^f@F%q*6AP=r2Jk1&w$n7YK9odC`#Yt5T4%A>GJ(_wi14Y!>}+D%@A zfCUeGzSHmnCc(HmBJ!`~Rg{F1_pKt=U*g#jwv8&D^mKN z_pZD^ZOYe;H;Jn4HQdS1zuYhA8I04N>Sz+g^eD^cNfFCPKBEHon}5_CL+-*0@!KOs z`XdZ_RldTDFHbk)PG4k!)k|L7pti9lm#8RFm4SVvPgZ6qb=VPp;FS1C(bIDwj+(Dz zc(~M3ri?C>U@C^38&Rg=kXW8oh6=EFMoQh%Lc3^6%N+2~yUHAdBL&QnJ|=_Z_Kq=p zJ0${)6`3R4&ZLp90_BgO?c^M<{$ST@sd>|`h%}bd|Iyhhp zkZ*2=CA0;PoX3yLyqPtuCK6HRg)q*@(B4uGT3rk+Jy$%>B8Vt>p|V!1{HUy0x?+9t zt(MK3v?^}G5`sS&4CL!?js)If1>lyb(5}NY?zWQi?4rw^w>O<>0jBKc0Pdxk`@$GkV9nEz|$8XL?;7r2MAA?ZAp$4Jdau?i-dZ`=+2CcF^NY+xg43eqw zpZQVFM%5gdlJ!)Q93O!T*dtip2?8Y%Sc@lir30I+PHLEv?-NXkb6+$WrAnBC-*YV? zp-YWrv9+`|fFDqKC{VBCBz`Zh$@E^cc3Ztxb>PtX!@wo)mrQq?C2GVg@ROhAe$Gwa zIW0C1>sh*+qN*z#s_T+2V2g}-1CtSAId478#eJ(=ZaOz7YBgm`w$=IBdq-RQ13MPYVFgR?#&?xhaptJ6=CDVYw%-Vn^izCTcO<&KbDt?B zo~(Aoxh+1sd9A&jS_I?|%llmr|H-+9#<}w7q6@OzIimH!F{d39_W^DI4o8KyBMNrR z^X^`RLV~(sHrO{ZCEs(xX~t4RavE;Jiz2YKk%;b|YS?Wg*{(3vXKNz(Oe=kE86$HK z#~8LntBo)#T3i?!rB5|jm%5$P163gS3XnZRfvf3yKi})EH}7Rz#>jN^{$WykK~F?w zL1mBbnahDytZ^*d!|J+p=v(xgxD2o^ck`|FTJL08kYkHlDXOf=wyi1fgpR1}fZ(G6 z7VUcm7O5}Esen?llu>cV%vkW)k-UrZkgPSNPh5{C9avJQ?I z9d{4v43iPELXvm7m&yx;DZE50U410EoD^o6aLy$T0D=Z~X3IKS4TOZq4$1m}j)z~u zdw6u$?R5zhK(%$0hwfy8hegEkv$=coug5-tr|?gJFmtk2Y%Nb(PB zV`&MfhiFrd0;*sH>_j7If6mhlXL_BPj z6j(j~;zpomOGCF*z)sSKA(>D3(pYV;O+*`wp@JAtM1AEe3w_dJ^7Ur$SNhjq8N0qR zuY6@)aZDD5`oTzkBdJ0Tzw*8QW>)4rVL3fb4eo=HGrnBgZ}#YWijUM^qhkHK#=72B3B)4o8CTep%I9S!YRKr;eUWw4Br^Bw~S3bMcf*lDC9-h4HV-hakCtQojHtOu+O!={LNzfS@QG zFN@Z#a--b5{qqxmYV#KcMJEKO?k^K0a%UsSlj^pI27^8lznmrpd^;(RP-LBzKVq+{ zRTWIz@2Cu-xF6y?nn%HASn(ol+7@6V3KGKL$!*5k|htqlRnA;DKSB zH3dN^_^5zXevRZ3=1GSBscu7(a&>4;cO>1huS$i_`&eWufG~_7y|<$6HDK=Nf(_)-s@vPd7X?V~HL8akj$i|_QB=pgAz`ECoZ@5jRHv!=&mGH`C)6RM5zB-C zlH`%g5q5c>&VVD<7$(30V=bU8IRtLhkuD)=q%c%D?f{21*%$&gCCnSUMmbJIFwrAS zh@CT@{KKGj@@aYRqudcL2UaKxeKy zRnFA^su)GVA{Rk#@J%`PhLBZX=Kqkr%Fu6YPz>GU%fP~d#IO`0P=)*duoA+xFbP;z*lD9aek!?r|{;hx3inYI0J z8pRwvEe|R_;6(SN=~AlkK`CoQ?oC72bQpjryZ;?^ID?Z05y7$dAjlg{;kU0VK^TE0 zg-4_7H`85?;37K1dGgV$mNF-;Q3g>@0TxbBzF0X%~KEuw5y_r@0=YbGNtTa zj0r)VK6^J}lRgc0n#hNZISmp5D~Hc$Sw~EHa!CO!`)i}1!-#yT#A0WeXlumN%n8Bu zIwdN3$Wh@Ad1x+-0Qz1s1ho5E$RcTD0P+otq?X~_YLXT0j{Zo<$+ zhefmUtR`}TK1ToP;r{6G#X6pRH)=S%6$YP(CesQBH#Jl z?GaMMTOxq8k~ovVecgSqe5ht84Uj+d+&SC-cc9o6MyjF-I7nc)rVAZK!m7X zEb5~*y~OxU9Tgvw9syc08e1+8JlXs9clBJ?^G`<)tzSKvS;Bhu^Ec=mWv+FcEQ0BD zpT6jOFCo-_QZ#x0d%xu4mm<^Ycbon~yGCWX;a{7vKN%7*Fl5V>d=VxD36 zXTQ@E#^fL2Gh|0U-_hoFFeX21R=`m@^@Xs4)}|(j?o(^RfE}e!1z`g!O)l36okF%b zL3$oXo!W58KAZG{-xUX02kv*oZAeCaF+$`;WJIB$`#bDlx|@3JO{t%V^B=smir|iZ z*jJ=bGL#Iv>*4$B;u{Q97pg$c5ec{}-}hx#P|WfMyv65I`Fyf+L?6W5@kk#3WV(nGaXZ2)c@>fw!VSsznB;kjX^xs*q(4Z)5k zShQ+SbWd}n3tHUv;n%VFh!aJTu9fhDCb4#DYuR&+41~MQO3E6FUSrDTtGQ-y2Oizb zM#!^i|4PN1q;6@wwB_W(Bo*}JeL33@zR5X_WZ&2Od4FX2-Zs2Ywfm$LzUsm$cO)^{ zZTc1l>gOBc6G#qwO%+c<@wDZ~c8d@DNwM%)IsYk1g$j%_gdwuB>n>w*;auK?V8U6?DqW`#W6lcF>PLYA`#4u2W2MirGb@|Y+j@Wg|S5Bsb)Pa8GdJg($S-7r#O>`Rq<29BD13PK%qb%)MW$7efQpXgU8z54VvZsb<~^dsY{ zu-UjNhDz2Q19GxipDLUmp`dAZTBwQ0*S8ruM%KJ&EM&!#H&=+n!BufQ+x`I`00j(` zH%xmJO$@TH;<(Wujj_2uZYi}IMy?u*M@R2buYdmZj%|s~bU)6waJ|LYJ|?p?aD3rzQ5CBBMrW(7xNtKEIhB` zrejE@l&{DKJg8)C2e?dIsaK$}5=Gxi^`#nb|3D*bQu+dD6?%t^-J>UB`QlO*24h4- zh;3gXI*($zv6mj7yYjz zGX$i&_1*?*#1M`5vMW{@Hpy;wx_?Hr2|doL*IM{caLDb0QNHj0wSy@~eDL{-NKxAf zR7Ns@*OziLg_pxIMqh>_JqlWuB#B<{?4y!s+sZEHU)Z=QF@;*JE@bZ9Nk=kH%*=}A zc*tgcY8pq74ndCXc{V860s_i;Xr9D)KuqYCIN!W~UPxBG*F^a=lxPa5c-OwUlit>W z!rcFR5Kcn9YjNIT;SzX8r~AD(b=K$Z2Q zq-3ly&sqrNg%*ygtEFAdm=>3BdoA(q+K^KyFBj0@emD8fi6xxovU}juJ?4;}&FEn*LOY0{IsoFYf=!BYwFe|Mry0g5~Y%O3Di5wokrWGBAQ3P>_K~vorTFx0pit zudi@PI(XE~hss;ag^&#ko@SvX$KUs=m#1T^Qcf%mQ&sx>#2FfcvnUkHfKb;&wX# zTI?_zx!a+U^VB23Kc z0F^i+=2)nq(-z^g5aD;J$BU(X*!X+GsBo+-*+O^3nPS9YszC3}OLoPC<9rhbV%%M+ zR>G-J1L1I{f^at!QE0IuN4pZ|s1nzb68COzI6alEG&DNAML0KJKDW{DNTDWAMA<2d@{tPK#+mS~^3QlI7nWzoKL##rS5 zrMq|DNheV^msZE+^CgA1prS+bjV{G*#rLp!_d6GI+=}hD%~7$oA299^e>NtrJR3HK z5C>2Yp9d;7xr(keiiWpTowJH%G*zF>B5(id(|5V6-`8I(TpNx>MUymH*Qn&gzK)u_ z&;B)POkhyxbE^lJ8bXld)rFu#5c=u5s;sPf1U{x?GUDJeO(|f)M8_)p}!6 z4aG&nqt9*fOHIvOHH@nTT>=fyRZBb+3zq`fqv%CwHEslH+{_(XZYNUhqqASkNpfk# za1AT(X_#CNKO-M;h#z_;h8|=P&tM)2i`QUrQHhO@_BtbaR2LdQOGhv>oVToYUuMvU zR;A=vGpnL06O5wQ=kV|zN?jJ}J_lXI;Y(!U@`x}g43Wnnpd2cW1w`PZnrz=Sn#RP^ znVP!%vvrGke*?W`>k93Q_YED;aQA2(>}c(B3hVBu;DuIqT8sJRNS+j3Lt5BJRA1xl zSPs+M_b%cN$?pAf9|@s0UATUY-4=2>{$n~>d6YWg-4>99LzFjG9XULT zH5K3F64|0{8lN5aPK!a-C;--|)<;5L_da&ls6|yodJPeKRS=#(`1n$zsmoUHx97xm zn(oImy^Nur7i8kr4ua(tBgyt-DzcsP5Lz3~_Yljsgg*K^ed9#6B$nb-T(-lXw8qFH zHRxVxxRtadPThr37%awfKVsGm2-2IWiE*5b569M(#80ujs=6L)O^j)NoGHmvD+Eu_ zqo&Z}CyenGM^Dy>kV{NAyb_=>!dj{WJ-f{iRi#K;S33 zObkt30k@u>zKWPoekqw`a9^!cP+jGLM(ON>FKDk;-IQ;UmbVObe;eqr@M1LN4X$n( z{(fL2@k#s&4XH>C$4+y@G_es)xAP2=z9P+qZdv3RSqT|mr^N^^D+21kDT!_o*W4?m zX}v3Yb|aGpTNBGj6QVE1@tMFcbpvM$!LFbw7nY%{b(18KUbiPz?mlxCo%2uo(T-{G z8@18?eRDz-W3G9|7>~ZGl6h3ayeG>%e0)B>ZW;hy;Vdf#P?5&UKSgCe(V1#5#6Mby zN|=tm@i~s3UtclmN8^IhhCy!J!z2v}`@IG4^99`mBaFmMyt)RxKZ_2brXR&^JLB0T zME~y8=$^gO8&1YCCuVT`?R6=x;>OGv{eBZe3T^6ga-r3a& z(R*9H_ZpoDB1MnRuGNX&39HxWod~N-)1t>0k?5kgkbV8;d7pXTKj5D0p1J3qx#m1S zpX2Zv!0&`a+Msb+0#UD<@KDkQRy#;&Q?zd!p~X7B>;O;cNaF9cL|^tg-t;cu;49W$j8rmgU3ZCh5}8XQF7W>0cr?QBiC7AvzVQ zc;?XFQdO{l76IxQ;17)^s79DC#vGDHKZNwWz_FG_K$Lr8XIx^GV{eBXA(=i61O>f$ z%ekpwl4a-QlNHBKG(+#GT{N=#_mxw?5Fva#rlD&MWd-z>jz&QuJ$GWm*YVkb0Lv}{ z4=Y@LZ+z4azOgh|<~kNnIWB~nlG2qL*rZ3@&q4Fsgo*4atvy)D27oOch)Q_xB+9z@ zMS+M39@~GoF^|T778g&1#(yG>5^utLWd*Ukjy)4Z!SN9f<12oAr@u@ajZUE7$D7oZ z4*7e_Y3)xc)a?_zto`|7R0Oq0UQWv>Bvj`Tg;yukjVHX{AwpdfJz`93;f)THjw8B` zT|RU~A&AXS@~NQs&g)y6M^NF{PwDP8IA4t3dpCSU%t6Ew(rT;k-=4|BAzku-2~dJUdbK*n~@zy7=$@XWR1nBul6 zC1aNS-!VCW0)o?o@6P+MbH;aVvLir32nU}v!l=!~wwYDjuwR~SkKwJvrq1I4XdJ4i zT#B}f?N-W;DWFRVoRXBB#_4Na(E-u~R*Q}(H07hg^k{rWi=g4ym>sPcF!J2pKimDM ze;nz$0|4CiRN6)%$yC)`a-l`1X~U}E-?PGwp|XEl$(75Wqc;Gl5A1lWWZIvOqfTL) zO#D9PRrAGhm2S1kYi;T!l!0A=tQyZ~TZ1k5`t!;bVf)&VdpwyQ6;UrlsTMKJ2%6Jq zs(zI=TE{>^tET4J-Zi$?wcYs9{|dt5zV&IiII>5H9X!Kd&c@5<34A>I`k+rk+3@%N z=j46Cif{Fmk3Jsl`TyHXq?fU#ID`yNtm7RXcpuchKExJ%{V#fbfhw>|*XSo^?XdNq zdm@6s3XuFQ?+_CI-^%FWZwuiJ@mKS%8!t+qKeR;Ji?kuQ&rZXSP4wgMWB$AlT-D=n^V!##Jv-!Fc@TQ%6f zn}3z1ASGZ_>ht?(@A9=2e!O89L4;PUiILm{uh&ksIp{wYJf(x9qT@t;gwsZ3x6V(z zoIm((OK%;KMvF0lXgn!t&@17ct?T1$Eenc2%#>q)=mJjSzhY=`Vh%fAkN0of&x4g9 ze_k9%QAmSXrUO%s3MlEQPJC=AWL7P`j``YlbdssS9O!$h^sV!t724o)Ou5NbyFOncv^NH z10e7^j`ijZ_S%Vg=H)NIa|sz-PP<}&P!FQqFHwj$As>}OBOc5leGON){ZFr(KK3^A zgpA|31rdp0wARRwx)!%Ve)?A8#H$Q9|6i~f z7%S3~`_OCjWmx$h)9e4~zt61mB+enidgglcKu3YIksaAK5v@sHRayW)y`9e|nk-=w zk!%SCiSMG*QM&rF&%=(tu)q1SwO|;-^2>)u&y@tmThG*1&p`g;u?~Pz4J5B;`Oc_6 zW%Yy9e>~HmM1tUZ3F(EGD<0Af2Qb!pIM=ZX1I#*ZzhjeeC~QX715%FfU-e;C3J?sL zO$49|!h=#2?j9AtWMV=zjUL zTDcL~gT~pOu1-Qn6Y^zLIiTVEV{LD*CdbyMq2kSXMk08mtcXw~T^QTHD~^8rDRV_-i3}MK6Wp9(yGQi;JPZ^asdf9wW&776)Gxj!6k6H2{u#*MGQ+a+{zr zEVD+@{N)>DW~)L0(_$r|w+P-~ac4;2A{=-^H`I9(Yeu=cf)lPx!spl&t6%ozk)Cp@ z$v|n;d$~S%9ppg`zEVFI4O3l z%2>~KJ}eA0$MeyvvCeU;Gx&I>jP-1+wWuZ?LR&IROZ9nw4<@KGN79^N!FZfJ@hVS> zD$~!KqVR`>!4uOhZ$HR`uN7NR(q;fa1=ZFrWgFB~RLo%h2K69PC3}7cQwXbNUu@!& ze3kyTK$s6uy4M^h>+S?;Pb?Rb+SSgiMl<}|(Ih)BC349p!=Icq5j)%EF!~1y-nrWr zI&4AgPpgs>t*f%)8;c-nP1A?0p<1rZNpyW2Mcxl%X#LL0u-(=&sm&_AJBF#4O5ew{ zU96&dn*bnXQ~5hTUggO6G+zi1K!XP-+xsmOVh4G~f5vOX0Gi2-%Pc1uDYFxX7e3Wf zhDvzBNbG{;a&hoV*@84HUwg!SeULGjKLVaQL*|-;$LfUm_^~D_w=+Eh>o4U&1NcXP zktdA)3>)Li#yDLc9QW zvmOhz&LXgq>oI;xc90)02V2MDsEk&JDU*|t-v|0!r>DKvD1fK`!j{WZhPo_1`lrq& zxByb&2?9^Q9p3x)g|tX-x{_-BSm7^fNiLs5)RRlR|qKMAK(_uGWV-=K8fhES}JJA zhd43qR0qxM4kx!pVx`ZOj@2Mc=(0*XT49x7qlDK7C@U~!=9uVads5hW$=v>z`gakO0IUXeEZt{*FcD?XlvP>O>aU{qdc!0LIk@D9 zO7*BflyI6@{U-BC^+>a!TfDGj?|=Nw$qep5QR__Lhu`5uJ>Ts1W4S`1Bw!vcO2<@S zloKNExwIA;E9G0a(2ukyr^=lAyU(DTk~fm?JR*^X5v{8naj)W?jRjru#z6QfWdt0d zuBlaPu-XXw>r9a~Z#0434{Bhy@}2Tq!>08nx6$?d^ZC=7r%{p?{jy;BW55e+QmuG| zHuanNIn>Mbcw!pxSSR~=O1a&khSEghyCOTb9*a%0kAKzN&%TBqfB3V>i}%ur^6W*( zyJPhyQNy7pE0G{{i`|sW^1@nLhauMfG%MmSUvc;#b2jKtktX;RM48M~dW!nz&M@yH zg-7Wc?TUj`sGe}W6A340SI}|LR=mCYC6RtWVD#*#t8A!ISpRiJv!z(AOsbMNE+BSY zL(9hDxoz|H6GA_S8}I5z!v@~WaMY@+#Q}F#NsDYvE*5t962}&r9fzZ z`@O3FwJ{~`BNkL9xa29l)znp5v3i^Xka8X9Y+nufZ|z_O+5F%3w1!mb6dbK0)s!Hk z<`CS?dhm`>Cr~*afFjXT^CFGpCPg1jGyZA+B3q;ODsO2uo&r|G3<_p_^&m`j9D3A; zkyyoL0l;}aQ|-T6KfhSJ55uYfb`s+2SC#$P9)#vV6E$ib7>-3$PI**dT27D?ofzSO z#&_u269O`Hq&^x$N^eVJ;zU#nB?wo;88%i>V^$B$J>*qmlpUrvP-ERJxhVmmWawGo zxlvB}d?k89U?_bDGj8qh`bIH zJ_!U_o*FwpyWxAFpw^H-OXP2tPu$BJjFl@y)@nA!F<7oB;O88kjuMK!Y(2Z-0tyiM zI0IjHx(&pE|JJ5$eCW}ts(cVm$9cy6F9%`8O?7IZ3k{0WN=+tSnZ?Ihklj`$zbu%v zOdXM5on|e{PDujCzC9Ix`f)l&;&@R%3t2br%;W5=l>SrD00h3xR=3)`ymO{#aonhR zs(uY@(`IUaxBB;BMRb~@^~(gqni(0iOoDQQf`3cXASy(#M4cY-SfNCz=;st3=g+ov zZP4lfO`)2op*(+qx_$YF&>^NpGkKUwy7VyP7DnbywVhB+0J^Mn4I=%*PW_KVuw_fx z%SORA@`rg;-P@-+I2>9;KmUA~V80|)UvsH?`1`NF%2f}-%7=LL)R+q~4K!SU;YiUo zfL%JmM}&(=1Kb-zNg+}(7y~nQ&-i41&cJr@($YoQKK*_1%xC*9Y z07(yNd6d#;EDG`jWK54d+07xNnB8b~|R7I{_RjLhV=DJAJ`KN`)Ph}D_Z?8G^ zuI27wZf9~6Z)a}>?j&O-y(4It!GDOZg-aEtio zmegNeDqD?sTwBKNUaDAIs<9U-OZH4pIi|-N+~i)SQ(JCQTUE+sk+ z0Nlc`)=Mz%8vsMh4tE0R|vP94acc8vqC| zq7>$Eg$3*vPshKwg{Ign_vR#4T+_W!9y`J%v3l7LqYe5-nSSzFw$;5(w!(u-0Toz zEiCp7LAIM`n+cb>8xk|BABj9cX8zGE6k=|C%t;i52ZL^^?0X9EXMR(O^l~yO3fqZ#K+v|Z6u5C%BINlHt-zQONQ}Kt*<^}VRO<0sN zKl35xxT^>1>cQ>iQ{qH1BP?KJJC0G>nNy80lj50|D)4#kVF4JX5Ka1_+0`Q0-?Ta^ ztV_@1gF(MMEO_kx-Xc`B^n7P6(Q(X?xzgyqnc*xapg*sZQZ_NNZD7715VrDoJ#H$<38pT7H>4O7 z80r?NbI@S{mZlK~<^*)-M9AdEcIT$ZY#zw-akM#lvN@&EhB4R^rK-mt_2-QIndD(K!o^nIk3d^1fhn{jC zWfo3gWk63=#BBu+l3Sdj+OmfNJjH4TEHdqS8julmbrZLp0oc-2p9HboF`BUTyyOg4 z7w9n+53V8TZL;a9^u29j``c`(;tj`XQI(~0q@*<(tc~p~YHfc&8YWi+&`_%@j#oA0 zWEB@jH45Q1N%eL|1UDD=_BcHBo976)3jfk@&d~`Y+qQ%1{*VXppq(GzyzN#O^12?% zyy)Zz?kam6_MdupV=u<-wo<5X=o_N;yQ+{lvYP|>I2uVY^|!6;jpsvV|C5N`SdZc} z__I&Ll6Sc7B=TK}eR>%p&pGdg9)nB zqc=vjRJZBo4wjVEPx=xxnhtky;C-IG>;BgFouiksTKMh$U6TVaDE3)27mLGDCs*?vZBHq(>*U+pPgCQJcr!;_J=0iRMvyACOM=n5?G$0(EeWtcB?m_ zXA5WM19=vL>_fZG`9R49ws!ST&(DD2IXb+xvxjH;w?le3^)^Wmiq$BjjEwTeLda4; zs9mdAhj0E4C|H+QLdG^cK<(ZxJ8(NzvAUrDk7Y0na8-sIQRN2Auv0E)QXI29-yb`% ziw&*%(v#8vqF~NvSpTs53g z3SSnp34S50Me<9^9eZih`RNfp+`St2nT9fofP&ksE7eIgN_&sfTRP2oBvL2vJ1*@A zR4tyCn6X(*i-a;tuUZ_?l>SUNN5~1s$VgLJuRzNCcbiOWr9rV0aP?)(e}RXXEtApm2vgaiMd?W zbN`x&KIHqqSg=w+B`4lo==6qr{}e1N2vF9z*i#Osr)bQQM|JVK6lPuS|Na^~ugJ)9 zWU~AGsl$SS<%F=aNntR!_g!evS!%0qk$%|U!?izGl(8u`-QgE<2ud2HkJzFcMl~*XZt3>cOfqC$G%gyeN`=EW}eY15Z#HU*FNV(@S0;N*T?y4 zI2*?&)WjRrX#Uep(~V6UC@*rZG#b~9X`pvW6`-Fysby0}iG5`WDsQd8tDD=Ml&?CE z%vB;Ltc`9`*_fSDm08JX5csrm`f2rRs9A~5UP)EzwPOBwyc|BT3?}tHJwwb`vz@Ak z;wgs8IG5VaUsdbh)?{6A%Z(c=j_nuog?ekdL}N;V^tMi|XbCNHm%Y3wm@_$LjRub* zjgh7qvG@i21=X;{cRS!tmd$ByTvo15_$^1hSiipIkK#W4{e{a&L0T!-=&(|C`(!JN z(U^WXR6*17_)|LUnK)3=1zy9fP$ zT|Oq-Vd&`2-Z4Hnylq=c2j9uc3obYq_RTdtv6en66N-3Ch$e=6m{g9$(BV>;13} zxu7vp>0fg)?pA8t^5BN4>|*`{w-g!_l0xBElE#IG_*qJSr8}O%ln#5r!RON?Fe=5C zjfS`kq;36!oF|KUo!QA)nPFompF@@_zWxb2)w@Ne>glJ#W_|yW)VsyjIT<2w&e*?T z2X@+3*-em=Tl366>8X`QbRIefYf5tvZT(36bd8#y9!Fq|{O?iXaT8iC6Bm%M{39Xj zBt3SDPOYXq%_J$#pWL(TfV2DO^derWR*FbnCxgli^&1y=l_wvKZ`BFQhAhXA0_aum z9wkQmF$jFej69w(u}OAW6pVdNOMiS|m=7iv#N-*YQ)lpwf%HZ5IzRX8m9mZNHYDro(rPYj;mvC)!I@0g!zi@IukoSFO)wkB?z8Vr3_xu z|9)xIV_|Lj0{6lm?l$&CgK;h!9PMtAu9oBj;h+bG?CKY=8>5Xf#b`e;X(-QNKL;N; zr&ec9^W!e$gyX0e;HvRm>jlq5ijoydM-#EFpQPkj%+%U(>EJG;CQ4o+xo~(#WPVSR zuu`|xSf23BB0MMt=*x)0_&z(CZRb?jbJvQ7);?SI7_UkAR%hviRBXGgavVT6y}eJ> zMN!6@o^PsqQa#Ic$AIMXEG z9_nJw@|TKo^(Wgk#FE>GX*Gwrx#bbXfDF8ul42DXQvA!x;nV4S+K4~93YUimM`V=3 z^%!RZ7vBcD_sepOW#4zF-B+-OOie13)oFK7<*7N|MQu)3_Lo7W@c~MAZ1regb992A zvW8vkXY=4UZ^3Vmy~I;BQ!NFK$yHLs^6#FPyc!k)2p=a}T{r{J zNMDCpmc~SMA-FoKM|9Z%I1JczHmP+ui!>U*@+Wsp;qoK}$?O8VvI601W75(JUATnu zCiLH&W@N2K$%+Ff&BITh!<>Hc=rS}unG($`F~TDy$@{F>@16Xq&{d-G=JSg;X9cKL zSLts-Uwz0?&QTsBs}S(r27~}?bLkEy_fo2 z-!p&q-Q{_eGK+_CO8#7hQroNzzRl^COkXpqy(Oq5*ub67eI_6+R^sjQc zBT4_SQNsHrRW_qdxdnrAx_$0A=*jI8yaIB!DeKEcsuM zmt1vfO;c)ZM^h7cfEJ^|oF94Rto~}!DB~-HJH}Hq=~y>8<(DjxR5FyrictNwG5^%- z;?hX&Hnp)MrAhB4i0F_l9|+9Hxu0^kpcP4G6cNK1=q@&q$~jX#a;CE_uRd3aru<3! zUnk1ax^Q?Ao+@X^w^(lS-hzA~mlrLl*jQsxcx7eVwZ zWJI0S^q-7LC)lZ-_Q|!4yOJLZtPSuBC~NZ@F>b^$j&PGcKY83TO&au+Fv{uX4s$Ng z71fcJDmzV2Fva}sgnn9>A(~j{-yn;{IzN#kew-6M{U_E>V73=yjL2xVzsAhI9Aw1^ zvUiQWTBiyIUOe2dNtT&&&)P1CeBpNJ(rBJNbM z>66eg5m?zV6$Ll9thPQ(0Oo%tWltdVmWw*=lM4~IHkRs4`;gwb|#tbL?ya% z_l!&wQP={bqhyIS=5{b5#xm`b1n#qS00lt@9M0R+9P~Kg3%I*i=<4MuoCJ~7f zq-k8Rpyly?)ME}3{<<`N23~>acpNZA?i|K&MoX9=L+qic_8*RjIjB0_2zr4blEx#M zdjKv{!1!7v=b8uYDY-St*u8Z~Z(#zXCG6iL0hun-TC-tbDv1RZ2}4lz&IJ8$Bca+# zPLtQ7LK)-%v*d!aHAgM{?`x?ANGYHk)8R;9dTUs=uRxY7?+T=>d_d8*K`2x7Hz$>% zwJ5jG*#w3wcsPoOk0 zjkkTOta)Y7cep>djLv#I??wZF<5`t3{dQuua(V<@C&_=X znL07VIdUz->o+$T$x68XA()O}Ofj!tG0wl70W|*uvar9Bql6Dr`#TB#wqp~wxAb8z zid8wxG_Ci2df~78@w>xEckYEvk^vx-mIe4VlFV^*3vz-kf1PMhLksu$=a$)tik2B^OEFm0|hy+3aAwt2RZCU* zE!_td&Y*3#Aaz1Iw>gzTir#uU$F@s{?s-RmK$aH$(M)HrFTWuI?~PnZ=kbf}Zo^%s926My#M=rXHL47g@-fyRN1)F6O9`L(+KcCy$}E`X(VGpn z3#(u8^Cq%E8Io_D;^g6s`5XI^K$h^|z|E3wi%8P-4aXuHb5!};Yzm~l`Cz#>7GH20uBRE7g+YHO13A7%Zc{ybyEJ~knRd>c& zv_hrwH_a;9(NDl%!-Ci3UItDk6Oz~+-`$xunEy6lgyc6&;On3{Xg%USxaG;Rx@T!@ z5XwsJ4}JLnyBTjI^~!sK+h!V>mJr6GAz4HIbulcAnli`mWmhXHUXz=7Q>%yx?{^6n zoW{7tSh^4qK>qL5%x-<_#{oSd&k9;BD@YMLY~x70H@`rAPdS4A;y>@Mzzr$lh&D;u z;N(+DE$MvUDk=Aqv8BwWB_yPyYKvMxkYZ+JiGHIuKDkH2t^TmOUWmvq8y(g39oB$o zKR~Nk_I|jTYmdMAa3%t0iP`)595fewWu5i$fG9m!94hb}nN|Wjc}4HG+FPg16UwLo=DO zP&fhH6(xMy5$WCDH?~`l3}DU#-Bqc%5~bqtF<}Th>MDz=zF?nxc~|holz+5r)m(3I z##Q;s$F-3`;oB3`C*s9VFU(yk-+Um(Ar$rwmNS}W_>1g)lV%xa=Jv!AUc787%Z3f+dz-8ZveD1xeN!WtYDEPamI z3}8I*l>n#)9TZ5(S~48`Lq7anJ<87cY9vVA4*SM`=?PO0mprCG-p_Nj^x^C_vTtaWwnx+9m$}AHCy??vTC^e6LXo;L%$qA&8l!+BOV`07lFb7jbEA zFotige_=l%6(F=eYhsFsBUn8o#W|`fJ7u~*eV({{($abX*yq_=VT0jnU?ut$S-);D zxeuzvLavnWzHRWce-4qQz?^)^za++7+HD?t7Juhj{2uaOquaylxzKZNtl;%uTcX}= zu9L?>$;y?P<<~R2->>77{Wtt}?fm0vc@hyx-vl7?6I$6eo&NtQdr6oiYi7$!hGUFs z-Hi|;WutGI<@nc)Vo_shoLJp_Wm09K_dm@*%f(gyPjx zC2Fw`lhV@anF_rE*)SrBTC)lU=#zVOfedpY(+6cQk!1a1vr8hYzBTOtIG`Xj{g#04 zs8ZH%fB8eARO8x*(7(6$#L`Xn`WI0*gDV7|2ecxYn5wW|=Sy}tP=fYVb^LF1go^LHUjujJj$`L=Fz0vk5| z_5p5;6=HkBQhye2B!pcrhqDmfU1i{pd;vH`Q5tADMbp~HZA59Gn~)1>=(!Km;(Dh! z#dBxpsr!UDQZXOLva4$W-moXRI-g;^vC`x%b#anEZf z4Xm^k#*APvN+&Fdvli_qkKnzQy01Y3Z(C2VUWNTP&tGpeoSpdEQskT{o?^G3xY1ba zi`zjGoIB)wiz&USA$RrH^d-#`6A;a4SSEA*cuYpI+`BFAWW*bZDVLMTTlzsnkGjaTRxZp!~aH9{}+PJC2v zt22&HL}2R84@8T;#q3r7=ZpNpdDKLWrDIquO;~{4*@BdBuNcbZ(`DdGMQpCf+M6mH z3`ew@cO)PO8?jdY%X#;$z<;q3GTI8GT4~O-fe!`8jVjcxe~n`Z&CQGM{p2?h8N`CJ zJA;#ap(kqiBbvqk0T06tU!ZZ>z}e?P zT;VyQ@38zJLeX8A8OQAuo*@XXPw2&uPpwa=A2$%2mcp~0m;-`=hv;knM4OhZNBq80 z1|Qb3W`gP4ua6sv>hj?`;o*N}4klv$)nDVfJxxo}$iXnYpy$m1*(MY@C+EFV*l3yp#Q09B4{>M*g{+L?%IJ>Flc{L=%iv zB5gAmN=h|aI8D-CMit(yTgk}Gd#7jCudo!SYyLY(3pZJ(oh2>jNUi#O4(-ICr`&vom1ldm`Lma(k+Lc2};3^hiL03f9cR%-+I4Xj4gV%gZsqst{^I8nA z&#@UVG>@bA+B9IO1mki66?aqWTD=%qIZ&!g zezh59{O@Yq&xmvg#%HFPX=)z7eWv!D=zI0#Xr=mK%}YNI;YSBf9y#Y?8e+Wv>tD~LC9>`$)SA4nv)g6-Qel8sx4^h6ve!)97*11bdGc8`sE=qXI;@pn}%&Z z{Onh=GRJm+52651lKq24{m?n@+!FLOiu{|gfvN1uXIzDXfeJcp&(V%yN71D=nfu&r zJueF1Z?Q7uM5N;If{Zl8e^1(+@ptv@{K#9nWFfuyNG%7r-@I$UiH3r zQqvc_qIBaG8ZFIV88!2C-T&!uBk^reeMu7&U)o}^i4=^?yVN6HgAD*r?&ho{cH zvQ7FjEK+d^27JC>(P6C5N>}qgAGdOPNP*pyYL+IH8KsKo};8cNyNJUK`awKa?NcchsjhlwHQSE z3cXxsQ#L4k0*z#o-Qx+mzc(}p9v{3vDO5`RDVj4m2BY>;^(u)F6UNEG?l#*Fm#h>D zSZ1{@ESh$ zVMijXvQgSJUXc*H1JeSv%BgVCwz_+sml0hnC0{Q_TbB0xJnz1GujSdNRL(jO)I^zB zl7Gb7{aU8Fo4qOs+-GGyZ&p10(s*<|=kWDN^hh$h8GrACD){Vlgm#-SEJQWpUwN6O z-;O%=??01}qFSNw6RU5B66T5r5YgK?56_TRIjO7twGV%)!aLS;xQ;F~KAe1XcoqDr z*RMf}V!-KR^nrHuR+u5pI_d8qGDG?0Wj3E(mayRCeWmB)JlLFiM=SyRSSX|gWTQro z{2e~m=|!~YHGlQ`V$9uZA!NZVIH@y&jz0WYEc}z$QyLtv#tZ^gO_=$*@i~C-(`on( zWdy~z*douP#2h3&FG?6MNUs%nI*X(_edTBg3wC@titw3Ck6dVpY~n^j#v=veB50*i z`f>UaRg)&L%cHj+*QmJU!DKzON*BWz8hX5U0zX+{i5=^IqX_~1te`J!md z!l``lgnSiR#9)T0qAZkn$8<49VlgLgVjl14nbVF91n*SH zGttrfi?L#7u`Cubk=F)MTA{Jv1peP)eU~v()YjWl5JxmNoT?O*0Zj*N+*AIYyse~n z@|A`-ImS}9fHICPFVMuFx)6tP9^e{}PAgX}t(Y_36pXs3xOBpmds<^!ij^7j+v_+( zBSM-=(dNKZ`T3_rPuQp9IKJmP@OP(^-K0|Hy*0E-qtnhP@is1kkX^w^-Mn08>8Tl~ z2pj+*wbGH9!l@W2VOF55YFuPaT)G4%{nd6lf*zZ;m>VGxpLMd4sD46lg9gLbi4G84 z!n+x8Bo59Hijop9eSr9@G5LTIq3*hp9$%EfE`mZT>zFoHBacOD{<#Jc?^9dZp8z zQxIXBhyZAu`YF;gVX}HCj-2=Zi%3&zqEds9Uct%Yx~U=_q@t;$K2RaC=lO>>)Jt19 z*i?MEG@`jFs-8in{z29~7&H3}mhS^0`YVPw(+F(jh$cut6V{@MC()!m=#dRH1%C;Z zPKgnqgoeMw%#mWRx%h6Eg=Mb<11yEfQgI|u92qmZ0mv4Q3st;`{m{6cQ=}beDqI|5 z1qi6ai;NftXB$qe3;>@_5z3a}-$96!9Eolr_S@}QN4w>ElSO(I#b-5C7fV#06pp@W z40#lUC@-aRFOpFR$p4#I$Z09;{5ERH`EhjF0x{a$S&QC%~CU8_!AqYiVObzOIDU9W6i=VV>qWHGmF ztpKcksE2aIqn;a9&nwH=f`0e{Rf>azyJ)Ka59GF9)jCiESjWf0aR9<(=q9QP1Zj7( z9RX!U&R&C|NsWp!X}wWy>`i`2eByYw)%9}f?Xt##bbbjCyaWeM^;F3<<7|2n$^BoP zn-rSrvv7?p5QII(1)#~1O;kk)ve(Kl4sRPc3JfE>$m5Q2ohERuh?>k6T9&pO+b&v6 zxfvx9WNXixa&<^2g*pB|l$+6W>Ru|kf@Y?bX10*xea1$P{URwoEZGg5)J!M4>3QH? zaG}Uw2kXQ@F}XN*E84IJfv980{{*650KhtMW{L!_j;a7b)&K;ML&y;Tz*-O0hHS&H z;D%kI3Zq9|Yu9adu;_&Cc85>xuwB5C)MHU1SeaQ#r+ZDEy%Y zj+-%$^I{+OYKlk+0&1Nidkg@udy%z5KoJmfRU&{#6FGVvw;Wxb$=}kpU*542pH`RH zPu$wo>slnuIK7PD_M1r-NH9G`wm(H;L0oj@*!XJ+OL~JQ-6QPZd^C`2-6dg`AT-`P zU)?X*J|IEY-52PMCqF=^-M?*<)%&7Fs5aMNZGoj1rBI>>B`;eMG_elr-! zgyH<0^LS+-P7d>zzvD+I1}ZRU;WyCP`v6xT5@i|^wMAY84*glih%*njTnyRu4(rJe zv)T@G77PWp4gD$@9#|Oe4#6ni4L_$JF$x*R29IE*MlUT#UH>1-?lT^)cW)Q?!k8Il z7`-!k7ov+YqIVJmA$li9i7rO(T||%GLexYFLi9dL5G^`M5E2s6=J@aZoOAYho>ymm z*6VpQYt7v2{$1<(uJk^+8c>xT$Tl3HzWT_M*ef^Q_gI@h<8_jI=b$U?AX0nC_-cqP zc+lCnkFtHpjj_A**I+o~aH87~N_HrexHlkwIA$d&9lT6s(M){ed&AFVqWttTF96c}sP9((IH)|xohUOV=Fe5@;Y4B}OAY>kISfh8LV zB#&`NYRAXM$0rWPr-&z}$HxZ~$7kGb3neBn+7qA0Csy4imJcR21SUs_C%4=t7tJU4 zYA2`jC%+#|&IXUq1cSr)#2~mI{v=NQt)03YpSnJn!V+U}1TlCz82noRDG5VRhasB4 zzz#9z=9L8^Q=~f6RPNI>Nz-(7(+m^SOo!8W6B!64;0^+}J8@LrW`_5Ath9DUkZFwP za7JWxR9J9UJY+_|eYQma_YShPISg>L!s|N0`=LEIE-}qv;y#?Znh>p{5_?UT zW$`c@MwL|eS-1CdCewV8oCX<^kkeSC%zf!Ne2KPssnTNU!Q2v(d|Br1vgCthF|TE8 z+H%MBl2X%h7V%22;7Xs)%7FXIP}0gs-OAX+%EaNyRERsoif~<+^ouZI=@@P!isWYl zv1bLvE%o{fcqEUZ;IksZ3gh0J{#RY5mFqF<>YV%PV%_S>;p*)jyjg%H+U}x=OTGQ8 zAc?G|__-vdukdZvt#spM+S#*7X_6;f_#c7GyM|A9TwP10 zYD#6ll_L4d>~*)%g}afHyRtZh2%$|#Dr^D?_Dm%qTHdi_#_rk*eRX8skLccwz6E!g zTWfp3(kST9bpn}<9V?+-yXVr9$AmvE2;;x8NL6RBP9WURj6IDwCIT9WH*s4UNPeZl z98m0Zh3nUi;C2*=gzi>3isToDSX7>2q41FH4N#p5I}z@}JXRY$CcNiK)B*r<$E1q- z*&Yu5}OZ$<5TNO?SM7mT_eWC>Z(q-BH zWl7~U&HS`0Q&J)j$j$*LX+VLc0LbN&gN)?e8!|{G@|^|?;h{c6IhE)O(0WYv$Ge__ z4MQA?!E?TC?GV-|fs=Ttfc8-xk)yx2;Y4!NI5o$x9um-=72c1rooQ6VZNaI1;W^dh zIVbj52Iuds<{R(Q6x#sXwIbrEZ%Bb|aE~7Pui9{IZj=X3kF6Q>fwtc0g#aU(r+;5U-7wfi> z(pWx!jwN`RdODXujonu-gm#V?PUOsxpl+_i3Nv7}OURlUst})Smw+Lw zN`FFLN-h*PRr~Yl*V)RN;)*M@rQ_{LsIfv0HKf4$)^zLv{`zOW)r!{YrWcd+mFpEM zQQvXUP?`LZA!cyu77HCV5@VwAL)~J7Ar#S;!i|N)rIAV`bxLBG@wcH@S-cOU^+74( z?X?C#QO!KEz(3HfWoGp8e&^}DD=GTVW?p@F*wL7W0-*etTMRJX9}?*V<7x@ukt*xS z{a%UClfO9V(^I(ND^kr8ooP_XE0zJR_ra;|r}pDBC^yQ>bbdvP_EXx9iwvX5`Gz8W z4Kd1)hs0j$KqrHGtdFW9kH$=v-A}C~Ulc@In8s`4l^9$zD)+AFKZ5I0KQz_t{8C3Z z=BRxy^R7&eqoOQLlYoA#%)>1f8hF!=!u>kNSX@^pR-Xqc!zZ9(gEkHINGhPH;zbm5 zEH@l@^EHMA`}`uVo)Rd*d5Tb3ah`pkE&jHCR_~v|y2?!e4y#XUp8dP9mGhWL(>qK& zvpSymMyv)Js~{#^F!@=LHQ8NiQ($nXd4U8?Ww~g}iuV zI(AA8ICz{<8hTBrJhC92mgZ!AL>B+z!IA!7N9$;s-#Dx^-MnryqO*)nI+0W^ocWfb z%)?-xSlWHvl(RH2t8v8%Ex@fcp538D!Q?cp!DNI~I5D0#Eq*4WsGj+hdb5~?m?9oo zs0?5fp%pQp>t zJnV`EVx;RzFaK*={{ExqFK_9fKz8nkmcJ_E1oOK2G3Vu z!}Nmj=nxlkj|%WU>OBXJd*#edA`s&xOmXq+Abx*EVS8aTqu475k$5Veoh_D5IaWyq z3`Sq>c!XXj6#o(9>7l1avCj3*2$&uB591qzUM({RI6O+&WKE=B#sP4~$p}*jil}zi z!@kL;O0gQ+Qn!!L3T}$Qjq=BBbJ-cotJu-rP!NC+hMvK_MBT^hiqX!?d_BpbZ9Ps9TQtXV6c)?U7S1Ga zY{I|P8y%pl`ix_2k?uEZJQE`u^YlnIv7}TrNop7|7Qm+yApcjIuKgSwx=lG9XFLa% zWQUOLN>BJ!7?$(fJ8M~7%)H>*%*P_Lx%<;dU3g{#_U!g1p}8V5c3aHLh>W4`>M@P4 zW!8witpbfv$h&HOV<#aWj2sCb~FsgI4cYVBi zVca%o^v1i~)#5PlQRl8vebA1p<@Lp*91Fx;2#wr6`YY@IEMHtBU6rN8k0|GL4bC#fa7+FF!r%XXo;a`%WL`&-05a z{eINkoUw(Ou#(P_Ni2$td_#vA1h-~T=W#oOJrLAN=Hl{7OA5Ao1Kwacwz?~O+FN1X zgWK`xEtnVn01{$H#wx)@Zak%58>*~J_8mY%ZZ26qsXKV*tzPYFly9)OEh-lH zS*7vlhIq-=Li3dM7{bKiHbel_;YKb{$CY!|5io4`SAmL^y$}+qaU}& zEsXm0>-FB=`QG03&d%xnCU&pu)dD4G$Coc(u2)vB78W*ES8rAtvGd8R ztE($3E6dBvOG`_iKY#w8HtK(gs?$;bAgQ-PD&|&59s8G%I)3wSA$4LLJ3RdN_8b~I zA09p(8u~l-;j*vqs=ND7clT*`_uu#L|Gs;7IZ|-h8;2cnzUeW%e4BCgP8a*`?oFe> zt&MszFz|nP)ZyXbfq{XKA3y$27`3^%xv{bFUoa{PTT6+pBEVMQ-s-2* zGAimO!01~<2^5D;*S zq5AszdV71{IGNp;>D}lm-Q1TtadG}`@#L$HZoT>ATO`%Z&CS`_`9G0VH$%gJBdNy5 z#t$Dp{I`&*qobptp>d0zs;a8qqNj?AivLDWZzP5PF;fM(b_MTXSsA}_aNe@1w`S@M zJv$Zl0sQW%VwnD{?c)LRSnze%WA9GqJxmHYq4Lsg1r z)MzRj$>4cdV?NSUK9)eRxLBmvTrrU+<^64Cq`7kH74rY_P+O{JD^=VZG>)78!$VDU zyNP4cdRP0o*=e@MV(eYraw}?Uv_Px%&FXvqU*A^8T7OtbSmF^eYqvFQ^u_8eo$qnY zz^ZgSq@p_wf7*^}3ffM}2K+LZC{*wx(V-OEZIB>;EPzys{GT4`k1stDL@c_UZ6{m9 z8AO!^>zqlUlE(ta9mv3iZ?pA}7Yal8eZMVt#b6&FTz+}_%W-nUCrit!Bu%SA}NiXHlk=9s#v|I;?@~`wwP!)(d_9w zMR7pI@E3JLAs&MW<_?~%M6r1%TP5M=RhDSJH;bjAoKK<<@oaDXOYciFSO4Rowi~4j z?npA@QW-k$yfAU7-pMj|AqZze`0(y#+d0JbAeG2Xtx}E3c{%d#w6~|F>5_o#3;cJh z_X??3+tV{Y!-V_bk<>2x#j#v9`z7(@jbO4wRlcufag)LT;PsBcF+cBJCT}IT*%_~@ z&*oR|S5*}?-wG=$Kvl?yZmgAJPRo35IYijs>ie6wX2&1lqE<`Qm3>WOHH`yrd}^CU z9vHe5)V<-m^-zUq4>ju9g!_risI2aLn_kEFG>u2|xis^ny-x4=TEaiwto!8g;q9|R z-iuDoF0)=Zwa;apF*UIP&iljM*VVm3WWnhlIYqAEojRMYKl&*j38eQ6giEb?N~k!_F-Scm@M|32%b4Dc8&qpF%vZnS-KX%9u>}LAczmiN zbjMkALR)g;bcVo%7#K3@JxL+J4Y>4FEp=mu3w_Y;|1~|FZgG@?%q<`vBjBv#nA05+ zl}deCQYy}dDL|M#_-;|c@q&lFZX9ByZJ&d z(Lht@*;)_-<+*BvXymzKyy#lnw>{0H=I`+Kkg}beg{PMXd5>B&Bv1OiVNAGmO2&f3 zt6k(mc5+_gKuTwXy430EW*GZUo9I{$pq{EJ^UDeka{pB=MT%ghKdk3#w9iAmd;P(} zgr;98GB0u)@GKOj6E6KlcXGX-Ut)oAio*ka2m;hgdCr3iBpMLWNnt{vBFq3T3QcHs z98No41m>r`?G#?8hh>H_X8nN%Q`*8joQ8z`6+!n_w&1vp1LAAzczTO?P_T5Q92;5W zgZ{qY*gQpftc+&_yW1un%esm%BQz|0TrX5#`|*vk&xh#YBh?n7BI;J!Yyt9qrZf|) zeMYukywiTQj2Og# zB+jG1Nuv+XpG4@DZBmvG%jnx5$OrypqmdjLsc|C5iEV?BQ4c5k`t(sUBV$2NL?c51 z98zWz02;dEErNckRHPWyj}~evG}TvB;;z92JP<3AT({)%UKmLZ^bt0d z4VOJVNtS^sQ}{^TXTxj|MRukLr1eB-A2xt#vwJ|?R$;n+qqF~bs4{ZBIx(7t6qG+J zrdz@YByduS3riT3R#k+xf!kq+BFw}{39g-LgvefJ%A@5IEONoEUONT(AO|ED!=jsX z-&RRR_0k_8W;>S7-uO?ve)4B@q5I;j9u2Ftg4_<<>3=sw*sF>^30oYL@oh-MQ~}Z# z)1zk8{HBpTr1MsUzKQ7w_S0TPWSp zX1N;1^IFCoJh!`OKK>bc4(gr3W+%JcwA@l}q;9tjaaDIKHp+#axb#0~k zUC2~=wByf!Fqj}1N1xc7vLA-M#R)j7(h=qn%vgP9G**0lRuE0O-J>QG>=_vm8P0Ul zgU?4!fM$h8F#U!?xIwrP*8P30x|FobvUhirGXvNiRlWU*g_E8O*kA`#(rc^D8MkDX z+x2{+V|mx~l^-71lE}jc=%1ouJQ+*<&j%QcRUvmpl!Ux83^Q(qF)1#Qz~rUYkNkz8 zJ>8%{)|O@!>7!l}n{gaKOiK0M0V|0isskb0O;}pbW}~5%-p}WvqF~n8A>~SM7I4#Y z+Yi@fRmw4Mob%SmW!2SOEiIk3NL67Nu4-+oU9zdSeHm`CH>C*AY5#?|qJul%S_DEL{s&e z)Rw73%^W}N^Mc0)yq~%VBYxR`3Ep#5Xr1~Yb;6~%W)e9ryQioZIM>YlyJbl32VFnq zA_6L@>`6BFs;)o%0}1OD47C`#a-gYn@37V5&hi(@(|FYpEJW$tayJJa#b;McWDN!A zW-!rG9O`5@tY*MC7BaCXb6TqRloeJ&e_e!sEy<1W^Nkn^fvO9xEl9}G0JO(wIBgiY zR2bzsnkf^W0P%a~qZZJj7ILbF$Epr)gpEUh;TW>XR-tEV4*bJpLEL0S`UKYij7Hse zfjfvGJA$GaO*ZFEiy=kQM&6f-R5po3#^RtTW$692CmOZ!iivLPP38=BIsxD_2q-*; z0m8s`gZ*DMKQf5(<)2`4#aqh6N2oI3x-`PgljY8WtnzMrrMDHqJ1dw2JS~;v00V8W3eDa3w2YzR zz&NDqCr&;mDOOqQh=N!+dJnuT-*}^cb9Y zPTmyLR#AHA2*&n6lU}@;XaY9u*KiIE_@OboKy^Bjj$A<+&a+2e(MsN7B3#4mBVA2) zmj@Pw$)s$}PQ+U=>FB4CCE(9<}-r=K&#yk0(Q&nEMH`DBFLDu>+W zugvqDKxW>EQFIoOflsV7dwd+6e+;nZtV)DHTkN9Fr&vJb00uDsP zI4Ue$6K+bFVvZF7M&PjQmzD7LO1q^rX_sn;Tyh&!bQYTHIbR%#ugpucj7NlE8X!uS zsrJ@H+tQc6Uo6ulEaUM6!q9PrgjJ!VHi@HD{BYQG18()VXYhV@u z&q-E|*1Va{5fg17I@Bj!Z2-?|*6?l+PNNA3mZOP+>ZL~OVE5`d$Z*3D?i%0f;bYzo zez-eW6p=d$5B<9_;v}!vv`NOl$w@OqAg_s7i(Ip)9#ix*-mDSUSOxJUjHxJy=mpgH z(8xUWeb;&=trj(+a(+c1up#S-X5-h3mhbWKF9@Qp9+IUZf>KRd9GN211oY$YZ!O+8 zsW80eZNv)!(CX-N-7$EFG^m~x2j80Xw-upF5y9CyRQ4XNF&s9rUi$2Ph~Mj09@iGj zu~r@f@ZEF2@St~*M3r_Tg!o~k3&QZ`h7Me z$@jhRTL3}y<~tkSGW=O!<&5k5hVR97HBFyfyFL?jlNAGj=vUCRs=EyS&|dK0+fYj? z^j9i$@*eGc;G4tOzH>oc{s~=Ym-Vb0t-Bo`ZqZZyAh<6E_WKxy3hD{pcvIEU6S>es zCfj`G{6Qw?4UQG~VyTo`yQ43t(Ub6FSQzfq?QNz0(b@51JzsCf*xUO8ra5rJ-R1fa&=;)8xXb#02kW#z%e)ir6 z_FK%4=nz5L4aY0;>(#g#5D6YoNc>3EixXy51p)?DLQ%tOljAl1O|X zBmoF$L6LYhfEQ5R#IzqyFB<|A6~e~JG~Q+Qsi2P(c9IYJP4lHih6P&LkmWg znKz6>XdbW|JpfXne~|FcXhO)z16#6(DbFy_0t{gnhIkc2a*cs^J&Ih1grK4msitYK zF=;B}-D0?3p9n(?%$Se)FplTcj(n{B#4ZB< zdgW2>I`o8b@Y@U8WWs9QE_YF5+j?^-E?Gj$Rmh`|p@PIQQ=ObH251Pz;R$@+$UL1f zg!wB2Sp|KUvyNL!vt!6_$5b~GPvl6}O2oU)_Kwam`1mK*w3fS2Sg34Y=tPFN+i1=7 z>#6mwm}}=^372wTmxoG3N5Z7t$XH{+d0UHx0NK$mF63QTpNbDYzmt;=(;<6xOd7O> z+YBc;yN%2ANW1A1|5zvKLxb@YA&YR*gLNWFVK}M?_D7f`1q--Db&}7=*HtDhZFD7P zgnVv@8_KR*qugi>1<=s%3m-zfirvZFkR&S&lB(-OzUz2i2$C)YoCS01a)MMaMBjv& zBpce~i@-xgFkDZ(U#WyjJp>n4mQayJGS-hf?rY3~!-nQxc(pe_;ajn|+7a=B5k+jl6} zPb#pZ*hz*w^dK}Jdd2jTyO=2G;TA3#!2#m72b-i6z@bJEeL+%5qDa%w09y}H9|Ark zteOgt@?X<4H6e7hn{+4LHQ%7TEtZ9z`bFGyabZcwo~#C5FKzNX{UUq=kHx^4@OJN5 zkwkF7RfS0|8%WnN>Hq-wUPOvT!J^qoiiF|Mj!CPf;UGb3)=6^t<gA`wvcH- z25EqVq(Vg1zb8Lm5PM9HumTBtfIef3h*Yg|7p#b@#o+lxB%v9=Pph8l)Zm7Xv;cA& zuaQXoNRcsx`~k9^r0C>Z_vxd(lZQ_~vylEgf|2b9gKIIQT}khLthIAmp_55a~VHgZIpJrLB_252-)H0B;m*%7WMv2E-P@e)f>`AV5nKt81_|nkn*3 zI4s)zJS*y)ivIWY<^DnPCCNr>U@F0N>Z=XS1AmR*(Y+fKVR+NW#Du(;FH|m*rp~8G zuRCwZgla*K**p9!KZ!N2qOjIi6lp!AYdSeiHdx@!-iEkMdu&TwYFc{h|<=2-O*f2agGVgeHctc6Q z;I#N2Z)E10DBI&pj~CH<%Gt`q^5=Eh%nn336`#BP7mS7ea+)>aX3K?wnao-yI^F*G za>y>e*>0(w?s!9ZxrGf=2=NvEUb)}+t)ofj0kh79*KsT?SLOYE^S@rZ6I)rjK}*dZ z6?3nD9VLald6p=9k^gtb!z^O8>XGXQf|US`{qGQmc<}Uf@Wt7orQ0228HXd}<)zwG z1HjIJ;lR7vkBBk4@KmYBwG3+DJUhzZ`Eb?}>p%zQ`Nu<5Yu2y1=DVD#B-csQucZhu zn=WFyz}QB;Nkw5g58TF`Kavs=Hn!uY$L%IC#c(tY*96+R^v|JIga#J#Giy`|${2Y7 z(F^@>ks+6D($RDu4swlM;kaEY_9>wvE zTY{-v5GQn;6+2)q6yuanr>LXG5+%l_9QNR+(0z*z%7=IAGctN~wfG{6kIO!%YLQD` z4`Z0PjYzVbd=kWrO=s;sRccOMQhqdlRzP9|_-h4wouwUSTGCv@l0r~ zpoJ>Yq9om-^-*YO7w>C%byPWvu^7`ix1UN0)$+wkF32+B4%lF`<~%9mahQVqTk8mN ze!K|h3o`Q0sGz{}TG2Bq!6iFzPn$#DVYsxKVFreNaLw3Po11XgJ~03)J5U&+V&I@aF8U z{V}*)+3vb&($gCHo9_4nJ|wRk@3bK){&|&ii*vDi6zxQp$QGLt-p@fL1d0 z^%SQV$g2mZdB&%cq`1_E_WHBGf|<&OE$6f4@v`Cui6;E^R@o;x56s-OZ2byOr->xv z08l_`BMVo&+7ri@NmpHW?lK(QdZ@6P8;&Wtq;AU%&+@M-awNlLB8y211?OR#6%9e} z(@k1V4u9-f+}w#E{qo~vB$QDL7X=o`A-4bi{guwTAItT$J%9|Sy5Wdz2Uo<0;xIB_ zE>$XGK{gnUJ4<-@9K~W4ic=BxIZS6Rk6vl0yN2KCe~d5pvunOh&z@0igJ6KWhd=H% z2&cacrWkIeq}GV`GF22SX~dS=dSm^o2%*oKFPkVO{*bzF0^-sFai@f47v59^X_@{NrJG;P^WB z9j96xG{Iy~bD>~`R;*9}BOj$b2F)i+;vk;MX!>ZUytpqYH4l$*%d-nGX-bvhar=kt);H^)3cn_K>u z=|Bo?B8WB>T!f*U)O_>H?Cby@d@Q9GeYc^YxpR;0&xl_5w^?=$ydLOF;|`A+axV-e z`+aFpl!|jvF?ZdL66+r>72n$IwP0RFDXSK0T0qiu%Sk)bR^PwcM~*a@N;9gX@Cozw zOFd@>!v|ldpW-%i#EB>Y>0Gd%+bz}i@OkAD=I)EaKD{30tx-%Knhc*+6z;*ns=2xJE>fyCsd0Pf25m?xZUHl##g@mewU1I?BtFI z%!kyyqZWHQSM;8_b$h0L@6(b$0dBloe+1J9D6V4S3F*a6DRp$_8*9li)9b+B4PVFr za?F7F;FCw}f(f)<(q(j$MGL*!pL2zo4M1X`K1LSWSP>UiJQ99d!1k^CGXgG~A2yK^ z%N7_u#`#4&g{;cWv*Qq2^gTh@#lfsNPgSeq6iGW1YSFpcP(c~Ho7<{6`-fNylJjX& z`WI~<%!%q(=DstY5AO{=nk3kJeoLO)WiuV_NAt>};RLZg<4Wfc`0;uee#_?xk7)1w z9a%@2h4u+%ljef6PDlA6x+%9K?;?D;Jq6MwOpMTJG1bJL@^TJt>{c%>b$`5ysLa%h zL9yaH1z)AVtPebxYz(P|Cpj2Wja9C#WD-39tjr@2xkY_sxBJ>Ml$^tl@`av#xMver zHVH`W6H?V`ZHh-P7gN`#SQLbXC;gFSf6UM$FoP2r+qS`?B^>ZPPGGxSG~@%m0Z@ih zbo{94YQ(DSeB#q~4fJB=JLEIH;2I8uWUL1lI1b~PM@8IA+@d|V_e_AvX0^?R9Qm@8 zj9IUd=1c|ejNjd_`%aXcx!EaScOAIdUg=^!`-hB0{@;7f{*#r%1)zL!Sgb?^~f^N1n>FDLlb9n0UI{oN0p z3oj$vu3A4Kgm>$8`&qM1LFB?vCgMhrjCmg;BDOZ!l>|~n|MQp3uZJ@1-W`>Xd-nKa z`~J$tI59Ps$i?~7nlnVj3gh_4Mgn58msJe>qR1qro{nb1+bAccb}ylM@3G=tJPhtS zxzJy4`HNbw95En}7V#Ri*^#R)!A8Uw?U_jy7SV3rq@2j;J z3Z34^ImrL@u>CKClER#9IOYvgL-lhMzc{GhF&_FvJthbVd4g`0F{HTgj28OX_we!~ zFXJ2WPWe8*KC*PMma?+QN?+}J4mmfHqHi5qEsfg5-8$OJ**_6)m%@mlJo)kRx}bVc z0_7VU6#;J*3pe=(#L5Zx1#qm0?b{elDOGz!RgQx)IRc}_t_C1PgC>kBHg>AvB?DCY z6`7w^-N(BfGnLhfYh7AY4ebbaA2+fp$8u!e6VC4nN7n%QZN^fSHik%^tpRmKSs$MU zS4uVBIc1Z~DtHm^z}Fa_^S+S&j^~k-JMjwWNI`6v&v107dg7@-)qMt@{GmtM(BWLt z#k_={CBwg()WKKkskck4-0D(|T<0Ry5W|tpaCLR-hDoWBc*CIst)AQiCAaZGCbk^1 za|(0f(L{lPykJVO6bb*LM&T8*;O_|7e8j;`Erk`Q&MEBFAo{`duy7`GMQ|ox!svpg z#%p4&Mv&$c-j|H~gedc|_I%>Jdjr+msRoz5%`2~4?8ZKT#$Wfpuw@J5u9fLE)KtmL zFZ4!XIqR96h9n|=iV0M>EB5hpueO4Mwe~c_3m`B`4ol9 z^ec1^cP6;-m;Ue9Q4Wo6qTWJh%uppk>08 zVT4vt)50PAx}1a-=Z*SuvFcVaVL+HKEk3jXFg*u9Jc~pfgS>bkk5OS^QeXpoKph?9 z-~1u9$A~mX#Q&R-#f6cz&IF;+bfJ1;OPWSN{-Y@lLgoEvLI7|SjHMBdVPb@`)5e4> zLQv=OKox#aPqd`T4AzDgdTZ{5S4D(My$^?XUYI>1HK_7C`=m<6DG$PAsF((-B)mL` zdENu^3m#Gzhk{BopCLQYoC`%g(N+ymq8_k?RfNQT)KjVVX6FzSqli*`AYs5HNgNtL zf%B}3Cfx-Lfqzzvf3&VNZ@0RXYZ9B`iJwzo+Q!N~3}iP@;2)0@I^#;f2RtG(~~qucL}<%N2lcs6n5|3TXi+ITV=H>#siF=Q|NBVQpua;Tg^2YDO`6HlH}-K%0GqSA5;fQTUBOtK zA(i#jCBSS z4{M*Uhln;5cw-~DX1-gcGfq2wXRT0}`XSF#bM8q3!XB7I51RFzjd+&f1Z>)L8m;4k zEAwXS;;j7g(}PWS8@a(aEkGz5WGC@-OH;f?@QE(_Z@7xlHmAe34#@@}zVlG`bHRH2 z^R`IE!EOHeZJOt{Qm|yHL1GKRV*NFyd%H`56SnFO1mOKG^GTZ!m7QnXc9E$ukM|of z4LhSw3;r`Z7R);|LOX`fZ7i9el;}&j&Em#KyEkb+|QL}Xk5l2Krc20y|`{NxB&kOfsv-b0$X#AXL znVEeNUq<`#INIY#kL(zW*a+4A=wC^KdN-*U?XR72ds&&=meDJ@>h#a6K!niEkcxfU zXL0udaPT5nR~RS!7$>-mDB~z$SsPRKoXyDg&Y$o*;Z=Z{6C~g`iWdF;5%u=&+i$OT z;~4e1?2Ec<)|?EzwsO%iW>ygq4S)gd_ZK82B&y$E$2AbVZXjZSnn^*VO(I-T;%aYQ zaY(kOg%+{I;G zCukd|PV2HLG)wX{*#VQg2$A84rCEfGBffX5mvDw3w%n`>e!uH?`7KO1MtA+7b8@$0 z&7ojXcVJkpN8TOv%_-O9C_FnX5PdYyoa9~mG%<(Kc=;jo|>rReOXXyqQGz<-(pn~&vQqg3*wUao_57i09#QM&t)mYC>s ziEm8KbtkVqf(;~n8KBp@9$1OkC!T(L(t9%RU7EHH&qTs{`n^A;aE z7F9TwfJhA@j^x$>Sd6!%2THcp8vDVZyN&{6JGgAydL0yCf7D2E|>y zIqI4Gx~2NGpl$E=s}_h;(@=9S5VEPAPP9ijC{7NVXYz4|Jq?D)-*#%gltZ~rT+f2Sl7Bxv+Dneb zdp^_Z8xwGhPgmu7EM)C@^E*Qr&20!q@;ud~`u&m3H-jg-UMSix=8vDFZ!N)RNA9wX zRA03eh-TRS@$+w}KkhHpUpYgmMBxBu|CzPk(E#HqQ?VKL_1izDBSetU#{==!+*LE`=-|2WHp$8Av|>-hN} zqRfD(xrnN@=&vt-{|TLfLLF22=^~c30?wZJzl28X@WkpsqXUNM*XjcF=}8QFgvq}8 zq3>K+GX-YA4+nwbMESpygLZ841b(#P;qY+ZhKtu>mVYM#)xt=Kq%0WrK?*y5#iW;C zd|eu+pg{)^=N_DX1Kbu(|5O&O-0T>3o>=yxnD!6!L)}5*Vae91ffObXpDIW-X<%mk z9>e?`SxvMc@-DvBRf^-qGsifa?5OafsMgoSIe!wdbd$lcZZT}Pqq+5HT;WKM^Pm~h zzv_jK;pe#6kP(mP*ISi)l^z6=RWY`3d;_WIK$Ek9=)X)OKUZVa1JC83=)2KZT}?l_ z9Q3=|hM;e+XCo*&Dz@fK^5W#kF&7zOaUSi~hOhGBn*TpM)JQ_A?)YeD*8W)Xe|e~E zgNgK#Ubh}nfPEZ4lFAP%va&Xr4D{z@TYDAwOcvpq)0mN9<()A>g6-5@qAy1 zS4@x(R=2t$@F|_G)QQ54(oo_vPGHk;IQ({|)nbR=nJ(!1TVSchp_N1|(&LM8SW&oj z6mLf5Ql!Bz`jxTPqAwrt@UXUGJvA(%l%VlbvW&C_tKneIpq6iBipBcHgskx3)Ve(k z5uHFng^Jj>xtd4K%uur;VsTrX7P1GDTt;)5pN@759{YI2y}2;3#YL;VQlMnUk}zEz z{7TG{zJW^W<-H4753YK?O8>0F=}mXW9gmw%wI7a$5`P%G4uZ}P*{AAxsx3d<0eJSm z_9@v0+u<*MLR0Fr8VL8cAuvP)zLMmDg*)&GQGR8A)@Ztt))#j;{{Cc*Wm)rGaKX2+ z-;6ucsVGslJf2PAz>S+8q5}iNB_94bFDzwZOE#7e|JUOwPP< zD;nq#G%_>YiIpvh+QdFI_pRpiv0|gd7r(9|2LKMxj2e-C9Pg{-$u8%#6uS1(8RXNp zhuawrVQ-1?LI`DeiW#dNse?R6t9e2aCCoPSK^q7ih1x}0Bwa{iZ`w=bv)tKAf=_X2 zLaQwzJ%GDU1ktM~8++v4X`W5Ky0=T3m|}ZQ!s=4~-{1J_>Bv5j-lc=KD6s^gdYsEZ z5_y~TOi6)h1U(1dQ*xJAHf2ujYu~0hrhD%8wC?1NZ5uCEzZdc~Rn04PDW2!3*TR2- zA+({!MIl2qL1$0RPM>q26lZNfkxafI20zKf2?;nq(x81$BCf^+ePLP|1f2qY|Wq>|3AL@2m#G1c_Gi;+CN_W7M z*KEYl%pYWb5qAC7kZTs385Z~z+;ov#Upan$M6?QFS0p^2j`@K1NAAa8iEpaHGmY_n_#g+I!ArSD*Wp7j&*J8V_J|>HufEm>vHx8BF-QFBVYi}{%Y;8 z>sn;UyvId+pTn!8%KVD_XSmIQEsI>y1HPXSWOyVIHGgpNzHb(C1$FF96ub`Wieb^> z(M2#0FU`+A>ML|QR#l?>q!5h==hW;$#O|x&1MvHi`}b+ZVuuL69>b_U!fmFVaEbfQ zCFpEY{G?>rzq66|G85Vn$J%afVw?tRu1b@iF{<>=H-f^nPY~abct8Ub%?#%ix0`## z-_Jg%f_s>%XHdkr+T2a#JB4r+7(Vpk?$^92j}n?X;Z}UpH49OD6B!+&MD>bVyqB3^Kw_#@i(~*P;(X$11>JY|1Pevsxrfw#-Ppu zvx$5L+G6fHkCth(Ro_~jA#&4Fl%l8+4JQE^J>hkf`Tn=clCTUXrdsuo@TXE8nP;JA zA`eq2BrTX;8B}~5&ear&_>|}!fT#X|i<0l5V!#mDYD0`%$8;>+(Swqa)3162cX5La z`a(g{=9@Bs%BOy z>t{NfOdy7rBDiwm$2^CONEf-U)8o6@=Jy?=V!n!l(fA;XFneex-*IT%cW``YYR=OFX#;tYO}wx}EE z6LI@4*VAkyuR|F%tLV=NT%n+4^e1ZIPrf=_oi#a_xU>Ophgyo^XY;2AFUvuPsytBg z_^0C%RY})ErjVv6XZY(Z2rCZDVrK6q{Yfp0^i!3kqNEVi!$fI+Rk3va)$5X7@hD7; z@LjINV9JvBZ372tGz`;sGOMWu@5chP&DCdYQoS1?eCkUGqG#g~G-p({Y?j#GFJwf6 z_gok8eSM3;g-tJ|sovEEg>lBw)Ro{6Dke8ER+%n!FSg}>Qulhfyh3V1)3M%<^PF3C zle1K%ChzcTau?B)3t1~)2R8J5o?{5st~~Y-zozARep-lCDTT=5>$F}vW}3V06LtX; zMabCm($I@jsDq!|w4|0*wT=lEYNlAM+^dRjZrLywy+H`NzU&+%+efH;RQDv& ziTud)nUni}(RPCid+@B2RI+~=(4IqR%vt!G}(t68&WU9=z;Zr-~wUeq(aLL=%?=F_3-&ca^?PHJ`H zlyxG=$kuxWnosmrkdZ}$DaRF9 z7D=4@UdINBcia;-bmFs6bJm~m$8}!_54|F`>XO31G2m4>{!6{qvHOk*YaApI$wFUn z33d4BR*wq7#yHIN5dm{Dc=!^IF{#;0&uSEASc9Q92yC2=&n&Cjj%n?3 zw9G=E%G6@$baDE3vtY!* zbXCS?7#XFy0#PESV30744myb|+)KgUPYXzk+(M89Q0}=2Nm!qh%>sVA38jbZ@$=}o z`GO*ujQ7(y{l84E(Tkl|OV0)STM>mHy0F<^OVjrE(XxO=oqMIm(d^{ld-|q4LjW?b zn*uxgXvUbS9ZFXFohrEyy*gKKQZR>HS$~tOJv5&)Lk%mZc@03LAh^xWtNohC;YHyOGTWoZ3aKR#-&N%f~-IIgRENXslyhuUna#$W3p=8@w-glz(o4__{_yM`vsVK>FGeo*V00zq-X_H4q=ZZ0Ald!1`8BROR&hu z70alx$ZA_i`*cg`7t1-a$jh*h<1JYLOWD)x<$pld{!OiT{86bV(|y9D!AZ4f-p&wF0tkYnpSZtI6pjf+ z21={V^hk;Qz-QH@6SB+}x6~qqirNIDsWwTG#Zti*Psi>*9kWvX_TFKb#c|6@x(Mhy z{w6oM>7)TT#cw)NlqfJfaCI$q-P(Lw&nz3dH1uYPCT9r+{dxohl3WJUUk1`e_6dQy zaT@!$plFiQV3E~NU<+v;`}e5UAPKKtcp_Lr<(X9E7G7200BiQkcq&_Mx+tFwI=| zo#siq6i8Lq>oZv;UC)M{Umavo z1x`#G`P2i_UJu41fQYV23s3iElCUxPyxm|iNv}^|g%46xGN@{qa7Mq(&<;0g?y~3w|{|FKw)vvZ{(%)v=QnbP96MArLr16(wa|c7h*i;5Hk>)uH#WD%u zu0_+HN<3$M4y5hI z_@Ms?@Ax@#X=^+eP(Z(3?~~k=Dz^I7B!a1)4y$VQ;Ntc<*w)r%&QkpBQ-!qn z5>Q9K7obDu;aTl8G$=Y!2HSacC$u!b@I??Zk#3oR~x`W2@OSNS(X`sTK zg$UubeeL*nW|moFJ%Z|1yp2ITdlfTnr5prB2Tq6h8ZKT4e{TH*xr zZhP3P65t4`*vqvhG0Jo^$?**LmWOGE@=KY2{Y-6#~Cx4JUkmH5e9jt5oJdZ!7 zx9%T2mu}VU|3%PyFU1^z?@A@=Og%+T4@qNEH`4a%mE@_uV^YYS9PcIUA|kjI)X|v= z>T*7dN^&?CssafLV%9KTx~k(NbdJpkt^}oQO36;;s^bB&dU#THe^#* zppn0!+O9Os2gnOWf*2B_{SvK96n#%U`F7a3D+hyegRB4wOL}-DE5DYVs);ndXakEhKi4ZvE!ERkGEiV<$61c9`|`T??RWa3B4O@=Bt8*oHvRA;@cb^6iuMU-D2i{Z+XJ?JJ$Wa;1u2 zn*3)rtN46kOmYUN(%Wt_(v32ePT>f5s=IqBG9mX`q4+PX^r3&CE$azK=ii0CTG7Yj6_&NS*~nk9A}MIn}dUF|&3z<7htLKR(y!*Gk~C zoE0?uE@;IVWpwv(aD0|;?U9@g0Y`Xf#|g>HH0ZzZz|oN*N~F{sbRX>}Q_c5y<#|#- z(jf0khsVz5#tvK%~hD)Q&Q3(xK3FZ3IJX~%e&>ZCu6 z!GB~P>WB&PAQKYx^>mr7=XwgAL4|mm%GjMW1blq;4Clfg2NG- z>3+`Xi4_Ww5M!@!JFoQgODQpTNuGy67x-%5ud)}L(yiOGh?no3x*K1(NKKP;CyQh_ ziM-6ePJ4E}uwJ{`b0#}vz?c!_y?7P$)u)`XsEW3|cEmIJ^o$Q?C==@@zR6x|uHf*L zJ>0mR5Z&*m9^!6|fx527OJsLw_K1=`_bq#oN511D(C8vFJy8dp^!M-v1J-G)56^zC}wrb%|u9nb>eq2ow(l*uqH za5?GAziAA4*oAZRt17O#gIJ)i(w#%E0n-4evuM zR~N-c8rIlr!~+Tg2hN%z+vMo6%8#93zxNt{_cb3hTsZSUgg9ClTC>ZgKJ2wf+#E?< z*+~ZcX{-)OLQRuAjFm(I@F$5T|M5`afsp}BRC1}2|K1i=nQpyPvSaDc!KWF#7N4V- z2{qSd4`URAM6XX@B7eVC&W35MOzZJ%kL8N{kya`&+e{P@A!(ksr~aHI7%7qs!!p5i z*9DwqSTe-Prv&aAGTkhO4#zqou ztkj?81E`hB#AkG)jeJsD7@=iP!U9Q-!VKgG z-2UwTMC-E2*;7q%s?z_?ADYaic%6iel}`TTZ36GzN#7ESvpIhrE5K%L zR9YcA<7$wV=Y<6`e&Y$tB_|G@`a!l&vc;Rq*#3Td{}Fv;p|%i z`OlIpI)kEaZeGXrnfoq-P0bvxAcRJtnKP0?-KC2w_flvuUzlEf z#iEk3tuQo!+FaK`h33c95e7j`QnQM|h4xB@!7APx;mj)Y)^${&)5ab(dy>iS_K0C9&Go=EA|nB9btRIFL0T2) zJha;qEUCLcWf{5x+|LbwQQH8T(`6A<2#R3p$Aw|VnMz#R3%#tQ;Lk@7n%{sIgjz^` zywE6$T^8AEMtoMu24N{l=_z458H{?Oi{7S6bu;XwcpmA3sazkbEBp%f>lZzgx}P(` zf_JM+`Yqy*+#B>n4AV7Z_lxi)m(L8JIkUlduJ8D)<2wz#ZlO<0UCXDBF)|2}eRTgx zzza`5wK?;Eclj@aiP-~ruaB6=JKhF7dVMU-81P{}lgt0IvVZ{x6yoglo=@dlO}_9M zvB-yrfN`oFD!n|NwAoB2lYEUHfomjg?imu^2sXaLhV`TuK5}ku_^x+;LG0Lhh{(KL z#^b(wnA3x^4BmANta#u?N4*Hrp=4P25iw%52ZCR_M(C0uO@ELWA%0p&D30o5Bua{u zoi>Hr*~qYRCqb_J> z0g}Iam0n7FHFnrSD$e~B|1W`=6nS}K7#8)XB0e%)F@og8Fo8`Zh9px#mOD8q&TW$! zNv)`;_B%0F7nhk$aY(9oj5u^?^8uP#Nh3Zv^_{>E_G5Sye=uHx2Z18UDv4Ty2TJzF z8=J@=Q@N%w8F9Ulj{$VylveEF{3=Y;No}$g;ToAEn`Y4asj=pA6Hk3s1NkY(RqV|) zvKK4O9(T3LI5SPfHkz~Ix>Kj(*)a1vN5b&3G^lloQ}R^TexTwX2X1oJc!P@b3Sm@r z0lO?Orcg2{5I~l>=};gpy)(+vnp)KKGw)0#5`Q6y`iEjD>9A6;EP9vB$R8lI--puJ z1A$LlH;Cjfv9@oo#`6VJ-E)L>dl3Ucl1uL#NCe-g_=;fAul&o4kgN*u^Q25^8w=>y zr~!^xn&&A;q(p(Y@*M;3iG1PAu$Li5&=Q>KqB#|68h8e1lqY+EN2}7)w&I1KZE93~ zS*gZ51FN)dl3}d@Jk7H`xn2F_uVInzfB00WxuWtO2@E|ASnVFidr{E`7O0lZw95qJ zYYJOnGw=dYkh~KDi9c@|@jr7aV85uVRkFGpd&dGc->T!(H`Uu^??b|}B;3-pkvT&u zPedq5Wrv&|b_yP#)qEvD-_mMZ1V2+We&V`NA$i2_?x>nsp&wP9T-qVdjW%$O8zl$3 zAWZ}BZAOe7RzGf|Rpfe8ZKpc~H<3CCt!g4FDCWb!fuf2p+^@L?mX(`k<7E|g8Jwg9 zud6OPpm{^Si$#y)6*7=_gAQKJ7bS3*z=ve4y{8bdX^`(lN0zRZk^Ap38TAI<#wuo-es2c& ziDFr=dt!5bw7O6KzzY)uZ}G@e47F96B+dGUcsKHbWRDB{3RU!}5+aBHV$~UI7nDq_ z%sQ36NCrNrY!&=z9rawPj$9VlUi)IA5vLx#p5xN=+nb7-K)i;| zYLjyJP34h}UEJq&VO7x6Qu*oU&Gm(Ef_LfWMeHJmLmS?ciE`{R{0~Xg zukG)1uq86L3>n%*I9*KUuzS!H!(EdSayD5XUwzidb7eOH5$md7jhI&dwtv2X&uZN^ zqH%zQIxQr)6lv{Mb#O?rp_SjF$aGqyGN@vEvOy!ypD@mqX=aYZecp0CQcgCGV$RS9CBLj1Hf@?|e> z{!3yL`_CMAI4vc%(?st@`G%&G@TSXGufgrSi@SLO{>}QcW$WdqK|l!klYpvmCz;U) zBm!k$Vh1KynD{SrL-cKNx99d;&ml?2dZgcd?-HiJHzLH+N(!-lH_-2yl)j)!4!j+s ztUV~Gz^EM@6df3s1MhXUkP9kYt_T_?hnvZln8_bU2IQDXfOQh zZoNs#Z~^Z6qbq;zwZO5zL~%oyVq4g^ea4}}&IPG&1c^6lPHVQr$BvJ{Uk<@9Yxi`e zY0A67$lBedYTulK-OZ<0atW}*rw@J~y5w=EQv^~{gpscdJrcny*B^faKf37;200~O z*gNAljNug{P1_H^yfwss5%`skFv-M&c%I%NPTXwl;w6BQZ-Y(~kB_{By15c>=I$18 zEpOvEKC%WMYhqUyLQ`Nu;9Gmyy}CQCejud|MLVy-znrGk#;b7hOQEqK=71UW{IZtV zc)b2E4-dEwPMHA5pTL6;kY^j6y$96!k66^|s6QW2w9Of_O%goPbGVY@gODIM$Q%wTvOH5Tt(o%h=WwO+8QR13&`K?3x z(L}MxjNso43-*L;JFvfNI0Q^oj%b7zhzc7_8_tSMbd?N8udfG+XcqAEqW$>_`I`U% zX@0)r8uCBE0?H@5YEz(&dWOLRTx{h1{(?P|hL4k^-4?HQ>|Z@_0|k0aA((>bp_|DILVoKwQ9U^U zjHtBOV8iZk1L#@9{!+rW*0a5psrIo+#+N6eIDBmILRygrlDO+wqdnxN9B#x+y&vQc{yyaq`|0D>mk-tgELDlhr{PnXIk0E@W;t}!*F*U@rNy-AW?L9aaCN|&YVf#T8;RP_aHF`}24OLSc%Wf<`~Q;Vax?fZ3V5nc&}TT zBrAr?8}9*It2FlYR0}ACb5D7!DS`k=cTmWt%Hi;N6HZ}?eqjOqAdqKp_x(S%Kf$uJ zRJUAC6I)Beu2Z2YHrY3;BVPUL=x}c2?%{NjCgJU|$Z{cf6v)7LH}GE1j!GjnDWv{z zCM`}$_ZCa+B3MS*&F~d5Uf?4#t#tA4X-1zXVb(f6)sI;mXHa=$d^XJjZ=&65*ZUY)#u!Wq_-0Ui(tYznuS1)<>GC;- z%3By=Vs07r5G{*8>Ph+m!0UBO=iSR%#`msxk}>6;(RJ5}17+TztY+L2^YsD%)Hio=3Xo6Ya_Q+`c>*O|C?XJ`NzUp zRmE9vc(mB2$lR#4umLPNn!;yQ=^tMee(X)*`d!!(U#ZI=(U!Ls9ZRg|(eUN% z#*t>|YKsx@E{djYRFAo~_8qN=s;S6cIS|Bx+_UkaC`-!I%PbMRwu+kbl4K#yUl8%Cm0WZ5%w^X2L<;LWVca#6s`TFViPYeR27R3lVr(s|Q4217 zTx-b;FI{;5h^EARFn+MoleOrINy=mY`t4bJJ=ry9@&bne4FhO#*WSy&s=8`~J7i-a z);&wj(<7hDw~3OvMl|c4;7z6VlPcuX80n5$Vo~vz9gut3^=h36 z@k8i18nWveQUVj4vV&Y-w0svKm07S9j?2@eGd@7M~rld4cB!W<`+EQpeFdRG~CiT(m;22s0>Ma9Wn6pO9b24 zkENLRWn(dsV?CugZaIU0#CS|bp{r{Ww?pMn+&6IXiF@KHuC;Ii(~`d?a0{b;5BnJwt@!!4GcxP;^ViN9L;8`a+nE|MZUYd32VSD3 z->|vgmqoFeAlMyu5OFFt=VCJ#C7z85^vk^L{D|(FUjz?Gbkj2lA^8@&=S35iefR6b zXogI-B{XjpI%3}me+-)IxLKN?5a&qdxVO5By%b0_w^l)1w4iajASt}qRsCGQ&~X%z z`0CM;C(U4oZ#8CXY3k2v-A0x-lKuch@705omfcIu^a+dP{k={`vm%1d)(gP@?ZwRo zPTt3N#A}L19GBMye|+3b7p#g4iTh2SW5j!XMRhpE>g`sxSXa1K)cXcIHvRJ0)$$yk z{q;M}eNIwJTAsaO`Jr(zclFA%f*4F*k7Srzqio0P43OB94eR^4-`^6v-j$f!Q$Tth zwD_`iqpjm7+UVCSI%Mb?Ni;x+3GShTwN5qtJ!n~(QvABt1m16P&gcW+aH~{i_%A21 z%~=WKLL;QfD&q>UcP#N66thPiyz+5n#khS(I@|ZUfbnuI&T#@ z@YiwvuJQgd`fVEU`^?C9geD`xC__*Z*FfyPe$Vs2MyC*lW30SWcalV!9|$~vsye9N z{Noih)6U|>`K;cFgLqyaP#$1B;JtXNTt7|v@vVmO8BQ?8aL|YEdN2C&K~Z6U6gh`}XXL*< zRG(WIU-8hLhbk@+tLw`2uR5s0ybFYZQ_*&zGm5|D9}o4uckp)9(`>!5)1S`<6iF@r z7!dlkla;FHYqmZK%ybS?uB2)Du$eW%p&M&vT3uY|++FF08i*JFDOA1G_HPf>Nv_pX zr}?)0qCh1}9iR4q-QDKy-tskocUO@8Xlp=3tEMuuyHp>9?|Pte#BVdf{Pkh+8Bu)f z3XLv6HM{6GkJ7=CPkwCw#-_VzIk}Q9+$K0Fd5Yjwwb#!4mcVp+Ws$Eo ziE&8FwOjnrv}#D`F}>_V)%4(B9;#`$FFJJAxAF61lgKCcbf3A%UxBdI(oP|&0Zh9x zOlmlq>8mz^3oyobUD;BkH2FEqB2kJ+Z!y8qduLJQ5%<+Ibz!b=x(IW&Ffu+>-ppsQ zkH1jOhPZoQ{fL|Up}QbyLlTvkWK;dwD%;V&_`a^fFg8=#={!!jhF?ySnVPZ6R#@)i zmoLfE9fP6}nYl=%w?)X~IjbBeHKmvD-YB&*E1O|!mlX66S{Ip{wq~R}{L{EzrW*Rq zVn;XDqpi%ShJj{JKCwQk>|Oi8@LpKkdjad$O7C|K%+z8hs5C$Sf?@?G!xuNT#4$~H z-zuxWMW;8-nBf;@rv6>9Yh910rEO)w+S4x?r@)>jzofU6%NJ9eOb}2K$-$mf|QQm)fadI1fmmj6S7{YJvC=c%Nz+rEX>RFBfDW@JpK+uO{% zE345*PgUJ#G<{E;drElzz{#>mip*&{{y zvAo_Z5zbjLVWeEWB^6VZ+4!mX=Xu$u*+P>IJ@llTjEY8yOVV3@o?BT@qub3AB-~Dv`ev=(kk>?6ZKPZor;&_7Ohe=|HZXU=Q!qji0_#a7|Eg1;ZHBXh4^ChIRCk-Rh#B=u(>_F)UFO^dfP_AJxy4C;6gr!c z$DFn-cqRn=#s2u%@(EPUYKHVRC)e^deKJ$ zTXpI09g&!QFp5)n&CoBBGIn8>EKWEqNIJ++iEWmIYCzrpZ;{DS?e=@3yIP~zYkbTS ze*0zvuCcV!*-i~)HKdi zDoe&Ja)qZMBI!p|!@P6MxY^}YpBStg_-fXg2{o7}mvV__FYa7BwqPJXxpc9W#@=S6 zR42H<-PMg)s*!MQYjEJ!bK+P&T~BBSYPod=GO%(5zgY)IPyB9=Mhy>86m8zyD~eWn z)@`I#yUWF+g_~3M5vGwNdQ3B?Y4?Cs5rhKw))+lo_)dViDE+p?DMU!H{-tiVOBcEF zQXY5h`hAiSeq*iwn-`0O{1+PFF{WVYSo6;1xp+LHO|@ztnYDF}IGPPA|E}TIKTJ)X zTW2+WwxiSZ+g`&fDZks~Mjm6&vQ)n!w1u=CO))di`zbYZrdVRFw!G6TXBd0nRz_fL z6h}2uVD60mxj2ArRm5m;?WM=p~4+qT#ZeEeT zs9;!=GY$dx_5LM+)Q5mOqhin=%eJy+K47cnea)9O9}!B<{L2VVU^Q4T^ew}71{U_b zdaP%wIh74!h&0}m*v+d55f0p4f7ZZZ)SF+V(@7wz+V3nTHW>t`2;RTg4Z>L=mm;d_rL)#^YZ=3t?UAgUT`m@rL9e zlGE{i)KUTQQ-ZswCr__b>+*4JdT|JR90v(2!Z*pF+eT^xk|tY*KhiZlaI5K9K8(NU z-19rsWrI@eei+)AT$~iFInQ*eK1qFzqI2aL_(*6L>B|BDc0V!Z0b^$j_haWDQ^0CE=*KTH?N>d7{-=0?FUoy=7 zx&BU!xoFA1IIj8lCrA==v-k1u)pyLbQvt?-u@E1#<%M$>(c<~9h!&4``w>2r1P9{` z2Aqj<`&Y<_dd+6K1>QE)i}Noq%Srv-s&-ZQXmd5TL`~Gh@ef#3q7VtdU32Mel0!qg!T5m6}$QEzOb((gvGOQRkhMJ6dk(E`zhY|(EO zqTks>m*_^b24Zkn1EUM)K+#?Se{f;bI1KWy zikI9xdy&@W|eVO3FemimdJw5~=SEdLe)^vC*g`Itg)oyG2Nq>BU zhbtZ0&XgoU`3Fhp5%G0F0;ZPuI`D4j_n(lL;S+dLEfE$E{NF7vQiULj$RL_0a5^s^ z-^(~kMaoqx;&>kD4+@CgcKo++C#1Jmq)zfOIFb!ht$5q~1>ZUMfmGwj5~9azP_TE&&(!86oJ zQo_yfA4+XaaSUmGqgVFkzIQTNs+X=tpz~_*cO)F(!I>>^{-kaXId&$oj)$1S)|`o{ zN?a(YGu{c4zS7PR!r^%~f3H$8!AS8if*p(w|utb=efW2{r85;prJu zknD4t?2xGJ&%($dZ}BqroQBUCOo}-@nJ=5&(Zf->5;9o=TRAg7bH96M#8Bt)>%J|oy+_oI#yBwqJZ|5=#xs)8}ql*+ol4*9) zC|e|jNO6I7ad=y?O1qBIa1lG6gql9`?p|}0&^vvfce*0E+R>(Fwj=|e(N^_w|M5^C zmb_9baknk;j4tsmFYz5N@!Ks4z$*=USQ?^K8fIG>xDe;ZYpbX9o?tltxot76l6g}Z zl7l2OJ-RHjyexaTEO)moAFsUdVfkC7@^`l7CDEAjvhwn~eZPNss0^w4q(VnNNzM>~ zz<+tD!xde-6(8{`TYVtSG?jN4>fmripHIcmaOIcXis9YLiHB9=536Q;DyMC$=J6`$ z%Bz;kE0%VvI)q^0fPizUn-9g$;p%|)>R)&@KG)U9N;U2xHD}Q^&OS9)?Ii+% ziJrXGwGV3{%C%T_wKy^V8t5IVEgr^hXDx1Cd-s#Nj@3r{c?w{!4t1ugrjMy;eGFxw ztwwOvGmq4^L`)X$gKbJ$gJ?bT1Kc<8uG<>8bu8#@{sZD$&DNgCyEFpWVZO-dcP?V61`G57RF8lJrI2483bmQ-+6Msh}L6Sapj#bUd8H z5JG$Kdz~qhRX(T1e$FBQu)06z5ex&);M2P^lREEQ93a1CI7JNp=Jn^y&d<5_@O--A zH=g&?)4e)=iIA+7t%3KbT&?C zw@UNJuFLBfyE~ESPz)$8AUZ=4EGSdn^P4#80M^Bbe-_|7m#G%26Jf_;@1Y{nDTg6J zM6D)pMg;z5_lQgZkr0r{^_l>e5ckNWkAo1n+c|6EoDwjE3&l+V&M?|54B<{UzV&({ zL?eh&VL--V8UUuCymy}JRBlNi!A>B2E|JV;2A(;?`D@Z3ZW=h6xwC=42jT#Tq2gLX zC@9bt03=o6Xz^)#ziD2=StapV_djD;b@+0#vna0VE-9QA9vpFJoV`RmZxY81ZO83z z)V)VA*+A@`qrvK)R}$Ma57dcT#<3ss;DpjsS?2V4qjBD;!wzq84+C+O0fJ3bq8smG z6X8cD6hQJUgcU#p7cjCYfG_ke&0sROpU@gD%7KSBiVY{VFVh?fhrG!DCbF$^Gx zzKZ`7>#WkC9R9L2Mz}nwy8JC}d4YZ^KahA8h2wxCSRKcBPwj*|+feQ{%*(o@~7%_f(zUOK8^ zF<@8y1Ct3cK@??_Dttq~x-As869|(Zhy7ZGLF%v<6BByj1U)D?69BzeMQE6T*V)~@ zCcXjita~K=c(L-sSk2q4n%Kf|YanB*yLJnJ<6+<%cgyrfy${a4=B}}AaPY&Vdi%Bi zRsh4!$Xx7KsyLuv=kJ#t{evAZhAnfWEx;Lrvu^TXl-3}#nosd*Ks=`Z@b8G z>z)5Dw**|S`|jWY?jo_hsfjn_M`^je{_-)c`!kzhNV%;B zFDy7<>OMFyf*(l?%{35d>&yVoGafyMkhMcB&=D|xfP+55zN*3doQV7J=qCPvIA9Az z4Ak=+UUw%90DxE3ET((*yTs778YN-=0i5_ZQ%wTPN8AxDDdzudPzP@3nyyz>QwHy2V*)3oer~P$!|xRkrd6u`s>OwZ z@YbE-s9NGMBRDCFczq4Rg^OF`>A0=}?@<5hW_oT@bB^6}?kE}QB01Vd;OtQ2eQ=br zD?#Ze34i(VJo2e;Xh2GFM~ZmaB?Oe}xpoNvSAhwaeB;S-N5nY@_|oWn7C>wra{(#5 z$O$-4z+7OFTmpz|F1_m%J?LH_9`?jFaCGh9ikG?D1@J&NfKgB0(}%jJ)oA=5hzeJx z*#4b;?;v7DNq9rxpWKNZ&%9qp9cPAL@r?s0wLSoWMhA-__&cbcux_F*Vj$dP$V;8* z0}osrz~I@LKpX*rU)}Sq_;8F0063d7JVa)nP9W#T*Q6s!Sk+h}@pE%&!{!Q^Y+!1{ zVn1G!?1OCM2p@MZ^dK%PvT2#SKX3sEsoZL&h^?1Jb5q+-W2gjOp{peS@le_O8LE)7 zZe7_LCst#*l1+~8R010V@r=^(p_d78G;}$glU6|D z(QZLtrFUe~8|HEEkrgLNID9AxDUEm{ol^~t6MP(6aL9=^>=sJ!e}cbEI9UdQUzdD6 z`{;KKFa2gerroFd)5b||u*{Urxr6!!YkY$-D}2xbw?;W4#CL}~H!jm&?D%}$U+f4Vmi+MA@^sp~21#P?QbKQR zV`CF#zK`BcxnUbl5IuzLCWxJY4Qj-Lw_3O8J)>Wm_h2)|Iv3$yG^mRaFuRV0o9viA zcmw@MP$gqks*^g>y{)PIDtBc)gdC|$lDKizO6C~x%5?Y~S(_PF09FarECN|6;zV*B z^RFv2*H3(k^3`r z2#jBrkO|lWt7M)BPu3}2AMTK9>%D9;1(}SanI{jao_pw7WxJp2*}U~TCt->rPbGVG z&|}pvRYA|EC?hLA9q+h*75+flQ>A(2qWlw9AV@)DkiqOpXT2elOIy!kz-r>TaUg`k z%On_I=+Y#VOxw#eoYv#gG?F>Z%Pg9s`O++w|C^V2yy*F*d7?Chw?(qD(3M5%Gi`6n zv=<&%mKo-0-d0(5%~w`AufBO(=lPyrSr>#*_}CQ12wmG0r)c}Ue4p)c{j&6J^}KLd zMf0_7WkbAossmjz8eG*!;cH(%5}sk#Fs1G5(7brR3Q!*^i=f3w)3i&|`9`}yB>=pu ztvuJG*OB^6zfSDFOUIWz$VSW!$>o`V<2Gr1yS=9zM)_x7pA<@8g~u~6)D3>8JyK+a z$&3d%#retLu9Nt5vknDowNn#J_hGJHN7~i14-g9W7lswcOtQ1Q^`KjO?Y))lDPf7b zPYht>w{tVOV}GHgj7f25;GE(6tIcdNx8f8V*NZ=O7Fz`daniZHzMXz zp5gD09voWWcAdf_Btb}K0xq_?p-4#0h;|*s4(?xL3=0Ysy(2rZp6^!lZ-Z^|v(B zJ2qJXp`LICfpz+KJC?k0-YQJPO!VjQ2sYbL6&txJn>*O<|AHPp07ZZSdI^fa+`az( z{hvdR7yoO}<9{iSKmSo44-PPgQ^!aDAdmkjkGs47xAORN4YU2>f2chE{(mZu-&a=t zw?vR+JQ{eKaU zx1phbz19EMh{rPr$17{YQ)81$eYq3OXP2syCvx%^D8W!i$2;ZG>E+8i=<)8S{J)_` zBO@aN0|R}1eH|SgEiElgP0fE>kIKr*3JMB$)}ySf?49+9LZSX&*5ft@=iQZyVqQme0T>v-YJhPEG+*GJ<`$9(bCdVQBnO{c_bqvyMrF#aQL0`Nc8_3 zdSt&_4*&qe03aBhLTy1$2#n<0R52~+pm<#_6J?htX6Oba49~ut-13jw0RmxRr`Y-6Q z#-uNrUfF{qiW)1j{EzTPew--&x8d9l;9#jkdT-#<$VJJ@hd`3QgetnLtG%Jb%m)=- zyn)U9bjn0a=lMTIGWhLQM%x;;zZOWxFsQaS{+ud(R$=s|z3Ct5u_j(@-g>dc*Y3MR zWj5R4iuW&Y`i*a^@!EhN^HYY#C#FNAZ)sVMo#f{C<{Iq2k9Boi9Ip1IU>uaCuFYFU zzC3WNUU9xY$DZ#?ugUZOb8&>TFo-W6@cV8Qdi8rCl)`2;2zI}eHV~}jN$U?epv(;= zliFbn`)ry~7Kd(L;UY6KZV^k-P4z1+&Qd4H$R zNSE^VXE_hBKgi-E0D#o?HNEV-9vN(x(!o(bgR!KvZOh{5 zJI8z8<>=c6;Y$rUKPU)F)?bUk!fVec5393<7sk?HHf<^!zuE3pZGFL`D~7?=f`hP9 z6Sad1m{x7g-t&2KnvC#e+b4f5$J(oEU$_0$G-p+z-PDfO4}wzw9F;*7Fb#A=tgI+q zyI0*}b$eHxXjRpct=(bQr6z5G_evJWK`qqZm%Hnc*C*GTL*)p2|U2vuS_NJ zWrD|GxN+(e>c%#16|Zo%PN$e>RTHOUH8F8#cYj+QOTSILv}c&Z$yL=|K(+b7m+)4& zQa4c=Mr|uU2UPXk7p}Q3w+nC%yzeh}Lx_c5!Q2R}8Uaf$w^oyH3S)r4?|9_e_>?kE zZ0g1srwka;!@e_`@`V=WUZf`0oC+2I;>p%k#eb1+pxH8zPvM*1b}NM!7eS2v7t5}B zRojInHU9qxQ}^Lc^&kHM|18e2kG(ne-g_S$TUL@;_9kSn&M^-nWG8!N?+A5lNjfBi zj4~rxm88ynzQ5n^zOVa#cz>?zbG=^A*YokFY)N~P2AQ2eLkr-zX+n9a<*uyI*lT!)rHN@3FSCja-^djF7mLo{#o?@b*;Qaz z4%#Z|wsg)>71 zH6c4ydMD@69R}y39$~Z^+win)P<3Aa$qpzT_~?%F2nqh8R?Orhh9|ZHT<(Zgo-~>b zDLF6QH?3D4Co{8XJ%4)guwG?Vga|#-KfM^N*ZfgTco*!-L-L1GSaVbaAF+aqT@K;r zW1hx~Rlb9r;V0Gh5pdI)VOT11QVO1+F{A#O8qt!-cE=)tuE?20_{KBi+tc#}RSOV- z%x9)1h{;?~7pcG$MBUY%{N7k7^RO_6@1i3`o<)HQDLicXz#<{Sowu(0#D@%RZ$(cG z&u-XGvevOJ6c=2O_%?tICyf_7OMWza-)OR5nqKUE@uMXuv&oUz_Woj`hjq~~*@*}} z_GyADm#n;XiO?gwk_Mz{0Tx;0F-lNwheGGvt&|UpEYfrHR%e<$iGATVOm0ja*OTI$ zr&$iWXT=}Ik??<~DYMf#`OC-vd8d9rC?Ti{&HgR6CGR<@WU~RE{ENIz2-k_(ge)4GH+atff8D4&v9D85uE$^S<>CQSj^)h(fPi=(ticrtmSqP$|P4wZuNn1zjG|!nn6zm~f?X`ZRV-w;>)E#T62o@lR%e|g`0FeFSa`I?X zt@XERAdr|~)|@}3;N#e)Kg2>MOOL8L&{N$6444S|?Kb4TaH~3kRki-y(<`MbHlgfqGp;BxgRnFd0WxLmm zOs7~b80OfWl6m3onqm_;fv539Bi`ylntSw1D@+W((1lVfEUJ5Dgsi!7j%Sa$WzSK^ zU`H9Q*z+n?Y!GDiU+1zVYq)dH)8hwuby%ons+2PkqK1jA)bO6pyZT2xgIUNluI!d4 zDTg(;VtlgJDPWCrk7NL9^C;Tz$`UGZ55rN4H)avzQ=G?ke9?|QcjWt?$bV1x5M#bH zp$MRxqw!_gT=hLJeM%uf=F_0_2{y?*P`w}MJ?bzA9#DEIP}Ux6KKq$@=7r5u4U?1cc2pPd#CEV?4sTYm#%D-YoTv*)UBeh*A)lCDfip^8BSk6vHNU}V< z@~rBRVt+Ka|ABKEcd=V^D$A?Vx8_WR#zB3%ns@tK;5<~fS^gg0WRI$wbNEuI<+yS- z+q+V!`J;MR5BPo`D%xIlkp0DXi$oPDUlR;&{}Z?Ds^mWUHtTa;{nOphjj+{&UV!mA zm?Z68QQdd0NQq}UY`K>MyIo1YDukU>o!35obc>JdZF4&PcpN4x$Z_)NN?1?lb z^BBgkmw0!r(9l8U-cA`#O|y583Mpi-c_p~)_%_24whyj{`pfR*zq0~wnkKI}Y@nW( z2OrZw$EzN$pU`S)5We0hSBk%#2%LGR`XuM2uzBLu)rq;q&v$->7lK0Jg&%{z1r`o` z`f(gFET=wxU!7E&{38Esk6@+A<623jd6TiYhvL?&Bdkz`wXl|uUN?)u&}`u_6pd+zYH z3N*kO9XE_NpbN7~jl9w2GFOpIqb#Qfi(_sOE^rPqT~6(%i<6^IAaasPw%C+NEVc-n zgatZ5^qdIZCO(xW;2a8e64OzX=^y|wx}aJLp#IO3M0%*O#0M$g*YHL#z^Ote6LTX{ zX~9^#1n~R`CGTcxuQ!KTB)m-yo4%a!vJaan40mF=3)pniy$QPlKs4JQYQn()+(W4o zmOt5~0TncJ%IV`?vDC}=$v~v4OA+qxQ!m)w-^gz7d8;k5GU(&_E8FnLK&FCzK1D3D0 z@Ny-N!w+`^ywx;*s$U4ef92mLGLxjIu>E%G3`Dl7a?+M}I;kwkla!3|H_y9Y=~09R zVd3_OP1_vJkIc*mu{_>x%5`o(FLS`BZrY0Odf{*ZXBy|e6bZZ3waeUp!}k`^AHV?^0Zx=A8AfWBR)A-mVYm8Q^L`OZPhi*Z< z3WH}9m#$GHr(FImpL|lE!pIKrnkQNMZ^=g=^X=)1=C=Uv5LD(Tg(WJ=Dk71I{h=Gs z*c7tIl1BNzWytBZG5fSv! zqh&AKWvMv5lZ4Ii$&3-aS0%E-F0#rf-NC0MEehdUao<$B^e$7e((ml4VqpjY;N^rb z-Thr!Ud-L^!!-~kx@uVRI~dT=Px(<5QKJ@-DK9;5o5ZXMyt{xyG%^fBr5rS3)!t=TqC4ekqaw zTVydsS6=n2ID!GWIwDW4s%G~cM%YGRsXrD@aG8mJfa|oU|bMVQo;AN z{zT>3ZU=a{nEY6~Zn3To+bH2US(vF>@QA!F;Mub$qE)c3+#Z0Wo7vBh)7q@dmx}bf zip=aQj*b^KQ;ot-LH>k^=KcNV6ys+(sx2?s%F!p8%PUP0JjJDxH4d(Tpk9*Cs;y_! z%-Ls6%$|+Dz^d^QZngH{SBtF!E7^X&Qe}(fzkD;ceOsxf+Wv}mWYGdVojrH=8$YJE zKlPO|m(F0rw^Ki9YiFxwr)Xgi^AX8l5ywIQT2L`Ib{wlRpQH=q5sJCN*-5;IsWdUI zaP|%%_L^NDQg&!9X+~@N*KFDUK_k~INWbWJ-k45Rdy}Lg*0OWeC9Kw!r42;m0*oWO z?V4Izy+J!c6#m)ZIHsOYFN6gmLT(Kt-KOYz>PjNU~FHiT2tzwJF(=Crz|4 zR5!4)KR;1=?hx}lQmr@q4F@C}I{dml{;Y9>3@y) zw4b!@YLhnfM|Z3awx_dJTEH*SRA3p3mBaiAzo>aad-IrIT;1W|L%)}Mhh@7&sSQ^# z)<4L4TeJHKL+}4`kvU}hCj$&!g`BD{^>4o%eBI;5)ROUr!)3E`5fJs>1UDb@ctE-j z0H^q*R=n{<;GQ6r4FK0Ig!_7kI~;jRRr(TJ35aSBu2vf{{6oCACH;Lurb$dp1i`LN zWR53?pX?3On+$;|M}B&8wPbVzzaE`D%nsY6`U#*ea~P$6jG1Z2C{u>3I^s}+qqmwn z=V$>Qo1F{DhVM@X%bvGjAuk>#B<(Sc$19E79*t^IPB21WNyI!mJNOYw_ zQz!1$Pw-H_daFGdCO(zl^kRsIG!_@2L%1BjeT|C{cV%uCAZA=*IdE4-s&$E~AWL93 zp89N)LK+>DB;LjEKkly{JU0wPBbp)7lj!S|*8X_O(W?CBkZWijg zq)e!GY-m~?tsR`0sC+&g)zW%2A@_5t{7{z8?oF?0=M5C-5(xu!*!x$+jdHYSUQf=N zGLU9NV{xr-Ic6!LZ%s{Q)I_N68NdCyYX}1v=~^TZk;o@-yC(}q@AaHO`Hlbyrx67_ zPykOFU{16iPrLEpA#g0-udUsT`YoQ}@4GnTM`@rmkx6l0G`02xU>p5p9GuIYJ2@05049G!a@y=5` z+oul3n@#gLh|!S$<}Hd#O2F08+cwHK^$(}Nn1;Q^Ots)?Vy+9~GM6Weqx5cwO%wn3 zCtUl`Z&ykm5%6y>3YXJcW&>tEqNz93{ zSK^>&7(>9rw1T^y3R2~;zx`$RRmP7pU~8cicv3i2db=o<9c{oH}?@4^rt&Mw~1=YZ7;5%7(Dt z(&Az5G{Kl#;9-ib4p6+HlLBE@o<%xoeN=@U;d<$|eoCTQvUr*!ypSA#f&Z7#M?tKEu=KtL?QgN53+i{@G`T0}UL7+AUKkKQ#RUVRanMLS&3L8~v(`TD6sQ;UL$8ABg#`ov z2Q3Ft7Rkd)vZ+0YNF;K!J_wyN0tYyguS>%R@Vh-K7Y=lT^A%g#uM9s0o+d~xH^&z~ z2F`g}EbnqowYH9=mT+L{K_Br{8fYyUB)>LMh(th8L?IF(8r)7(aRT;{rrd!`ss@s4 zXOn5IpD%HV5knSHZNEa_eR@#tvZ4Mb)jT#41yG|Ro&E4Qh5OH*_I?CLS@|(5h#C-r zruuH7QA7nuX{S1Cr^dk{;5(bpvdy+Ofq$!4>D|AE2%mnv;ymU)Vrh8-ZNSrraJ;(t zV1@m!?ECuR6@t@})J)I4Kj(L+QkpM}xLF)ZA&szo&PT+dDRT2a=n+(OdT&BIg^E)% ziN(@&7*5bJ9V@c@qMrqjG#Xg2+%_aak7cN0s~zJ4VX-^@2hx?qk*8~xqs6)BWT|3A z$kA{52D3`m#7_5N1DdM%_be;|_MxBW3dop^$D>a?Y+5;64BdWqAKG?$ye-pH3l>`{ zwtP=rbH#*oB>o<*=w&R`uxPqC{?M(pZ2LGY*fRa8pGjr~G+h&A$6ohwZ$uo{iwc9f=Nc#Yx~@~>7Rk?Lve+J;tE~v^Ntzp zsc}D*7k5}jPk3~nZ8T-R&9Hwb{6}eWbJgv0_D|EKh_juytH+X|k?u!Ys{`g{%KyCH z3e#L}Rae_-p+4+AiZkc^Hk%==0WuHKEBQz5-mVROARAQwL-9{r6X4zp={icg6?_Hf zrSxb95edY-x;k#Or~z`z3+pf`rK8wv?$mVXvkQdC)REC1TGVpInbP*t8&HJsg0D8+ zpf&(@->Ie2hc_zO$)ds@oo}E`?mmUf zA5CsnGX_B3n=en+*z<_CIQDOzh=EG?3U7tum|R?+aPdwK)q~a*_IM{3wB5 z+pbuJBkr5@wKtcV?<6xWJzeClmZE+7;)9(+Eu)38WX=bAMjvsRUdQ_xpu!rRw1uCl zfikhTMJ(5v|36 zmwrw_O5r}%>|e-kkruhQXMK6NutyeQF;3R2DT3>~W^W3IE{R95UwxGx>aqGNQVuf* zH!OLw1G>I7+j()BC?0%n?_f#;XwnzEd;U@v?&>+gAUgifMgB~{6WCi9P z&DtC{n;0iNl7$)8aT^L2st0ktE}K7P6L_5&{DE0y-ltF}rY$ zEPgQcyHi-n^6KCLcN%~{0^L6^*&{Ioh;zHmW15gxR=tq7y$_aqLV$6UgIwD@a@6h`+CB)=vRAk`^~r&rcA zJyWmPiK1jf0`Kb)Vf|k`7W|LCng9y6RAiYt_;0FPFtTr>o%LKYBKWg8sLu3wIPnkT z9l4*o>tQ4x3WEdGKX1w|H%Y!Ub>ta#;~%Ovc+85=)ZzF-|HgYP(^`xYaB1>hKI(N2 zPUcZ2QSQU>G8y%TDCP0PxXTq#q`7nt(XmrQXFD?4dNPk0Aa|(rE_EAdaWYOp9FVCR8$$CrvhsWy>_E~wm!>pchQM_Qx6Bd~UqJXmovnzs>ZfFL z-dy=)&A6#W01hS8%h2#T;Ta8UJ?KloL7h3Hv6)1aHN90&qu^5*^ydT!e6)9;u6lno zciOPHHPbvk!Pnl6_d|9FeN$kZpAp|#sVoF7@?MzM)~SRuL$IaU;!n9f$pBrij$DaL z*xsFcinK#JLIA?k!$J^MMovcYnL3F;HY{PhWH_8jnOk7Ndh6FiB9qUg{!kyjML8^;3WbC`v>(GwitE>>#0=o6 z?khL{nj?JA^<`UM3`F5}cuu0&&Wl)X_d82nrm}}~WTfrqxpI<9hc(4~N^zf!RwfPw zxA~={&GpjTc6hVPQ=a^@Q5hyVAJ$55{}R^zg}r7Ur%lY+>riZQYxU_uncBVel~(2+ zrG(Z9XdLK8Am;KWLhBU%dYgzvzb_{Zt5M_hwJMBWsMYVOGr!?Oz8MImu+YO>wR|;s zx3XB(`lE#}0IYm7cz6%=P7dVj^|P)CFpQf(O3Og`I6$1QlnsT&9k&eDhF6v*!h3uE zgC18`H%KG;#x(-}D`nr)k9hH6C@?(Lfyj`KA{Z*!^txBqe@*-v;+{KH{w78JSKotDI(M7+_#{{@3?aXpJI2!x}aQaKLpvO#SMI&_B(~Lh3)9 zM@rsgR1bh6T8}~>x-l#45B*kr7dITe@$;Sazq4~fc8Aa_9=-39e$p}@_~icnhVme~ z;o0bfqC_2w1Qi_V{Y&(lGo@q~QEw#h>ZaJA>X$NNI2wN0RilAdMJk|+mX6|H3vVnP zI@O>8HckF1y5=fsSW&`Cs0l7 z=O6w+@#4?utLuKw$*-kH&qglXuzyd{;rJv0N(93cU48UOR=N({U4tNs(#oBe1i^EB zrFFZ$j3lxY-HZgYdndZurZU4v0jf=M&BNr)4Wl=8IoF2iA2wajV_H8mbL5S@_WOU) zM~gl!`Enc`N|=8vRR*Q^aLj@CWu+Ka$-T;lrB`uA+vvK$T)mJwHwAHo@-Wu5R7as4 zN1ywOb55c2uNv)EUZpgM$7g5($;a%)>m5wToH%q`7&sQ_00*`yNtiLmP(Aj9;hrs& zN4K7BXp4ovz7zkX$XMeYYhbh$hj;U+hOGV#d2YK>-Ftcbp2Rv%{_$`Q0Zc^`0MUOt zyCK$JuR~NSNS&FrX41WLGGtIc*58oNSDXp|G#(8iq_`WzB@8HksbmouP8zIEmY=kY zoeHK@eet<89zT*DYPd9Qcz1Q8C+)?pizx|^5hiv*V!_}V2x$4tURRM4H8_PC94a_^ zUg-E_toXHI~|l3 zVrn{m-5JS-xh>qE?`R6P4Kb6LuH+P*1*n?QU%YL1G`kh0qyf*FqSTbZjG1r1o6|~d@+`T=gqrcdFC5A88oNhisF>@9J9Z%d>@iz zff`epApCZ)`OWSdFufa<%5<8z#Gy3{s&9f9N0owu7L>IXOJr()#q{Wg-jrM56+%YV zFJ}IVr<+|uCH*jVu+(VfR67I)WBb48V~QLL7Py%d)IMg;f>l~hiD5~_XOu8X6jGqd z7(7ZTJ-V3xT1nqZ6I(0vS)OOvu^{xWr70j%12;Q)Pm)#lG0L#iJ8-PjAPEAIaK{i@ zP81*86FDrvDsU`EQR+=N=mtKu%nw`NmGkY(eDA5%61#rNz7~Q0ecn{55qu8(ww{iW zoCcPvtV}8?hSm9xdju$)F!5bNxd8y4DJYp3?B-<(W;5BPZyx9V8OEAE`J(b`e1Qt;s#lWEEEHKr})R%nN>8|#0Cw9Z++x28Ng69k7<4gIQujBWj zCJojm0hX!46P{1m!uC}Y6mCC%P3m$&MlqG*XbUD`H4YE`@01Of;>u!+ ziG+kjN&?X6DB^h=JUN!-KkHFPVhMv>a>}gPxQ}lN;D}OC@03_I)%)0*iH-UAh{!!o zX<$vlEYDWbXoM5+5}*KlvIYgvUpWQI4!dEPDsBvjQicGs6O-t%a?bWQPf{?;Bu)X= zgh>hJTo1>^(@&tUrZG2eKDf1*he$M9ek!oJHv4IXvdb#>%V1+w)CMmviI$Hd6>j?9m5-)l-Emu+bX$z{Gs*0hW=e_k%_l}?U%103KWn_b zo#L_0n7*)|Y7B6*2z0lI-_F6yTsV8U&I!M?-T_|i*ph!{m-uWl;hyCTK#_8&F1io6 zFXj^6N4)GCVNc7-E*EM>h4sn&fURvtvfL)ptrt7qT&^69Y1%|W5teGkvSImp*W!1* zR}dgjvph;sSij6ohsi^1mt4ZI%c$LDI+=J0<&hW(G$YcFFj5_hTZH@bdq^_RSW{23Zkg+_XGf_Xo9Kk_FN|fod3YlFm>LEr`5@4cMxEEv?X5Aq@5APk8@`nVLkm=< znA7=Wl{s2Skg;t3kNAjA)Voai5l3P0EmzpKw&-VWu|D48pHKM&tZp;ar~(b1*omk1 zc*jYm10#*yB)uVw!R!NLvnlF!b47Fo8&bB@y#KrQ!u%ilNWv1i)*9{}PwFo{3XHZ- zIs4)p`f@3ki!8DsSwR{`0Z8r%KR^zf_ATmXR>-iAcHF5;zK;bf;8NVrRbMUc;Pm}- zywS61q=#D@?={yq_{j<;Ja2lkGk58~$r8!I$r2>^fUyV&2A1%k&-t@LK%%Di(k`sx z8R=i&Zx8-?>KX52mZ4f4Fy`gdDQ7=PJ64}5(Aq!2oVQ&Xx_w(x&7>FvEI^thEI=7`E}yTfP~aA1 zeE$Sm-VG}ZawJ-huYhfKq~*i%`U$`UO&Gx9%2&)(t%PZU@2I3ZEr078IRBz?|;x^$bEK*=YFa;I*UK`Ot>&4WcB&} z|GJNT|KmQg1f~_7_GnA_ShNw?Cr>l``b+7tr(Cde{S&yfJPC8K1>dPk+kG{fQMN14hboNCEF^*?^H==dFF)o6!@cmri*O7e zA(Vvcc7cbxndc8lGD1aVimwP5Xz|0vOQ<5y1moK(&UX2M5)%hYxeJdXx{vFeoXK9s zKYz~t*u|bwLNqtoJ59no>+j_vfHX{4rpVC8Q-M-*=(k@lnb)9q`jV^KNX$2flBAAf z%I}2>VJV@MhO~)adL#4WerCZ_Oc7X9I4PRBfkUUMB0@C-kbH+J%PsKIv^Ba(DsAC7 z)!ncvyCABr{A<%5HXII0fF*>VT!rXZc5wfJw*x-3U~V9+$+Tng&An1?Ut>=u>-vCe zMj#roaLdWdtRg5M0!Bn1UkcSnkX(O@By+`I(OIP4Z-BPkj&>=JDv7wNJd>1=mLsXS zUW)knfRlLWT0}xrA4eP>mMzh9QO6m0L5b+2!F~!zIO&Z;T-fbDi}kv@fF+?9I3MMbw(=T>hk`-#1#eDo5rM)+K~{ zrO~5UMrI-fi*Aa4YX%n{6`Hv@f+bOHU9}Ui%ZI_@u28UH&jg>FU3YwqR%#bJz23JD z$pk!1y5#_JhH`5$$i6Xqxu`mY7miDM@;qQwJxIg8 ztv7(noylhgR(kLIKaEdkUL@Qb5C0y;UH@SI{tNc(u2!&RHk4Zp@nOU1H>MV0u=14u zp|k{SJ3)Fl+lw}q)z}>%H;=01!SbX>=9<1LimXa|MPd;D1}gQ)IzEH2NBC0L{H*-WI*?5O+H&RPo^w}ExIA*tXS`E zwvHk>U&bRH@_DNF7hjAY0kelwSx`AqpX#rSO03Gb56-CA!IVT$yAP1=9mA^5_m--C zC0fiiJz?CtrsWga`!=aGky~1?-4WT;vHQcA`f9d4|KiGM>qY|sK-W8sUq@g{vbN9m z>|*n%Gl~A45`p&-2X(6g-E+N7Htmw*t8_)ogS^G$AWoz+oygla^RGln*4}G*JiE~4 z47-#jZhm=Fu=35y>N4ZvuTkXc%cUXYiYM74fo&s3ev7z&S(E^R`(KOuV@RWuxk;el zD~j*0-DcGThIbSlWt>C}!I?013XN`k*^j*B+Er_y&Nc<9TOnOM_fTlj84npeEc&D} z5of0L?T3X07}=uF{v___#5$c*p;%B05qi9B4>8vT{{_&z=iL}YEW7*)sP6`fd);sZ z`AkDu{inry9>ypYoui&!(`RT;*v6~uPBd`-vTv&#QQ6mdlV`>UQK&LopZY6t^tD-S z{Z@P)01MN84XV1e)V8|TeaxD31JAY{s@soMOMPk0@byQe`uXA42NgFhji9tQ26P(b?xC6aTz(Mp2<5A>LF zLWCX>BdPnYEOJ;V`Q8Z?(==WnF+`7fl!ce=j2{!N#`|klnU?Z<7-DjfUx&4Wy0CxbH_9&^vocUL7Q`=&p_&BPS)vK zr_opSG(*EPeA;xadgDsI8o{VAGO!jK9BK%*oulzP=|pI+v9+teQ1-T>3!!Ii&^A0t zy90A$kiD$c6y`_Nahl?ceQs zeWM*K#~Ww$r2P>8K~bBssU-Sy>0|=uk#l;KKPYD6;Vy^NvxH|BUwo;J3b=xPnVN{+ zDsdort*m3Iv=SQD4EhMFJn~u|uR{rLJ43Wtw5gv<{%F*n`PxMulIVHC$2J>0^>SiQ z>CK&jwrcrhBgM+hIBz$48D|zXR(4v_8FI4Dp#W2H*GI`8-*V+;Hu)r~%?Q{wvi3w{ zv#u)8b1&~()jN^FQM6gHaBwHp_&1a_kK|E^5})kv2_e`S*}ZF~GE)t1&sPi_5*F3A z!ssd3Pe46s?$7FxFe9YeNJ_wwTj?hfz!>gw1E|I?b;Uv|jFfp83$GfSO>T-h9I%qA zdB!*yjRlCm7r9c5sNQ?qroT*pXM_^b$A8~i-&F*IKwY+h%$B2)FS|125n*}72C zqV)}zv5Zt$SZKkI9*#E$gJ-dl##L&cT%hcbgy-$zw7U*n%{#T4$Z%g* z8kF#6D(Ktsggl=tR-p5dzdwkyr{m03fG6{vWfV?U#6yJ0$3bI?rVL)*b0h62jTgSj zt11dEQt|h+oI7pfW<7f1w)$D9Ar%yR60@4 z#p@{Rs(2+c>qpDxpe><&1isXlZzMyloUOwE24nyxg>|X+Ev4AR%{{WL`E-U43)TW^vF;@ z%_7ZrK`4gZmG0)1>-*e9t0F9eV#Dc-!dXz((bMly4`9K6Iv&Qxc_OPkLO(iWj#b8t zHGAI@b1+xmWPeE5CSLiAO{L{6guP<>=t~wWn@~{1e1J9ZTE9B*o4U+WSL}Q|B#GOg z`~K#SyhPwKiDKXjn9_+#*X41SQw4q_3jYh04!AYYiCT#O|CKb1&Igm{&EKTZU>E zWcw_?{`Hqr|KjO7*(M6^tnH5ZU3vFPV{Fjp)1?U8H3q`NVVfXfoA_a)HW(|fj`{bY zOb^Rnr6m7W*d=jX8?~BC2+cA%QP{RMQj-#qX*0B%C z%~pXzYyx!LQ1DHvNY2xK*SHhMe_JeHdAL}k$69~bb6(rGQ>}WQRJjz>tN!IxDc+J{ zBP4LL3?qo7AZ-#PFBg72O0%X76$cLs9cj%>?j^cmNqqgL>mJShm ztkE{E(etc9uCK|~Aaz{bkt@^`-uy;P{DuYm#=P4`b^Ipe+s3`y$QATtFshFh(qGK} zqUHVEmOUyzN$n?{x@x8N2~G>{qMf9}@NblF4R}+r_NJzQwSKL&nZPZZ+FN%7Y&>gi z0{;hkw5jEZd@9ERx=lAylrwz$|DeZOhnE7kG)GJW$8Z|u!#s}KhSWRVIPoN1jnYx^ z&9oOvhz@<>f>rJOq~+R9~6>Nwp}%GUkA zrX!N}Qit;b$&r+(3`GBDIs%B5Svsol36OW9w0s@18>1PN0LOwfz3EXFySA8H{_dXq z0d?9lIL&2kRFP|EZ3Q{C9=Kaa%XBoD6Jb5Z+!VGhGW*%6#ttR_>Al{kgrj6$lDY4`@MQA zy-|@k*3w}u{}I*&G_(}NzKrDX*Htbh%N=1m35Sk)737*9@wY1A znm3WgSZg^`pw|#*Wx*4pQrz_EC7iYs0KVQXI2a&y%$b@&)Jk{pH zJLKAnC@+4tQnzFn&Z8(AorIxiA10Dvbg4|IR8GoD$sw8?BS?49R}K%WGm%!GrM`+J z@*pO({3svi*Ox%Q?=HUio}$K6)LN!?dDG4lnWEj%)nA{DecLJPKV3&2S#o2Z`MM`c z3n!Df>q<5Q+4&j%UK2pmKwJw5*?R2T_PM%DP&BXqsj={g)}^kNDW-E#xQo>JZIq~J z!B-OmsBw4=Y^#4uru!zH|A{;PPK&DAAT&&F*p-I$Ro{$Ts{EcDfQUXGVft4yY!Z2qXyi6j^pMVoTQioLImS_IF^vaYzwZGapd)E z>dh6Mb$_PsuS=-J6KEj{cJzuqH(}1BGNAx%Zyi-(8_-l@D>+6X4y4Wi0Gf99?eOs{cv`F z!#*uKJZWyXeoH^ln88o0JE1me42(5rg`pR6DHSx6mJz}zN|zlj9uyW|CFoH&4OAS| zRbv3Nvy2Uzc`L7tDj9kn&2!btjGkFkaCYn;vl)NaoZTe?R@EbQB_Ndw0hzXR?`L;c1=tP^nwge3MK z+K|%rTRbu-!+R(gpA4JR5ABEYn;Qm$XwGk})O$g*FV=>coS6*{lw2XBKfygAN#9^2 z%wTV}rVcvpXX9tB)bvH~OoO5E5TR>b3HMWy$00?p~t$;8~kP2Vc{J;XpB_fHmKz_G#mpi}5JpD6o8s>T^*|Jef`CeB|{ z`tD$o)sPBQ=l5;de;`?@dnkZ)=7W+kAeP3HvP*`!OR=PjSLi;uuB==HfjMAKX5APC zUC!aKxG(rcmWDn^(NE6cI#nUG(TM-{O!m1-Q|HIx#%3Sce4izT_ksG(37iL28fs|@ zZb_tShl+>i`rg3zb!>(l++G}V+VD_qrL!;1=dxlKFXv_C3@=bK;0-f*wWjX7J91in zp)}@6CxBX;IG0z4q_<+0L=5oWB9t)Z z{y}5jGK*7)7!Db8M}d}UuU`DX8vc+=QIJ(ry!&W_W%6AA`oirOp(jp5()qdUjps#j z1WI`|6#KQV2CmID5$1Ng@rK)lX4g;DCNhRG1o>)4lSIL@ZNawC)$Uc8S65N_h@AeI zziV0eDJ(pEO2KI${1!Wk)KpKb`@6x>55osN0UO~tWKPb%6fmf3E<#!Ma`QL zVS7KbqmnfAMq_@b;o1n?WQb0rRB!NuF+GPcKl(_N zbhE-5n_*~=tzYlCPIwf%Le#iaFt5Kbl z`!P?RLsTz~ynYGPDWDjTn%AS)aAjYp@@!Hh^vy3(F9_IzuqKu*YhbH*k*j3Ht&*gK z5PM+aOJK0Q(NW1Z#!1j6+q`5s=;J$A-jNt6@G#+hxKURm;!4@>{qx9r7iPSS zJU|X$h@3GKD)5_nJRnmjc62KvQaciew)m-EqkJaPA9gpQQZBgQ!Q}%LT(fDg`nv?q zw1B6p{RQu(qU8FEzgXxWg=#5Z7;wnSFsnv;MAtT|pvA5pB)?&J?xnqKIcOH0vevIl zd0FTc8Uh9YQ4_NMJqAY{+H-Cn5uIRYc`tMeGn046G;1sV%rP|eMt6!jRs+Bvam9qoJ`x8F1x?P!E_Gh>ZRIJ2)mbOD;B| z=Qo2^A}Ih(GA1rk7CUf$U2s>mqpk1H4dDBNV1ucOFN?8#N6!tW>1V!`#~nNT2$2Vu7RolHH!`2Ajj;~QO2vAnT)$FybXFO4%M5I? zW3S-4IfA!dTvRnb_*Y|eIFd*3z14KP!&AW5`Vd*F$Pxb3_Ga@$y9duA>Vs4XtPnJH zBI35mZ`V!oZM`0s=NK? z_B*l=AEjdo3mg#IDAjbJ>hMmKgn64HH@;3~Sb$_^Q}-cY%H+EYY18Ly5gMKmBP`r7 z4~O8}p4;P8g^6c3F}YY1$P&VZAG-iNvUT|*ZU10}zgj9CS z1n`ED#E)9jXD{w|>wmYmuFHfUOtKN#Ms$tz9gh#a269BU*U8D3hSx1<_(JbyOlV?f z1t}enZMzp~v*N>}lP_{BhPVd5`@jjAfw+C=!~1ZDu%6F0%krPvhhbJf zb4G0^8v=6Zr$0**u#DT%Z*DtdTAauo)|T~XK7}&d`W2HphEOT$GryE|NlqRt8Y-ph ztSyaM6q#6$fpP_HJV;j&rrXXF`RL(Jp*fZ5JpbD(8$${gcp9Dl+odv*b+*qnqieIC zTf&hI2tW1zY@?Xj7V<)}K`8q9LebsX8QSSyyIBPPHCXzvV{Yt4g^E7U*e*sjYL8j~ zP0afxqt~;28*5rK;K!TRX$hL*3>S`-^n-tNM|HPt?YmwtHqlOZivTJ?MXx(f-?+K2 zRrCN^5S(TZ-eE4?{eRHr${(mT!v&Lp8g5^HYY}3V%|3X#?v}ae_w4Y=DW`E4O{Vj= zW<<3y*&>Q?|8fVsFo>9qy4-t+$xf@icu(OKw=`>2K@6|*?t-&*f6ojVe|tVjANL8Z z^dV}uDg9r0VAgHeLPMDg;NRckm!o7?kb&?Bi&%vXdB1^|T6PFm(EGbpbmbQr$}()_Ca@xo#dxrAS@Q z1nE?@nhL6w2!*ZF?~+~>rqcY+;a=Jq*c)pP2@ntxNQXz0kc}4zpJUbhb26MRJ~I!q z=*wi~JoJ$N!a7%^uh4p$kuF`ryF8_*18Aj5#D3vCEi%wJ&UqAf@rC>Q2^Nt{o^BRv z1SEKBvs##L-?i*W;^FBp($O)GUg)}`4L9T^k+n$Dyl|(|=-0JKnNOkJ%#u~@9}(Qa zfNLCa!cHQ(wi9Q`!~!0&fCD20xnSgF`t~i+cB<*YEncw<<2Uie!~(=K&!>M%kvh^Z z4vW9XCcQUpZg9c=;7qbev45)Y0cvJQWpy*zdKYDntbTw#<~2QeL_W)Eu1aOe%cY!1 zEUHXl160r-wUOoc^T~SFQF&sIVxG2S=xHmND z{>EU`*am_ya+Gu{N{^5b5KvSkB*dV*yStI@?(Q623Ih~r329V7q+!?m{=UES{GZo# z9OtzgpJTUn9J}-RZ14B${e0NAlq*IRQIhUz3hRzXDc)nX%YjH5<-}jgvKm=7^4QMk zekc>)t#C1ZD5LKeAK~-k8l@Z#a#^-4W-_+L5A_sb zmWn6yW&LkUYE>rvam!L!x6}G-3aKnkE=W>_26yV|t$?DO@S5wy5;@=CP=a{nTW+tS)e;sX;rv1VxLnRdt_ie-%dA%= zf#9g>M18R_)Q)B2CB5zCQy&ZPk2I}!Zt2N?CTyDe@g>4?7 zb~EoZzfUU0Ma)^N8)p#kc@loKPS3lUSlY58#%(pN>-Y?NW6}-L)7HsMYp3e;r60?9 z)IU+yE;#7%=jJ%i6q$`%y$2+Sc0#sKU3XSmoGbBXb-l!bzl|oC37$j3a<-`V=0J?% zV!cVFGYU@YGBEQ#w0B6B@qa;&`L;n4`oIl77qQXTZ^#59^*4C$yHVeu356p`Rz|C8 zCrU@ZiM+|MOpr2plT1M%{q!Ym(#r1$0e+1<4#Z++?H{Vx*#AI}rx#y)7@gT3tU@2d zFXtv1o$uI&P`$!(w9j=f|oy*Gb zW2yQt;kG5q{=%o4@-Ldu@9zIdojCY-E#@K+8)dO^I^ZI+wR+<{wwFTtQqy~@{U)f; z4@ivRka}5MJzVzd=LzX$lG^2iGQelH=7I_yYxFcKYNBH03N!KRi48_L|N6TPDA@)y z{gW6?K!vUXVe6r!^x=?{9BkgNV3Y=gDbT?L2 zU=G9dk|vE$pYehM50a-~fJit`Y%Fnr4e?IRUYQYXFZ;gu!S6FPtOm7L6H7p>NeZk1 z6mO7i6p$VG36C3RU*Hjc)+D=MPR6`Lwtm39c>v{`fQo7D&9KmB`N9g}#A&}so2=o@ znkAamIdD6>P+K2Bq_DIs;bbqc!iu8#6GbM`Ee{P5(ZgG;6Srh)NjgF(I5kLmax~8b zsIV_=sSIoZtr#Qi7$wSDC2jyCX8`>ZUg5Vk6s$ePu5qEBemq<{=d0 zC|7@y+CPT0J*HBvrZOOBdguS^xxj594t%wJrXyqDy8$G3CZ}_(=~s*C!+2RSLJSE) zH%JQNNIMuS1#yip+bEKtb(|5V#q_%zUOGt%a?Ix;%!U}|7uGBi zwUo?t4ByBZ({to5knp`j#IIU{-&&lfwX{}v(-p-8Z<*7RUwNA0m}fI zDPzW#RX9=JUlp>$?_uB=)6gctu(9fJok*7!+0aM!WWqa@)_2UFoLN4h!Pc+Pe5u`E zTZ4HXabRO=A&0DCPwt#e-kI^GZ|iXnM^o?S5UwHrnvjw>5)w!hnnOLc$}BBQIiEu) zYRt5YLe8U@9>@|Y;MSsYczbN!z$>OV%rxRg586;#sW1m$|0hgp8u+l%rsyY zy7zwfe8OmGpwP5+AZrh)Eqcw_!RPzY;r5dUr%zZ8r#z6%KQd5o5_U*$mDoK?!OVI= zuW3$07U~KP39>cv8Cj&XFM}Kqj~98nD;G$NNB0;9U5*>y0?Sdht@^SNaOnQF4+o9X zSBXJT1RoEi4eRa)Y*35X%AEgZ;h1_b{TR#p{Xr*G_Sc@6lqIdqJ~yO?Zc|Z?xR>Cg zA0;^NUj`CsCqacXAbWTSSZ;mpK~@n(Ja@G8U7_dfqce$7ocmmFndtSAT-e`1sXqF_ z{Tdb!=mL9Kc#(AW#$>ZO)Ll6J5f8fQ zM-I+YCBy}T5*4%)Lvi|J6C2t5u{H;bjF*Pe&hgDv0)tD1MmLmnn`o~;TG?<+nedq` zb%myeiSRMA&OhR#t2BTvJhzTfmH``&BOm=7@z=<{18)(TD5xGQ?5wM+J|v?(WSV6r z)V!x({!lM~|1s0+$2*@Ne-j`%h9f4dIk2(tS5$)anlF6DUj;<7y;}o?=NLwy=p2pj z$ph%3jYSFNZcX)A;FQM>ZQXmh$Z-c`jj>dHqZ)xCp0Ba0c+c&D#@7b@CIU6gLU;x) z+6GG#P6~(nR|l}J75<$M@VL90ubqE+{$Xdki(i*Z=Z*xsp1As>8Q;qig`%jJjeP|_ zP`ZkOb$##t_Pgbeq|{E3N*;R2^_re&>UC`sQk#nAW#hAu={E^*e7-09k0&47{b|c{ z;8l1o?&dUTK7;$%LhVs7z8n-=v&t}^OEZgO9c2rnjgcfc)^U|?W=dq3N}a@5Rr#(3 z;zcKvy219CzJ11`dE7KiW2lIkWZW8Y?u-3+qCu_w_MIqgyC6A}i_%YD+`Z%WRFhqR zg@wcC=Umh`frrGg8u$az4rGq|=othEr$bV`eJP}3Om3?3aJ31a+rY&Q2yn)2a=c64 zK}*9V{9UmQoM)lGBg@ol`mHhWF{@p^aPo8y=4uE73D1EfN8@A!qQ z3biM&ab@{As_Ib4*GLuXX{=7xVn^;Oq?{y!&^c;hr9!5#T^RXuwYU(FJNkX~;dA8- z!%er}q2}yk?6L`jojHc_*e_AL=id+BdUj)C{rfGI?a_)r+}Zy4NwFmjt({K5z*pL! zSuywuWm5rMk}@>8Iq-5VFi0e5`lrS`|4(jwxY_A*vlfqsF0M+=ME6_Vno`6fQBJr> z;DhIph~&sWy^(tqQ4`~&k%Odb(ZyFrV%?%)UM@acXZ{>7o9bMZ#9Mff$k$Y6ia@u> z-?LVqz64UG*pt27zuBd_oeI+tC1G|8ZoU7a`~fFVE2n^%gIub}8meP>)m%m_6f`Rs z_P{UdEY$7vLx2q_w*TYa^O?ABXQ*|ZBnvUNz1esm%}b+%TQ_IPAhBcuD=QBFShJ(V zo^fN-FR;uQrChP3$tJ79)-m+luL^f!X<1i^CIy64DCd!e0kS)VhP8eWVLUwT`)j>^Fi{x2n*Pn5Syz{)$2}}Pt>V)KPSMJd)h&BSo6AsMK+Kk~b5SeO zTh+~M_T&8X=26M&i(tNA)%wOH1nqa?UJ}@(^}Q9#yuY7DH(OqLK3}eP zue2F;56--o=36{^am0-~)&GdLbUqs4fui?ljA}QrVxin*W*9W4uG3x*Zz~t_@VlpX zL|=r@Q}Ds9y=^+JLHKAlD>y8S{h=#6QsNX#h{4~ zB)b22bf33(Ute|u7l{j2pan=YnPhi$jzOmH^OxtO(8X@T4m9YBq{RrdneK1D(<{c= zcaJ^<`=qo_Dzwk(ee#p`4t07y$_o4y<9VXBs(PYWBgw%xSJC?KXo+&+^rJ9*<3YEM zA+M_;KgnS~{n+620F8_OI8SC%HM#=I1d8{5-|70LO1ges_TZpLpk#0DRksu#RTnxp z%XREjZ;Yd(w@@-5@9Lv~a{m`e|JjaDhFqWI!}^CLMt@LnYMPaN_jz&?8d^W1aU{)0S+DxGRjnH~#;j|Wn@A4t zJ@g6;{f25=a9uumUEVH5;TjH!sHd42Lbs#tFUp;^4i` zAXQsxr|^i4*>i>I`S0&RU3(wsmrEZnaLsQIop03U$era-0XCpkUBTTFE8mtivCqm> zp?Ls*Af4^YubnsJVXvSgS=k&nV=oa9K-*^SO|Vb;(u7xch4&LUj#}(lV$N?lWsJRi zbql+k7nMnzR^VKN%pbbGo_`f>$9P!mzIDsw_Bc@gch`}@H@iQK`I24>ve)GgulGMJ zk+f&rQo?2yXYH=v_>h|b-U1m!EB_c`{|GQW5cyVEo=$AyeNfN8+2nf)`_`;sxK;S7 z<(B{LCcgg1^+opeX};Ixz$H?9mx&g*J<`4R zDVrN$(wE7jO!8mok&eaAen>@L(EAKP($|lqGQWn4U2Vhj6hgGHO%DLR!iA$Bc=g&$ zTUW;YlkZy0cMu~t)iNYKWxvYs-~9A|gOy)3MFi03rJBxvc8a_u=))Us7BBcxM!R^S=&jCC z!OCE&+bOhj&gIKcUb8!Yv}Ehi#>e!0DSn#c$CCvXdRSMw5o!^~PmAi?h1re#Uu%`F zQrc^5$M)txUl(6-+ig9`o$ij2>Aty6`w{aYTHk4dEL79n9y|Gmkj9g};E_xtcD2`mY60ymL`7lM$NvF#R>F-h*{x@ros!vHz9l#nQ2MC zH*!)e$Ll&ucrOd$tlC0yU#mPEnM!nA4ttm7eq>tw{F(iXNou1Qvoe$8pWGFt>f?m) z9D*#u6l=>tH)eZ_vhz)CmF2mutSoPm-Gt0hv)hHK1iSAI4HIRPnT*gUf9GJ=AC`eL z-89n-4caVEEi=GO@H97ys44rXBIg!+eO5r@^2+EZ!5&b6vA0GzE5eDDqrOm7#u2TP~7gT+-%~ z(}1o3!QHoi<~@*1K7qhJd7k?XT1x8GQpRHmU-IbL?@Y&~(yj$h6rG4wp&e5Wq0JMyAQGO(PMp)=K%C$O^V>qN}klNI}F#$WT_ zesmiHf4$w2$Ogi6^48Byy%Nm~-A2JgLOMKhXHV5d@I>!6s`FdN_b#0{56QHjoB4Y1 zAn`OpdoMX_I3SUcAd3J2FLgmSs=J{hWpP0elj;EMm?i*rB0pw8CQL43OcE2SFj=AL zOZPesQ`3+Ze$XRfEvp-#A16yTA02XenM3VG(~F&sv-LDl$wN$}q_XFghdtLNP3l_d zkYpc>iG4#Fsk4C<%J@5L@&)9Guu<(-`-v}Jv*u)-q5EG3+7&aW@?7MG^O_4i z$$}Je%FOjuB-W`!YZnSpy;OSwg{BzBnaUrq4+ww6+{GW0`(r*ZB6T9f<9GMb{Z6sb za(w%gM~^mzCfpPpHmy?W9bQ|Z?$iOvc?HHW8~mMxGDzX4*~sIKXTxqRPI(SFU`kF^ zWEjo6I|c7OZJ%9%pUKZ*6q7S4R|PJK(O!Ajh|p~wR#_R6sSh-t9jZKU^DfD$G_(@E zSgjqrz5jBu^$lgd5&c@0BJEU$Gg*8BWb4fH)K}kH7M%?tK6CQPu5my447)l3z-nsSb@+A{zw9BTZbo8uCT1NdpAGyp_(q{rFSivq~*?Q$4Z~EsWc7nd8GZ z&ww@0dXy=m9pl#J>jPyHa(PRI2;Qh?n^!e59>?~7G&f+1=xyI@wB?8*E&o_FrJbo_ zrp8+FGBtdr`H6Z%{=@ygHQJ6=Ip@Y5#|lBOc}24kVgG4L?U+0?d5r7rgmX|OJd-GK$cInQitM*FA;|mtQn@+dbdoN*>Z+UaK zqI;<-U|n_IX)QVOs#5Uqiq5zkpSv)r;~Tj4nFc=32YZNfx!J1YTBQ1H;zeUkgiG+M zGcB8(qxQksB1rc|IYyCjI|=QdwzpnwQ+M)>)Bb&PSv;UoOLgraQMs&&0h;? zTa{I@Fu9HSP9Le?)q;AM29S-i*VG z);`1R#TpareCU4GUR-s@MvwIQm_^r7>bI*kE8nfs?`zY7??zZ>{NiCXtd#H?6mOTT zgMlDDyX{#BF~Bxjy+DC-$w=i(Wi+LXfY;domA6I))G1Nfi#_)&sCltF#HdIf(GNy3!0fnTWYLF88_Kx9PsbL62u+J~ziW=y4qzin%`kU&bAZ zeN>I5;5UL6#8NyIgkILbRy0AJvXI7D3i$(=8~|`;OT-mNyo;vzbn2<1p1V{`AaKQsa-UrYj1Lc(iAN~h= zbPZ&)C1lG9lrI7Dy1Hd@1U=h!(taQGJT&O#u)p4L5GlZY;SSSo4n8N)my;Y1m%ozu zANi}>007yUFZlyMs!$5*ZI3%No{U7Hyw9n6L@ftqY@M4Zzp+t+*`xET$RKrS^O+z0 zEJctJEE0(y2nL04hCS^GmDY+J+zyqui>CJO#v?wy@XF-%b!kUCiG4^q%Hw zHU@AW)2CyI&!r4@dzYj`RhS&SgaHWw;<9P*am=C|>Mye>3;?jjLfcUIL4vSTFu*Dn zmI24lU9nMq7jZNk|EM6sD8SO8$evR%jN^Vn%IkOXid2QCV7hHjQD2I`5iAUJ0QHs= zXmMf`%BA%eTl|(|!95rMG!+}cbFLxeW_CX;fhaW;FO}xi`3L>dNHMM`wbOX*u%uUU zrgI-Y=$1-Y&Ls(->yoIj0F#qkxISe2ec*cW#)~W2hd9Nv)at%dlB-#YkyeVyciS-b zq^Q}HXqBhlh~$Jh-Zx?~VQwj@t&|o!NvYsuf0fi6uCzYmR3?+;G`ExtuGC0GYPm{6 z_Ia9vO3L%Fw8qv)4Jv67h;%=(v~j!KFVV^&*KQs<0{MJ8O`I{%@ZKW7vjzrd6a+8JpVpz zzOtRUdujTKO73o0uG2}%<%0s?c_wWelk#eU>S%%bZh;0#p%!=H(?^BR%nM(HB4h5N*B71;ajJUc2gdQ!;LFT&uK#wHFE^S4gf1$@>Z|=X) zW1x9SSX*&uSxMBR;>g{SxZR>y?oyjJFt*0m{Ruz>h4!b`=J-75bAE191Qg z6h665>6g(W9S-~%-BKL%xbUcQiMDi+q$-NLYQ3yv!@MdeylP1oWPx(1{FBX{SkWz7 z&5x*lHX<^?{p61>)752Af%E+w8s4WOLrV%`ux0zni(1@WMQT2R3km`FS_D0wL1 z5w*8Tb7|Xa!Rb^K3->7CBowwBEUI;mCUxu*b=)3x;t92k3pMnlEW!)7pqF*WB=xYe z`l}Ch1C#X`hxMrTI%$apxrI7K)dr>ZdeyN8^}PlS(nc*FY~xea#%C6dFUCZOkR*Qz zMgYkg5kT-Cg0b%a#PtusxCem9)==={2u4jjuK%_VKjb#*?=>3nG?`j7y)SRF+-u^R z{7W$I9Yh0S6YGnb^%fcpBPe|In%+fFn6)=qMVOZjnpXuU)^4^W);7oOHNVzt7?L0QYbNV-2+UpbDVb?2_J`N80Ko(ON{;!X4L!OUb@NlWu9kR&qQXEt*{;8plXO zv(Zo|BTyh5mWHFNIlAnal<558(K*-NxkL*1M%T4| z8Mf18{o}+M0Jr)5+=iu<=Jy!-=@eX$4!{ag?EzS_hUgg8DYDr0i>~|QSpOqxNK-6DR}Jak#xn}PuL&B1rg(G! zlQQxff)m=8dwz?h=n#Y?9`2{`pnx7 zY0Uo+j4Nd3HHiH3_7AJzo>*vwBp@#q`bQIz)J`)g`H7_kP_#n!8xu$Crk1S@N5s-m>q61|276h=b#gk9A`YfT`>+ok8>T4A4*P07rR$%xz~IRuO|f5C{F_TFf{6zmUkG212Pw! zy2wki7)v2`05bysE;A^uuO@CwVSap^;#{2){4~m4OS+XbeYHQ4BTU$gB$PD567JfP zBmv+1E4~j-LiAyX6l}pg=)Uwxt8Yz+J2-+74HiQZqM{Hi`rS!Fg!w3BnW_S8A~>A`MnOVLO~}fMgL5baoYSwsYc}k9 zjubN+!!UPyb{=KrOH}e#plpo_>9CsbW>_ra8*Ri4$>@{TEdsId?yO9TT&ej`t@*B~ z`QFa?WWA+|bP6^uLe8G09KQL{UgC8lMBw(I>Ig#M0A`KGBKS`22O<%LzK{{wQJ+YJ zj3i(OWkF{KtI$C_j51GgR|~d<1{>i=V4#t{6y|8M)CZ7WB!o*APX_*JVa2ByP0ATJ zv41@WSXqi=UZu2NrFrE*R|R9ZS>+^OWBuuqeE{1d0|?Z>4kH!-ISc&Kt5n{rh{x-q z&@~oD2pbe&b@q=I-Lj~#ycl}8rp&)iJHE;Y1vn$26qZY~l}nkOYkXZadW`FjZZ??s zH%+6L0h;)G2gF>H%e*(sBf=zs>Imi%TeePw^Z^XpgvdYjx$#2$n^6YzrfN+By(S6x z{Ur}zS?QmXR#!O52`^*o^Btf{5G)`YGfZdpUU7(`Ovi5#6Nby}rE-#_M^i{LAo8;) zimE8sVs|6bDJr1-@OZ$f4 zmY8dmcoj_{Qv;K(qQD`HZVRB9Z6b|#?^iM?+L2?SvPXAfj(Bp9c(W<^vzwn;4&^i* zNqmKFyY2?n{^qp99&z~`Yo8tg0MSOO(VHp9oN>{KlgEIAV`-mbA)}~=2e7nQ5FmC$ zCyMw0RVNxl@nGT)`>$iEY6=+`z{Do%jn4@Hg}-Y=!n1k;0Gw(*A;GN)0Fa<{%uwRt zuTkoQbezR#RHXYb_-)B{k{^s9hN3>_Jhf+2#d_x~_>imiFhhEa^x%80w0Mgz^tc`B zQ;m`LB-~gbx&uIHi(b{T}cY_Pd(slM!p`GP(m zv(m)xIUp11iDM*=zvibIV(P4pp%|S2)f-*{Y%g28FLA!(t(S4ssd033aZHH##MSFS zz)h_T_U7XRh0Mp^N^qYr1TMCjN)oT~jUGTu#c%o#^a!xcEq@(=5r0Zd+PP|1oFNc` z1+(+kJ$?a66rdnsdk;5OND+E7Ua)iU5S}4sC#THGic=Wx1x*F!*qHX}ql5XW#P{@} zMOts5IE8WdufnLjF^|dM3rfW}v9}*&+zHA?e_-bkW{&ZBN68W~AX=suMC$A0VEpx$ zA=+7{U-*U1B4-xhZf4)R$J!={-p{KN&7{hG_py&SJ?nogw~bT|;Gn4WQpcMMQHG4e18l4k z@H1S|W~mfELnAc5eV_)*-rCt6P0JyvR?mC!^40~4fNy2D zLV!vqI+6T8oB5MS6$NaeRn=E=6#nNo+0LgN7W3FdEgwCAlmUP5Cp#l#UJFJ38+Vk>3>i zJ{ZQ`#+gqe^)g0kYKB>gD|*rq?y9*b{9B5y6&X-Hol|JFc(s2nk= zw0^KI#66*{EX$1gL(J*!nARiuy@NqUTfv?~NvWqF_ciqaG^j+!eXh+GEKDW{Moovj z-XfEG{lV$Eu0`XY=lTv`oL;>0`19w5Q2>>*j!DG56CKlp{|!BUaMm?1Z#>bptpDPy zXWjniM9;R5%0=IP?B1!qLi8vpm7|z1q4pb z;`gd$ok{Gqk-p`bFg^Eoc$OKVu%@EI-6E~1^2>g)nKQ))gXGbvIw08X!)UExtr(B* zuWwAW%4~gEB)!;7na`=<|Jz@5!1;^J|6hOc8hd?teSM9+y1-r@UtL{YUS47^PX0qM zo}ZteotCbUCnwlHf3U~L*x$dekB`rej&6?E|A)W0`>((F zbMo-u=l|PZ+}u3g{{A0-ad&rjdwY9p3pcL5vA(|k`@i_&)#Bpy%*^-2MeMgy>_R&B zOU%;J(&FOc!otG*{QTV9-0bY^*RNk^W@f&8`SSVm=jrL`si`UK}CRuEgAh!0-)WpR2`1r?N--l`$K$2Mn-CCYEn{Ce0+RNOiW~CWN2t;aB%R6kMD)sn=@NGteJYdle3?npO25v zje*w96UAM9gWV_EH%gK>k|H}QsvFWMFE1~5cXt;T7iVW@CnqO6J3E}i_&*g!VMDp1O($p1YmBj(((ZDEbt3&*rh^@0j4;Y*YXV1NUd&$p3$T(SjHO4lSeNUNbn2CzxYf(>EleL!MrEk`m1sem*s^nHxR6< z>AqdgU<`*E^sM%1i%9hN*0Lg)85m`1m!lt<6cZ?{bOvu`{u zcMiWf@nhXWeVC6qR{r%D<8cp=U#ZmJd@tgtnH_I&zsL=Ok+?G3(Lo0c{p0wE@^tYR z1^@bsC2QddVY4|_+rU^9!QGknfBnUh^=L6~-yuRtFxU6k2X_PwgRh;o)8kcHUS=ok z3lV<~;a%G>!MQw`M|Zi6b~ciYf>jnj?1;5|1qeZMH`6Seb~e*(2Z=ezE#b^tnXa4X zZy_KeHg;>DN4HCIG! zXx^iU&8S++;#zM%w=()_LRVfv{FVn(HHhcSo5X?=i3(dSD*xH`8jtf^5f#MPuO37D zz6VYPSmArUU_V>kU4Oep;MJwS#eR!Up71A*ebN1cK2K(P`i`?HIzGR{O$osstSCaz zkM0{)oj!raR!u*zztAUP0u;_)6r>A0vZmb9TdAjprPOvYcr02?v`484V;Vk4(zT0} z&!R-8ZOMO6Yu?YeYjy9GV@PHl=<8ryXvrGOj~;HU$MkwtFi$?rS1*}UDT|8j8F-wz z#xWg8@n^{u#^Yl8ECK5R;lmRH$Y<+*Rn_^5_aXL=tP$(oriF;OYq|xir#A%~!6wnv zi~T>nOem-C=F2V@Btwg~LjRC0eIvB;YWa$~=Z#rU+ahdjY+ipQk=HKs?s(+qb8!^U zG^NSK;V=_jhkmLp2qrl)%Zw39o)cz|1nfgH`IE)`?*XDa>XjcHpH0cKes6gi5eJYI zBo+T{%1S7gS#k@;UxVgvXIc6@{aA>RbKuRU5`5lI* z?E%5Z+rIuZ2k$!9Z_~oIQQn1Gd>PZ}_#AHn%oIQbh>!V<*CIph4eJza_!%KJ#ZvfJ ztFfVK1uWDf!}2UB<_Zw{%iwzFy@G+;zYly-!NyXw+xgG%xCVJ3@sYX^HiQm7fX@91 zd=BwFlIV$%rm5JNXq#P>w#ZBTr#f8E70hGMkRnr2KTWmPCcTwY`uKI(WM+H=xJ^Nq3GpY? ztVS+HS>3!pSUiz+Sf1%uO8`pHID}OY7m-GV0t6h0rCh0CmbQLtYBm1<^%uv?@djG| zRI;Oj`6yj9XcLjQ4s3aN+g4{@5#{42W0Y_K0Uc5NT>PMGS>ok5;^uk(YW9OYogeTB zn~K-Oao0ThR9kqWD?Q~oWR>rgROhGCP8v$oE6rbw&Cj%*G}c5_TI!XDT41&NDC$2| zS{rzTh1lD?2p;@mv8^fS7i zrV+Iz^Vu!TrR7!@Sn9nTZp-R{>wQEM4F~rZy~p63fLmbnL%Bx1$%y&S#Q^Y*4@k`@ z@}vPx#3<+ww48o)EKdv75mcv&G|FN8(X2+5&`a}n5$fTJM6)XkS!=;zSMu)MY^DRl z4iT20(F76&1#Z*+E!9C}fDRfZ7IO?(W2FZfQ4+%HyAsYbPXmy$29Z(P!FJs8=w)qt zDvaEax)%dUtv$j+n7&BwP&~P&NY-k(4CDvC007ft2fGno`0MRFEYjv|h{8LsZ41DR zI6ezGHPx@C1)-cFwgV3i;-U@dSCLsdN|KJ`5!%rI!jAC2up<_^f+|tt;hP?q&h}on z11AJ|AA^XEZvR0FRPc*3y*Hbl^-p^jrESuS2Q>&JklDq6p48-m-Qa}6RW4ckl_{vI zKAnLI&o|F5A<4BJQJfb&kl3KP=F0J!6kPF0*TW;Gzn?(tXKl2}XCOcrr6{q_41IZU zWX0Wts3R-3jPi4TKMtMm92*>Lq0gbcE(vV>?IrcRcvOH z=J&(H{(Ah3@xqu44xztq(nZ-%de`@j8Y={f)o9&O>`D?R<(w1OI~fpSwDJd;Z<0oi zapSPYhy}?3FpPSPSRst0>}uPUPFzcWnJI;|WR0oXZE$iJXmQ-XfM4K0MhI+f2b6h3ioN9Ap}v;bA|!2{eA=T-KtN2W@)9ERFoHqO_neoPj zsjL|OanO%$*l!f=@MOr7D20FV?R{8^KkpMCu3)dDBKpPG2oJFIn!NO8fb?#k^iPn? z(Q9~hEE#?eSpk|Fks=02aU~YUdmiF6#^Lwrs~Gti`wO@@S&skn5=mlL`mScW`-$>G zU}j)K~E1x*DwZmnpN0ARHZQW$oA`p#F06Y2OO$ay=EorWLZ$ez8W>Ly4@`HcfU2u&61b1LrTEMYM+kW7(7wW*?i8 zYk+D=Uj`AL6=~qC1gs%8`$}5H(CrypA*gy znl^$}aclo7xHxD$m6|0lo7qmx&`HeDZI;#(X45yv^vKA`0G@Rqlx6kOtJRF_6)I>~ zEC0WP^d}b0^s!o&fF;g7N2bQ;y;i>~i)GvnI&1 z%^NZo&l!0&y&>|s)gwt>!~BjS5sbR|c*Z%i_XTo_ov-Z#3U+e1=5z4u!9~Fy{NWi2 zW~tBw{AmE$_WOLs@O4)l6U1VlRC5bZNxk{-XzZ-??3SXw%^i0JYx)^b56L=fh`3>L#$FwXehK zTeQF%9K@U!^#ot5pz`;xY3m>D)H3tbiSuNi)6#FcC%Fa|s4m!3?Ij7U|>qQWQ^fSUZ!UYE!{%17xo)-Vbc>yupI5_0@uBji6p(d@D}d875*_nA)KOTHru?F&=7^5? za(YvE?nm4BCp_&dmoWJpN|+}6#0XYh15VL|MWNb+SoOE3I{lS9w$dBUxVr!ejFcEc zUhXVRx=FGY34tFhmlNJ7*mHc^`HI2|AQ_6Mj|S7z=kGTAM9@jVbFWd!sSD^}qV6L- z_=Ybj2xmH?yM=yxziaAwG21g_(Zy)lQBBH#7Yk-CA^DNpTAW+}o+Rxc1=Jh$7|Uhi z)%i|id>>T!i(mCIdDcs3)Q|Sy`K%N}G6rNL;JA5=tQAnCAk45egJz$dLucUm;-Ko+ zHa$p2O~k-YRhl>O+%K`fhZVgCCxLDlvXcX{S=Bxvk)Ti5oDf?{pBEnooIW;~cshI^ z1$tx3eI!Rv91Z-xLpZ(;L(hhtA;X35`ad}jh34Y>0&FK~2i+h_&-SvlSR-=whwUYm z2NXw3-;EYmj93@b6QK#ocOiTUBh`{aUq-!~_1W)Z3N&=bT9wp3{g#|$g;Qyg{y@UI z5AgaGyI9m(@gs-g7OBM#2pbp1hCWsm(TdO!e`-@wV>p&&zAM*c1a(A%M^^d|lE%6g zT|4&uu=}GslGH$7urJ0P%Y%_rs~y4ZOz80{g_ZoI{}gtq#O@0VN5c32fKP@dK$QdQ zp6Ir#Td%GPx9O*L7n?K!@a)5SZ(X~XzEvAO4#LA~LDP{2Qwr*YcZ?xT(~_M}DNm*a zsXohfK2b3E%Ug~R+6Oj)*cP59(vGc3Lk{(&qux3J~9@%t6n*P`q zePi4(zZHC%3h&Ft^wS?to-xeff#(u4pCowA(SMjrGkB78J^ko_P{M^I<$5mDV2082kV!=PFT?yJP^-rOD-tLRK%&YyHuFKR^J0=rac9=Q>6Dsm}8HR+*V&E+d7!t3=So-lbHM$Kfr0g?#7|^+pow`Wfu{aQ4J62OWo@w6{ zY@w86vGta8Ly+*SV&aGL(7e=WXQf2RM`~a!*e8eN+Ngana;njIS)=3QtF^jm9Mkn< zIgs1>`&;Xo$WJ)n5zlQ2`{^5#`UrzJ^(#rD=Ntsw5ldW>MMIOsSil25P103O*rq0F z#58yi=R2Yx4tLN!?;*a}XgPwgfc{|`S zZ-nYz*!ap)lJ)JC>{+1GZVgeK7$+IJB+?Y-O_ z_Eo3?1SXG9E=t3r4}Rb{J;L5jjbDe`F7klr z3jrKfW!ByYK=`Nb*cb>hgMq`7&Keo4AyhoL0~)<+iqQ;G-uQ?o--lz2i}+YkfBi*1 zgRVft(@nLsdsfTZVOp$@KM3D^!SwlZsDoug#(BAq-+wGnH5PTcpx~Ym_8ES#cN)6! zxrC>6?U*ZnZ#GVRB&!gSJJ-PVeyJ;n?#0i=+P51Q_+^RwL)9J(Cx1u*2g^NyQAgib zwls3Rzwld1(Vy9vW*M`)GJ9>0%HU0o~mY!zJk;-EL=MJC~dRTuUd zP1)T-)V=yrZ>4+3YTD7ZL9ghZ1xo+ie)H2is7pke%degI*L|HoMcbXf33DBvC-mvc zaPu{1OLbGUI3#1{VC*%Pv?-^5etdiJ^QPh$vomtRM2arKr>|*GaXtf)sa$B?0sMwI zlF6mc^l7kNb7$-%m}&OZ$irmV_Ihj2KvAe-HGPtSTy1@=-XxNhbr?g+4k1OdPCv0y zG$+0tE4hdMPOw=HIZ&B3Mxm}Ea+Bpygu%vrs)#epUaM)>baWLajegJj|4?-oPEq}D z-0*i{fu*}^=|;L^>F(}sq&pW_y1Tmt>5>vy1XL7IN=iBu1SA9n_Tl@x=b5?hf8flV zIcLs%=3LkN{feV*iSSTQ3{m_&&8*<=R3iV`vHKI#r{^BEPm_vRvwUZYsoKRAIDmB7 zyfLkQjCP?k-4f(Xguj}oS*&A;Az8eT{=aQYb?qO25rT7?$n`t}1uOfVOc_s#Ow4A9 zGj$!s^g2U*fMJp|6{%%?uknI8?Fapzx?1@wD6;t)It>vAO`HN`mIoa6nff>Mookau zUkn?HCyhPYH@VC^qRb1vd0Bu&R=xdc3O9U=sCF`CmB-Xu4CY3NtqYCO^et4eiyQKR z9S8m22}sj5R>t5)#@4@Zl-n)YKfZpA!`qx(wM|6Ym$XH9W+jB`+MqUJlPNoexmN75Y>p@5`H1m>ycE%M7xzJc%j9 zd;ERFa9D%n3S8Ez`u4C}hZ=D>=#kZyq2{{m+CX$-)2O^Id0~22M{jh?OzqXJ&~>lS zkt=1(^J4gL$UE*=l-eoyNSoj5&DV;n_4)-@Xi3y^-kKWX=PiK`voOh`_ovXlVV3cC zEF0_d<4OyuT+^&Xa!QNs0=j>zeC zmt38r!r6I$U{v<-bX!RByBEbsZL(bMOCWH7U+Eh_tm~B=wyjL}c$PLy7E4(@I^c@- zP7^~Ki5E1_68Se5OT8Y7@5L3RHdvKt%8yHJG#~#peB0uV`~_}?cZ@=uTGL->Odm@s zd`B|nlrL`rPuiZUHN=kSBMIWz@gl*&|NB3XSQAy-q-px|!eH&{=&@OPvXtcblxLNq zz}9K%KVN&ymv@TuM%m0Kzfm#h7VzCX&l0IyHBs#bh})~}sq)wzAc-N$U9%UqUXu(2 zOHD)$Xt2=FLwi*I^(yy-za3c3rba<;-v1$3U`kkABzrS6b)Nl&>BQWGbWv1}r$oRf zPqCUsnl+}kCqB2|F@w#aP+94gC^P4}UY!aZ0OHlmn-Z)hzdsf(-}zEJxp0sXa<5^l zj}(MWE3&GYi=a?T;bKk&91PpOnRE(D$DVfE6kNJ5cJ%_~VImHZWW_VK8FeBq04V!k zU##s%>+2jOPJ}Jirt-T2 zSiaw*VnepYP6=Ps8{#lR%~(EWn(1gszx!bp<(?J%in}b4n^VuIYXC62Kp6ybF|}iy z#Co|Tlj~z>d_YCo9~9`U6aUKG?al}Qfdqo8vYAyIO?-ods!9#Ug=+X)-iU}eA`R0G zbWhB_zOM;rB9qgl0uvc#{&dOIAlm29$zQhR*3m3jkxJ<6uRSXPi;(s1 z1O>CabK<1jK0|C|r(1qlFw&9T?Z|Or7XxPdqS&layf_nY;ps3r9A{{;1 z7(B|-A?@tI`@EIf<}?U5m*b5$ToT1PX+mV&+Ne!W!Eft|u$%r=$tMAUZX+mCZbh zp8^T{E$ay+8hZLO5q#60FFUbwy_--eU2&-jJB1Sae-fMF5J*)L!BHWx!<=AG#K7@; zo-&Mmc53_mt*iBjddQeroRu{6u5}$Vd)4dyhFtC__mDL16B-hRD05qo-g6(Ad(YBi zDm`)VoS6NH*UM4di=nSfO}RjGIWC*VcNExxpzb&ZsL&ChnBzYSj`Io_6dfMcf7Vvs zq6c-vOP^W=Lsll0gSzr@Jsp0AeVa=N>L{gs>246dwlsCy)h>MsFo4Y4&h+(V(t7!6 zgl`<62jSvay)pQsp{mGv6WQ(zvxOiSiaHR46fqe#K6NB|3BOs8*L*&)^Zy$uiol_ZPDqF`pG_STJ)1_5sYBNzTdYg@lmxhKUrGM-k$lt z^|2%K4+d>FuJ0xM>ZpA58hM+pko(qyE1>W?x8-KNyO(Q>V7-Z(5`?wd88tt8`|+*( z)o7?{qVF~u6@@I8d!7p67!YT4(@%QpsvC8d$0KFv?|Nf@>KGw4iaB-+Mh93@7tYcV z=g6LjKQn~CUpSe9etQCKWrS`DLKzgH9)qLTZxX!2hDj}3_PEe8*?}PgaGLA4$kGJB z!+189{GV{y+m>P5T|O2tY#oIk+|%0R{v5`WLuSsPn^sL=t&MS?HuI3kX|^C(Jez3t zh>p7uf@RFF1;O~P7+N6;Sn@HZ$-LrH>=KR>gv=8}tqrJP_!R@dX^e;T8u8i4$(FgvirUb?lgz@5J#&LYW07k%Zd>NM_mO#z6 z#JfOsC38z9L1ty!n%A_hfK~!-74E4&D2hQX&n+r3rs5s85e;^&+(w>?nzM=^!Va|T zglV5Cuj{gW>N>a661QZKry<)*%QhAGq{Fqs+nj9T0e0@|sh2pt(qRnSe$$?dMXuNcX&a*d$9xPmjxkeB7*b_#%)sgz7`COeS1; zwx!B#K_!iwDcw>k_jD$yb+leB4i$n3*`FCIow0^1{Ih$n<@Y`ZuJ%J?X0HaexWnx+ zpj@q}Ixnw=wJT}%@VJ_HFA26LXDu9IcfN z6~sVe-9GQClxic1Fv~>QVg$p7G%e&T$?S?_x&j1VH-W|2qOnb)m8oCjFORv^3i&>) zbVNxsFkddS`fgPrem81Q$Rr^{~dk{=2KOcJujw_>?cotV! z+#7xmS6)rNt)>xrvP=PtX$#m^yttZU9L5}`ez$Z@kvmWRut@iq_I{h>^LSb6t!Jsb z>g2BnEllQ*SYL|VOw}=#XuvEVt~YdWrLhTK!7okKh2>LjIs25(<<0S?aSm%vLs4d^Hp{5X=OCo|ypx!C#PL&LJfO?(l@Qw9)J>Pw4!UkWV4(2 zDSy^i^_`5n5$8Qfc;(9lj7>ltpea*Y$cK=X!-SlnSi_`o7}iL9vRi4Pnj?>aKcdnY$}azC9}*<5{GMG)Jbh zU<&}?C|^gX)89_sB=P&F;Pb^E2*-9?^%AHiI3x)t&cg%dnbEQ^lmRe_G4VLl*nTva z=`p%{@3P@*(@Z;~jm`3_`kvIAP0aG8bm>$=0Q}O2ZkJ_aW|O6@9y2uF+Upp&uxH88 zfnh-r%eWdJoCE~$0iNwfVcR%INP=!Th8aPurkK&%0rOiUo6LpHo-gJEcq_&1sMBU> zk`p!vTFWe`byt>&xY%eVUy=kAJq7|!Op5u>Yn+LX6$XoyC$-yskLsM^IJ5P*w{85g zWR?HD(-!FeT;1)wL;93NM)%3WewyjFklBmnanq`K1QQ5`XTAn=wAmv$Wwvq-zJp#{ zwTtWXOp)`8a@;~v5Y;2E$Kh$-&vg<&uLOo zI~3ir)Z_RZWN+<*OE&)ME(sRvDQwXxPC=Bs995#ea|WiUv-9PYrOBc@8ux*@oVB&X z9CR8;#p&t^jO{Irlc_22^;{2FtiPas+Sf*LidtxsZ#XdLJzV~|C+T%)GrG?km5NeD z=mrD0E+1Gl=oDoMx|%zCUe>y+Ih%AI9KCmb+2By%O6@^_>JoHd66G8s!wNb8ht9;S zGNo(Db&DV|7vz5~F>W5V{>N?h5iQ+J>*4cyR2tWGsB0ch7!C0hT?Ap_=G#q`S1; z{I?DZRpGW{i7)5je8Nd|V~HQD+?myEhBBNApaLuo0*Os9b61RKk&nEpYk12ei|*`o zLo&K8of`oNRJ2=X?7ot4PykD`aE(jv0O-R`-;9zW@fuDMewZTuf?_|NE%-1blC~Ye zXB8r6qcVC;PMDEh=+Jo}Y0yiVgtPh#%;wK7n|%dIXJ;Rxl2uZBh{iCK_`nQziLqIh z2hP91XnRexSiG1XLLsVoGA=Od&jqU(dO}HLs~Gc1p6{*K&dFXEtM(cViBF-!{8mBE zZNJomj=IQJN_Bzm#~9A4uO4VUAD*;}wlSX2VH8amfFm!DotG%*vc*-R%MS4HrX!?@z&vjM!Z{5m4Jq!t6KG&8G34I+A-R}V=nSJbq|JjY+zx+Ol`>Gth z&j$~Ww}5|ZgW|xk*Fip*l^6QFXN6+GR^516Q|Qd5PbjD7#T1KVzNyuUBP<5BLaBejkmA!7CkfHIy^{uy?s9|9dns{k^zv(a74<;Pip$G?JcR2&(+N?a&n2h#sKw|JWjkj*8H z6|eEe>z;|X+)lK1{bxCVrUSTCO9?d#3@)DjR{%YWGL6^0jLSXzOL!Y*ot|tr15cR& z*@@jhv*f*O&N7VgUdpvY-d;x{KmXh&0p{7Usz!(xHUjPHe62nv@iZa8%(}!(rk;TWcjoI+pQ@&k%*R2<=#e50oO-bgqBPG@W zp5L@iDx+lV6Q4Cljcs&PUAQ;k|M-ip7Z7<$r2DZQ?0^0uzJROPC8Kg0DXsJAap(3_ zCZl8mjoUnWZ&U+H)_raRY$k`*MLtjMidC*u43jg@_ex9Ju}+nt1;d3+AHeVwulnPf zW3kwzL0FRDhI6^qyx;FE%-78z=Gql-p@ap)2{R)V*gw9h`P?te^P!xgzioVoQIPLv zKh^|THrf=KwwNl)wuu1aem_n2*J}6v=J%+JL)dySTYxWA8l)t6JYSBG1Zz$vz!zZif4y_;q7-Lu88Aqr~kg zdL`FHe`XO>2VvVE-!}X+wC$v~O_btQr7$PJ@8J?rJ>a=;*7>V&rpy^787E&AWnQ|G zHkLAmUyBQs`3?dn^b3UGcu+uespYc@ZCoF%4(tpeGHCY9kJkoZ07l(qB9UOS7-M3| zNXUFN>pj6|sWn$Yd@*UE;3~KrUL8>A>js25M~yR?Fw47>v^GuGS;Rr#@Yg;A#mcn- zEfOI4Fph!3tL|2uFP1N^o6dwOsELiz%a_I{E6~fF)1)bgSswbMnc4KM&<%D~49Z}& zMR&T{dUZcb$$AX|zh1gJ5HKc3AAJn{S}f|s>0GT{&+$b{g`fv6<(JTV6c?|FzS#K88^|llTvDyYb{O5?fMp_g=^42nJWwY;kq^rjM8~AP0!@|mpA<3_fdN^ z@=oz9?^X~07{EKAHnnfhdisM9yTr48GGbbXLZKo$d{ zn*F$RkK|$=(Y!9X|-pi^kM5Ehzmg;+p2}Zxu>A%b`32ju;^( zp%M@LU^EWN$Lr;kAnC6k=^wLH=wuXwedj~I@!<+l)jj)*L@~l7935l1v)tXxsQBEf zxyzl?HhX9TDo1FxSP@n@&y}6gr#>uSwF$NL_tE3iIoEuHg`YP^Vb$Wt)v}4HT%b2O zsoxW@J|F)W?)!E66J;b=ivq-gox4ok618+dbnqy75qd-uW>u+4jCJ|G@sUO{2~F3X`Z^2?sX;t;g_LE%|@96-uEOyRUgAWbYayVK&X zf1Y3XpNPq4F)cET;OXf^43=*F>|4QCBdBv^YtaY#|LF%~fg)d0V2G|J*3F)sbKo9p z5=pR6m`FDg-!!2yQRt$pEj)#pj!09Ml6!GA=-dC=zgX7gQu89HJ7DiYZtPgz3b?T?Jru zM}m*JYADtMie5NniX>uc=P~VW82e5H$m-eXyc&pr?lcj|PX%7bRPqW0z*k3`G5AKr zL6B=Iia1gCf7ei`A=ts`EtFXLC zkR1pPt_`?siUCIKr25J%G8t5T=yZQ&@J2D9?m&uFVCkeS$f`l$>ED@16U!GA1C@)4aK}b|Xi9mLi#Z5?6g_7keGDT1eOy>+wU#$Tv z-$SQd)ev7FMdwbQqCF`lW`=V)Lo<;mPP)|}w4UU(ilEzYog|MoHyP4i_CVK*8E&c` zh>P&%D{4L6woMw9x*_QV=o)cpwyc#)B@$mHp?!1Y&(s>2Z?3}SkziPDrWSh^h@h%K zO%WZNL*xE_+V`$3j2Zf3a}xDRt>7B|^z7GtgG`~H#UPSd%4xNI3NK&1R8Wu4<3ph1 zUlP%Ws9Ij=FE{!Ly=Uzj|DSB=LfjfipOcbw(EpY)G(&p!Rw_KCf5hFXMRgp|Y&1{A zkk@5s+*(M8iBRg1pTs1v{Ev847^)5BwP!;v2qJS#y&P{6*ue5BUL+KH@6L8oac5>! zOlwUkVM#upJ6fr_R^A0GeW32?#4jlj!}RokCg(Ez5s9qiOAI6teN)m?)*o?U$fR9B9~-#BQrSLGZHo7JU{nlWhJ;5HSWcoO)eD&QpTRT}!W$uWI|0 zh5Ea>anSkE?*o02bYTqjp z5x|An|8czikAv@0ct;k6@92$|u|tS2Bqhs+X^i3AxAb2;_V<;KO7?ME>Ifnm1J2Xf zPlM@+EqnG>7VGjA-;WlV)?{@xa2M?_ijW=OK7Ym`PC7`VW_EAW@qW`-sder)_wCcy zyV&{H|H^!>UqU*-7=SfcM!t*Xo_2r8IztzlDhDcB&znLQ|ED0n>ET&o{-2R->27;g z5~mH3+H}9haV@v)sc&ac0RorPja5j}anrd$dy><_Fn-nn{A;5PVWP0KKapF4W}Xi8 zTyE9TJ5ky~4|e#5sHOlcGU3&$W3~3HatqdHY3m&tXoA9^@z00wqt0Oq9-@^A5&W+D zGvg~BpaPa{(o7T)|j%p7py6vOd;)WcDc$e8|(ds~n;iIY|e` z8&*ZPrS>IJa<2S$DHClhHSy=!&XjvU*h_s5v_;XcI7wH85l-S0m|h>OGifSt&f1)2 z8!^tK@~$e-yUCYb(0??e!yMeO18++bQrY)>oHU|2=HH}tvvClrQmraV>0AZbQ_pWw zpeHQ(yP`Tim(33+fDbDaEs-09RCbD%mdy3G)|24R!1c=!YSdSiDnj3Kv*q)&%<$|j zjv}=2{g(Xa5ocD!_^P(N96Od{wsuWB3d|dnZ>Rwq@k_;(I5jr$`-!5{0W8n+(#fvB(@!MMY=7OB;)e8#UP%NZlW4F%UDwL03?&7%Sq%6eSKI?2)Up zQxr#m{SSMLrQV9w z3Af5oC5uL`j0R9gqiIdw@Qz4mQ9~=?tCoDtf7~O5y_$Fi*HqO)L#KyMJbVx!mw_i`DDU*~J>g##wPe z4)TR#6WWCTuLsKW>^&AK@NDBGP#`1+Q27;!%K>A$hTVU zgGJoxp3nP^V;175fys2Jt%Nnc9*tXj+Q&Pp@GtDe$XD2T2re8rVG?S845}Fb`V2qn zZM=eRqcY(rvVwITwVgW-*GV?vSl0!~NnG8(PsS^jY8zSx^-ooWpfkFNY)hT4eZ&4R z&cV;yxz6y%9UI$UHfVCWLize&M+Bb_9IeifdN}4q2rBWT{I`290HAe@=v3$FRrlxO zSM$tTG!wEN3bKad2>Dj~i>Cer?wMT>5TY$Sqq1`hj0`bT<86M&XyR=@i5|3#kx&Ia zHIO|)$fA(|BA@~!2=?+<67W*gSp?&=^;mW$bMci00ByqqwGX;YZkcl{#Z_d$vF;GE z8w#>wr(XtB(s-vQWzMFJPc?@Vg<*C(%*a>>-`?`5EvxnZj5UaW&Ym8ZK`w7mt$tBG z9x6bifI$Ffty6enhe?4>3Ci-=#^MMc>`U6*N~c`sKYt7U0_WI9$X>*DiL~vZzgX|A zE=p%y`K(C1Yq8T|LB$QY4)eN|_d3=FQReW9R9DMw5dQR2z`th1AxR=wjpM3&)@F_ z!M`e>?Rzn6L4b9wld2FXBm%j0+g5UA{qiKRU2%Ys`vW7-6GJ_23whd46$nDs)d$xh z11PxN_p1Y>)6sEV!0B16T2umQGCBHTMYVUaVy!3|fAe^v)8-N#>1_!beJ2-ce zVetN<f2Z}YuBi;b1oW8b*DuIC z^vQ!?qWtVoq0yGrMf4`aQ_9k)d6l^gCb_~HnXl&9a*MJPMf3;NZD0QXAlWR(`Eg+P|ugr`fJ@01wciA4vzlb8Fm;|E;KUJw(iG&EL3jD6G z3CL!x(6&7KAwp#hPUJKC{>yO36+rIMY_A}Du3IW>e<$yG-#>+~LNo+*uN8*JWfxI#W&7cZqI`e-1HT7FGELrE z#tGDR+vd^xL7!xu%|->4Y!WhxBh_$GMB!hsYozNLglB#Q5s zgnCuJi9`huTi$6A&{N5FmmxN4Ytaf??jUQ)(z2izNW=@2zvU}^&i(_nToCl@cO2{- z%60xO7NPlH#sBmPRd9U^-CLBC0?0lf68yrd-VSPi?XNZnZpQ}gsw%`4PnI%ms~L#@ zZXV1S8Wfo#;*HCfTZ|PL;cYt_Z1lhFR0;bk2eP$6IKK?Ote0p}@z0q1lVLF=vUVv% zfh>??&*e4@Z)_K9Czlv`d#47)GD-z)-3Rv-{tLU8loA{gp~~zhA(FF|5C6zHtN<=% zn;c#bS6K-L4li+D_o;C2`6NqHaNW0;!pm#_acZOS;txUD4f=Sc5ZDsb#1fN3AtmIK zw}x@NnTi^VwI*CctjfbH72$B9VQt)&e%M!lD?;`GcL)p?bz z*TP*#!ymi(=NgCG5cIr>w~Ws(E!|_>U4(nL)K{BFd2A49Mx*&F{7sI>5>oPWT-%t3 zL#rsNrYZDwOY^G7WAC)I)y=nXu%s3Z2bJx)I%_hF{=e&gO@qx4$bAE+bL zJHAiNXAI)gb`m`5i}_YiYcShe8nP?EwU3ZZQaE*yv1X6_SSx;nKN&8DnwJR&bgWa3 z@hw$GQQL=`$KCyAjL!L%*$??8Yr22+{mZFM=-FP>kB`yhMKk@S@IqZnNF4I&Gcw;r z`v3M92l$==#sB<8v21&#RC0c8Pryram9SEQ1QPKaN3~owy#|tR7u6q<|F>E?#-fHU z=#eq3Cg?I#4tkz%kf-b?$wUWOK7140({E7smFYb;M6zg7>UYXJ7Uz4Iw4><-mM#DA zFza?%XxMZoYtXE4!_|+M)cs`%FjTnlFRj|NHNbZeN*9_|q}&92jH-8F@;o(|r& zfUh?0f%~MRj0@P>({C%8Yob3$roi6ycN0nh?1YA_3Z8!$Ad5#e&Qwv4hJfFTg zOF)aGG#S(qWgjTym}!hA1X-kYcDo@(31GQ-3>*o0y2!0JwPOO)H1jb*PpNXK84_5v z3mW_*NedOv<=R?nGQBTZ)&5o=!n4!;+I(v1C5fZCh`}{oF7_MK z5{&$nkK7_)Z_OCRHvZ;x)spkN$oUiR+F65^4*s(ld6b=vch`agG!+(5^W8}i-Y5f* z3W4N_ISMGi+x; zdtJ7mUh@>FGPMW)L>)n@8tUR0~NS>46cOf|Fr z-0Mqw^ymWiy;$3r+5{%soyLp|gP^utlN3`2Vy=XSasl!_$-hv`3Oo^J-AeDB*PG&)97+Yk4#Q zr7OVXOLJopz09@wc)#TSaKmts85b(;=+Md>X#ISn1O>S&*i5!#EdZQ27@ zrZJ*_{o!M=zAJM_vQeYrs89THoy3aI;aHxt5xBurr-K2%jAO>+jnSoMRUAf;$y9Oh zv7wnN$(oNt0cm6SstlDN$;5H${LGhBn&4BzL+;1w1MgkcF*zYVOm*GYOs!Rl49XM= z0~g+qr@e96Wj+GO`CXV-^A1!`hX#- zos=c7%SdYPhR(uD2;|II;4%QgkXsj-6gZRQBYZQci^9(wBov?4cI^N07gu8>P;#>3 zg_!A)Xl~OAygAunnlay)`Dc{37JzbCAT(CY8Aa!u+|&(6Ho0aswS=6!um?wuKc=XI z^*V6J$qz(N#5i{>`&fB*itlCQFiYR$6iV|mQ7z3Vi;~rm^!}Y=xz5sb;>|7o6mTe5 zO{wLkom;Zhb12+dtmWKQLq7+Fixh??$r9`mYzrNUFBEGBw&j+e1-J;j==`8j+*wG# z59N7Mz)Gqb3;sla&B?w~8-|ys`Fb`9*SAT5jtrC$o5Ms)nyj8&p{Fb5qGLjY z{F-`)4?_V#!C0#bctIV>ZVY3ndv$am$fd=r@ZE|6EPhrL&5HCIHeHM_D5{UO#Kb^U zmJH!^*E>89+dvPcyQ3K4)*bp%Q&e2QJZA9z4tNY!q2C@h-cX~Iv@}){Hgi$3Y8u$V zyUzJ>kV>+8bcs=Jdpep#j*xn_%kg#(#YwIu|Gl~*-qZueG;1MVI0-7a_-e|bka)nLdoeIWHYA4YS~n5QsOlZ|R=s5fSwP%X^4>)fj&}w22BlnHvF|d>Ut~Y^6nBW!lLSV!% zyBRFdO^*C$K^e?5kQ3jLi2Vh{@qvwSU?>SJLbFf4E7k+)OG?6A zHf=YoreA@g$oUDf$?l7ctJCqPy~qAWm3T3whz=mUC2Y=?lAjqZodga)7&DoG-n&ou z6@2`?SWU7oLSmSIw`FP1HS}$`*!+ruUyo})1CH%}E^r<#zO(yu(zXFpv4GClnXxioQ7#Dqt z!^fB}`!U&hzd@DmTkencu2FTyo=7t3oOE-)^tM;6;Hjn|+;gH6+3K^jlabX+&Aj%9 zH(a~pXuqAyOb8dLpzPtuhw?;nof(FAT=;3g`gJ zFuMio?d3bYiw4D6rHVd6p|V+nE)`cCK-5nJFGJ&WAq0iakIVjTfmFnFJ#X&jq*r~y zc50t~Sbhro75IV_WthWEc3Kw*ulPBpV!bwiycsvxa*Cz0HI zYXM4qBc2rAY8k!H#fi=dc~acP|4NYZnCUx7{m|Gid!L!HjfHmt+66e{GB)k@J^XrX z^8TBJ&vNYTk>U-f7$bLoN9x>+obW~&I=q9txG$1VY65B^NhUb>=1!?DZlM={b$M6C zd?L31^iK$y3w6|g=SaHq4?^C|R8V$i2F3!EeL(FV%>_{Q0&JG`2c2{N2|;`}hyHku z#=wWMr}L!GNc8u4aP^WQYT|{D)(V9WTHrjE5+e$^5*A@2%Jz=zRP|z&E~@W5>U0*4 z777Yn9t!heH9ZxkbH+31c$oCLc)-E!W(6to&@Uh3zU0Hh^Z}q{G43WnRNqndVFO(z zgd1kTk9-6OA1sTG4KTkG*$xWnB`)P9AsZvn%_#>jl&Xh?^act9;$e#F5$o}>%w{oH zBqW+wkxf+7%~q4C+d|gHD7MCFlkDdA$9xa%sF90W5E3BGX*D&862qyttfeiDdp(tg zFQJ0(Q_}_6OF|abP9nk!0`zM6Cq6(h0T<3MVuKpo=Z1rj8E_N>ei#gIVw@Z_fx5;( z9$N*DV4!uKAhz7W4YMV_Wx#)C?XF{p6UIm{#=)(Z)WuE!v1;SkYSh665}qy`L?^Ku zAq(G_XN3l%7?j{?du-YF%6yJRQj1dxLUX)LL6!m`*`dpLjeC6fKZ{VF!cPto_Mb&a z=~>O#s}qvM@Z+$GiS&|0)CHBfiu3hv&Q1ZYUO%okU0f}GsMj#g5kKztU2C_o+$}_) zC;7kTIj6^2w6vO>L3U(-F;?7NBIN&33Dw7e+%U4yoqu2y%3~tHERY#AK{~LLzKF(J zAmFRNFAKB#QT2t1{;Q_^7w)m&*kav+(pQ3Vfog!1cl#1aJpEYDLlb= z?Ne(a*7Yy6)42ci?Fk1N!cKD_mQ^&?c91kE&8;2%ST(xuZ@OR4OyLftpd2kuO;Os3 zKsP%0^N#Fb^))9kR=vK!*ca>uh}1iOsrTJd|0QPyr4hu~*8uFrE9o6#`96RQ;w#S7 z34w^M$Yz&_3NNp?5-s{`Q8Y$SmmNjO1WK13`Pw#a#5grK4032oM`Z^o@rP98@}s@u zzfuAEJU<3+NsUfPBoiukCj?XTT2W6($tXa{tVhXeQLz&GoF`Ut%Tul$^OUJp)(XIx zbikR=mqo=>{U^v8J|TO(ql%27zutk%Kqymo&Uoc$o!bi;p!F?J*&#rAy+^A>i>d~y@(xDuG={S(DEpm=_g{dlFQKT; zE^1npZaPGcLjaVsLm}n|5n`bAQ33ADZSF(qgsLGazu9w%G-Q6O(*Y>l>xnDoHFr7; z1W^D(@>+WVMkY5}W=1NtW2Dc5c`tx|Jyk1AxqSNt$j-^^R^?n+wKm8E zm6UEt+u=_w+HkdTg0D+8krpPQQOn0rtrz8)3rkIKWUyAu zABXB!A@2}4riP)VE1|`rk>d;QviRYmOhCtKV-h*O*MB@VMHzMTxd!^fJ+8wSguk>g z;8miv(-!gS~F)C+rM=idr&==?0VY+!jXLEJh>eZb*ox zlzO+>Kaauii*(FHrTK%VCxKAmN`Z^mcG0*-pSZc2IOzc;xgw)+z!+V%l1CuR zNw3nU;225@0*3yWZ~afd`uUC_v)AVqFN^$ZS9^Oz8AApVO|BD7NZ;kfBz^U@wh>BR zB9B}$MY9Vg@D-B~_$@0o9@|b4H^&&=U6VQ@=BPyO*blK_j8W=^$y}mEvddz@yyCb|_hqtT)haPZYx3+8ux`i#fwe~ist4^uR?3O zCuZudWXI%E0}E3BeXES5s4@|bz^2M0l&Fq0Dmh_=r~uPhtZJdG&@oTey3b3d${)I~&zC3`?jz}A2p6Sd^r6ZPEK%0;Bvt-f zWoA@O`?txcB->^+y)dlRrK$Po89Iz1&mv9{yX9&K%WPRwLJrU)Av=v<`J2}BT1*C; z>d8tKW@FY(YTk!+#Hn}SPT)OfolYT?A9hgrgg|sD^@gvqRjZ^cx4ZZyyM@EM#fQ43 z|8>8h#<~VzL5F%O0rGqnIKL#YHP^ep<$_pCbM-mO!+w7qix-mS?zDbEXkQ*2R6H14U)P>cuEL1iE;`8U`pIn*0I^d@|053}Z;b>N-F z0Imf?7m$ojvdiD1AGf)yv#NJTa#X{jN6lhX_@C?d^^m!$(KE?zo6->z_YojXKSo49 z%g`9%$(Y{z{&!)+w8N~XpXgr%mi3#yl3c5OOHsE%@~UJz0O@_>a6{EfDN%p)Ejjw% zxSkYqnkU(A75dgQa2V4-n^`7#JHcO;xszuEq`-+~){&&NQrKu337d&2HXi$DGAaJ9 zaBU`xf%X@WHmn*$C`@2$Ep;zUNl%mXDV88B*fDOn{n30T^`SkpOtww$eRgPN@amMe zRIYHD@{u{qKS5*33 z^xKf($j3F7z7=H2)Mm*ijmO2tZ5&Hq(u@$F;>UO9cT33;%wL>zi6$_fVi-ed*H5I^ z&rRnIme$ud=6fLofEX35>hQUdz~0bO?26avC&qXa&%Pn0)W{Y?#a&ON!<)$Yo5!j4 z2%ImMT2rRmXA!gSX!a}1TTtF@;!lvxRL?T)%`$Cy#Eh)RN3QDiyehAnUI3`v2XC8E ztSxK?)ZQ5~|&hAich%|ve1z7@p|lOmvy#w;5nWdUBxS}*^hTE2M*wFtYB8@ciR zd-F&c@(#*!)w7Wcz;2QILHzwF-1=|u)+OO{WF`9ir0v`a`8#pM6U|17%u0!4E>)p2 zQ2qP$>!?e_T6SmU@80Ms7ApquW}MP8=Il1RSmnLeH8$S&2cZ1ibL18K|MwSxeDjE^ z>d9mhVwp5k{#xaDa?!Bs)yq9aN+i-TNh+Dh>AB`pe=q`5uwl0NKYuY&dm&Gqb z)h_hON@~&L@f_ynFZG(G5|LQK?qAr#Duf7`j_2rw%qtRpG-|$D?NsjsGneo)o2R(1 zsC)hlVz4Y`)|yIRziQhWiTL;T5nGJ!-EdeO9;xO$yM9+1wMP9bv~*(`hZ3omyRF~Z zrppRTXp=&I*(^k-RFrMboXsaXa3 zzDf(eo8EuY=Eyd^5CER4Z45e+t|<$qnBH$5dL?~4Nn!R#sA^*GYo{d}FQsZ6`FHb= zT~y4C3Q026W8$_vR>O>aD(~pPN{Zz3CsU8+Gn+ER98&h8@w$>s)CFkJN$1MMRIBx4s-F(V`U;xCz;uVtLv8rnirh&x0uKhBr) z)wsKNec%lz?-FeOOWrbsa4(Nx77e-5fM$B?uQxw9X*LIg35RrtqPm2<-;vpH z8;k@!F_9pG4>V4^&2jA$h;`8(NFshyo_;gCd;D>M;2%Qc*R3*d=AV){=l1^G>?_r6 z0SPaTr%WRHvgObx->Z~B-DO$ukzwNWGC;1@$X}kQ|5$L&I(pM(g?)2L-17 zM!cUv<@Mg|TV1x8iwVQ;k6l_8-RvT(QOGmickw{0-g%L}uqAj*(zxlm=Iflp4ZS## zKz|d5$a@_#rk>#ckF)#!YN~zLML$VG5(p_20Rbg|2#RPBDN=*(%&&3%1 z{O@*c;gLoH_4BRl?p9u52$4=ST<>X z`*WIJ2+Mye8gP_fcZd~ zlH%(cW@)i&g<8>mQk@~_+HVloeTB=0TbJ8}`!-RK&I{I#kylr9J>X)UBOn$Hkf2YSdj0ej{@GH)4EQnbqLn&VXXPyGyy5fQ6}Y z;A|B>wY5O-SXX_Bs#+=Y(m?y8-X7uWc2|sP5Lc(eS{^>uO6~Bn&@iPT=riyqHUXEvR^KNLd)gJus>*l>Fg|v7OOQ5B&M-euP`?-?~z} zkT50|tyH!1N(rID1p}AANB zoQjAgAd9OU3z52&2d}-xf~nLB z0(Mj%{b=rb^CBTxql3?zm3Qpv;|?o}MSkkk^U9G~Ht2mO%gw1~D z!2iez7|2^26UvIow?kl2kn&4r#JD4|U2oK?kpvib;$X0N~B{|qxSx>fVvvYNh)cbPe z)-v9@s?1C=3Ndrcza8Ydb-bGu2&&p1Z&vDO<=ZBY&P8a4Sl=y)cy;$Ah#9by6YSJR zJCEi;sI7v8X68_)*K)Dy_)zJg5t<-=5Xax;o(pU@AOE&Kko+;ABnUSJTom*YV|{5r zNpbacgY}POLGq!m_>7^msH&w7uQ1yr#bGb^TMmqY$$M(yx_gym zrHyl$_w<62Sj8lA(_{bJ^!D3^<`uh5$8mgv@Z|ezz?NmOf$0UvAt0$X2Ox%jvM0?@ z<7jUZ{Zjzo*Mx$cK?gE;^xN2_xs6iU_VP#XB*tn)Rj!-`I3*e1L0_|P8Zbufqzw4{ zx}~gug$fN>t@$iTEgjy($nE4He3un&G>?#DV|EJ!d{;E=o4;hETnmi@e+cO-h+PF7 zR9L#H7d;f^qOdW(>tK#sSolA!wA?3VaDW8kp-rH1#V$~a9z^;!hwjGan}4*p+?Q%) zw}zR0Jia;9Fc%;lcPQ&0H4QrqGsE{e!cuS8C((AUm{zpA0oM9_l;e?aR|FCV7VaFblmOBmSKFf_g zAO~?CsQ`dXT$HIvCN^1%NCp2%26igpz^ns?&ynf5BP77FxX^uUi6Ayg;H!fF9fr%} zjcyG4hKew*Hux7K@=+yn;0;l1zM>@Xp5pBKmmISIEaP3uC!1J3wF1BNMFn-|58I++)U(| zS=h4>_WZzG^bSs1?)=zx;~ z#8Bq2rIhF#>KMICF$?^$9`vzXA`wBw(W`yYeT^|kdJ>x{%6sCm;3mdjjnTdy(Hq5a zD`626FWn(D@n8AletX0&r$nvy#UVZ8&z3m>RdvSm@m&3k*wiQIQe)XBWBFGUP8ws^ zf`u<#Nf7d6fcD2kwPu9HpPn^>WZzz-8f8?TS=Or zO62PxidvDAlv5MMt>Oh%63P#f4Ex!%52G%ZBuaX|q^txy_KfSDkB8`hcy=sF9uvm2~tf7u}UF^rv$1pKt#n&!(a00zp_kyrK3Qo;l!| zIoY4t)s#6+lht;ZIX9X9>XF+cQ{bi+C|p0;wIgfue9CW{?4ADPZPo03&*Z=1*~eFs zkNU~kKKh`WTmD{8t!k`tU=cYKa1rq#2T3Vaqs=YSH;ATwRUs5*JeidDF!!xvZbdFY zk&bMXvv``*8$}_PB=Rmt5R6ka`9cwy6oPTYD*uui*bZ;Sl$Og;pIbJP zDUCt z4~r^@3j(%4&2gw*9G$EdrU8rEt3-8RA+Qn9@)kOZ25`zj?qg9gl`KVRrDfkrE7;0v z9+x$wm9;#^#E_7GD^Z-H;V9_S-iXrD52cWf@@lm*$kVdM(lTl{6PkK&03ZInl%;R= z%>ZrLPcIA@M@JrZ2k_udJbDd_kY+3IdR#u0R{mqPbZ503`n2LeBD~E3wYP<&QNeVo zmG?X@Wf4foBB4CAz!Coe2jl4ahM{r}h{ahdNC1t47T6X;_shhenu@M-s|=zI-oYW{ zb7+oCU|zXZ9BWlrf$B>()%<1E*Vd|W>KKYQ7&Q!5kArD%lg+h7Eo54%E*w{JNmlcE zS6@K@0^h4|*!U}jnydAg-<7D-`4#H;r$$ep_Q{i4BXvwVzQ#8hnAW1RF@dekx&jXW z#z5XIcI>r})oTrHFfId?fCEh}1|~&Jda&4omv?rfl}+d;|d1YA#A|224P^co@9HDhmqaJZi~M z$7CUz^VFLQy)ngQ&99!Zq!e1cKem!%WvOpzZCq<@`Q8Glf-VE#NE_HOAs`)!&Vsg7 ztGBp!v;m~nrsGy>q4ve}3aB=s2T#Uq2v~1QUKJrA`d4Xt23R^o3>a5gvf_}GCPoql zQju%?c%MaxgxJtRPv?+)sVY8vV{yRHtyDI0tSOsj0|1(opmcH(Sf$t0dnAA;zKa=>9XK>FGUAf z(*YEA&u-5KKsjF^r2v-u= zGY3WPVVUJMTCgA+`3cd*XhGDmbV`w|55_3D6JN9NkSiz&{=p4offLy1cb^l?grfdVFyWFXcE$% z*bSjaebc~D>KXf4SibrUPPPtCpA61P4K04``o|nJf!Y6K4q6Q;W2}4Kc5DYH)`zCn z2WL;vKk0lIY=?|l+|1mwphy7j%d-1%c>iShhz@ATX^r$oFiiK7hif(rFk9C?y_g&M zyN)@a8)4A=43X=9_zLYx8v0EKTyMLUfkXM``nK4F2h4%U04%J-GDfMxmx_$&n`Qem z(CS~+2#!N#;4!==XmBITZB5KCPt`~VRHOqWdKeXr$JkaPx5Vf=0TS;P7+a3i6GOD& zs@@KK-sJe?E;sfpddwOL*lvtD7-F0>$Mu$I$fPg8Ea-T+hHY@f@z414%rTqkv7@aq zN9pknt#JVB)BW71ugJ&JeRxoL(!y>sP;(;9Zo(6bGP3#1KTUNN33#7=@y+~3@SP0G zoJ>aom4e?75r9%9sz3|Vh#dW}P5Z@%#pn660%leUJ7{p3^{mI6@CR8li&)D++O&|O zPkj8U8Y$)=Q3Dfx^0iwN<3d6QUzJ$GH34|qZ;_$D9*#ok$prfb}vuyBN6N1R@4=JlJ>!BY^mOq5M5B0_Jw@ ze$b+TZ_0>WKL29}Isn%f;xhxji_tKc-FY+jWN=RKqW{qr8kgm^I^3|5**`!r2Z0&K zIqL*CP<@#dilNgHWTo`IQ^8pOr*JrMgGFfL%fhs~{T5o74rnKguSH|dgVGNB4XKUx&}xn;6|#Z};L_a(S@?3s~|p!uY%>&y{RFeYuoAhLW}X zVdJ+z_%CTz1Z zM(>Q}AdZe&8!>mr^76t2p{ns&%rEO9mfM3s7V<}4K4O_v6<&#|!eb&R2xty$VG9AF zXoDo^t*w8w!6F09nnu$qpyal_5AElCf z8sT=uEcC|UzcHJ727k^_TcCSeP>z8QyUJ zyuniEfar}em{`ukMD)h1*uykq3>N|Mdl>aD zPA z?j7a4Jubet=d0{~MHxkNqmuc_Rf``8A@$J-HdCH47O)m#Ij%FHBk(#rh%kb9fC6gp zABMRJ{2F{OA9bGc`6fo@mE*V+V=n1` zUQkWC^6;(s`Z`vl!@xLDWjT}RzzWeyFLQnD%O5j~VT zG`ST!azCnhc&;Sg((qb2opibWj{O%lHbA0jz!@^pNc$8PBk27K8f3Ec3hRm;r}&Ej z)ac6w6I)Na9lsawV@%*4Z!3 zOdq>%&ApH1GoCr|++F!v@%+cksrSL3#ZN`XKhAtl4)->fe*7T&17IcxJP2`X3lCv@ z;2;NOciEDI^CUUkp%tjzx|7M>=^&4i+})B#s83$zV!a6bQDD0Nz)|r~!Tis^{$fuD z-IjTVSEDv0SE{?JH$~~}%F`T$_9h}n0Mq03o4~D6O?vayerT9zb^P;`NNDo{yEmyn zSP9p~Ooe9aB6`YJ#IBA8+Q%eI4Ac3V1u$8G=ISmlgs_r>%@3b(vCy;aCIm1a z5@P}+sGegT-?D`zncw`^Uv#Yq^Is5pbkV1p3P>^VD7eqAgZT{3hA>&X=Ez+Eo5c86 zyA)giqz;H#W*geddjI%~)2rVO_)wfb_vAt?(l7AGKF_~k`OTWKxn4Eg<%wC&*H8#4 z-W~9m<5XJM%Z0k}yz(%OU_8z#3Ne|3a_MR)x?=TP_4^XF4Uq@g0aW}R*kITl^mMa>A)^jxICGqVg{x2S%?l@rQ6 zZQi#0eVj`rN(IYy4Gow#;*9QJ$ZiDq8M2*f?=Dlx7*8F-go|hjg{^~GM}B3w#i=gX zbRxv2Z0-%+_HpcCcW=$t_%@px?{4II;`C8i)`xkrlS`3mP@W~Tivawuq@Xf|6g;9L zk}2oxjC^)_MmZEr@V`mHGYTg7e^&*`2M1^W!2}NvD7@ei#TPs{INIMQA8h<@u;9tR zupoJNjsgqr?QHGr>}*q2z~GM`KTfB6PQH$kzh{s~!)In@{{Py7{YM}Bj{j8!kNWzK{v`#EJG)NX z+bM?Nep~zDK>g{*sN;@TK2&Dgg>gNIAO$q}|@$v7w=z*4F=c zf_;5`6i={&a{l!M+uGV%T3Q+#8!3`tRaMo$l3)h8oS9sLAQwT&g`oe&1o_WOSf&ZH%n3tEAlaoWi1P@Zv_T%Hp(b0dRWB!o@V;;XtO8Os3FflPPK0ZD= zI{H77U`R;FUw{8255rvt$3ts_c#0$F@9*d5cV?`4c3*?6Dt#t}TQ@LVSJU{Zpy=b{ z!h;Rr#<7&Z*g z|B!;#Q+-wckb?3N9I6yjFp>X$sloZ`IZz1B>_diXP2pg=xbx~%e@)S+e@Q{L+TxLX zm8W9|y|pD@inQ|8GS%uzzn1CMSWkbbD;uvc>590ZUSB?0V>)@saG?Ip_Xdag51Hx> zZ>L)jlP6}0K{}{cSB}r9qjYd{iJ|CpjdG7m^F7?0lq-Er1x6em-`R@g@@keo<;X`~ z)NHO@`BHqp%xJK=Zf(5MY#>XsrGDdkquDr4%iSs(>ds~^3O6{|3Va{SsPWbZyYuT) zF3kQq&gW? zE#U4%2KEzHo)nJj;h&GXb(X{(a%t#gehkOwr8%PX&$@gA`Ob&t8kfh4zeEqp<$M%= zz<*^i>A|B(jzs6fzZoDFmw!pYE5B0AW3Jq}z@1b=Aq4|V07tn{)}jnq+S^5j%FQo} z?x;S#&G_nr@AgMNKW6LY+^{2vrNQI7VgOP};p)miq~OZy6jQHmHf8hGm7<(SYF)s< zwCZ@4U2gNM(z3J5HcD5Rn-@97(mB) zX>GlVwc7-OeBBvQR95k<*IMWM#jk>LzDHLvl^*njkHSyGD5T)Jj`E8qomWj1=suh$ zfb3IMkDs|t^z6OSCNrF?B%QM9;}WXt5u_G(*KNA1w9421bgK%rzN%zl4UlWwM-c<) zS;XBdvv?A1H^O*}(wxfpl2aU7n8)k7ga?!Ge+I>uqV9iGc}jP)_u%JC$G(&Lj5qZH z&gr$El^B~`B17 z#0&&(?L;9xh}R`5(h=_)47y3&aS-9StHZPS^D-}H;k+@J`8e>)mfuN?wug%cr&+__ z+g_b92gF6aJ=uQ5h8|sUd>w;Xm+ilpxB;7+Io4_+kNV#G5%kV?p_4~JYK2_9%o*9& zICOHnmA%}``<(=i6>@f=8VdLQ$c%P16K9EnvU zql1IC5AFk>M>?7)<6InrC8ogipxh9l86a3=LLLsi9W2c+7yOVkA5@<&Cv!6%%&W%@ z;TopKrSS&@R#w`@)qX-)^|dgwEriy5c=`nLl?Lmzo#;5Sfd3{(!&@42c~~9K`KbTH zqvq|Gl?E0dCT?lqM9=}k)Y8^Uu%31W$Q1Kpo>q2Zd*a^X-%_c(e>2CK!Ug|J zx7|0Z`8i=G&zzTMg;C?OT9VBO=q(5E!71$vf8GOt`?n*6_ifOHX_NOb%pIyvtaF^V z4@eheu;f4<9}*?HvA70P)6xg+=DH)lz90*w#{Y5_+#+r4M@b;#MwjN}^X7CSvth3^e`NS?Nl+OnZ%rvc(k0p78bk4J|y4Z{<^Du_2gVEAFvjdly4OCbgwD_Hh@v zlYn}&)g$o{|9wPftn#Lw`~{Hu)K9kk#y-urPRRpPza;jXhNIuQ6sb?IK4xjoTJF91 zmO={ZBr{k%9M@0$i3@AmYh6CQf8@p;fGrO=w`R#F$3Yt$G+HCP|8Ys?`0!rF(f&IC zwIvtA6&WgXD{nKW7^Kvplg^d{Cli7Q(L#|yZ22A6H7&uz@igG!P8RalEBAb@A6BI` z7C)7)icp>Udag|T{dLhlLPt*{Sl=~v^If*_ViGkfzy&-LRj-I6YQ)vh1~F69bjWV^ z7V(P$gcrHgqD~kv@#pr1pqh*Db1;HIR2N3Zvg`8dV~oOR5WPI>drtbIMo|Y-GE!W; zTY9@U+zG=4Wh*Vb)HIp9K0)b2-vVWO{v0%ZBc=o{PQ!+MwB*WmWo_UOV?UdNycR$I z!R~yZ(DENN$msR}=aiGHk`T(LAc#dx9L_gJAN#~3ZVObO0S+m_X+M37xc(4$BAF|gs6{Kc~l+bccB6?Ge!g?5_| zrMu@M_|i5%FAPOBZf>v1Aim$-zDUb*q#dnlp5gsnU^mw*g9&uI^9Mf}#@%lZYMaxT zx_%D!xmQkRhb=9guW-3n=*1AD7vB@-{ZNXgIM<%UZs;lCK1t?|NlqT;{Ut+NFY?li z%4*jPBb7bZtN5b0fZYO|W!5>;D;2TdTa80!FE5(DDH| zOG^}t<*1jr&Kz?=oQ0F0z-8&^@swf+!ua6sSM)sh#e#%P!MB14LKDFce-hC9-i};& z%{eP*FrKy>kAlcCD9AC7+JHM~$MKl&SX!y7Abw#2BrMR4i{=!ITu34)cwD#|CZod2 zQ(_`=w~?p=3V~?{odYXr-co8bSF$WnvRzPefB;Sk%5LOfWk>*otYr*f!{r=8fxb`~ z{y=waU{i^fJ3lm<&-a@<5qDF}wToEF&*SHz%E}6`VIr%=BWv{{>sccWlQ4DN{!O*& zZM*6nw1~eC$fyJ0kFj{(C9nfX0D#Cmc$4CK|_c0Mv#V%i-NAT%@vTDF(2hnFE z5n4e3Y{TeZ9x=-)F{_O+zly19UDR5|(Lutr6t$<3q?<~u!}Xey!Rwsn)9i@@^A0vC zdR~JmUU}jXG)-PGPfS6M;a8_ek6k2Mdr z*w3@54}u@zA#z&@aySZ2n0ONaL`Y~G@+|a7E0NkNI*s3%p^5n-26;NHDs!6{{D^q2 zIGT?ED!9$fe*UG~NIaNIy3!+3FZE?(F{UF&quwPUM-)>p3?Xkpg@ouTa0t>YMG9(}Hia+~#Mo z3m26ROLd(KbqM1?o@cDljd(~ly}k^}{H4$Ixj!vfOth^jyr(47SqQWVrFE!|>mk}s zTJpwk1ujiyfIp+);+|Kb5mUbWoG?32PNy;pr}JyUv{1dPOcw!96YD&9c=pc~zP_MBf;C3_ z8?b%n#tR9KBb|)jO~u+|F&0f+hUeoV&Cm>i#sa>ZE{ZJ0mJ-DP{#wuWwVdY51D~(u zJ}!OAAo%5H>f>+4?^2myv#?VP(y=e^&1znfH8BL__6eX)D=o=5;?HF$?<~ENakIQf zqC7vZH0ncXSu?ZL){8>bvcYeDH?9VSes*u8EzY=#F)%Hip}qV(;qs58H^+J9Tesi1 zTxBtv&7pBDFlu)FD&b_UcHv2m=VWuqPK536t8bP+M0rvA0Uk45#s~Imv=256I+)?P_VGMND-Y~FPY&9!4*{MRjwbR_F8wGb{J*XTd4BdyfopMolB zku_{3)@$B}p8RSPbhsz=OR9BCAL<#`>g{tqjDa_I(yQm;_1oWSaS6m*9~yqGG<-~} z!>4B^rZX|m!q&ZNF4a zs`8fJW|}&nn^9^0bfxLhTJzQXW<&KR8EwEnu8KI&3@^jnibJexp{FXLo6nmE1LE6{ zTgJ+2Ys-oWYc(Iqk=1s8K-XIu-XFIymIUJPsQO{33?7!G7oY20axb;5h^Ey}pw)Jy zZN|GvnF^|is61j1p&6llKU-DPnfz%s`R{S^!9Y-$w=KPteFCh(prsXjLL{3&vgD|! z=a3bZh_yK6%VF2=?EFEWNhqJroYeaB<<&Q$m`((Us(+{}ua<#qTjBFe&s6>q49iWR zFSXE-T5UVt+#gc~u5!FYb2Lg!H49zqP>lz?Od4-TwLkCe$eind1fY9xn5wP!$iB`l zxh$Ky?%9d%S@!o#8m&TWJ;H0{et6{RR*vpTLw#A`q80-DlxEqayR|yoJhG>(xJU1} zyUV7jgKWb@g@;z9N7h8vmK--x=OSR&FcsLI?EwK6HuK=}h|s7^#&yYvjCV?ZK)yMx z?(6RaHA-wL8y*-)I1U{S^tIm1&o<~Y*LZX8=7$1~_MZbiI4bC(caB3wt*1|!D`nz5 zi{!N(X!%^w^pTir(A2IW^O~+hd5+2lL+V){XprP>vSBhmy8We<__eiO&vuY>txJC# z;^)v&*4n4$-O##Sv@{jGb6fL+V2+Xv@jf3D z4XPt-I+ZziQqn#N@hd2pE2uyyA|uMF655l~54RakkQ(Vc84&QrNDadtoeXYdH2x*G z3P{$Lu_1$=E2>>0pov%vW(?X+{LJv?GotO?mFai*kv``sv^ptH@y)2a{+E`(H@EHl zS8DGn6H-9hs8kc2i#>}H1KJy*B|8mS)@F7JNGzl>i4gFB%{m>pcuIf5| z|FzizX@R{`x^(xidoW!mMO`2czK_RD4Aa8qbTz5;X3k9}NKYmiPQLP;Ov#)~%QWyG zhAk6m(=U9>MH-z$4z?yd`ji6=l%9D0-DvZiaoC%QC_Bu)BIxk-xQF3G!B^jH1jk!9 z9yFeQmp?bvIcWOa4&)1zeIbF|Hom`)e$YMrz-PLsouRrc+E+;lVSogTq(@cB(!qk! zK9lR+a(}3O@qtQ`p4!Nn-pTQrZ8KJ{>E?aQhT$)vSd79J`i|l7kLY0<>BiHIALUbw z%sDVWeA08DY~hXg*U~*Kf;<@3x^2qbMafRh#11NkSj2ti-LO0L9afN@vEg8n9)=Ny z(Lyfq3wn0*J<}e44vI7(bkf%^PB*e{?={3Pw@Y}(;HcfeLfZ#B5ig`oZ z{&_BnF>MQ73I1{dmV=FB&}$^bZ5+li?w`enD1dQ3gXyr| z{^ptc3f-(MYN7DthZY^v4J6!Us%3TXC$gQ<7Ki$tBcVz{xRC*f69(0S#c+{O^>~O% zC1M53Ap>;dE1}(SNYEU3XNy+Jf#!&04j=iY8c*b7SrTp^sAu~*er=}W?!p}*sP9%> zW=R}jhM5b4a&`y;b3MQDM?(yYQQJZ%d%zC~H{3|*&Jo&a944XwQy9Z^{>`eg*pg?= zQaH!j2VLjlR#^WqI`()8Vf0dPh_P{tw$L1tREYv{f!49K3%m5@IIb~77uF1 z(1En+ip=p_`0rUrq4H&h#TLHeqWPbn3iEO8HPu zMF$N~JmhC3`gjXD0s$OyP?P~@4_z_T2^aABI5vEPXN_80bx4~Z5c+g3xnroX`gLDyRmcy z3_HSPw8#xio!!=Yf@fdOPieHBEayiIr>`7&ZvG3z7YF?^jQ-lV`)#IGRU1yuL5Gpi zCpl<)Zcq=F&R3phm2iUrhjyr?oiO=*2e}3AfP=FOZ_Dz~tyMbT+b@6Xa>svvp?AZB zlj*?}Y|@o3E^1Bw$AT~yNHy+Qm4IxDgCNZ4x^efwjx;N?5(q51?u6EiA9HI9{Q>~8 zsW)tBj%dxMUz2TJ(OsoKoT&cO|)`FF7E;0}#zyV0#_NUmQY- z0BPDnjdH_Iu(Wq7p(H$teSQU)D-GlIbpbdOQsTO08E7uZ1hZ=YRERhy$Q`_0ex4Zl zU!3elYLh19s z?K5f)y)Bc@5Xl){+n1$t!I9^ATu#KR7m8y!??U_Y?_Jb6#qX8dHaRXQK2lUy^f}@y zcwYSAUFd};f62CqCDa0!ec5W}rh~nYhXjur-UDVwVX0&Gw9ACRY=lpz7{Ym!I?G#d18x~ml*WUX|oNp5!U;6iD?BuL$)GQ0m8 zPkkzUgN-abk&nKf@Z_xuH2TuY;MI9^p{VC^a@c#CVqcSVvW`aIXvr(Sj2or=4WWA& zo3?C5cX*fU!B?~eQd?C@T4aREBC8|tzOla{gKi35I$^96>bk3Kp{jZVRGxfmvsoyvwtUu`~EV_b$H@J+4N_Fj;rgr=$nC2Jyh1uZ=K7tDPkJOU(M2n zf*i=yjm^(5jpNqXUU`F&St;!wrvT2>#-kKRx@tXv+JpukkY53g3Ckd%4s~By~fg z!zP>O<#X@vDNpl^$UFHwDv~6!ZAYA%AGJwKi5F%o|0*=NRH1K>*}|8v(dIGFNqd$* z7W>k7@E2nti`$HR^H$`wH133*8GYD=yFIrvg%jp`#bgdIS$Ul;j5oMTAI14BbOq^L zjxqGwp!x0hc~eZ0K6S7kX7cmnc>H2!q%YLP7$ob&h3hNl)Je;Fzvce&$;Q3==!viA zK#g+b8YD)-MiL9MYLKCJ>jwKQ2ho&=)*Xe!5e~avQB!V?L^uwIVs~;BX(wLqmQ)1u zoa8EggoHAvVa1q%+m#d?Wz>HXxxZqSfd0QQIq>6uC&X8G|xk3|hQ+T1?AXm>`PZNE=yRXbtB zW>G;;F%-zi<8(a=|6a%~b|+0GsalBRYRGx{hclrsv!g678DF^*aS4mYq~DP(j?Xl( zCOanoU0V$EJJ0?(^+n1L$PAmAi-zv?L}F6;!ou~>Z)KTG{IW~fSzO`rKH-e_t`c+x zNlo{_cES$J^3SV3PQI7qcIJk8u%g|xqG3IPIl}@-Y2im2CLyueEEnQr8FiHL`a5ac z>&x=Kdh~<9Pr%CbsTAy}<5uCe@hLl?WbxrbGRDt9Y5(!PY7 z@8CrqA|Y;yA*rGdB~++MnyzZ2h1zv?DuL(0<wSoo`U&|{3N+0~m z8;E^78Z)qKg^p-!D82l}onbLm?@s}>pX+wHzpuvQ{*t>5KWi)RXTm=+U^xfBe$65C z3R%nUdGSFS=_`{(qD-i)zrJ;HE3UXk8ugk5o~zirxrhu;-#V)6pDAI)ciGy4^Y!Zs znd|EJuBuu`KKW~VY2KFTj{P?@B=|6#02F?YjGw)#n&);P~t+gq0! z0RbwFH#G3!;oo=Dzt;y=2li8s8A<&$_?!2pPF%apjPuFcOa^9d_Zr~h5q)$~)OZb< zPQWW*G3;~QI7!!Qvl6QQgY4zh{=rAZ@n|?06g*yuZeMc@KdfSwnm;cn?hvNUV7Seu z*z(=3GH7EBb7GzFj^$U$$Ss3=RJyz8IT##cl<)jxf>k$G`cwv|;|WtQzrG_1l2@&} z^yiIpRn7^0bxeAgZ1SqRp+>r$Ghs0@ZXaR_NlQ|4Zun@jBO2e|&UTTpp!HcKoh{=; znDUb_0>;#5k+UXeK9DQwDRw8-GcI9^1*EmmaHi*}cKy=J4TVRdVri-oGH@Jg07UpC zkAq7bP8l+Q?`BVa=oZ<%y{7&vcwz`FmjIo-6S3GAiun9cr|b32Ma#!L5Zjvvz3eyJ z&b>0-=WajS3lB0hWn^q=?x1lIT+y|Z<@D-dM4kt^y$*S-%Wf-opv-Wy4dvz%bdHk% zr&hte;5p%eaW;0r*eYMRHGH4m40Uf^l-_jBe=@z>Q z2w*rr{;Q`XDL&d~YD6)e`u44BM1Nq8>*wW$Cc(Ro^%a>LOzy|ud9q$Kjki%bHb|0q zha66oI<|s2=06RsrTV|G+Vk=qlumqq+XoYmIqAa2OqIXtZCzshuG=@; z#w)B#r(e$baP5JqCijIKivdVH^D-t-VQLG_cj@*{E_201!ywA`2wcPpndw{SVub#I$1)j1YGLBlzdn#rM5_ zpT&3I7Rki}$gmEScUafCtg)R-%7cd^iRa&S3=(9`M8d6`Dh{Au?n{|)T{!pj9mjmt z?ER7*Gf~~uw=@HU&z)7j=ikY3lU{hVv*Jm)=P$yoNnme0je!Wf{IXg4+Yh9QyURoi z*6UlxGP{v*?cq>ff%Mx#)ePnpjO86P>$02a8ML;6=WuyeD>YoL0z9l@3^@Q16Y>vP z*hkF)@5rrU()c3>26qmbb@I~5Q|$^OCQ8Zl_;a;a$jOY<#GD{`2ap6V)Coh?uZA}n zIcK!e`S++(NJE|}xXP5~4b68dYw&1ITQ^a^jJVp@2hz|)Rd4Pap4}+;(b(Nm{8X^s;3-m3O9Sq zTDy5c^%1PfPE4Ya{K^q3%HfuPyhqB#;Tu-?cEizbt0=gk3eg)6GsH>0U`m@m?iskF ztPf@B~)Yq>jK7d7~ti z8huj4Nm(REKbB4*nu+ewVbBGY7%?YRE`z*;Yw7d~sx>Xhm%>sx?-!%v zcl&ob`Y#kDX1bJS-Fl}t)oSU}FLMxt%?&m1d7s_dzoV8Rm?2Ws&0qXcCC9e^4HF&O zf%(obCRSKoKT4%SAw#M_w2EWEVS%LKquw|*z$1wiJ`a8{aY;yipg2lh_fLh^ody~YxCi=@G)ix2^swgTNvRD&>bf4} z_drZg|S78p6EYekd<7&;gROX93O^52inp>KmgEdM_az5Xo zX10}ES%-gJRlM+k!-qR-o~dwQVW8huv*2Uo{%p`KRj7Q<(5jTOb9dqAo!*)`x!>z| zTR&F1M!}C;KkYqGKArls8w{sOgoJ(oon^pJTIr0O?&$^%`iF~Hq{tl>aBuFaPaAZc zBBHK;!D!)z!F%`qo@A_P)KXI?fAE5)1#5{X43}IRJZCY|%Bm3V7|JlAMNHA|!)sx_ ziqliG*h`IwtBnkr_itX)C>f@cHQ{eB(PrNmK06tHt-wK8AA!HVH?O7x6zd4^4xbq4 zTo$3D+_RPqWAiY$osU>GfgXjbEye^YyyDw$f*ppH?-CGAIf#}N9jQ5h|LIlP(=QKQMQ_?YP@dLtEB`t&@%i!=m?u!_TH8Yd zZ2J;8!5O@z2igzFtZCAR`ZQi6iE0z5sa zc^ZQQQ^J0-W7LAbB0;0H$RQV}`-xiweAp{Pxfa83RKB*-13j76 zefv?pl@y{200FLWH9cYwhRO{?O+x}GX z=TeG2)rQ=Y|en8qf05+`uU`j6PiW`t8*zB7ir*W&(=!XkQTod8bhG-~$ajU~H64=su_^ zE=Z&?)C4o`iGc?;wuWhqgQzenn5Uy$Pd(2WaT(ry*#}sr#DXx7SgxzH4j}?IXp<2L zGQdiiW+8%esEjB=VP#03bXa3bWV4>}_DVJ^^Ji{}=|^g_a!sR`%TZRtYA+X!!<;me z**F;ld!%L3Wqunoh3ZbN!!=i7svM|1vAxs53bICflybSRclW z%e%kz6C|>Dzi?r0fM2JbPxss+s(MktOXJm`>7wn(ODqr`4!yWFEPwF|nfET>^uqwf zrlPcPM7_Y$LvxrDDqCzIsAysG_GOjtr=R-QG0wl9&sc2aKdhWKemJv`odS~I1vBD% z^`MWcM85o_!u&bE6c_Nz{MADI>0&&8fTe!u4c2mdLS_ zOBJ8Z1oEhol=-9tREy1VH27XGmW zDr*VaQ+O^f`t-3|*qvo+A2>`C_&MS6lU|>s^~lOT)p9yv$ywAgPA_mloKj8zWcXR1 z+xV3f7oaf_>a#^HkJJ0gzY0Eo5vgYFpuf7U^IZ09895whu?04(UyXgX`q404y%Of9 zM|`MdGQhe9o@D+iX>;4u%6nxIA7d52x0DDc+zN-vVuN)5E=N3Do4ZDHewZQ>5)I|keTpsED07* zZzqt-$SkwrRUal6Sz{EZ2Q&iuCNPS0Xjdy;RA^K8$|@{u)ejf)sQ;H);krsscOn7y z*d&NZB8bx2p;4*6R-vBPUd+FRtLEQQzrU=HgWc8xo8h3&F&2`8Rs*Lm8h#V+Z-He9 z&nMr$_zD$BT(o_~Yk8+CZ6l zGIVP#rW6tq<{S5-ZW=b>u?4o$8qU~43e(tr5v`uz2;wJdr2Ia6Va=`UsBc8`F*j6h z87y51%&0l=H`vC{5?NsYTQQ6c{X&2XXjl2dp=+Lixt#zekQEwaR%?XR7&yN|p}A}jQ^n}cZs!{@n9v++N1 z4$>3%;Xb(FAZ#FtbDL*>lRtSokGP#F@Bhly(@ln zUaQ{2QWDO3FN`(CG2BB|^2Kkr6qr#;K%&?IQ>+)H0o8UG48oz98h($-ESFyle>%JI z6mwj~a-2oXpBwp+gVqi%-VSCBe0`2KIcuQ~Y9BvMn7U03M|4a8>wk{}z)6$aac^+FB=O4y1?*uHBCk$ZCae)Z< z=2}rr^Pbc-P(PW48Cv>2$qCT}IvQndtx?a&Q`tU5m4n5U*WlR`fkGdl%QPmH!NHZm z#<*i~+V!uWw1Y9!A&=s|qvs=gtc}~@r#A%^!Z&6c{KkHNNU((QsDyEw5EqI0i#P3- z_+)xI0P3Cq4NKF$qBE#KzkNRU_x$erzwMlzopWv1xpww`zpm#aTv`@4n#ywv z=YL7TFv1gI)dPO(q)-t?eR6RfJUO;YZm;9dD({EOFKuysr^`F1lrg8)w z=IWg;suWU~v9MbqfT(WotB`F7ta)rGT1ki9BEF?|K25hgtw4PayX|!)E+AkwCK)fs zxYmzeBdg3bL&cIPT}jutxs}0pvcaVTp6T$}Z2i~KpU0a6qCe62wit=G@+CGArgJ0w z(rP@F249qu=FBdJE$vG3J#ZjQ_Ep}<)bZC#iv@!;`-0UsXNmj(VTTaG992k^^FZ_CDmd$L6*a_2<<`@B-ev# zYb28KU>1j1P^ohvMm$P&Cg@+TVsYF(ValXXYQ+t6qJVPL8sg@dED@OxNQdha8;fph zA(vQpQ)Kin)npfJ1z^;#5=l@o%J|B=nu=MmX`pD2p*S=Ge@dkw@h<8-QIIV%kUh`o zjp7D@{eJ{Qr88B#40Ru!H?(_Sn>}rO?3+K=vFVnNCGvm* zRU)M#9e|B%UPmXU#{UlIlpwhX;uc9II%?3k)cp7dAk;Nq`+Y0`#fQgJ(Dc4Xd;e^> zKkCl#oq=k(5fE(JWF7NMzPEbhOlHJU?H9Rt3YzZMt|Y(J6!Q+?lfWm1G<;z&!A;`jZRExasyJU9`pWyCTK zj~Lia)sT6rnriksu!3->{_^{&-^pJEQQmnSL3<+B0qXbID`K(r2?r8!7av$78T=r? z_2u+wNSNSsK!fDjAhg23wX6x0Eby-P1%Xt(qnqfDe2rvXXgSBuH{{{r*5F~W0DDeH92(Bj`;F-gz(FgxSwXuj!u4w>&a9MXMqd>-!;3GrWqNnMuWyaQX_ zz{cO_q$D#>2E!ql*&=^tDNq>U*GMVUNN@{}VZZ-1UB^&^@ck+rf;u|8{xk)a=hh)}1iO0iIYVa%lEQTaan;qXM=7+gf8yuxf# zJcNV+3O0d}oejDvA+}TpOeh~jU;tO@kD@-DEEjCEEZmM`LQOMcPlE8p@@iCg$xCrf zrxeKagfl@@0sTnzaTUpcXM%02u!SoiK?BP!%ij)8I!0E=Rt{KTAtwbs0|W!aU%-9_ zq-jfmDaxemat^$4ZQ9Bi#?a!C29u)WG+*@73~*Pkh|2m%6!p_k8ERn9b9{iUAVPo| zTlV@K3|M%P({0Vd&F}&&E{Momx+E6%Wd1~=Eui<|eh=B=(QJ^Tje-bUJ#OGsQl(^N zR)zzmxU67`9y_3sg$g+@U?S~^O|FmQln{l#R&q#L23Werqa`r?Wn+5Qx@|Q9R(OmP z?k^!6fmQ01>ruDE!+egoaas9W;yu_d_Mt~OGCnTFCkF_4fD90yQRt2!+L$FV(|_cq z^M%;TrJ~lH;)^s3rq}~IW{5mFY~K!f`LweB`+EVwP~(uMzzLHv@p~Wh~Q0=ak-KrIxJ9T;$&NQmnL*gV)P!{PzZgD&i2SK&z*gOsl48 z83L6zysD%Nz{KF=A-bP63!0CQV3b$N9UuB8Dr=NQu{;;pUeND2)KV9!c_`CTYsN;4 zXCPxl+oH*8W7SFILD~oM&B8aNTA@5Cd?~dB+tTke4q9>l!y2yXD)PqVo4Yqsz8v*c zqX^$mXVwee)|a!UF5nHq-N`!7?Cp5lYBbGLKYgr;~V3g&u`9~ zN_>uQvW@n&^!(gWzVs?iTybk~lRlt&Neq!vnE0Oji5CmTEO>l4l z(x&WU3q-6fHa;~aThE!jA+RRj8du?WD|p5ycH;T$pSQfnJfSu$l58E;>aaDnGvHVv z-yDxBl4`>F`5||zMDkp7H6`hl;&m_a0d0wb1#F#Ko@rp2l>fIiu43!t)EGnaw7GN| z1!mcQ9yh}lG{eeY0-cCwY%PE$ril(PGhEClRZkz`UN!41lvYjCdXdzcw`D9|XNrtA zy-Y*zFxujkCq&Z&;WWNj;lbG_=ViI~X%ZVxrV)VCV!j&!5%FgWeArbXe6QRVLCOUc z2CTN&CIdiBA*M;R)BMLh?6oZ5*+A4cKHnO*Z_q$WLzm` zzb&|~R=NEps=$7yEtKR9qQwGkl%8*l7ThTIYakr!a*ic`YBt$~?^dp~(!2lFlJzmh zn#NCkeN!hrFzD7r%JRi(GVT75VC*x$)sqwjfF8+)iQ`PRxy7hK<*XWLS#D}>f4&jj zdm_cc|DCYj|FSXG;B~fu+u^wv!gU1avy;pAU%t!aPfA$rMPuG9XgHZ>w~emltG!d1 zrrPX9J9YHEyC>NjV^{^n7C%e^X6g6IlJOTKNjaf7*e%9{4N$uyazrER(~f(`I@I7b zWtX_O0krJxY#x?=ua{uvILzn^K(Q6X-R|wk{CQhFiRd!$KFp3;-+zyO;A6D%Wm2nu z8r(OfMND9bju1gDf%~9yy;xFq>+$wbB(38ld zt(-SqRy7plqn|hJW)d&m_@#` z&@L$og%1hI+d#}W*7j@!Ka{<*VyQVRvhC88jb@SG8eCCw5$h0FNs6u3V%i zJBQo9Dlbt7SHWs;cI6|+hL;rE0FrMJ#4^~}rLFysY_b>!Ro(U!& zF2fnATob9y8D)GBqCey-6M4{O{j;zLxtT&Vh~oV(ZpeE8r6U-Y>{Q_QD94QZO7%wg zy^fIf7{1$6wEIHc%3l&-Mi!XIAy==!Mh$TsLZ>^XRXM3wr@dwOedOdLTAR+zk-_ai zVXn#Lf%F!gU_v1?xPNB&ae2Jv$~mdZxvuhcwo@UnJZIRTW!*p)=+Od^q-Ws_fH3+< zuq_aY+Z4eE1Ck!gODwB_t%e_u*C0E?WE{gu>OnGaej*-R$TIwijM5MEl&)aIzN;z_N`I6$>=Hk1-;(Jq4_C87g{g5;- zD(rrk5I2(aemEP5jc{gipKxT^*k@y+%fE6Scz`8PvxPn;`Hz$nd zUV%LaNEC_UX_F(Gk`s*t8zDyQt0+3}NX)TussgYF!o_a50po+>DaaNKbJzw4Bo2wfY7LbX+y1Rk2y18> zjtg219%Kx?cm6&uqe$QOgU<@dUk{c^0rN@GS6}mZNi%%wip2L&7IfrMqyEg~0ho?I z><76%r?fSkNtd>xYR-tbz*QuTjrj6v*b{&x$WeG{TaVmSU?zxUL(T@h|MAJ028dei zeeH)HvI(MV8+_!0j^H>4odW^OAk=bN!^&&>alg96N*(enR#}vSY~-_b#)_X` zEH}-@zBM}kB5l-gRFOpv|0^9~j$iwQIX(%ag;EIPA%f|)6lp?X{4>JXlL8Qn62Og+ z#)Gic3{R^KNWnpXUWJR3VIw^d!1Wjzz}p65vYp$~SVoE5E6CW+9u2vzGVUBxDn6{b zpV2;I)r*Zf%hqUPKBH{>hJOYiKE1K6QSc~x0vg~TjkF@kvPMwiQG*3S0CMK?5~w-Q z`0z3<(ApCu#X8t@0BXgL6p%V9|MD)YVI;guk!xmH_Ht-)>~Y6i{*`Z!*Z1E2>*h}5 zoY3$fsoXl7`-|p%epsY|y91)KktZj^GanWO$fjqdr9)HLZggJ zC1nRxzC(JXJN4dS@Qa)PMm;1@prao7ae}#JQbBCp5kI?FYqCURMov|vgf0f3emasK zYTvucpcV*F`}ScL8ob}A)VhdkWIv;^h&tMp7wxG8pAf!zCnctj zG`r9jYFBmk5&bx>SGTx&>l2U$A&NBA%lENlZO0VuO*s@R?nQ;cW&>r(Bjpl}oN zBQWB#xQ3x(CVIFKeXZvIL^=2`iVDJbsUWghp^<|$T0IGPdQn8zyzsKiP3}o<%?mkd zly16Vg-cgijDKwUpNQf2$m4-g&TEZhPZmD$(y!eO$?xYeyJ_Xw_&1kAu7e7^@~RYf zbsJIn29c(rT}>Z5z-J9y1%K6gMZQ-BN>E6Ms&vMnUm(STUJc9N z?F8=E@uUUWcvOmG?c#m;7iAg?XvGNU@X*WJ-ot8mj3aaRdO!SC^^t0C`f zET@C+l%s;Qvx9mPp5AVgQ@|r3s8c;gsUdf%?1cB~tv8k{$j0fB-9E3;A3c*oy*_{L z9=qXd|CEsHl~-+Go3Jq$n!g$X-*s6?uH%OE`Oo&DyVDHrO6S`@J8Y{+67fS7RVOy4 zH8f_>Vq?i-Ms&tv`RKteG#ymUg28 za?mN34ST;%@^fCOd|D#v_RnKI-D;gu0g?;BjkzizSs6mF$F|jJ79ah1In&;jFa6u=LFD_pZx~vCtSneP zckUh=lu%uIm!U%zbbHwpN6&k8I70U>HAKR(l7E=j;s$X%^$}@9Z{*oYr{Pn&!^@jT z>K~R#Be@kzsy1EI{<=Ds5lc&TI*pV(k3@S847`9?4H8lu!ag#PIai3fBJp}WdFKg8}9D0w!_Eh6qDyVJ_B5(?dcIPJhyM4|z(%e|b(_U_deWaEUULcuZ zS&W52We&hd8$3ZZZ6o#%^wwnL2p{EA9(Ina z8)_0&iL}O1O53LDAyop*SW`qhZXt!w-$;s=Qtfo2T6jMwJH-!sF#>v1ZHvK-P186y8(uf^#>M}hVK%c*cU#u1)FO3awd5vaRx+6s zVV=+qj84sE`&mKvPc9qw3ING4}kx&FzmxIiomFaMZkPEtGgrS7is8&1ktx@|S<}P%j2Di*Qi>t$@ zeP&rsnxOipA`lFdE-ZxmJv^r#L4pJ zD(vO{ISGc5wpEGx@~U&)E`J;|Y$34&3g4c`#^_U)k(?3Ji0iJTh#I#&-g9*_3Nl;p zGHmA_<$8Q-W;l?x3;u4RPG_ILR#e}bUQECSP&QSM9MSXHr-yRhrV>16ggoJ%Q`oFX zQ%q6y?`}7rSUm2o_9ZgHJ~NqQ^PziwihGSf@JG=6OT`n~1OW0pVi+=J#>Dcxc$SQq zpM1j0B1K=ZK)q7Q)jAX@4x_R9pK~{%d~&rJUuIXUjps3p&~0VK3J_^M;G9_H5C!Af z;EL9thV?m^*TazR`@c^Q#OG=n3B;Ls-I`yi$xA*JFe!=~&m&fU0V?R#R59=?JfEnCrSdG}zMZCGTYu5!@WGcs%8QQ!(_P4;M!qlRhJx)@#L(=FkE>FlH{dmM|@7A#k`o8}A!*1|mv72Em0)$YY@s0C_t zo`f8-wXw~maND$hqI-k=IZcWU*BP9Bg96veq3J5d1HoZNQz|2t{1kM0A$pWu`0#G&wS~O4Yc-@~B$4Rm?=zjhGs(XT zk|z(7Ur{0{Ta=0D-Tp}>KYl$OM(~&|NR>AJxSMwKi3Abg9nm!?1+e&djwmGny|l@g z#Y{)vbkXz}v{--ZM#KrTdU6>X%!?u@vi~jK1omuV<0g*S{|O35xCjF0^;7=IOzX^O z|BwY5+DWJ_|%<>-i7uI7^TVB|Lwe zuMVfZ1ri&ACW1y`=4ZbmJ*fwqS%YTSjtM9M0BlNttr+4xct^kpgF=zIkH46 ziZcWr{f*Tti=FGynhH>f^8~iIk?Xt74|l*J%STmc|e=>g3*VVi$b6Cw1Ki+ zklLn9_sv!sGTgUfm|F+LqU6R8eN0gcqIwPl49&qgtr;NlkYzb?Rsh&)kZ!649$zX5 z9H4)V$(>r$-Q$(mgZM+EmmVFT-V1VBd!OZ`@zd$Cm9#K**Rm?7x>F0q^8V&V7+fBE zaKpmrz8?tUF=J1LQD8IUjaV~XZ_%Z^fsg+-005Y-NdUYUZ7{sHWnYv`8E<(jRk>9Z zO$ze%W)UG}zT2WE*I_Yy$EVLBlRD4kn~u}f!sdo#C_uss3^E#l)XE@mBamvjgwU^) zjvoczwPK{ShWC2IhgwB2OR*~|AU}l5+azhU!5K|LtH6~3LVYvvH5seb&l~cC7xWhb z{z8Ar_2|(CZ1`JDm)0sS%1p6pkVHA^eJFraj$vC3v@h4WiDcvsgX?<3jmaLz{UEH^ zWBMXjtmvbdIj4-(s@yuq_B%pGgBidn_&ItW^+K5NFPTib5Vs;6Z&Mhr2|Kp1Adh40IR30*OYr@P^^GE{J|>)o}0u7%(eoB(eUB zj@7(Guz6^)2t5pJ3#x6>z6avk!;RuwQhXK-Wa3;Z0T*WPp z%1cj~67`P3C1xXy&t!q$g$(-)WzgwB0TvKRlDFv!x#1rJ!yb$ZKQ-iqgzuM7e=lW- z26g~8DR~pAZv^O1O6fp?dL4!e8RtyYr6zYNit|3SI+yUb0tO=6Sl659W$pUI=NiB) z4U!X+D@78(K9h;H^xmQg$Cak_<#WRDnSv{XFbrAN{QOs@S)H#{e?1G~j8&>4_Lw!- zAwr(c@A;Z957!m>9T}_W0Bth~s}umX91eV>|KdrijqIYCuexoZEnwW6Dq7esA?3Mr zyMtCZEM1P7Vz2f2rKN?jsr0p7T(gzUKF*Rgm)EqT9f?z*v6I>mkl)3gO`fj7&1Tro zA(`xE_0oYtS=1%Wy6@T%{d8$M?Mgxd0J?ea{&4LM6!XCH_rU9Lm)s<}evf(JQ&0*a z|LXq95S^CwvNF^8fy}l8<|t$f2q`^{FLBE!aYaOcPmqLdn?8DCzDEAOrX9W(e|+_x z5~@@AS^7iI4#*tEe7}Ypu=&3%uTzw4e<@Ai(p(9=nVh4A`HbrNFztA>qwq__f-3!k zYCD1&{sc9P1xv$M^T12?;JLd`R#M7hA! zv_OU(k69GnO-Ja%pHQGU3M&AG*BSb0lW4L8g+q;>wL?aZdD=ldf`ra=_^)JpEq?W~ zA@*J&e2oBu(UAxjexUv@|3K-0ufN~(T>c3&?ToUxL6I#--Tm3F0zyrep)HC8HK_1; ze`iV2h|n9axTl6EaFOwxKb?C5J68)5LrJU0jz~{FX_yHFbP&EbY){Sl7V$7yv)VDj_&WIZQm3 z&nR{yJE>;}S9>O9k^1Xdhd_b&8$=iC$4#78*po9%_!^FX^EH{T(+evwMeeUNG}nk% z4x`?S(&Y*;K1nmBL2;}^4Woo0a+r6vMz!q?wjL1r z>`5;A;ZNo>@ny%Atm%PJU(=U;Id6Qf6T+Unj}FWqWXS~EWM+0{=Kc+9M>^4#qFnyo zl$quQcBX?(U0-!(zcSA6>M9Bx&If`EhM%N;G!08VqMli?2Zlib0eQpA*(}(JLVjLs zZxZ>Yix8^5-7r;QkvB~gWK$ltRj}% zO0Z2?&!BN!dueiDd3sklj<{?=STa^XMQ~J!R(GNQ-@-NjN-~Lj8?999?pli%W$i%s zXU3Tu)YYb@)nLrmUdlv&Q>|uJ6O)%vo148wld=;Spt4fC*!}puA^ARr7er9C%vYfW z%;3VSZ;PqxfH&I}gVEp|=!ezvxS;wZ+KB1f8aAPZuR+b#Ws?V+{|(WX(reN*1Du=9 zT-qNULOMGLr0!bfB-@mN+thm6wCLJMZrbFYx$B0t%?Fm~&=D?_fVsI_Md+$jkKUW| zbod6ByY_Ub@U++;wnyhQCrLKt&?0mJjB`0~&ehs|?(WLq?mlPIfu#DHLm1>1R@2kd zch@s0**hBC+wiuLeibKKvafC^qFGLY?^!eUVMkbgsW=^>;oXOG$$kaN_EX7a<-7K- z%@20@?^)D8{0J^3xF0}h48F?mppoiiO6a6`*2fjnn|246FJZ_@{oqFX4vjEqzP)VBC}5M&M?nbZ?YgLFm(o z>btMdk{#luzhOpF0d={RB&#VIK@X2Y#*%s_eg2CK`T%hsnUz98;}Q2^G4%LnHDv$3 zLg|wUvI-_}?n;WKYE#W7p9R%6+<(yk6{F>+KANXhccL^nXln*Sd*B*^rqTHY;)ClG z(6uIoK(6UKIdY2W%%{_T!>8{;P%*tD_hR9L$aIp2&w3J*o?KskN;MO|AZx;CgQZmR zR?mZ@1p$0`R52ja!J%&R*sjB*+7mmLqACA%elwOT8Sy<6MEdO|du-$}L_pR1Fto~$P zYk!s7#eix?EqwV)fC*!C!{5Y7%l_zHn4oR`%76&pWI~ZHZ83b`lYVs2_xI{>Mn36A|%p8 z7+;8eU(o5>)T*t0zYn($qi1FaHF>`G>(ACl=502{y1!-wEs>v1pZs_g^5fO_Sxc#F z#iCt2dCD(?I1-(csYUsjjJ!D?zBhNL>Bw2g^kvq5-@_{UfyVpS^pgjHjij6@jUIY^ zyz_AIv2z&X6rT2l+H^79BiGaa{z_t)+>*GSIQs3wI*s%<8uZ~J z10;d&y21RqHvHQ2Rl&3s<~;Se@4gH~@94<(>oZ*uKZlGK-7GHORD=Es73TI0*muy9 zd#qm872ncr+(v~CwOfvLS#tOGPjk>Lw?bgHUH9ev%hekLl$KxgzEuK2sDZHmB?aju zLU0AjFr*-lS#PXB`B)OYq%!Mya^%NY5%j-BM~~`3)g*?K5^K=^l7jZRl6E;Bf9I=- zsdXQ;_oU*}<0)|o^xm51&T<(h>Q_Incg|#9N@R1feZVKFP;IjPlqa1a+OXR0Dj9FL z=IgQ+&S%Nomq2y;MexP-_1kAXnljeTpne4dAipaX%1Of942$|4Vu)+Jg$xr8@NDYASK(Z8&-tmUu%cEC{Z zH>xk<*u&YGO+i7?7Liy*KxN$^*qni8G5OvLEi(26go(8M6-x@8x~Q!ZQxT_ys_LT& z+jMQSOlA|F=PFijR+MHfbgc>o4K#HzQ;i(PU)osY<;;B94V~Vavf8~gv!6=`DRDUz z`hEY)T4<^@VVYpGKgs}?OWndE3m#oim7Oy=chIzBY};2)4HD+6bjNpKc%TZMH z8vpI9LhaEX_OC_r$jEWAu~e=28So9b9x}qYHIr!#om9Hq+IZe&H;VjB)qF$i+&sp3 zN8QYm8NX87zBDpQEr^aMQF5^mw2l&f5dMAKfOYkjq|@*LpSQ~itH-HGo%xen&&m7B zW7R2{{o_^vPZArZU{^J=`ohbd#DMmowVbXWw62IDJcq-gAt+vtZSSeJrst@2!?QfK z?dOK4t@^fH3$7xALF%%_%Nl1$I?FwNQ=Vs+EyjGoIgRP0&l0`AJlU9=kh56mty)Z{Ut9@JY3a}kDpzI%5 zuE#0X@O>e1REp%A?=!xNb&sG?t}zQVVZf-ROAzUIQjQYWHTLjjaKYuMq zKMkKJin%UsH--o3-wh`wVaeLvUtb$kd;ZWxJcoaf3*(4-F2%;JMUnoLDEH9yFp0}C zU-B}rFd|z!);9XqhB5dH9Zw8&nAOUi?B924#tvoKEw@M zR!BXYdKbMngCEb^r!jvS@o_i9a(d@_{pq(?T@Ot6vN2Y_6o2p(1Bu16L9|@HK&el+ zfJLm<2gJ+zm5KhWQqd|l>|jE3YII1o>>Jc$A6(v2yuxy1e1$t7ac{!5$ztdF@h&xc z>&AmynjAq&-i%s1&$~mx1%W5P><}Az-iyO@CVXLq%BH(5Tv0)OB zA0e$JNs8oUmB)6X$0izo)a7L9y7}~@qw1sNo3$6zuSP~|Z1vN#r=CqaFR?1pdSyhB zR{|&|%D5Y_@kt0KAq|R>>$>_0DXY7k5^?O$S_ra>)}F)FY}NJg$>IiWap~r_m2>J3 zT^n0S1K)~iREMQx_vG(0&Eia2XL{zWAKS~v|K&H-k4p`RW8Qfy!p^H(&J^BM+Q4n9 z;cR>n+#P8uZO5(?cJHOQd08bJ_f<#WL;%4z@|6BZ0Jh<`SQ?RdcBXe~BC%gSXRjnK zi=yLZt+COU&fCZ7+}`1Ar@iltbybyRb!T<&ex4WIWE?17boD14lPS`DuF>-Mn|()5 z##av|pFL)aeXY3zubX$+bQ)z68U~TTTy@eCJ(=k ziHwUH?$n?5O1?FuveFXFW3nDy*A)HBmH8vJ`a+&xC(65C#%PV#2%k?>$(w^LrAl~} z_No+Zcf}VH0F{adJNpR~b6}&KbFcDW_D6j?KFmrl-kZXm zSpIf;*wMKaHO@9}o$S(P9lP_8tAV*ALu!P-PZO57yIMC`ZtOoq{{Ed`)Ypv%=NyX& z#Sv+0Pl#Ek0yZe=v4VsLuG1?Of-F0JO=oX9gM7fP)f26{y%o zg2^V-GqEVaPM%S}*Lm#ZbMu>*Av?mSzth(W@#)5z3E>=JRDOVP`k`iMSR{(!Jsb@p z^-CqnOo20WAwkRsdU#=-a!h&rL)>Snk+U8vpDI42)3TK$%M(DT`Z$}5IJ{7d2ZO|~ zb4n=Ol8(%eg1+{iw7>IZz}BsAEfjp@Tv!WTmD~x8p~BX{9TLEK0qBCqbbbT@nxaG3 zk#O}J6&S!O&QBEyZ@7s@`fMeHncGm7eQ~edcq!rkED{^-F^n|#ObXXULGDF|WWCP9 zBtuGokjI^a#Ba_bc|x}E#ell3E6K4MA=~8dI!7O4YVd!C$sG^GY0bCKQxZaUSs!;z zw3kE^@fU0YnQkWkLke>A?g_r@`b?#Lk&ht-pKNqZ+kC$$rjo*u+Q)r_#;oc%(M6IT z!D4Zj5%_pk0Lt&3evi!fVE-uq1Nc?gu?6E_Qrm9aKZ@(!O7hdGP5pjNiTeS{93MJv zagxy)@$K}@pWdTary-|38>hOsNC2}J?c?4pVp&gn%`#Z1d+!d@{~-mF|4zBQz9{gQ zVvBDi`OkE?TJbgVg)WgX0W042@<*8uVc;-G1SR;%kZd9V5W@Nbo~0Wjw=MHWulm)^ z0QqZq-3I5dCbNxu_OO27Bac!I*)4YJFhW-=T&gCkyYMSst}UK zD2D%bog{Dm({;iJ0GO=^hLAxZIlMzF00;rRK;Z&Be8Hu@=0AL`IQ%wjL)c=YW@oLh zn{bukFIfHT)hToY#}SWBY$mE)9b>h`#z`=(ZTB3=atgFm88n6@U_!#OQ;5KD7^d#j zL*=G3h`)~wI1q)64Y(Nx_?eE!3j0RkdE)JP5QCJh9F-$P0^%OsI8z{^ZA`3DkRXOq zAHq&TBtN(sH&V$8P26e)QB8rKBEbNDr_5;FixekJL-%hAo)R3tWXUZFH&LfOHdx=v zttGC&F*-{zn&c|Z&N0HF)W;JR;*|{s3E+%k2t$4XFgr}wp4iUVZp#CMZ`t)zC;k}M zN$!j;#I^jmtdB7Vb7R#`R86L-We#GKAFRy*GvODViI1<6$EZ`(7F}60l5qm1h8-y$ zZYYkI-~3)qnK+0$!%cA-jSjDPgIk+w-<(YFQw^4@acPo_Nt?2&!D1_uX}VH*aw!;0 z6Cqq_BwH!mEU9F<(az(EkrCGT6KT@5l#iU^$W2qlbJK-5Gx#SQB!8xBOwb^oq-PnV zci5#}D55hI0@F(ZQb#|gYffbH)uwS@rhWI$cww5U`XrOZ({ivq(_$ivWh+C^lwV-w znT=YOvT2rYSG4*{R`5is<%FV#TDsR?m`<)_IG3eETowv1^V%^b?@|4Rz06^uF+eEcsd_-Ufx^Uwc~g0ozO^J;~QPK7g1!dZC&77BYr z@+wU8p&6Mh`lR!*ML%ncjwXtJ{VY1gD?aBczECT^aw`54SNylO_->;3;U~HnjaTCR zv`E();Ce>vngY&90gDX$KT?o{yOd15lpwDJYF0|~wv>*xlxnh+3BQc&uoR(Q#wJn5 z7GFjeRK_(~M&4bzOIz+AU(NrvIykTF)nPR!eoYu{Swvo$OVCSppDJC!Dy@~8 z{N@@1lG<^BS~b$#SAn&*dbL@%H2IULl-io)1Re5M+4gTY|c_#JTBxT$Q zjkhE%5_P%URquo93f1dI6o6$&pw?Vn|0L@me*FhCOx;wd48Lx&yN-CUzSFtt^D3=?yJ38lW_6NgleTgFwqe(~;YWPq&$o?7la0R)8&C1yopZmt=uX9N z!r##)-X6dU!379Iqze;35us5aFbU3z2j*qCt{7zS?YsNK zcL1Iyh)WZ0T@xk?w`N6rgbD|2CK=c_|H*rI#|@*SYXbAYu!5WLBw=drZMCj#^{QH2 zJe&FIn$fhaSOS0n4Csaf5I=)nHW4+Z)Bs@3WY5seGM`##?poy6njv~^Dm*az66gMWs;3796e*7F6_D(rVoi1zd z-Jt+XywW$gBe19A)m;am$ua5LF_k@`EZC_dhw@EucWO^}h6XH`zjLA*uns4%N8%in z1Oco%W9vE->nMAnU9~)2_0PIMh+cCjAOi;VI0MHciL-S(WAZx_5-_8(X&*4{&p~Jx z0HAP2tjceHgv7(%f?&Fby($D|f6z^Ung6s2y8#3)r5}!uKAiFNbE)=UC-loH6MI|1 zwnW|jX~a6|4S;4poYM7QJnP5u?Ejnpat#~s?fNCDrW-{fB^3dHCUJmX3TBTY5-REQ zX(G0A#5?16L(>g_>nXXXhUn@C7%&w49upb^!EE3Q=ej>6E$WIh_Zn=NdDku>^oWwI8={inWFrJ_Z zOS&Hic;K2Jpa~C3pv?D?m{sf9o(X&1ahBr=K*>0UaoxH8?}GM^ND~}@-oa!9!KcE+ z@iu}cVwhvGnByp%LpRMaEzdpXgXN)!H;_0l;RGA}Xg69; z*!!4ZX~H??qALdQ_78NWO+L}ImDhO%QU0Ay( zP7Iz0m(EKiQOYDO%6(o`lx}tZ^*Jw#cqaJklfL=!GQ6DuYHLyZ&1D+FGh+7{nrX_H zR#Vgsx&)vpa3pud98flFHJ zV}+Dw4eMK48{m+Qzb{7sDUhQ9Jn;EO+$-L?nc0_NA$9wo@<||Qm~(-rPvu9N?`QZu zO++gtJvk)fL-e1D3qxdKpTTkj%`=oWgaGdW;+b2qAMg*LK|D@P5bORjR&!)eHQ`-T z#9c{5Is8ku`DdrF9dPr`+|~|Uy*%in$;t0^x4NK-1X|h zO@Ie*Wpl-TgeZ$2mJcJsMnIOO{VsKzk$@QE6KvM^A0>M!Tc00wJco4=^+Du-y^Vt~ zdfRTsSdc*MsP+-a`lz$<=yv}&X#Cx4+}L06Sk4g2u{XcQwPBM)03kq(+8J@qCK!Mm zwlcvxJF6T1GP3mgc=b!?F;UDZ<0$|IIo!m@3OkKj9?_V?Kcs2Fu(R7|OE1q4+^Bx$ z3qW`IOYA&Rcn4eg|IS^MIQot4_yS73E|&F|A}>=h+JK8k7n>ep17W8 zV1Fc0FC619;<=!}Zky0!Ks4;xeDo2%k`>;59hy>5=R!33LSp(th8Tc+e5vSu37Um| z+r(DegnoxRb-EWIUb0rj*B`_;1@yF;TA!gC z4qJWJtCiLJsqRwq^wP=m+DY~*)cp#pv=3SYtriDc1>9)$A8Rm!l?MJ6PX8s-1aGB4 zb=9|O?Y9aL&>yg~{L~0Z>H`_v&O|*T5_i0V0h*A1dzBxy`5ICDUk;OIp=&U3BrB*% zm*{UdK3U>_vBH#lkQ})GzgS_{%qSLOeUPu&zK3!&^nUy79?*3End#rG?89Q{LyHOY zWB~I)3~|!gr8H1}Prjd=zW+juzMa!~SdxW(%}H9rg#jQET=v9;>|y^y3T_QYGFxTV zakynd!g9WB@%T4y^~>XV-j{WpEQUvVwtOS|h`Ws;1%av+jwCFABzkE<2$$}HYzcCr z(tJgKU#~(fle>~cJ3G8m&*phL+suGmttk^xN|bi2aTBo;DZ!k?Tz`Awr#U`nUdMMYtxF%C={D|E$Pu`B zoK8az5bkO%ulU-DhUR69g}wowKM`tn$NoR0;6FrpiClywxBsbG{_pd!ZcX>Q5C*s7 z^QyE9$G46gOWQN2lpl=MJ~CQIFKZ6oxJ}6Qhi-eg{|_k$Qy}+LB-If9f21JgGoSw< z1(j)C+Rl~fy%#)H7=tg*Rp1fiUaHIq!oO8n(+$1U*zAh+op%+6Hqy?!e2rAM=dhZ|tBGQ|JAc&wyPM-IjGqcW|wPxI`%$Vxt=^7B6>=u z2c|uDtH(NYEjwgMTr9Ug74I=gfwgKfaJ%FhKq<^;-R4LZi(1OjNc2UzHqxY>L7!_G zvMMMQE;k$MoECy!h?5QF}z3dB3b}mfotk?$)b3zeK&`~pM4YW0wvnXK`iQS0NBW380;4YWjn}7 z<#4ZtPr(s#4ByQ0CDm39XG+V_6#nI$amt5ED+H-;9N1b4MmuDna#+Maq+n#t%|!~Q zRHG%GhHO5%t6RK`MXA9FI?wNlGK7sJ0L@;$3s(I0%Do(x$(Mz3nd!gZ_&2y8*0IhR zISbsReI~=*m+|m5c=<+}n{`5r!{XW2Ob3a*&3Bf`(4{;$K?V}C-}fj)NY)Ggkj{VoH^cBR87@3K zyEy#^EhOuOWVev?FVc|o^C#)}`0vl3CnqNtM@Oe*uJCy6AH48C=)%o^=)(Pd(*ESZ z!NH%st?%TuzyEi4=VEK?bZhJH#>V%r>wmXLNE?lNdwaXPyW88_{|Oi#k?q2N>4g_x zhR)|ck^@IbA0Peydf~^9A7^K0KYaM`cY6Aad`wP~rV@TnjQtrMy%-oc>+kw-)`Y)b=E}<|3wx3-*Sqn=MTtY;Tf^yJU90uEsd1J`y(Th>=Pa) zB~KDkE~27Hq522d=*{4u-}gN)oQ%HSbFHbVdH(!)Wo2b~dHH|xhDAk1|A`r9WMn*g z^e8bgF)l8SEE&ec#9*;lGGG`L6-9;$LqbA=f`a_~{Cs?TJUu<#-QDlqyXWHK;^^pj z=gu9nQh0pp*10A6#6T!Kw8*BkEJ;-0Umzj(9vLL$MUu!MAtyK4 zB)ni{x?rLwn}oOR>}+goEG;dqO--*~zi#~h3WwTSS|}7sLqkJdU7d^^Dl04h4{qVV z(L#QHek2mf%gf8d!^6$Z&BevV$;rva#>T?J!pzLf#Kc6V3;%z&kdl&;L;)cIfg}K6 z9}I@W;V|+d_n<+c6ciK?2m}lUgFql45D55hfFYF&VN*9X{(lAxAz=cv;QtXYbgnr2 z-vC3$>HiKGf_%>HaFqRqS<1gJ)Y<30V=`jt9~)QOkO4zJUhNanv+q-!{{V*OTKNAN zFbwFHGVexx<{^I$bWWj@mN;e_RHgfEPcgoEzFHU(hsm(B(d2SW| z0EP|C!tem>@@7Hc?6XY}=WN5+G5icG)sf)0T}sdu-$5k~ zZ4?E8Cr~{V1;PIShH>H^RXRlTo~o*f=i*iJG|OBiQB)+As_MW)%EvX{E8&?XnLL*6 zkCOpM`n5eQ_a#H#cLj+BJn14v7f$HDsDR0YBKO`-dH}!-@@e&VpvbA!Vnb*~epV-}H2*~x^+O5PF4<=h zlI<3B7;5S0xfh3hTx)0{#ZZ3SaU07Mfiny!K_ka!ia$o%i3LK;0`d^ZLW4t(q;Q zo(SVkUir2UE3))ThrKVZH~xXCYdkxV9J3KPIo-O$`WN69W1_m38^;9!(NZmHQ{Fydk8Q_+;?*_XK?xYSJb$9tn?T{=EzW5Id9D zZ6@`UaNG+31b`y+Fd0Kr%GST#3lJ=WOjWJYEG?sqw%6F*+_Y749aH#6_;@oAaEY?X zINrcj9!+U|!Tsn&kp_X-&eG0n%F#Gkw^cB&bf0WBJUV8s?wT^XSXgGB8#!x~Fp&r- z?IQG8Jh2cZawVup%k+L96^sU$VR`Nu4BIaJ$Z0Al2Qka4MvJET(W>EmtbmW`;V$g3 zHlRj}5aAx73pr)hi>ip$A1eIEGSok#@gKZcH;ey*Hl&Yg>MlMfs22-9DPsfD=ob7a zJQy($XGJDPGCL-1>&GkVuaJOv<7GKCxw5jm41{5ca2{za&?Rp;PQ~&uRcaNQR$4Xo zH3Jmd1W_}s1AtSUI2ocSWND=1AGWQPeV>b$p}|hwWW#XhB#4T?EHO*x=m3to#mmS> zn}g>9pHlrqF`$+K^oSXtzR7co$NvC^KcAUh-Zd{Z{P5g1`eSx9< zYMs3cVZ#5cHszMEElmPnpOVNPodih-^3{ee{Cr8t;KaVvNgqsu0OTcTvkRNk4RNF6 zOgqusEUGa1o@Iy#N|RdHXnx4{O&FsEkQ?<%lH*-VD3s|%}+@eXKdV6$&>#A41cxE zjlK+SBm;)wzgo#IeF%>4kzT^Dw(UJB;YCBmAl)IS4kY;YmeHNyW>ygd0K}mmofg4} zPt{N!&`@WZh-Nt^Qc^sRVI5h9>eaJ9tJ~I)4yO$Eohg;C+0lmS$!sMha`i8Zu*`|@Y6O`&*-YqcfoG+Uoy`(d)fH%R!1089mXKP_m{DzN=$J3$3K zzB{}g+I0yqs*KdUcJN5K1CrzGsH5PE04su~yV}`{sc4O8d{Iwf9tS;KH2jni_F5!( zsdCx6Xl2}Wc|pcAwq=nXK0Mo8Wj^mhnUdU9gxnBd;7L`U0jWBQZi?{q- zXDB`Lv^snKZ6 zRpGnleG7(T1QdwB&3tC?e5aRhb@s98Nm}%0;p>e?GhbzcL}WMvc{Oe?ZkQGTzQypQ zDJ#BB^!7^9GtBBZ(3*!8`@erLv=?+s)nVcGi{|fw>vGYN>*;Iwu!(MXxLz0{^+Ghb zCG&uIrDf%4W4|n~S~&&wmjL%27gDE zmel&U&_85vnS${QUUTo$zQ5u9TMGA;IorMXO;Cw2iPT_S9@aUvu!|yX)&_i!RDCFV zo0seR`?7UMN7CQhQ`bzIzU16d+&?y+ZaN$^IRBYQniF*O-)dBUU8(eSONcN_{Tup_ zMpWp>FT?UJ^|t}4zbX}#DJAus@90*Zu)W1EXs`51S22+L`N zsQrrcX_AV{3=BL?3~`L71R4Rcz>3hMs@$aKO-U7Qx|Dpl6ISDHOXL15<6(Kkmv!yL20Nak$Up1MxADV;tEC6N}qS+RG0KjDmKw%v%KpL>Te4pTk>&}h*yZy+e z$rH#38WHgt(Z^1>Vkh8YEFGeDm{i0W%N(1=f@m5`So&xEv|6_`^H2{l`Fj8)1cnF-$uU#MpXy+rdPQzioP*CQFf6c{Nw6XpoJ233SzjTwWh3!e%Vv8L-b zvoN_M$_A2*=d&ueli-~+&z6n2+3)ePt7%O*${f;E5~+rlnL6jBZ;If97yv-gL~+Kf zBe|^GjL?8fKt1-yI_X)VOwm3ickTP)5$ow-^J{m5@3}YJgGN(sVCk{|Iq6LS8U{fV zE1-#-nB=@1%CnSXe?SxBj(=XBrsiXa=0iOOk5VfSddNKh)+4Umqk7Y$&I%#oOJ5I9 zNo3FSj?W2<4*Jmntehl&=kvv#gNc*0(AqbsKt7q6&?V;y)TZxG^q^+7KmFvOL5 z_$)M_G5^j~zHd5~TC`x%ooQ~~H<&VLfFu_5${=xbrywsKq7e_DZdRLiFFe#M5J`~v ze5+Xgu&{`db%~YLasC>)2-r-?N{(nbUZ%z#6mwOD?bH)8EZ|1>iV;HsKMb&aVSa0a z!5aoSZ=U6bu7ElbUW(5UTlI;@U7+`56dF+??twUEFY*W}Nq$_i{jB7!9D6?6_auw@l}Q^sXjYGTW!+7THoT^?ppE@*g#lZZ6zC>P%?@9Dg9!Cx_`DJ{2C z<_xd8uSxt-2lVFP_H7BX5f?ilIae|yRe~lZ$73#Msff%tUCw^;?Ecfsi>sGo#B*E? zSp|KmkC)}*cb`#(yCidnIbnt9m#a=FpZ%&5dtvdSfl9pGU%av9MdN~am3V$?JW)xe z{Ki3m*+FFqRhCst&I>9rxNlw>=*4HT7a()tC*d`2AQAtVn#C5)_u)lyLqS0$00;+- zZs7BQ-MFM7nfGEf)4xl#-IR-Wi;p0$JVCr#ttrIMNDowoJ=V_6sXrTsHdcU+qqD1i<(sp_5Afgg-S%+_xaLYy;tcmc&qzaHuvlG zsGrNXmIN{YYz}grB5Dz$uU!AgNpAVyzn|(g{K~+nHZWkdF{W(A5y3>Ihg0iLE$;Q%onXEwHKW^`8d(aP!Vr7K#oSuLmJyxINYaTi)T# z#3^qlZOwvd4@hXQS8bJ1Z8{-Kn?zX7R%5Esd*MIy=mT~pGsGufsy-~;EP=90wVj|9 zmAmua0Nw$X?9eyrSVps2`sVbNl)?|SP5G!O{OEt7s9Xt@CuWpwx7xn_BJxznAl16~ zB~vD;3FG&fxQVclMlUh09u=Dg`fuzE#)#iYT5vkmd;K;J8nK1uZnczd+Ja^pt}ff* zHo&@8*Tx6m3g_RAxHc;y^ zyoK$>z6bbHS&%$?9ZMU6&mV-+Gk0Y-rY5zIuY-2=KlBzSMLcl6uHn(^4&eP(U~3=&Q~+d2juZMFC# zw;?f(Z$z6Mqs<|J=hAdOSm<=!KuFaX&F6_R&avf176a+gW9*xc##5hM8`4!3y`NFn zicjK5zg%8ef_@_?L7k5GC-BI^K7QJF*)*+WEiwetcZ8_l@f)L%$e_$Hwiwn zyspy`58|UMKwXsaD#Gv-US<@4dU}Rycd}?JOpBP*925d}G#=_GaKa zE1i=Gjp>&+Og=nrwT@CiWfJHi=Cl>QHrGpRcHYjVe4b1DJ4fLDH(=<1?SSbT)2Eot z7nsa{4QlC=RMbP%MZF8u%DVIC!yTN%T)Yi!ZtO+X@U%}?`w{`~Iz^Xl<5wdWF*-$b4<{iNaW z3GK|2?M26PbJ6zMQEq{~7(VSsyK8^3GXg`O{?; zslv_}?YC6de4+8aRQ{&%V&xEqkp{l2EGB z1gg&%`ZWR-J3qpGndVy^-3VDMWPnXC(`{pDl%)~g7}~RC+8h9r*e9;Eg4N8EQ6aU} znP)4UFWaw158??OS}7}!zOuLj=;lzW4j7t%1F+8o?I9e%OQfqoLhLa#n*(62R5p7qg$C6z$$chEB1|I`SpH&DB!Ve}Kr1fy^}R6NxFEt| znJh8WFA_`u6VR;=a&eRP{WNWnG{XOY-cbdS@PYaFHL?Cr-+z)me9KbXrF^p2`?2W4 z%kAl>17)9;Piethfcwl>Kr?kTBPGC@11k4_3{YA@Iq+u;mFom_VuI$S(+|r*)LS85C518+IQcUEuUb}JtK0HtW!bu(U!6f>N4*F0KXljDyGmdf# zDUATohsjfYK>UgT0*G(Gc@5r~WH(;!OJ9%6Q;be3D1M>w5)3H317Jz>f*k z)Tw)g^hKI?n2-|`)n6z+plBRAq^1G1f8`PR7`mozz<1xF%8A(YC#Mwz+8*z3aGA{s z;GJ2$Gt+x#Zt-W{4^AQ%`(f{y)QB*fi8b-RC;9K)o{@@~-U))Hv9uZ(9XYIswlDp2 z6vQ4y^KIg?&oX@p0^(Xnvx1V%@TSrxQa;{4t)6}`S5w$9)WpB7^6Zs z@9cIM1BW=k`+{31sT5h@_HE{>owHfS+mLMnt;}|xZM#nnISP@@^4nap3ic<5rq!Np zgV*QwSk7O9HqDg0x{zBR`LDl|^gH>P&nm6mj$>fiKhqj7)ID|yLVGr0TnaUWhRY*v z1$5o&0C_>VZI9iiq~yTuf2`&24pzfjAJlNjlfGqI9iu6A>8V`i^WBT$K@L zULVb4!VhM%gPy+97kE@a z-O{PgWzzeqfQD*FG~k<&A@1n}E(y)WG&oeyrsk$62t4o`NtT_U$Q2rKd1InD9GE=# zp{hD#tfeE6@_KfgC6QkJ_JCI-Y;R^v=O^g`IAo&y*=3sn!{R7!VW4WCb@}QufqFA8 z+IPm|nQiNu^pZUSwZq0hwYLH?>D7T2xE_G+W0-yU+u04}8 zTSg3bEk7Bs0yh~vzxP^S3B#@CsQO($57F@-rac{up`}`;QqP$CArnkrf77j)B1C?U3=$P$^Foof!ut!qMyYik)tYQNGn zl?D%doF5kk_Qj4<8j0(&#T9utUXQYS{-yfe8pHY<^N_EvHlhT-*m3df?8{Kx2B}?e z;fw4*`mJHFq)0MMpj?$EN4!1U!o&Whr^wO(5>ksMXnXU zxyAIGkR9iO%Fm$w>kon!cu8#^-;;>FFM%P_EX><{DXHa;LYr-ubH#1S;ALVoOnArM zu9zovcYWQGN*AHm;nyDHljtc36zUx2ikxXR366$*FP?76=mKyIGWe%dkKvE0ZDH~I z3w-o%L>WOCO?tJ7PPJ`w^-ZtzI|h-n%vU#KZEhlyd_0Re)-1cfyPL;{EPmJ-3xZL| zk0fwa({Q*8_eU}STwSov{Oa{x$(AyA^#u8m^dbhyf}W0?h&b;Hw?6F^+Hkq`1-{*K zeT&Wbbf%{QLe2eybk8&RB{H$d?et{0Zbr5Sli(&i@5&oudDi>LaWRS2fzp*%c0pw*y$&QmU*y^g~vt%-EPZ7 ziyjMt-z8qDzM7K%OE6VhOlzbGedEbSq#%mvwY(Sr$ieeqKYY2oEh~yQN{7~&j`NF~C*^Tp{OV2%T>c>=(Gwdg|Brn?Z-?URbtq+GkaHa6H`<;aL zT@B3eef!ibSvccEGa!@nWQNE+*mbRLOzuuySL`&Xb)HBwOZH0(oLH0Ruo)+Yw?L>f zw=nCF3#M|NpNrtBdbP3HS^1ox+m1r5pIn|;mGUusDdwq5c71JC|5E5VO@Q8&i22!O z16lD)A3bdRexEe9_hwuIp`OFH$7@m-zs9R2lc!3=!Q(nU`hC=Zi8P7lSKsd2De(g} z-eCa{F7!babwgH#Op978yEG#2HptH9-JZ_p5GJlK6TuLyH3F+*a<4xOn;m8jo$LEOc)%W%-~Wpzr*r@F z0FD9)eKOP3tM-6Y;~(^Rlv63pSJs<4=0nWKwuWE<%cbP(7b&t7SYH?bGl8hA-jMXk zdL20`)9$^s&iQeK>4R_lO*{tShTPzNG3T0)e!fPLul!1rV@{^d>nKvDlJyq}eS_?va5)(MVIbf1 zzqj&%vBoIK7vV0A7&92Xa>wG9Zb-|AcmDzmH%|b~U(|iVKSq2$lxlqU^WFD|;ruV8 z3#Imd0K*9C$R)0W*WgGF>X?t8mTBWd-yd=N1+Ni5u-W>=%OZJ&&~^)>QVGBe23nj8 zKOK1t>MEfG@eg2_TlK#IhFfR6#}hCVQY$6l-+uU>F=|fa|R(O8JjTi0%8e3cB2nVrW)IW#)YHbJB1}BRwJoyoU zx!io)?nQYFm%7aW?1F*3hnx4Yq%U&Qh|ERv5a*7SgK_kQuHDwblWO<*q#No&Kh1gq zo{8!q*t+5#W|jPCU5b27Iw#%#t|$n+ts5j+rSf~|G0$k_)-9&B{@bM@6XaNV?z1fo7oQ;hEi3=_IFYaAZ+ro zvRxn=LH<)khFk!ifFtRP;*<$cKL9WVd^Iwi#p9WlM1l5QP87Xh_d!I*iV^(Ar)U6y zQzoE80FP2-qKH%eM;*MHrBPJE%HG!fxJB#WsQcPT&#*+o7!#kCgs=&OQ|`P$-X*~U zNughWRGf<4f8LYSf|laaK&zognb4pn3OR=66Tl-v(If-PV4^%@%DeOZ?oef8eiAgVQ(QDo=z|Bnb|fztQ&}dI}T3_BBzA zQuSsBCf*eoWE;x8eV~^mDU|KmM|2s?S=3>U0CEqAYXS|T(dFs*E=nqC=i@;%Xefqx z$fSNS83K@uuCpOW>j(~A!q>1p>3Jqt{+w&5I?y1_xN12(TAG-CY&TSg?s_3t?mNP2 zRc7!8&tKm&^uk`Kp}xF^h6uKi(Y80LK-a&*^Fj2Pt}GiV{}}F|8N7C5WO)aB7#8hT z(AQID1P?Tf!t-q;k0?Dct~)mlY#UiJLP)ShFAmhcHy$>1GG+@`6fLAHDy~EZAP2A*qN-o7H1^n^P^2V)@v8=B?_w7DGkRRJjd^zk7@B$xk=Wa z)tlN=jkj`**W~de4vnA9k3Tsdk7XVKKL_^?;JC1(@S5JAuZ+$IS_I|`pxMQ+?1>?+ zHy-tUj6ldI0%%p<^qb%W>znaEBODCxco;vM(cT>Wsm4&=4Q6->6JDNVD&!VQ=5IfX z9jiC*?40EOVE(0Syd8_p%>{w9MnFHuVxO3^IlUJ8Ss)y1A(?8AjLA@ zSemgANafd7Hn?)vVyD_@H_Jr!=D5h+WY7V>s=gr;h2lcs4bfd8h3x6^k{j^)Y011q3{afKjD_EhTYr?98kXv=MA1Y5kNC=jO)cE!X8VW4u-3BYZpEVHZW9~f`1P3fT$Kn{2;(kzS(l~<>1ZRpKlI-`#^+W z(n1J$@z350ECO>U(r-hR*^=-H_(%)@pbt(G!#xCm0LYlATsgcn1<6Y~!O14>mdQ-= z{NPczHQL0?-gZXj-3{Gx%O(N`#9K-xNFBsI*oJwBY5{CwBXZ*uCz4!66TA-~I0Eh=u^s2DQRcf~ zmNZ@UGxyos1<-u0I)wwb=1t3$C2$lI~fOC6}&ZvoL#fMuyFs8b#JkqdQOR>aLg0y<2fq4DHP zDYLc4NaJP|Vm+(ol5c)Y*~ks{`to^Yd3{k^t!5@&XugFQ)1M6!p1X5#)BZ%oDwE9y z+!x17Xy4|Ji7=z!Uj{j0{skD;#knbi<#VC;5Z0m6v3wJdK$9;PEuZPzbASC@c)sDl zcrW?;!1Hqt$Kfc)jgiD?1**q4r~nu$QYDrOM+7?i!UEhVo?eF6EK}Y3jQQzsCo#+E zGp(b;@E82{>gwKFA>2jtr9Hr=!uUxn{I@gt%WAN$fbHd@AZ{l5v9*X2CzAa1yZ$A%Wv#g1;{zT}4f(pseB zotrN&S<#6bGtV4S{y+%jl#r3$+fBf$#4kQoWm0HQiyLfn|-6&djpWV{jctm1QTyeVXDoIBLLB4dD8@5$+yEwOf92#$h!Fj)4 zdpSQBpTqp%L-KxNA0b`@<6{q%{Se` zZ`)%V;4%n-m?HO_+4VB2Ts;we9lq# zaD-^nIcO*{PKgNdLalmgZfS}4z2n&uN_TUH?j;p%6A_QXkPu3J&(7OBf;TAj^`TKs zaVE+@+$k^$p4xgXz2A`NBN-+FK5{e;f*!)-XXevuuf zW5#OtgQ--uTl`IZ9DV|8*0eV=HY~R2l`Tv84_DYN4={`M3k3`0#I4`k-+Z}WCj2!i z0eguWdKBQ;%Olx-wU1^dL_z-2tNQ37$JSwzR&Ud#$opj%Jj8%gMoNl74(M9!W+)UL~6CR`>mI^ z8at1Egn*BvLmEjk)~ehCWp)!_)?6hyk$}XAqo{y@7zwrPIlRes{Pm_IlVylYU7TQl zB{hCTSff4rv<00`E_wOm;ftl%tIu)A`j3wdDvu2t1BqaW12G;m0hVYwz7G3oM!Ndq z(_LQx>>(TM1}xqi162S7M)I3zJ=D+kRU42 zk&{Mn%%=>;39#BWAl&HW&Z85h;*+QsN7qfZX)7O za^im7`$dZA50PkhdaMt;LyWhvp`oY?K|T~ADJI_NsK0?YOJ_Z^?ysyl3V|pjAT;2N zJ_+ZUA6Bejp{O`^?Dyahi#KCu1(mf$`d_E%p>gvM;>xUlmnoe^w2Wq1 zpT!`5;1HnlDAu635bBS=Yj_jyHsS!{SjnC+hf7-}FRM}m*g!#;C~vK)dTi8*GA*tCGUqZr@LhQ8R_J7{ zkM_wk3E~jfIU~PLNHA-`J`cBMfbcxZ^O;8I9-wBrF2;_iL@6-V&*l z=i!h43m6iJ$nc{c!N~x<&dvld_lzI%kiRd5gTkV|=}=%GnOi%99KH=5#En}pSYEm; zG(zCNNK9})5*{m1q2vLbxQR>+fKSEIoIf`ka5X_QOH#BgL}nXgGWtF7LR_jvj0k&p?Rf8f-%)w=^*enAgLLw#5;B@1Dac;%_i=X$sz`F}Gr6Y$ z_7Q*Qrkf*Pj2lU<-d=^kUJBPQxf%D!A@@Tf??(JIh=2uA2~rF87e_15k$XrR=9&Z^ zsmJtup>btH5;(L`q4{oN{N-il#)`L`^b;rKMi>F#h%g>*LP8nI#guVlLq}o(f>t`P zai&#UJjZgSUZZQ$ywb6~EL<3LGAC?rr75;l6dx@%Q;a=%X0CM%0bxNQ+v#|dXz0ea zDS<`sp7D?*7>AOUETzeppTC8a>|p*O_N?5rl37-P?~VA27d(_p#N%F%FV*$_28_(E zLi}dT;h1z(>01j?$+$*xe2wuzmL`Gydtgh}vuO$tjpU?l#AO%5w;&LpCiG8DV=ceP zGt>1|m;L4*7MC9BS_%NxHoVQ3spa^2^6ESBqO44n1=^lCm2oG|LfVdF*{%*UV0fv> zX~(@f@k~nWFca}rScbZNLfZ%eGMD+(+G#toHL#f-$wYcB_U>sa2biW#SMephP1?T! zpbZ_p`nBLj_Z@YbuY<3lUJ?^BUcS`o%}AOK>hN_kl7skwb;g4|C|dPnrJZu> z2bL?vve&L!z_&puEKPrSPW-AZkd*zpD0+00Ho`9SL&ocMmNyTD3o9K9baYtmhDzbH#q)Eh+BXmL= zaF_ZDs{vTKF1myJ^UD}jN1*hBSMr=cCiMCb@#+?ul!j#>9`ak+!$w&~sP8hCgR)0$ z`_+qRF09W3qY|dA{+^V;@8Hi^u>3ty24s&W7{Jz%qV}P?bY%73{m9bPQzlCHDsAqm z1hmzI9G%PilQ?bao?9G;8h|EK5DK`M^E=@H1OmIBmhxWPo)t*Gp{?BK z;+e86DEjw}!G6>x?qq@gvvHoj4hMu#OS%fstgckEOiRmoEg-~zCJs}wp&93i0Kr~2 zg0*BRbic`ktLmwNLL8&0BLFHjF*o8~!C)IZx%SC3Y#8x61Njn9AxX*4xiDf88!5P< zF?B|7ZoJDiOjUs%afAZ6m;l#&XJu;)M)T1~Q@uG6l#txeQ%q+5{5Ro2*&n06bnAFC z2@x$5-PVWe{*NhuJsPJalMhdEyt1+hstGs7gJo@ zmmbqmRBWk<+H{8#G`DLRAkuIWJ(tsf7l(XBSs0PVA?jK_g;8R&%9Qn^2VPeuzcq38vOq--DDVrN;$^ZlsW>bH z>iAx$R6lZ-;bs>TxWPCZ{l>1B7g%@MR%ED=Z=?TzKvwV+ZQQ4EY`5E zgCAsn3HPr+)QmM@D!Cw@0+drvoSnvAOkES83J|~USA|oS&tBZyx4si@pC78typJ>W zr;v!_GI-N`@|Qub)0{HK62vw4ZZ7P4-lu1@E|7Wx&riB3fP|uX^^Ss+y>nNh$7v}? zL2l=&ZNwd%3(_>~lXSurl7B&j=zi3%Qy(o@WXo`dprknJiF5%|`t3s?|K_{PSP>4# ze7Ga?=Q)_%$?!)6r=aDUkZcB}KbKcz43aniP5RrjN;s|Wy^&_*7Fd@|$F9jQcz|n5 zv$!h(3(bZ&)S8l;0UnrL8jK}cWvodO)=)9L!=aP1C%{Be)!9zD&r6Ik>GkxS5Og@P z%VmDo>O1uA8(wp;_z3WkQ+?iminLAtdWy>hF`CVlzmMJH5BH_orjeAwLbin<>Pz

b?v@ps?dw$#1hv{@&0;%dq6-=+{1oy%OY{GnZVZ zV6c?$McdD=r}E<@?$M3G2Z*-iRkmKjjH;)zE9-)NbceuD(lo9~WaLOUr1(R!kA-_{ ztpK?gU;{Y#!&Aw)&PK7SE0bm%>BMbfb(-DJc$AvLK0FXzbitUu9fQDB3M8G3>@WtV z=trzItc4WZ1*Ql*ihSGe2jzh=Qn~`LjEl-gU96+Nw~U~`$s;e_sfGBrw-;B&i-NjT zmaMf2H9I5fY3j$^__1T6oOGp9p3DR9Ni>p$$`L)NG67RRAkKt;tP$hh(=HRaMVaK7 z^66$ofp-=u23fuh1x%UIRnr%47qSj+30NGZcw$(lsL{oJVOD#24kL-h4JI`Cj!{Er zfYwi1>q6tkD(hg*YD}-fz6=cD#-G_Y`Wu(|=+i(7k>v)XcIeRk(^(~(HI*ipdCyj|M6o2J{W56?al{@PLjz|v&^;K`+j z^*|YYu)8^kGnaGqbMdG-(WVX?e%ckk0i|4z?w$X#!jSuO1(L{sMik6JFKju>t>9Ld z3VTUliN$UqFHog1Gf1kKS_R!!&zfJkw_JMJJzTUGc;#jAmU&&R)#GsAF8&2W|p4oyC{bTS(KH`NC+eqP=-G zkA=1EuHC{F18zOF+&k)L07S+VlVSmKcFJ+taq1f%?~>u&8Vntje_;b%8D(2Vfyq$s z*hc~dU(WbNg1IK9g>J^k8lX7^apYJbBn@7oYFa~0KX-0c*q@)3C01k;BpT;b@^gF) zSjgS*MgCsT1#QX#ZO$2+mZUDfTv(T4m8NQ4ry#Lg7=z~`fCNwZrKP%Q+61UDB)qi{ zaaQb(RTVZ|+WEI%;tTZ|7I6&g0>!skj&gl`8PcDg`Z}mjm7+L4>(SVEGAwoq*}J%uVpa%rGV9kS z;SlC%j`amSdqF@GNR_CqR0XPF7SMZIrXIX*Eq^B-@kEml>uKNFvx70zTA^FQ50)%) zRdEeB7r0H7VM;Ns_NM=oAR1-s|21JuP6boJyy1iL`dtd0zN%@_N z4To@)14!7BrNZ$?Ic8zQQA*gEe-oo9?6O*Z1KQ01xaYKacY46c#hX;&EH3Q&VDrvx zVYjr++eyOiKZNLLT=Y@gn#K+v912nF#DdG#w-l#uT|Cu1?a*k8CfkG37hvI;XkR)J zKbA^A9ua@xN`EPl0L99HYa)TVm4T)rK~f@u+g(}6m_Sg>Qya~o2O^68cms&(p@3UhtFhbC$Zvq9{4Gwi3zU5hr|p9sfiRK!2nc8#k_*es{;9gvpSbbNBJ zc2N_a<>s6rnxa*aGPdnByX{^fY~&5uxW%*S&ZF5upaG&-*+|`7=N+7Z-Il-(Se3Q} z9LUOsyNZtkTjFF9Rj6v9Mj(hGCFYuBHag+%oo0UNb0)lh2A%^=dkW@8mUE@)D%h^& zKk0K?DNsuQDp2)2{!FxZE@&0bXL?Zd9awz8P<$B1z($#gLTg=WsPFweM_2xTFq`8BHwA5tZnb6(aJ-UI8+_1)*pXy0_qH)=+S# zU-#XCEoF#qGZp@taTm%B1iOUyp;~Lbcw+KY+&I)pJwdSjNmA}=yiEAI9!Ss>mCn3U z3{K&HL*+GbZ^MK@q_lFNqC?X*F}YG^!p*v6L-A0vZi%u^4mO-(E`zKk51>pEQ0+O~ z{>`r8MLR$HtxX8~a<|F^`0F>%XUCE&=hahEd$pU8*OZJGngHLQHO%`p({KK7WpeRm&9(b|@g-Mr8v^>yD$(x+@oud0OXqH;2#&AD${T+W6Y zgXKd3nw~LN^_jqJ;9wdi-+#mrloi?lY4zluBpxvxVyOAMm9d{1UY8FJr9<274q%Ym7oA z*k}UTUWyI*nljg+CrC~|R-b|d5brPU)pu#i*Wpx@aqr!H?+0sNbJLDVI`|d4Yf`PL z5`CZg(;#&``Y-4!AoG<87xoJ!*fORk`!rf(>BGao;h&4Pyk8BdIqpjBY!|fn-g|IY1 zeHxU?&21#p>%F2o{Iy^Brb`NhtxBZ1$s6XpE*&ydA1~|m2pRR5o~(b1D&7lQp6Vsv z;a>JV7EpJPH%cpXL#-E^npJ0PhI^)flqkQ!DvELJz6^G z#`XHNa&8mcTz(iv-u#xzE6?j!mSogF9 z>KIQ~db^+W(~&I@^)!Ghz6V;>FNsc5l~5>%dux+R-Xxbt&4*fB6|+5 zSP14)2tj;3pQ78KV`{n4tYw*mX|vQf zA?YEC*)JM(^#`Q`Z^hi_^Op$m?{7j`1|~de_P7i1l#7QA#qj0+MA3AppM&S)!U~O= z_+Y1g@2@^f)MP#j(?>7c4mV@V8`;K{?=fMJY%wO3n#Nix+(IQHZwmi-=EeW= z=4?i%V3WwxP!d0qB^t6S6%}(@+{2>z01499l_WWO06pCrZ9P@2D(U^rW%+r!5J0^2 znMvExxQgfLPT0x2@zBzMQQ1f?$HgS8%C#e zgAz)Lgrc;JZUm%3_TBruzn^o?=bX=e*dMUluGe-wugCScqf#SG{Ki{_KlS;uDsvUT z=p~a5iu97rze>sX4l)1ir8lfOfo&k*yK2f`td{d?ro;erycpX(!eh>qRRu+YecR@x zNRxflq}!V8Ldluhs^l&;x;uA!B~^@kLi3m7d|ib`@$Kj36;O&&E-~HM&Vq=hdeIw% z6#=L`LO^--vGTn>7U>4cn|n%aB)}V!ZTYlM_;-39*k2#X7bo+%$y5aT6(zPs<$Fbu zD4!6BKOF+mG)XrNN_BP0G*3%SP|k9%cKr}#<}7~EetCn8?976EsHDWjS_uq<2%f%D zWBEKd5_2;&=v(rsD?>{*(X!*m>J3@Ri{W=4c!qE8k;r6a`}S&tLWt+6W|fKV8`U?+ z-jniIQ1To7;vZ?Fu(;~?8-PXLzX679`A`4(`zTyywe_#L%g|l<*G~v~245+_#v4~w zk9QIz7GRh3@jYvw&I(MXZg$1}@mT2NeD_TkZ2{esKO3r-oGwH} z5Bp0g!1MZVd#z_Xum_Kc?yiodDiuIpf6`n900=W^2?R8Wk-0fs3OE~cNNXhp2t z^q-kOPJl}W?CGz*fhKZ4EA`{SB~w#{Ob1dVMemR(h2uw=Dgb)206`OXGj#WrT13^d?B_kU zUv+xguxQ`IUncO!_AOJ(WH_5>7)Yk_%S^VTo~eXo~VRwq2Y|E|>iKkH%M z`2w=iRt`JU<9QduU|-MQOG1WnzDDkD)f*)Z>pQ2GRI;8Ne#%R35C3k2?%L&$-4=P> zV$H9HsQ_RB;Ro1CcA@4Ql-WdilN(rqL%yMqLCkoCqsT>80 z++g*3YCoyctZt80?_H4p9HUg&#Ezu#u~H-B1RqS?iB5K8s#LvWN3bthp!`IY(tgh7 zErTQ^_DF^Hp0Ob>_(V)mD?*v81Q(VQRU)WL< zNUjkp5lnPtG$iNQ+o4BFLLPXfuRHd?iR3*TwAc7|EIXfOq)=RZQFE!25 zL+?7R82lrY2E~!ju5VeXi~kI>neW-Mp!>?uiIY$7CNIpRw;#XYF$=SfRF4E7gcnk`o?% zD}1!ozK)m5*EKO+{H3^Kr*O0BiY*C1qhDyH`|RTFj_@TosebaIh;>`|&yJ_njp0Uj z{G4Ey&KGay1*dTK zp|HG1I%Y3m0#q|huI?|M{+;~9#$Ezt8bS24N^qrj)jbO^`*gP0Z8ZO;kW-fVRD@nV zG|%Kh9UDdTR94K`ogr-cyxa!Qnls05!Y2G|&bvD%B_Fl@+Hc2?2pwlJdP#%|0nzm{ z`DTI5*kdlC0gHEd8mni_lR0m^SBla_zA}gU2=Xmmm^DP@E1Ls|-O#op+(ggi75#~} z38Z(lK^A@?_!I^CaUh9iz(ZnqFU3=JDrDH|g=#1^hU%nrP)ddQFoem(&wWnsl zCYXg2W|1exeU4_Bo=y&wA4LoZhbwWxg~{Q|tP15JL`-n?XYolXCHL2PpJk3{`(TnQ z-PZX{ZPayx@1-?2mGH)G#*i<(OX1iGL3ve-7=V&9>Y1!W5_v~;xso$WWUNFrqkuv_ z;MjOKRmOm02(w{wc9~?cI&zCr9ls}uj9leQKyZ{)b#m^$+otp~y_WY_a^7jvrtDFs zmjA(@+(>cbZ$UoC7jVt7e>Fzh8=ZsW{SfEPqvI%U0UHd@}7*ca%Z&&wxLHk2z2 zCgYwe^* zmLU1d_P%02R^bqKNz-sf0Ge_a9RiZfcvgRjDsgchzl%Pm#ts z)Pl;0F*7{vgK15!rrPBKax9Ri#($&jv1sT-zhoaA<+>a#^!%_IAJ;(vo-wmi;4#=N zIc-os6;QrE*}!^}*2dDi_xPdp{lxRVg+Af;Gz9YF`h@z6?_cZb9p5#HiU0EHH}3JyKB zlja!m4Ht1hMj5c%O~C!Tk;zXhz4!8zb#HABKm<|4r|%&nKEyBa%}mFc>F&8;aSq={QR@cb4V2v#dJa|B~V0% z2p*lkS41S$a;)H0&B{7RH{_~-+&pQ+s5z+Hs+Lxprso)ak&+zD`-^WK2Cz3Z5Cz&ldCFY8w; zCFUn|1d5N6`&Qv!Mx$%&LytzSqoo)sqi@uh_>8xu%-67E!J?-X`(|CQ5P+$75G2*5 zeE+h$_jfs~Z?U!a?FQOcxR+20)t3I-KPLI`VfL z)d65$M(}EkLse|OU#Dlq=Hl`3iF3u^3t6rksNWN)> zKgDr9tL3b1R@X5h-#5b2c}8w7(J(nbXOnvVT{BRUmTSVCMLS1AIpFR+mwB0OiSzU^ zsJP)Q>HrS{sf^z-2^QG*lHW3)oK~Id?wP(qiUkD6e+Xut z<5^;ub#nA5A~w)uoJ5h_Q`#aYdENK!jlp2!>vM+Zh$1-=rM}Am%Wi4qb&Qqd6Ef$R z1Qm|E)Q_L8F4tHMB!iAGeq0^=!n_aUx$}o>$xl%#UosGTEwFzqx}BX2nEU2;6d&ld zWBTq*^M{A;SkaHZ;D+*HODt^dLMI37#;HQSK6eYEd|0z0t{ND-FYXO=>~ab{RBwu9 z;6Z)d&%}0m*>McdrbF^Wf`Sf&xCQ)UrH}iC4o4FX;5M-V_)))Lx8I!RHeh!dg!$q7 zcpgF5XTK4JrGYxQ+CHb7*n^uiCp=DWkl`Z+>_Y@zMEn&o@nNOosTDp}5XnB;moDH) zi02F>tOJ6bBdpPk0ewvOdkA{T2%&vf;qO6~?D$-V-%aY+IOM~s(YSLWV2Lm!;VV#6 znHbLk@UXy=9gp~uj3f%a`Vhu>F-psaVdpbzdGvVZ)(KK^2z4dnmsw_AAqG7!VB9lh zdR{<4#tzL1V*VLKuRH=p^)g|W8MyG+*n=1k*cd6edgKq^`e8QD6pFhJ308j}m4AiK zPw=q!&h6TRa6j#c^-wex(>xkIx?&mw4QukfUZw(|nVIn^CwdX`2xetG{QCgv zmR<&Ob_NguU?51E)QqaGpcp@#gWbinZkzil-XF4tMT&QnogzFD!TcV}Hp2KvRwy>D zL?)o{on%FdhJp|o3N|x&Ce>v`M-Ssw0c)G-Zz>U10z$wE8#z>wa;!H;d6%oz68dYI zJ85~>hl26Pb8938S^F~{>_ZVMk-ihOHt&l`q48%JmUX6)9z^N4%5qbB0YzZ>GW9nT zXsiNbz#-xnfF-yOF>s6+P2y7N;d0mnW))Zt@CtSdGrnObHI5~GSxDM@#Lm$p5xmb{ zMkajsxo`|V{5FWy?GNis5UV;FL2&`S)DS{=nTZaJkHN$Hy2*SGkL~p_!s3`-vr%IU zZP|neQhjk1aEv#Jl1_*7!VzGRLcrV_89Uzf*0^*KOqLlX+xh*Yp%9lmnq;eyq%w#u z=NUmM9)k>k?LjY-TO{7EAb~{;^8+@v*dSJ@BEu~?JK9C;DTbje~`$bW7>Suf~K;|)+yAb;tef#Z?BEPfpDhYFP-yJ25 zCg&am2Ej0+z?>8G34olP05g!WQ*^MgHZ7AgyGa=lPzCg{?#QcAqSTt*G>B@)A7I#r z1PrR1WUs0EbiO-RJ1es^34<` z5LaO{M-0>PQ%>%e()>T1ca8-uskuJd(%q7>zsBenBP1cz`1LxoaKav!gzM z#|F3VvL4nbHR9s_3!p0xK0re1l+6MKxoXf8p)#~iOlu5xEi`>o`W1|8*cw9Q2LCvA)w$IgK z#P5NzQUS&mSbjrti>EzL)}b`|X?f=-+YYoJp@>JYLe{5c`G&^yZ8PucgqblRnZ-Db z>rWEs0}GL3&N|H%CU(5JV%W#8Z~usi%~HQG_xK@5@;e}yqV$ZRN|z`7j3YLJ1`#ZC zic!J_iP;aIne@{T<+f-GE~{QTI|$V~oKsu8F#`&!%rgZ8iiu$hV~4sl_NN|Bi)nAP zQZ+zmYQq6K!gL4epUQG+HcMxB+SqAT_iqNHMe*vJ5GJAENq|I>5%QN1rd z)6OK*cWh5}U!?oiPPy~8zEhcg_trCzSwd`z7Fi*Fhl+-cP7ijB_T4=94WkbF^HT@Q zcoC%179n+(V;Ihex%X$nQO)1 zfizX`RFU>n)1C6;bCk`c#uY8#DVkZAlkG{H28CAbY46*m9O(g-%Q#Xz8UIm|-AL*i$((+J%%RM54-RrwBw7`asnedL z2TohgOda>m%T>$U_fGkhnPDLrT6>uHKon5pSi+71=BolWsY1#u z;0~aG^QtiYDN7zEy$)gd>=Ej8FRGt5@Gm`DbFNM5C)Mk>&@4RWV2O3oj=MaDq}Cm! z4p*fvQf2NwW!`h8yXdl@tWwKLnzOGE7LQ5!t0I+-0870%t*eUELi3njrsD#pXw$aP znfp9aq%G*G4_8&aQq}!F)x#atomV6~7?M$+_x;Fw0-qs{V#V2QA=qSwitIW20;yUt z_Tc^C!fpTn5OYJtJc?(L6X*LBG(1glE1XFug`JyG7xGO{Rch0goA%yKn?G z$r=S-`Ut9KHz!KBQ)kzwGJ^Av@C8d!lza<+cDo>Bv>jt(5gl7vFGX7qX^H}qx^P>W zSKD-3o2AtIY~K%>M$M_dq=zQ>=6H1#jIGocw%lGiu14(2@OMM=U3g4v6Sz%u_6O)f z-C}lgDjFid(ThfYd^_LK$k;iq-~C;m9f@JhIqC+=^k9i@1Rys(Dl*NPjLo?{5+^8kuenRwFI0|+U(xTgicGJjFKI9VY@o*+6x4r5 z2IVy0|GU#C0h;@IgH4Bx>54iyv~zI!Y_JNqHDBn7lBrKMfe3`ca*+JNrr?aOj@+9L z%dQ$1%>nC$0djWgp@I>QoG)MJzm(vQe)9V;cvF`vkKiyOK>;Kf6zYs_zMAJ$EHiz} zoMr6qs9oF9ufv#hdnZx$ENjiQ^4YulN5yZ+A4 zcYZeN)I34L@=WS}fsN2sI~G3 zBKCJJ_5OO0|GL4$cFG0t4Kr+Xv2M1iPVRL@f$^Gmz?$rXFYdBiVGpIF@_0CIx5#tq zn@u41Rwa@a>rw$!(|Su$wi-t-ny6xACzod%eu?LWJsq@&+t>JQQzI zmSwZ#;aY*r!QC#K+>QgA%Y(3$-P3@&K@+E2;|^wNeUsk0qF*&-50BmlY&MhcUYbuc zci(5sTiuyy`x9_X**S5y7?$;`em;wZg=q)6^oN}F=TgAY=Eozg{5ZCJE{-?9v(b>V zudqr?t!B23<8qyJ;F#x|U%vTkLOH)ey3-;8xuWye(@h`&Hi#VL60s<7HR;M7l~iJ|W05&WMI&qQqBWAd?OpL?wC(gm``w>x3vDbhEBB+4 zYUcBOuCM-*NYr6^L!rk%q^BHBi`9Fj0t9|UrB->BTHDN>R+-=J+XD0X(rmoyDf*lC z;Jw%3cB&W2s?45L%ie60-8>mY+R-dJCRy?JuaO3|oL+^5ch=<*!l$=IT`Wd--S)%x zRo&J+!^2b5d#Bpbec7&yqqQ$2pl%OO`+=T$jh7T9<1hKO3b{OGVps&~CRE-|-?G}^ zL58wzf!KkmTyMsLGLsOphs36#P!YNmpPKs3*Wpj%dIw+n#ftp!e-Xt7lhre{O$9}q4B6Uhx>>xMRVHm%1tlufRD#3esZL@9OMs3`rumac?j*8N%9(|3 zufBzGY6U^A%8Wu@udSzBXAN5y#qYFj8DrrpoF?`ylBqN=Fd|DXsKrYvs*|BRp!~@a zxALbID@}Y=VKqPal%tO6wu@SRMejN^&lPW&q?=u(P^c}q{GdkQ6IH%2`+A&_5}>W3m!7c&Yfi)Wnw5o5NWax z24;jG;cxN?_VLw@-c#oNqU>k_gYh!CcX*B6P_e$JpQsv3KIT?^raInMV6CGTe`bb|o1d@$R>L00JZFbp-icJQEN*EqL;Qse@Y6*;J*-a+>b5Sg!;cnZ@N{~?X27Hl9E_swUMeNtV%I_317Y^AO zL$isLh(9AntU@FCmczV=(ju8{AO&`8NB4`W>zg+H#r&9e-(3g^#6Nk?#6(FRMm&HO zZdi-h7BNFHeGgsUTDH39R!BnMmcr?_Au4*40d2mhmbN;yuiGum_{cLL4>@K-3PjOQ zhkiD(dH=%k6$MjbU5<%$b-Yp63JYVzpp0Qd!b5@)gdBJzo9el4#K}wc>~F2qx9=03 zLfKy&H|Fy`nh3~z#cb*^^vSRIZq&XRK(}Gc!|I?Zz4vrnjcvqLeDsg`!)yy=s{2~)(uKLe}*4i+)KZw zPb4}jkGiM4%CfeltiawI=WC%vcFVM(E5|ny8K@i?hg}(cn=#mI801%9*m49SgV4Fz5VQP0`6YT#xX6a_fv-@Vh zHZc2;P}OhwBiX|DS58LL3s2o@4J@2Fg?1k2_@Nn{k&jHE6j6S{0Dw)TG5swb0l-?3 z8BV9l+a>}x=LkW3*YEd|wfjXEf(pEUF~~q{2C=2Hz-QkQA-^RLmGbJrQx> z!2P$B-Zqi$nUMI-oOp%SB*g7m@cYh=I<_?CL-(yUeCMWWTAGXEq7>%;iB9O~M=(Oc0~aNAl5!Fm`}EYce8|Ys>|u+nv=_dLX_yQT6()qZLs=)0+?? z@K&C`Ye-NShxGx#xbWqF0)}>etCSIKpLxfE{sjy#hiDIwaz#w*d~YPtMhC|aKgn!( ztGB0OMVVErGhzr5&__hKe>xlQ4wU2FoyY*MMOn4$P7@Pf%xWp9!fQSfeDEzTNxtK4#R!=xV(IB ztL26q)-N}Lg*#GL_CbJf$lka=@wql3d7C_`#{>YtDLlwuLjv2!H-TPneTFNO|Dq)c zyp<+=xYbYgck6r8Wewx?ZF(S9Tr!<9asza|VT&u&a)v|q&}3uI=0G-sb8WIT6?ozV z^b!rt;S4+(40@$v3kVCmIuE>ki~wZZzu|rcFV$im3jXvqkd`{wB0cbqYVe3&NKTmt z{b|tMp^(_5mw3s364t@t_-`aagN5BgM$de^{6Smzu7*ZH19KPxN=4~cpxfwCbC{XIB7;9#Vfj1g3(+RUS%Ej-a7PcWOxsc zT%W39(aimd$e3YkstyTw*HGAJuluo)5e-8TK@$GO)-faHame0S04BDVIF8{Y0!bIY zvK13x9XCK6Hrp1rpCP>G6}U=Fexe*-I~2V>^!QBT&UEA*PG<^TA`~7k3aEx6v_TO? zp}-X=l3^5d8wCR=lJh1~swGm}B+^DD(n}_CCF+y7Ml_ZuVCa%QMJ9~DcyXhDhszYn zKb&-TJ4pzfEW(>Cs+KHflPn&UELo8(J)A7Noh%1VQQ%Ecy0qQNpcFST&p_gMz7);v z6fJP-Gv3q}YS`2#Q9yNrRD+6CBl=Xm_LNuPG}GBsecm)ngS6K+X*R>D))i?E2C4Sj zX)c#3&b;Z`v!=VcTp(>ACpr-nMe7gFptwvAQpJSh9rs^r1qD{UKJ@w!A*UN)uiAWbH!Sf`myW!D8e8o^&q#&5?4s6icc9x z1n}h$wkrk~N0S~Q$x1Of0Ot~ejuM||&tPat5({iYbLPy9;}USbctbQ z(fgfB*b#VJm`DN+KBxoZs&~J`p*9GDDg+rTu7zd-B;gDi7AA9j3?D+1>PW$50kAT8 zg6tlc3!1iGs;U{M0CfDrzMDa zf7J2*#1NiSR|j+fmrsBm%7c%btEjH4C#Bxk?lcHxlfIXSAEGjyWVs1@cuedAM!>~qek)U#@DTlve#IcTnzrvA&5xCj1vUlE^WG(ZKfI1 zDD|ZgwA{$FVT#}~1K(pxiqOselP~0`b%K|{KQLrZ`3UNd^e{AZ z_vJ}1G1ckA!R=rZljg@gSR|M>as(?u-ZB!~7rDvb$O8pzZ*Gmo#Kr z9xi(bdkX-}Yrq$;KY;AJ<#xL!NC1%0o>(LJXY?!T(GS0T`CTR;E;xbD8TVzQeM7Bl z{!%xno;0n8&gYctiZJaIj(>Xi6K}YXK<1z^*YclTE;i2`LW%FZU2OYU1?!5Vp|MONoT0m{g2H z0E++*?`zl-T3Yj018-&EHeCY_Hv=v*gG_tis~)IJ9q4Nhlyk%FH;t1U+mKc4fbHmj zBk3TnANAdn!F3PE?Qm>*Dk(raV%Va3IBaw{@@BXSSDzZxT75XodIQVpA0%KS3hWvQ z=^BpM8}^p^0^KVo>F)VR6tRV+tCqSVhrqos)fzKe52*yy2 z#-N~9pa~h3KK?nt%b%?;`V{6xubw1NmZS|zL6fBl!>yg64y~jkh_*Faf(AS2FAqq+ zFnm@T{$+1)tc&LO$@p39H~>9`er8{?q6+446O^8sW@-4#?t`}gk>o+BI>Ur+EB%g+8*1y`HGAGFJ=P*gv zmk0CGAKAt;P1^lE0R8*vzpIdS;VP7H1&|!`95!*x*7 zX91hs;O#Qn%y=M@>{HIut?>A*=&`N%*SZUv{uu6nwYLFVo{NvzcAEsZT5q?Bf?A>1 z`Ywq2uMk*@<2LmH&EUuF-1uGMpw{P_q_g5cF`4bufbBOFKqchCcKm^%25|8ZlG6SI zPaOUlN>?FIrYT5gU$)@P?HR;I_NoT=lR@`sfBJ5~Qas9QDdRBa&Y?YBj)^dgwQbu z%fUFK-IVPappWt12q8G3F-SDm(w64W5hifJv zOu%W9)6G+BF#jcOwzl6OHywZbaj3`@Qsf`)cV2rhK;%?-iI%X4q@@FMaOALSPysS28c3hwPu{)iK1q5*#{oFHXviVVC z`Q`bPSgA~V<+V3|#L4+`_S8Ww|T9`f4nER;sR^M^HztU{*Z!Lby zQuIwHx@iH8D z5)LpVXBWKn-u&!&Qh;;b4PB}w?G)+D$^2<}tQCS7Zn&XAzb=R#00f^AAz`;sME$;F z^e+DbhCNdkWl%&VK_Q67m@1Nt&XOwf5hJ*-Ui#auh!R3P3)n;90YEM1t5p*e67l>C z7{)?EeR)L6sq8@vVe&x2zA>~GzQu&J=%h}vX3z+pik3Qm^U3okZ`nC>)dM8VDKFwR z1S#I#^5P-GMA4Lm6g#9@Ys{i%85)D4c&d#JV)F!mWUmM0g|QkE!*2R!F=A)>VIWK> zqyL0KsRV!}=1FoOPn|uZ|L56JG&t6P=>9#8s#Dz{gywjb-&7Qc!eZY2+}KO#Z)lF! zZu9wTzu!MNpsYNm5h;E^8ZVRJU77wI-wwR6pkPLii{%{LC4aU{0ss%LZAicspawVr zUf@Mwaj)B3?CsxM-1~o*`Tk+~a6aGJf5Z7suCA{B56*Xrz1aH~=exymd}n7khYyGI z-Ja}WPcSDZC;ys!*rQdP$%p;@`|9xU>i2K#;WSR>!>N3?`)j{<*KapBuzRD}?Y`TM z4(wXf!NI}a-roOU`LGzw+RDnmG9MPxj9n_hPETRyv#~SD*dNjV+vl5^nfXtm?_XdK zJCTax^d=`KCnhFvs2+BtZt?3N_T$IfruWz{4mhF@``HlN^Ay`Dhiw(ZHVI%GIB@FT zmoHyNMn;B)hWh*aaq3=APtU*bUT0_Lf7*LZO-&6A4cI!Vy1F`SRTZ{I5c{46TM5Tj zkYLL|*is<21P@yRxU8W2P@Rku_-blus;a6gDk}bU^|1MlCB?=6sq0~rld-V|Uy_or ze!f@_^=)tCf4#k|tgN)OwA9qp)0q+F_1o-*+`S|#Fd3oXZ zJr55LS6A161wQOsJ*?qVtdUz6|Et5-%wMtXXB zFJHcV@#4j^XU}lD-qWW~H8eET)YMc}RUbco{OHjm6%`dFC7iOSDE}YK9`*r0mX`y| z&WvTI$I{VY$;q%_A}ql_Fy1XKMVbH~&f$}mmj0LG6Bif%e`bdI8l|QQV8*LXynyaR3O+H0CNHy7OGhnSV zjH?duvWe_h$=pfwY8G3Ze($KLde$xl;fD550ezw6zPI1mUw6^&cMqcOXyiRqFqw6O0HT=EZ$`E0is&q^H zpUsIPjr^w{I^1`Mi5SKO>%`9wK6SHVPi}MlJpOEciV=#;J3Tw?RJZ}+b$|SOeeq{^ zsr$m;2XoQ!?2+BO$*Y&|O}}@P(bau`?C!T>AR5(;LoHdXRfN>n_SG#`M(AppzTGX)PTM($ zwu_A_p`_KCPR5QaJQ-BSM8|baz_b~^Q!mM??(f|51OB7WRJ+qo?F4a03E)`cdvWsB z6D!F*_~fI4eW2^KLu39gKaRCv^YkwL_owX}v*+q|Xfom00@AmtpBVa_@z!?fNyG+3 z1_>1qDh#(cMf3vwNK1ty)JDx1{$%uh1~3XEN3Ep(WPa7*5-m{s zYRmp2>*r|cgOI4Nwu;LH^G#ObpVXc{TtUa8rHUA)hsUmk6P(Jh@nXjA=KR5sRTj@b{-8E%-;#V`FQomGDs<#sePi1wM z^O-@polO`Bhsl5LgFxBxvI5h3AX3Z>YIB;uE1Qvoos(Qem8JYZsj)9tad zV9S{mdUW5U?29WL=hkXdXvYRzD0H9TSC!rJW7rw#d9sOtK=EFfC_w?mtDYc+j-!}Q z%n<_(&$9ee!q-D)FTR+7Mi5snq)>olsN%*ChlJ6M2em3#YE0W>DKA`y&IE>buZ~Du z%Jf4hsh*2|7c5<9%d%|UOUOJlt`j*4dp@%@p|mZO6uGydZj^O5uqG~TSJWD`dNGhs z)=0bU8*F}J4oLvHn{xPbsK2@TQTOpzun3KClVzgm{&V+AS7s{3lOj5T8L=!oy8*Gm ztC=A|jnYPYI|cF1F9kHG)oyp~^9khX{z?%1DBq{mWgPx7Ox9YGzKF4Mx||J-Zz*Ws zmwt`qAR5{lBx_-|Ff02$vohBDabL!6$)4e1?m%bhh8f*u`Th#Sdwdm+Ey*UN)k z;&!(m@{r;VQ$X%EEv5-`C61g$1~ZAzOk_t%37t!yu`hMe1%Ho%mDHC7ic(pJn1a(_ z()ySO?PJrtE(5682*BgkGKY@`v7ZKIVnN{@$*cS9>wcTs;-=%YcOKAy9IRLBB@X4s zvXrp{>qKlpB3F~)CERLj_wIO4O~=ny+$r7Jr0D30d3xS)=ks*GDsndJyBoV~?mlue zYn~*8Z$QDS50%WcE)XI4)n&{TO=+xf9}gO={fRW@jPAp31Egsr64o@tg}M) zu>A2VhVaG5KhL!MW$l-)SH!!o7GZ$P`8U|x$0&}Q)%PE16*txcT*evwUxR}byEZ>~ zvZm&Fm1%uANr?CWu)ti+jDI|99sj$VFpj_#k7FnNiIv$XCL>juhA5!-;?#+iDaYxe zH|!R?^-6e`vX-9j0qCImEt#FQ!Fiv)~v!pEAWe94n7+U z11bt++3deuVV|rCfw-TYj5OY zsS{nol|&qtF0q>eBK-mYxhTDvF8Eg$(DHb-#0C~Pr_SA=JsX=Fa%Df3oQPCa~ zumM1*P?YHPjI)G6nx7<__j5kK=R9HWc!CWw0u(c%8hF%BQcvj8g?Zt8!tt@&!s?PX zPiE6Ic=_}iIgGz$8Xa@y(PtIXbE4_F^dnLXqOuqa2+boBlB0N2XKm9nGn;th2q)RX zC3%FCvb!qSJ9+Pv6Q}p_CXmS!{Y8-y9j38g@|zoEkJ*TMds``8W>wPXoDBj$!9(I~ zvPUJe$1ii|C~~E+4S^=gc}JFco7+joYoIT!x$8W6rLE~0$$T%hTu+;Pw(UHIGW^FC zIVSYkOB=Z-l4v%fd}AV4k7ajo0h%Nl?b3_(6JdG@2zgzRkF`N>^5heA6jXuGQl)t{ z8CmDUg8gb%X4VC#-pNcIg|*~q;2ks!Qsi)_NHjW+)zD40$GXTQmll#Ja8<+{U9j#Q zoxodoxy^%DM_4^n#5<4y&&?>qN)!}TJm510tso0hit^!T?NTJ*L5r%L<09n-`p&Z5{fuW+D&n`Kd z-)~1D)wUuJa@Xq+#JZi4uZ}w?BDL`>t%xr3VJHf?D*N7E3R2_p)FwK5l$-&{evG2p zQ-RMMf*Vj|-|C1phO0hgm3H%q^)k3Fc9bnaYHG6(jy=}#R#hqV^y%90GZR?WAwi5b zEXcWX*0A=brBd9s*uJCs&ImJyHj!~f?ae9dYc$ok6#QZWck}}pldnCStC}|~LNZi+ z&PqH}AT+Th6^p2;Yfo54Lx8=+>zF!NOeMKp$ugvR)wVv}kQD+TiskabpJ%lJk#u1B z;Q8pfhN$G0wxC-07^fjJvA7MAqAixCa@Wk_b=_5=c1eYq^ke=v|e|xyoq)| z7&P5gZ#CmZzaz<$t16*1suy4^pEV_P*Dm+CZoSy?43=&~&4>q5N^rVD_7Jc}IMDX0 z^e$sZp+^1C5uR(0bsrp0>6$jIll7}w`}Z=L(N&oVSICMy=oN-^^swD4yEU4mqgaC} zE7~Cv-o&F3?g8n{$W-J+!h8_$$WuZHO}l|z*Wh*A@t07VMHF7^#s^D2G}^3x<-_;hpqN&co=QReelXwRcjO_iL_ zeJ3RY2BbW7pPxK=qT1CB$?3Ycm(o@85zzDTd({X1;o1*I)kD2)u{4m^8t~WC9al#k z201CCMT#|>%6%jO| zLH{2Bvp`J0K|luEAPWM~0qn2}MUVuta1L9k2~$0D%NiUJU>MU9c@o|L_mOrw94a zDr&$FaM20YFc7ei3vm*|7;Tao{mzFw%d~9CexU+&AP3miiYHyjy$lqs@Chqq5R0G= z0^tGca0wA`0ib{lG5rJgpa=|50gJO_oO;(n&qWWUSPz z!MJz_gi|fj_lg^QPz}%G(gN`U;lM-!p#B& zmCYp?c74}Pnb+e1(t3T)u*%eWu>o^X2cpmqbNa~~Ej(3yJ?M~NS-mOHfD3hT0npG2 zUhoC7U=7D21KZFE@AC`1FeaV-*`Zw!?_1ZVJ)o%lwS>LVX-l+X|NI&ly9TXE$lJZz zNtx0>fd~Jf5A6L9{Gbmr;sMRT3;v=A=+G(=Fb{kH0GSXCWF)5A&<6nE z36&=hGw=^!005m(4L~i_7ERO!u8!Hw9;%(%)uKn+1aJu)yOMqm%8a0E%<3h&S;WWW!WFa%tX3*c}p58Vky&Z|)OgqcM_U%>ZBq%HG!~zN2c~<2+8-JI);!jp+cG>f{~gtv%-r&K+2Q z=fpsEr_Sk^rs-{b>8uWkuFmIuZqA+_#=haya?l3-aJIQ#?0$~k7qaTVo_fLF&OZ+1 z&aTJbjTnqu1xMbu!oKY^3+)yn?b9B3)vn9duIsFN?afXcuw4hMg$&AC>h5mu7EZqB zo|)-x>hHeCa?aO&fw5RH>exQ)jlt`O?CblEgZ+N*_@3>=4)A~B0B}$TIdJQ(`0wJ* zzysfI z-W2cg3rzE;9rIxe@vkoNmyGai5$Zd@TJ_HHZYmqqP8>5&^d)EWO0OnJAMR5x7y+OK zb>IUA5A+?cwpfhy2mbL1zV&p@^jsetEKmn=@Bz23v372H($57 zQR`H|@@Sj)XAhl2-}e%!^>F|8dT;Ek;nZ`m0Y8t_fgcxD9~@Wj`1uC;ldtWIPx^md z2UhU(#}M@{zxliV_Yd;68x-}u*WjoJUZ zLf-zd?iZSx1qToeNG{HUFRAFC{EK;S@v1q~8Z@TQIqDgBCNI9Tuj zn+FjsUc{Ku;KYg=J$@ue;~x!>B~6|@3F03Jlr3Gpgc(!jOqw-q-o%+x=T4L&N%FkN z5hzNbLrWGl3KD5jjZ1U(sI#TOsD6f;Qe^tkX;zpT&!ya&YekMOPwAykoDVfwWD3UK-=2Q85Z$k#*H06hHUrn*TQb=626Ri@Y>2S zb<}~gz)-(Y9y@zIopW;Jmx@`xh8|LoYSv!=eCSuJj+yp8%U89+-N9~p}En_^lw z+~rJd)Ar~Z`gH2mtzUonJSp&@+EFkn zUw>rnzr~MV47{BL%!$B@0>GjUDh>#ypFyMuY0_QNnk4L9VeLZBwR3B;O2 z95F)6;+tuOI^_6Z3Wp$aFF+GJoR32QF0?U69e3ohAP>Vs5kSO9q=`tGj2!3+1py$X zDy3$m3`(7Tqz}g)uf#G-?5NZU$(X!+3Cu91%q>WmRH$Q)4R+|~m=vBg^Te{ayv|B3 z@5D1t$LPdKOqcv5ip(-)jMF70|E&N(lzu`vO3>{bwTaK_?9{VTOE2ZB#<2hmw9qI$ z{ghCgNT8z*5^6XGutq^0lq^Z9qZCtFXQef!S4(8IRm~XV)FdRUsN)I%MkB>nNV_|h zrdy$lwN_`Jg*KvPXX@41Tpzs_TTyM=V2(OeFb+9uw;gNR*_w?uU3F(Q_se8Ie0RWj z<;@n^dNZP;4lDprkG*k+oEN5cV?%dcgAdkn;4$xomtlH&4Y<#U3z|TVI#_^U7za

7wkLKHIl_h7n?6U=E z$e1??=WJ(??shD3#z!aJFt~g3++E6xOdY0@5gj^OzcJk6u2xzF2I=(m{OkR5+0Hi3bIPyhrkJiu9L_}f|d1yo>HqnVSWa1O0NW>^k@c|l82oD~hC{bAP z0af&37;OkfF)9%UyVDN{MYzV18Ne3I7|0^dz=S`LV-^Rw#PXD<2sZT5kADPYAO$%{ zLKf1HheTu|6}d=8Hqw!ggk&ToIY~tNp$>MyLm~cB2ugO+lb`gYBG71|@UhX9r8@;U zz9$ee{38ekaUl$4SjH!kk(OSx@Q)^V6P`edppeQbP?R7bi~bYEk=ogka1P{~Ymp~CC3>e*yh9A|lfeZ5 z5QIu_0S9X6#xI=r&xdu7pwu(zN1*Zs1gLX^?983&8fTF_E-xF_iReUi+9N$GPY?j0 z!7tch4{mfqe$pc8%VH|ifu1yfC^>*adVo;erF1C$xr8+^`U0Gma;IPY-9v-2P==Bf zY*v+1OIF%a4OX?OS4HC`rg5K~g4M3h601cT3Qn`)t%FYeh(Y-R0IDR^t$#HNR_9R; zZ@l6L|6M)mT_roWyhdcN7`d!o`|4M6o@A{JImSzwideWF;e{ZeKta%;hbEk%8R782 zq`W#=+HS3~2g$5vm%6ZknuR+FsRIuJ&?H8&Zny6Aib(W$35%Ej9*U4{WNSO!k==G9 zn_U%J(@NTlSnmLt+n#Z?yAzR^_JygnNHjJPUFx=%WY(1kcA>}J?V{8q`wK1s1ZS1X z(U-g=?La#o!Cvy2mXmmb0wlflT0UItW2BHa0mf`X(5&6-TI)91 z%2x3PEYt+_F|KB}u zuL1n9>DHFN0h$pKcxwfChQPuR9w~#LOW*{@IDaZW+KJ0s;U&e06@sNsNK4$pt47?# zGrn@WZ5*ca1~tr$Y!Nhlt4W46dA$?sa@e$+#E~pj|hV5P=!#e zC*mG|J6p^S8MLe2?;2tI){#wi)S1aVa&Xb36P|aO1luTm|9j*sO>3hYTJVEMIza@G z1qBJ?f8Zv3pZES4$V=Yz4jsLxLl64ZcL=yjKpbJc)je3X! z6eSpl7kcpycj&?i0~tUhwsDVgP+}lskj6c_@zaZx-uZqHyyS~M3F@{Jix0s%1cx{` z?W4Y(>%N)rf^VRP22z4qP=g>KgKdxnf#?8sScM`;0$DhRjsS&hP=g=f0y7YZAD9PE zI08q|hiUpn}kYduRXv=z|kZrF!?$cD!P093GtX9xrQ z>ji<>hDjI*H24RNB8Zw=o=BX;Vw|5)WVRsm#7{KC4QQHvP`qWdMD8;Tbm%8j1Pf@u zg^suYXlMm5_ySq528~LEe;@*Z;DUcRo?Yz4Uo41N0s%-g#(4xhWIVcQq_+m_J%Rw1 z;0JwR008iSX5fWV6bMB?2Llj@{|J}|J^%nr$cKTrfPYZI zL>vf4^g?2!$C9i>Wdz88ltxm~m|$44l(aVo1PTvOf|^u{KAqn#*FmwLY(p~ZPTX+-&l`r9q|W+miSGo8@Qlw)BTvZePyfV~1Vo0CyUL=QspT6` zdMr@lY)}UU7%51VLqJgR63duipR9tW-4<9^x^cfvA8}UbXSfGS4;&~ zofr*cSO`p9S7co~p4*2H8;BR!2Lh7U|9SN>5;CDyN>zaf2T1VN@`O@N{n(vIJbj4( zgncu1r9__N2Zt4i8K?(|bybRuGB@hhKDY;hh=xvZL|K|4XA+`j^4XtNrl4&ipe5QJ zGTNgR)_wqnI#_|EJz5-s+Ng!1p`}_If~J>vgh$v1O4!;*fCO5Q2AGvuY)hq|uvwhd z*@6(pJp!e-h1%3{RVB&g?04M@}?N|dn(2y0^q?povID{psGLua(=M^$I zoliV<+}stRFaXn`Tp)|6sEdLhU_6Cz(AH*XhF$g8frYybHHj41w^68rH*kRH1=aKw z)t2}K_W6YT)!+OjTkDmqh9wAyy$H+XzglgFd6)$mFkj+5U-m3foj8Cd35LJnfnQVC zlT}#VaaUhRRbTMn5B7yzL<~yxUxQg$f*^uMY|aLDU^GQvnJ8FG(t-l8;Q1XunS{_1 z{;FA+g?+FE9-f6-_=c#gwtsy<nJ%or%O71aD!1=e=MkM&gW6m=dsE0B`}^{j=)T zVc=PXRp19$_~KPSg-PJ5{}pE7G=AVUwuz-Rgai>5DV}1^so$5tg+?FV~J7TDTy`X}Gb>t%!(wCSACLjnVpodGwWO~{KMgRa4K!rgcaH09XWSFaSNkhEHbU;w9uA1PTmw zkPm2@{#j;Xre8>g2{5RKWv~QGScZDo-p18pYZf1Rc&u1}RvM_~U}j?%ZefDPiKPvN z005RO5P)NCm#YIp=1fQK37f^z_8H6G~W73Z7?fd&Bv z3#d62m`zbeG-nPOF4kzq(F1(g2T7d-To`F#E@+buXPP(wsu+e8sLi?aHkejDlzRyV z(1S{-ggjWtjIQZ5l7T0nNC5Z(Bk1Xp25O%^>6<9nz<|9ENa}}9Vwr9UA<%|-kOpa( zhiu?6e6H$@6XbRtW_B(K_2`Em#4jJ9PrW8*cYcXmz=hI$0bH;Js;+DCnFW>r;>f-u zfsWE~woc2=2y^By>p_6PR${ykWS)ybfY|LB!pw5DR7Ylj&f2ry`e(?)Fqo!*!BZ94vJk4OQHA%(kB5-hlF&z9{g z?NB(hhA$X^0r-MyU?cvvsWKJcIhYZX5U0;oG#2%KHN^{WF+!lWonby-zn!`|IX(f?;3c(Xn`046)s{H_v%4@ z@?n9-|LxpLeW`95XJ%K9@`(7pQxpggmh%u6Z!A}wb4X195Cn8E@F6$ypZ@B-hQ`Na zfi!t<2_N$}#ZrrizzMuIJNF$)s0UC01VAu_d60xY5A-kxZ9u<>Hu#Ge1AqgFa8X-x zh;H+OD8eIzbAu3qGtelZtaC`Gn>}ELc4!A?*aP?E^iBtJ^frk$NR@=S*LaPDsKw+bTK~(VPBL3AP8p+uBA@)%MNYxLM>4w zMQ1;VR>%b!hzDvvgKNO{Y^SbmSM~|#_L2biP!M;55IHPpXk_PibloHU_>xCI}NhaWJ2SlB?C zulXiTZihbgw9a{r;OkJx&0;_Hp;zz~*K~uR!-!AW#0KmK&F2My9ejMSzRMPXpdqvXFmNt{`~s)69nP^zXuV#MHOqDwfEG42xe!{AjtG1iUkZ& zQO6btptoRNt@VbXRPSXp1a$WCHzJ88n)nqz`>43$KH*?u08Acsl^|0z=49iI90p)W zKmCMq07EL!Q3nej;aJm=DUuwh#eX)L{ikX@+E{ksLNgV3h@l*e9TY3aVc(dla-sF8~0NO^keE zr{RW>YNzK|b|nx>kAq0mLmhBTP$#7Yx+ZB?V@mnwpsA|5DrWV7NYD`U0PusXVmiuQ zsK4ckE2$YCWPvFCAfstSAHY#Z4|nd$>t=XXWNMVCvN|ob)$+6rCk1h$4FFw~(`a0} z_F9&+yN$aTZyAu%&oOOGWJMiW5TNY2l`cEuy(B?v(EtN@Catvr3p_AJYTQGODymFl zj~W0l@(H;1)+=ge<(gYi2*C7Hj1&{KP{$l9s5!B?&F1Ug|E(GUQjIvW5R6btOElpY3qXA`nRM4^H%L}T^bO1d1@g_;T#-FE;e&?p zN;5Mk3dVqD7d>j)kgwg(Fm6Yr!W?z9U?$!?MXgik)ct&sJwg;Tggt>5zB=nt>Oqex z_5cBZBeygzv4Nq(^f~Ac)DV#pSY-~-jyUljS!>8Hl$etg~Ri?sYgXQj1P|68h4e?R`t(bF^b005DCa7Nd@ z^+m2?cL+)_$~Tb>#Gwv6*j@P4m%OmRZy}%&4QZAGw)}ChgNX4)8352fKwyI*VX#Fx z{(%RAu;L#s{6{VrQo*^oPeC>GTm(l_1HJ^KHWUfK73zS6H%V}Uk*b;iPqjf0GO>wW znZz}|01q(yAsvoj2pTkz2Nkjq7c%&w3uKtYyWJ3nWkgaALozvG_>dyEkpl_Pct$xE z@GCP!$bSGNAm}a8iGKVeNd`a(dGLcD^~eN8xHu42(1Id&q!$5=h?o$tEg1@&2zktt zqd7v5lSKr}BMp)w7OBWZFse-S0IAAVUL*oY|M-G(61l=fz9SvlIK>OZ=s5MH5t5QD zOU5Wyh~rhE4q5;b9qTwLPiiET1-Vj|w$!CBg$XgKWF+iGP3s04^|v|2FC&4p5YUAYSOjJKUiQCm2Ks@pwl;^pFjE zR09nRDJe<=E7*jnv>@tWL^;oy&W%!3ql|s5V;_sr$VxV#6&S_Fr0@XB#&be%&_HG5 z$=T2rbhM-esA*5@&W`R9BiPawx4cylFMNXR)cQG_JO;vB7c zKs0WF*MWdRACWjhCh(zzg#dQ2)*WnN2SNjWG)y7Rybv>Ks7$Z~08_^37yzzg6r|WN zlHLn1M!q``gCR^|409O7e!Gn_{GzM|(Zf9&&@BQn;UA_ONGDt&h~)wR7PcVBGf+X@ zK3=ygArQr1Y9I>nRG3;Fc)}C@{{e|7+@J%V_yP{fAdPKMU?K9AntP8}79JtPT>}A5 zoCZV0O~$w~ymK*EC4w`Z@eCoYfLMPIvIuny!~^TNLSY zn4m^t{nHY`b+{|R5{49lB8oCkYYZ{{2P-b1i*(=v9I2oWkXy^1UV;j~eJ;x&GF1@Z za0(8(Y43Q+#ph=Qxg&h2Mg;(ngm0>CyNGeqO;Nl2N}X3zG0vP_w46C|FTq#HX-5^2MERyga+tn z!aycH5D-8E7dW{9G+N<>|1ZeG8W#Y-EV3nP2ABHOsWyl?#Z2K@=VS`|Xh%QL%Wl@y zx_3QZ=2)cgolxvJy_5=!5CtIYd;3ax$5zPeVmG_m6$B6e&0`uSl0Nw#{eeC1mi2wkX3G(F$w|d?%sev*iE^C(;uHG5>aZ_#$NHljf0 zpee-z+{AI^$xLVqi%@P)Gp*gfPZfnnYf)72WrV zym)_2_a6Wel4KA(|AQJq_@WHRX#{(m;s{A_#XA&NkWm8w4EczJ5iTKJmfyW5DR5yK zG|b`Fi!JXL!TIfVZtKM_Bm)`?#_WBqqabFX0KDY=?vGwJkAU#;BveR}-TdaB0l*B* zct<;W@r8qs9sqjK#yzazSJu;>Bw%o1mCHXi+gk+p?bp4%y>bA|T2dj3xy>Akj`;T~ zpL-mEq7+e)71@vag#;}8!_yUD?H!zW_21ca1&SWnfkWT0hvB{b2~aXn}=bpp3a7C~;syxDqUN#@nHw zLU@1+wVV(N|BMR81Pk8W66PNA8HB#|L$5J}U3?53h|B}(ppP|SLL{LG9wA0-5ifvY z&3K_ixZessq26Uh4af$+MZ{bCN5 zN<{{+4KPFq9A*dH$W0w;Akt9~59Y@n0%A-210c?fAT9(NDxo13;!_Ynunw48tk9<6(G~0~A~}W+6t7 z<3@sHE&Kz6fh4PlWMU9v8k(d<1eye{p(+vyz5ykoQDR0q2|13S0k}{g=p?o9r0|hs zFves?L?N*_;Q|ojH}0c8isLfYWI-B%3z3sl?&LJ?99H%sNul{;Be)Qrjpv}$XF`@FWJZKg ziY7)(h#hD^e0EZTGD&kf$9>Y=1L(s)-~xX#Cvht1f;ON>$YVcjrA9R79X#hqg5@Oc z;DwUNgSy-%xR3`_XsY<?HsUW7xA!dzNJCQ(6*5~hfbXn>;3iH=B$&YKIJ|ALFY zXoDVNhK|ffV9GEAUq-;o7HGhZLg$kDl2Uf3P6C1p?a`423XJw>Pl~Bvdc+h63ov2? z{;9x!@+gUVBX^GFUT&fbb=sE-N|?T>HD*K#Bm+HigyEe>n_B6QCZ&mLDMvQLKkUMt z_GgmTpM+v}mJ(>7)MSl@gmq3}{CT z9UPe_nbzj4((0;OM16XNsCL)|lpKYgDyjylhDIu!QbY~Rqlab$2{cf$$m*@~-LpDU zs%p@jg5d#@C9s-Eo<=KMUIb!-2he52@C2N#7OJ71=1j_IL4JV?^-Z=`|H-zRs~Kqo zj}*ftWyJXyTA9l0yz;B)21pb5B8mw7C_PU~&5 zEN4Ye#&H=J;sHifnKeZJ-D& zN(}%r{KGsfEz<%lmR_w}QUn343n|=aMdT=_)~dh3ZQMSscL@+9Py;-`gENdDe{k(d zokEw2ZJ&Vbr|zkMZp^)&WDseA0=zBVDyiApiqfe88VmsuXaYVY|ACOkZ26hvKUjj` z4sO%RXyh8*L>y~}zAA2Dq16_y;byI55@$Oo!sZ?=?G=FwJx}OT3E{eIMM^{fsO`LL z#IhcqsBXmZ2>$O#q*oTvKk z?<#Mj9KnCIm_aasJm|wa@NK|KFU?T^Jh+hPVegb^FYNX&LWBTcOyNd&)(2c=>6$M3 z+Dc4a!a+oU5OBdJr~~xQukFGeD7X+8=FgIj1Y?~bkkdoW%`gcS5hn&N1AP-G6L|M0~s?8`DlFR()G9w8dI zP^j7P4RbKGKCY@R1O%{6bzW)^#f{VI@D6+NM~ulPgaHmP!6xv787wghW`YYb8x-#^ z4!bE8hvP!<2r)qEMR1B7u?(vRfWtkc123ep8Y`eCxKJa#F=w1m3e6G# z3;-sWLp|`qtJJL&?;`SoPrY#HZbs};G;0?paAf}Ro^0}T_^ls3f(tFf*EzCgWYHE$ zvLw6%8#F;Jctgf@VH}q)5o0Yu1TT27?L;g<$`S@0n=%3i^YZ>OU9fT!L4phULM+QN zXDHGDm_sBCLqjC|S=`kd(MHJH;bYm$y|MMM^v;S=^{dQO7ESU^w+a7N(Y3P9>W6Eq+nF`!6u2RVTY{Q^Gcb2iV?`Q>jc zPzJgwmO81HKBbmO=MzbnbVeyuJn_gdi~vOyuMZH^NuxA8%`{EFlTF_=JLNQKu@<7< zofx=KD_k>1Z-ydmG(mKFx64v!Be>b9!ND;cePi4HCSKO zRs}R=&a+@Oz$>^=BNVlB?6V&dgtQSvx`6;Xg|trNv`XJ~Mdh_#n>1gy6K0V@1W?q3 z7+Pulbzi5nKP9$bFE(Q<_G7P;PirjAdB8Wg|4=`(wLZ_%Hg|JFfODRW^ZB~0ITL6_ zP;EX!E;A2MCo?Enhlp99)C_>yCCHQ#QMG!3&YWZFh$By^s=9@;TT8FA#w)5jS`nt{vmC@CZg0+#u9~F^{!& zGeL7%NObEo!V3jKb#HKZH#Z8WfNX@aMHIIFrT1!oFmpfiYd;5kuMQu$P&t@DecShN zKe$X{3NQ>WMxeGp5BNJfH$?ZzffLRm|ARB6UxR0_dk5_t=j=f2fP?(-0v!t-CLenb zYeNI+PgmFsbVD1Dxabx*fCqTL0st|u|5-*LfcP5Ug=;v5J9H}7xOJUh5$gDk-?uPp zr#YkZM5yzj9r;5ic{4w^(RSDXSb_`X!w*1tltcKGBV7Wp4MJPQZO{RBYPpnW_?8bR zlcQ7zSc40ZLj{|;e(*1nhh?B819?jXOn2~%v$lG7M6Py4htmufl-xg@0#W;UlmL32 z<4y?pDa1~M1Eee#P&hUE_>YtNzuvhvQM3!4fu)b_oS*Fx@klU0?3;lyP>}RV-@vAF2Yt+DZOaZ=v%tGV3AMZMvM@+9{(*Q)m3nB8bpE-VKI%{Cc z+G4~CWDY4K`m=NUwu7oX_jw21|G+^0!#GrWwv#xItG1~_kc!6}MkM!~81r&Nd$b#S zJV$hFQ;z{$aFL>AylZ=!7kk}cmXKQnksDLv%6Pdmysq2%wEqzk-0wfYLlGoAo|gE^ zp7FX!u`WM$bM>Kj?Jo>6Q`9FBVMT5M9pZmXOMFe0mMhx8?#5t43 zc+oF<%!|BO(EOk+pjm$yEdxl4;e`4KRnplBWc@L@!pGs_pW3_ zM7$RKCWan9#dA50XFUFN{{S?+kZljXqZa-$!@Ni&Ku{pU)Tn%?{P))zy|YXH`zU=_ zF#VKpsS80v7->G?Tl~d`MW7Lb9!$;o4E@XJeewc-(sTY7;*Tf1kfG4Nh1&k_lLZ6> z#ULz83k=D)2fx_!{KAiYmAL+iz`zSJLo6wO?N_~`(?#x!z^)W;72G|!tN!hie@Mu@ zRB%6u%z!qy&^dgY_>(8=J1f{D1VBI-)^E@QHV*(KRJc&#ge`Tj6ks@!VnvG!4I;d_ zkz+@T89jy+$r0p8lP3X`M7eSyjej&)#*~Q?#6J)-apu&?aR8-%KlkhuI+SQpqeqb@ zRSLi*%%v1nKJ^$?|0=~n{f1efO0fWzI$I_@-CDKcSh7$Lo+X)9Ez_4$CH(^hz=bJo z^~8ZHq0mdOckXmKNjRpKxp~w6EYy?DUNtluYu;=-IVKQzKl44IyqR-n&!3Gpoose9 z>8ch64ob<^Vt^`j;*gMPx-IS6tUud6Dtf7xZ`9^0nWZKOnQgKXc3`)vND^7+5K_tn zCdi|GY7&Cc7wJeQd`d1x20eZv164oeHXy&AeS7zmd8^fZc7D>U!yv5IXt75fIxVWI zZ#LX=Bd{|8hl&rW4z?-dm$?|y;~w?8cnbg~{t;p#TUJR37F!g029@w^dhas>y7_6H zBTQ`3#TQ{j|4Biz5ERS6vn(KnpoC0oVU9X{pz+4ih9q*o0*@qXMx$E!1b_!8T11_M zJXq(F2rd8x8}%4s#*>7^fkYupsF{cY5YTi1=Vy0h9EsMxw3~ zCO`cwQX!5yst7>HJUQD_DMgWD6sJ3f;-i`ho`g`L7sAm*Atk!mXP<0tm}rlCl1K=j zJ``#Morx|%@255EL<$UfeyYWQSaHo&SG6Er%F&~K#YvzYc^q`m7z1!EOFPNIN$}n8RpGb z-+gnM|2C;;g#vh``~C!UA_ugnLkkDwD{?f4A4b&3$^69$kAL*Z_#b}sVE_ORn&E}g zgcL#NRsbTHhYy9skY|yF!W^?qi^Su1CN}q9dl*!lOJ;LTe?WaRodOocRTVg&Z*_P5>H^2UP&Zkf#xbK2)fg5own9 z=aEd92ECx}?%QvDgEmTFod!3ljedy903!ljgH461$15Bs$z`J4qri275`<@{2||X? zJvPFgQ;tZ&m3Qz(SCh|Wa3Q;VA~E8U??{C8?~7bO?-$!|@7?zoF(=CMn1<(wfMEJD z|AZl`e5hj%03iph_?4zVsd|fo#|g?YT>S}$gv?;(opyTpA|Y0~|3x7^w7JKc$7=uG zqDp?^hYk7h&)>c51D2XT|BG_CVuWCMxZyz^>d=FUMGk-gYM_m%mK6Tcsb=~c03^@@ ziIeG%gB|3|1PS**2(~2vz)0RiRN|vLP$5wwT$Br67{RGo%_%>tApUNEj-RN5OCI#$ z50!Ma|H*KMYMDYm28cqotUwNgGSmX42g83!QD{UAjSzcwL*E$y6zD;P6@eH=F~$Uh zIk}!m&d87wo=}MhQ2`w4a0O*S5lQPwV@U4EkTSAKi?>q(t^N@YBaD%dg%rvj|7ViN zsZcQ{Qs{>WiIn_!R#b2&$5GlAfpCl z$wL;t@_{J!GKO~iWeB-REobs;m^{0HEYRbHvoVvM?bPEqeHqRv$}=XR=!YmQq5(HF zO*Y$v=0E+}7FE8eocuC_K7KL_cP^BnZmHoAy-ClNq~I9+kU~We;1xJLj)4;0WJCda zmVvscp!ouUF@K`2hOU&EBcm z#$H&OR8+bYC5r6G9YauzeoTQP1h7I*@8Hpo_B5oq^yJ-!imL&f=O@@v>RC<6RO`Xi zjBMS=Rf0i)i3s2|a%h2D6Ny*i>2cxhup@EmTKpQ4 z1f*sn0ic5Obnw`XX!aw3eQ9KOqS?l>hp@5Q0|geF+A)q6kDhI+YZY=hViYVPmi3Pg z493-;?$)aU4XR1)rdr_+cRZ|JBxpkmTL7$4c?%K1W$C~JrTMguT|JO;DPr95l$N;N z_3jlPx-9D&#gWD!phD>CAL&kaymYKCZ>yqR&~W#=^|h}|{uxxHZ2=JOY z;8r1=?JRQJir@sdcPaVx41Mn#Vf(fUJ=xfZgAYvIqezpQ3b86?3#j19?f1AEzOINv zf?>`;Si&tP?j@|jx}9A_#ga5}QS3Pig%seb18(Du-P>FEN~Ok>VX=#myx2=jBgMaM z6p2fmln@xhq6t9&PJR4i21jqmK_;@3cXi|>k2$HAm`6Fh@rq<(56pst@>5+4S3^0# zD|VeFidTtemKgZXTb5v(b0uan4|<_!&_ff>(2Q_+z)WZY!4dv}g9l8S(v`OKr7@jp zO-~vFY{0;#K^RacU*P-5Z zuYqlAPY0XVH~=)R1WjmVyVC^lPz0;GrwBGoo7&a3_O-E{ZEbIx+uio|x4|85ZWjWH zdboof>Hvp3h@0K*cK5sC9dCKho8I-dx4ji{>{umx+5KK-G&a#_G(lR@#K!fn4Nh!? zC%n?6NS+FiwFMH8de{s%_`)rI@QP;~*cj*dtUdnmOB*}9!VIpzQLfkywBr#p)_4E( zyl22l^B7QoqZXc~-hTTwocLXIvF8sK<+ukqU=f51e|^C{|BuO(`+-0!ARx+JZ{f~gi+41> zIUz-!OxVXB_(J-9aeCjop084j6$+rWhIcIAFS2zlce%lA=i|@?pLv!NzQB-=yk0es zjD7%Py^YU0m*1QEAU-`IlZZw<(m{(NARF_Vx4k<#&tALZLL`GrF=|u5Ql-tQuuBcZ}Cy@b=ETk2LA{H^m#XZ^`El( zk`J*^2yodtAfq2USgYgt>-j!=-+}ml=lB;w2>t;)>ICrC?*RLz{q%4Da$*9!q7FoX zrt)t1iU|CO59p4-(NK#b48Rtcf%ei50Y&hK{}j;w>TV`j09oQd2Xv$jCXoN2?)ok; zh+O3oD&iEt0RTxV`bMw^^QQzU&?5-I2k1ayNIj3ws9$pRgh}-~p?^k{s^8y3YbDPzKX*^(y%j#e-sIINmp5D&jk4I#?6#_tr~K@3>OTnbPN>+lhI<_-zbA|?Q*>L3gH2>@nF z$9V1wyU7#h>8mKBd;UQX&<_$(@oywi^+citkYx^hV2&U_N2sb31+o8va1hxLtQ;{F zeKA*7QOHDM00^)evMG3q9O3V!4puZ|d}oEAK8r5Hd}ZFIy5C_3$Asai>N? zn#^m&K$Gjd(jw3DDb!IaH1afgGq9dgD|2ZD>hTS9fbmSip72RF=`s{O^RLqJH%(+W zdviLo3p(%5j_zO~eZZ1V0s^G!qLi~aVQx9m5jDw4EU7a+O~NKA!vUzEiRhpTv}q*{ zXBgTtJQ1@lYg0eVQX0`yJpr^M*i$VEpa*sm3wrXE*a$!OlR5L#K`*i~19U?B#X8S$ zGXkImrg97JAOd9KE$y%E{~okF#WT5{lQd6}LRFL{22?6Y-~r#D2PgoOt^ycLlsrFj zL~}GkdC@Uf^henYMaPpeCZGy_L=LDREP};^I8#I$ltguuD9v+Uq!UOVvqh0Y0eoOk zNYW&Kh33x7NkudK5b{YM#X{SoO085cv9u@zKnHd*3tY4FBxf$c)0;vF? zFa9Dh{}iGLmcbszArcgWF&qOj_LqNq5E@J&Aq=1#Btd;S_G_IdZ0mO-;L3BS_Hh?D zg4g%Y3iu>^12_OcIEceIkOKgegE^c7IsgC!&fyi3fDh>5WdJ}sxWhXLup(HOh5ao8 z^Z^ePq7`a^hRu>Px%3KDAOqa^jo~+in2tw44@RJl<#;pU7l=_eh?f^PRhJaPSg-i z1s;OR`eBt>xs_e{m0>xSWqFoqxfn*ElqoIbaM{;3ZkKhfmwoxvbUBzYZJ2SH)m|G(ZGK;G|JHrB!;RS-PcN8l_P{ z4^ZHxRayjy*_c7P(r`MbA7H0>+NVJps51_k+16UH<&d|fTN2`1!ev~_1ppRWAsiZ_ z*9HJ4x}&>!g)dtDTo{JQVTK79kONtQh4wJN*MJ2XpgrPZG6tbI#$!N6WE7%g|4t@l zR%V*3`I-SBn*m^(>&BwDS_JpN9s=PAP{AEy0F7Jrti{%k$C|7eTO{%;Yqq9qz9wuE zD1G^d>Asp@jeVtCM7n^?6-Q`!5Z`<(wV}^kldI;$l zI;2AyhAv4d5fKCt5fD)67QIr}|1VK=wW9aUXE(4H8N@||b-*ukXd0*>Z_qw0; zyn6nGc{6K2wtd^bpT{Rj_s%}I`3OiwKURc30gz90x}F$A0lg&_YYyTgJGOELGCOT= z=hY8J%o6og(X3|`_tUGms;g4(2I%Ys0EocOw}EQD5zW@(Gpj*n4CU#w^w|o2x6gv# zrZ*O(yFvY$Do-2M#To^sg6GrgN&=e4PHorIdAI6)?a!k3W&@ysd|*p~rjzCl5iET* z*5Ry?N3pr3ubDBBi&fEwBLmB!@DVq_HO4+0(9pc7s8!4&pWwnnjZuPU!Cgk%is!XsEE$!es%6mX_GN-EueYc ztu59Qebn>1q3uRP=PefVcPwrCHq3lh*b0^~w}wVf#eM~cuI9ku_vdYSx4J_!+E!Uw zCIUNt)DINw445bm3d~{qSnA>$?&~e_uxt%eDUDnS8ewc4VZ9jPP#Wb48Wm_96}}i1 zR~nNJ8k1`r!}rCRgY;@``Yu?8hgb&IZO}Byv^N_kZeL8;D^1=DntaeW>2@*csr2P( z&=us8gTKmM@--knPua-) z3M|)BHqg(iG*lK~!jifp7rIzS6S3d#vHiGbyYQgt$Ku5gPuuyY!K*`!t3kGNp~`ES z7eo!1=wZQc^VhyxzFM#DTmK%=8>GG7SHE6x$zPOJTN=EvF1GQM<)=#9MvB^I1>2^2 zgV#V7Pj@iqWH86f!q!+Y4{qV|J^vDQQSzOim)plYI{{HUew{l;54LI4@Zp=-uUWhl z?0X-Y_(|>zv1Tg)>{6VIlDygbTUm;N&5{x!lGkv1O1NLDDhHY&2fED%2Dk&sB#^{1 z^UoY+!DZLGs4KmpY+f7`G~g?BIc(!ObVLt0Y*8$iEfCtfWckZ%buF~BYKJ!$5AE+9 z;fYreaQrm;m|hKD)WSBpOxu(mVIce4vib0i3dh}$qlb4m@3Z%j{B2fIF6Mje`|vy+Hs#x^(Kl7{FU1$^OcGD{4fqnN!8shMI&vNb%jr6cgNnEytQb2 z^YkjJ>`q%EA@I&78)1N7e)8Nlr&d0o>qwBLFE#_rO7BkePF%IB0OZSWnRDYSE0h4j zqJL`dYjnznX;Z*WQB@r$1F)U3+ZP(CpHc<4XOFgACJlLJKWDt+*m?$`38f~0z?HO{ zr|Vb~mFkbS=IR4*6v}v+Pton2wd}?ffD`u&E|qL3-NuUx6LLI=>%SS6`Cd38Ro~}F z&Re#CZ5#;54kR79pG|u3Vj0f0rGbR=O~ZWIRM$(tEClSywIhJr=jsHi*Uz~i0JSL$ z70E!|y&Os`asZK&5Q73tXYEKh*RJu@VhG4f1`|c-jb4g|O!(%xk!OzLDIh8cso$(L zI8kXhP<(-Vr2RRCu%=aQGB*x&_dD5#@*76dx0AI~G#MUzyUkGbBAn}9TG|atQ4Y`h zd|6dW!@APHUX1mUIf~4%@+`qYD4Ml%5H{wBN{Zqtx#w<-j1Z^&Ai2XP6f5C;4QiB^ zq$U5L;86I*dSRw%O|%lqPTf$52Ruw7OuD`b_DNI|6exJvS}dTR;ZK5sZrD(_5Mpq4 zlExpJFKITt+djH%mZb5BJajte-W z`xMLu<16^cPm1eDH=fOp+EjOtGy_<9Jbl4;{;h3@8=?d^6cW*}D-<{VO)w$TGg zqX02MYrvIDO4a%NF~~;=$8s>N$)0&IYM^3}%zfhcxRbuYQGHpYNGPIRMca2va`+~V zo75^LvO12Oz+l0e-KAn`qd0o^j+ z4M?S_6jinR=0K!sCEEUbP*2sNH{iRD8ZQ|x!u}p~_QhUb$CBsAeyk?A+};=eV9Ssj zl4?iEzF1(GOpoIi2{_W;6Q^Lm4zwB~AfDm_DyQGPNJU6f#WWZ`>wMkkGdDH(xnUjN z#Cp6CE~*TCOHWchRQeFK^O%w6azq}$+Od1sv#9>`u0DUd6R^yD=l9^Nrb8-tFi`V% zPwmf|+U>^(0MX5QVNxD~Yr~w5V-qMagV)k-!HBMXk(*jJQV{%>O$bU;W#~<|G2}#3 zkDJ6qPKj#IDCj{Bmh&yf!>+5HL{q;Xk2L}izTa9p`5aRya1Z!lj{7dD`>q6#r@|3& z3ps2+FP0K6<(a6)sLe%Z8bez8$bMKhQk_#QNg1$XIvb8wKC)N7UVhbXcP5c_uc&Kv zZzPEvl#ifM&5gvgiBEFE%4>eqxL2)REAU|||j8U|Q za?we|xXC)g&U6s!{7A}3h$=B{2R8$q1wY4ATo(pr?yS!6b2t)d#<3X+2W*CouYAsv z0)``mKed^JaX-lsaO>6qEx{fSzXR>V^CPT&jwY~~6|&uf>3|Rfv8D&?Nhhj_M-}Cb z*l;k=&7T@onVAN*D`Yo#V4B)%_7;pFUR%>pe@}u6rXJ^;JKzmz)y=wrahPcZW0KmcJ)jceX+z+ zs?*B$LtJYUO9xGD6mpZ>xCx*vDslPJ!a%%T(hU|4;xgap+^Ab~UwM6G``or&rAgu6zb7s5=NM8@&3J1WyHpFJ}uAKui_oD z?ec7jX+z1lweNSZG>K&Iidepx@JhCX=Sh`a{m?o#*u;h;b!h-vgkHu#kyMFs&S9EK z3{d6P6k@u8CAu|im#nRLVN`w<0;-Glv1R${-k*k$Zt_ed{`i#*C)-_U5~(mHPFi=( zp796)-L4CFWE`97l${h$3L^U!nHI{p)lrO3P&l;Y@gf+#Qa0OQ60ZnRs9P5Kt z#Y(KrW#J7>x} zkT5g zX~tt5I22h51c#s`5s7#}(ebxepu5UDMNsTp(Pp%dq26r4Yl+$2=vNvMm4iUk*J2LQx(DMNO{ z)Bt+{bcAkEgu^PRY6YHwBqvQFUat-|U4g%_3*Nm?%_?(O{U{t_LZMq3;h+71tt>I`Z%!5BSzD zsoyTTf+M>AIUtqRy)*U;8dj9w}op}9Y;_rCM%$S(KBz|Bm{*Vs- z-<*Uuo|D)kIR2lU#5wNb>;jKUoS)&&PyTWehyO1*iH-j~CxIsYulUQG0Ut3#SU0wbD{rlIiU-$5s#Pagu;v#P8BX0H!ZY~4&CFTDB zN#MrDaHCnckzm|_*V$nH#Kgout^^*Hz;##QdLQ6AZE+0^mo-U$6p2O+T&*JRvncK( z-@nO;fq?^)<-&hOiDFzCH|{+xu9y;6 zMDm}a#PK`ky3(}&ohXrw%Ty}O&BS0Z+1c5+_c*p$zz)4tJTmN5j68~jM$X&&W^5ghXn$L$j zcuwM!Tvhi9rnR|XS~g&%#Y4`C;} zw5-_uN~C*UBL2T{65Sw-dHOux-Zs#5A4jjUAafG&E#)nJlWp1Fuh#$MBo>1da7WFc zv~(1~o44$tRUEMNF!jbR_PhVVNeuqDqxv75#7kH%^ntJ4A5OxGlVBM?Dhn?i=}t?K z=|!_As>r3~*ic>a|K%jOgPBRB0CLTLa}s81wHoyLW`8&d3te@H{6d$5y~Cw>;cNRD zA6_+OHb%2#_fCO7oWyJ6XMosWPGWsEnxP%lk{v>?15yHu{Tso3(+>FYuW7eOMN+??dbmfN0R8r z0$pK#LU3XpZdwU7?ziWNzQ?t53}b4wq>_aav#y5|R(HNoxG}ZeX+#*YL)c* zZN1rRpEJEzh0k|0i$k^GYR+MlG{DKTUb12RDVjl$kln@M)cp?^N0ZQGIPrj@iaKM$ z)vzHEn}~`;k#eD&PNhItK8d9LIXp&5m7zUaDUK|MSg}ZfiF_YK%p#jZ#kvLvd4L*W zwE5lxGq?S?eOap4wcMR^F_UXQN|va0!V&LpDA0{GWH$DDpb45nS14w;|K%j=X?ev{ditGsAEyn*7fPj0_wl76-%O43 zNPmjC&Vs54zblj{+x44^uUnmc2VemhJc;;DLRmf`bvC&_p|4FzlHW$F66+1)!e~x@ zWdr0zNa)WYy3Jo0m@r7vu);`x0Ru@ub*ajkB!oAu&?SyV)7M~4M96X=tmJCM3nS?8 ztlV6lnla5l}0$Mb6Lkv$i$dCHp8T#~&Wt|?pMUodA|0gHmZ*~vCMRgs| zNhH;wA073Ef9o%{sHXuTp4ij;H0DyJ?NJZ!rV@Bk$;Eca-&a+4Sn46nEqXnrTT_0U zHA#p^h#VOag61gG=gyZr@YhpUMzN%bp#)u*Ev#prr6(VLzs99MZDUyV@kOJM6IaQ! zf^rUfk65eI>*?u{g^_fY1{c}t-kHgnX!-~)81&MU=nKwc)nmEWP%t-?fPr5kdWQiv zZOSJBG^{ZDueH$grVw3Bs8gw7Apm~gL)18zRA#D83DA!5AOjJNf4o~)S);ix*x#_K zgyug5k?raX6gRXMKU~#cY&{6OLI`S8`DiyAn!hWn=0T)%*&@3{LjSa#kc_t}G|8*K zl^B{6A-~cRYp6&CXySk3W)8VF3_?_o?ox4DU3}~};?0+cQKhzv4`yj?v~i>fRN+}X zojK`Lo7P|;t04}4u?$UJ15->6li#7;uEHrLP4(VesqC0CF^Zz~zt5E}a6rJwf!ce) z`f}!^jIPU$;_*#0P+~xSIQ_lh#Q#dx;rxBn?AsN_P5GRUOf1GUpa4s{^Epi z+v``o{Df6M+ORU<+om+n7e*Byt(&o3^-`>_0mh58R!oqL!|kA(BN&RO^qN3TCO=$Qg%l@^;&7m#p z;{E*95SfDS^ImRvU;4s>ph6D6ZPO;VYV5N$c;7)i)Jk!U;Y(HLXAxH`W-gHa2kG`f z*29l+kAIe$*f^2|e(5$S^Lo{nfs|d98)np?8AiaQh3x5HKAc_>iLM5cg=2H#l;VwK z>R0;EN1Z66z;AuazelT^jv7USfwVgp+pko@#O$NNzZK!9A_wKrg#$qga7{EdO`M{&4R}8p8iQ%OEblmxxQS)hEb|}*uv6Ej6Fm9-XE|9~%j> z2v0@>8enF8>S}SxKL6EI(dwsAX9XGz8EJLU?<0RRnt)}QP-)5F4WCd3=isg5fE`Qa z79M!pQ>j1Ru7jx0W4mU@h77wr=ASG z^rf|mxMJl7!UpKoL{zT^z$!=!5%8AdPyimr$pyi|iBv{Nvph&@F!bXxs;I7~1JodK z?Wi)oh#y)JT2oOpW4;L$w;B&``8>5Fu)o%oYJl{O! zVP0^UA~kL;D)~fsg2)c6Wyj_mJzii(_QMYD1n04%RN+Pwt)Y-QvFqT6T>vOf=W&9w za}q;L`P5a9G-k{D?Dn$44py;ubDue{yF2Y{gz}r7D{i-q&r8x<+Q`9NR4G-Rhh0(~56emU$M&KA)yp z>zsI)113AUJHpQ}=FB}&lXz*xu?1t^@nzd%KrBv4$@4SN9nhE=2dktdb&SNG9mV3T zQdFpuOU09yOp?D#Czal3r|^h^rA4hdr|{N_dRYifMhW#eqYu`e9aazs7oxd(&{&4h zb)4@rdE(?KF2Ved&(3lL-%}^vwR(OCf?4u{HRN1m*3ojc&y8!@eRKKn7=(o`XQ%|f zWo;_27k`Xb@}uX;B*ZW2xnBmPfKgf`PQ>>f`oYhvxGxw|y?U5^KXTvpdgc3o$LiUu z!0A^8`#g@nX-L;u@g}<419}tGlPHh0U@dop^;jdhSI>yqd^zE)t*L1@LHxO#ucu$L zgSoGv>G7(*{GWd7K+;?6e&doMMpUp<#gA9a>3u|j{j{{nxqR6w~#i@nKR ze^bMmLaCin>6dZm$*tYVA_uQNSOUW=}0Ed0*wcV>6S z_1NahdLC<}#e-Ex>X)T=Gk)2)pS>P~w@V0=ehwL6<%GcClH8y?G{j1+43N4LP8vyYV*# z3t;PMN~#1OuoQ>J+%@&3W?SWAH^2dhC17dK@64{bq z*~**uWv9jIz3-4Sth$K&uH<{wr)4%T;eX7C5!mvx5`|cdT18|Py zE3L79=@AS6;86_TBR>9F&?#SmyIH{yP{Bm{X&=U>U3w#k$)07$SH zWoXeyA^nQ?r}@1<--Z-_@}dGP5&7+aw_IGA_6&`SG5HaSyj`$Dv*fJ^^QS)fPi6sy z(>eH{R{A*8$1vSunVHYF0hN0CRg9!no*VQgcF?p={~M$!+tUTl>pr?O#{`VYgtSS& z#Zv4eNF_WRucvdl=)Xx|mT@@)Jpr7t#);eVRlioM&vo8~ZbWs4EB3Z2zC}t2zw0%u_EyJ-0v?Eb zW#{@%(hnJ=ud+(&-F>wl>{jDbBHQ zmKN&s8-5;8Z!F3fkA<+bm`CP!)HU->o8#?sKnM$QwRntwCdO=VT;JL--YVjHbDg=Z z3(_Wa4qS`B=@j>-69N9E&?e*BjJ)3TJI)tDmRcU!NKnz(7S})*SBWF(i1e&RMHT$; zt1tQ4ViV9#=Xa;^tR4`<4+9%Y;yP|0G?4wOX#^F$cnB4a`ZT!Fe*ImujcbB@r-Sle zFXHVinZT`1=lAzrSTfj%>pfMArez*l;#j%|3Oh7zb#3T4IYl`|%~JdlBNdoxe|)tn zy`eH*k+%0C6cv>eC)CBv&4Sk=6#lJ6Ai;PoqT#O=Vf`;H;-kkc2L$=?FnRbA4G&4r z&y&v?b3GkrJy5?*@_68r^!757ZXge6Ae< z%^DM#%fM$Q0AQHV?i&Or<{ywu`7M{|9H7s%BPRfn)(+F0&kePm40-kSchwJHC1)0} zgFZ&NZsDwZh1}@41pgorJmb+n5pcG0idS$DJwP&r98vP1jKc!laMF6XEPl5q7NF$E z3lX3iezz3C`F@ds37O2!W>rFO)QisYP{{nm!;~@P2y_A=LWQTK;1s&taD!p;vvSI5 zEDe~0XbpqUE|5*vlRw8B@4J+O0yfV>CvILO-I^c0BitRiSr<|PdSVCNxYsdmGwkU- zAe%sOJ~2iB0{;&rqC?^j60!ajk3;|f9#D6iB3y2?Y@FJho~lq7z9#&skEP1nq};;e z(?im^2MQm{Q~nqc!+(tkvA;%y?I+k8QUq^A1mR&(JQDFit`j3XVb(Y_);HTjR{e~% zBZ_SD4gQ7(4)ykcUBJoGn7fi1KUFP*40aa{@J_@qTfkOIQm~bf^vChsg=aL%f*_?1u3i6w_iN_fitx zc`m>69`>YsH+(kVedm)Tqa@>;$zLG?OX^4l1R?$c5l9FDRezgJzsdIUjjYkl((eH4 zkHmoQ5b+WZyG1s^k9;_H0g2#D)27vOtM5jVrG1%e3A*cGdqVGINPF^=T9@^w>Aq9`8ag;GZ)SCuJMgxM$Y#wxbG~!ryH#?69tv`Bj@>SMtwS zvJ$f}Z0S|O8(L`_LxDf5IM<~~ws;p9UbsQCQ^~5BHc+;*U4v`6Wt)8qtHs-^w!(9w z!VHAB2&34FK2kK!+iomUY}0mcf*UuCggTzo)BkdV%9XF{RbT66-Lg5|R`D9$Z}L3| z?(9%57~FO#O)}fb2mmk}4LE8Z)pFA)GnA9y`akta3OL!+q)M$l0yO!(Gcg-ZY;X|lS`8I#Z z0WxQwzI9(E>9K0kcg3My(#3THerk}|A14gjlI*|<7bKLozv~cn}>*$lw zc48^Lu^rSL4(<;6tw?!D$9Y(u?T$(MnXhu1duPu_9OPvOy^4fwrY`n2ACZw8?kS&} ziJrL{T}a_@C!Edn5&nPJhzsMfXG0fdkJ_hphGuZ9cX#&EvVTW~z*+isOyLim22R(E zj?wIgna!8~;w0EK(u|kYqR3g5BN$BV5<+CTZ5vK70|fD`94_DR&beALmjS1cpJ@U1 z1)txP-wivnW_7k(Wm0}L_f=!1y)SM4ND~;%1UAh#X6vSf2ARrAIwPFpk@D}@D*aRK zEJ_J#y)Oh)u*?dIPq;VUw*BZVB{$ER_S9RHk%WV6@A>#iA<^ABj5Wy``nb1BU$BWV27kyOWrzTb4mLm3%fqP z``-t$`9c~L7T1uo^&tyYLBLh-XDqPEq~Y#kg)>nIrBZk&O*xW)QUfk{xO+gwV(D0sLuf)E-p-IiE&i4<+vNj^ z0tP_QzHvRE=tRVkz*T8)X-MeukOzuaGkXS_e&#P=p{^64)N7%Tzb2N;?r01=s}u|o z+{bdg(vUQeR(&|yEB?LS^c|B*;Ei%w(%jZWegIyOZEX1FajECS0p)Eeb8}0c$5P)kSg%-|h(tcK z5Y&uqr4R&s<7tWA?!}JBkeE}MTO?^-yBWsko=uwMitVe!EG2O>RavrMxW`xLk{7 zAQdv4o_`c$P~nj5^P?7-!c#i!6l8LAluNu)9!?0}pH2Fan=*5vn28H0toykfT$Z|) zlkK!?`0@kXuI;Xx$L@;Qa_e;ayHclmx54tl{>@KczFK$3u^{E6f#Ba2o0v?k`u2=y zuX>NRfbg@)y3BKCk21q;RWcpc2v&r&g_K}S9KZpbe(f)V#Wt=J@(vn?!VS7A1mEQ|or=caB^PJDin~S(h zDPW7a_a2gZ`2gi%lUo$}qek zfmAkDbPV!(#+>=GOYvO#8;`g+*cw^z@yKn}DeML_?y_1HhXdh-Q$)7>qiFf2XvzL%iV#^1POwR|CZ3ZBPt)MN^oUUz z$DVudqLgEDV`KtXu6%aZ;BeoIk{w=rC)KSgu`mc!*>xiSHG`Dx=858K(5!4p^l5is zJFL-GKKkEs5=5hL?;3SBa44O+)abKU?caFlsX9FpD&n&h=LE2!EuqQF>?&d~67y~~ z(W?E(n@tZdGGX(vaJe0Y9|FvI^6r`64W9I?Mq8NLL5Dwv1WZj0Z%7C^{_>r7 zMSQJ!rx=Am#val{7WDg3KY6B|xv8<1Yq&=tp7DqXU#6lI93f=SHD94}^7Emk)znHh6}Xpkh|1p*KF zx-ZQ>iZ^Pg=>bWaD7w--LU*iQKy!ESry4E?q3dv@Tpx$n`y#h3$EyL;5gHCOO;=n! zKHn-^HZ`tLQ!3M@Spfv70frB44}A?j*8X`cHZ|`a7#Uy`JTqByr0K54W`!bW40j#W z6w< zx`{$d{K0zt6h+c@eWISuHxdulyT0f)YFkmhi^EykV_#i()a|%O@n1=}zB#`q#ev-3 zT>Ey)RDcOR^n5`@=-5T|yVSyaPqj%4)dk@KS-N{2DhqXP>P`1w&GlLjWOAbWa1)_D z7)qhY6Uj+>6D$9NA!(@LK5r>QgO!s+y1i@i2V#s-$~#HSj^Yo)m#>GC=#1Z(&@ash z){Q<2wxZyFMV8_;JxcAjAH$*aQ~B6zIQ;Sn{(U(_!Dbl<%yY|~e=nz)Ju#Bsc{p(% z|I>_pa`4pxw#^EVbg(g;eA^_P=M%VLBcmYo%zN>@pYT=<*v{4h1`EnWHbubCA>pM&ze960xxL{LJGGOlb2WjOMod@PV=`}$2l`FVT-BsW0 zvy4T<`!#!wyY*|cVdw4}AIvigTz{{X5kC6#oXXueQgZIAwP%eL51VI5fF;5&7F>~_ zWbenGu~2pC+kZ^$wWeJC1I|~wFQNgx;vCS!fcw;Whr&IeZ*J{+&hJX=4eNBti;n)h zp+vP%R^O6%2cOPuWC$ayeiZ2TIcmEtxFR=*?gt6e6hPh z^N$SyRM<>4^`>LlzP%$OQ$V~|sP|w{NK2cIQyLg+Ecoj}&`AAH7vjo)xDa3_m?kRP ztXL>kM+wL7*k%f9ZogU!J3|)QNjLd5$dY|LpH@m*`=dheDYk^7{;Ckp|ELf|*ng=I z8~>p~pgGYmn6ji@)vvwBqOD4!7&?lr^_ADBNaNHx53XTo)qyRxnXb=kqs<{ z6cuH$8z!1e_z+cOb^_&q!$eM^7vHt(_qT@`^T3VUj3Tt6U>(oukS26TL5J)6HElhGw)hJ$TC%rSjPRsS6^O0-Z z_19^3<>HF(B|J1pD4oM_v95o32soaH*d?U-Zyo}wg6AP*c|wQ7?Emr*p}vHy@klln zov^^RJ$cpd`A zl>C>6U{DV&SKb_JdQGeIv9ck|v9wxBr<=PYJifo)mwW~hshHf~Gk5)lYh5i11+nAx zyvNrE`?Yxbbql*eO#(!$nEozWwFj>Cgn2z9+zq3SXw!rKsX)zQeiTjtNh&jJ@XU8$ zF1~DOub1~+MkHpUHmHwc5aYI;sPQqWx$ z43DDn9UB|(Icg*R7cikyZ*}7ukF-pqsoa1`rA92UM&q!QqG&!&IH8`J9IAtj^7AE> zfI}Wm_15#7sYgm_B#h|>$+Eb?(sZNb(@^{qW4p|~iNgf9u+a}ZBB&YA>{w_6%-keM zV1Ai(kr7QIi~r}om0CU47}Zo05ArW3Bp47UC~%4( z6oEG;^bb{y?dfpqUdw1>;br*qP$PnG(WV%%|3t*1ReI7!x|P+Ng+|$wb)+ zMi@d76G5t6Y3qDpm|=e2_5Imq!a3}fxfUK9_0jNiVtjn#ldc8e{7mN_IFmlpyF6#uvsv6;6oaFt&QBX|6Y65`7UPw1s~$ zPkzO1Qh#jf;`OcXTiIedV=3__5mrS}^6Un9V?yVPlQYr1Qd_4+TR@+LcDTyK4)0no zoNdX(w4;p}vW>)+2(H=H@+`KjSS1loN7U$VaZP%sMc+&Vod(@}bz!@E5ks(>VuyS) z`TLHR=0K*iN$47(%~s?Ur{yaaON543gN?;P@lE=EcAxnkbjL!aVoc1y^Q-(Q;ts0} zDf@4<6e*GRRnyV8(js}wA|EB|CbZeJEsRkY-c6BJP{Y2wB4&`TsX3i87lsIJrG?Qm zEaGyJE8JyF!Kg@c4+pcf2*$E30SkTVvb$HW#k?;dW}QwIDZ4{XXP5K`m_Xx!33>~M zS05o{nsrefiz*iKvYI0#y{KQDksWE_PAo^mQ17^iSP`V$Mb{0Z^fM08ejZ>vec&(l{f6z^+lX(}e~k&XCVSiM zdjQ2!D*pECn;>r9QKxAdxsA5{V@wcwZ_PDY1g^=MmQ7!M2dxx3 zVFJ6fYW!+cgFna?e(a{g#EPJI@XW++q`%JMBc4?+5f*>oz18j{6XFN%{^XC~tnb>k z#7Y#A_yf^ZILi5@6Zy9viBn;gf0+qiL8r(|ZWrGOCKOc6uH~`sedmRH!G+E#u+Z}p zLQ+f(?bD)%VH#%Q# z#Qs?FKYBs#@H(Jzouz3dMb<-e$+i{BT5O(iMdHPWqnrwGin<2u#}FNmLVz_5n0^#To5z;h0VS5Xcg^D z`0ykQ#DEelBC;so-cbIux!~Rr?6R|s*6U2fy`hlD-uSWL!qH@r#2;$C6dh0#9h64+ z_1EUN&pVmKnW{>88xE59X+zj`DHJN;sF}DByO~XgBdyV&@=cVAK={|=9epAnO#xnW3(?>EC*WA zlkrU2GxFO;jHS1%|H85wG$sf1LK zDlmjB0h+q!l;UaIGJ%tGw6`6Rvd2AHc6%M4!%zLXy`oZyYyfk6Hxqlu1AFjdNtH<$^6Rmu%9-@fH zCL)>8(O!6LLdWOnqKNk^N8FaXkIR;rA0?qbA39-sO>^LQNn}N?xAgflO$iP3W9O!D zD8P>0QoHXf@c86MmGfSnZ`_9`!h7rcfyehn?*>=D4})uajYA)6bm6fHUy0u${P$At z__06qyMJuTaz^0t$}f~3)zJ6UIplCv3l>|c6A!^l6Op`0(QJ5WqFW{3=#=)BKUel+ z|EvS!;l!|-qvHFA<8&_3aNls}zsv;s4>QrKwf3o*_2e3bcHvp=j;D6BmxW@)uQDHz z)n5rRa$;2hcjz7dF(!DV16o8`RR1w1;1N!iXP>K2Esap`@}7iaf5m5yjZ?ZPvt~#h z2bzaQ;L2>mrPm_-tfpCH+=80@GOAIpkx{X7XyAiiZOD`M)mKKmXgo6^y%RUobiw^Q zYLp$OdJ<*+D0o$6Ym^kkE=MGcXC@f-de|=uDIdq6{$VB}NWDF0n}angqUr8G4%ofa zX+Cv^!T>PzA5J2Saz;@W4Yq2&Yf8;oLC~ez8qWk0a;^EpNq`k%g&vr4v_0p0cwUmT zkAYvG-QS`<*#Dso$03(C*MIR1W7MLlgZqs)y=T@%JZITO4x5Zn@@_s+IHjYJ?uwhW#5aT&}9f60j)wwmf|+jDh3 zzqVOF{v{_oUo%O|Y&7*Oirf!oLeV;0pmMrv+VJFrR{E#!SrheoUz8jM$9amvw`ZHa ze0sEVsT3H|$_8+gUq zmm{hvw45WFO=F3{@iR{mMw?TF;ih>A_gE4?oiiko)e2#^6cdr4GoHXK?Rx{hX_Cf~ ztV$xsZF;`>nETmTM0gBHYvBIf7-LS$uXe12$iLzQ3a2G7Zr?=$Gu53=OVjMJ)7Nl0 z$a~{f_nS8ZLi}IkglxR=3dIdgr5Ni(bwZ|bOhgq`3&%}1Q)?}VjlDMQX=cpb*CAH~ z@4WG(ZZ9m%^gmtqZ`f6Zvo`<;ooj~5*S_apv#6UXDOsn|dl?bf9?t6NjCkk%>hxQQ zs)9?eKv4%%!23Ig2eQU^abh_9Q*fEyo%g-w8#X23F-Sd?p7XsFBG0LoHZ$yz&X z1-ENPJLj25!yeIRaz4mE;zXVc8f6dywrEa+V53d~F%k$X7uL%3d2Rq)z(F_Xs6mrP4tCX5a7202tB!vfW1 z?)W`ysx7o{7$qZr8wFbF6-pOLTe=|23wIG1wuh4199}p7%58ncPxlB=HO9v!2IY2J zC~Kig#ZzAifW$d9`H6THk$^2^fk^-TS66nO^M_SF1g$%dMvj>pC`B@lwx)+%x{prL zQtsPiw4JYCx_|hEv$H!?ztBltDK2UIHMZE`IetXlhR_m^|IKg40X-I*>-`sQ#Aw5No4*n|nOE19BK^eT8$MzaV%uLuyVjU5Iw!jZ-wbNd~ks1ul<6LSG4Mg*V z$%_Ttub7l)Px5)B1te|-a*I6vodOeDCS7acrj-7j_{8}ut!Q%Ic~Fe&+IVk7?*8W;C>eV)%~_+CSh?2}6oigsK~WMVKvS+j@`$TH}t z;SVP<6tw>-`!Wz9nn8tzP*-Az=I4O%1e&6FdHyh#YTfU?7uh( zB|+2Y#p4AMpWhh<37X~MISD~?O1O9wM{aSn!W0N@b|GlhCOBE~?DKow+wC|#gIu8n zIZ|uFly(&)2%t|>V?KmK`E|tLqPr`s+ryD`B;W|&hHykcca&0bXq0qMWnp5FkdC_^ z{HYi?Yd@b)Pm**v+J&xwZ_8C%h15F8!jASrEQ;z}U?vu;N{}aA#A1?kXgO$3 zoYl12iKq7_%|0rB?P8Kx(Uq_t^Deut2RL7mOz`axauy$xSZ6@aXSF*ZXc&90M@jr} z&m(I}eyDonkwoJ7t_u5HLDu_YO}9zaD36YZ0kMO0UOyQdG+z?rbpqQOY^YZlO| z^2iY6T~e7f6kii6TtdfznbvrRMcCQk+>6JgM~opTTOGJM6-sjB{f__@zxv8I`45cZ zW>l?1KN2uIQvHOZp_865FdKk&%1#XEULuE^`65=*(vf1S@QpSg5Qi2L}t^jUEM&TLJ1}1;K$O!b8*9-o6=*Mi z212wv+>U%RoWOPOD-qZ)R94H=NFz`U(cp zG#i0(7ohTVqC!MRady+*maBvOk1XM+wPU+#^}0_>!Zd$4+n7a;%RDsq3IwyMi}P<* z=E&MheybSvZJGVF=0xQrC&|Yj!`LufiKGinw8pO%1_4+Fk+P&9D;p|6_7`$|ZrOTg zmY;uDyYuPo#{<8uNBdo6P2&-)CLTRguWJ)o&TDqF&(2eoOcu#zkDEe$F~k;+)TC@c zws6@tdIkiVtKVK6kV3MRiL_1#fRcFIsoDr05Jl5)E@U=q(C(jfN&LL-({RW#f;~Dm z@h~8PIrH$a!|7|u26hWedPjL4*o|}Ww}czx7$HNLPRa$@a3AUxwzvFX8k@buVJgRY zyKZf6v`5U&VBk(D&Yn@n_3oFer91tX^(%4DLSGR&9BG9hfuiJcFp#w#?Bi>6m*F=P zZ$z)(q@-gnHr}T)oc@kjcO9r4>NeNL6z8V26$6f950g9B|D=RHd>EL)g01X8IW4m% zhrba}I{w+*Jmv}35`Q)l50eTp#J}qE3hT&{fXqnBILRrUK28{75H}ep=EV_YP@Yr^y*S%L< z`r${E+rq5IYe?~OotBsgB9GK5+8ipa9An3nH=9dzhLb9^+AO{L^rj;#tapqZ0gdyp zxCTf(w;|h44qA#xW@=)VNe=yUbylZ-R*}KxRJ%{a5KuRx_~skkB9vBS4`RWV@3ftR zLYK4iFB>71%gTme7+exufe^@Jbol|gCllOEdcrezxsNpXNqYEgmkG|3OLB7I#ksU} zoL}c7m>qTV8rzq#p=@(2Mi@JiHwfeY|A)1^{)+1F|AoINV1}Hb8;0)gl40lul~56e zZX}czhHeBzq?GQEQjl^80YwoI6%dpXDWy|n?)hBT_j{f1x$k?OpU(Ra*lX{#_FikR zS3Do%5~K!_q)VI^NI7z+aJ6MZ1P{$}+yp9n z-_BdrJ6$!CaPETt=tA>JzNk=S#Um^-j3dcSRHzMU%M4Majq^ibc0SmTWhF-Y%X@|j zK`5Gw303(Y#0;5urw(4y>54VYa%oYk z44>uWs~ZCO8A&XqS~Rn%Y)! zpg|%ut`4kD=C-_|9#z%wDi8fN=dvoaet(J>FN%lS*0s|2c*QRl>gAf` zHT9J1VnTY-)hD1zkWujZQ*C&&i_l@5fXtdlT`8aE4-xGWXT~h}a9v2Ro0R$Cmm}iR5a?<^8f}U%9H#+(KJ`4Kl z3Pd(lbF=a*?EhrEf+IQy643QP#+x@IT@!iYXxOzhuKzHZNDC^{jx}{ksjCU@gNE28 zh5ViuxX6ULyH``LqZ(_X1FF$bXN@!rOKzM<{+cF0aLL@L!SHyPFR!KE)KB|7k9ZQ3 z{;eh~$SpO2SAXKI)ag@00`0exFh1PN3f&T7Ldpt6={DBKjbv;d{Q4cfC5DOad-d$E+y<5m!aef?J} zJ!P{nTSU+BC)RU_>kuNtw{Eg)@i$ty*v_+o)XSQBtP#9O(rlZs@A)jCCNa`IQXr06 zAC}xV1dlLZPOh!Y7Ol#yGyLsV?OO`y)<5qfB$ipNw90Iqb5upqFBs7SS(ecQll7i2 zs$W#Suj2gCMY_Z!_M_X*t4(FAmJyoEtfgO|tuv%qakka)lz+I%wK1W(yNi=#aZm%N zH6S9^EF%`qsu^`!Wmti~5jRnsyX_+(#^@uK7PS5C`2eCHKiX%|)3x&Qa#NEXKL!Y! zqVVO+vqk$t6Lw<@0%j(`kx!SU(K>mPObgpOvPjNN+ zSIFN?!Rz85&NodiMdLPcNp;%>dG6bBjZ=L-gSzW@Q}=%GA|N%W@ecC!h4>3sF?^U1 z$d5u8TB}bfoSNd3@wTB&+3sKb1Tlg>f@|cm@$3n>kg=)IR$S|{;Tt*h%d++^|GUS( zh2}9r%jDje8W1Zq8cFmgq@o+cB!2n)!%wVdG<~gF+sdt*&u}-}ouuoM_~^U!ZE6$$ zVvuLsmxH<=k#4qIN4D{qe>T^LgalZTcxMu~)j7}q!?bC2InPc8%{3pZ6XeVO0w4cY ztI%~P(|gA}=vnKgWGw4YGbiMtHf}OQ_m!^iH`<*8Pj4E((R7A5y3yDxJ&>QD#ddzP zli&vtSx^7cl3n&`=Xv^E!~qq@+Om;oUrwo91xcaJS$<}1;^GdIcZ^DpB*`6ap$jC3 zuM`Y%hrE7QY06NlVbiFAfL00f`~3Ua22XRl*lvQH6lNDQ|H%(o_DMr7f!a$FLFab< z)+jg$q|Bx7wDTyc}KIAxq)83N6ZEe`wDM`gf?EZzP42ZWzJ2<-^L+1Yc!TRsbz~&@ z-0~Ff1yVNciKw0~Yh#v}(ST~ZCgXIBB96W4UCV*M?ypLb$-W`*JD#b4JJOOO{A_~n zRS323F^qf{=91_@xi7i`R5)er7<491y{JgSsI}pEf0>V02D)p2qGZSUZ1_quRm)Z# ziWgYzCf^%CSZIlVlJ#}IYUI$8J=65T*L6ENF|~5vLtCk7~S}f zFx>K%syUe3^4=!*e17D1B@{DXn2SyXnwIMd>>Z*{+Z#4m%<~`JdL?f=B5z58iQ*fu z{sFRH(BvGIw?BDqPmsqxWVop*$M*3yq-OvjkGZjvpi6-0IkCmiX!k_p)ySS(F%fbs z?T^)6UbwZ$ExqfAW?Jy<+8pu zG6IQleFDamRUK$ie|*Be_0BC`U=lGA%oi@Z9V2tA1b26$QJ>wEozF`vDmb9NBlX2W z$?!4nQ9t657McEO93l8}nH2fuj={U{_tP6w>130xu_bFXCM!;f5WoE#0$1vHNwk?; zMsXZX1N=+P5NQ%cSoyPn!tI!?<&3er4+3eZ?hYcN`!gvd3_W$} zT*?`Vp+6K(lheN=f?huUt|SRbU}CyEgom?V_bzBt&PnYYk_r~l`V80%Abw~eM$d}s zL!bQ70aK21hm72t1_>I5a(tAoQuKNBYQ*@CDa?lWJr9P9o+~oGth86L#u`Y+0m0}a zKEY0unewW4SNPqqZ+Agse+Pv#rWqSA%$7gD^IaP$+uXto3UO^^>KLet)4SxJeA&tP0&TzpEG}0 zg2(I)r|kEDz2??(_-O1!=d~W|^YCvK9sj_y`b7$Fe;Qb+X+DMnhb1KOFvw!bN% zj4W?OyBD<77Cv;19Vo4SrDCyN*ARQ~*l5~0w)xVoMnKztrcJH{QMI< z6&5}d)^Zn+1G4UpT-JeNr~^mzM^s#vh7MFf#q^=^ghoLGfE?v`vI48bHDqiJS5eSZj?_ zA`Fv=;MUDyZdvS4W|DTzv9Tal;F*;p>6NofG_!e#6;uCgm$6*bWwf6%5#Y_1zWm|* zx!={SSR0Sjz7AI!Xx$nQWLjPO)cyF5eWCtea`x_EDGT_(IgN;y#bTUdPy>DDt&o7Z zzMK`u%X*pSiH;|ls_batpBh(6|H)KS5n99-d>yznsQE5MkqTpMcKrE1uBUYnjPT8u z@-Oi!H9Uur<0!7pZ6-r>97~w&cIG#xc>IjT0}rasG&=1$-KzY zDWRUZ;Q|+MR{n`HlmV?I>K$8Xp`;Fz2^C4kyB>}_N87xqAWK6?Wi)#<<<-$1TQBo| zlHM{OW;m2S38uPCS*?lX(n6su?%$%fpEFn^@5-O@QHKbplNKjSsOZPh zt)6zodt`eWWFF!NGDO*DY#b`HhGuF^;@_@t-N#=ha@}VJ@UgBTAnOvH2^MA?d~L%C zCB5nZEwyoLwB%t=A9qimY6vae=_j+M+Nf+%kn=C3MH@?}31J7Rl@uoC_Q%L>7YQ`Q z?w2HgC`=k=VAJ#)W}-v}3>9HP?r6@ik<1aA#6|WR7L}71ZGOpyc~$KngAjHhz0@CA z4@xV_2;}8JS+iCKeN%>ASbgepkC3@$NJ0UZ>w2Fz&$eMBmK?(Gs9uKiq&$CX z5c%H~0VG^hY&|u4Ta)dinKW!|z(;sO58?6w)tB zX8EA6YgD_(Ye>&XM-~jZOB`5ks9WaPTh9_5PDt0%Ae`3yctrAIIS6IQ=qrw% zS?Dt-BhJulee$97o|y7UN+4ybWFRT@(3#;RB-bFDFB^o4XOheYH=36Mvg4q%?F|mhevOtVbGf{UGf`Z!5b{I z@7>#Ky0)0OgeGi{$ah{IZ%gQ^7O1&VLA&qGM7wFEcJ30^tQ)k&bN#=tVL>N~8f1;7 zCY}2DXm|{+S~oGs9c z$*wF^nca!y!_Z)4g(#%KX>LWUEI;ezW;^xMW675b z)^VlO4Ehf?cAZd(xns9Ue~s8)=<26b7&R2F1t&qFPlg1ER_NU?lDf4|n96@4e{HfkQLLzxWoZ{T?q~V0 zqWx=y&9($l%^RGb3>Fa?-~; zu)1*JlU;E4(!zG|Na44Ur@_6C(_?R(w0-V44mLC*4ht`i#iY6q_R~D|izJ#gG_oG9aPe(L41F{|zt@10Ly|H+@pCjq`9rf$vmBW>BcW>|v z3aQYt_v9e_r`k8wJ14@3teBA=2k6GJ@`u^`cPol-Z5Rm#e|+-$x4Rz4?0M5+>H$+= zV`>}ZSICfd38l5_&U7w?P6BOvO#IuupzR2Pk1Ezd-9yU$_PZP3&ll>~|9jrJK+DAa z>egccX?~K529(*0kte%h8M|MFX9HUM*moX%;Szi6j|jjo!@L+H8h%7(BiYNj)YHJ= z`SFkyl9ziqYi$eSTz?!A7P1t_;V;~;5hpb@0q4YvWe!4!bz5Ag*4yUotPdJ<6jn!^ zlW6JlJqq!*)ox+{Z|buhT18VH);)dV9wRp5tzhwmlx?K9&j*WAOg-1=%%Ar?Yi9ptCk=`x~g(`+BN$mPwae`yAB$;2vUg4E5s^f8du zx76AWP4Hc4i{u}>#<0s$c#uFZY5?$#W*I^pyY7&vcfv9Vqx^JTaBei z7AW8c#_eM3v^+$UBKr3#FKMYC6+xSP$qWv{0hw6tCM?u9iFwV7yg#$Drumc2vsY&ywFj?Erc(kYcm#gJt^KXG!51Qf8aQgi{1`tLb%q-U36NeVOI{SQkKgKMYtr!m+w zWtBck5CekHqOInr8ZnlF4VdiYu*BXmD^f8j^S9{|#}N9yBdPv$Gkv_jx@p$AFAbBV zBltJDj2}5bSQQx;+oR$3qO)uskR`UTJkh86U}CQSbD6@NY{klJl=mNsuJ8Z>i_%r3hzyU?jOfhV zYwU#|Wi6139dD$oWz~;Hg&PmVt}pT}5#O?nJV(zecN#g8Y_-@-=?~WwKOJbm-YXcy z2!`uZXQB(vA>b0T$=}z|M-!UgGd0G>G(hc`{tWeA88LPg8Fejn8MX{M7)|hXXQsxX zp3n&&$x`wkjtWgd8|z@aY9WnNB{YCUdL(1T0dwIk~(COodcufzQTn0sDJ09 zVYR=Gc%x27JEnV@=Me@{0$g3g%kNR}Mr!u6UN`aC)gw%sv`Cmz$tO$QRg1@fDq0h3 zN<^~uc-~Q~!5%5pPhUNe)z>>PSH6c@%i#+z<9_~;eE+SHJf>+|RzuoS$NH0=j;x}p zyp_g1vnUJ+a6lDQa^if*LyPA4m}8PoYtBV)bVJTc^_~^)b3p|x3xVo-!8tAOybMD0 zk)iCPn>QF#6hGNeG2Cc;CMbZ@YNH^RL-Wa&Nqud%d`52*WqHlP@>Ykuh2$rG_i5eq zk79z3hf0CB8$Vgb%VTDrYb+eyu9wxi0XBGaNN(f9&5sd@={KmpuC~J9Sa12+b?V2W z9G3gxt$U))S5d~nIAaC{9@7o~7|Yw1_v}9&*|*UyWje_(J4&vlH?ak)M1GM1ChSYlBdU=lk8yY|^F__N0mgL|8$dm^KqpaL)JRq;kZ z&xesaGtlDnlQUP4%-1$2k)VBvT+i3p?k^2fFIyA8p{0uHxO>_}2nAM-&lv6uTDhcJ z`qT$u85nqVu`H6ZvKEKj=JI#mYUBy6f}!uD@dN$H3q~IUeKI#AQ06ctvQ9p`lBMf7FX0UaL@0Zm1cPU-x75 zlSJ1xMUit5a~D(Smy?imYp^0M%}2%v#8l`Ak4Uu)IqF`x-i!O+6+>rFJpXKYD`!U* zGTj?w6n~!U6?M#T?>GX|83H>S6rO$uPOb=_ADtm%~HnE zPDwsIvMQVWDhi@@_E1wfM<+DL;AM`%4d^i%svU~cXN)(SN&kNO==rmx8v{moZCl+M zV_?yEhR5V{1fd2c1H*yK8een=Yd!VA<6S9y;M_>ji<%#-@ACX`UImNKvc%qqbdDlMW9 z5Zju_6o6q~lT;!!$U`xnpDnk;xOY#@D9=Nc&7q^X1(yvk#GQr7)p$I2LtqpEJZZgDVCF( zg>oJixtjRAK3weA33K-&xA3p6gW;{oojq6>t>;;*kt@+kf@9Iy3@xeImlc6o9XbRgQub%F}uO0po zM*3=c>^Fu%Qm?tEX%g8P{yZ8@J~D}(7l^+YO)q+FZHu?J&2Wl%)7|o>R88$w_{fOW zh+fazMqB0<+qZ#5_}=g_tqXj=+B*aPcmCb4CohISMvOPYJMYgA%@$qE&%YjHAJUlr z@PU2UNb$q#qG1Ai4`N}M?#Wm=`>n^1Cn%nDZ`h7A-JgOij0r!X3!lFd$v(B``(dSL zO7{NS_eIlh!r!ZNyr%j)Wz_qD=E*0}!gN&l$E{fCbw@Y9|DBVFzdw`QJCpu*hLH6? zIEm7QFK@upOCi%PPbS&ar{x#iu7cTm|907!e_MDW=8MnwLVZ8F|NX4@``^FcL01;N02m_(2EAOQxw7>4$s(2A6368dQ{N&t zk&}43Bz(Ed@NHQ-a)rc>C`zoHEv#sAF7_^Rq0_OHC8YYOxv2Z%HkUv07k)TIu06QD z=5e_ezp&;X`7`|X&-f=|c-*)6$o1sD_4Ld2tScLjA~*8;HjGl9tEkJBamrQo$<|$w zYPuA(UF6EcuJ-nk#x=tGzHJRgZfo{!zrS3Wyz)yr^4IL;^1|gW0{4~QvzMej_zY&z ztv{HZvzVQeft@4pt_NmUFJ_m5>qG3ot`25TJ%$(>uopeBXKl3K8?#?JuwMv1c!W7n zjX7Xr+2`dtygzWD!8I5abI1)o;=mk{rGOaHKkTc7{1WiaD?6I)@CNKZ^SE^3|VS!k>PP zi`P*XZ;ES~QFMK!oL!}~HhQEsrR?k6Oc)E4c`4f_kqiXoA(u%;m$(eED8MnTJ$!)_ zq?9C8I`9uCp*D*8*b%lMLZu`WYpEReG6tpnsqtyoO>F`#b(yQ=f^gi8yjeD;jZz{f z0n#qA+2g^bv8hH3wOvi1et&o98Urwa$*G@ z-8z|oP2`M(J0|gD=sPA0JUx9ZUWeiv69wRV2s#)`<~R?9%iaeBTz;8?rIBMgSsvb> zoth}py3Ug(14fsplP}dc5siu#bD~kHy!UoLBk_c5=e$$!h^B^nji1~pADAW*={ zkqnn>%R{!7ZNk$|qAaVOG<-#deHyN2L#phY#lgAZlIdvyp;ZFM{R36-Q2iUK$mz5)MI|^GDbsi+CMzH91~A0*oWK1J zd2(IWOu2Ca@7bP0umEQu0r%((E})@yMRTRO3<)a^f&8Rho0l4X0GxuiG*j>^+|NHd z){A$*@3Z~xwApuffSSpqGb#YuF%+09FD6QRz7W^s^S{LuW_GTE7yDHnYx{wOX3}(; z`w6JDl7T~od2!;Ea3BRA0Ld-z5j8!iVcYPvDQ;K5_Se9Xinq*=@Usgq%(Kw|WH(%R zd5NVyZ)uQqJ%pBr>qMwkTjckUl%qtfROxH+Z~5!56{n}g94QtX_H_`hIbzEZv-gt{ z1i~&v-l+OGTcj#7++{wQzsSN57`gVN-gck==!d0A);1s z*9as(N2uCj1-`09B3TKx6Q#>(s?;x6b8cn4Tw5@VF;j4h=r>ZZ`5i-!F}k>>y_u?L z8n*h-`trjMoNJ#l#^i3>hby!5e#o6Zh~&lQ>+X!6{hGTh4kB;MFA%I{52&(AQs;Uc`naiE?Alr82H4X(G3gLz-Pu=~3&vL??*^qmPV}n#Qn( z|AAHkfXd%ev-=#FQt}(?7}?i;3GzJ-)WMyKh8Mh10IvUvw^MKIg+vHkW|{of=>UO$ zY9ayFUrHSc$5Eim8SGAD#2TWz#K7289pfdYhj1;H3>v^|Q5Uv8!nMZ@h5S(EBA8l_ z@Wxmqhj}}45k_0}IV#9DYoM58>n<9P0Y9!3+!dZrDL0GYaDsbG^36T6f=6(+;v^lF z3J@1I1}O3rU>Xgcdgx&2kC?(~-AHu8dA-inLU+4G=SoY?3iNQV1UtC$95} zkt@zgWR_i9u5b|nOlCfkR;(?bBD(4YeY8MaNvsNo>S({p>U$@FwzQSIu9$aZ#BHEK z02aLl`$~oj4*Hk}0M#=2FKNwp%L~p=N3KMGfXDsDu5<1AiOV-8LIViRPXTiwEe>)E z@iHfLR|Crw1_})sYSofEg)t+i$lUWrfft$BkDC((I`K(ieE!84HcMI1cWECzjsabGXyYkZ&&eCAGPY9vyPu<05YT!O<7S0pBrS& zF-PVOAitTH$M;BG<+n6ACu0wPLA?5-VI)BF=h*g7tvBQwZ0Ru8fZvO@Vk&VU50_yo z#P=L1*>qIed$35Z*ogrFR9%ymi06lu=xmQ7#9=T;SN6fQ`jquDrYr(Hzdy+U336%bu@) zAU+ZOz`w`QlALT=^Ee=v+N5i0q4Q8vrgy`XD~|LZc!35Cwj?^bZJEAC+nUsnF!xWn z!|hedzdX!S3#R*=hgIkLDXwy?e(AqNw%qdBwh0&Eezi}oKF!V8N*O0PSar9>{=WAO zr+kga%)d48+`er>!EDWovPn>-a?ezEph`%uMSnGVT!EXlN$N+Eox?RC!m*pL%iERW zeKDmk63Tg9Zq?NxT~aS>g?*=UM1wluWD3XDQ=<9U4f#Bh0mSh8^kLG!QYj+t3(k2Y z^<*LpfqulK*ksPuRw=c&0|fy$#7L+SBnxinCu^U$l^ADwxBNT0cV%MWO$W#Re{&Lr zGVox6mUaewL|s>hr=@yMTLF>vFWv%R(f$&2lsF}C>-S&0MZ+iV9*V~dO2|LVeHo`i zqLF)PcY0R15ND%Ck^4E%dVWYgID6+6c~G>|^HT$HK9L%ESRvWF@o!GzsNqiUmObLn z%vj`c`?KC(cOLwi--6TM4b*v_U%1*aIq>Hb@uK~-$Aitqa7ydeEM16 z(X$76Mm?0=vP$B|uMn5JsZkfe#FeuT4=xYu35TS4L)tYhu(-oX&R%3(*RfxEIL;|n zfTc-u^(rAG0#A8_q{1wcOrj8-CH|>6s^d(m#^;eVLeX^k(E{3JGk&C3q~OOWQfva^ zsTA}+np$IuuP<6Xr5V!}QSAtO&wkBZXZp~}S}eQ=0ltH`e~eZV}#Zqbym>yk1-4d6ip zG~$jsV!b5c0X#WNDb9Wu;Rrw_Ujpg~T-Ebb<_nhpp@)_yE8b8-qc?MQV_dD8wxQQq2%ssh?JpXGXLxFpJO>fb5f9V$Igg?iG zKmU`qI5}NqoX6j(IMgR@ci)b@@SKA@cr=c@ZjKJ ze}DgSZ+UNTkFdLYzOzI44{))){$Iew_PfiC*Mzlh!b;ok-@pH@Tl`PjV*h{97LA0t z&xH9Wm;Yzlf=F0QJ|#><5Z?Q*e#HOBwYVH@AdFxydwU2ykp#TS|3EDS{=cZjn>TMp zMn+!0e*GWUqOY&7r>Cc@tE;1S{&5yb~YCM8?|U?XsD~J ztEs7}uCA`EtRxUEixU32vZw#$T0DG6NViyhh$BQr5rRxNg9HBWxE3Dn1ZNe(O$&mV z9zk2R$-&Os+uPIA)6LDz)z#I>$q9?a+S}XP+1c6J+TOZ#>p!%`)vH%6EG*2-%uG#9 zjf{*83=H)3_4V}hbai!gbab?|v@jUVe*qV&;siMff+!yW#ZF+RCm^Z+p)E+D1PFux z23;~SR7i-ctE;Q3s3@{D9FjlNlQyhN=iydNQjAviHeGfh=>Ra3kwPg z3J3`B^YioZ@$vBRaC38`P$(`gE>2EP4h{}>c6K&4HWn5ZW@ct4CMHHkMg|53dU|?V zT3Q+!8YB{lKp?28sVONbDJUq&$;rvc$l!1|3;KiB6AgH0X{b3BN8j z+iLfrjH5oNX7+{eN14}#kfz%)r0zNJ{*GtgU*RAWoW`BaOM^*tqIT~(TUJK?qg!Mc zO-T7M)qn0re~&p94!b)rRfQ-s_3@M6if*!pB;C$w@@};uYA4|by+S9qW zGWt-|e!S=9!Ow|uqhizE^MkG+_3yso!K&N8zq!Q{PE7yYJDdJ#QjPFbRr^FsaK}D1 zd)4>%&*{O|_YbcKE)D#5b039+8({^}!QAeTV<<8@IAVP?lgz`Rx(ovv+}CTC64-;* zmlDlx=Q#vH7~267p{kmHbc^-nRIy0xFih&R`%1dF1UfU$ZBIY4jma_*uJ)+U@37eB=@|bed5K| z@9uZ4;g-q3^{n>rqfo6Mn9``IMlVU&l%mia^>uJUeE4~#TB4|3Y-do z@RBv7C6`I+$(%Uw?uaDe;_wS13Lty5XnZb{=C8tYI-|qb*Gzr82Seu8naByvPH~Os zhdpQ}1~Qhx!uc@pyrjh40fpEIrDalMn>d)-F1c+D0!$M6G`vBNp7DjB&sG0Y^X8vQ z$M<#;l(cXBAfL+6E_&vPp?Lx(tf7a9o#Z5aV;&lY3A#SeqKmZFkcI#pckSKaKmNtK zcgX`IvN)zZsU%rrX{5Wil-ms=e*twvGI)|F^u;)_)98t*u#RPndfK)Hg6yCGi2ln_m+L^4Ao zJ2V-WAD(2|FIxZRLBY(sDus?W?|tn83qBoIDUBGI`oy#qts7S>eyAM}stbggV5?Ps z-Y^ZF`Up~-aO!D4A&f+x%X(bUlhdsdH?s0HQ7J+Yx>NIv8z|?{9)mbm0Z&qKJRU0G z2O?K^JDCx7SdLn#p^!41$}T8jsm8mD`Cwyo@UayI&7=nQ4it1K4A-sE7}GWslx~|I zE)X)pqwh(cUx2G(zNg8e5S@O{cBw{QURc+mghbZ(u+HXvomI!%PfcM*^;oKUn-Rm$ ztp!I7?k4p%RFepY8lrBYmyHGls3$(i;H=dXeuu!x5sI+4k-jM|7Jv^G+#w7>928b$U*4As6L zV%z}3jtS}Sn1@TKr5I%l$VlBtnRpN>2kJL1T?+6yohROq+9U~D(#irUc`-;H`tIw{ zHf@~S#0pmx#ZE}P^*8VhF#D<0h*+K<(x8EtvwmiX1%!^Xtr_I}ij6~Kn^QwB%0nUC zyCd}8QgFSQHwF${QqIiuWIGQBn8sUkHLtxijsV5wFTz+Nq{zhQ0jh7OI_s^f%U@34 z6CCNv1Kdl*qy!Xa$1RnKV;0hIWx~+gd$0F%VJ7bN*CiO1IulhwG)aMpMW*d$Jw*lX z^_Zmb_p@^u*@+21Gbdk;f4iZjk--htcu4AV=bB{##rsVwLFZ3;FXgVBSNOvDtq}2<%wD&+1|QVTDVu^IE~gBD>W5LK*=Q zTp~Cg;A~xVoyYh1m8{*CduovnmE^7udh+wmyjsF{PL{x1riWs$*o7_?sPNZ#{mlPH zWOPM_UF9RPBMtpOl^+~6FDV?Bg)h9+vk!cC4Wg4jskW%_;k>c(DRwq#j+p_k^7iq* z-?jL^TOnT@zWkIw?gj06-cVKj`0>h#V(SxIl$kydLy^M4e?@}lS$E0t)04L+d%tIX zsoEALG4&T#Z6u5KEZKjIaXwrj%h2d~8S}K)@z&*$;!p%8o0@Uzm%!_qYaCm)FxA<~ z@u1F+Pc)@ysA8_i(i(#Px+`TM*AxkRuq9>bUBTcxdXZaoRchNEJLgoB}u_pw8kt`sTij7r>F_T=C|}@ez(M)d45N_uWCD zMRQk_QF{*J8343HRfq;4(b-r;IiGg;D=N9wB}x!!!CD%i_t;CpCZQxZ0P{0UO({`u zB^Ji5q8Snw)|p6^8%LHEP2jZyYuY)K!_HAqjm#ts6a*+qk|Hd+Uu2Tll^`B4CoCw0 zl~o5;wSX;0e0)x0d}Hq;J8*YxQg$2@NtdoLbfz@GqnSdG-R9)r(&!jC5SK^vp%M1G zbbWZTDjbFJWK1wL#q=@jt`#K=jT_PzAsxLJ;GQzEE>Yv|!PIe^*!qv|bcAp#tykJ@ z|F9#;g0D4GMR?Kbq~)tK zHFu$()M zYATzX>0SvpsGpylqdND?!&o}T+#uypdlm-gSw>efR`*bBz!@f5IIpAyGM5l`bK{{Q zcPMTuC-^Lnk>{aV%VW>U$H9A#p|W|hhnfDNOv1B>AvEyh<)go(4@1cEYtHzb-nf2= zA<`7AUu7Pp%sy-jWfa?u0x1BRnevmj_!cu_LoKP3>dFX zV1o)z>rc>#8|9Z zmS4z{r!9uBs0VO$`G)m{b#?V! z45Cv1NF)ecYzS*5^+`DW*(`uy^*A}O+qc;k_1QB+-a*DP-j?rB&*4 z;&cIRYWwHm=eN5VEYJ;ur~(Pqri`xkh{<*+H+8KPG8IdGhoXa9v?JKH!*%_+%Vvi@ z2<(q53?zH0L7oWTBj*%FK52dt_PRMmwKVNd+ug5~8Gkyh{Gmg02m!qp*%WPLEhJ|s zG7UWJz&xWg{CPP=d1ZKc?O0|WTXppo9ejfH_siVZ;Sb9~NIzo{vwm&KU%S7bci-#o zxh{<>Uhfp?c6$o%79`xNuQ2TW;MrS~+N+eq9eiF)EVYB8Bl}Q_il|ay#6Kk`g)P6RmAHfZQGm1W;cw@^rc{A z*6@SF*SC92Z6nOy#1Ck1SF6gIliV|p@IyeksS5p&$meXd4Av3zBas&)IQG#Pwb3}+ z(VO>RchC)Q2)nR^`OyqDYt4p&vaiFLFRkw%SsO}?+>00?b+F;a*|^ybd$7Mem^T2=IRrv2?kJ0x(o)=uqhL)vgx$e*w(vob7_*6c?3nnIAm;i&$c2l z*FE*K`;jC0FDXPDK4~y*@Mry`hST84J9-i9xS2=~MI&S8F2ZsJT-i)@Bt>0`M1fmK zdWkd#p@hO(3h4q+?KM-kn)5qIQJpMOMf-{D&QBP6^l_+9aI=nU7`GZNK?CuDI|frT zV~xfwB#Y)$mTl11f6Bh3^GFKt5@@@G98&^q!BN}yL(I1zH+CsLqL6A*h$1vJtpxEU z9;xL${U~udUSwREawfW$UR7-P>v016`<~yn^qhDqCwwTR-<}cxZk9+8>$xY1u(M22 zH$1|=h3pFvipZo;Z}}3D9vu0km-F`hnBK``b)F=)Y&8h9}YkV^OopM~CFbNPB zUdwS4bza1HSo&}*)dF}H*aa^mb-^vrZ_S85B~)tMNNgtc`7UC7SAHHz29b_$R7Qq2 zuzkM2AeX;@uAYATW}5nPQ4cg0DK(YUyO5$Tz5zIPt0TFQRGm_cj7X}6W|G@TiZ6cR zGI**&DfBBmh4=n<&?N#QfqZJa0RKIqbGzX2-1M7^xjCODz#QU45nyxNtHE0-(! z7UMoh+YiQg{m8Gndmy9CpGGLE#%5^uIpwQneMmq2Ctd)+1N#K?j3V<0ur!1c1QcSa z%1q{-xvsg{rFdNSqkpgYboGF+6C?Ux?^3TCjMGQZfhWwVu9RGnDdE+^BC60(!wK>o zKVc_4f+z#s$fQ{E6A$bq(`tr?++Kr4ZXD)qyq;fpT)#cmM?XkToKgM;zCGpHuPFJE ztyq)v{Vw&d35o?uAY6)Szl8d^6cn=eQB!?-$alNKYeQ;e`+oP@N>5Md7Ss|}sb{(w zB=P3;`0uKuZD3)|lX@xIlb#O+3p9uS#jbwz{YLp~r-p2o_~Tw6v2&0?Z=T+m$gz7K z`OUy_4*B2?ZSfAH#tgK$PPYZ*Cj~1@7=QD7_apoM7lQIWgWdiYqdf+D`UX{!G61Li zeIxbd&d&Uf%&S;AvrkGN_7tKHbV1(&u~6C5F2kt(QsVG3cwc8H;P>wuRnsFOibJEF zIUUfLhApyg$T)0J&seB^wUiH-K9^bGLOVzH2zqfTnC~uBaIQ7~`*}9kLCu3_xjP>c%=ViQEv$bw0{x(qPbVrK z{6B2n^;48@_%HBfSzrNKmJW%fyStaAyBnmt8x(Nqr8`9lNd*Z}Lb^dZ1eKN&r9@I- z&wkGLoSE~(`2(JrooAkzo%?-V_xts)y7Av9;`}$nQ$eNI6EnARXTPQ3TWuR}6?-ok zFz4T?Ugw#O-@Ufy{Q`GN1}6jxON6>d!8iBQ8~C##Bcay z0dx49k{f@Pv{Drf(=NCFqg%w&nj9`>tJnDaR?oB7Zvc0M*!(2(8fbLH&o>!knx>-| zxWyMv{!+h+Qks(f@bo|3BJ%zLhgZngxE}d4Ms8KC`O9$XuzWq&u12o|^S1o)_rmhE zK7PDVTzbpDZu3=CQBjuHjV^WduR9Y6WW>=f39!vc3#K<4991nZZ^g&HimEOSrZK9$ zvhJAJ)-m~qGc9^M|Fhfu+&Rr@I+yuAd$%c_^fowkpg_bc>dF1n%OjN<+gn+Yn@>vu zDWw?-XeE5#y{79*MuXbdzVCp)ZWB4LpfSFRc#Ls^h*z|tn)1IP%8!(WMT4|^3FWj8 zP*Sy${e@AlV9=pkNw2XkFjuaiDvfJp7L59Ni=V*1Xa;gju1M6pB#k% zL($aXDbkX&5!#x{mWiFpR4%pdnB4L4FI^EtlY%Cq>Oc89WN$`5O+7Z^ zmvuwq2SQ|hTt9`*M$D}hY{V1PI;7LHi|m1(zn@w(!QW47vrlCCK*_E1Pg_FPm!wCs z-0!=-UGCc7slq3&RO#3DIeOJOTdC~FqC3PkQBq7mpnQdllOcfSM=(WHvs3PK+}p2} z@1`c66t>l0_xRon*+V2~!5HTQeJb~qIfUL=%B`Ud!t43=*P7mbQ`$RPWYNAPbE4BN zSByuqT<258#*XSwK23Y7O$W_a=|#WW@IAhzfh!nhy?a&C=UqQhxpsLD7dhN4v~V4V zeyt)QMG~|I!V`{s(EJ(ul8nAxK?^7BHg#i4IFU2sTxy)BU?A_RUym7O_u8V~es^f~ zX@c8@P0n6c7-Je$OTcHM3A!WlbSeMu%Z$n2I_iucN=_x%a3WD zXLIXPLXn`_H*)a2bY3$Cj=q%4jApEVfky`HpV81)JN{*eD<+u><(Yb?WLY42Na$P~1N$&&kgiYr@JNbR`FObTWc{J^Sg_%X*?x9W;c493HkM zI&Xf?rby=+^8?G{cvcW}^w2Q@eI{)2kTZj)ukFw+sNu{Hv*EKTO!PX`oqUJWX||xs z`#qf4=MhY4ugYGL?z+KOgj%wIN!#QC*UAr(4H@R&ZD3;Io#FSJj9ThHq`&y5XmGDJ{z{^ZAWkNLqeBttXfB1+A02{LiJd9li(`4lBC|)B9;V zi=P)v1_3~#iE+&J=p+2;A$HN`4jl`R_eBz8^z7(%jer2*9DE@pU$GEWB{v#Bf^(D? zVu;T|DMaGY=ZbM5^r9{oO3@%UIF7V_4CP`Oo{AfSqEkOXe6bwOIz+drkC%b-qnv8k zO;xOTMmf&NXP?(qy>0KEQQYec$LmDmM=_cvE!i&w(yAovJ9Ubt7mLI`)Cv0+FE|O4 z0o~zNp(`T`_Q$!kDobn<{o&&o=|+`$yR`M%iVy}^B{rHf7NPF;NwRY~iw_%q8zdsu zbUc@x6v%D7bSt8P(Kz-12t?N@F^`)`))TQ`)q5xvB+in|CYL80@qxjw=%9wg$bw4k zGl*c50WO*nfFx!wkAGa&|F~D3nXaIHnUuh^@o@@rH0)e`1~;P#UzFFuM2kmb={+hM z03eF$hdc{%By&$Yvbnf5(F_U3Y*Lvkq(+O(-%=`SSJjYwXr`lk_oYLpJI{rxXnEU5 z+^j74b4Q4l%>wfkZF(eDpwU0;KVRxPe0O-w8a}T*az~oWsOJjvzF(VXC+%1~*bMvp z$(H-28B1rwanP^t-wCsli8$2BtWTxw_}D8+&jm*%tnIPSw)1j%;FDKA3U5NtlrW_ebE*wej|jQ>@IoPslY`XSzFy1|3FL)t zIvlF#Kg)*}NpXb$hNPzEs6g4>0ZVE%0Hogked>0PSD%8k`3415{jTyG$vi$?l&CO? zGmp{Nso6ZujGW=2tMXI55D588M~7+-^PEXWc^)O%*>u&Wo2kU=x%5DuHKD+-a~k3) zpybNffUJwTv^__JBv!)XFng+B$mntsIgc9^i7|PXCWe2^%+i~c)I;5(kz0FnW`#c( zcEjQ|RdhU_n0;OB!VzvV>828xiH5q*AD6~e7=#s-Yi9 z(P1m?p5h+gA9)9as?G&GdDYg~@VmCw8KTqo`h$$jFTefJ)!mU$+i4wd_-E-aSPWWD z=pZ8*ubIcIZd0KHTJL>T|2>`ugi4wl!xE+H%Na-AUUV(Ja7V3KZ80tr4C=}4XVq8< z7&K`VBg*$>-pkJ5zYT4bg9H>SsqE06`1MPy=TS^DL9j?MO4KyBELnF#&4F9unK+GWV?N!j4{U@6h1y{IG6T^}?^8hND5>SakC^2g>L7a=@!B zK!v!BwPWLsj!q)^3y&97;R$7v_&boS{@A!ManQ4`Cq365Q?mB1C!eMRr+unLi6E-D z@Gbg^n}pf!AE|heMt}Ijjg6vCjHKXws}94Hf%hyW8xvbu{O7aF>zuD8?x&X-&=)nC z1mpv3{J(X!Z%@Y`e(mFbI#Nvk_xyF_)pTMq5arB_(-w7L)f=^J|0Hxb6djd3O26}O z>ff0Xnv0oPl>&b@=XdX`>mMTWSKSKeRKe1d-HeFi@Oef%FjW(fL_Qu2Z$b6Wyza#= z0sk|S`C}zMABcZ+P;!XfcO_GL$s^yGqX1fj{{{5UlJw#(_Rf3CSHrNRFf=sDd;C`T zwN*dCsyy~;AGI+UC!*)>vErRoGN&J*Gg9o5M=Dscqy`!H9L`F`8Sh=2=+7CC>CNXm zh!6F{vuTfsrbeo5COi|w)1XEP7A8D9#a$`xhvfDTzgEP(`}hyLzxJR59R(|kp@uh> z^(CElRj&a3YH^h#~Y5#Fbfohf-z2qE)1wT zn^^yiL5NQ26OYpQdqq)Mr5Z3&R4{9fAcZn_P%`xs(20O}GePJYN0}QX+m43|0PrEn z*{>5B0RZMPJSJ|GPJ2RhSiCh@Y4r2Zx9>x`)^OdS{))cnzhnsnNF^g}6^{}b6Kev~ z0}vogC00Ey7>Xh`Pt-&L2v6g@%7)ce64U^Re(E?>P_PS91p@?znb%Q#2Rq8D&T5Ug z+zrwG9WCTUZVXBSTU7^?hCPSi)hpPZWdNTNwdgP`|GqeMv^mgsB{6aqmjD}S)P(1D z4dnlg6TO+BP7M~h#v5Zs?FchRuBr(S4Rzi0qvvGStO!!HC}K;-DF_ft8i}1T>W`Cf zt>O5DC|uK(7=Bc|Cz99rIuQm%@nYBx?(rP$@ff>0=-6lhCV$XY(z9-RypzQIwt}2@ z_$BYFcw+(?jMm}z`9H10900fmxNgQLlB1N>@vxy_jMgCs0BDURMmHg!`zeRhp`P-p zzLQmLyi*f-q}61M4?O6dpzetkm7QFb_2Nw?HjkOH2D-c9=o3V{UgH?if>k9Gv7lhw zOgxPGA*{|7-5yf|Lh3Z(+Ov*m1!;_s%b-V7C!LK|k*WBsQn;KbxvAe>amwl+f|7k6 zVY$`fGWykb&;g$b;xOySn1&_N007v93ASTEK4gMT*iiUN9FuvRrnUA)uHvSw+;)Vv zOHh*hFFbw0&#_@j_fFH35&bm>BZ7W>UQCz@hs2PBcz$XW4F>Fh5r_ts$kJN8S1nv3f5m^&mv**)YHwX9DNSBx&~~ z*~{*sUsDt|@)So5QU5fzQVpnr@qgrEleQbQR$~5zix@5p;yvfa$+W2H4PQ0s>BE8O zAt{m_$?_yaP>G=c+dR+3Y%0779Rt#)I)cVnMKBPN8v2W>KG$cP~?*RdSx_Jf0rHe7Bl)V7zdt*9f*t? z%-EOMU2C2~!Nu^03HApw-vJoe;e}_$Q;*fh4$GG<^%T}31MqQ4?6Gm67HPYS@PFVi zcs!pVn6L~~Xkt<{+$>1@T3DJTS~A|B8k;XHA-Lr&5s~hV>~|4w6o4y%xlojn-13UW zB(;6n_{g+A^1UKAD}WO#q7OToI_A0lED5P0kJxH!Lepd6>usRk3a_jb%&{ zkKfeE>Gs6_&ALP9`soq-{&02GElSlbE;18z;SEwNi+4X*`*goX$HJ9E3f>lbvcm_? zZ>>qgRLxOtVzF-m#Wy25V*?Bl6i~HE(wle*n_%(UbkfCG0G{7wqJO)c-wLkHX3R~) zMsp7L8(Q!jJ!)QO9co^+%Vt{%+@QRyI*YeA%if}Sw`D~Db>xfz!}3|i*w0^X{lwXZ zeOzZUW&g{DZ;R6ZM6|WBD9{$e6LWyUK>$q9)rGv(DCciZdEgR#G63AND$i=k=G&{> z1vI;$iC;tZx{nc)^g#V!T?hS%dQY-g%C@Oo4|$( zpeozQ-?a8{fjx=BG1+uAM#Y^PzVsEJ_h&b16$7&>CQuVliAPGg`M8C#;iIk1K{4iW zRw$s#gR2PGkCct7V zmYUy?ow$`B`$1ZoNlX~gV{jVgJ**SxOlm zL2Ue+Dy+K8!+w|Dk9$87pjd7Cd(mz(kT9>MS4V9lVBRnsuS{ID35w^_rI(>nvWFW8 z<97(ussus3#uzNWx%^5P17vLVN5hes4c_TC9#22_ZQ%N(^kGM=BqpVStkr$?bUl8B z{E80)&`wE4gMTbRJeqVX2y{_6eX$yaaWaKk8()r<-V@M_0ee6Ie(IPr)5G(qlMH?^ z5Jl@a#-iAhh6p(^;6M1moy5435MG$zUWn&CE9SH2+coVxaPI*UaJjzx2>@q0y7>X% zQe5V{yZoo%=liMcIM%3Hsy-a6*%RU#;mWZ+MzlXr!j}fmosC|GNCcQR<)ShWCR3EZ~O6 z(;M(;aOF_@;jjHkUQAzw( zPYn8gkD)DMMP^m(iO!7Cu*xw|SXhE;2yU49`vucup{UD6Ik4u;3}-Sn`%IAF#$Vi6 zMTb)1O7(ax7+6a`-puTa{lianA^@vE+#T<^2-R*N)i0Mbl-kEob@^c5P?1Vx;yNW5 z)}-djagvyRcBtwvULO>5aBjYQX;I^cHh;H^>UAbwzVdAY2i58Wz;Qu>q43b_1c?qj zaAt`pN-NQiKR-BuDky<^0419K?A>*33s}82(Qp%6o-;li8JDgXo{JYAEQOV!k-+l) zLdx$fgKEEdFDRjQP{ta?$ca7Xpre{`WAl+h&MhItEzxBbd+hAMo7j^q^aUL}&%xZE z?Mlk)>ZX$TSsWZ@8l+Otw)3CdaexKT$I&gjeS`Kgo+%~4dlqE&6!t8Jj4t6q9Q;!x zkVWt61F@lqV{`26NSQL&bPNY0cYG4S_F8$?)4O7?01gVg>-T*YMG`kngA3bK(SkEScN{ATqQ3eMU4xlITkPNjLsUt!SFY<5l<=3SPg^t)PVjOpERO_o)O6ao@ zj(gUa2+_x2+Us#8O;i|)XKfi+ba}ra(5NPGBExuJM;#p?L}g8dJboG4FL1AB&;2n- zD-x;IA&attUWIL9VI$)e?xIfrAKfC3fJ)fw;FM_yMWS>^$aJ=?h*=V~`%OI;O^e5% zCJy4tX4Q;iH)>%mM3^f$Mp7RZo+l`2CGrG*Tpbswn#rPdXT59MIUsd!$cI^HLzcVE zzs}xVCuLWtytQl#I6A!GS!r?@&1ORdZz8em!~%G&ge$+das1$Zq}jGf=6s(lXU|za zRYLD{gkI-UZ$IrDq)L>&+tskg*J$#wFOI(6{Q9|ABJlY4jfh*4E0)E3*G5`cqn9F& z>T2hyXIo_I1>vQu4}v4GmYn+0RiIaAKfSQefn@98oniL-Lw2+$$il2qa-<=FvId z;7H`)nreN6*+%S(ucIb7Fr6-ns@#Pvfz3e`4OPiznLlOGVG%~|F-8kb zNV24fI5^J`gRtz0W4)vCww+m{*jV+rKnpWMB3P&2Ac3t+{fU1yz?GiHs&R}Oisl14 zX!%dDF`87dWGVI{XXb<@v23Vll9-${r!&fQUByXD<Om_P^y>KIGsyn z0J|bXs)gS_EDBwuZ#gTovg0TiZg+&oSvz(D6JMLQs-R*ZYtTgw>(Y#ltKBF@3ckIcr0qal-0Z!*D8RG{}o9FCt!UY zp!3g!9oCqH5L(qgT6&t5Z+!?v;gyPU^L{$&e7xED^5OcZWNVs=3ahl_Y8)Gv{tMu7 zAf16g_o}qkd^_nGnGTB(jOyeQiI!}$i+Q}C&+r z4OD<2#?|KTt0ENX^GQW*p=qgK)^;j)zt2Tx|Dha{uq=ZmPCi2^z4EezxWb|K++#v` zgq!?)zutpqcz;gGJi8ZLsW1V7r3y;?N7#OFGAGG+SO$wunvGJuH)obHj(ajeZm=Bt zIOM>4-e{s*f50h(UVJ-=2LdqdK2XeL=mr2#;;JGkL0|kcEzMgYS}rr~i@Jcj)z} z0l_(-_A(x?xNw+PcuNj+JRQTgGmg!>n1N_LiRisa=?l9;%)1{cvy`U?H@&8R;_Mu! zDqE3yyiD3&2?66yaQPo40Co$ew8c?!Kz74vaHOb2(G7<0}PlWBa6?R zs)FHsyeUaP-Aw>V4r>`fARNKSM>8>8HqGL0Y4m~se?YmVB`*}+KOt&JmZ9c?MV~`n z^*HcrHW^(V^|S9z>gj@b;-YrBvZ8x=nqRXtZMZQHz2DrUs~O%wsw);%(75_ zUKugAn8`By@P?p&0>Jt|;zvOkN*kwzz*4sI1yt@ATEc>P+CIXEl@+OUmi|)-FO1!ng#4FGAp2rR+n+D7oP52Y|R&f}^PkCX)kG`Kcp`E%(m$4138n$mi(64E_ z`MDv(;IESj;vbr)ybG}0?ToZk7YSJF0V~+Fg?5Qv>W)~rMSv01e_3@|ThBe8Uo6k+ z7HM01Pd6s3wp-m5ZtECSc^B}KXYD5`Rp%nxv1Op&+U6G!gnNZQtj=@oG&{882cN*x z_-9Z4toOYp^{3lmRqL2)GW~E#Zy#x+mC0}yTZ&T`haf8ki$UA_Fthm>vieONk@kK_ zlwceS?-ssM`vAqm;LF@IJVM5HNF*~TQ3=hvO_I|-#4hh2N4B+&>eE$geQ%=(JIfet zFC+h6J1VJZ5EJcHPIcm!$p211lX2(=J!m{u{I@-k2ybQ2RiyC4pBLt_^-3gdQ%61v zZ=E;ag?|2d)Kc)7aPOD6j_*%r3X0#*H9^ntNw4*HFE)7BcdFaEOS{!C-W7BokvI`< z){Z#l!%{@9?H;Y7;^DG=5EHN>elvX3nhus`MQs6lGCRtG^23i1#8mSq2-jM0?53V# z6A6Fjvix4Rkbv4$C)dG;v{c1Z#ju6*HjC-I*+AjKmCwLd@dPoObcji8itqoC!^oqiY;GRB`+%>;Mq0206MW;4->_*$LqHBm9@aMwv_)?^o#h`wL0b|kCGm3ld?e72l&PN4dKLJYJ?oVv@#pDkTN0T zQw`LzHw`khG&|>+7=_2r(X79C(#L2PB&Eb5akxL5V&HuYF>agNtduBRo{zKf=GKE4 z@gx2Muo(jAvpEhD0Q=aiANAVq;NSSEDNxQlv&DIpTg!f@l!eX&91zkBT!H)K>o_LN zUfoW}w43ohcTL)i&PtD~WW{qxe17oy4!xNu@AVI3$qxJiYA8!z6GVsq#sZvh_R3!> zV*368yVw>|ZCh)nQpyCpN{EX!fbPt3QW5?DOz&>-pR;s>HQ5w90D ze0D%#WzN1q1#NWf6cN)hc#Dr~1DkeT>2H5H7@^gQx5TQ7_jGfP%LF%MeOE3{EX_{b zJ4caD4GdQjyN2tGBfW{DbPgZ z7h*CKg@M>hvH6F{V1ti7fPi7yiFWo>+^cM=PuQch=iO}(zjLS`j1Y9A(`VLJnTjG^ zN-}>DRMbPivEU3|gL2l`IXC4@(nA!ix&PL-nF#F2#F+*8nU%<~yyFl=S#g5RikM0y zN<$kF%QX=P8;+=Qr9yJeI&v*VG68-N_nnfA7fU61sWK-s`McsCMPaw1ceahU{M4Wx2Acw~1L~o_Guk;((F$`t@s+qcFX#VEzv>(jojlWkHahCLJKr zm|5h@YdKX%DGOHBRYy%|zI`{CIp#GE>!KsRQxTL^Ig`be;)y2rP%o367I@*H&(Y0# zO~sHE&!vI`g3^fjHr-68k-wwXqVGz-qsgocFh?zXh?Cg{EZRA#N>?e*?ig*eip`Jd zB8nvLVyW*~^=}=RrE{emru0eU!s!Oj(?H78imGB&I_pk7NmcsBRcWAIz7aUW-`Ol5 zNAuMW%0E{9>h=oy_PTwnxlOy;h+Q>UHN6fC_&CGN=LgT-;L%o9p|!KpZ#HY;3PDOV zNJt*4$Lowx-!<-GGmM0t&FwPsBasHxj)!dK?5wuw&IAYXoXYxImAjU2;vD#0tfU=% zv*T2&As*c2G^~r=%`R!?)$Lu?Wa1oxE`3?xSfv(_{hujc;J%M3iMzP5qv@U>gh>kH zTEJ>T<*W7IIC-Vd8>AcQH-p?P_wAq5h)%fb6z`E1?=w!o5nP1fmb;<+B!Q&PPuVxF z3)%EGtBK}ZBQMzo44gyR_n$*-ohFo?BRHcTKrZ?0u^zAz+2~gAo}ILY{lI<*vtGzV zd?dksJo_eqH8;=X!1|q=uG4{anzPijivslz*9tNtcDIOp&UvW=_lbkkGxV}T99`-N zDgf~%Atc^SbvM?yFAJoEL+7UK!I2qYpD(ehhmFPNPO5V7lX}NRngb-fA$hZ= zmCTth&c*Iir?^vzbFV$SxCyIHCvm+%_)e*ox449%{pk2J@l-iwj|)7f)w;} zfUsy}6)-udkQ?*rxX!bf3sF($MA3hOtYtN1_I=L_ZknDwitDqla=J9v^QHTW~#7 z30Sc)NX6YiJ1Oer1o3;HH}9GAYH+Jf;5I`3Jayk{>z`7-iFv(N1n)g`>gZhPaB=Cp z9a;a$sb`n+WBgaw#E&j{ZseV(I$JKcHt#SuPkqAg9q+gFUlm(*JvBF>oH&OA6_}>U zSJn>Pl84d$Z+JUe>N`4l%zU#S>6(L1@gB8E( z`D?mwfAdu+B95q6efZ`qf3JGjyB=r>HF0Tyk+<54zSj-Y9_WLOCoVJWJOaANha|kLo`5h0UkOe5!j2u;T;O#PR&GVGp0Z1f29J z;6)a^6pSmX%eN#f&|8jy<@slt$AfaZdvbE; z^X`;V6*7xU5i?0}TKhxT5Aa%`4{|#3P>#=PJi#Uyba!0xihncUjXAWBE)4++*9L(m zKNb7_xb^)O!jI+XYr;m(fouZi#4mer-DeM7EA!*Zqt_-_>mQ+;7Snl&eEop5aFILg z_`{|XNs{ z(Bhxe<3At9ro&&itXThZ)MvecUT>z)_>ufFng*Z~DI#tvSrtaB7o%eOZ3I9HDUpeM_Zu z-U6SGACX~=&~YdVM#~-y$}Cn0{a6JJ4ZaaZ2ZD{xG^YRHU}HksmK}M9%iwIwy(0>| zfWs#(UqI$;)F99ulG15Fnmlmz!G;U7T-z(cX4Wjq=x-tGr=YzF4OM=3%nb__+4~ZZ zgghTcohzOKxod@|`49-5uSyb$A|fTS*g;%1AObzDbprg4)=b}YgA`_(x-SQ~%UV0? z4i&-_wUqt>XGC9j4&Q&=S9Sn_0V7k#e+5#S4L=KmT?VLD0c1`gRY=pD)K~3q%GNTDsAgERafw+iyMEg-I z=cm^2Vy@zVOl>s9;()|&=F=$g>FjuNhQav??K^Eh>u_#+Key1{NGYuJPh);Up-UMjk^a<2zndI9HUAV^%V5L8AVdtdJ^E!Yrq+pCIVkKd(J`kS3+=Iw(>ym8u|B zrr;%8m|dPCqC6&6q5WQ25)g*&k0Vx&U#6cSqE2S($QF>w;V7i<8{*^)r|+XciFM@J zO69wDGqAu{b%jlCybEv=y_^G&XG%a*)`KR>?CqO8LCVI-!6X$RTPDn5_YxtM%>dzyxv#Uik>J-ilP z%6bn&zu!=hH^q>WY0(IpivxxGafztt!RF=jp=(a;DO1^%x6U{Deus|TvyVgf-_HYf z5D1$=or|6m8QIf7>9xnoR<^AhxYxDI{7+u{+`N`PX3WB>m9ua}7oZ=0;ywQX{It?0 z3n;nX6;U{P{qN>k#BBx?4osbw#|Zo~^_D0-@e$=Q=4m>55s^cXwBdn%x=Nada%VGZTBV*q z3^{%t+G8p8kvYkot2@%9(Y8Nf7CJ5{J!UkOo+UtkRf?ll`a)vX*bzZiA(ne zUPb_#=}y|TYT_dfm`ldPs6|MBW}QAPZXC>FpvG)n%38YPNbX5Gv|y9m>BFfS zW6?q^I08{d1#?o?Sv*H>SA;f-GXBm5k29oXrsNJrn}T?2Lene>9Ka z>VIAW#E6vLpow^|)=rj5kvVe6WH~CLS(Dp{w7f9tmKq-@y;q9>5^uyUOvpQef>ikz zKz36I84qP18(H|`oElm>s9GF*S6@Gk;HO$4wkpCQUBdYKyoJ|>S*(ihld_SaI-g}c zEON}w6@j%zQhRZ4! zgMo`NEqs}f3cXu=m&SBsxDbI)^IuBw;C{_~&Jf0mIW4aSoXvy)@ODD<)0-o-1j|#o z`HxmXp=^Z}-d^Xs*A6G~W!7;PE?`7ZyHOd$%E~>W;5rH=|?#Yfk4EPe-__Kye=rcIiWdI=0IM zJ)~S2Jg(I_iM@X}k32$2zA{OA3NGdVXV2;W)5;P1uD{qOHGxGFFF{}@Eur32*jp03 zC-do5n&rnge0_B;2W(DKgNZ`zNxLxO6$2G8n}cEvn+E^cK%(lU)DM`z-|#q;)~UsI zc@tASoU(ya2!6D@plZXCOUVE6wf-&1@N4=#R4h&*KteEV>;7HXbrC2LJ%Q~ra_#IE z|EJy6mJf`BOnM$=K1OK*c{)rPS0=R^^l>Q!Ngp%RjCFaTksql)ez)`fHS_Jy8dQ2% zv14LS`f|&2bV}Px^h@qAg%|id(pZ3fK30-nl4E#Z4Di9`ePmx(3J}HpNwKMeB;aOc zF-qZRXlfIyk--bvr{|9^8!~N=S(3i*;7OznIrGyoML+%{%-@|iVvaRbbR_KnFZkV0 zyI^UD_%H5&Vd9RJQTf(#`S^n^22Dw@d`n2CN~I%H-YkKlwt9>3PAu$=J`>@bIUm)N zxR7@=Wi279y-t}fETpvqbk$9?4>wS5nVs@SYoeq~Ec@px-Y?bXk0 zI8OZ&!{4XGk&n(X)Zr))aEi$|94zrL8HY6<06ghP491F;CC`FFoxg%?A_;U}>g>{GgfZVI0x{ zRN!3#)}Jv4>YaXYd>Ap)G_+J=+)RKPsl?+fxUc3KKb=$?=zP!%N<4TCskFs)C`3-S|K z4YQi;75Fwcs-fNbS-*!St+e$~wN!S3`ng|Zj&+k>TX=86^0>5We^@Amn zR~5~0@w7hP=(M{X`JxrJGN+(z@2c^gdfIFL{3E0RT42AUEX69S{r0nq_UFZ^CcZ_& zkL46II>k#n{eg&&cS`y)J7`evK$40Nb=6wbx6W3Ii@sSaj|<^WRqU`hQ?KY*QvoZT zJY3ECe<&B0eO{yO7ImMqLIB%an)d4wu_lcvURME3`(IcdRpHCy&8}~*1-PM&^x4r; zOLfeT+gT_sTaUCG12=4STAOHOeXgvdVNFP6Cy6dy^v1+m!owvZmo?Q!PZ_w{Fo2sm zd1U1g@#FrLSNp<{PjfC-5xzu+voZwWb`r3`RAHn-j-&;Ut^8n2ysFh8JXI+z+0WL! znRqttU#taEml^WAOIu`&w=2;-OnL3NhPJ0+*Ehu%kIFZM z3}IP-FinVpMc^-`v}Yx6ZRR9BJ{?5+Zq->;k}j%q>_}vU#BD;PNs8{Ddp*Zgxyc_b zx>ij`>fLVo+NOOw*_NF=BQn#b9vu^?`(h+00h3_`aI=YI>wP(FCIL1L+9j=sur66(CF0^e)-yri%021#xc<){d7XkY z&b`vF{7w;3C#23XA9sa0SVscjLZP;z9|HHw_@{TVJk?(bhKYi%2(`4hh z%h82H1``4NH~-12^tqpZNDkr0=ZjhNSfroJ&LUfc4rqasv_PyO2t-h?onRhz65LP>+Uod1Pj)}^&XTXAC(2?27zE9F*qDn^M zk?-F=UR-j#9Qato*OLe05NYI`mzil>c!JR%6CD+PUQg5?x#CQ zMFh1-O}%G&l_T?>j7hlbwZ zE$TUv>yuH;srL~pW8*gk8kCD_vXLv-{4yvoGStXp;iS;RAB2Q#5-GDza_1R5rZ90f z(Ni%|(z-B3vl-HF^S1>GO9J%vHb>zXMu~ZhETWE=#xMzTGqnGOF-0CP5RT_}K=g>o zT6W1itf6;{%jk4M2M%7XiUU3-VPdH9z`uYU9sT74`o5|;F3c~^lYqlke zDPvx+9iAT;l8#B^-f3)$Nq;!+DkJ-{7i@eKY)=KWU8CSNMt(Zw^j$>WwB*?ln{qYg zSuNz+Q+=_QS+agv#<6OL7xEdawu#m8gSEw_y_KotCo%Z&lH)F^(-s9U?Iu{5M^o^f z07TK~;M}Gv$n-qV%~r(as}kJZl+ruIEvEty0uVSw>He$u)#>l}A=nPb$n!gq`?8XI z!57jOAGI2o0e+k5e?WLK`Is?|rI8q+yO^lNjKEah>F=L z2+!y2k3-u>8~cxrCzqz@lvd?2pq5jjbfg5$HXwJ4hsexv_tMYo^7=qrwlBm#xXJ(7 z0;f0t|0y%1q|B8bcp_S6H!2kPl-k3+x7HVz+th?qH#5TjxgAl{kK`q`3n7y#An7n zxCtPDnE;iYK78N;bDvj~PN5$QwZHEdm4={r4T{)jk}Oc9?UW{g{$FMWJKb0CM4Ib3 z1L~M(CNVF~P#hoPNiO4U@}=G^*Vk^I2m=)oq5);*aaDzbm~3RwKNrHWm|=3Mjy?M|cRZ4u73jq-PcoY3Y(=~Y<(^IzOr~Mm2z~$b#;?SQjsC;9erqv*vxHEMjhQpUJs$()I~FEo^fJD`j) zyWCr@^QGd`68Ed>ZmF8!Vt6?117=CL;!AzCT~ZFhPsF0q_G`5oZA^}Zed+D2|9Z}3dM}>!UdiysVPTWgHY!>6<=wV_7U*De2ru3bZ&iH?KtAoFq$24RXEMZrN*{|U*G>}4E~gchvRLwNUW(`7VI(|BTKCWLE(A}I?pkOkAo=EMiEzMSWyU%)EM(R>+a`F%kL@=`dr>hy;1ySKbzN~w#OF_RfF3%)fOS`Y zq!{*h20%2J;M2rxCKOWp0~#f@CICjY*1dmL5=c+>#OYNEJn69@pB0D5yp{J(Y# zoiFN22;Qud%Jsh7UEq7;8CBQ&ZO`|~e&EAx58@sF;=5DL#_L0v`gev&8&BM~P3E5# z>Z1PDudksy*4;l*Cmi)0hdznlVBq-?^`d#b-M{CTt?8-Ua?Vv0<-eZaZcmQWC{OS= z&i22a5~E4UdaKby6!vXZ;)9Q|P}Nw*T7DXJU-E zOV97QdhcyZ!<{YL^Pb;e0g-*tAVOMMl%PEV&x4LL0xZO=oB&~yuRP007*3;;dCF?e z?1;)@MQatyCJ9$fKK z5&xrG*!4J!GmCnx{8|`N>J|QYaNRsVoGqjJuKrZmC9YT^VeL_I85S*D)VoKX(ib|5 zZ>&B$9Z831t+aT)uJpFTG)UnhzW-Oydb%}~@>n5Vw&Twhrl8dvBG(zTGgYeBn=TiA z@q6{t!pgDSUC`}z&qH}+jfc0%@qBxGyGI`*+9WX&3d z5Q@fK=Sy2HNcsY&N| zKgYtKRGH-PL9`0yp~_Kv&)=lH)-lDzufC=<)xV*Ex6LQH$$x)6vBgnYvMD0YUXsxD z@a5GMts_hI`6#A8;EB!ckvm06G33J0uPZm?@fv&HW52T;|=vTAEPR~|l zibEXw(lwUV`-7e=B&h{CWk;I^X1?xZs|K{94uC%+oC1`>=KGoV@n$?IP|6I z{DS>$bnO1pMK4nc$mkLspnYGA1X>sJAhA>TWhnyB)3wh7#m)*8$*vK*-e1*0F($qX zhfC+RfKEK`71;1l~GTMsQW30r#ZI*(;P zY1N}U9v}wK3UWJBEQRhfqp3G3I!KYYK`r%)3a-w$GryaYIHZNzZZogacgQC1s{5qe zcpHC;Ck=h(`>Yxwpr8AfEJD&-wl|)Z71svH?2~;6fJCD8G!6gLkZBPum}sJ$%-B!T z@-DZ+67hx$oNGo#Ch~;*XF}TYUB;R%7jzb+H1Ai*Dcc`-`*Cwlx%u!9apfJ5wod#dJBYi z`YiE|65Rgq@{0%dAUqwt37S1><*U}d?KHvd(u36M2X>&~cg^eVS8^^b;b>}sJW}Yf z-7EiQ-t7!Pf582;B0|UjN~=<+(B)km;*7m+1@?>M5@8VlWPSP97#DfiAUM=!3xY~f z@TC5HBd)!N%hZqsVK#vTTpRA+WXcPi36LQ3)`MI6`=DfGfz}Mz?eTWs!?3Om7XWYf zY+30Mj`F~D4~%1>TAl^mn$f*yY_Zpcbz&Yro&OPg{@ItaKW|Mvb-m+=GN%fT{hk z5M1E$UobtZ$~+pnOWRO;>!GK$Kg^;!m}&t4ou^(Jhhq)6e-`kZK;Uz3m1oe%C^pKd<7{c16kEeLy1QrZ&p8xoQ3ps4`7 z#+_qk#Bh;0UaeAi8$Vm0KQ+R;N7mzDv&uT+@NFs6e~e>FFd~qbdV+Z60WsN(-DwBx zru`sJppP*gaOZ=Ij6hdgWcZ}qm+tKK>mUwv57>?tQ8FX_r!`5*Kd;6x+F%DR%x0## z3A`_V--*LK+{!(rw+y%qssKa4ExjFrgwKJuGZRo4b+jyBxIajxzCrQ=i%IlKJnC}^ z*Tukcinvp%+L}!G%F}1oOhm7%p0gs=L9nSglX^}VIG!tFAntIj<5cgNA58ZIcoM}i zjFav#LR~R#KX?ddvYk%9#`*kI4sS1_HE50LJ!qr)#yvYLrib(HXWS4t-hK*1DM6P5 zyrwPG<_3|W*(l~u>`pd2Quw6=Zfz5uEsM*L#(ZLb-J?dY8ZLx7IuFpBHp9;GSc5~G zbx@Io!yV_p{5@^fyVLqk{TpbJRv=Qk3vkA1m}x_W+m_A{8UB$iqQ`}9AG8cV`-K+h zS-9KCuwHm>{nEr=N;=Evbye*0tGA~Xo>L<~v5L#eLSepmSfP#rnX!@V zZvpp$@Oz!{pj)QgJmrB{()Xp7UrlAjE|J4%wSA{p{3E{JNPTzf>Wp_EJKydy&}PXf zBO46a29;u&7UEFiZ;{J*^inVi6+yp-M=vkZdD>vCy=3;~m3HLfl~x(gi(ync<2A%E z3S05o$_Wr=aQ!0FrYwCTNN&%P=}C2hqHnx%UA+2gJWeb@4+(fu7=BWidMGe4NRkI9 zpQ(M)g@`0;;%yU8$P*lTqglalU*QiS+1xkDDncL1uaRHQ@fk-no|UBAr{h`Wdt*uW zoi*u{JW%7t6cftN=N9@;6@8n2Nc#7|vmR^Nbz#M7rO}Aa7TwU7J zk+f)e$UK=|fpS|OXW6C)Mdj;qc+mX>-~%HL*w%1R>%R*K@nQVG>~5WW2HE3b)J3E{ zz(-nS@+CvtDAqe~G8Q;9&ygdRgJA=m#GZfY791?dtJ>IfEYlydK6fhz4w50kiS=>& zM-}<}jW2mM0R%SjyKW3|L#?`@pHYlHdmGsN)f0-gjU4l?)$fu*#x?L^1VSu0?K)5CSUn3*FPLYqM?`Ulq*b z_u5fgXki2@@++gyo^KPeuC|$-&(Fcu*$h zTX~RM33g{PG^qL~rrjV?*vy1qggB6qpI}AB7-%GpiHc=&z!zx)$VLZDG!|{Y1rC%i z7LKemF7n@{AhpR*;v&-0zcxIz_D~MUC}-R+XX*@dJoS_7mzYO{BkPSO9^ zLK7VB2c+JYSTEk6WO^QqxYbZ!9LfH_BPd&tKmQj5UG=+uXb)TUF^1`M^Hfm(;6*21YZ z5Nb7uS`8f3@%J`m{Z|2{zP|q70!q1CbyZb)d3hO)LdnUYrdtjc6i}n1sbMDHBLe?} zKPf6IDkvz(%gf8o&d$utOifKqPEJlrN=i&jjEjrI(_&Vf~dasR3~$)r9Ra_W8Br@+P~}*UteFEed6Wi_5a47=;`VG7yCqp zsz9?(1gU~NR6af`7dw>&LuI1-M?ir>sbDY_1UkW>i_iW`Kv7fs|4%?+Wo7+;Lr|{J z2$cT~L7CitBK%(w6eXtVe-M=6|3FYC|AnBas{a=RMMS?)`0-KIe}|x4@=L$1)F6Eg zUqhH_a(OPXvVKX*y48Ck$^0tY*^iZh8Lk=I9S^l3at6_}WB(n3vUB+<@X-4OgQB!g zS*eyN!`Z*swMp28D&D$CCH#!mx9)RMzstUV?7Xq@|B0Z4Uzt(=hz)rA&eZ2r&+(1$ z*9&sVR2i|S-80No4|~^%-k!rhTVKY?F5Er|ZTyPLeDsuh?RE#Xn!VfslFIIO>%jbX zpBA6c>S8>`Kzi(o zZ0FkD;#Kx&vjQCaZh0b@5g5Q2iPSIu2ZCZQLeOWiwDnubx9FDzuAUXK|6+65gx%Zb ziq1_z7aflFD@6evYhR0l>GXvFT7W`3HR9`N1?;SS`M0u2TXH`}HrSyc&E>1z*NbVY z)4msdh7P8Ra%}zAstdmw-UsV8%NB!#INd&#OZFDj-O7^Bm#|Ncyybs0+nef$scxO| z-)QQT)?bF|+HCpNeZ3?*2n9E(&OCU`Rh-xA-`*hBisSc{Z0fST`n`SThwA2|O50({ zmKxPGiM9uFQF&e0veWK$YZyC8w$Bbp{(KhbPyfTeJWTE5lNYUH_ny-(=t{{;%mH?d zPx?*&K~Of!d#Z13qfx*z{j|^&GA~uiVEeRm!fL;l>}|nAJ9)gQPmz}4zuwx|U1N_0-*UEl z6%HD^F{Fix!MqV?weKMK3>0>xU!B_DeTh=={XG|Yz67bXMgEe`3Erm0If=KpGva3g zs^dQLu|nLC>fXM(6OtVJpiH&OJPCrx$~YwB6jCM5LcP`v+%X$&L&HtF0%TEvC9HZK zoy{HBsy5vwrE9)>_GWm`sn2{r{Ml6?H-yI7$6a6nwme?akN+v9jDv)*$GdOsf{uSr zB1jbED=8|NGv##L1!=qB7AEN?A*&&cTgXs41?OD~QA3L}FIgiQ>W)&cy1}5UnO@h& z!qx|3YU}41kHTrYBIM`pjuO)2%BzHs;`1ve{^YT8xa4%EuF!;c2usN@3pSahXe&X? ztb)$85MN63=UA!=`A@90XyqupJeZNQfFUG?%>>)koS;oDl1nA1SKS6W`z`1M&c(}a zX`3G!vuW#UU%Hfi$%x=sBiq?09l32tlNvQh!}K>B2e|Jv13E(FJN%SpQ1B*>Mam6; z$hsv)j8~z!EQdA!z5$dT2=3du0lMS5pquvxmHyVzIdGOUP)W%`E7@o}PPd$DS-jc_ z#n8g6Dzl+55yVZRk9a1)ECp1HQSA-sg(@JyZ2-3vFzonYr=WAZS~`4m%;{xLK@UTX zY;yhBWtLxsBb(K7xufImFY&0}5-)|?yW?K+kKw_^1#`V4uL8gNqIM|5YC~9z9?=~Y zgEf@Gw5rbWfEl-hARLZ3FiRsDx<6j4`Dc_m5xaB)_M4#&XG~_We#@Gph$RRtGFzJ2 z2$naM!%z$rSyIlQEA5bAlSG<)Fq?&XZ;R}Z$hBLx4cWFv^>Qf`AH9&_?0v4f>0 z>oxhR7 zEUd*(r)qvRzWgwgDsl=hI08TEdlE)X33dvT(^vE-gSSR8yz}dKhm_%fZS)r=HA=tW zh}-i>PB1cWaUqzt5@O^=fJby97O>2j*k-cB1wFRSoSQGMWW1C1TTPZzFE87X9*dJI zZn*l*bfIlkfF1U}U#o60_wF# zIXyk|XGq!hrEn*f zY`P`Lph1Lk_`4+qZV3bzbMXXjue8T}4olS_?D$$oOH2G2gbb}3a=XsqxU^&%ta5`g zht0ezO29mSj0~mw0X)}M9QDlJqJc<20ESxW?PCGIlgHfZGiC4K>B?b>{j1FY4(3YT zT5-91>ecF_*)GM1F!Pi$_Eo~AZnrx%CIJ2oTF3s|gn?u7d;&0j%QP7@qi&L!}q`IpC>#m30Vs$6!4ORo|vnwA0h7Furi+56DkNPLZyqzAl z6UC)Z{(gAJbj~NqrN|@q{D(lupUuGxHU_pTK0H3`&ST`)v#DGkw}v`88whCO|7{3GJ@+}mFrraf9Wg4l8o!_X5hgK0Zyu@P|-oa(pOLVF!)BxHf}!Fw_fnmI8b8kffm@@F#oih`oqA`nAJ}n5BIzk3fqhtc zSlc2b?=jC;#q&$FW;SkUMUqgS{GZz^$310saz6G9sbUNByJlHI!}Jq>rFl=p=YEw2 zv7hhVxhE5|ag`7Fbn5xRbTHO5lR6LjJ%+9rpYQoQ<3tUo zJjL%lnK=FtMLqoR&Xua;TKJ1=W-CbrN@fC42Kc~OBK)p_5G}ClBUSwiL?4s?yG;6o zb#S#G8!LS(Mw>aJASdkI9lVW#!YK-xY5(5{3R46~8mhB$9z9=a1gW6g(1T|y8Xr*T z0K73kLC(_3)3zAXf^U!f2^T}e2lWB{6m%j!9LjmtCmbJNi`P_EVlX1m5EQg8;Y%{% zGsGFp?~ELhyH$?XUW8b$LSz8o;w<=XAKI=N_7|TxTM4Jlm zw+^ptUysdmF;Kgh!p^kWN}8BU`#46FbtWJR+~{fQKo~~I4Xr$w>b82j0-nJwnxTcr zh&NzBxP`yv46U#AeYT%*J;Lcvh>x9NK$CBp|9)x^GpJ++rHe>YmLP0;N$v7rr0>s1v?X&2(ME@AEAK0HdjF5F#rfJgbV6w-=UM9N( zK95K$=p zy;XX6P=4`E*+*1idtEeLQGsIxq{O=j#a(`VwEV$ZIYzazRz#U&y&}}Gf)ZY#&kx+d zkRb0XQdLs0sU-p?mC8kIEE45nABr`KZeOkdXU*Q;6Th>6w?w7r{$_!vsA|>vewBm+ zyCo*9O{`R^sK{Vlh(b3?q@-}@FXOYIu2I^F?=;C!{ktISQRQ)c|+Ri3+W}6Mn6}_6jw!%rW&op1U5(Tr2*! z)W53I!?(^n8^W1V=ucM@&=8rU+Q2VVm)uaVp4t#1!4AU0lvZ=}KGdlpA&q3F- zx5X?Q2(T>rdg*?r+&@goD_KnCA_LdcmeU_wSW@cQsD90sT}|+8NC;3R`mq`9g!vpy z2gydRU>?gCKU7SsfT}eMoNhJa2QK0wU6LO!-^Db!Jp{L)&W?#ZEo#Gbw;?{Z@zS@l zarCS2v_KOVTyNshmYh)p?*}8mEq0EWJ2lkEjz{#@TO_Yvu!4qcHJBzp{S?uY#bt0s zF$&Dgl#a2zwrg;o)?1hVe5&pF(U{rE;qwtTGT6)v8g0hf4EJ$l5VdqbIFtK!$=wN# zVxy!^5JYTX67u>gD=_~Oq|Wl<_3rJ1}&u=FU&buV-dgV zpI=gc!TjvSfL>qM(}6IQ(+)kbOW*tDYOmiBuHZqCnN_0{2g4i5NZXA%RjDD@TbDnK z^#B+sb*ra?y|-Sq=Rs;$^i#GA&0VWh_>E09{|K{OwV5kgaNs_M=`tSniqcMaHk3X- z%KCOFxrS}Wzi}k;X=~Ad>1QO>O+gY%_rVgqgryUd#WP(CF8E*T_aaV zayLfjOW0mXB1S3b-GkALMs}WNMz^gnNVW?-0N8J#6|fl7E%Z=0;(&72i;Q;7M$O1# znu6&y8bkhG!Mx36ysWLUtK&c6M^)QVMSx%N3s?c;9b|_+tv}7ENdjpWc zpRs!23g|pd5+VH~iMZhZkwjhriXXR-5IHy%TL94>w5w=wK0CFs{_s5GBX6}4eF7vz z7SSgT@o$`|3t&^gGaV_trQI)3+~~cmK$LPihjQ2>H^$x_@JAAAWq`h`SvcNhHrWNk zA8^dfItP@yvVJRW@r$#4C={;tWbyG}}#@B!Zd$M-pikI74CR3YJO6GtKV+ zzo_L1z!LRF7Gt;FW2b>hQy7eHneAU$H39P`S9@u}N< zmmV`LqR23pH-0`)MiWMn>msLF|I*7Z)WD zOHevn6QCFj@5$#~&ZR47=Pqk3El07vphNUFkJ!Cl2%-#WJ*OY#D055E&S$UvC=oc zq!h(gwTU`j%#8oBN_6TYJ}gOn{cU@GZR>bVEBlpIaA1eiTFi;py|Y5erE7OO*8-e- zAGt1RnX)muAdi8bi-Bv)E~^c_(~X(mexB`(;@ueNUC<@;T4NZT1J_GWy4;U8n%35b z9&RL$uL?-Bp~}g}1q_L%n+c`s+O6x9AMul=Gc%#Y*romlD#>)tCkelg(2 z=J!(*8=oI;OHq@gCz@Xb{@4ke(s2&q-}XT-Zvuyl)k|A1hRWa{!lnYAK6+Qu>Q=;^4y1ky><4eOaTI*7par^j|h8 z81uL6QZ?c7Z(YK6PvEz%=V4FLzRf=lJF@l={Oji@rW&b-FBg7|Qx}db{~Xz>?(Tp3 zYknESxd^X#zMJ~!SUqS<^XKvFtb^i52Ns8iffq2S)37xqhWQ_VNBD995N;6{2V>;b zE42KqlSHR=bV#vW(o1DO>pECy^~E6bj7BV!%X--;2Y%(~fmQ1jh$5rS!+?VvLDM_( zN|SB36ukS9*Oq5jr-Ljl;*?Wd6(hGj)2qyxHPcsZ)@>RtHMzbhYF``8b7U0x?HKA~ z-=Z|i1dTd(ON$-eD&6&c_%gyte1*dw*jb&zxxqOL~?jdUWh^6tS~1z-w1pq7pu| zdFJUbkH#Jw*U(?N(TBXwj@Igg<1w7taCpfA+sE_>o{&Sm?BhalxbnoqE$Z{H038Ba%>Bkzo9 zXDV4>zYZx)KeMjqW!#iE)A+NjP%C%lzQS{P#0&W@2vuU--Q;p(BWqWBhoa1c=06CE zp_N1)WvVq)n(~pZzwZ@G(wb<7qEb6@a!07W?ULPP;nj&f_3v!cyOtVmbSk01{j$qU z%1Rg0ZG^Kf*=Om8U2vFayVU1>k*DsJk}Rgi#yhe7*K=@&d52Swx%0VMbH9AjRLH2; z^+w(B?@F9*FK&j;sy#_ub&C4QEje!#Nt}A} z#;GME+?i1B`GhYVT@!IWQMd7rd$yspw1>7@7>Ac{^_gkM%(De{9}{&&y1a{Z6%H=u zAHp~dZbQOQU-V*P{x}vs{+<1`_>On?qmrxhcgO3fAQ)~)$?;tNdcD?Bp=ot7Tx~O* zH$|j0)Dz`_bv!WVQG0Z0y<4MzYq@R^t{$8ccp#V};fwNt5F+GO zV8hfIhN+&5r92<5H%aqz-D!XL?0Iibl5_AIL#?{R+nx3$xhbWZr`%tEbG;BR#x6`- zM(;XNpL}HeEhd!j#LDCP&6$?3Ec8q{i;$J%{cp+e(qzrZwc6U=$c;zIpTLSzR9VMs+AO5CYIH@H%#HkB!i63+*9N9rrn_AVJa>g4)s@5$ii@2nKF@dei3 zr}V`?WTjpTEradL3JT07qwJj**!v1K{P4u)AD5pf zaBuckg31=jtnVs{c{T1RDz&~L?QxUEUT()H1bpVRsjFIs);}@s{UP;>FeVqE+hwwp zNlJ!#4H#@^N-O_>u>&}?03ngPu;TPH{KuIcP9w)8m^??SyO+OTm(BNPdkqFJ*~`M( z9mgO*VG*Xb*_UC)7J?0fa`S#}H*IR8dNKJC(->4$Oj9ve)frg5l?~zMWxpAWwIpj5 zYvVxYM+i*MF(%){MxP|;HD7y=VN!n4bs;+YSIJi!7FBA!MLkd7*^1R+SseC)Y1q`A z+~y>42hs(%ovBLnFCQG}r4YeCuiSi;d^)yLC0=gVt4B`|5RuFHx%#V8Ch?MiO1G8h z&CnV?ja1fU0LHNL>i(SbyjD{AGqh1THn-4FWrvWfn!o{krb3ho=*wu@hy z5CAKWRG{|yvZZR*EKwGfSPwFUeUOqK9Ew$z&Y*RzDPC%{%@?xkxoW!+Ss=O@D&O0@ zVYDSNTXxU0?xli+juDWh`>ef^8j=`Ly;}5+oa)(JFfHjd8V6Px0TmBn^t^OK-oN3P zxdTfX66QI4JJMn6kaPd5x(b(515TUi0^WyT-qik0+ueoCtHw9IvW6JO0^z&Ci)JedtVI*& zdrSi2bQrExR==dhd$r#>^PmtPCOx@!4Qd+K3{N}0=3h(U39zv?JXJJRGc%gMJ^0o1 zNw?xxbD79%fBZH1)2-i11z4 zKgj9X(r5TiC%@*-4YX57i-Af@asOw3VP$?~S?BPT*m}~%qG_Sw14E%e=E7ekOA0>c z4e*m$o{HT38jp~Z;yLq0thJLW$=$cn>c3mK> zl477S$e+s0AVl9Ck*pSMl}KPHXa3k}sDhQl$QXU$otLfA4dlJq|0iUsrSzN|?DF6&i zo=56gA_%Man}rF8I>3UQv~d-B%{L(kNWN$fBG@ObK>%Gm;`i0(jL+B>EbxEjwEqXR22NGe*i4U{Mip=~Xos4Dnh- z0)aFBHcmJWSBX|m`Td0~#zwq1pw;|9C;g&yC5fP1pTj<=18lV4DFlV$?{f+f(RjF1 zT?&;B55Gi1Eh1o7al#k(5j4C*azD9EPDjY5ze+$vEKi5&zRvMu9i5|o`Y{w@D=`+E z#Aei|6Rk&joT5teJDLY?)BFxg09eI)kH9$Dh`KnM-$6taB4}l-CN#gJ4u2cpL&t+; zP#36-?8mj~|M^IBru%XuQ^dvLtm%X0UzB{KQkX2`uGqx++9xg^{NsRp;UenG()6hvAImn>Xa*sB{(0){h^CnSbH93|DLCfm751#W7q63cb zKIKWgveo8n;3&>SextZc5eQD&1eyeQ?F36jBsmj%ZjC_sn>FU5=&17w!}Gd^GWQK% zeHcj~fnFWJ1UvgPp}JAyC}0=tky9e;mK5%baG}Hz@F06)@(o-fijCNN_>?R-oVGja zBj1H#&~$ZH&%)#N*^-pp@Yy!QG783&gVC~aqr-T;jDVM6lBf+axXK8jS5+BV~==OG2MZR+wl<#>IlnHc5qEury9#qlKF@j(WY%DEQ}r%f`NGu=t?$~Z#S zm$BizvC9&}uM(7BM5_#qk39}B>m3yFEQF{8$EBIRlBOS^-t{woH-3J0Q}siM`S9*5 z5*9rCSnihItFh&g>HEkR%;~kPuR{c1$CJliC|dkD(!r2hF4U0(0Ohbe&Sd}YL=wUV zcZS^jdLyr6b5nUaLGf1}5?q+>=9{L3!|y!njyZUhUPoJWO1>5hjo(cBlW@T;cOpL5 z{O9JYznjR*o^fHVpx`vi3%RdTeL)80NzvtrYMq*`mK4~vcKE&Xhi|!71LB$>(0i$I zFL}(^o6bklrRdYJ4evnG^Hrt4RU|EMH|aD6O+ zunLMs(o280P7^r&Si6`|h_|AVA9&a)@(Zf^#Kc?uG$j5_9)bHRd=VKdCWBF}d_M!7VNWf2FRh?1 z4l!Gn_1%8c>U};VU#4)G!Uv+heL@T#TI2#XAi?}(XBYKm>*y+}ZuZHE_F8#Zy8ep$ zmp)W`eWiZ z5kDU%NU(oL2!2OA2EN|4zmv#U_`<1R`eRSb`|WL~pMLK*?y_9juS8g06vbEeGCH4t z=7u!*hQ9OOT_L)VN8Nrqbgb0sISR!o&v?S{SU1~q=c!(L5Xxz9joe(bC?zuaWC z`<7^KSz=E9wE5ywX_HGD*e;IKF42;9qI*jtKkOqwUsk5|=WQ!?NBj>G!u`_3Nl%v3 zT^if0(q|LZ<`YkTFSua)AIrY`;ZlSbMq)?EcOquK3r$6=yh;H;5j%-u5a1!*xMkdkGMkG5NE?Gw;q*yP$4!t-La9Ko?Xy~QK%u3{rif1TyU%U61@gdU55*lZe z;JE0D36}FbtVD*{cg7E|T$%DnorTd-5?1y}7JHuO9Fv6rK(8DQAwvR` zmuszc1frg=|RiYt<9LJ}|B16de& zDV4tQH*kr^#wl+nII|ML@epQ;TX@0z)gh#$Z{k%V+{R7lGOrI`Ws-g&C}I}8sg~^N z{q0GkJJnHycpA%Y84SdYu&XG8kD9zzR(zPGSCzVH*azZl4Ad!jb+Yx)Mql&=KYy(MS&iH5}=NA-2^e&sc4_>A^-Iiq?rg&f`oW}aD8xz{@!(ylYpym(0xT^!pLey?B+nAm(TB+MBn5@UgB9_#Q5s~4z-PBZ<8)@5Oq?M zIBO3nvbYx5<2U*Vd8rwGmd1Qg;{1(ZA0B>3J-wE1J67eeA)31sNAjWvT^son`1BK! zr4Sa|nH)8XaPU(Woy4C@e9tMQtc#9P4$atpyiG{RRIV5ms{D@^44 zRPXn2M<*-j#G5!a_AGG=B!?6Bp9@hJy{qmqGe8){&>8X}C5FBo zpSxlI{7Yg)@9KjaThp-ESp+Wt*iaJ8zlC;5{6;=;Zz|mCL?*)frd0}lYuklfuqK`; z=q6YuIuQvGi#O#u;cn=?I_|K8*xd%-IAs)EU@`L`fBADw$bd!RfP_SRur?k5Kf)RcI2cRn2q2c z2hGNTmHW4h&_8N?w?zlC_?3_hM20g!ME-?aXSZ!rw1~`js9hb*6lYobGqQL)-oF_U zRi31Yy?HzQuo}I82MOSs(U+UIy75<^r2pyQZMv|QuV|o^1lUtH{P7{p)qCWsg@toXoEZQ*VcE%-_}{zT2J3HTxc@N4qSN*x#>R8z;!jX$EYJ<@Uaz| zVg21tRwPjgrk4#71{@Roe=Ti}*ac2xX@yh$KYIqcK6uWQEpcgcUv7CMNA%)Qze$mz ztzBhYwOMeGCxxW10NWn@UJmhtd?8JV=&q7Wjn!(7gSX7Ec^xYQE6MRbKzcl@OyH67 z&hlk0mM6#WR4%Wc4?0@6lgfBs$~imohTlQeam(w)sll_kd~N#D>1ewjCmKilJA$!w zLC*)`SKNKZYRr1qZ)26R&9wS31ZL9u(N{q`#LSOkw4ZofP}cKchE0bAHUCP|n3mQapy z?DDX3ex8+q@DdiBqDCqiaZXhqf-h4uow@aKPRF5Of&mY|Y$A{0e(j2HfabZ+S~&3( z%j_E;Zi$xitmhbN-&zIZ_})8rEfl#1I+UbgtQJxJ5%~_;%pr|^xC&yo!^i3;FYbzJ z-wgRHURPmao0SMX#-RbV@|SF>T8{p{#mygVbYzY>Z4W<|0a(Vkx*UPW1)dTBgVJ+q70Ya^)b_b8so8&jB4QA$kwmR$1=#jo81h`hRr90&HvZ2!6 ztgbm*LLA5>`(Bf{1rv z_NaP##NPIZv1CuEWs_}@!dta!W0hjFNWH&(KkY^%^vie zt8;FiWMIIDR9t>{IZA^SJF@!)byvQ9FA1soQ6s`YKVUK3NCbodz?AVdgP5f$l|0ls zh_>~17V6{+2S%mrZ&J9}U7qrok%%&L&Stm@C+N1e+-D2RI@V)$dOReWpW(p{@v1L~ z*LhV}l>@{qXW!3+PA@;}iXCKk#+Y)a=P#;<00#3WqK2daHkR`KVzW0Qmr79dULIwK z%fn&P>HM4nop~Uf4)4*Tp@sw@n~zC|y_JlFpC3`#B|yQoeoN-G{|c2lH^E&9g|9wD z|E_1Y5FZOO(a5uMWX>WzGuqRDmjpcv_+(%LzNk%BFj_a46D7vnzAdjZt2x%9R8?|$ zN@PjeISKinsdV=f+#EDAWJirHb6D~{5qAxATJQ8eL!AbdBNU`6m}ZGdU?u_3A;V`r zEnh&9hM@RaKQ5YiCUUOI52R?1E&g;QqWq}qRbbNNlCOhbl_yZI=t^oh%`Lwv3AV!- za0>Ufp4F;+Pnn2`yjXU0gA_Z2)+=63yLzPC^z>~o(MgD=V0GB_?72eG)(Fm-RItyc3` z+%jI`Z3Rnvoq>jgb*_nx+S`|$ah44i*2t2oxb_Cy9tqpW4bx4$zcDZvs-7)b;u5>i zKjR{*ZvKDHi(dS%c~SCZZcK(_LMYaWVknqoNn@}HMwdOsJy<_Zn)2$MNwE}BxQC*Q zT3js8gVlM-j7^Mt-vFnFhGpe zZf2C->aT$J4QOy+nr@G~VNLf9m*6=mmyRkP0lu)a$ena+&YA0}J_CxxHd6AXKP+W&5eM?|cy*2p42mr`$>7n`=BxK(1^3~S?(vt*qaG{5WM5&;d z69e!(?W6q_1#eI!m>trQ3%~lIUZ5g|ib52c2S&VFFe)hRn_eV+Hn6}7#c0~J; zMM2sL@#CV%leo8^`Tj=iY3)~Jd4`p9b&2iZmRg%N5XyZ( zQ*7)=Okx#FCd45Lx_>DjV3Oq9z9G(37+2tx`okFO)Ov$g>5i%cj1kv-Zx9y&f>1W9{HFkx3cn_n8xC$x$wA;mC z_u-tapGwiusOO>S_=&YIl6*QRV_(lDQ-vAEBMj9-D-z?=xq%4EkVfNm>-MpG;-%za zEnCpWq-e$us9Izb>tq7w&3YQlDE7TtB z^WW&{i=6nfaOI7;o^pz)!IRtyLjurUtI6NDV6y$(dV6?ggyCw$01x-VftuW)R_fA8 zwzk&I<>Bq)n+y+5i*2$p*}q(XzW!s(SFuu7!G*2N7+i9Ja@}R-uD3dTRc2l?pfwl= zO*K2#MsL!70rPM-_xoW|iHKlBW&jT2_=x)9M7LLbpfqP>#3IaWXySs^V<1BvK#Xx_ zaFYo-UT3sO$sJ2v6BP0a`hp@yC87ec6HSGa_b%s*yD^FA(VLM*^xdCrx*cP&KZUbz zF+v77Uo5N|vB>iyBr0k;7fWyz?A&^iNAW_970=wyAguLd`U&~wcKU(ZR z_&g8t_|%TAtK;VZ)4uc+e%A`-jQ>I0eMU9)ziWfv2?-q%dhZ>iN$@l{6tD-+J}=e4+D2o>6v6X~WTk}W`uCxXLFALPCne-$f`reWHnwD7F`fOBe zc^$T(FB_n!7n#_70+H_zpwL6#A=5v_0=mEJT3C{7f8PrB%WWq;UdAyk%s1Cm!S;&g zKmTS3%uf%qTFf&%(PWz){+);{In!B_+bGduF8R)uYh!CGhp*Hrhzj$AKGV2-Axpoh zV8Iq4zIl?V1l6$1+b_Wl-ZVlM>+pre5G~qAv5U`_77E&NJS-M@*$ZJycbdm>Zpe2Q zg^~=Ya{|nuNhm34u9e9P_I36*5^ENxoBWdcGMHu03`<{37ux0^`h37=!YV}4F{@MT zUd*NDNt@vrrHk)-A*oT`<0Ec=EZwOGLD#?dLlJ#*+OZnH0!~Z3?pa@pmcFK62L}4( zIFWC0Io^E9W7$+OhxZd?=!0TR%$k2Ax?cFj*##ZiiQE@5Ya{W5%R|B`Lb-oG7Y4G z&|D?cPGDwqF8x#f#+vKVVvk14dW|N-VbDecc&DWjwarVo$1jVJxmA*Q#MDCgzF~c* z=`a-IT2T%Wd_}eNXHw-#!KvG$ygjd=BdQSc!lsM8s^!wQDOlMYUx`SyN;{>jmTAAw z@b}P{7yb0>xZ3(G%GCpAJMAW=j|3E=3G=n{d$exLhLW7U*sEjhu;c7zA&%g$r7nX> zj!zKi+md@M4#F*?5Ps@BTxnly_=}lZUidb|^RBu}_rdV|zG0)Dz_!!#gaML|y}3Ue z`uMoUPb-=mD*qPrL3lH!o_+jk=rWh2Onu%jxUn`93@N%yY!c-a%;V)_2aEJzNQ;M1 z79TM6t;pr;@geemtH zR$D;R(oXH1706l~%vN;cI;^;w#=0gSz_Z2 zAPOx@n)`lEguAUk0*2r;pdTzTsl+$DRo8Kh(Or)?$9TAUKteI*!G|rmS$A*!3SY=Y zF$XNZs3f@orr)ano7xAd2xd^jgx$bxB>JTCL1bgWVwUF2(SjR_gHY0s;i}5MiZ2wO zJ)C>yK0ZD)eo4%wjpWLC_@ZtC$iVm&hmd)jZ7f;$^G}0Pqsq+YsS+hu?7^?I>4z|- zgA)RPR~t#gbY@#eq`k&id^7#P2<5p&4J8^-cR4IpQU)^kT<@C&$?QFZ?W;J`pD}17 zVcDLxb&0RS>3|kRYs!I#Q))so$9x^rkCszTirPY?A|GHxQaZ64LlS&#F9SC z-TB1EKj?@6%c?afy>-lYMDeq{5;)!*5$I1K*GFzriQ2lDMg*9qNCZp4lOGIt*w{Ds zVXBbK;;LDDDnJmykq69Yo-aS`Z*_SYf6rmi)|XYzbWr-TVSpruol49q@c}^`6CV4R zP>5GFiCmdNWB6^4z^hu9H%_M-g~$8^@?axZIE9!;$C1jen>lvKOrgEP7<;>Q^GiJ; zfxn{gg#~u)1U}YM-`W`G_7k1q9t~|~R}26gljiy3>fO4*7*6_p z=dF#;n=2tp8ww=@lvQ+l3p3AkoE8MCFZOeMlX~={&DJO9Y@fIJJ{#HqpSHf3_D%vz zy_8XvuBoSgKR;k9N{a6ixpy5&BSAa&SwP7LKldwSs*l;#m-5XG;X)`vtFU6eIrmch zeRRu*SIpTTTC%(KS@hw;KPA%TZtlk+Me5BJ_fNgCB;zsKO0GnWSFT>a?}LnBDDwE_ z3Q4lZLrBCQ5{zY&qMj=u4!B-Uy^iaDp##PdC z9wd4Sc}dkO2A^rhB0^CZ(sleb{C+V?H|mqTg0>HieT7L4H0!S#%26H(_8Z3ky_^Ph1T4M?Zt%_)v;^4UFAv&1);B7k`eSzwHt=2lwjx`t(1sMZF6~JAFT|YTwC!Lj-*fHdn z2SAg9qyh*9=0N1GkbADHaBJMU32ELGh%O(#9ru26VX7%4@%hMFolz zM-Imi+y%4B3(Nlm&meL87ebUZ(1rz&mWF1b~pwQu8-K&&QnG(+y@A>rZ^gvvgY0W{rn0QW>odK z-fpTb)%kI)iQ4qF)5DF~xEDNxyIavc#`w+~@KR9=BLRBn@6o^D4%f? zt+###fV6i)xO_KTEKIzQpym?~ud5&J7XLWm@Dd~x&A3H@@b%^Aeg4AQrwJdZ^F9aH zaRVG1mP(;Jg+g_Gx5T$RN?oFhv8?Tn<{*e8VnyZLU`bQ^BrNV#2+b+n8l{>XJYY4z zs99eBsu|=dq*wWvd(~i=>HP!ZBCucwyc_aDptPkbDglF#jCdEx$Mdbv;{k7XgJFC9 zdAVIMQLj*BnA-zE_4h9?=QwDniNF5JW5w;WhlP+Ta4_M>ZhIEf#omsRR;?)>2qnA_e9U-aIt@QnBX8{eS)7ac^f%=i!&Tt&Dqj?s&xzcy0h72(w0Bj0F=a3?YK)Gf--NoACTj^E zFPyVV3^oT7<}73VzdcmX9*8>-d9q?!f_&316zNsqQQ!0Jc5T!}qO+ak$z~tSQS4UL zkIys4h+#e!+mDnlWnj+X25^68NX_k~7+}^MELeQO-RxGsU8QpJ^HF%^8&+qZ!jxqC zn~oAdP7!xLFULjjo;oT=YUutn*o$jKs&RX*=2)D4%l-Xl?{gJKXTIK_lYt5#E}@8k z6d=iMZmA7k;-1UR%H}8Tq%`5K2e3mj-^@>_L)-BeFj{)(xFMwcWMe^y#4_(g+aOV?ovnlqE zR#3MML!H2rA)8X?C<4AzuJhOYUicllx2Hd3OK0N(@&2x0d4aMSZ{tJg26TWm%wC?L zL;qnogOMTnl!><296xc@@R>R}k)30>Ik8nmgNYpKH%PSjcoofnP{2jq5cxcoMh^iB zPEt!|!P`g@8Svnz$vQ2uoacnRKAq$aO5C>&&)~h3Uq0fW1QEVnTIdoJEftW*^+*6? zoGT8xkJMXuNvG32wj0c_syEH1k!P_~iq3nVm=NZIi!Q-;P`!A46saYcO*_3B6s2y! zk}?*_b`(66wqxKa`F0ubU?K~k{F+cAT%rnZ9cF%cglWx^twCQbIjv)u%wJWq_>!vK zVmvN6`D|ko0c0CXucizNmns>KbUmG}aZLoz85Tk!&R!TMeywJ|tr;nJ(Z-)mKhH89 zSkc5-ti(ORxG6Z1se5xWZdBzmOb}O~n!GAcm{GYQ$`PqYxoZ@@L|Y)|jy?Xs&J|RI zAfTGeM0&B4WFOi_3Z)mKmq2^5jm|j;_?`M=Ox%k+A=_lod9~=L1@wl#SW;wJhDHw` zWz&5unyF^fi_f<-*UK1{dFnTmv*})zy|eEYRB-MIC?b&83^z{hLIH+q2^3N%1bDC2e4^ULxKXiMQs9pv%lb4H!dei zwU!gux9^WMjWHyLjG&Y1(jJIUADJ-zHoC|@-!mHvJgn`)f8gMry|5T*Qj`K!mJ6I9 zk0o8jX$U=VX^OA_d6N}CC#!f_K(o|woK_SSh7kAzij2bs6kp~4a0i8In0@hXSUY$D z{lN3|qDG8o@}k`O9S=UX1LU<~7Q0WA)3a05ym2eRMD?Kf=ra&Z+_e8I=EJGVm1g2q zin)VGqTTlxU6<*RxXpFyS?zNR#2NkIyigJN5ExS1)ZnV4B$wn4idEJiltA)?jbi^& z4&3M_!*fITIWK8whdja=KZ*yz5zo$T;M5}uGSP^~R8^;a7K3&AB00;ndQ^@7w%;2y zCOFW^zr;=Q#~_BpHZ+eEx|{Uz{bu+>im$-3Kso-i5uC;@zxMW?KY=9*;>RJH< zKywPPEM%DIc>xif173bF_`Uae5mUgnikKv_cu%<)6dUrMehrineqJm?=VSn*o-7h= zD$@#ZGM18@s`7qaV1BSeZ99wlW*B$&@w+D2hnAVCk9wL333suAWzPo2iiSxZ{6U)atU z%VbeEQy1i3)dzRGkEBR`ie_w+Nanth|7E^f$?nsu6W|saZMKG|CQ_s$vnN`$Fn!Q0 zE-8VGQ@NfQ(%p2zi6ohMe{D{v2d~kaTKthB*VMe-c|A&2`JQjm60a3qdm^s8UL)b9 z5cdLmMCb4~nu7iP{)Lbw520rXRz2D87Ay&~i4Y=K?#CG!UKK>3M;>`V<0Jl)3D@lN zlK8ufr_&WudJpiiVs2N=P%CXSZwTMa{}5jyZ5Nz7d3G5`^0XUt3{B)H+({Bb56<*z z*3$plhD$S3pQuMX5Ot_--^x8L5&pX%0o}Atk!RlcmA3Fb?izk57NyS{FiPSPEyr4b z+lW1c$=ZGR_4|FDzkO98FE0@}P489#*29%|@B9a~iqUOxiu;4Q{=YqsPdUY2@%(k~ z3xfcCqz9cxGK9DLcnqnp#Uf$%LDVWbfj7TV&(FTQEGxdPW&*3{${6$g!No%DQPTJ2 zvDLvbkik@A%-uI2q#sgmq;HQUCvOJJ%3H*da2F{!C?&DvOoQ+gMFxE1{_D3lULi&L?TS`L#Q80pyQRZO=%4^esy@6wjy%zT z(3Kzlf#m>o$jBV2Pq-`(jh-MAoS+t&pp+1#YCX|+N$ftwAdMW8Fa-Ff8KD{VWK)84 zbAq2b;;n4!X?~xCq@7T|{)O42hKXDSc~}ycAYcdebf1W5s!r6GPoAv1(~~ubbe)`^ zD)Gt|fcAUP-L!Gjf{cP5jQk$VPGg7VZcGXdqSVAy#r>eVDja1?!s24=8h*+O+$kNilo(y}iL;PT% zffMD-0$>*~gn~E+dEzEdxx$EWJ|>MOc;Id|@R9vw%{fid)?%>e-p2Dwx z(rI}U@@ zf`P%vs^}pPfb)ABqosb6$nX5zrf%H(B2@gxQ_;U#?4*H*G9SA+%>0MynLMNH0m&H( zmxNvHl+%$|j3imH=u8eI#E;8}wb~bpoM2=Q6DJc^&OK82R;Tbvi0jHo*GB5`Ld}m5GBb==HM@*~dla;z;uPB& zI0BmKLW;R~T1%u%jpy3!VCcB&>!==PlJz5EQsqn|>9TWPEz;gfQo)r*{W}twPp8}u zS8@2DgmLl>)1R%1DhdV4<&>CW}mgyoiw)d*7gel@;6B@*_Wbcej$q?A`@$W{I=%8@#b^v$ob)f#UbRoWdg|$a-;_6-kB!;PMaYP4 z;QW%rTZiJY*U+Uq2Ac<)7!}tHzj6h9Kl3J$$VV;=glNvow{)mqhpcP-@p!Eeo9esQ z?A>`mR$$`SZa~!2OP_D$gP&}_1p|5IKmL@)ga1Z7RSZvQ#@q9=#D^JHeML6YJ~m55 zcHCfg7cd8YFm75e{g(owU~A5(bxvurfNy%b=n0~BFP+;<9zE|bCE=tRW8{U3 zjLUp0QrtfDz=&vhrh`6TYtNCu4RPF}=$$AU_GH%1IK#a^_17~~mX?00uMpoaMbhIe zGSe6UaRJ>p4hbPXkW$LH-S3;0LCzr0u-n7<$cnslR(_jNe4z(ha}`YLn@H7~NOzOS zKn2NKJ!+ed9uha;Z*|m3X3-I2Q4H1A+)&QnV=%yThHA`Z( z%Ak$|JOok0?Y?h*TQhN$|GSnRB#{y3oAJICeNjfP{zNgxr4zi&%#>KmxyhvB%PP59 zRA-UZ)1$x?lFSE5QYi+_U*6;sNfwa#6;QPm(ETY0BUt*{!mP_?ET3s?0X4A= zGjU;4AD?5K%*lt8@O-j-i=VBegRz~Dp}1P=E?M^4ugtft z?6u@7vrhI4>gjUd@+Tk5W2q-XB`e4XDl)UmYb7RIo;;l$e7dUgY+>2FOM#^UNsO?~ph%i6cjh6-AAjmkbcy=b=;y_@E6hrA_dMUpcm!k3e>#I+rxLhRj+{@Zl1PeLP-A*>s{{3_3?~~4*cHjOCFEN@oGyXJa6Ge`)^PPFi8Fezu zqF3UkU8JrVtK;^(z57P2Q|Yq%v3SpjP#=y(4N8Wlf6%9QOR|OP)^RSo|J~=FDf0oj z#XfV&fjjelHqt?(#eRafEkrp3YSKf#i&jV3Uu4|-tUCIh+I}~s`5cHNjY;myH zXE=anNGqoW`gTOBekA(sUb`Kau|aUl9~&01~GYNpOcG>Kvys9OPddk&qgtq5JXN;)`zrocHdBpv+H^ zfS(ebKV|NID#%Q#1WamlPU_rE8puo;2TbV%Ot@N%#=reGCH>96W0a0!ENlR%3*(uC2AZt)ID=4S*{C z-o`789ap6t=a3!8{v8?cuAt&>8GT=S@GcK{k4tfnBY2OkZ*Nc?%x;BQpt?V@Y&}Nr z{NvtfT2{U%uesvyF6v_*&ocetQsCj|!oy_BqoIzYgZtGRS)TJ}Oqg;^xC~5$C`RHB z#^9ABx)sKGdO7Cjr$e&x?9V0nP!bQj#YCTrNuo{^!8jJcXa*(XRXQ)e2*2_tiTT!g-zDBls`Pb&zYw z%^>RL8^aZzH4qn70zzOq1knS`xusA5*Duk#cHu)XK8++AK`B%Y$K?*Fn&JI{2<9_P zEqb#T(GO}y-A{3umQ1zy&60~qXSfyqpAnQ>9N}_gfpRppOq6hiVNt?#Vud?L-Y951 z?FEh@_hNW(WXojBL#>?P@CK(l76Z2-X&oif9gR63Mc5kR^mqa31|=Cjm-sTRtvhk)_Sv9P)6^6hynp0-r`T# zui%~|PV|`%r1jzKbJ#x56m~w&Ec>6x3@`$ww?aw^TDQN@&n!c1L>MLU@LCYgLtCf> zzW^43@^6d2KJ&5u?8-Zkhgg0%)H`xD0y^bWb8`9HA$j`_z(@e1+AUiRg>j8F+-pLzyhv~iABdP&D@rzG>` z*MzeCC`~K+%j+NliJBB_1b2hL`Jfz+8&*|GhLhRzj~_%ycgq2kSKT-(>`@PnC1o>Xj&Sl4j;@*WO#brwf!k zC8T~dw*C#WT)*Go%CeE91~-!@(J5A(u?5&~H~PP`Kt1Swh;j^85hrghS6`s|W zBDjzvp{cshSe7HPzHuI<{!%aIz3qn<)4E__@-sw7j677L!08F!SQAG` z#F7dJ%lL(I_$xfQCAmSas}&E4`#qSzk_sdZ9TY}wdus7E3kdhYEXJ5)zhyUC>sPj5 zxJe$S9KGE!{}8!|C3iFNJ@EPy73;l~6wqkN;Ff8jaJ~8Y03RN(Yr_EkB__8oDDVy_ z2ZSFbLU}v-sBJ$n0s@@!XYNSEfj4sg4Xu*0nk2fG)J2fh5)0;_1l@Ft z*zqt_NXd^=7ua~WUaySoIRgU3HOM|iroiqCASm?;YZ5^JSyo;B`^Uvf)VS1o4Yp+L zv?r?!CYF&@y+6_E%OC~@$`1^5599U#Mq-M>l>xu21T3`b3}k$fJuiq4=!hpivBvIf zBT)~BH!!h?7a!3Us;g43GYDE@OVaj#3?|((T^O-d5Oq{Xzd=egq=yMAtNKu_EJMU7@NZgOxao8XI`b{lrj%x@ixl5hJHf?|iT zjvZLuSRTjo3b2wO5h);tUVQbP0&3BA7TKwZy3; z*#^Iq#|C(ipdG~R0ghx z^dRA`4-as>3Z>5n(bjQd!{~#c)Gk)!``g?~EtlEa*uA`NYq}0<=JUb%CQa3^d0k#; zE!2GNqc+zE^VS$-5#=b6p)`j3rN<<4R;Ce+rF4f*=6HyiFW${fPy~EmFp7!QitNZI z#jC>k>3)rB`y$y(r*1qV+BHlHW4MxJPX+nXX|vQh!J*@k`C`PXI?j&iARhhV6maCt z#S0G(<41p(UQ3$F;TJv)ErWcej-mGZ>O+Y7lt#VIK|L8vze_pnTHlc%Npds(eEd@enM=0D>;=PWiFjsV`-Hz!FXBS8 z;h^O|KUveeojUWf|8(WX4#GthnnO zd;9-=J6Caoc8yTzfdaY6nQqtB(kp5=Z(8H+%c5F>lSr+%>!h_ly7vOR?_$)5)>?+r zf25pf*P0KlaVd%H2NB!^+D|+qgjMeUsQ~G((_Rj%lysb(wv`rQQe6cPz9T%(#|zk2 z=5L!o#mAi&^91Z@ziRvWf$*YSD`59gZQE3B+(or>z@EiX+e|m%WnFZ@zAb zUZ1BFeYAO7R#X>}nD7QTf$wZzb7W7rOas&K1kbyhu~+wvOhE*K=qb_VHW=_mz;qxA zu#H(5`6Uq!<85ydVFiM{`oyx~_dUY|L$FX`eKfB{5KS?sI>T4@2)f0!$nm3Y6bgny zEHZ)4jvoVVxVIrVQ$6ssI)>^5yge@h*qSeXePDz>+z;KO_8U74eQf`J4FPaq7VI8@yhf4{xT6H^`IlOuqsS|WLOF4@qCi6i9#BOBME^z5K11#_->~Z#1 zv1Ht!(RH%3={WKUSig>8ECBEr2$WyN+Sr2oGr~-Iz?MycL6qS(EjASAb=dNCknkSt zXwK+Q>d}5;Ky(7ZbpqjMeQEIlg6i~tD(?WmUrW`WkO@?~N{B-Ezq<~r7>4^J;0HZ; z-ulrqk+E|=ZxRFu=eJ{5u;Vhyu%E!`jsV@Y$he)z*Z;FSaq{1~6Mz0YcjEHDxD%(S ztG)lLJMriI{2onDoUi_eJApb`LAw)w(bmM#^uM7K_Xm6bpc9*$sQoe2PCx2*>wk+* z9Q~&_QH@%d{YRXbP5j?*6BDT@q(5rZb!oEyKe!20Z!hW}Zo&rDZHMYoN41Efn)p!- z?Eg=>iT}fz5c|iPsH#BKu%kYbqpFDiu_pcE{%@3tCrw2k3JVMW6Pk$D z+>DJv`TL{Z=q&sB=H=z(h${5IIDqjPEil%2pmR+@AFY|I3{qHKCmHf^rG; zhSPd)uSGD1b6Q8zAtrhwIZMk6BXC)58SVJz$!wkqH5eDgVrSV~84}30{Nqk=Z6xGa zaUubJpy1!#34K+n5+Y+trr)Wib~_t*7_?qCX3w+8N==!^$s#o?UC02z zAcY3m)M}&A;F8L~Z*eNlHJ?wN4w`0PqE|=y(st)-hf2Av8nqIurax_EW|O)&t(&2n>?jT6xLoKZhM?cjDOTBCUB)js-uo)+j-l zMW3sNvZ=O(s4_Zb*p05be1wA~MW75%?jLu;h^+o;t1a4{;Pc`_4(hykkbq6bG9akP za1`;dNKMM@*q)VQs`2N~wmr)+v^&vcC^Ta%q$n-)`%F)X;nBIb7DGm3_pdbGqIu`+ zj?+@!=e$>ot>nzHQilR(Ve+kuDDtm*Pd*ucb@kK7N6;Tc7JQSgGEImO+qVs_grvu? z#0!}-HbzPu#TdT-0))~H37?nSjAAA%rb#H+;GGK_)S_KLdzWqzDF*`{X_2Llt8qt4 z%VT6e>lGzPp0BVazaw7e8?8JTsmA}0I{^y-aNgHxpYnNGwa{NpCJmDBAd{kqtY(EG zF3!}#g~5G?To+$WqzAgCi9@Dhs@Gp^LTIfOBT zRb1h7lh&KDvs_Fu@v_(0>pr4;#(|L2dPv>czubw(!+j*|`5fjLJp7 z2v@TQ?N0nT`v4Gd${8no52p5ld<9fwIk-ZIDEsK39|weSvv5sg7~wZ{U@}onC_@aQ zNYq7*2^Tl&eO!Lw&7)q52L=RQ>TAX1G7hp&^q~UCv;WqexF}cGsni3Z355ZL3jJ8_ zN6-nKme&S3rr(?#>FYwc^}%#sSR${y+!90&f5*D#*w8&6nQm^o_=u<;mM6pHh|XkLqV#b=;kjTX>F72q8xbIBZij^?TruY#CWt{ zcr>TyZmV%rN{oFEH2LJQ!Cq2)sq?YzvguX*;0ks_&^y%rM_(2Q0{o3R%6`lex?E%> zb$ro;e2ov3Z>!R}xuG5FPmG@VYK(qxoIBTQo5v2yWVVc0{`((^R*rjd(W7i0>xm8r z$?TrVQBq>GknjRQ?N3nJQ0c_|vhG`LV1Y-pAt?k86&b7t9!jGZu%SnB=D5Abll;}j zN4(TBByJWI8X^p)JK_vuOTq>i$JS{tdcH70`hv~SKiI2i)P1)`h0jgcqNl9f4eyaK zOSpWOS4N17Hg^g_}qUbJ=;cR9+=^UQXl7@T)skIMmD6LwJ z-^r>|q4!{@eI$?uRx@#(j+?4dX50`}ojjFKTgFU&CIK(AO%)g3Cp~E$k8bA9Wk9V6?t}nZ>SkYghnC&0;ZjPpVVX`+mRr9H-G0#=SBl-Qb+2-l+z|$JuD6@s* zY0=Meo-X68G-ms*qY7IHTf3{cZezN)e)5aDiyXBgmb;%_A?SSjyXJR`shxx1D?O@3JW}7D z)Q@LRAG6Ji(YJmb?f1}brQKAAm5r4VE9LCq1N60c!?mAW5^!?3A+sLoM!E+f9S8G8 zx^1()tzH!a$9$qQLgQ608w(ciNK*TEs`J^oCSAZ$e!BU}heDY{=#|?V&GVb_ z^sWm~e!x-m$}P5a=(_|mplKy&V`kZt_A&iRI>j)K$I{^{$NZ8dtn*Z2y8}-gb%TuW zIxjnVyU)fNE?m1t;MvkofA7YqD6EbWre#Xd5Vqk;R?Awbh;zuNcz5^wmG5%89;))& zKKO39`~K=X>i(}BiULq#N(nec@W%?nOOJIe=0LNx-_@p1-y^ zFy*taelK7q_VRef*Yni(;!W_G$2-*L;0NXJKt2H&*E0Po+=C**o(VA7It;gcF&M1$vb#m1!_eKuyS&+M+Tcj@_thbFlz~$nj!IEgU^YD zVCsj^{lq{eK;?q)(gECt9@3pM;V%)68j+-#SYh<0@DqElvo~RHvH6RxNINgg%Ob?_ zMd4P-7Nb)Z-;LoR0)*Qr1lG%8e|K@`WK-wV?FR-y;G+^q24xtIwd*N`cYt_Q$7zJF zl_fU0PpEnb0l6pvU`4EIg(V2S=n2^7c<&i0nkQ}}Lhj}5;5!xmrcga7Kk7Cqh=Q%ygWHw{s+1mdQC98F^G$EnGB3 zH{SJB$*B^_+JcxmPqOtg<0Nk~TQhTv>$CSCr&(NOJOC&DN za63o7Q4cX@6dbsQV z=1sPkU$JUpQQiAO+4-U@Z&Icn%)4VeEO^oGdw2D$5`}`|35|U2tO9LGxN=?oj$`&- zMTtX{dHI(@Y3kB?(c(*NXClUuLCd%oW;qTw>`s}b>|aYZMoN!y$|WU9asL#;-ju+< zmPNIBIHPt;q^Qf|xXW=20DE|`iBl=o3Aj9;@LYhvxQ^YwtsJylM)9YF>rZ(IHK{0L z$s@n=3^O?QDnYRuRNT@wU$d~#tgyJPFmb+$EUFTl2+)%+Rg5Z!7~qW5sB>tR&(H6GlBb2PqXfoCaHl_1rbH!XAln59X2We&+Ng! z$E|zIT?fUh-kmQk)r3@=m7Gu~p0!b2Xu?+na4`(9f9cngN0(Ci*ZtUa(Z&6wKm>9` z$ycXGl}%;fj&Q>>;PuLiHN4T;{8AqU%@u^48x;g0(@tf0RiALIpw~!jDSfO{eXIvk zjWUj6K1E`z5ZqljtQrZ{oi5+ot)i`}e>YEp?S^^8{i)UrZY4l)VM(x_)nrzc)WhSBbZ~UFs=vGx&RasYq+oYQH*?C8S*$w8-2oHP>#ZWD99IYv-Y|dRE z>HAavzP;#6MRkHysZ)^Q6SMquIZst=LS&uZ>JYcQaJ?wIvL4f}iFFKe44bV>Mn}=v@BWxr(CcT9@kD zFz-4S#`N;T+HCLI&o+9*R_GU1H9i_)@!Qx^q;tx@6Vu9s0bw$n-O>5CyMw1^0@4B5 z*Z%6?^ToD@zzy8L0LyXf!LRQ5LetYY&=D`y&CO+Ag$I1hZnbM~b-=5zH}Au&hq&~# zFzvP2SN3wvJx?}oMenho5Uoy5Ej;_J9Zr3a0+2J@tP5x;8Z9l^`+(Z*JEyQ!GO+~! z+?5`vaUH(Ae?MkbqvUNh^by-a1Ib=GJ-Lzpr4V1`|@~( z0`TW(vlu~Gjc_st2rlag{8mX6qX+yW?3}*XJ#QyGMdHd}_lctxTOP;Musnc^@|5(; zgP+DUtL&4SAPIh03aRzrTIFLrO(3XZgwy5|7O!Hc*5UqMB@;)~O3Fi90RnIk#;F^Q zyc_lnIze_agm6hzks65aC^p6)gZ4I>m*QY(wLPyUrA;7s>gJ6x@s9;zoX@U)3~Qsn zx?bhALPHQ%IFkbK3IRNs-qB9{gzlKe=-bBFoH5K^z`h4_0EtGI#?v~+G^}tl07Xne z>}|9LkwBP$)*uqlg2Xp*OIUC|z?_fU#0VdOE21gf!@BOb?qq6j$GJ1dBihF$7RFPx z;Z@XTZL7oVZ%4EguztEdK;i>D#{^2OaJ4#uzoilOfVNuVJq1rH-occ4;kVHf8m={3cau6xGun4E!fuLpaC}nB9|5sHG)^#4 z39y(u*lhxg_XlXy67P~3dvlc+#t8EQfTUx5<%m`y893?F@zd-Xu8|3eu~w=5nYVQ4 z23O1uB%GkjL*V!qQ(?`I5Dk64DvtEP&iT@)X>)v92P`sZ5R`dagJf30j98n-w){vze#NxKG__|+;q5Ke?$mS=VQ9m z;WczNKbBeZ(b{_5HRFz=AERksbw8|k(Z$!TT79m&t)sgdJ|5v+^TF@s?%%J*_-cjuROD5wwYR`D#xXEx&ww(sM2?-RS0569y~Q@&zqQ{nS(AAA`7uoZYT zn{lMRbLggfeBM-P4{U#WdN{M(hyCGj^!|X5VePK#nE}D^odAB~@^Rt#M#kEk&i>Eo0(AJMpz=@AOU)-*1XhR0X4u$r|U>SF?Exn{f<(_$hAO z{Wd$7PwkjGoDer12_H&puWH|&)${+QQu{ma^tXcd>ebpj(ETTwf5U#{x(@bdUSF=m_5N+vj)Xfp_!I|D1Q-m-OCNK0o-{y|wY`Wb^sEFGu;q z-;aV& z8-3vqwb1TFvXyR#@{GC!(00#`u)u_0cWMBQc@-@em8e1 z5^~45U+?ov5(e8Ce*3L=KgAiyMud3w_3M0LO^@1lF4cTKQ6V%ZeUjYq&VH!K_Qqms z@@?e9qN~p96D!Ypo$ac(BE;K=9nb7pk3(YT_cn&!+T(_fc7R$LgxCs*j}DqAL4J@I z6mFfV`uj)U#OFKi@_N+mU#6O#LdoW2wU>&DdtDdv3IO#NdWxs2V`n*&C^~x#g(UIz z4ViMkj~Ve$HB2@$$>A@b8iGZLDO>xGMOx;2`h1thkmxFu=1~*@~5%2@Zb&QynRMuI9;X z+#=>&|HBWn6tA zK8J)mX^$s4#%?azbk6KHxYI}%Ds3rgDAlNG``zb~$3`UkB2EAA7N*ukrtrnG%H@r@ zrElwHT9*5|+z<^L-spF>ARK`!yOY9`8OzX5s7+$4n>`+wXU66EeRe2uu81EFTF_*5 zA&Mfj{JexLwo!jv;`nSR?VW7Yxo_*YT0e(vVuQa+m^v?&TlyVuD{4uH9K(O9@y{BK zWOGvI*Pb|;ySm-Gc51ZA!0^M}!~#aemZhHJ_$%s_Y-3INy$>PRKVk7xI*E)AaDuYh zv1E04-`H3gH#@vP{)eaF(=fz+<4rVNU+nW~!L9S4X~s{%uYE2$(y#OQs>84A_dmvM ziLkvPvii#(odK;=(u$8832+g3;;Ks4o+CWCk^AI0hNMi9%xbkl3)0vfn;wK^(f455)MQ9eybGb#S+r&gE)4G6S?XXsgUH@z4?G9 zWj2myNOELqH+o3qSilT3nc`cznmre=> zP2vM6)-z3$IHxan8_m2-$4duZX*xd62X z>MCuLS#BZag+Bz#RpAsQnx4LU2ZyHLxyYv#efFVWHfx4hUgk*c5JiM&yc3>&*xzts_= z7e#tSQe{7LIlXeuF%tCL)i7kxE92+sI>DLR!?0BZEYG5;LQ7*w*T2P>Wl-{gZgL(; zPO@>OX5)JcmK?2*w9^>HI7$t3UXy{pA{G3pRZfZmh>!9kpV-w+Xy%}mAlJ5@pWUvGRTJ zB#X5^tTk&Ha;5ZT^H`}8m*J8u&;JmmyAVnHqV1mqf8eJT&hKZL9diS|LB38pinhTW z-#mG3&)Z+s%AytBE@F6iKZBmb#CYelf;a7SN%G~b1t>aWoMPBrF2jj?zU zd_6DEh2{fZK3qK@TCMY^00UE1EUq%*{7 zp};ra^82@ZXFeOHv1~Uk4s}01<&a66N7R@PBKUAfrc&=6%GA*GyY0vE&lFwZ{_{=33`zX!>`A0(GVyl>OyXMdM30?wWIg%(lw^f!!gtzbij(13PAZk+_y= z+`ZI#7B~&OyoeFFM^gLSb(y7uV^!Ba8ZR(@wUBOb=!tU8Q}m{n1bnQExBbGBV>Q~M zDIFScxMTZMevF$B+q8su#TB7npvWmaB2w z=gNN#k=_NS>m@nBE!s2`7FCJ(h+P0F!wE{b!KtJeA0Xq^Vge&qqlceNq39Qj(59D4 zK3SPqy1QK{g`TZ%s=D>drj}%y4g^U)OAL+Uq$*uw17S=6lBN74hQh)){gul%MklN) zP1pTDrQvN#q^!C!bpd&T!s@QTX-GZak&j*e4uFYDlM!BjYW{kzL3|4--H}O@PoqwH zWeEVhuV?4Hb;bt(K+1#W2cQkSCy{7%GSYtPA>CRAAA9$kG{osgn z-%?9*n(2-EU#*tg|$Vv|5zfOEyqI_?$#V!_+iFO~yAwR-YetWAd2>gcu#H8x} z$GywGveNk-)m#`B_iQ+k@)kdO7$187fVISXbfOeP4ha$k#DoFDi@|^-NECe%;dSDh zo30pgrS|>LFwWlm0whsxThgPBR5<$ipZk|_9Jx^w5pnD9FUh2`v4V=R?y}ITKY)7~ z;ypu>8vOr6honUL`w&49ENe_=ED!?FEl6lhRVaPk$==_`D_+56*6V)Wmu{5d=mD0t z1R-va$DsB?qb@QJJkLoWhe;1xHNFu5#336W5(d1l{(1~U`Kx2ys-ZFg9o#VeYWE14fPqF!F_ zL9D~hJYpC$@B-3$-oy(ePeIL&Jdzv2eLh>!`U_uQo>RdPtk(x!w*+=$!%J*!oUyP5`8Q& zdSj_QoMQgD%C(37}aU z9&8j2eP&LkHG+8GqZ6AT#o`2`gOt7UaqFh>j6Q?sdZ_waXdwuYrW*IoMgQr+kkkY1 zlq9faTcU?7hJqf((uQA;p1AH8^as*CW=J9cK%XSxTX+DKYA5&#^|}?40M)sU*JUsy zxRH2*EKlz{F+nH{DsYcFghBA3IxydlF?&5-yR2)xqxfZkGkKSKjPa8((3If?MNDK8IOaO$8GLY4bg0D4_^rk-prghf}I#)JVQhD`<5W)2$*;UB<}@Fe$o$nL)wF$R-mn%5=I*|EH~hgvjDvHfEpP)A~(dO%z>FzNwNk43Xr2WD5V zSgT=k#zJ$CP#n`bMShp_{?LU0nuj~>aiu5FZ+tAWvc?MZ3n5PyLZynnmzZI86Z|&u z1F9GNuz1!m)770>&paWJI6UThCWhS1^bTFCI_DTaXYOj*@%WzWEW{<{SvuL8lTXGk zR0BVjAb7Fn4m9&ATx=;cRwpq`^Y_>K>DV#9!@-8*AVu~K85polbjWXSD&-+M4wIBiMkSIa}9|F#Jhw!(kD~} zi-G|35KmEnTs@hNflTETA@h!xDW_tV7U zT{7o2g)Kbh*wTiQ*51VJ`@ih(f*EVuAE%fr11R(O+dnjpcZZ|7af7 z7T^Df3PD!{R2ox7>7KDg3&j!8==-ewMf`{Ltz&l&8($QL(E9X5d)9pR(o83$T8uB^ zTYtnyqU2>#Q0Gyk>6W}1BMOUa+8_H5@1VQ{66%o9W{Vek&5xY_Ni*k`4T~*>;Wc&B z0W9mKD?GNI?9`Hy{5tgUWq{&z;7Qu>_}&-$?ZWOwykMqp@o$0U$DIAMn!Z<`4r2;d zb}JwKSM+mLnIW{^C1w*idAU~Uru5?<48NK>eaQp)?LI&5V5@R}_|xjupiOwokve~( zI|QI4iodCRkU4&wQynuv%8VF9kX^GdO}erl){cJm9Zx?-TR|d*A&S^I!^}ht>~W06 zF_C?;_;r?pwvCQ67Y{iabiA~BJ{$u69Jd%Ff@GIq-iKxs$r&X)vBY;Rh?Dwbcd74B ztVMv2_OhLvhz2{^Om`usq4-8P;B0zdop*5j&T{t}@CP+6?9tq)Ek50I`0&U714usx>bf(g!|go7C| z3QC_Y@VAR(d}-xCXF+HfSwzu2sUS+!QbK7utr1)wL~#WsTFDw2#1 zPky}!Gtt2qQ-j6oA>s69GqhnM^A|DNv7R5V(kJK0i$g1<|0w>vXm$yYTg1~IKKhJ3 z%-72C8@`Sij`OPyU=i86D}sTrp^uk;rzZiz!`Dhw_TPxu1k)y~hv7ws;i;3aehmq) zmdTBn^f|0ctT_(*kT{#NLZ8ZioPj=A=C~1<2oL5k%-W679>$BRj(?Zv-~No%3*HtJ zfRXDD&sDk6X-(qfO>w*q&q(r>c@om}d(u|zB)JXbft^W8jH*bEiz%W%On(taNPOgvsFB`+TiP6siz#@;RN1FGBs*IE#JpDta zsm*Gtrdil_DX>`YG?XpmEzSAgQ?G@i8`=@9UV-?8a_xislC@64b8F(wAxjloZgt$c zLyo2z>T?7czuoF$!+5-CgRtN7C-EO+uVjLbR_}L1bR2uNL0Z)motlrGBcf{;E^QZy zM0|cN80LVp7^mwS8e{_9m)zpX@cr@{e`e+9NcbP!%3b8N{(u(-5dn(4YkmfD+s!Lj zodCQ}erfqk34WybY%5@BVzy5uGe5@j;WX;mwrwG_ID%K7B#Jv$k z?1pDY*>e#@Y|OEQO<+U_s@q#KM}OZ+Bn1U*Jfqut$ezOYzO7Ve$t>20YY|{HAiE+2 zvkzsr_+iV?f6?^CfkOk0$0V~^!Qmn+UA>b{oW(m000)P#r8dUig84U(%4X7VnaoUG8#OPP6BeHCu5ojmNEOz&jL zZpi+MrGvMw{a43+QmuJJS%pt_accN(9(50c5Al}KdkLw?>88oLltQhwd%c}?ZIPei z<66Xxuc=jW;~3GR>lAf`+)>{aIFUPusiTf=JrD{SYl*aI=DOTJZbr;Cfl-RH zO&=a^@^^{$F${=J@Lui!u!x4@{hE%Ry4U4us?0MPB2tC9ASRz;qXpdO0bk}vqZ?3S zN~!lOJHwJNnJ9^Ix%+U?l4CtR4LLg9WzKpHkz947E{K&0$f#ZwqJjI-+}J6U`1?%j z@s30)NBUSS8ME}hqV&?*I7iL|U?Z7(%Un^%MaZKf0WAbj z;S!@jLYn)g*?}>TRdy?Bolx$$`+P`S>S0@s2Fp+8vq`!fY)|{o#oy0=gmLm+ai)lZJgrmiCP9HotXdq6t0a~ z#H-Z`avX15zjr1I3&7* z$uR~|>_GN)fjQ7JO;+F8|eo-9EGi`&? zgAM5+!Q0F|NioaR&SasrWso9tE`GmQ#xq4uc9P^_4chGIX;GZaG;)Is#m5{o@5Y}r z=45Kza@_A0_VCoJk_EV+AovZvLd!j**4hY!0`5L^o}4|=d)ArJAxxX9r231k@DB`Z zq(_B2pIjS58XOA;i|4!>a}{rTIUdFR|92;vlE-ApYv|FFZc>L11q$eUcS4az{(qNz zVM?BNp^YZACh}kq>@W#Va@f^sk=pFY(| z5#U#f#y{h9A{5`ma@C2(2_rd}D8u$I^zs|#`?o53ix>2$lM?ViFX|o!9c>gdt({YR z;&>imR!)t&FHQjfSsMRWoQk_IPIO}qP?jn5bQ!?fm)<^eMm(x0_a zUDB#9yuEq0Y`a*0z!KQgiUk9{%YwYQKb2R0BCg~`*jb0`OlTU_dCq%0C;Jj01r+Y8O zljV9PM(+eYh?5WSUm-|X6eplox2j4=AcUi^l;t~WIK2T)rg00Pq-K$9`r;JpjP{!X zX1r~(8a&h&Ddfa2ZlRQYlX<^2`thY-SXDQR+6X3+!=0mbd9fvPn6v;JbQ&wZ+>rjr zMirrehi0yKB=cIO+{CB*!hL&67RLGK$FZ*LRf`P+<0~zK00Ck~@+RMsXPtZAhi#gi z_<>)Nzy7pG#3=uxAi#kZe|3T7|Ks$_{!hMNfAF3yEPvsY=(}Ed8J#KO4+-n# zC^~(A^rX5O5WKe*d5l%Y3U3UMwWvleuNgcR%rHD64~hEtzBB939PT*!&y2$6WA@}{ zs~qPsWJiMp&t51kW{UZVj5#7vSF9aMegPQ@LtGOS6xo>)16N&I!>43so2-Gcp-cN! z7B9sY2g!6PZk9b4A{M-FPaB5j4kQ1gm~1!t>w0q+gixX7qK-4QGEf|(^FJMwVVf?^ zP`pU=xyuU9V&4BxdH2n;=mv-*ee3D$saTy&MNRadIHG?zRn|3Ior`XJjp9BP`WRq3 z$<^2AI6gLjojOSrF;9S@Q-C$;A^CaUMiT*i)=CE`?4YI&+?{;|Th{{{(BbMFsR`@tj5LF`&5Q(3*gDSESsXwUUxG1(gVEmAe zaa#>-pb^gT5$@dVSf1Ms3j|hx_e(d7~ZW!M8bFJKC9cVz(s>A()8z9;zK8l#|PqzN1dvu#WI15!&Eq zy-S_tjzL1X_OO%6Wa)t!S#{C_m1uU6gmu(73(cz?_J}gF^*92?ic)xm?)A3mkrRnF zOwx-%%L9-l_{Gd?TQk#@dz?emk4xYTu-iss`7On=ciX(9ADXKrA4snS!$!!ezUku9 zyW(Vb<1$+Q&S%}H($#0jTA}-D!~T^zU=}whCb*>%2>IoyEyvI0?B>Sq^<7QVi4JWb zV1CbZR|pHcX=SpCP43uuskbobh>unhO8+o?uWeMf@xv$1`|P{xI@~i*oig~XsS_q_ z7`}bTZ72`7q5N?^=jydwLV+Idrg1ODx*^ek68>^4MU+va$CJf&L*=U#y*xB{d$wZOHJi5;OiGhGcoUtfWcksGw{g-* z)lZcdbwA%XrMar;OElEKkNEInzTw={SUsZf9J$fs{@-?=p{p2a`LtvK4aAix7LZ5L zE-`1j5gqP1rLb7gddR;%N;$q4$UVG9cMa`ocRvmddTs-5?yPjq{18615D!ja4Kn+sdlw@{%bKI%mA6UhK8iY4vMo+Qw2v;= z>!URr&s`t9&AWxPrfJk$Yj#qE*d>>}Utbvr-u0^M;O|#{!;}D|KS7e|^(yfeKP!0O z@D#X{U?n9O~xn{_&g&P%4!Gf4)>{ZAHJ3MX_xi|bj=D|7TYso z;OoCWOMiHC#jXd4d2nlif~zX-s42{@jwb6@wSf5*L0v80TLe|AGLd1_2Ky?dJ*!z?DvW_}m`9=;NsgWb|8hvNKX}{>GI0!jNKk`yrMe)Ie zj{mNLkl@`k^a*X<>iD4s^ZqyCV^wl&;V|EUh0q+zpVS0JI|iUM0;z<>T)OdW@}XV+ zfuDwabaNU1LCpmqMsj9?l@@zLKgKRJSj~jTq z>nd;*1<%kwzzj9Bddg!P(0M)SLv^qWSMC}ob?`S(-vNt?$ltsAi|?_tFB%x=T=_$) z_{&jVPmy#_rwmo64TR2Eq#7BN01W{kgk0c*28!`gG#48sr~et#lSZC03f{y(9q1fq zw|h#Iu%_p+N&pa!->7y6MlhX;QY?x!Pzm4XLB>(R3-IL*8ztIR^_PI6bWLJx65>2f z;yE!2;intR{#avGCBU&jU*qzv8e`d_DMCFH(Wsqu#_?KQR)&(LC+n9q7vCcQv#dUq z8SYH>S)=TK608GFiur+Z3+IX(P4pyr%||S(XahyKuax^B1y4hYR6|^k=(cpf8(zX0 zY5<(p15)y16*ysP65)^AyTmJa`VRb?^un!w-e=AtLI|W_lqJv{fO>Z9VFEd&P$S0- z#Mky@8r0K1lq7rm!x?p+Erjj(2bQcS)ArUJi8r_;43L|R6S}|>@df)>KnSA7Dx)=E zCkf}v7kzfYWRX59Y=wm7;N9j}B-xV`WW(zO7n0N7S_2Ib%!COhW%2fqHc0H@`RP{% zfD%U3O2&t2=F&nyopMq0YZ0cqu!qI0%DVBQ-Js5(kH_%87ch(g&4HA?!jmv@Tt6^3 zksA}gZ^AV*C{-sOqRDjNTs8*~+*45myEb{*2OZc~rFR(#nwfoS9RBXhf3+3z_@T%W z9Wd7fzl#BOYe!75%(tbZfP_qfb zn;RC?Az-0UA?e@Yexbwy>dsYXn#a=s&RT0%nbd+OHp()=0+1A1HN9s8dSraz3!D)u zpDvt6f)&yUgTcGCV4~sB0Q@$z0HhmrXfbJ)1#oIe`Q^R+*p|c7^O#Z(ozB}V5J%?k zy>S6zS{LcsG_w&iX-ibSZIyiW+g<+J^+q&Ngn>7PRN1m8DZ?Y#{gcH44xIsCH=8`& z?v*7bl=+a-B5~}Os9?;38K=E!%MkdJ&DO6wck*!apjxyf@6j)t&Z`LTi=0SuBD0#8 zLb7=e<(`wt0E&6V(vA&^(WKw&^^qhd1nJLyA$m>b>3Dk$b;xtf=0K znl-r94N(zx^)LLc^}a<@IYjR3(Qe+~_BbMBlm_L;5`X4W-7wPtIaR;g51o+~RGm3$ z#vGXOf2CcI(<4tQN%ktP%~ng_a^9 zGzHB~eb3i)Y0Qli%pGY^SP&mQq@Dp|xm0-EhLlDdD7Q5pWN;iZb#=_*@#twdPBsUH zb`2>gPYZPK`1d=9=btk5yO__ry3V^jp+)ibanVDHU($L}Jla1dL=qcaWWZ|)0OZ_e zZJCa0iDU@Pdw0S~Bb83fZMH4z-ko6M=)IN!yNo1|3`>f(n;=Fx@6w=-OQHje(lWxO zW^zFl21QDy{{;6;d9_Q4HF|kpWsWz;wTlbcociKSdO7aH%sRQ_wwNO|$=7RgCNt#{ zD3!};{y2I*Y9+{_7}NUhYug!m`eW|(L(Y+Is*Hcn7dM~RMZa23(C%~7K^Lk*b%~jm zwp>PugzWtY81_^ubR7#)W69t5l8w6@)^3jF<_XkPn;Q*luohvQMqb&%k{$e8Ud4!* zkynLQLVL1!9)2zixBmeU$M*+RZ-`RqB9M;T5a8f0_CIe@!*Ip$aiW}-r{^N}H_vX* z_yCiRFF(Y=pf4rRCozih1fP-;$>Xs)oF&@jasnU7<|ER@`Bo9bd3VgUlf6V@x5IKj zMpN}-?f;%S^MPJDY^TA*e;J9=;GB#_=IvG?tXs+|)_R*FRf{_ahu~*LSefUqpIt1N*)^jMbz?$08ixAr`f_ zAi`B;?t~zr&5qF+s zlB&FfP^m@w*s|bfrTILOR=qMC_COe}#b&1VHlKs&1fl(!24Y~j70)J5C-+ph1E7u! z`KA*mvFL$9hyQ_obUsy<{^%tB=TgSem!Yy6tQT=3@;%>Cc)@WGMeAd0|BXJJ3$M^& zI~gJ$yU1CR_&!{tEMwlvaKcVg&MgtN=Zmd+S0_LAQpv(vf;@K5ovd7pvRGYG@+8Tl z47`Iv4xULfQv;b2>$qFA>tI-I^C@LibtG zjbRkATjZunW*642PG{BL^MnA0wWIdQUU-7H%7QyeN6 z04;BgPyR@(f&KD|{oG-n>bKC0?x_V?S0uMvA zs(y?`y?c9i_ON}`SJc&_7+;2;xq@d|$?VoHW$B_tEB- zDWC34mE6A`n-(w0xr&=?d#@PclB{ROp=PlluQYv<)%?hXnD3?9D&JVfN-4_UCrH~k z`!q>nmY8XUUX@XDB0aC%j$1BRN6*eMvGCyAf64?z6lvM{>VjM}t}nARFyxC@UCx`Y z?c8!A5_(Qv>{Oe8IXx{s&*Rej*Z5%$y$)SG?lg$=se%pYQUw{x2kBB+H{i|yo z#O_n#J@?o?Zo5Wa_w$ltKE25C&)ZV$)%9@1v#f^7!B02=X2rH*BmU~ zYO!;;=CCPs73rP{Z1S>uh4f`9&6{0^(80NF@rK$gTXpLusW~z+px9pomC=7+!Ss3@`;igM|fSbt3V@EU72WN_84*5*_74H_Oi`wDMtQ^Lpn(PCze%mMRCrqyl_ z%mh6kBW=VVRQ7sv%Tz}1JTNBVz0m^k6gq_0`g8j?qm@28!3Lh**k>-PoAtuiLy4g$ zDbk&Y{cljD;iT<~#|W(9bpfp5+0P$)Dvclo(Mjmow z&P5l#0xXs|KyNJPCOH_3V)%Y_J>Fo@TJ+^Y*j*kEiYX$uV_N&BSH&>m+u@N#O+-nG z1IEjw_?8s9zc~_Fi4Z@eMBCoVeFxCrbY+cy&*!LLF-VM1Q>GwgF7!Hj5*pQeMEbCq zXNRi~7Bm|E^ss`+?nj}F0vrBG^5YYL`SWMDdqXsTbe3JI5*wTz7&!Q1x0x2Nj=Fw6 zx+6DgRwK&%#XSBoJz}dWdcwW+OHSO`kq}gRct&B_xBj+De_l)Y%$glAXJZ9C7XJII_|1u2W{3LYy!PRKsfvf z%&Z@1VBkVH02;>uHa-;MKR#ne0jBxw)*a3&y&&L^02MN5s|M6c6h`*`8Xmx9O(w=2 z3w*G{edW0vZ1gQaRD=8I^2|4J))3Yp8k`h>!}LN@5Pvw?K@plHUKIpDUqXRi;sIik zo4S*4NB9DwMBg*RS~4N2y*KRakY+Fmt=7|0BSKteUC|_j>x4vCg!HE<#eOf;{E&wk z`EQqu-3a@%7@qRu9fW{_N`Hjp@BxL=sW^Ss3?eO9y?PmJnvf)qGP z&OkJ-Y)tZAj-xvZ4)4di2tS+RYFb04)DWr zo17BIXAy2sO;R^9y*8lzV8Fn3#>wZzHeO1P zHpOXt#&bEwKsU`P|D3*33}N8F;tQ|vIOCWSI-r6tS}j4wWV`hMaOQ@dFP6Atflxkc!PTi2mU>=0q&_c(KK5 zp!C~D>Aqi(C-+QWlg#<4jB60rZ3EkKvGDOUw?7rn^C>|!Q%Q~{o{}KN3R4C5Z+Zzm z>K;fj^B|Ewfvg&Vl3LRuLsX()sAP260r#O5e@p0Iz!hSe6gJKko=_@=2hzT6Qhs@= z+}^~2Dpvn{4{K~fvu32<1j-R*DbttyR~c4O++88u@`4UHh4*Hn68O&UrKYHtEK$T#ss2i;9Jxnh9_yk>G@ z)DK=hmyAWEJ*&IV| z2A3b|tV!q+%qmPABXz~~ZG-iRauFanG$MgyaubgpiO@?|`g4jZyD$i!MLxUGjh!`Y z%G8!?WH%}{nsIielpIP&!MrIh=qRE6^R#b`v%0|@5Ou%kxajA?_=TxlIC zxj!Q2H^Js}lAKDL$+KPr>FJ2^$Crb_Yk_kpoCLN0(>a-jU?%f)m=C+N;1q&&szmeB z;z`~kwo5(Tb1UOUbCN&=GFS68T#&7IUvS!D>)Z@%ZfKtSaK^-jE!$?x7~ztu`KFkR z%ZZL_!uacj?e{sYLnn%V2!69os`?mKEP^V808zV1yBu?`B@t4x6K0pN_Nr1)qe$yY zSSx{#s&`lqFHebkn11yzpm`DjQv4Z`I&a}n`cDWwEdAfDnan3vFQu%s(jRQ}5_YIE zmVSd-B8Y>Fi5eYg$Ya5?G1O65m_-S***EYgkR}aH`oqzy9?nJ$gmEHFA4sbjzBuY) zCr?9CFCr#9_FPY^06y^bu3%?=CtF-F@Hpzq{Y$Q1MWc``oT;N&k`_gJuqFE*?w7gA z7IMFR?#QA}4&X;r12%OiOBpI%O!ZoPn#LKFfe2y;W?F=(^B&M+Q-Aw{ofO`2^1}VU zJO{^FhqYd6(R-HUAp#G`LS71<22!#XgT#9n)BC7x5Qw%-HqHtpDW|GvzK_(ypR91U zbvQzAi$*vaEEXO;k}sYbt*tinnSArw(#ZH{!b=)TbjK*TSb{l3Xb;Rhpvnb6_hFwxKE@X=iVZb3p?j&Ws zE#(9ToXH@r>0q}qIsiC26l`6Pk0u&NQ_v%*+mce_|3e9;3?WHw1>-)*#ywZ1V-`$l zZ%ggIPVJFR8wg7qx$f2UF%fc7TIR^yR8!vVQ>J8B;VoDBrxupH5C#NyUvcQ?T`$|NVMme7UZag zcPcNn7S{^-K(vA}T2T;f3`RQ*qI2Kk4soL7%nzhMJs7;o5XuZvddQ4gaQ*$l-zwB$ zj?VDsTs%&t)bJmt5#D`D`*$NsS7QJYGTK9(=0Lg=<1O&rq(3A)+zRlsnDq<*L&dOI z7e`Dj6qr*Z7G&(c=h@}U@h3s8)48l(RJcmDu%iDs*L=5b9LVTnSR>tHI*4)o0L1@PtnU2c%<+9|C zN8#4iWgVqDf2)icwV@sF8c3_!b*kth-lzU8$YQ8&_?z@8;%D1m%B;UN1J>{J7|lPv zGHLo-i&GW;a5q_#v0Qx_^5OiIxm5N)t2l3 zM116ltPGW^>n=B8xoLRY;V!V!cqw10!qo6Hr%WdD8s1qiF;~H-(5$2Ia*AG89VrquNn~qyXY13O))B8o`#*!%ZBs2BUboD%a-NT~T`-G|YnSzMRCfX6+Cl%Ev z*VTtpy6sa{?3ategE-=;-}W0T4rmni>)Q<2-VPWR4md^)dPeoRb`3th9q_+*C!z*) zyM|&E`$G%+K5Vjyd%uxfQO&-Udl4n~YIWpihftf==XYJBA8tn*6u*3m`qJL@rTg{^ zK`-I*-bh~DSWe$q9Qf;u;%Gh!`mYBTt2izf)rv-rA1e0k-QFK3E)~cBbWOzEP5_mL z?&*ogU6WEac(t3di#lIp`lh77(|l^vJa4|H#!f4NW+c|8pP^YUHM?2dQ{Wo0NN*sPH9D#T2A#3arZ`h+*7QOG9feMRUy^FYv zr;86kOW=-%{Me4^C`YDUAd8(U`rAY1e~u7Jr+XBSwWZ|m z75nq z;v^!yBRB7?qx{W~6=3rD8=VutWs42M0B`}&{@7v`j+x4H*<$)90$<iil#} zr9csyAeeW17#jt*^47OD?)G!aD5inLZgA3d#1}j?Lv{~g6r37Bihv=AaBgTqJ0LR# zhOj}dqnWtUqCpyxGGT~fb7Q>`StoSP=yWq`6dob ztBF8Z0%-un`0J}d6OQEc?1cY-GxzD+fh9y&tN_6nMoM-XH%Aey{q4xcZ4U@=AF)$jmi8kEmfWpCA>fH?-to4Cu%kd4s43_~074Cx^h{53}IEP$ATwkf*uu&g-x zA2zWZ7D0%3cMKL48XQ&E4Zki63S53h8w^3|ICdN3c3!6mzdbpsdmLP>m^gZ6*VyeZ&a7| zf|IA5G7+b@LHds=wd3#sQ~LNw=`>o%;QzzdeTBo-zWW1T##C)aiQaolj08c5-iaD5 z%IJcqAzEbgL81jg5Iwq)XwjktK^PLEglN$vT13tKz3=bZd;hO}u%Cl<&Cyy1Gi%Mv zbKm#(qi|&*$h9y*>eRLPxoPnIQpi=`QAt}XyCF&137U8%^>fnR>~dk*ilSugQ)CIm zB7P%E!{hDf?XScE15|AXC_%We_f7D2B@nfr5>p#jSQSkSrM_e-(t<1SGc{!QDhGtg zJ(bYRQIOjo**8}V4X%uxKOYsX8?aA?%Q^0mNj$Po z)mD17UwN%Ha8UQ{Cu!3B8>6>Lt@jCP-=_x@&On{rx7RK25o){Q5&oZUuC@7%D!{56 z#sHIrr$VMyb!3vSQz^02`lD4xU+%V2)-%p{1HMWt%#K~}Hcs6)zZ=%-`Olh>Vx*Ur zY#xGT6N!vp#L7|n*9Ci#D+iV#wVmge&<1N)a7ZR#Aigz;c{3Ls20IbjjUz)i<1EK4M&^ZIb3&sv=*WzEljaz{S8)S1nb)s&m%0w0ac^mJQQhbw zVY_VJVr@(&y&f2O1@e)Er-GAIv`v|)@;FTr94U@f~*`j^7_TTUXyx*~Zn zA?n(f^qPDqeIk(H#%TopfsUqLU}*@eTY&xJPCVF;@W?F0GTgG>)UA`9e9X<-6*bKgxZ3{2#DGNXtWSbmoN97M z>~X?V7o}J;xr8g5Hk97c5~i5ZDSuAd@3pPIu8^pCs@6LNr5A+3S3} zqzCmW21QqQr0(2H{>MIm1a-MP+`1PTilN&!&=6^4igx^>!b&9TG4|3+u$*`^*?>>K z`ha8s;#BXz*0i9bRCsG{)AB|A6lG07T*%~?kDT-eiv4`3Vu^2?jRs#Y9t6bdyoh}Y zrTKIody}=|``nUHZ8>JUpCW)}v)coB#Te_R8ZyWuw@il*u@Js)iqcJ{buM82(XY;P zJ(XmERN$>gk@gIMFc{b;QB(KK>*;b&n<7hNAjv)JeDQ-75_kbd!`KEIAK<#!zvE^j zE$Ivim9U5T!#Rh0$?oEOFl5HZ8r-Fd)oOSZ3Qh0mTzKP;Yfmhol!0o}#kblTnOLdSr zl=I~ozK_8-KQ`Evr0`F36mp$2G0x16BXK>Poj4VkLS_}g>>;1tPqg#nL@zTncY?0e zFLua2<)M;N?$@w_L|FGg3DzdlF_Ba9K6#B1AZsR^KY$@6X2O=Y z?5KJx!+uwJwX4_cBCl>^j&21aR`?Xy2Jf*SFifAX%IV4J>#+jCt}wuIH%XQd28;G@ zKX`?Fob_lyjt@uqsai_R>fM47>f-U5JuPi4A~TRqwKE|N_kER!!Ze;f-Kz?vJV-T^SC zfk^rF$fZg6;%=mhW|W$_cMJw1gN5yM-c?_Z(iimj-yQ=y_?RS?c)9-mCH}qmdwIOL zAYPpP>oJ@X&yR^`XT-B3;@RQ(`T5!9>(k%=pUQCX-zo#~_wS>lqu;-O6AurGzc+~o z3nvE~|E)6o-CMa-87_V;{fA^A{ujyccW0Ei`GL6hp1AV%KPto4*4F0c=KA{j+S=Oc z>gvkM%JTB^-r_&&`}gm}?~TOiN#g8F;@AJvW*`uV<4OP83?2)g|390dx0l$|MC@}W zwz(5Kw1}+=#3o5%{Z--{zW>ED3=Itp4h{|s41D76%3G4ZP@C*qF39+%UF)=aG(a{kR5m+qt$&)8x zVPT=6p~1nyj~+b=2ng`=^YiiX@$&K_y1EkWZWGNEhIEhzziM$*{b_OB~9g&`nNQ)#QDTw32EP4h{}> zc6NR+n2n8%m6er+g@u`!nURr^fq{XZp8m>}D|B>pw6wG|G&I!I)F>1Ri9}LSQBhD( z{2wI4e|rozz&{I41W4eln)v*#NI3P(@mlo%cnoTBH>u|S@fb7`|MeK&{Od8OUwRBq z|9A}9mmb6Fhh(e2)0zWsUyr_0j3i^zt}h!a(tIv#Jy>7<`L#ijcCL1V@Utg3E3QAr zuZB-nTfe_{=`ncxx5sd=$gy@jP^YP8t~Kyrb8e`q*0#j#?O)0D0Pn8u7#Q~*3XG3^ ze+(Bg@yzR*LmAZdDZK05+qKbrl>~OZmimp)WyX~@pIREWzTzE*^7L9SJ%$<$0@~o_ zu2Xm_5&Gv=o0m^V{~!LZI@9~VO3jE`ukN(B{N9>+>;8SDz4gzpg`NZ=hki%f$-(;P zO54l0u%I=M$3&aF7q@NB9_`Ie*uGGhTOE~=RCa2<;<^wH=Pz4`ppaT$h-|W!RQ57w z>Q#g=I+rc}$7A3K^X`LjX1FfJF<&PL|mV*C!4AaFFq`a!jX0~ouobNgq-CZ@2f@*z9c5D3CW4KTE zQq5G_AoZ#hb}2737}rJ4cqk+o&rq)zMPXAT`Ks_mu26cBp%U5MY~OuVm;ZPSPpz3> zg|aN<60@=6%li%tEX729QKv_HEl3mCXLPBm zvtuxp+h(yX7>K+%6T<>Humk+C!%3hEuQ7i_Q7b7zuZK> z|K50g_GjG@LdvsX^iwWEl}mB}>r#jY zIoT{dI+p!(H&&6N5Je1W2J)II0dAh@)liJE@o*0*s7~#NM?O*&!OM_|#@)~qPj=Bw zcCsL7DXlxBsHN1S$GRu$3FcR&Y!aeJ{kTpXHTz{x6Jkj1u5Xu=GP+WS2AKbH zC7BNLaMYl&B6@bfBVZ{tH?xoDE*Cke94EuBw;H!4e#pjoKZVht8%Fn0*V!IJ$>>@t z@mlMXo8>|Fl*!7CqO4Dz!3QtDeB+ny*Sg~o|2AjtAqYlby5suhAos_&Rmy$IMwywt zyyG+n!%R*h@^M=a1xQPkDH9L#?F4bXFB;*R>?GW9U4-y*l91~vj>TIZ7BYSkRI@;h zB?hN~M+DVW&F+)Zh=SPJKB-E|&cs_JccM-gl%Rrx6$8hnF5hg~@B}i3-c#73QBROq&KLYJz`PVkkxK{xYC&pi{1L z)vL5bDvfrvqhEPHtIXMD4Cip=qTSqOSK3~SjHFAw5v#kx%@Q=+&3uH%ec-*O+4b>B z;5h0R>M~WLV91^sbNN_Tv2P0060@X#j^ym;q418kV3f)l@({SW_;JQF?`;FVVb$G1 zXV#fGlF=Bx-Y-5mJu^F*(YWs+ayT#ib&2__Mj)@|HC@AGs&gLSAEfC_4fbTN-#Q^j z#!I&VjPM{;lxNj$A6pzy>91!7h94rl&UcC)!z z+>1E(lKJIQLRctwG-=}3>Zr=mW!dAdQLUef4^!eJ0v9<<*FXN4qKR@LEOWg4eC?5d zd+Tgnm3YQ3^!6YLIX|l^%_dGmSYl5NKy}e?;5DQexsn+cxY>#DdBtNE43R(3Mx(|o zHN^<*bXbId$1F#P^obx;jt9*%$S7~@K`5LfI2?Docbj4$-nRYd{VCg&1{>GM4EIQHeUXU_m@Ljs#xOQVefgRFYU}>CXGn-3 z{&xJEgKm#j=~>fe^(NyS0@8_&WVXy1k2ky637)<6O`Ykc&7k!QzsstCEotBs_zuco zWjY847S_WG^5At@lN$ruslBNULDpFv%%8Gu9+ln574lfuxPC|RD1|t^={seFw!ckq9tiLDJa2W}$E&RqG~I zy+hT@GWA^vl({47Ga3O3M~vpvwKKS+zkaBla&N!@^!rh$*NZ2-n(}9{D39kP7x)O# zsfcUG5$NU!CXA{~8ukEfpMjwyEg*yWL#tM_PY7hdf_C}={3`&EE>Oy4gxz~|Q_Ym_ z0ursSNhe{1$?xh>#z)~W_8Ds1RB5q`&;DHLW6V`m{l0o@MMJ-8JxNpaGK$ycc4yOg8q3gLi78hpO%T+5H;^x3ZO_7v1#UU zL>DZq&K#72y{~Ei{lj&oU8L;-Z7Uv8Y(TD)67JU+9`=GR5K6)PBHH9DuHIZeVO=~$ zlVQT&dSXpRx;aMRvZQv`X3YtOGoadBfR&ep@f^mA@Zww^(a|cp9mYm;2L?7|K4Ut- zLB;|N#_Tv6gFDJ%Ucp&~8ttzJpm;Gz3S9Vbp!!IrdX;97W}SNxQP(IS z-N_&&6G%9aN)e2E_6qb^Pukr!_WsrBr?B#Hf+k(WYZpFZd6H#js@zGCLTrMl1v<1Y z<+0TBN>@5=Zwk(@H#ra(@}}qVOzD|MDNi#J!ctN!mC|yY)1de1T1_b+ooW0V&y6fH z{QMJC9MT_$r{66|&+AKPy-!EB`!Emf?NE+WxStWsWas)$$}L9J!xk=d7t>^h76^w0X5P!nR47P}Wbl53NO>%jRjQRzg1Dj% z0s;#KBKNZe_65R0FYDiNMf(cIji-V7vb?nDq<4MpaAqe3rM|Yvd7+e*9}%Th$TvKl zW2nq$x|B2iF~=(PWgEinD*}ijAbSOJsAMAgnDU+w!*hC5H5!8Q*tofQBl6bX2~Tch zRUd~b){*R+JqwV@aTLlsjmr+&c=6+Y(5_a}J|bVa&Yh#|K~cGo$-7q++0x}Fbd_59 zW6}j!hJ1J(VA?F%a^KNdBZu;|z)LBQUi&%eU^w3(t$K1$%z7?yvfuj4lV>~ z7tmN1C~^U_C*+?q^0VILiwo!7a4X{1F5bIe46g%yz^5^978#%9D>0Y2gGvY~IX8n# z)Z&XYgHaKk?oPP;rTAU6l&Js?4#9RTFDb&y^0{Z~7S`;XBd0B8qY)eJvOhx`_ zW#MK;VmwNA_u&y!+0{$qb+B^SP3UC{T`pNwt#DT6uQs8gZgM6au?Oy($=Y#4iSAOC5g>9X z=PPH`472%6TXlzIZ=tvF0Gh;)NI(wYtDBi$XAvm$PiwD|7m2aFzze@+ajysafH&ha zdG4XUb|Pw$sm7DxK+hYc%2z5w_2N49Uk2+y;ec0up=E-PnG!fxi3DPYJi;O@E=v!) zFcI>4v#mF#BA#(>HJS-cRtd$j2AKEQxLXOhFNO$6IC2Dy%JmNSw6F6U!b$W>Cz8s5 z3`vSRsrGlt&<4S3txY$!8kU&>6MQk(%|>yvMwff21#dFa0{9P9)3eqJi75G*9{G7= zvL!Usa+e~u((aKCUgE4ZF9Z*&1Ko6|ux+VztgNbDcnj)6w9fKBJ!|2EyGu!cjVlkbA{6kj13auoq&-^LF1S}?LIAa}01tE0 z#2w!IyLIpH?7g3Koehvq@cA8RXy-b(QwR;aV+tla*F&&&Ez?Y)O0GJ5Tq)C`Zr4>ciKEAIz=vI-)^-1{L>2?~$_h zU7^rBIP6gn>E-Zf81jD)B)|XG`fjzd$xpOGAD=sfO$w@XTyL#%(=ElT+f6341Ds$Y zzI{}npPSg);BSRzM!~pP+I%MajYtqgZwXOFvS|b45&=P*+R?I0_0yZ&42^QyrP#}- zs#O%V<;k8`5r(8!mH;HUXW zLNw~F?hww*H8#UF!Bn)EKy?6+`!V)g4-I#U5Y}1%FMK`er<9RxI`(`@huuI@C0j}W zxTmPEyNg_pg`Hr9T`#={Lle?5vc`ofU!74E)?ONcVZ_{ki1jc{3#ngz?bV(8*hGvo$qm z0=!cPTY!e?06oL~gQu72F_a^qu}i>qAz2Mn2cE?v&#;uYxKJ1@)#)yBgi~?`g&?(q z5`j$8u3j_4abxQYi>>kbp>fMk4YFw1{>_#flx~ugjO)pEGV&-cfU?1Wo&lh&=!94= zkWFGm#q%k%lOeX9|t@5*q^IBE57T zvJEJ?qsz~H8|UyO)$`_a=|JKwr{wL`S78Kluro^HH5vLKnS|J~*!iXFt+f&K8gJ>Hc!Y9Ex<@Sl$C zoAvK@Q5-B@+nb{L8BzdvqG6rrC)06zGgOE28+(*-`!$KX&Lp2_?^AHXcmA;dHhPt6 z;`Qv-ub%a}?|Po9oG;2gzsaV2Z~JM?T0u%3OcM zwEx(P9SRPt<8QBPa%`ET98LU0L~zg<9v@}M{<+MR3m6S@`t>WY_DX1NfDHOX(eNbv z$w~C96PkA?eP2&d#FM1=hY@RtQibDUB5jmdX+=_Ml~;hd{=s|wE6=XNpIDxyJvqCb zau(KhR+)5cTXy_x^cZ+@Wa|UmMZ=&?HGQ_H1H|{-T^Xmtub#CdLu-h8c(E(b^k5t? zr`e>lxl!7|U$u+h&#!q+5EL$gy$;32u0XsmpaSIp$wF5)44`0F%`{k4j-h0`#%jL1 zs2YETL%nz}DMl^v(qm9%T(X5H|BuID-4VrPysDePtu=0yxd*+IMjdp-dwfu=U%(ef z|G3OygvIe9n^7*l-od1tUfiuJd&1eY#=1QW!eY8T6@RZ}lb2lF)iT;-n#}6#D1WvF zQZY<2QTz2_|VCsRUbQ&166Ssk~^#OQpW$7>Xdd8M<7n!khw15upBTOs&Qh%j;XkX=`uTK`g#U)6IV` z)Tn}OHGesia&|_%O;mvuRS8NGy{;?XpMx0ANG%o{l%U?Cel4YMw9t2P`q@zLY@2RN z<8YYwt-bR) zyXSM_OtN&JA?_y8HyfsfDcfmIym0i_8a)92mN2u9?Um$HKCnvTx4g%kQDQITW|ACs zD#SgB(RqCI<(eKT%@^z14*|nAhNtO9Dk3E)EAkJ~S`jx_y|0+Me0-cT$0+vOSJnM( zNz*({lYIF-o%cT;eQ}kS?H&tD{a8@oa938E@7|}LuQst9o>hyfhm=jW$KP_Pm(%&N z4pf&zhP?$*;p3V8_nC4S?9VZ2ad<7;UWW11oob22f=q9O~=sq=1Acj5}i&F zj)kw4X3mSE`)|y8jcFhsdc}H>sK$vnle{L43>4>sPWOyxeM#W6{cPK+5WKV#h7DId zs4?68Ry6vOJon*`7XqUX<86-D629K58`yj5BWCibTq@at%Hh;5vT*4&Gy7s~Wl3(( z@2_Hr?;L+Emi+xE>-cFY=nFZ)7jefh9PIC<#{iL51kn?)Fjh|JB$fm$MF>ZFtQvu{ixGd%6;7HDS}Sc(Y!6`i5q;Yc&N_ zewmTiPYq+QWsE&_QRSgS?kTrVc*l4}@c@l?HX{ZGq?~FpSOQAyyoao;es0)im=+%o6fW?>*uY#{(j_?Y&8WV+@UDvl4T2S3)13--AzWY?tIl1PaPS z`njIJeqZQnTY>J&Z{V^iuw-v92?&r_fZW=yqtrV;$p86p{Q4ih(JT~}%nxsLyel;3 zZAa#D=?LGHdB=@YPb{RCzptCNU&s1DqC|UNkU~Y)I6RS#zg%Mawy~Pt>peO*Stre~ z)yu6eiG)zabY>&>XuX)}v{L=KyZaSpMtnXJ&SL%_({Lo$M^DoHYAL@^YES~tTpL<-YW}UeWisHy!xv5;MA}ERQ|f)S%B{{Szk+ny_90b5SuaIQe>s{( z!3}+gQ?6OY2eKC8JO12{t68i$UYn=80#w}u^4xE-<_9Sm>GqU`lD!)d1F~svYAK&P z&7QD3`DSG8r6Fj1V<;^7>6>miY%2+iQ~nsBZ|r~Y;4V7k<|mucMuBPUpW>6xs}(dh zssvlOU~;nda1rYqCYmxe!D`=4=Z#CD+t0AGk>4%6WE`Y1kYG1Uv(0NfDpjh=gIJhI zS{Kv8vEt>xybb8qTAQdv&C8kKFPp0-{6g^M^wrsgY$tH*>FhNXO(01He%uLx?)gH8 zlfkynJ0^b&+|V)It#caK`Jfm> zEPr}sDLg=;yH6%&-+cD7LmIb5yMm_{37AX$89UREE?JF|6iEzAAPK`}VAu1aw$;*k zMy-ucdFjjNKhn1`m75i{IpNWk(e;I_e>gQn4$GXS7+RV+Ots>EXDtnPH}jAmn~Mhq zSgL=&Iy|6KUm$sr!6u?Qc3xE9sThAE0JRX-Fsjq9WzT(KC zI;~ZGRLEvcEhS1`S4MSHq4w&Mhu7?!!bYP~N4tqtlGI#-vlb$L3~5L>n;%*|uqJ+& z_kPoRR$xNqi?7{Yeh%)u`#~}MeZRGtsl)69xL^7X#ci+7zbxNqA8B&p24jjgQQO>2zV&Do`LS~%$_|X} zXT=NZCw7H*_!cnCwcKG4)dr#B!x$r}V6H6_eq{d3nvXXbYfs0fExn)#7o6N?eXOQf zucou~ZISR^g|dE-kz*12(t0nPsvBb6*2C7++^q!Ng+KUK#F{Ft$yn@@^nmdTm$SlI z=jR%~%&+ZZd_u~`psbtOn^cFHpJ}cp+*PBawailxB>*q}z(osI&!Qyq{(< z?UW`dvR)Ayxrgy!m za40)Pew zP8Dqr;)q-CnLIi!USVO{`unUSSI7hvCz8<5tjpd?wkU~$FZDfoaiyEheSo3wmWJo1)cZCxki*8N6C0cLONBX>l?r5AZ{JQ9%DZ|S%5vp0KhTeG63O| zz^N$0NYOZWCQSaaS#KaVvKjk?^Y#@v9R1;Yy@%?F>#7E6>VwP1dW3x$6lW2`T$R4bA&n=&?}2M8+y;I+T*hQ z-nCeryRG8qTL63>J)Z?4x!fDAzviVHM<%D?wo5|vsrbN!hZ%8#_{^gpC6fSXtm{Iw zC?Ue7GkWPIOph@_&Ah`IJn-UBJRncNn#03Axu%KS3ek5MVf(t3HW^|Ml|*$;F{3J4yz zWgp&tGBemHkz6D9vR3yco}#tL52T3z2ggTJYU+UKq#7R%RnrYbldE;-s7DWk(;H)3 zn|nG$hjVWzCy?uQMGYk`G*=Z3{Kv$~U^ zx{;hf4ND9y5bj|jG9KEJA4>T}S8v7g6LG{(6ZW=RiIDZ$U|?M5!$K8$jruHw)OvTU50o6x!h8`86 z83Uu-GhwDEQU!d>bGig6|Ib+wpXt*-pZ31t$J6NN(-tU$sO86h^b+EmBP}{(?_$$;+TFFt$5 z02XGv0E%t~w9yk!R44Rk>Ao1UO$rf=P_g2IA6b=43vTF&m)vn~x!v9@5IF_R(wW|t zf5&?lC%Ho~er$^BVOUSeqwa*sp>bTtuu>1)P}^M&w(bU*f$v#TfPrR=+*dEXuX-i8 z$C_^=UBe$^$kiU35j}l5j!6JHn!AwzOk>K_szf4*FKbG-a~^~>A2ilvn`{s<4RbY* zOb!pmnLo-kpBQdr8K0DIhDBkadVyWH_h0E4ap{08>4XakA+_21 z=<5bFC6S#|kyBH7lq7#ormOg75HxdRSFNi*%zSR=?D)V;LUZ}ax2Dpbo08`&F0lq? zX40mj%RRml2OF$d&q^@NrIGn&ArOFT;A`SJ5D`XZEhm=%JcLqie*kJ@8*uocZ|3M()UaQN$f@ zwmZAuiNC+U{bZBz77?R{i}lA9*0-5Ghz-IWuHuZ-sfff#J?~LTjO1;_n4qCDRGch|p zoTDq9Moq<9V5506AYSVlSqopS(id8E6KHmaZKcCIcB^Cv>Qt*s@*FrB|gr zZHyuvpQFcW&Yr$U4d!N>E?SJy7D6^s%y!$i;|WwZBX2aNlQeV+rur<(vU$VBv>~Ap9>QPYw?&0$ zPSAPm6cj_V#XbUarmX;rFnK?*b z7HuKD)oVJNqPg_>_D=JN$E!5=SUgbEx)p;1WTkb`bN89&ou02d5u=(xL5vT^JHDl0 zmKWJQC&ISJJRZadl7Qu)gQoD2g`t&zZSgA`0ht?-yAc7$4;G;F={B}GrOUf{#s$(O zqoOfx&NxJKN?)3%>#Fm6XZR%zaE%d5vL4~48NIXW8Ti|iCc&lS@A}b?IPT^}3|ctW zn?)9GTHev%C1gsI3<+zF4Vj8HN6DqzY+q0bzGU2{`sKY$?VWzKJt#21nt+CV*==Yzb$Fc6}I(mD?Ou4Xi@<~4NRZH?cR)^EX9MVkw zl2y3&QW{nT1{4)zufY!Xj(n3bk&juRhXFVM;1WV%Rb39$Y=5gOxM{EbLSdtV*TD+A zq(+%A&4oj12Cr|&FAgQl!zgDdO;7q)ncT9jQ%w>Qy z$JOHxzwcyB9Ic{a)y718vcWAdrKv^$6j^EifW-RJpjamX6r=U9N3Nrl>X2RiKbz^U z5$>Wf%8zjKv#p(raz#bM+(0JXfA#$p^9ud zE#e18@d=WPYGDsff*um9rY(5&vzEW? zT)Xjh4tp#kiIz9SvNMXs|Lmi_!OCtV(e08w$%iTs0*3z_y@MSl!Lf?Rd3IClNmx%& zr9bb)FHUGeDRkgwQEHEq)huJS>5A0;$N^)g|Jl)j7aPlvCCizB1$*5H)V zFW8dP){ti%o^bC=9qj3==&2a(fdl66Va+hy6Rx%s5)7)7!wdG0$FRGo#7y*5{MTcM zK~BmI{Nph^V^c~M-7qNr7^#Q-twWDf)CTldb%nfB9fotbd^Wd(s7prkk!sq-DJfXZhG(s_ai29w86mNwNJ`0S& zo3PI86)SNKs`vuAHDYj;&hgqp4~~OQKD*u?r8Bd?C|owRI5qT-$FO~J!?oI>TFX+p zJbNatfPtB6j``62setnDEe2tgI|$EJ&Tz)rgI^8`LwT~0= zvU{X@JZQNl2V$ai@CjcgCovQDPI1WucKi;r9+D zTNChMl`N%2jr%b1UwRBJWhM@LZ;{0*KS>k$pqL4VKy2dc`$0L%3tA7_b5L|-zL!9s z{g~dn%TBkuAJ+?>4$6vDH(Zm*;8?bbfHJ?pJ;(9>ObfVD`r9YiqS7Mnk#fofMXI6! z#6Vnwj*%~6qQT6`eWEg<&rPIxG2VUIyk(`%fV~A+fJwcmSY59B^Wh~&zFx7$Q(8kN z@qQLs^INsifP)}DE`s^yR@3r79>aAq6a4}hi4qc!Gtk{`%^EDJs|banaMv#$GF~C` z87@#Es?Tbd_?n24PgEBoZpz*GB>6-#Ln=!&O-l;!FidP+U~1hXu+cs?fY$%^b2I_# zDm@4xvhS>ZdG(H!ZdisAjrF@edoDR;wnNNmrq3mu~{pw{BxcI*Hm@p?BQix<_mHKxjkb_M$+n?lPgigbROT)_6Hp-TDoZ?NI1E?Me&1LZD;C$~=}U5+3kBg6Qg4EJL^ zC5RVLK45cP)3T(8)d!sS_+pizN$E$isEby@O5%$S$aRA0WI?~s_82LEj-cOPHvhJ1 z7Qrp#;AJ+}$+C(8H+@Oe=5w4tSo`0~P41H@)55@+1$&r+bvVZbHRbp-qy4P#u1v!i zDs!W!q1MsC5_MWuAY2!L8qNRp<48b@!)<1xy7-&SvQYxJ zShQsYsVM)VeEJOH$Ftb^x;Ya)poH=@r>HLLm#23Xons^g8rNgp%~#0Z3ic~(dncQm z7o`yK(Q2Kp4Rpc@sZ*AuEQw>t4LeAbpLB#)%_^*N=kqH(le}peUnXz7yYeZ$+S|kF zI&C&)YVd)t@eKziEbmGeGVIGT4f|q=k`Xm|lBTbxJy?%qcMaj1Tld6GG)~Abbu@GP z245NP$0A;ckhX;zSMsrjk-1{L$K^~|E@PKcbAH03=4E;_%m8v}FEM(7gypC#hDo$= z&@;8ZSo!`Pa2g?+G1oX{BUD57jbS`J{J_ude9=ubUjpg;;d%byn#4W&FE1#sxKBLQ zstK5=w1v2vLl+}%mZhZewSg#aGe$~T*`bhl(ksda5h5d8FJP*X^emD%BE#VxoZAY- zp;I=XsVDsPT`F%4m68B(m<;8gT4W|*6jcNj`MJ+Y;Yevwd)msW57!&(5+85di(l$y zij8kF+C7~3bS#E_8{a0)VH6S#ai4~#xhsPTW`ZYy$cq%WYcF}ljx z3)PX6Np8Jq|5ZsY|Cu;v30GjV25Bh$ZT|BfQRrB&FyLbf)Z5d;g4Bf;Dim9Mn_Btm z+*Nj4lG)EmlPSuhcvymPlK7_fpO3{tmqosxj5l>0wTp!vRDQoqvU~p+6X$w1^j-G6 zgbH*U9YI^Q0J+iJMHTjoD}aR-mm6(Qe+wr(Z)z38smumF>68^FQiqd2Tw?wR>11r7 z25qpbvUc9U@s$CiaEcB3~F~^l5d!hVg)c)EGRQr**zl%^8KLGH-OXg zHN{sq+hx=x-n^@H1p)zb^W#_^JcbnMQAmE1QAMI&DV(T@G!9BL)ukRkNH8Q(baHKT zdA;Z=?az}q_vU$#zC^#wsCX|GkpSx;b|D`FN2DVI(b<%~@P~8~paTLaFdy#qczbz1 z2EZmDX&jVdv4oHF+6ZOwis`h4rOjJMYTcM^6RQRKjn4j?x&?fmvky~$md*{8jDux< z7cN7mGxQbM{Aho&M$4OVwKeUB^PwIi#>_w5Q`x1k!C<(aqG4YF0uXeZ1y_3kmdij5 zZ?g9?O-B#Bk^f0OvmMP>fI1uQuA$XR`Z?=&KSEq8?q#H-`)AolXT>nV#Z3I@@E{oTNcPETHks6`!f~1!0aOnS!|rw~`XQ%QDCSQT#`Gyhkno&@>;qJn$Rt^f0nyWv{>;_tOcfnVz4|GiDithtPD(H- zAPu)d2E7C|LXM}Q)bs`VoSfug1q|0yXfwdlakMg7v{&5h)X|DOxe2V}WXOmpWEc`< z3HcVcn0Ls^e33+U#Klo+Yf$_}yIP%Hn`77MGuxmx&l}^WIXc>i4;(SdB+x?r`VrP` z><*JXOTz+l%tv15Jl;#rK#jZGyTEjNQLxa?j4nI}XIrrjCeaN4jTt4zEwQ8&o@Nz_ zyjd!|h@_$6amnFU?_3faTr#C2**pYo`4rySCSM@riS<#V8|@3YmQ|7!d4hPVD0tRI zImLt2sNj*`5Fzixop&J&OmhZz_sW9|9<+fl16 zmgQK-Ade3&TWofXkB$3_d6<@kvZ@{xpLJhv3@<75;^&1jMO=QoDRh;q!VZ0%PknHa zL&6BQ&1a$RY;w+LcAe;~g;#n2R&Gh}1&L}spBfR5nYo{6>9$E*e)(pYUa}V|SaatW zhd)$YOYeJ@s7Wi?P=MT9#&mo8oo(!yr4}9bf4GlhAW=LICY^mx!JgOneaIkJXP~-K z{F=wnIAHZ*imK#sIt^0nU^M+VD68L|%uD@!pC?ttJZ=ysnzzJjS-chg zLr4k&A`Mc~ARr*^P|{K&h#(*!-JSEzd*1KFI_vxkd+lehXW#3(uO9_lM1g~<$A)>V zHL*l8XY>Yj(#B~@wRm zcO6%Bod#}ILHQ?(2+9Z&`$#sm;Wchs{>EEOUX4n*^dN$rx9c-kMP(-Lr*fxeV>Pn8 z1a7xYRf+ZRE~hUHmF@;SqGW*Vb+>}aW;?T1lhkaJ%4(}z1m5CE08yoC_IiWZW;~a3 z62&sRgh7OwK-1p}0%PYIW@pt>+qWBz6iT>6O=O8J{QbEO!KrLE)sE{MKa|sP2A`D= zp2COzIJ+mS!H>hmw6;{laB=i>srK0>q{^pS<_b>*_{C82G6FqhE-chl%*=vaf49|3 z9h8fXlA$Py-l7dEo zMXAEZaz~DD2zK?b-@Afl=R3n;_CO-WytKLsS>xo|<1!H`G-V^`ak$efIl-kTwA%P; zm4+=^XeVKoyYrTJF1e!L$AQ`hU_*v)Rtp^_?)1f0t4km)N~^qZPzyy#--z}O6NE-n zt7#a}k`e~rPpU)p1c3V8da*s#6x2`Z-PxAqk+9t-pOz3SAD zsy5XY&b!a}P~XEo{`s-{OOEd{_c?X&hBEr`l}_bMFz$8gdZ&<}*#5d**9WuAkGPZ7 z7^Px1eXs($TRa6>nYkOkgk&GF13ldXJ$yEFSL8xTjhrO!z{9q|!GaZ2D)_J=FAfsYSFZ$VYE zBz0G@2VyvTAAeNm3B|wq9$J<+{6~n7WOSc#+Fex*4Yfydm3A{bxN|PKo(hEyWcCKcQLh&IkwjjOpwk}+Oound2uKn%`1M%6LnvRoC%9Q=< z`IA7psuB(wG6U|)IAT@yyx>A4!Gx@uteFBu^$+UBFY2vuP8e)=cmul?i&TXo>a_y0 zNpHalxRcsWo;rDyepa1Gv}u%>SN7lSNLcuAFkYEPC=;aN$uo)A!KyC*Y$Xg>9^zq$ zIWlZbp}kgBZViL5L|DcXTG1P)&C{fvG(5NcNu`nqjTn zn3j}klV<$l2D29#dq_fxHp8g$A^toml*lNUG{c&ccX0hbO#3U+Iel()T9{_4Q4^l& zbXuSd9S9AbYJ9OL<$BiWit!0hpP9pPt5ZjaOHeRJoC^2h8ezhXzRX$+s98jzEgqdZ z-ZXeCr@nLP7t2QYup5sAPk=4Ye8p+}(mp@Sk@o*&Z1d6AE{NVv*rBc#Ehj<2#&hP; z*MO|_(tWG0Cw#2eUCRMRkgxQnbm83^5T71T-hU#oR&dhK%s{@cYVgN5I9%XY3CScABUi6CuHau$EABmZDZE0Fkk=dO!;gU#JNUx8NlM?ypjM{T`r)f%|h~)n9 zyqWhROvU4;if6>MNeZT0YTxwTo&9%rTv9a;Q)lb(zp01mf=XV=J_aWyO4YyZlkp`* zQ~$9(X_Pg?yvR;#<`i-frSp3Pmx74k#yzop@7j=|ENdPg%HE91-#UDhSnK%XK3R{s zS_mG-xuhu0@4mR~m#*_hk2FxC3j0Vn%(umm-TwoW^X60~KT`c=xZl=}tbE<&!tF)H zC^bouDtl=7lV6urN72Ub8$SE}72UUa5+ONN7g;X-vies^t^BSTXBhiqm3;ZDeAR#g z0^z9?48p(0;R)RXvs8HP)9S>JcNCwWW>G=~Bq)@!E1MV2OEgO8r>@pDu6)8o%jC+SXfULm;T z>9qktU`tw^Q;!s1cQ3Ahwn}VUP25Ub>x<=rKz>r-MABfTsjcLB;PBffr!ftYnU9Yk zh?6F9$sesB`VLMJ*SUWKX8Hl_+oAluX?$6{`r*x^6*R#7(qudC@Lv04Xxo%8^oOqq zKPd{pfcdrqXU=-A9Ip=|@ox%Vnv|mXbnlM3?)?h6KNr`|Op210Fi>zt{(c^`de}Y? zj?w7j?v@Ma#a==vMLsny-v}nR|9X!dz{|5ZgtF&!O=~E9^~Ea{ZuT@m{k)LCQ6Qz} z0Y=lV!@r0faoi4#j!{RevP-JIuIpI&B(%EM@!T0AvKV@QwC4_*_t)Fz7HHE^YH-ga z3~xJtT{i821vB%x-8j8HrTnst`^9=($ih(vqqXw+P$HfFxpE-bFfin_uyt3rcR>@C z-ntAqkVOD6nM6xuH~~4Ap~*frbxMr&7$CJv-7&PH8kOl-k0FxG;ks}s$z~v#_4buW zbF!^&GIQq5+ZcP4ZkDwB-|x+DpO5D97+p%x9Y&5N--);Lnt(ngD^lTZ%Ai!o0AEYA zWi5IgrbUcDmw^$|N2fo?S*-keLF=%98AC*g1#ih8Iyhv z;`J=o>eqTHY~7l$rBWcEYk0;CXt=yub4By z1nR~!rLN)k1buzY25sY2F0so<#0Eb%W40uo!D-F+=H^@2L|zMc9u@DfMiXSUJKE8t zGPl#}D`liBy?*p1Hz*+NPkio=oYvi#XE!sDZF7&_Y+3$}g8QFtCfLRVz}=UEyh3gH zkxiTy$nGf7dUtg=bOxyo;WU$7W7QTq=!()fMXJJukNqN|b@v~uu%6EmWB4OoZNf^z z=-h`NXf|6OYj=#ojtAZb`?DgHLGCJ`1lfdrp8l%b9=^e%VhJ5&zQULtiA6L&P?ESpIp>LXwF`9cr3koA+GDPxJ#*J40S_qiGE4o8raxQ89DCr8|OSnNKAnIFqha zCz`AD85u8;Tk_afuAs_^exV!^4zVDESCl}L1cclh_tG*)hpj2^ty7mkf5u&0ioT>! zfqac`dDkmt1U@z`nsH{Kq{b%Ez^eAxFiit5%HopnRh|tcAGRZp3r=X7TRqSFB&Ts? zV=(u)^zT=FLJtt59=_?btf14*ulV7IO`3$E`{VcW)W<}l!(iv67{X~Q^R7a{ho*Ql zi{Uo{J|)(ITa6r2m!f|oo{I|-#{6{r)cEYT)M=G<17pX=uUF%>DsT@xB2cEOKnuWN z)U@73?IZ-(dhMrBIBfy!ORj%w{Hr!o1aeH;$YG7RXX?O6jh#~K2p$rPbn+xHa5G(l z_eGdo+7a-_4h;=? zL06>y4zJl3iv$(6mF5oml%3>CN(38BtEa+h7uko*u|-r|kBEM9jhnNzb51^HlP`g$ z+6Tqh8@r1}Jb&4Vf@=(y5u)%{YNbj1Xn0FULbGGUSqE4NFnMtSHWQo|Yx(bqFS2<0 zQjY3%;KlC|BpxQ*XP&;ax3u?s(OE|5IRRj(z9kNhwlxu48`^m6abnrEsK~^^*PO%69ACE>L zUBs-t{v#EtYFGYzBJh}v0TqzgNxx?wCDZ~>G(;!Tf;&~EcCASFIj}ugqFH+72VrbN zNijnCdAb5JX;d03xc%!kN8hf;)xx#Yn`vCrjY|=}=Oqe<#2HD=yvL z@kin#^eF3GIN^OUK)E7%+x1xyNk0?IorZA`Pzubfm((R<%Y5 zjE=R9f()sx?~!YKKk>>JEV9qm?=)4b(&;IsZs5~4p3MAE{88C+48%X`s1+9`T0N8L zv{_R=n#1;*c;4QEq>I6%cGrlQ zaH{Qz$#L(@LJ}m|BI6xRMM|0*RJ_59;uL25ah0v*iJ5+@>vrLikwN`7jBeyRuKAj# z(djzH92~)=is#=U3$2wAXRNYcAaMm3J`pz4RQAy$}{@i&rUU<qs0 zs`m%~3Eq+3km#e#se8NYqc&lrheWfOaT8vNM{*bXXI*DCC8=z2Rd*b6a9XB%BM-~D z4G5ipvCr`02HUp=VOK9NCu2C!_4b7m8ma-m>PEI};+b~EzW6gx4oEo18$46BzAzAt z?}j(HteN@-bS(T3s_o6$8|(0AUR}rM|1G)rJm4441esVhZSo&?C5DeAB~@*LS&mL@ zPZp@5j+#UNKlQ6Mx_C~F^B)s;k&A%`xgPI6X0HnRHV^(Yac|51E2-=k!)|$$(iiww zP&zEcE6+0@nzN=VeL4Qv!mCJ_X+!7v<)rtnSLyxvRfUDUWTSZ3IM<*&Yfg{?*^)RN z^D|Og>8qdPxjqdab9P)XzE{7Nc2AXnW|;fu)}LF8EJ|}ZdqHPc3m}%4ozUF`7V*qVRb#&0Dt`8>%RI(!g}W!H5bUjQ9gBbQ82hNyTgHMJ?_y!A;^|ZD zA17iNzP!R+(>8cpaX#ppQG@{L#ov&PU2Klrc&J~l?14OcKzM)Vc;dL>c65fi00G;0 z@nSQD+ZY;(`~J--rr^yjd>>bF821VGI~&K1W0_wXc@4nFOA!T1uyeJV-w`{%^=k+S zhE7YLFM7FgrxwtemG=SwF5?IMD1A_tFhM^4B^xWlA6BMkNXWVxPLLb1q$=@a{T8m* zkDrOmNT45-W22X&girNIs|YTgLDV*k@%oSs7)X8exEBdk0k+=19QO1 z+-g^W5s)9i*b{IG|KQy&5&Nu=9l23VJ%e6-By?w^daWHO1CJniKt2g0nud+uhC);l za47x|+;*yO>*MhrP-lFle)NaffsflGk0phbKxK`L$h}xalstr-iWU~h_fL&FO*SjB zEjdlb14WDgIY|4NR<#ja zp>FIB6GC#ycXU;*zsGS%|B&=+6A#HW$ea_o<(RdHK&mBB)_+~wBM0Xw+C1Fk(}(IbX+;ywT7dz zk{xj1qp5QA5&x|wF2PhK{cc>Y_LHLQGnv*&b_&bd=sh+ZgjD)QgMyaa2qkxnCmrYE z&CH}Cp&{Gi!z7bGIII9W5h^a-X1@Qe@*5o$ZPH;JDq(_pgyivPSD2)5EGKZphM}=E zU0JM39FVQ3QsAbND>+iB@Km*ukQe{Xp+GfZ+$APT$%cSO{6X|iXsh$5s9%Y*aSCe0 zA1gLY&NWdY@2W5etBA}Gbs7_E1;ndVNU)SmioQM83OzzlPjblYFmXP^ON}6Ux%1)0 zL!q*i@rdKx?+v~zfMd=-)YBDJYJ=Ku<_1Z9Oqe>6*npN5p0l#8Qpz4 zWmF}pzu^5O=+hIZk1*vAb5S-m;y-|p9a-_B9=WHbx}>G3l(Aopwd{#C-YHu)wdvWE za^fPuoM3BpB7hMmTJpBGlCpDohpGIoO~?j#S!#3q&=78Xelzj>mx%qer#*S2eb5^f zK}5izH%{^D1N~Eu_dlNbr8T`#wwG*l)HVqN$&3gki4h|R81Y2C;09_^9wCj<&u5}{>LMSh z$V7L`B&y1$tHQIvaz)ng$~^jQE5@dQsFr24 z`6!Zh+BPT*$%xH+s;Thwr~rVfM1-mWE}*i=Xo4g>MloOG1Nv&}CK1$%Q$F1n5x&pOE&UJ@H+W)dxUx)2QhMlWI(MCoZi|gPT1~INM{i7xd=_~hfK%F# z0+E{V#fWI;izgxC79>bQy-ubUVU+L8Ya9gLIW-w30ev3?2TL`@FQuoaK4lQ&Z^HyU15;W?wn8Kxnfub@=yJ=5y+Bw@xa26+#_yVAB@vUktar%Qe%S z6I4^khG5yYgc~Ahw&}Gt;YQ1gglcfG+2sdwIfC@n2S~pZYm<~WFCE`CvD@d_+~dkJ zinPV;vbEH(v&RRpEh7Av1$&%N5ifESFD2x4@NYYb@l`1Emdex;Dy?|ss4t-pI! z|3JRMD4^kS>mHSBiENm+8TOYw%E$RR+)dN>rKY^)Pd1VKR9AW+Rx^zyO8{wFq&-_i z80OYEd$>8fE|W*5kcV5^+ESI(BEHxx{-(O2^{?f})+f8IodK-@FWOx0wT;|awSzY5 zb_L~vf`RDZZGw>Fs1S`sMnfdwp(QifPhvRD33vDMRzn65}4iI zCEo>UW^={FlB1WH`DC3c&LW;Le)XK~e9jo=H21YL9iD#X7IGc$ZrYy}$f+)a^QNu8 z+vPQXP2Ye?9<|Q^z4)N@gPyYM)5@?GT-Okp4|ZOU2?~uXdyOwE z1TiU&ZShWg$({gDOyo3<)8CB$JniMoc17k;sJHux&X3;Bi4JERBrE)5BHmq7{vk1POaxd!%5wo$4sA0>`qOXCzwxF|-=F{X(A-`F z!J)GIt5b2VH)w9)e|rq`ONzf&gMM$c|K7RzePI4ul`Zx&&d=V|@8UO8)J%)D#G}91 zITFN{sDqd2JC>Mkmspkla0dV3?f4^j`$tr1Su%K8wqsfGb{T20^hz_PjGX0Rd&3SR@hFq$J^)A4sX=dX*>+BDOecgNcE-@k&C)(3LdUggefqVPNT-o{?6 z*qZ&yQd+&M6w|FcsvSP_Hf-}^V)LWLmTEVCc_uzuX}dRgd!S=`JciVLl_5!{$ zf4j5vdj~V!v9sKJU!Mn|iEI4FMHO$=1 zPvPA2T+J3dY#~Bz@D<6BBiS!UikKs$^09izvG&3rFj1S(LJS{<+xYzn_fzN-WpR^5 zmK5N?<^8s10^~)=S+~-e-}|#5%$ck5`74%#m@nsqnDZo-ea{8_raa5wI2=9@W0d-3 znX*acf@K|xWg~__o&98i{Zutj0{v91_k9!l+VzK^8>f?#Ck59JHE!-?T(4r_i!6y- z3-I0dH@r-@dl(D|yLu1c5;G`7i{y8`BB6|g&4?8A#E`R)6=6LFwKxWOe}(>o!u})< zjBchvjM#_4cLGmZ0tv;7hcmc%4GR!Qg?F=M6?eBcj=07Wl%wnf98=gPiYU^=f`}x` zzn2+Sn6}4CR{W?kYxTb&lB%4kwHeA(jFYOGZE*h867=g`C#UO4(_IDxOrzWb+k3!k zANxenyDpN^8M(_66J}L3{|i65%&f)d0B3AyTG+BPf|M3lZNx&(0Iy2oll1O`i2?7u zzw^J&ggepU#I!2~TRE*y9_hTlC+PRWX(-*Ag;9U&eNLE^-MH@OGLUs&V)#R!Ao@nT z@cws{Z4-`W?N0F|Qo)S$)t4vRzgk1y7*Di_OYisaD=$747gEs+-9qTIJ)KK@CGZC$ zVyQ1s&!Yi@9yzPvvR|eor34=TjCvn@eL(;Ra478IVStRmH)bW1Bzz=mc6Tg=|Jd8; z2Q)u?S%8b3>4gvwnaN@(@DfeNr^2%|C<_H@p2Z1&tTu}fEXkySIvhI!#M{`Lic!0bBmjm993qBXooOP(B- zLMWx-rvuB6WGm+>Oi&?0(_qFBFiOldfT;M019K_~`$5E4UAUDIZsi)@&53eu50^gHRpgd5^%$l3jpBGMY!>A z2a!x}6C<@c>DH=rsZx{L$Vl|V{Eq8OVv&zvTIaD&LNInQFW5{qfgg>Nrz3zDa{wh) zU2S#!g26X~b>g#MZxU=7Qgq_wn6aA=@_!a6>=k=1AOc8%QJs=b0J@lSlB%a$`7r?0 z_E6C>iGP)F)zhE6|H%)=Ukyup!{YtPUJAKvF)ZdQF^zS?eBxCi4nw|uBU z+iZEnCsa&T)T69M;;pdR`Ds^f8`FOew$sSn-XnFj9Uf1L>oD4W_BBhW<8W0PisBur zb09hv-C?1^u|P&XQrKS-_57B;>q(UC1+%uDU}T_;yg^CU`g#> zeHgsG+j1X3Aqw5b<1DGzfqr`piSi`4vllxf2p$t+1_Oj=2wtsgChi77c>=DV(e;^p z6)$#=cL^+{6b49*-13R5Ycvkvgn;&DZCvUxJ6y8ttAukm7#EZWh$7Gn^P+E5%WPOg z>HF^vCa3CW!GYAg1Z^sg@RxJ&_srw*<%n>JLOueHro*t1Kr4Rcv9EM5-Bl}W3g|8J z-!&0=Q%jMe8OyN}*>*lbdEyA%>^$naK0VQ0paA|haf;!Q%-skzOJ+>wSEb|pH$my+ z6eg`pv#$&82VcHT1U?ia@h^o{uQBED_2{HANS9a|h_e89qXem;{~(lt3W!2PfgoaI zFN3K7)>rFFx^fSEi|Z+`5v5ot18M;v91TC2sy3ujCF7urFt`YW-{!+SBFW_SeFNmg zkK(EWLdwV4I=ILALPq^z{L1Hj6paN$_W&UKaWg)*SrVCp2qC{n>&%x4hY#3bCo!JY zmf_#WiK6?_R8+B_LV@lv{IwJrt6y@KW`MaJ`*}I(?`Qm zmn8eW96;mr(Nr*L;s9J8nQy;QsMWqU+Cgd&0~+bwVx)U094`&?l z+zOgZ{m`djUVrEx zAFOgxlA!RU=>TYIi6{%4*a3Fhg?EAAMn9m{W2_)wMia;gxeL&b;V_-k5%6F8B+5;U zi_U4ic@RkI`~s2%?~#(KBP?*XlfN^oCHG2x21Kl%^_6+0>2E^_)3z1u)y#l}&!_k1 zFfo~Brk%0gc}U%^k2v11gTJS3Uj*&Ff1+rP^)NJ&8Gp~Fe*U~{2a_^lo4}mo z_i*l}(vn!MaIpB*HRQ*p8LU=VF*zA)iIN@I^^)1Ctte}MZ+N*ynqZoTYc+K}ud4^EhJE(x~KcUpeA18=B zC?Y7!I%0jA`Mvn7KIO2YN~(wpyqua$HUsxs7cff6I&07HqY^-bI|l@8MX)E2SbOEs z`scVFz2A+NRFpUl!WAp2_=9|o3>8p#0@vN-CW$N@b4mDIJq0ljK<(?=u3)n_%S5mG zWENfDT+LlE!5A@7Ms%QrfEhvl_RpurJWr`547-`9^~H@K76;`r0uy*|=VZ5&;)2v| zFB9+elKQjY&&P#auLys+7=3el{Ex@r`sHc?ia8$&xjp{)oL%mhTiE9Wjd!qt%kDlgt2Rd zwLBtx_z)(FrsV7o6I>4yHWB8Ago|s1OWKD&v;vY4wBJz#c&xgoHN+v7ye}1S=7x5m~kbXeG0`$pz(O}%-FaWAfL93hiOZ=$PWB*8%F9sbX(%ACL{MyrGRrqSp>i zuOSOr#J1!?p4CTY!f^dW$S@)}Kq8(e9d3wQ6hSS)Aqr0jMHx)@hC=%dfPx&4L6B(N z$VCVPZ;GmR%DDs(k0L!!Bx|g>3+#ut=0PxvYAklTq+cT=5?6_K_n~^{iP9VLlo`

0*a(*sQ(ZPvT^)ks(0J~LWX5=DzA{` zW@qVoZQ);8V`pb)ckA!Q#s-$pSY2Jk+8KL){`_lato{CdJ<~ToKR-7&_v;rnH$VIH z=g*m$nd#~2A3uIfO-+6O{(W+Ca$;iQVto8^yaOv@T#SufjE!E5jvkMWUW|=gj1F9U z8@?DGz8n}h9~e0PHncx7ay&G2(bsp}-+$cKx8L7?G17JNwfDTU>!PFMtfS*%sQF@` z`tobhWl#E5Pvq4X|I@a%^Tx*WPt{j#p4ZLR*NuiZ4O%y~@?&FT-@bht9v=Q*?ndXA zFYWE^SahSQsj0CMJM8=i-N14iw-o}nWt6ui#J9!xw;#Y*Xyd%1;;O>tri%Z%jDDgb z@n3P{GA9RCnd8Hor)rx|Ez8Tx z|Ft>(OXc{N;mFL)OifLF_wHSCa&kgKLUeTWzxqaac=-RRZ+Lrqdw6)bxw*Z>3LLJk z&d$yb4i5iQ+%PvcfAZwX(W6I~4^@x#?w;#N9jd5aDDz!Q3$01Z-UzY(6&5|>X1`^j zIbdgBVTRu@(5)~q-qOHsDWJEcL;?Ex|56A(sd|MDD2BvM&f8Eb9G z%F6z0ZAeH+{7-9xkB<)vZD5rR4h{~ivH|~3V&lJj4SIU|e{l`0tnn|a@jp$CTS9_c zJltC_&MgRp0f0APFcA?EAt50I0wEwEz{khO!^6YH#RY@G|0)~Ulkh)%4N4*fga%%0 z6pURbTdTI9H;zu+aSrQi^u2+r#xiQx6%D-Qd038H7B(Cjv3NU>(yWs|k|pE0IXCcs z`5Fdd;{V}mluuQdd~%#0Y^a$2XxSahq}y2e^OOB#xuPzY6(ObD^tI}8{eSx!3tv#+ ziu31oAC{u{d8%ZbWw32=d`zkdl`lPX22$@o`$j@hPLy5NMhMaSFJHr7GB$+YlvWSm z4s{NzcUhoG50KuQ#kQTCD$boKQ%SQFEmO5MAFYiQ>b|$Q^mhJ(uHE`=e(mG?bKyx8 zM){^iBkBkSlltQu)^c^WzdZDQVa|X5pyHt7$NNlWM@$LmeA?+jP?)~>V2>t1#G1Xf z7!K3mS&E=CwqJVn-@XPslIKq}$3MOXPZ%8z5iVf&-sjA=FX#2|aY%0bpCzr|%762H z6Nzrn!$eeFF8pKm=cg2r(@Kf2)D6e46Gn+R}! zhi??67&~tK<7<=^Nxin}F3yW&*d#3cDN*vY=13!H z{Ij{$yk1=K!T>EL=M0j3jb;F`)zi(?JMbMlT3r2^+B3(@Qr8&NR{z>#9jYDI3WAj>*Liq1^MWnm(b# zt$UKcX;-AonGOF+`vt?+3CeEY?kkZmygg80b*0>DpAfn_8e`eHMy6VJlgUrkv%(}E z)Ox(#323Ky$Kecy56HQ?SwqFR^>7m8%2$X(c~`%ylA04Zc-)h(dd(&cbU3L=?Iw{u zw_l`u(7Av>J%_Ds^n^MVFl2G8a}jlH%RsU$j-~oLNiw&%UF}s#Y~Vyea{w@AiD#w< z6L^IZ2JoZvNuFzUGt7!ag0!?CMfoa}rTKx$W18Za9=Av@g=IRam#RvPtck{2%Ot}6 zxJu6~6E(0=Y;hQ#{OwvZ|am1S|yQfqL2CpOsc9aH%n+AgorraFoC^ONr5XMQpSK{i+NI)+R7|c2=W<77{^y0-+IaE5SJ> z>7g$WiI#9=OLTCnePMmx_Z;#^KD?4#+EvX+z(`WpcxuAva|AU$=_yj_@-Qu8i&LLy zF*=k@s_MG))m2*Haw|IAE~sH9{Tys|MXKHX_dXE?(9V7X?^M49XoGw zsCwyXLruJk5pU;YKITHAv}we}EmAI#0BuQ9i0Bg~JXF6HOUpQoOHJeV#;moR=p3y@wQD*@SRSF34DHl!{>i72d{OPo1Z4zkTjF zH!9OO8hUz@N>w7C*r!lB_B7%5XSD3RLsN&(lX@~u7BU@_K@yxY_XPiX4numNHPzg4}kT~x#NZbEn5*%-xnLi=Q{ z@8sd}q+P4jeMxMK_B$>R@)qc4^5wLGJh{Ls7h=fVgV?b2B^HIT{hH`GDtf(cW(<5G zS~okMa{4YtCht5_X)yFPBVz>Rx_uwNmb(t{9Yw#6CXg0kO{9=0Wb%AqJ-c6QgOW70 zd=u#*#J`{5w}_n3$ejoa|EVGna5-t~3(C2Irp31R?rW1%Vmu;D`+YSa%NtULKZ0Bn=Q7`rr$Ys~!19@b_*dDRG7`lbrSQk+~?xKXoS()5FbTr691lOu$kmuI7?_MVP#GUD&(3Ay7=5_+w5-YGndLjfEN7gPOKSa zmUf7F!Q9UI%_HWanOmI?G0OsOv82dF-e?_T?KTojP=#(YnE5?l1$u9mYYF6WmlUkyAPW{2q- z2Rv-Fs4fh-+07%9zyH-DvuUI7JGC0O>SE z=*>jjJCD$53WShrzqL^ke5swm0n5S#ats9lKnLHQGzShV5Fu4{M=8EVL7FIoMWA~C zPLo==F4FhlL4@kdC^Lc}J&+QW2sHRS3Pl$kCKDa31xl3AGU6dT(SP>KQn&^K7`@QH ze^w9u3INx*KxPdo00$Nj_M$wV;F3s(Xdl^p;v;=x__SXeRm97gSPkna!p^7&nYjA% zsK|7fAw-RX3&!PR4J<;gMZh8=uSG1eeLt@`EnRL!@a@phf%6y{)!1s^aOnrQgpcsb zW&(59V(08-YSvvoq($h>s4#^cnsG!c`PmV&WSy z8Q5B%hDWr+wF!(7I}iHnj_dFQKPFMg!E4teA}^ZOF4FFVHmMCWW7h$B?xFGA#}3AZ zf}Z4om}TFxJxX9i%li?rOkq|h^ z&R2JS!nZ~lslRvx#AN+$zrO1NrIxU#m8qs7YPozDBZ+C>!J1MXFVY(OQgM)WA^AZ* z`EPy~q&%`t>t;t5za%!0Ni=wzh}@UpgNP^j?u%dE|eTwGDWraAn_MeZi|d&uUUV_p~x4D@;k zj8WwGcL{uB%cqIuoKO+;qRN5x80BprcEBC>i zjmt*m15Ktdk|C42r%-lHTy8PScXMoWr5`&SaxmRHMFR$i8VAp)%Apw^e~@`yaOGNZo6R?eEj1}`f+ zW-F>LD?J7)Q*<(Z`By89S1oQ z8Gd3}6UUFAV?SQbRt+?FfH)v4;?3&oeOg@o2DWPYU0s%dk?I|86?bTwt7HM>hi zR9UGsLm%nl>KL+Wx(2IDS?j(d>o|4aac|Y}W3p;x?o(@KfzkB8jz^oT0=x!JHq#oQQsjv78@qW>Sbu)ly5L@t+XDhIb?9| z$piH6NLcXKTFTcxds1%0|JiP+5{!Nk>-K4CyixnI(d|i%Ms2aCQ@#IC!>&Ib;aRPA z>*r}x-(aU2clk2!Cyho=%Gsl0Ukx?JKZ!zJHR&=mfAViIlyB;80VAaGiYgp}H=2L( zSxtE={uEEINF>`uk&LdZv}QIJRq^wVH4EL^{zVpNagoTj2B%D;=BH@~U#4r1jUF=(Y$=hDAk>U0&kS;kCOAc(P^_S*Ba;lB|)M2=obT-h(`-7<1p@vUt1rToUBR&ma0#tio{<)ktT(M`}gsM^YG`~ zNO1B&8;eBZZs0ykvc_7R;ADG39*FTn+w=G)&=?LZ6jWb{{G-1G%yk zc3p%vcA9{#GzKs_9XM5)qckp)#xCTah&J`1{g$s^4-ZdO3@6SpfZQNmjR0-@msm~w zD>R|VKGu$bsDOw|;9B%CWH_~;jeSBW98{J^DqM?mft|y`aQenbaL7r+ae=pJGK)aw zkH}tW!R)+%?;51zYNT|6=oc~jV}7Exu8E}QHKYcNR0)Zs4B``jKF$(M2PYK#dklJ0 zLt4S1y@rNj;H25zq*)>`mwo6TS(uanrBBebjLW17Ytv-g@GSAK$^(KUI5hUxbih)5 zg(sO+@f3I*^c_vo!V3Bh5ZmbE_vMjNS>w#<6RF{neiLEH6PztFhmn{~m%EhtjZD{8 zO@GAf(84WaTlK37t&6@kHzPX^LtAeO;SphZZ>#`M6U zgn#w<2o}kVU5IeB1R_8{Q6edrocJ6vR_U^66tfsuwn+GUJ}?wCHcUWik%naUTQ{d_ zI$E09$Kg-ml0ZQ#^uf{q@zxl#<03Q{2DV0%EFwfN%!nl12ygWkr4mYHa^uN!mK8c^ z%@%!7mcQF*YIQ>8o!F_TYw^d?gQIT4U+hVDQDlP%FgO%{I&r8~;IDN;u`Na@%5v*wWkO>0Evk-r%OQcbKnYq0OKTCzX{!D;Mn3js z*F%!bbKrWO_{ENVFay2_0pbzvpwP_ox0??ccfbleN+vr_t*sl(Up`pju}2ZF6K?T* zZdqY|-)RxvUA?hrK?}(vc;`cKkh@pZw#i_21v|K@9um(719xV$+!RvY zdsluqH*gr&yv?+E#NvO1&B6HrGxfZC;QM=WUuHWj+?%%!)aUnKTQJCr95n_X<0$+7 zx!13&oUIV@0)Z*C`tpJCDJ=-V-%i~&Q9gM6>7@PliN*WFfV1N`r>0Gdv%qm2AGoEO zTZ*mn%!{Y{ccEw7XD6(D$6en}bq?@~?TMQc&I9Pqd6ds1Fhd?Je(MQmzOHB6ziIuU zUJv%qLtGDao?dVTT(qWLWG@UGU=BkL@b-j87L+cjgfH<^5J^Tr$iS-Pp{QMSNH6`1VeAC{jSH|4+e$(2Qc@S%I`PnkM1um zQ2CGkO}TgF^5$kV;p*2Lui=HVZ(k062va>3IqDJtttn#!%Wr8$Z+AX=0S6z!Ko}nB zzrIEo&ux_@-Ge`Bv3QhdZT$z!Ut?*-J#gs{^E8tFuS_5&xDI18Opq!wsP{K|W?UsH>Vvo6`%U2) z&L)= z>ALkxb8lqIl`UV!e0eg|zL5>T{meFW+R;P3j4ivEa%rZJGlSgxTK4~J+O=($jJ>pT zW5#(|YyEvS_)f$w6Ga>jHThB3xAg*b9$or$>XmaV-R;{k-sMZXEB&7G^t^Wm zerWUR2Cuh=A7B3bo9~fk=MLur1OEN}{|7KY0S6>dzzg&%FhKn*B`{*OFL=#U0U__(vyUPMNvXCN18E2%iMjLO$F~=LTcu_|m ze+2SJ9$^f!NF#w9@<=6d1Y<0C%;Ru1^xg^)J{3{KGD|IGyOJmt?K%(&BgQ1NOf%0! zGfg$uOp^&Xm|!zbIp>tqO*rYqGtW8g)U(ettFR+OS=5@cF7^L}s_w#WYh*H|4ZbPe1Jx2snTMwNz72HC0qnQDwE&Q&n{})=rz8CmtOL{m`yM zgG#izNFN0@SYe0ywWlxZs#I2GmxXm%XIpLdS!qj+c3M;c&CnJGaFsGwwtA(m*kQ*d zw_J_H-RW4mlC`#7POEh{UU=hecV2oqr8OQuw%w}G!Tbda-09FYw_t+{CYUC5=VJF> zckOl9S%@Q6cH)S!ore}F_>IytfV&b{x`YoVx#UJiR%v0m8m3rUi(7_vRG6oI`CeM# z*Ce zfNrDM73@F^4PlCUy3-EVK-Reu?Js{9#Nb3MD3SmEUFClORA1CW=(G`@$_IJ4#XN?g z1P8+JED{8b*Z4xg&uK4%H^iY(HW-l(Qssl>E8)z72(uxAN`dcqNv0kczX)Ehf;P-y z6s2gAgl(c4?LbE|W>64l{KJd?UoW5m+PsUYYfg}@+!5?!c}T@|H{ zJfR;<^c#z zE%Alc;~fpN$H+dG(v;63rASKfk24%H6%}zLQy{52OUg@<1FYqxgdm3$>f#5ToMS@n zIFw=HM3nQ{<0+LnHlxAdA2>K9I?|zyQDpxhArR<5Hf!*Y7$m@(-vnnk#W_xLmeZW% z3;`UP00efn)1B{xXFTOOPkPD|32;C{J@vUye(v+0`Rr#v1Tk%wW)oWLxy(YRH|0hs#jGi zB}6JBD4Nu(ISkq=z=1u3sNo+kKnOOq$<2?p)ve!5=Q<5KSGuyZpmoKoK<}DYzUp(Y zeT8Qi#v+e9#M7Y=jp#<-x>%1Yma+ejC1*&xbrGW7o)9=?+*Oo!!MotWC9I}iltf#ikq&%x zqZGM4h-j6P+{NYBS{|m^ep~g0Hx?nl!5lDlfumyVAlO$5W^jy&M$&|6I4K-HpNN%v zU*}Si3YpyGrvy9_7E{H*DarriY-lWFCU+OZNwG0faGX9Jceu(q=CQNDkRe?3K*%U2 zG7Lpi8T4yL9co@vX4h>gHJIpIU*)BGX>xwn8QZ8yLzoKF1i7_J zqHQ`e53JC=#M9riSPQSW~y)nrmXh7edo7Zo_vaKY7rV z4D@uZd}S@q_seCa^jHn?3(RI!$3rfXsl(F6pU{SROYrlQ3*GDWBf2r=`(~sQo9S@7 zxEjGtg>(NBRZ_3Dcj8`@UVY*k@9z57^`4oBkKNQ|$8XvlcJ{VS>kzftLaX4;>Fmzk zOINQ)IlK`I6>xp;mq+>6jGi>W_gL_i{5-u%XayuH!c~iB_hbH1gKTyH0tabBBY40D zX@p|~V9z_|b&vm-zEi66lMKBr|4qwO_aKGBh@;}w4Qbmhmfoe~Ve4&DSra8l$*=_Vw@U?azeU zMe(+9Grt`JzwjGCO;G{{ss&j=J%npFh3hPJz=ZtUzY4sI-bot<$6av%nc778yjc%~Kl63AtU>=Y33 zt07F(#8-q3P82jx6dzC|zEPAkQCuHeAPX;e7FA3SN;H;{y9rJBhgTW_Rp5qu5C>HV zfr21|XIKYyXofH-2m#0hZpepn=!Akm18c|!Z-_94_%&GEKS3lrLYz26d>mXZ72w1U0rjG)#ghfp8Fog1`Z9=!bsThROo~R=|g8I0H1ehG!rMZrFr^XoLTM zKre$(s}698#ca&uOp&Ujw(h&Pl1#eETsr7%y5(9#JIDh^tjEm^v(%dlGlZpcC@#}< z4{BhBkB|UrfCVxrgJaMJ^kRj7kO6`igMZi}-tC;$N10BLZB(j*8;*gcf_7ohf9cG63(b_+ z032Xa9H<6ZfTj+Z257LRg1`iG5CDQW0C#u<09b>wB8V`6PXHi=Y$%9Wc*_5eRL&Yr z!y9F}91Xm!)XD(ulpdf36|w_5m;xd-%OjOLKczbeoe8*fz=u_+fg6B@ zbvOY4AOLHK1~C|eX=sLvtcOydflKH}#bnb^RR}jdIym(_Ic*tsWSmKh$9VVyJLm#; zDblV1)W=KGn}AC+cre6SgJ_t>XDEY$I00m62XkuzCsbE9jn*8T)(w*ySLeSWgT2qm8*Ea>(IL+Bs z^#j@&Qk11w2Q)%IG#4!hhFutdnLQYe{X~zo!XDkxL!2BxP^d&upgGu6pbgh`6WZ>) z*rCf<`A~pe2nHokT7zNQT6EetOjzNAS1n*5T5tk6u!EPpmy{i|m90dgH5Wt(21Gbp zgsEBZp+*0(#nNiq@k`wD(-bJ+1&1vH!P0{va2UMZG!z^qgMoshRe-=Pm$Wt9wGBn6 zUEB_I8zN{}V2A=LpaVOwf{3wPu;|xD`dUH@Tlp9Ovdsd|B^UqD^`OHgK+=uOktK#Z z(19ia1MJjV6AVVZ9mbXg+k^4j4dGox8(gcq*;38fQ;p0-s1;7CnmRy5*bUku^jhfc zEdIM)`Otx2_yr57Uh7?7t1R5#72R9hUTVFRcub-opq*HynAmMR=cP&XJqUMjg;vT7 zkc=-}NEjwX)LvKwb0$O}ZQ%Kqxt&#{e#0J{;PV;Dcn)2X4@WNVN+F zjtoKw21bxzV4>hgvS2LBUxPK!d9a0FasqtC0+-Ae(KlNI6-Ud29~i4xERZK#J>PyuKqASXxqy&HnScPk8T7;VxP3C-dxqArM|e(Mg{rnrXe#;)tbzU#gw@4Pba^A4ydNZl*| zf`2M#E>Lg7dML%FsPKmD$Hs5BlI)at24r<;u%?eh_}l76rtR}B;4%n}=4b$zfsan= z3>@j;l}rqFl^@{6;ys|1ew(WP(}l*Zp^<{4MF0a2ae_F5Ce~5~R*3N`FGUK@RS1WC zmWF+fa4MYe3tsBFq2~1y6{(gR4+oE{o<%h_1w%50BvCu!Qu3N`pb8>}rb5)5D0Pva?@R^`=zZifA z)&fkowt;X3SMUd87r!&%=6H%EwY1^{Nb z1cR`IWx(^HDTEjXcDySHPpD@oD|H(_^(-Fq1-Dj8g$cch3)&=*`6jTNS3x}iF(KZ zgUA7UD0q``U{umk`QfpZv#dx&{K5A%7~dB=eQK_)>=`QSeA`04_AS`~SY zcm`E4h*f~E=gxH!fngbLc?wL28vuYxzy<oFBN;cUV77319yzAUw4<3T|(+%U9pB!Q??1eO)`7M$m_TpyW*$bxDzU`%V0J zl$#!~%y>BSO%Vb;fK>yG9NxF1%BQx=FMvkqgih##4E=nQiQ-=_{xdWP6A%Lt1%NW3 z0oV8XR5!`kzZB|Ezw6%=$pr`@I)K0dqT?XKgbEijZ0PWy5h)A+P^@UNVgfh`E^_SX z@gvBP9W!neY4Rk>iYWe}Ncj;4w|dsB)!X*MCC;1_JN)aQ^C!@tLPN?5CTJ+qq)L}E zZR+$X)TjV>`jiTCcpaBU9EYD44Cvnm2Rq?D_LYs>pmID{Z>8 zRIH#)a`nphHCnx}XM>eZJM7ze^X4|}5yuV~vITFq^=p#wYLLj2t7JK}UJi?4+%c~> zxjOcc9)1M_k^MXP@Zt+ob+rM2tMuyAr~a39Jb>23=P$HPf4=?u3V*=e{qTw%bW9{o~I@w*f;CGA!LkNZ)diWuT7iy*&eDWEH-*6`qm*0s* z&=MDK4LKo)9b6>DqKbVL)8vVz_ll>)m2 zqs0HnDXWa@y8y5ggGDj0^RK0@6+D);HxG31e1N<&k1kn&RhJ!CFqHFs7LVkrcp7iU zaZ1lfJvG(Oh`e%Bi3EcP)?Ite*@fmvVv!{0&@3LbI)8<9!EBG!Ln89bV~Y}C`H%;2 zJsiz5rb=_<^k;x)>D;}!ehm~9!R&&-;f*`~)PjVQE5&$6O)sF*(fXP|-K0NV1iP(rV>Zl`4 zBUWjNcEFvl&A0S!x=x!Gx|nH*-e65JM~$9S4<_su(Z1RFg4yoU2+#P_j|=FT(tH2$ zI3W^DBK7OPe`qa_=-#uUSG{VDZ-Ak5NW$hZ3~q_#3u|f<0k5~I@?nH&;YpuX)|V1k zFarhch#woYK|lVP#0bIo#a~FM!ulDmFwfhZ00%fR8H!JWd+C88;sG=*jKvCer~?%q za=_V8kRlkQ%n{pzn4p*=3;_5b09-&F?6h!&91%b+f}sT~a?y8H%pd>(W-}V5s({rS zVnRlz8(I`$EJFBJ7p7-JI2DmW76eZcqoP5Sv;$^PBttqz*u{<%A{dMqBqF``MdyXF zW@K#LBWF09I{;%I@km7X#G)oW2th+xP9ofc)3h$4{N2VH9!NQREp>zL2yD3T(qcGx=<$S zL5fA zqy`h-^e)tv=;QCaU3&YGlF$EF08CFGGvFvbIAP!pE&D5(9kvH9LW&;b3!w zG#nB`Tik0)>Q;xde(EQ(q@<~X{-Ipue&Ql1I0p|X!d8&T02JKVM>F;cPSjddsNHET zc;nhKZE(UOoybOQv2)vC68B~~i$a;|$-}mM&kk5POK#a>+?pa6NdK@bW-r2rfAFKg z|L_Mt3Lug)T%#YbJZDjk65a`Kw<3+;2Qxa+31;l059zJWdJX^B-nR7<5DJ4wB39a# z9)Mv@KEUsY=d<4nPIg^5<;Vtbpko|V0~R<4Nf}aMj(Qm5!Qy;UW+<%W)re>ev6x9L z!~oI&j&!Oq2Hhu>&>vnjj4uG9Ll9vsR#2v}RsF3~jXNVv&wix3*Uhd5AR10|a^O%) zzVnsl?80`6G@g06GPOG8hf0>NjeM!Ejba06+RPY_Y2Mh4K{DNr_=6gmD1msndr=K> z2+y9T%!Mv1>JDt+0Uu^gh|jp_O^JyJiO^v&XX8LN4Q$NJ4CS024H~mDWz8Xh>v-gf z$R|bV)5g}yh2GbXWivY*pddgr`5e_4l62LW`cn4RnArc<00@ZEvi55ljpj4oDbno{ z_8<)vj2|4k-B7tuB*qbnT7^O!mFR>z$~#bL1D4uWwzb+=G)!%c3N|ycLma;i@Z#dy z%w^T}|CU%UbPrN%TyrcOB8UtG*r)@vFTCwUW%^?rE@Np>|{VcyYX7ajb>G36x;v+8OkAYD*O4Db(akh`qPUp)5ZyK z}1TLUYv%XtMHupx>64R5sh-xqjJ`CQ4_bg$Maq!B3i*HN;3+k_nP0f^|#3v z?%v@5qPN5-_|;8?7r?7tzpTHQ>(Q5ecH&$oNnPq2n)=iVw{`%*>pl8CGWOUTU%kkG zy7Eb!g#PHF<+phwxH47!nO}ctG6gkJHLUy)yH-B13c9|Ky4|C~WANW()x z!Wo=ea-^E{fF6AS!6Rr->6{LIY|=|nU;N2f|NTt>B2fw|(NMrv%+MABvKA4XP?e1765A>=hJ=fjL;cT~r|*5*VW2h1f$@K#>c;AXK~%$=zKY&W94jmn|%Tft(&~u;Et> z9&=D3QdnU}I2n{l*&tffEd4?)9U|{th&Qak6U9#?h!9AefijfCKkz|Cyuxz*12cpK zBsQHS79pH$LAJnyAxz>D-UcT=gePXq9`0Ko{>u6d5;>U@D?Z+ZYyy$6!x=mRI$%Ob zw1Ft}K`!nhGnjxnGR9Q|A*v0bh!Ou|mo(qP_`%lsUH&oSB#y;1t_CO$g(zOcs9jd6 zc?30C(+H>nH{63bs6wDn1Q|TTI;cZ4IFUubKs&61MKr=T;6paFK}b|%7fn<}WuxO= zhyZkgJNSb?+{3<{#5q#LD+{`Aj2EHfEsYaD*=E8q=PHWzzrOOIgC;QRKqf8Bt@73KWIV? zgn~Z&SpVRjT?y4Me1J)!9hN+R4U|Egp+rmqz$>f+I&i}(u;WMAr2FAyJkpSh=!WV1 znLIYcG7e>A!iG@>4pJ81G^YPVyv^Gi)Z4w~TSe#;Pkk0eG(tWc0NfEy4*WxG0RSn$ zf+V0N02qTZRKzr}0!WBt7txi3-Q~~mCPnRfOJkL zbylZ!UMF^Dr*>jz2*5!T00DT0r+AJhd6uVno+o;mClbH`5~Qblz9)Q&XBL1;JQ#v_ zu4jA3=X>I#7w9K^;-`NGsCzO&7F@t~N@oVZK?WQsgEpvxW@myf=z~rug<9tdC?!sC z+(v#}$WcUEvDrmb0y zmhM3%5yK#OX_q>X9`pg3rm32)DVw&bo4zTWN+~5^s7nl8%p6_PQN(6-)}&EH350_v zR0Ixq!?JCI3N(f|RA7u!gg!h%MO=c}Ttt%gB99u?2XKdX{3yl+>5y6kI#>dZIwy2i zD5;j}bav-=3aF~CDtH1YtG+6E(jzcz0eQMAtb*qf-fFF~r>?Flfg0$6MyRO{D}@Rx zu^uaSUg&0`#M)Ve+rgdOJy&#r=uS`rGn9k`Py;NGK^bt9?jQr(Eh+#s>Z3-gMdWA) z?C6peMW<d?0Kkk^ zgpKZ|p4}CaxvRU0qy~gR82m#fgnUiCe{BCZD1X$=tna;MAgntW`Z4^J_TEeEjGM>I+}oj(EvWILJiyiEUd#rkqvE{ z!9HXH4Sd2|!fd756{ms5i|B$9XwPa5F5&(z8iIxz2Hezsg%Z$bj6~3E99+VA?(;h1 z9ahl7LSy$rTEm_M1WF(PP~b7xI{7{($1nBghfmDco%XMn)Prm!vyFbnI73+n_7za!;lVD>J=9ViSi*dGqR#uU)V z_44o*`|$P}5e7TO)doe@R)iuNaU&+NQSqG5afU4@*A^J>6jP%CFYjkGug>%^Lij;% z>4Hy&6<@H}%jwn`$4MI7Q4nM1B;VXnyrL1$A{`f1*{v{Vpu#`g0{{T7;P&yNRB=vR zF}`N;8a}cP_`%QMLg^{;UZf6~MI8n2#Sd#n8w14~Qv^4bfj5GqIBp?@S)6Cw!#}W{ zDf_YV0-@w$u?&L=AY_#-7}{_VBch>PF0bCf`rpG039UvNtAnFc2cJ+F`ga)xrz z=tW~xMn9rGGcP{3vOYV6N0*Lci5XjXm3>{CE9=NfN8w8I@*0PtLMzHktB?u(!UAZ< z11MKbJF}YQbRh4v^Y%1DB!XiGwNRtQ5a3N?88ui7UO_iCQy_FIKebEWv{4N}7Hv^w zl)^u7URK-mGvjnLuktkOhgf4SS(o)$JWRx}+EFLOE>{Lz*KD1fHXSY;{_Rt=5b{DiwhF>FBTe>E{kBDQAvOv|1Sl7%_Vy`LH~R&5 zR}c5{wf0XZ!X^@znk@EmH#R~zcVtAiOZ>8Hc{e&ulpzX6CMXw+a`#-@cIP4R=S^aH z>m$HT=6bhwQNDIKgNJ-$NK~&7T@sa65WvN%0)Kb6e}DEyzth$kg51c$VW*z09o)bk zxJmN}bicQ3yD@D~cZM4kIsK+oM1pcX$VC zldF(-N%2!;_CFY=m8&^@JGG8?29Jw5ari-2(SnzMx%Yriq7^xNLxh5xIfJ)2oxiwI z`KDED!#{k~oZ~p8-8pCEIictB9rTthIIWOB1VG0D1ZDb(i&Bzj$CAUxnyZkHMg>p& z!=zt%rDu7yQScTh3@&*3r#r;MkhGo`jC)VviubmH#yVad`)phK zW?(v&?Q0fP67iZbFr_wF5%-u=?V%r6qNlmBGrCa)?^ERWKj{CCvoAW912{)p8x&{{ zFeEbe&QWsnbgAdsnd@P{^Wn&>x(XrLW-CPoD3^t|ySvXiymR=f6#=LS0~izR9EqU5 z1ADmh*SH5fw4YPn?k!Wqf^rqD!sAQF6T7r)2DJy;q7gxv5W@}MyJSjVKJUB3A-a+m zyUCmTxd#IiFGZ35LnV~_!V7WASH{Yl_=>>=JUFn-FT@xlT;*bXQsd#jTLpZlM5+hd z$&1te7TZ$bVmcH&(R+x%M=q`Z+g^yZJS3sEyG4uT0nF7r)t9-r=RCRZe8!D%Fc85~ zyn%ArK-ri3yE{^V7a<_Xjd_=}LfCSc(Y?R~yT5NdF7f}oQ6aNZC|8va{Q}EHnN=C^qY?e&lC7 zja_|G=6&pE99=~}l>bBqTTNE z_}2kvPoF=525osKSkYiQen$KEFN9F1PoYMYI+g!w)s8xOT16>yg;u8*;4rZ`mTXyw z636zCHILXGvu_nfoT$Tz96Mg%<|QjvZ(oBLHKttYRp?;CH)Ya1yx1gG#*ZQURItk^ zBA<{ojgKf=Qg-nH(9_f4UZ4~XFuKbhv=d*ZCh?aSV(L&oQ z>ab&vu)n66Z7whN=xER8rZDMgm%iGoPK%PoBmtmV$_>2;N$JK!A^JR`&fdpXyiK9H1EQxBFZSFNK$60N=R?L&e5HMdAY@BR`HJW($lqv zFYM66iJ;rAIK;R+s+%+87YqO05^UIEXPP#Mgx&S06tK4_%SM7^DO0BJKKjFv=Gwxr zFt3trD1e#AmLIfjuZ}8&pE!Q{h}W<4c0VukZj#<;BL*2np^qC3NqXK3ipYur9gmn{ zDSa^D18G!1pvVq6w3DBodJrgJKtWq1vI7?~S3b9CE-)^-pV9IsoX~kh9h4v-_#n6# z0vY8%8xg=NmU4y|?odDy{0Rk%W5I*Xr#0|!i>`!#B{29Pgd!Zz<(5>xjUX>FR3wZ{ zYR~~KHi#qza6~?A@WQO{a4~!f29E$h0HypxGh}olc6{g)APPr_=i<%nz;!M}De8$% zJjndwBSipM@iBzd%5?vh@{do9BnR%`$2y=V#y1|ubVX4@0;aJPQcRMQ%aPt0lu?d< z@PQ)&0EId3;fx@iWR9e%qqbI~g!I{BOSQU!9qN#)COQ$2>Jg+N7X!?yU{Q-5;9^G} z0E01%0v%x#QXD&Zk^xvR7>p3dQZx}wZGJ|2Z4gBtM#&LPtOE`_P=+@mz{@K*Lo?QU#5^b!W`KCP~r?$NOGH0L4;A#u@n~;l%bIEVK@OG0CS8A z03pDKBh)FrB(>9zd~qD)YL&z+1!08l%x8G^dBQRA^D`^#$TMC+(1t?A14S9fKlp)$ zneOy34<#i4T=4&oFmNOqsmQ3}ILb?j+~FPQ(PN^fkdTwMYO1#AZVZ7};;IE1#uE!OO5U7Xt0w$`<{&G3zPYhxVmIIzA|jI^LR z(++H7DX}0#fl$X_B})jpHi4)_DcXUH9+jP^@go#E)G%#z0jdnCYN5Uyo2&XKt1k<1 zyqdgZkGKFIO9=%47(h+zshQ3tk)8&^0H;iZL1mgy#~X5x40KX?d{%a1Je8m=fe-{} zP{ijwEw(umVwI)CIpTxW3RkR!5qPIT%V>Z@crC1}X*KVoW1bKt`nGT6#G3++xo z%;W!Y;-craAYHp$V`$8tQ>p%b9IYU4^9@VU2X!~%G#ZMU*#H=}O9>;BT1G~+$3*0Kb%>x-l(D5)|z*0 zVb}EOtS%c(@Gz&Q*ZBLj3NI}>Qae`wp-7|#OfpTQFhb)SpSiU>uBW7aZ3|5`#LE5R z!Fp1xr+lpyx}@dP?lw8GKVo-~9jX z0n+s%QZSH|B5+@k-SyIP6u!JtF~8K=y{EmUxPkyFnPE}zRdxmgp3omJUu%eAHoTi< zcZpgQx=i|XeMWs(+_@Od*kU3MVeED3YxH$cp_uqWU7^`sm~K^2nb4EjRyspf-G` zOAL@v$geCAu%8t0Nc`?~?oXR=U>%l%9ST4)oDeRo zAZ<>hPnb|wR?s&%4`W_%Gte(~s1WO{@QrYw9+n~bt`6nq4yywkuhvhH)bs!jz|(iqz3{nFN9Gy#*re3k=#TvRY-CDO!0v+TyEZhg>;85iP(l5?Y;iOP&7!cExv6CJlk(j|MDsb%Vaht4B zA7_UjxnwPXA<+=#ASnWEKBzCsF+)T$?>w=1(vdNYF({DnxH@SBsv(gu$|~yRUM^Cb zGI9|059Ao-4&q@RK+1gRqb?{16ALo)G|{S7(tapyAsG&99@32>A(5m3=e)uTgCVVU zl9PH8seqDChyY4xVc^u`VS2|GnWQPfEG6?IAxYyUCukjoLKFY~!Kg++6}aIZ#6cCB zVk5}l8P-7^njyl_KpD)T9V{z-LSnE`N_TgYPM)s3n6*Hu0|^r-BT=0UL}82aw?nUO)}F;TSeT1Jc12 zX5a>n!5l<_6GFiZULX_t;SDyz4ERA4Y9JK!0S8V(7KKCr7-%V4q4@}d_2}<2-zYR= ztyUf}1XE5tI_nBj<0RwLHOmh+2Z=TbgD!u_E`LG;xM2;T!Kgf<5%S>x0DuhcCI|ij z21a5TTwx=OK^Zt=8V0H|tMY+fzy|*z9k}o@D(NW9(~bYo)A4F$Y;uw5+>#=c4kc5R zOXRa5*yXCtv|u0(2xQ0Ub7C1JdCW9zX(8K^qLzBcg$O06-il3IIR>8z@YR zWa2`*rvO?Zk>q4ECc_mwG(=-)M1^iFm&6ZTqZ`{(Hv(|(Skxd}6g6U$Zf4ZXY!fOR zAsf;uM?0bf!a)=`0tdXIANpY%RAxZ)VSoTY9~^TdF5w)m>(r#wb;3YFHk1ZDBMYFw zUb28odB{tDvQ^6RAM1`j)$#<>lqpGwXrxj`Pc`&v6fw?$2R6b^H=+Zmff-mr0;mBN z$e;|4K^xqSBh;WCB7q|el_L`MNjo4)d58d9A(8(~VHG{YIc&l8F!g~nH3-2JMOtGR zIOtQ?bRiHWHOY}a)#F7OqD?zPKjmmuZGsPQiXZmHANU~$H$WPkA)PjY63(IU0N?@Y z;U)n94cvisI6_G|qDi;YGXLcOzM<=ojb13j52h7@s?`jy6+_lD61i13+Jn);wOj8_ zTXqWD$;JkH=)K z4rO~HM`IQnUcdy{HV0_{A6B6TZU7e6A+G;^RTS9P1V&&w_aPH#;1ja*U>ntH+#r!w z0Xq<&QxflKp_XXt(kHF8P{dRo$P`6mqY^2HiF$);+p<(SCn~WcCW9hJP3_dUW(}gD zFrOj*Ug6ZBfg>7$8}dOLD065BcV$E%8xqOYvO^2RZdn-Db)t47r&c_E07|sXRZ_AS z#e;Lj5oE{0T*p>ylgDf!ggdcg5)$bdHXuI)fc54qcnfEED~Kc2gESk(V=GS%1TGk% zcXQvjBBU1&$u=M3R0eO?Uq(Q8|G^*NKtP`F7cNkIuZDbs$b7>?2|6TqG7&X+CYR#F zdEr8W4`O~pk$UmOdLIOPm*WJs*IxexL`QgzfCyp-&I2}Nh$AEONt$rF@zNVY)i$WEI5g_>#4n)5;lgu$sMI0ZWkhJ87lyB3Q_ zmYl6aba4co590+A>K~**9_vH^JZ*&K8E<5{C$4cZve6<`n1v}>6TR;)sN|PhIGD#- zi$Pf(jky$&c}PN_CUMH4HAM%Ec%mtKrOTFkF5-}G|mqer+n54m0>Q34v ziFrR$njLNWMy_%xB=lI!SXybi0jChBi8n;n;zXY}4z(?lKem%wQ>y`(kWx!7qA=%aZUd$=aJon*~eS*FsmZy@Rc#!q_Ho zUIxIdKBcl{uBr79vrkyF^WqN1)U%szW8qV@uh_6Z*Q8T>sgp5U#9$O20A!vo7=D1Z z|BkUo8Ml{Mx8I@%_U$Zv``;D~{DhlSi93r?yPT0*CP`RiXaS9-`gj#t^J7f>rxXqg?<@p2bWs%!krQcgLjTd=2`5~ylE`VAE3A?KWI&2Xe zbW}S#SevJqmIMC|oT(E$J;P(xh#{Nndm-qUEhW6a-Iv9O@w8p;xCLCE6E_&b_ruqk zx}i-Y^;$fLAbl9PyBk8J^q_q=(Z#KJyayV<3p&H$NXIddO#~Rnp9#wAjmI-vJhBxe z!5NBzfOmRX4kx^)E8M6r9N1=jqIEdN93eIqyhmNU zOZ~sgyUG7q{h+NJ11*3u7FX6wS<>sF9K0bG0@WmPoiKJCR_0-all&mAAZ@gE*b8vb z>jTF3PR47xvWdbXp*`AZeI(kT5qN+Nq#+!-*CXsoi||UXc8}~yT0rt>*8xHwyNIaJHG8P z4CMdUowm)Gy`BC#I8Fo9;Yu&v&L0`iA0k$I!D<_P3MMBHz}nkLy-f8D0S#8b44eTSEPW)h-7B_Tf#-pzJJt!Xq{z!>zX_1>(S7*T9mpm> z3_Be2GhfGzp&aso9E{-w>KwjPW22kbO0a}|MacCtR>>`#$h=CY9q`sNBQNr*o*tvpC9QX2>W?Z$_Lo`J%gUD&z>2A_{HN0!e0rK zf6P0&%+K2S0Rn))fdmU0Jcux1LKOc{D0~PpqQr?3JN)ZFF{8$f96Nga2r?q0V2u9+ zggl8drOK5oTduT-(Pc!2D`cv?0EdZ=ojiN`{Moa}uz7}n8a;Y6$QL_wtRQ^~HLBE| zK;QtGiZ$!hs#mpoJ!(V>gNO;>B(RyX>{+xO89HPOHzLfqbnDt>3F23_qh-@?ELBF0=q7}3u@drYpgrz`X6Jv~#uZvA@H&}7XP zA9%XAYJ|)r-3YTRoQCfZg|mMTAAp5j!34#>j~}>uyTrdAzs#6p+I3-v9asNYr5$z% zCOBPo41y(AcWZqY-fiPORKh=Jf^ZtCV@Avv%-|PBbzu*7xn$O4maler`=RAm&v8-Q8!<1}uVh~hk z%$YSJ$68tVcL7MEe#OA+$%gOuAG^nATP(D-R4IyRGKvppIO8uKl8&!QW-%%cDW+ zu1^NHk_2$hQdK?IWB2yP)$vbmyWM22bvAi=G<{paYlrvIkc?lnig0bpvD<6`QA_-2 zJr!({^{Dq_mzA_DW!*QeZ|Qpr8k?8f6C}o$^h^Afnf!B>uS@Q{3>Es3yv$o-%sj6( zb~{$U`J3_mMKAt}vkfWyL+Q*#VzM9f+s4$IWvfxjsp$gXa=7I4(htOqcJb^552cR2 zw;Lc6OucBghRCaK9cF~XvoN%LZ#Z^74zrzyvW&VbA5VQEmR70Dd)uT_GZ?7$Q*BbE zW+9zhY)7_ZR5}4qex4?OP`>vZllY;fr?+0=aZ*eKFBSz9^t-Ph5(TM=gYi1 zM!I01W4SIY0>I^|k$7{1LH4KIV!+r{=+LJS`c}mPfqBfUg})ijQ!p zC3+K#k3}<;r02VyszF>4#raD5H9GM$IcqO(g^PG765W2963BWiOj1r9FY(n*oBixs z4vLC8>Sg&5-{!QcL0WNK6Ea%#p^94g%(&2dQ6>SD8HvOU2SU?Cmq%J(eIx&fw}|EO zou5G}0v1PUZj5qF@+w;JVVdjndjl+WsMrNw2!$IK%n*bvH;b{$%rNB%Dt}b!o~D{x z9AWkTBvq>cidVP~?cKT(F2(r%u!vct_@KX`hY})g=ZANxtGVQBCvdxH(iZ4xR9NWT z@}J1NZ2+QGLb`e}IsNlLSh-aTb~VJ!P?c-`V!7TBy{sNahnu|-0T zzPqbW+S4f{e#onROI7clO{n;@YF+osi6@>J`Ec_OAOMW%dudwrg%K@ znHU>m(GhX&T}h}`hij$iV0pUWe8SLem#X6J9R%Lc@MJ6MdAq>84OzV5XIDhR`!rPq zRASiq^F%!!o-asT!QWn{TK17|RdC=hxyBORC$aE`NsljYzx#9D7hL!{Bl(v1S|QyQ z#RF@exAq>3q{}DDbH9__D^6aP`%jmxNLRgab>soB-f96E2tEI7RqOGHBsOumL-+p2 z#h~$fk!O<;4t4$W5%AMb zh|~FcbhG(aXtwHW^&_jXLAsmsiq7CCJGvRdtwN~8louNx->25EBF=9l#SYkXEbVQ4 zvGXU?2jWHj8`JboRAMUV@2OrBGa#jKKO3RgcX{vq-5MV1yU}zT)Y12 ze>{1FW;3IeqK8tB@82zwuQxLVG4lpwS(k8R+GPqd6CxUW4KqF)AWprC$qh1>ScO$` zeXno%#HtPQWVU2Ezh>?o+Q+TKel{i2cah18c4*z-kC^nn$-qpf9fWH#e)(tqG3)&p zafeB5{OR{%4pCJ~wx1!)-P%ph(EWK6Ybqc4MPxmbgM1W7_~zOvynl>+IfFVkL0GH4 zvaz<~S6?~LF*0rJ`g*GEF-Gl(OY3RSn{|fXbNbZvfI@~*fu5W%lzG*C>;3Oj*S^Zx z+?%m$3l`_@ix;?(ymjCFr1Q{MzQ5}Xz=zi9k{YQI0$dl}Mus@yDT2j~uB4mXH%S-( zJQ{$4aKZ?kHUK3orXKI7J24Hjg$Y>0L6adUIcmFAD z0|@L89DzdSVPPOs%6?(ww>ENeCqLa}W;kcigWka4x1PXPDHhBV565>eaYR5HpgDsc zroa7E>}`4I({O$NsXtU$M{)oeLMR8_LLr$k@DDhE8bdy35`x9xDZx3Af1nB!JXIK( zjfQzKg!vUyp)e*5Tg-~R20@(+E!rqgESLy|j6MxgAPvtW4)1sy+*u!NMi*@Xp(pgW zQMHA?5<_w$;km*{u_f5$C}KVv1RA6C;C{nQ&v&2haECn3(u9I*yH z6DGUYMrgJJQRrZrNC4Cl$tPh%=O_t-2@+0*52hk}O4ImIuaSo48S}&+Dmp0jI~?Ld z?md19aiI+W*ndjkW_XZ^j&NcWlF$Pe0|2GH5tY!$8Xjb=SnThx1er4=Wj4JkDy29_ zWg?p#BoD0Pd=--t4Z9LaZX-y7kWWgYkl{%`l)~rlMt7g2_IA?|D&h*l|EY-694Gn) zz!>F_DJF1p7vKOF~aFpP;E zBS$h$fs03`7)TlRnWfF9=30ig620dg3oi?Y38C)Xz`Xxoy>X5p014UvD1@FNZbJb} zEFx77`~eeK?}3l)Or=s3zCHrYuAxaGbpqi{AYdJG0(f#9#&s8m5WxV~Y;))%au`c< znEP{BOLJ7MNs|mxI{*-i7m)!#qMrTF;;z6>t`K>iNI$U#K&pYtyC0D!UYf_Rns@JW zo-BF3#9W@dYW{6<5(7sfHp3i7fRr&iUyHmzr$0x1C;zc+fqq&JKRTRaEZo{LA+8=W zX5u>{i~&{qp31>vd6Cg=u(NE~@68V+rPLsdk{owYv`aQ5E}Mc62{TN%|A@>HRUD{V z9Bf-08c`fxS{(YBbd@U?hlWP-l_aQ^B-xfEN0g+NmZbNWWbTxFATQ0~E6r0aPQ(_V zK==&j=}`BGBD^?NPih9JIs;M4N3ELkETXJ24SnNYB>rT}7zF4M=F*k{ z;!Q2eOnr}nTI`%kVwXxv@)0VX{ko*v=Ti!I6f{WgId7yie-oAS4H}sND(xmb)#Ea% zC+SprYE;kEF#G)iKTB(gO=})wl%nLIK`6JE=hW&H%5mb>#II=#Uo$zJ*E;V~JMufS z57fN~tY;!3v5=&0)UFSb%l2-fYMrSDA{&^}8$#!$Jk{J@G<`y8*PEJgTcpj0*7Oim zn@HN|olfGbrsyx(P;Er@u}q^*(kE+xI(y#h(|kQB(shv8yQR##mp>(54H}$HAEsR| zZPHwG-gL95nKq>O9L z@eaGgwyeG{14bRM%s-Qzx4)$L5~R&-{<@x3N`dSGnQ`6-%b=5rqP{tpN!9$tV^@G< z6j>V3`KY{8ZLm{guTzV%OXpUXu6ox~yDt5xE}e3cU~Om^8v1;&ix<;nrrvE~*KHNm zZByP&$>BTxzGI`QwVuDz`4-z11-r+u0?+au@4+6Qy&gZxUjJLYf$F`%cD}L=DiZ*Sx zIqz6J9OM%jx-{xD6dMeBHt5nclsP{nc`>B=Y4ES^&`q7;jqihgPQ$6pLy?3zTLkFv z*2t0i$ZxxmKT#uR??(9L$oR8I@RXxOu+fXX5s>{TDeEY4^eDy9=@r7#G=zoSKLfn^~{&CnbyOZ7OL4`joBpo+2nmy5+wPeBjU#> znYk{gioi3qQ9?P93yL0vrvLy*7&aycxkGr1av+l&A^gISeiYnB9NCAZtQPoR^|W?N^pponNWo=V zhh>J!Wq^PZ!&k0nk*(vPLT%tTDCDiJ0AcG7K18bswq=?Z%k){xyZ)>Hz`JmO%Q}Fk zIKX@%K!_nw=*N<(%&LaNs?)-}7;@_+5XJ;S4d47n@2y-4_nqz^B?tRcRs+CoxrwN7xN@a09tQ%Ol8uf=)WCrJ zY#7*-a&QSxA9b*W5!}8nxBcFsFs0S!BpU)*4snD6&ZqQ+g2-65?S!nVBnPC_(vI~h zoo#Q(N4C&LPx=Np@HuOzOa^Hx2fu;&0UCo`I#$1LgF8ZZay54ferz?y>@;fvt%Ar= z!TlW#WEqYURK4#yvmXKf$vQ~3gaQLd$R;kvHf0+m0dh}e?hwEb%>kr<@IC;LPYWXr`5*uW2d>8X=^P5&9S;9KPy_Oo5a&yX^ii2*M@mi{Ff&bw+k)eL_h}S42K`QXB;^!YFZ-SB6IxyoIFcv$^<;zT1BKDc0=r2y7Y7G1j z1}1vRyu!Lr?*!@BhCdYovQ6NBmMG5!++&2{F&Hog1CK)?%^dMCvp&iJ+yMs?ypBLl zT?d3MC;>neugJ1izl}oQ!*faHKO0+l7{!Q?VA|v%&3BE1$26YAvVXJ~WD5y%Qc9Hr zGOjAbpXIVM14GZGYY(eJl(OXmosXf9xq$c^I;B#*vL{q zJ+U0h@1;_y+tMAF;8&|In5Q2@8L#SyMscQ{;V*uJxS39@$7}e;N=e%4uftt4+2*9f z+<%(&#s$_p)pd8JyA*Q0ncCu6!FlJ={f=7{$}`8ik>;(YY9#X~U#XU! zCmB?4blJ~mj5ivL6|>%0%9sz^F+0sJbaV9JIl3o&=7!&!t&43s#(ujO!J(pSWN|3p zq6}32UhS#+@JJiTos=)xyFs0YgbecWc~u! zs?JDF^=e)U;~*U+CPd9Liw;lP&m4CD#CU#<=G4bLwok;v(9WWbzpAOP#8=f?M3*dK z)?Qq9igj`gT!btPJ)x=3eh~MI6Akv|^S+a*J<^i9uhtVEdT+Tqm*Hj}x+^z$@+qJ;08{?I{gc(lNWb9=e!)94HQAg#rzt-!#OzYp1k$$*-X; zGlTUE0SB?7#E5!nm2Yx=v;}D%l50g3fhIbIKcY-dNlAT$0@i7Pamt44_L}05%-2Y% zQx46xI3l$0@S~rmo6k>gMuld*J6%P;N}jRr&v{{iZbC03PPAo3^s}J0Cp3hyvy@#!Ed@B%cS zZLs)shg(1*ox9J{-ZgtB4sPas$U5KsxOj#7*-roAB2dEmVWumF7l&d~1hcQ<#?$6* zO79pTyysS5Tz1@V4K3$j+STs4(~rXda4hetXX!uFJCYZrh0c zJUdkGRKU^K|LgS4E2po_0cQB%o!39il>8r{t^y$lasT^komJzR2dEOG1-`b!FR?jG zEK*|7eVIapjg;cGZ-BweCozK-=v+x zS9<9MVr+Wzi3r@)KMHZfW<>VI6Lf6wYFIfRX>Sl$8QQ|mj8!**S-|s=y5-}9^fmKv z%{G`B>X(VZ95s>b4d7`aCuDFQ{n1ey_6*oFtM*_8G~>ErIn)eDzb0h;nl93W=%#$- zvJ{E-?51)3%6PLagAB9*eW#cU$!#=f`=?`5^p4Qr$CazmgjF5&g&NeUPsrD13zN!Zh*bNAJjv(ewt1xC^*FKcNddowjhgY_$0^-U3hxxy zXxMw{W^6nul3cgZ^7*Tq4S8DpfZJ9l+UrR^;iy>6!d5r)?~`Jsr=_|Dwofa(o|aoa zEi+oT)o=Ox6dUri+>HCR!H|URX2#Qs*Z(9yOEa~;Z*kn{oif_@(r?~)S_OpdzPS9W z-v*f~BA)5If8ZajBtY>C%8*tlx4b0+Q+AHgH%JX%tm};y+`L4NKh;2h4|lks0eKf(l0=8#m%-{pNufOqQcM0@sc+hq*8oCp|Ox`6k#gyd%WjW^P4{dN4udgeEq_C!zujID8w(D2*MvC?+?#d3cl6Qj;IU^qIj_U==xeU zfa#O~kcG-v28h3?Q(W{r^DhnnI|kd!gFVD(XY02BJS5)y9b`wE9#-P_*kgSt(at=O zKC>GxsSC+`5twEZ$`oWD`LR4Xqv$IZJe26M7k{7%aq{(8M`Z?8jKG?+dXL2Jp*)`{ zLcJG7nvh+d%6e(7V)PV9oe7Z{ZI2SkEMShR>y$132DLY@8q1Rik+||VV4?Ut5G>Qn zIa(BBeatcbvCyreY%bhs#&Ei6qs~}J9zrkoiZy)KtvcGrt}-i^<#b8u=94fxYh|NC zqW@x*{sI5*R_O)7D!n@Yi$6cUxVZQ~xzc}wO7VYo|J^DjK&8j{U%xJojtExi)zQX( zSfvE0^zXsJ<^IaQDWwMo2YY*a7aN;b8~wZ6+gn>(|Ai}ET3T9MTs;5&{l||V=aUoo z*_8jzE&b1EDSj;dzd=iTkB5f|Zt2;-+|sk|Zh}>M+|_kD(0}2Y{o7OY zw=?Og$N9X?_pGUj0F|D7EIn_2bJ6(XqE6$gUg8pamtdX}tkPfY?IR;2|HhT}_4W1i z^mKJ~wYL+r(to(p#>Pg1Rr>Mc$Li{8f>nwy;U)N_S7oeMCA3#X@T)@7s{+t@nd@aa z_kM}*X-@7*M#gzU{8c*YS3)AeC+$cMz6cDw^wItm96}&UFYN8FETwgwv`eVX~6O)%OU;Z*QI(s62q^WhLCVr&&@UNW6m6-6Bn8cOHtt(!RP2t;HeEfJ0#-Ci= zYwR3X%nWPHtpE6=*Ql@H6z2c3O$k1!uCA_+qT+uLrK+l`Dk>`fp_IzW$^E~TQht7Z zUS8h+0+q6{vHfSIl!2a}j*jlywQK(;RC+~5c122ZMGU?I{iBp#0e}F3DgAe-l#Gbz z|DRQ=sBQW1|I;dM%%ubc3!C+4Jo;Gpf3r$S1}=>HYfHWrY5#XtsR7mkQ))a=Uorp5 zakW2F?bE^VHGF?<_Qb1##TK8-O5$73xR*P45S%h49wL3+G0Gsl&mEQP11Wc2{}^oi zxS7LyRiF(hw{QCAYkZ(f@w$tiDl_d7+&4Vgp2*Q{_%YP<>E~iw;HM$`c^9YETC1|w z%;%o_8-v%@=rmhC|K6SXXm$h6diHB;;j^QfTcb?hTl7b*N7t5oX?p+4&L zXm@es3xUf9AUsQGVmd;X1N25Q%Gb^5<_oJ$dpc7~npb)`!3**!IU(cW^)J+OGP(cV zDlIHtiQv4)lV(S%h+2&jow8ny7TYM!i(+o5ZjX_JG_DfeF}6;Pd&`l!7D9b{);#pH zPw^;eu7LIWf3iwVIyP6VYst_GaO=X7jWoOZ?TvKD!V)l}M5oPW=G$D9oVx1xB{kFRm4I7^m0!i0U9ah9>Ika&eb;)Sy8;;%gH3O}N^dIe)H>qf}I zGq6SSw|^>rlw)s;8XbaeXJC3B_zNV?m{Ist&RWsHO2$+_?Vrq(iNKP-?fJiU8xnEy z!AwKr@UX;1St2&EITf;lgjyZJ=ltKJ?jO{Dcc>Uov|6f&Hn zc~(a`qnV&KkKvLfK>?qBL_aq}NDNvpJ<=_v>HH%fax`(S`30=y(Jm!h;@C$iS$Xk` z=MF2HXjEC~@_0fY;RBHQ05HCr8Ca$D_^pqF3^o}b)kP#5;$k^L1t1NkJLUmeFv#5i z1owS(&G4>R9#-pyz>@zzOsFYWo;RGQ_kfbRIYShA6A`q8i=u8%N5S>&%(5W&tpy4h z<=`mF9H_EN2X(+GK%T=4Jcr!rACf~AXDgG36i^bzStJ)cNpdMf6ht zU1(=ivZMtckx8ImJ`o`*bzP9u8E`TO0mWiU(;>6>Z6MsKjFDU+$Eo-P`A#rB<|1{D zEvem(={P%M*3w8@B$_U4$y-3QK+gJ}CP4g^Im*MI@!m2dP^^P30qcMBL|+BS@TY;< zD9X$MfabeZ$aUlhHCe!jqTsJWdB!%O6_GG>h*kXSGA@Ns)hA6niG-ChCFv{q#;^#N zXI{GKo6R|~PPBofq|2S+Gu7nNNus3vgwNl4Co=y;6UMz$%KR z2 z@q@!6AxPWY2R$0k$n*;5Wd4M?x%GOdzJ2T6vw8IIsZR=IfS`xh$nMTs#FTlZN6%~I z<`l_i$GA#&?q>^uWKVdWgpo=;A6+EB&6JL6J+uU+R(=0C8Uj7it*TzZ?BLR7TQ;!UH>`Y|UocbP|_krH>g~>cf6IkjJ$+=(g@WHvF zv${>`x^R*BuqWI#mosyFN&=~^5{R1GBGzJ%&Z28-xGD0shxnF{<*oRXZ*2}4Mc%p6 z2cC#`E1VzBMvG)lh}wK`3GA29+(5r(BrsXnUjA`VQJKDPzQ5UZ&i8SoM{Phv3;Yds zdPrY*Zd`QJpEz1Ex7-s01;9fIWs8fC1XEEwYL?3)W6myW?DF zWvP6$!zx6g_>1MI?$~Zo@~E>_6oSy=eC0$Q_A7k}|6o;d8v68phf|DeEhigMcDUWz zICF}&*e4ru2VL73!5BHy`B7QWCGfz3iOI~hs%Zl@6O6WXMc$!rHj{BCy zwkm<{V>g!r%UU4X4o%WAA?U@zN1R zn9q$A8m>`OZ=9p^P3zlYLDTYq4^0Cf`Ue)r`{xJy-donX0|{y>0wEM0k^&d9$6vQagCF0>YwrICJp|d@}9!!7x@~p0KQj z+fwh`?l9|Z0 zUK)o{$Xyd~b~Zu+0Ez(kYdOdm07FqnycG+tvi9AyqCsMf%aJy^V(#l=7|A$zB97?q zD3k!Z;T<8uV^L?tv6T1ysZx>pC?^#FV{Pq8JR2wG1jJwv5;#xLA?&9)5`knVJM5WY3Ro(=Z#zakn zL=Cb;c(zp?E>Zg|UN1FC`7B-l7g|*p!p8WXxE;LLhS+I)9E(8^i@oTC$!|TAJyMgs8k676Ci|WxqZv~I#8ZL{QbIga!ctTG8KII%(1^1X%vnm}Qj#X* z{VU%0a5=C!K)#s`wrPBCA0E%w7q3&2R4ATM;F(sMnpRqpR6d)gcb0}dORVuE^ylhx z3a8&UNdKIgC^eg8bDESao*~>$Su7V1n8YJ&Vy`s@4mAeN_Zk(f6V1ChsNaY|t7OdC zAcwHz&^{>02@JzGW|&iFE+&PWoMfC9XMs&gN=QhE=`acnnP17sZIE)=O9;EAm_=ml zs9fyYnZ+o5BsE#&tTo_OPtoa?`O5&wgQVOtK}=)lrm7>4XG2PsU}q-qLF|Vv5Atm} zL>E$xC?X4-7Tx9+oA8iEWQpQX+vcz_4oU_3kxg!i1KBy+Pnzb?&*g!L;?9e6dHb{Y zC1`w2{F%*iM?+uc;3&T*TgosMkP_w7GUn?U7CehUa%nr%C+BZ?X0gVD4-Wy7I9R?g z<%S$AsV!WaufXAN-k@iJfnm0*VG&6?32TUt$WExnG8u_K;uIh^(B8HqW_*u=443j98HY|O+li_SzIwB7EqMU?Hj7$1ooN`lY@*(p_OD5X$ zKJ&eA-YJf?EuXZl5T*jha8ndVWP)`5@ef6D&|@65fv#k#9;hU+v@T1z!k@8H197rt#ZHE`iUY-MOf@2o*q@I6_g+ig zigXn`CnU3LjnrzM>{e2FBVTAcRH8m=q;@Dp>@XH#KOhhkdG+{9E_N zD8@^-VR>YP1$huqm9Vq%fs}F!(hV z_LUH-Lc>cP!4krhYbH!W$l^P4kP$f;=n!-)OfK$7cCnNL#V>!Znh&Wqs=mYDWMP!8 zha#o!2~{wvdYD5rkA;NYL-PHmR;A*W!Xf6Spyya2hb2TI75R)XvLl-^eC5;XdH8x$ z(Z{AH%hydLa-=aN2FSs>7Jk|?IdVYz3rL4-lMs$_gl8=Q)Y{~;IBFpbBGD0GM^O%- zkR!sXfH2uErfutUTgyxvrC005d0V}Ao#gL8`f|T_ku))mu(g%;>o}M+7gBQcpA6KT zqar8{vQA(u0hr;(|H)Vyh#`5&*mL5(N({E?q_>(IeR6nSM}#9GJ*Q~W>x@coSJQ>d zqL9A_h{iFLr5r@#SaJ(T$X7J%hcjp%k0M`Nr5wcGd_md$>N)aFAFXvpH@1neFVOx| zvLT4D#G}^4G~Xao4J82!lkmk#V$sWeMzJiJ_hUDmPfqh9Zr5NFg!bXTMA5`f+GV7`)&D zQVal}I+BZLgWI#=1vQYXQL?*okp3mukKC4AH26KPMNDdBytFTaa=T0`EbCi_$-r&42Eo9Dnd^WcBSx_w(@wc$7I~1B-ltB86^DqU}3PF9Xb^=N7GI z_d_S0Bj-kKuyR6Sqq`sFUC9E?r$?u)-rn4)ir!K!w zY!bPnNY@L;J@GACaWIwyfdyBq`53G3snOrnYFaZZu#2$F&&kVFGs`S7goBwn7p$>j`Hwl30_5H{DFJZ-v)iH*N6GY?K{tIKnNQV~h(I zR`h<*mEng--b9mV3~wk8SNp%1n($ee(b(>*U~CqEiqCKPTy6Pyuf)YHCA`>vuQ@IY zrym$1SuozRS=}rm+RAzHDiB`i>bng(pgX@s>W#*JFka(|>A~HfuWq&Zcpzt{xl!&r zl~vtpyhMJuL~e0qKPI?edBup8*}HhUSDLmL;R79nFJEji-QeKw|Bnklw3R#*8>Gjw~IcH?b<)q!XGr+)8A$X*Wz*^Bm14Y`&oyFhE)$mafsRP?VFD9 z8G!r;K4yi z*;5k8_FfGgWokVsT7ub}N=vAA=binL_B>M(KO5Cb7?-^iF}R$Hz4S+{D&pnJr{A1S zeMuT&zY6QJ89T8fft=AI;%=CtkS;3jE~n;;<+_!X-#aO!$PdDF0FZlgF#~C zn(_HIM;pBvk`GUg$*8SIBSh9lot6cEPzOE;cXs{jYNna`xZ+--%HfV)rE!Zd3A0{# zpYG0hh8#apTa>1`Ve|IMV9sE%8O>B(B=XIV0PnNE3rwik4E~UnE(z#Nx3h@ zY^p_4=JYJ-Yb+N>PYmhH!;`Iw*qZZvrYh;M;XD6WrRLa%KWpbPtxyt5#~LE}8hDe; zN_znS+^ofRAg_6p%LgGvMIK($H+L!`O{bx%p$JSHD`JxDemalb}qN;4Wh zvmFH69#c{FNP1Rgel0>zMC03CLz|+ZuxZ6dzbEfnkbR%Zdun76W)R!SIz6kAQ*h7N zZTiv<<(#u~QsQ0|k=*Tdx0E{4>}!jDukYp1#K<*!3xZWjR(CRBS7+St$uH;KOzs=w z^-rd{0<8_5{^HUNX0c!m4;>}t5NsJ=PFN4CIsXkth3KbTr)C6zS$OTGh|=Aa_>IXh zD_|ptlR7UFRHIFGkKn{Y znV$sneo3-M(`=o1+9^k#Kw7#(zUfAaUCW>0J)4kf`^LVqD0{2dm8S2~=h3f+(%{&%1jQOxx?jDmbWxuhAwc&|^q;jk>90Cm54-;?5fas9d*AnKA zh)G+D1|eX{&$<^|?li{*TBy7uVuiWUFg!b!h-q;K?bSM+O-0#;zUhjYy#cMhRwL|a zYrCuf5oX}Gv!e z3s9ynS$dBxkPcP{(>`QDMUszEC=z~BljN7M9>qm>hfAX!y!$EFk>LHMS47Ve*;{^W z-4nd72;OcZX6VZgdhtD%$V$U5Hf7x8 z@kb?bp$(1|D8dyjo{g*ARX-7omG-t!GJlE|9~={|*@CkfmGlVM@^N%9D9dzmL@`3K z>gX*J{>P1jmF4mFO>5ko2$DzQgLr=^;Z%^CpRtSTx05`lIflY3hhjnGTZW=j;R@}k z3gky8;F^-hzp_mJOhNa3b@NT!u*HpM#{q~<;;kLJSxse4-862IewO3kaE6J5^p;-) z9IX!}a~zOG)U{O!G1LyEuFbpYxyf>eUL%%`FZait+&HD|$QKQ$JR!FcrCEdV7t*3! zdYA`nmB$ocx5o>~B}@Eo^rQ5SK}g|;w#wsY65bm}Mfc~)h<8w=?9W63;L_IjeZoHp zGd-ecNeKqxCG?_h{eE})-BPd0jV8mlUAV4+^O1PzQ-7!5>M#>t>fX=O;Qr%07h`@6 z`2Zrx-W+n(_MwX`uaDXFR>gQq1w|q9cK!aW?yAR6$~x$ps4~3dv#`Ad&#m}!x@$J8 zDIyd&XtWKc*gDHkY;6rm$_x@bmf+4a$Ol4=1|dmPDOP-F0WbgHDY`#(zl}CuCNakg z_U2Gbe9L%shhm~4K%hW{$&4{_U~Uz3t1*S-R?M0s>DN7wZ&RjV`aAyqJ4B`#bTbYX zO=|MBe??og%ZA-P3-{qWD_g1eEQ~AWCpqKB6Auga-Wm7KPl+^K7x#K7B}dV7u3+D? zEiMp`LzA%Hkq+bSydu5GUXNX2@uLFV}iLY z{D5`)nGyr#b+o!2C;RFWK1hB-F8ZD8*E`P|1>-yWBD3C}7O?+dWDy(%1l?x`UP4?_ zx}+>`hn|591zpl6n>TKM@EouUamo0$XDOcSc~9?Ydf*+sh0Mfu=BboJc*t@HW4S5w zSDrA)Xifz4mI=e!XgF`}VF*3OA4cLyB&`$|sD@h|r|c6Be7>y3AA4j9_4jP3%S%bmAMB(COSL$SzcULbb-`s(r>(`=YRa^ zc5nUd^X5jIKiN6NqYY2e`qLNhy+o=k)<%)#=<`M%?n^i{&2CeYPJT1XY(T;b0Q*5t zR#-@8+r*`o0kXvF%#%}{_iiu4-sE2=Ch=6NB@zyI<60vk1gzwSee&VhiGsb>UltrL zmN$;uwv?5<#*kO%_#U;>?w>csf8t&pxrSa#p6ePggr_uIqF69Ww_UFj z*_7u}S}{QGO$6X0{ARLI=BGWMNMD|QUYrxp8?4n>bMB;1azn=}%w7@7TVG6xB5LwRlF&CL{R5`vh(D|9dqQuZT- z5ItuEY{sAFyT1*A<^ceB7{sa<9oRXYNzj1z%_7?fDBt~Bw!idWH z^OXqyPAr&(Anj?B(h?%c*&$X8;M-v#7Hy(lND>w-v6f_;re}acL>c$RK!vY94O~+YC`I) z9h}S`#{IhH=ADkr2k}J6%Ff%JPZT<1wL4YzJ}VJ-@1%E{=6AfRmEyyI=g}mnwoarg z=Y%fjkz|ba9V&&bV8xlP2k+XNPam4qN|+KW=hO5!4N95sNuW+aJBK7ZTmDwWUo~p6 zniqwf>eLJjMMrbp)w4l1CZsOHA#eD@pkgGhCZVRn{*7BoO{YpOl+v!Qy@mYBE*UEL zf-;bJ7%7{GgvUfDm12{KIr6n=obOJR4=u9=hL{x!Ha~^Hc*1mn(7SC9thH78A_XF? zd&7bx!X_RSl&Lsg^yP7aWVOll#3W*9+s6VpY(?R5b{JVKPr_O{^=YUmfJP7qJRT^^ zY3P&MTj_&Q8GDbM*ZQiZK4-Hi)$aKV%)}YW1>_BO=06ww{EEd$J)UYS_(k#UlIKiJ zr=)bx1N{J^z|#=*u<&3OifYjTHthiwJ9TA6wVOQm+mQfi}T^M~eYhvqwnzE2D-G!G%rf%qE?0ZX*Q z%Ur`NqQk3-!)v0N!f3Ft_V8xV@YWN}4Oh+W+Tq=Inme7E%PhodT$(q+0w|V-4x2S* z5;cA)jvPN3nH3%R?K<*jP~*tXe@KzHNj=`x=+mfOnl29VOKfQ3`Ou|~lqxz9baxc| zaFqDzD2c@=#BG!`codp6N>(sRUN=h7HA*=-3WgESV}l>gj3Td%QE`t^+iR<4Yvt?= za&0%hcqVe0!Ke!jr56rsV;KzKQJ?B$pSJTq2^wMd(OM)P-sc*>&I;NW9p_5YN-A%QhIC!7Bs2T9jRy%_j%Qha2d2>Rdr)|BR{G{CSO2O zgCJ=c-)<>DC0W&^GZi#~J0d1P1!Ba76i@Jtv~BLtg?7oZ)p+sP#EGf1JS^I?N6D4JQ6U%Azwdb zv)hN-N2|Q)l5uR&MQeP9g_FuU1~_Zz$v;(1csw0KP%W_`K5`JeQt`ds6n)4eU^xQx zZb-kAmcrLf#jijnZb8OhTH@ALtYHJF=#IWV-{gp=L5f9xP#f_(9I4A`5W`?(qy=Vg zWoB(mKL#*}5S_IbnDZ4djVEMHAA` zV_}g~8fx7dMjOW8dyOSf(6pBruwb#oU{~qqYY#A6p+TZh0#w<3_{WW(MtK}CXwO{tQF0Kdv z=#f@)yqx%o2^7Fe?75W=s!I>wC6J;2sFQGlIw=gX1(qHN&@|`QfNrFNyC3^$M6lI!c6i{D&<9e~ld4bUn3%x}j==&p5$N$09U4}LJ$B!N#Y>d&P8%B4BbazM# z(j@{CLupWn(MW@oNH<6~(nvRmGtK}%5^4T_w=vbN!VhNL;g2)Kw?tqiMbwEc0h<&9+@?F=?cTSBot zO^F@T<8Y$kjD&Da8S&)V^IGfRE)e>k0VQuSVQ2OXQppscwADjRnhpdsf#b-elixdV$=9n{xjg%ZHFIWV@~^JFNA9 zj6efdr$l?s$af0hVE#ylvqBS!qGRH zNYH^s#I6G72zKfE*0_JIk7aU(Z3l5NQHanL%yZu`35Pk`iaCE&b1wd{##=}54B0C) zvlV5%ziwsL@eu7;hX}6&Ifm@HXfEvib-q3TnKa{?`$lI_EPYHk%Ji`Kri*!0fW?ip zuVdMx>$e%o`r$ni8s3ZH&FSi**^8xfbe#nF^a4ZYRx~}YtE}ax1-o{ohh^v2Uq$ow zyb?m=KV750+B!_x#(F>kk)h$p&_Ib-E)`47)`>45u29Y>cwJO}#;?qhUxo9(u!n!` zJs$6ibx5Cv$29@D>bh#hO=31S5}m#iJaBN7@j(=tNt~Ww}r2A>Pa8QcKd<}E+NGkHg4pe`RH1jy&?pSbjyr1 zwv8Fip!h8N`=So4qY>((00h8*ucqleox7%|Fqsj%{b@{15_^DbW{u22*6~&u|9kTG`<))CT<|Lw5VWPZhEN zH6-Y%8REw1%(-vKnsbd(Ac2$$_y7cm^oG)!zK)zZPpYyFQ z(1z)~*CnBMVWRgL0K^%Tix#wv;!30dN|zXX!#9Bxq&WGS==^0&Y+df|t#zms(4|cT(hdP`^1&>6%6O5$)bLlUadg1OrHuER*V}R`YYbkf1&b(`f+*{l=pspOI zghW^$%yeew#u_`Ij^QS(9ODT*+&$Ga;|XbbSNX>%{L@pAzFCyB;0tH7sCGPOI_!|> zsP%x4w-#zY{FAU)qoty9HV=6MwYGfPZmwPmQFSe7SAK~%zD3MvMr8lq%jx-n;r}rGm8S52D<;d7mV`n{b<*~`1ezp z922sC%yEJ=ErcsE3J%Q5d#42%yP{-NWcS>u1|fq&~OV z@k%dCR-!|E-@i5Lt>pV)sn080x8CGJyX*USx^>t_As`JwtiT!2)--(kz2(jqsY~?^ zxksa-H{Nz%zYe3IKfZiED#H-hkE0oU47Yo6vLB}gfH)t{DZTG;U2o~Ve8B0Xhl6tvHdA{9BE#kQ7FW-3`uCUth&NmPy-yZZa2 za(`OCOl{C?IH$Rqz?4h7@02IUtuQ@XRr>F>HC{*HRqx5)Cuhk1D4rATD&CnZ_!20uqg{@H6UNEV>ev*uQi@B0}#!B z{!C|&)g1Dd1znK#n$qXkdOdAq79}H8`Fd6Z}CZ7_bw0`-G+}Zkl zvB`^B?qa}Mp7Qa6!lvnq{Q1pyV2VstffjsQmPFb6+Z{s)OnGw#6FPxtbv;ENa?^;Eml@-a~ zeMLewDt3!>AYcu;lFH8?;HIeQ6(Ao+k~9tOXj3p_Y+?ERptnSCgIGzg4N<)hU{dsHUm`AsX$xmkW2{lQRPa82-L*H~Afjvp@A*UF zkOs|)km}5)*fTG4YHW_H1=?4}+{)|z7xtm-J=La6-LMO>A1`)(>ayafZtG4F8$8lZ zE0FRut+73J(aoy;7D^%Y9;wID@asYIXP$qZZnvJjL|iFl>Fi94X66d!e|P#`qSA$L z_EmDLd{!@oWm`H}7bWq}81l=1l;@hJLVmXTK)~nObZPy>j zQSraLsp9X`{k~=Z8ZT3ZE@riVL&bAh2S>$)vbA*H#1UJyCkaLo|2IJjToqE z)Z&S`N8=E-b)%fw=X}6ok6luamWay~2ntg|R_#og`qKeI__`i)lI8KT9Pjgb@4oB} zacS_m#HL1c61JrGR?yA>$wSjZFUf}_1g<`j#e_cY>ltOLzohx*wljEE#(+riH9G1r zMFLll1OC6)7C3+AWg)SN(UW&bZ{AzHA0LW2q|5`|Ych>N6^9+P>nxgivS}3?gWlo4=m(>PV!%EWu zoY$z(%*nmrdbTz$R)6>H%c$^2d@ogjTjZqI3Ma|dErNFK3DeNkCKRPs@ zBF+jZYnM4S{tn=W!-|O~007pe*(C9hLW^rqFL#PpSXN}nXN9J6c`TNhkkh7U{B7k3 z8XuCCAEyNdY0e9r+_`Q?SaH;1jvAE0nAVr}AcO8B_%Vhy0Nv{a_=lSE8R{Xb`>E6p z_fY|{l6@{qd|9lA;nLeoahzGKZ-0rzSST9mmI{&!pu79xHl?#kVSk9sWRE>th+`25 zds+bJfCRtrQc&dp-Ksv5J;gZ5d)T#coI$M^hNuw%F32@ zwKvks)EYrKps!tR4{aUsnu90=fLqNxA6K)PgJ7y_?LK`g5WK^)c{lgut8EC7>Zoe-@uKzX z&7|l1zptWm+qNNBK82(Qe>VYtKH?a(^#-u;Zk+g<_EUTnjO^Cl!hh2?uv-GhvqWW4 z1RuuPv_76FO4ZR)=C=*`1t@aH8sO_U^>U_~MC1RfkBsnV{*1~8(S`BuGLg2AsL2VZ zq*m{;iL{SCeJ7k&#QT#=I)JzucE+4m9X$pL8?*i=oH@X|CzKj6ng%^Lvlnm7UO$fD zbW#-nY;8-D?hoTiMzK-YTM5~jcCK9s=F8@8TnV?$M79XLBdR%27Vw|_EgQ!3+8zR& zzk%2w2}|}@oz;83_dy9S5h(m418x6-V!7r3#rVDQd|h`pZ3g4FzbM*f+Lv53l?C(b z`8A3aS$x$ra39XWarx;ouIsE8Klh%o_A)b^Eo*Am!my<^3fKyLY78BY!C7>MZo72S zK7|oah52p?71~sAeQtA(%xKBn7*#7wcHGFjyVH)W1cG+*{#0WYpC-RT(704hQ;m2L zi{1K@lbA(HUTzT>LsOQY(5Ji<3OGZ*97v!%9?)(f#b#D{D9JB;3a)~X@vYRO0)O)CK8c-ps`?UtWDml_x}DpFxvS5HJ(5z#0CZ_}-L_Bx(d za?OrN?|57K=i$*i8;vKvmY+37*ad7DpDw3QUWa)#XyUzc(!PIIqRfZ-_g4M8!(0r@ z&8=OUTX^?Twd>W*EYOzphs1!?+!^GJZCHxL_rs@t8~J15DtOqsoH{K=3(eZO*&h4! zYwsHaiv8rclgLt8X#!ws&M^>aq0~nj--P#4p)_^M^f)dE@iVUv;+DIA z3?e>uX`uWt;9>Ot&Z1;jcJCE_u0=Q4Jf*#X8mkvr5&D$`|2CNTt!uDnvM}e8Yj|uZ za6Tu1MS4}B_UyP`(64uGQ) zh`WddKso++`R1l%2w|oo<>QP~x3%86@$oDJqZu}z42F(Qj4J_32QUX3av40+HO6>m ze6AQFS&%AKpDNvF1a86Jp;KYm1!Br%@SOL`hfFCVlms=Da4-QKFcs1KFx4(wjflzR z85sT4=P$i^3hOpbZFv|QV z0TP!hoD66t5>v@cN%G(aiz2AKAd^Z_kGF-zV!|H2fU=)HuycSU@b_az_Nuu0B=`m?k z;RL2$^ro+4R9l1b5>C>i06r_4qTvyLu5S#)$1Uo0m-WoOcXI2b*!dO&tpxeCpDGvjA7 zmHhEXqVY%J3ZfFqU{(-&(m*W?ARX;M7=ps*s2(6(NE4(3Dk+51b|BFiqd!Ro7PX~n zU2JO$jKs4=$)J3z4ovH>AmYJLI)6o9P=x%Hl>+XbE#V8RI*6nB0RF@RP7)p=a)4_$ zgb)-iRjsY$&q{Nw%#IADVU7v_0qeyNa`r80#6m}OVo@C=!YQcBd&-bA$ zB1}trV=G|H$({_4aWGwX31KazT{rkrW1>uTp^Rx`zfuvavz@kUboE;atwhXx#KwWL zR!zf7e9&}=N44KyT-0_32M%&uxVMBr`Stra9&qcT~g)xZg7~ZYhr?< zUcA^(0vk_%$3+#v~am*x^fl15=1&HGRgeflEmzTD}O)dpwZt-PFRyUY+|oko(E zH}%{O=Nn|9UuGg)W+BXk*tOuO9C%*-XmI3BrbR(VmIlH~eytAGIm+n(#Y!Pct+`V% z*~(}l4h!;*>aEK=mOZXA(D(SVk?_1a*Q$)N$m{&V{(Wr4(9{J?VsJzg-=rH2Jv;$Y z>QtF(5Bl5A_%ON|Uy90!y~2#c_y(C6KvR)L)!fbfNd+6=!fpF6DHStx+6`x)bw%-z z@jMJeTxSG4XA;K)6jg@HFhavAmnrJpQEE8)cr-pN|FnwW>X+L?Re>W<3W*L0C;k9F z7)o|n%YFR%!BrXb3;inZvABxGsyc2m+kFd63y%fED?WztqM~_kdf915x%*Y|NCv}Z z74mcuuSEN*n*^)hX7dadR@up=`*mctUk!UI49G_VXP@y*a$}8-70+F)B?AgVhbKQqtoJ@Mu>>pOgJw}aeMS|hDv}q><)F&^CPf{|gJsCzr`hYX_ZpkF{ z>tJ53W%qz()UgfHeM76dvzN)<0F8sYwOv+kQPfnKlT;7ytxRp`AQ4Z=A{RRN+qt=x z<|=-MoZ1Ni@;F01GY90877lTt+y5fA=SqHJx)GgWxM+gy;+^}qZPv|QCy!3{Tu-kq z_@3O=#6>W8KmcXDzF-4=;dIxf?f2t7p7~6x;k@>F#1~`lM2*Y4HkAj!$IXhES zL$Fpof%~tJ^iz3szmk zG+YSwUsx@iiCDnt9qQ0UG~W1R>yY2_#!3R%=Tx*gceUgq^6F#4TBK`*%sFSY+Ne6l z_6r`PH{&xGCXb=&hgj?n0}{9APb{VcHdO^Xy(9&&p`x?{`ufCfPD5!vz#HE2 zKch2mj6Wy{Tyj~%$1blL1)@ayK8Q3Bcst=QOP^r`E~&sUv83Zf_X@F9)I~%Gnp9Tt zRMi*DH&jI)287{Fmk*6rpi5F(;y=Tungc52<%t5dqL20rAcKMnN)$5dd{;cVkw2q((VH+)los zPW(z*z;`s?H}0Gsdt8<1M!C29dT;RBa^m`-VTw~dQk2cEmhjU>;gz%erTGmXMb#={ zqbj;dgb?<7<0-c7)4UvWY0Dd$IvDnskW6R7!*`(0(^LSC2bp*O?N>&-w-&ZnJtX;{ zyp?qmu+w~W@`39M^=lZCs+& zQo--%lCMnH0L{3cc5z0s)~%tm-8&ny$oZzoA~Rrb7IO&}0bC0&1=S{B^n|anb-UhA z*ICh0@;7li=wzV}_}y>OunouO$@_U*bt_TN_#yD^fP8s$5@VYvM^y4EbIQOV39l9} zor_PaiojHnvxu0B^wo#&+PXIBSjbV;vRxyHg1EDHW?Xy3xNp|LT~;SzRs7bq070xD z^PIyqcm6gP+war-_^0oU88?`g@jd8?vH0I*oZm47Y9m2$-w+_ImaJ(Bg{OfL z(@mfDC1QWJXH0JyW@41JiI+#+XIg+_zwel)s-XW$Qg_I2HE5&g+N;L7s#pC#S;OB~ zSuk6P3QSZPAVNNt0R?WPeq>5mfTR~`aBap-f?1>$N8K-JP=Sq4+&=vI_D(y9-ZvyK zZqjgOUVb61HHV<>OGMir*FOAZ0p7Ug8bV^7)4$Xn;oRpa(~Dt z^?m(&pD*uMFkVveagad)JU~vb$@!-0Rco$Du#5DAi?U4D>9Fd~z3M}V($>g7Cnb~=5oL-Kka9P2D zXF@7HRYN_Uhjl6|{4?aEQ7T1@1*Urb=HEKf$EA6Pf2qdhDL)*`m-jE+K(yP*l$^t) zdi#jzl%MFoP!4`;j(9A@#H(y=tCS{y)&*+t1k=&Vmaw2?6L{WsL`9Tu>E|c!L*^YdT;|IR%AR#+`@CATMTU6E=J+1+o@`TBexPYNp0nItNN&jSKVRtn zFzrP06VrJ=hs)xf+^4{+@!6V}-!~)!c-oC&X%8iq@j%uAAY>18{?96n*YC&Ss@CskLQ?hj6G$E_LY{9I zs74bq4eAdtR3<4WaBH~D4&jLeqr8;a3Y~jPFo{&4OmsdvkZ%}o{Nuy13AaP(-z~Tl zsmD)Q%#HTij#N=9K~`QCL-QsK$N7NsdVtr$)X~6TI^rY+V5>1&g#Y2zh)ufAYLMi= zG8(2UQBtl<$iID@swD9koTNr;v2CEOOe6;H&HH!03&VDX0n^@$>=+iX^G%ADJYV^x z5S4r}YrJ5fX`&G>GqL7~AEV;oIwti=bJcWXC+;Bk>2R;+rB`WO}hSyLjEE?xev_ZH~hG86cDu-Q(vC$*f~r*pk!?X~;p zue|rm#9P~mic`MUQ6Ia$+rD@!)&`Y2p`%FPK26$*P5rB~tQYZ|xn2E}U!++LLP4_# zi$UQ$>Vp>_q2wxWAk*;Y_j|JnhZPl5uN@;liDvC(8x2$9t$||RKvWNsisEX9PNlYJ zK7F{hYu(H4&w%d7eDBmB#>vMz%MfYCvFK!as@itMBVdGLu6he)D@)``+qta#-wb zz9COG$@kO!)$06r-pZlYy_bD*omlNJNOJEEE52#?@-_ckA6k73?x(cdDQ4cwYJQ&_ z^d!pk@b>T0OZkAgk6*02v(@HoiMT92+MphZIyS6V##?2-VU3ZWmt&D^?;<2ew(!&; z`GD|NaiyR5ue4o1zkNq0G%%F-9#Mg?0SP8q><&?o9wTwe_IoTb&O+&>KIhy*iTsb5 zo+_M$(e33&Lt5&T1RRa-4PPtXL%gDYuOc_}%@{C24y?Pqa|)*)Ddkv`W4{>LEt!od z^n$-m$}1u z=c_tYGa7HfTa<$`BTls9WeVO=E}~%k!7P?H_~B9?cU)`=v=s`mMug>0vjR` z5ZlD=I#tYgYF&>KL-i`h7cqofEU+17hPr5@`lhgUD=<7)5-N=dePclYc>{8Iin<;rbIXttpW_6&oxYQ zrJ%1+guqa-dHy=gHxt@i@3R;Frd`T$JaXtVrHuePTyO)ojdV=zjk8M6a|f$n2W@G6 zpWBTp$O14Vv;9+JpbC_Xdu%eTW-ayadxTAsv6^vRI9-eF z`Vq?T#&o#`;%A461Oz>CL`HB>PYIDY${4UPoIrRZJFRibin|X31Xw>x7hpb3*L}*F zLm8I8`DlOD@rA(NZISvJX81(!us48IJuEz3g%~X&*Q;^I=i&WF^xY@pwt+Noy(^e8Gs+uhIg~=$IkShOJ6962==HtemKn6aWS;KR|Sw zy5)7EuNuQ2w23iVb%${M8`z7gjR{~y99c+VZRa&SUjM8a0*pqx!3TxxYddbfRAO(t zm8!)s-#OvfKPr32?NXarnE~iR;Jr|a2Xv7QIAW%5dA_gor2`hluTwax>4Y7SjQYyo z@H-Fxxy$X?iqgjnjndh67XqcbPxADtdNe{G734z~C)uN`aDcxqgchLZXILyRiWMaN znd)SBuYPZ=!EBy@maW}|!KM%O6h;PlECqw$1H%xb8|K9+5Ah~!7WWgZ%U9=+oOr}B zf*>Nu2E_P8d923KE-`&sUQAJ3%|6k-hiyi??n%`-AJyCNobOm<2HDt=GnTYjgO6h8 zGzRgX5j=G@ z#Ct9|Hf{BJrT_QOGRHm%1(V2rkU5SNhv@Xl_MeFl^AqQAtQ?QGCWOQ?Hrl9<`t#%$ z-dd%WKMy@(*#8md|KDk0h5tJ(3@(gxND60I^jA@&DIf^8RMv!7NO5e?uh>6wd2?%o%^@Y+(UYh-&@+w#&bD!`qLlJ>h2SZe;LC512h;beS&L(;bLwM zRKQt)l(83(9zUE8dwY;$Mi8iTIY1z~6~+Gg4Cn1}?*-|8F#z^2F>r)RwrB#6MB%-| z?0m#!-S?~TBz-)=u@T7gcFVZsJl^o>jgQ{yHz%_WN5@LQ7CVAmCIx)7*vOPP2DA4^ zG6s*sl9oXqutE$A{+}1+8W^_6j5GONGvOF0Ie|xZx5vFgv@q~-Zm1xqGPVVy+Ytf}{!P)q zj4a@g!jPx2O?0w@kLY(#%<#>eIlit~@x=(W1kH^^fnS}05An?@ruYr>>E7AGKn6O+ zOw_McFpKTT$B_7u7__YUu%!?*-3UW5C&M_sIA&By^`Z%sP8hrTK;Di-fPxy~Dzdm= zWOmHt1nepK05@yalaMlS;>7N0()Gm*>fbcBg+1}VP{y-!#)nYGuW(>~D77mgfU|&Z zY#hBArvqjtSS}zz&n@F@GY*Xw%t*(c#rLlf+Pj^r}8f zTwU^_*oRKt{w~<9kM@RRpAfQ%+hV)D#x7-|YD)wb_E8Jx!vsU=+VC-!6-gFD==u9# zh%G7zCXJ{d)6yhdKcAzJ=`7C?Ln1;;qJd?amA!~BPVG3^*5!+3@xOk}H_OQsVv`g* z$wburf{{raHFn^q`TRXlY}DBn*=q&tFhzO~duqi3em!K&j4h)u2DXgd-v+@L6(n_F zp-BrXZlEHitu2q(IExh~>+0#FZ9$GD0^;Eeo;76qm8624Qnxmgy_{iNZxD<;vz#fx z0*4Xg6`W;m;e+kTXNIUDXz-MYv991kJc*`E9k6o3$f{^0QMkd|SS{GdCTfIg;XXjx z`DuV43%rExFWJVErGt>7eyn2dzbPsbBKQ;2aj7riV{J^|_ zY`#m7=pp)RUb^oO>=|kOAnDD0-TcHKZ%7DfU_TXIi1Fzt1vfx0^+@tLv()>DxUf@t zx(~{>;2xSXQSwQ7l*L6Um@Ks`MG#cCb-Ayt5P{u*#S>&F!0KJh>CMKQW*Y3AGf}HL zSIgQCR&gNEm^`GvspA_(zX0R-qozdmHOV3`pVGfT_~m7xt1+7g*$eiQOT$Fv3&+)t z6ZLsRm6$ZK4^4cB^}P~x@F~Ere|A(FH5M5n{iS4im7;95qWabl$gV)Vl*;NUkzV&3 zk>qNMMpgx^Cb981fec7s^Qrw>Bjs1GrzI6n4Yr@kHz`ro(4!T&co-r2u-On#d%##D z$X$h~S*N5#!Rl0@jGdr*m$APfkAF{*#n`YY#!#={u+Liwq3~}dNm)TeLWNLYGkqtv zxl~82Q_GkgrRQA;CD+tb2WAv-@Y=bOgcvz4Jk!H56;m>uXRk6p!{Px!o{keXk*Wht zq!QB)Q?7b4Ofs`g1P#fi&8{4@@;RD9`_lF_i;OK=P2}pad2ix^l8|xle3V0!J3#2J zj}IT-mDSdj&U0Q}MKF1wJv#)O_&|5@p*glqjHSy*+N5$NmV4D8s zo`y*pT+W%5UC|YH-+-mrL6*W66(#rK*mr4WQvyBAtNlW~*)IG8pV1W`K@*(!nlX38 zhryf0M?6N3f<-Aqp0RiZ-bc<;tlZwKPT3-FDz5Zz9)`bYwc}HkC+1YOM|_PzPP5=+ zYs`bHT5=8WjR+R!rC0xoSW@z+!84zBre31ATGE_*=FawPoioD{WD71;7v}ooah_ql z2Oo4WPhntuAui7@Z4C)N}%Zl{q>7UW0RmtFX;>xvrq>v(|5Jk%njmf^dP)7 z#SGr!N-7O+^;S328Sm6VObVF=SIYcM+qb2~^E`%9~Yi>B^8-K4iYjyqDN}1gn{jG$6W(#{6K=T!2 z17GRw+kRfE_GJ3!T*cdzWPO}uOgu-nDU6b-Vgad=?WwYNsmYjpnZ70%KVXmoN~cf^ ztvh=KTl$s47$#-mgXIJlNs&sk4_;YfNkurzaIxM@!a<3TuUI}rNPdjDi~rGUUgq9z6&t(GF5 zl^QXwir7zckz>yJrV5-Zz$NX^;lRv27f^11`Mu;)8k1DfkA}{&^Y0>d?non%e;eFgbCC?Kp+Fe5dS|w?P zBC1rwOpJqyRIralvTggqlqG_Q*^NFa#^QGancp-ht%%Im7O3X~SNNswzk}NB8M0rC ziSIiHy59aMdVgO*wH0^UR89%W6mqM;@eA*64PXDkx7X~_*pZmUSEcM!g`(XqveMwL zB~U8OcjNc}J`w0PpY>kP#D!Wav8Sq%s}&lE(Z5TRZf2I=ai5KO?@7P=rWrFl`TonI zSOIxL-Og~`>}ARC7NFWeB5jW4K{nHIwz5oFge|D1gw{fv1`zl5S z0wDS=cwf`zoICY4a$wuir+Yaq)t$z5tIxhPQ`SB2QQfPr;_3?E{DN}iQjSJ8T_cLW zOZV+K_F)(H8IZQVk?z-g(eIv~r-(VA8PP-B-^0TCuLDOp9vOKGqX?C%P&J7nUuo>Q z@n64h!U~aXNFTn@9QYeEz*xTW4g+_1*yzMoK0LQOJ-hJ@ygP)enb#9`Wg6 zl+RC2o!6{C5_hbWaEkn0d+^9?U{oTVQ?hAKgaq-N<)q2OaEWD*94mubV7u2yu9)da z%;Na@%*bNL*NW_kR7$Xa0p-l^>Gr{4B24tsYkmW=t68b#ea5Un`iOLn|5X=E+>U0s z4~=4i>9XfiZz{#!&KIl|gS&mhhM*w>ZXmjjyQOaTpw{OyH7FL@#B@axZy0{k7Oh)L zD=}>-qYu94y6fxi3g1s&Ng+9oeP(CBAUbbNN0(-|i04$Xo3OX7f4rIdWa+?hzw#L| zPtZSKu|@=rRK57ptxNYdmVS$&>r(`u21AiKREf21dfi1v>*)E$N5lpm=C>PI#@Sm! zsOx5@m0a^)8CV-@DCmu>PWkD(zOut zX=jmQLh&CXu|&;=~KQ`Kju?=>z=bN5rbOJ=boPySA;YqlxbTsD5H)j*k+!iaVg z^OxhVnthiiyESItb|mMfq1gznpc|sH8`)nsem`+fwGaN)-2TcvVnj_f=SA^tMtMG_ zWf|QQI9zU0y6f1ezJ5~OzImlhx7ZVW_d|1?`s0$`twAT@cxX+Ui$xU ztCWn#uvl0&aN1J3_2_cv{f3Q z&!LyE630!Jjb8XK(#esMMeq4Xl^Iu=cgKponpf&Jb9uxSuU@WqtYOz>YT`ACBz)0v zLhLwBFX?SR^d|yqZ=^NYX80KIc6YNEias&TepWL-7@NavvLYeeUv9)^@im^h3eURR z((xa@RFiZ5OX@_qkqkjCE*sH6A+q1=41GZ+s~Hlv*C%TTf|p`%J78x>5TgJae}?eI z&xuj?qlohM%fp4Zj15iM=F?b{qmlYIB}85R5&9P!47W1(UyuIYtHr;)Kl?dcWn-X;W-#BW`H4&~Cip{xckFkmn`o_#7)UA$l&CT!wdpiR|rwPEsy_=YK3 z`jZ&U=r%pt-lz8RLOquMtH!g?A7W`tYBXL3Ad0VpEaU2Xiy2Ho3gEk?NMRpmljt(8 z_TA{DzUBEC{ioC`4BfrVfOK;Y&9wM=rZy{L%L!F=a#>#V%x5$2Y)Z09#_nDY#n2Cu z6cZsXn!Et10J@K0&BK@Zjwboq0_dSZ&O&Pj4VFOT-2wy3rUksc|gl$3RW-p$<4{@t&8+umOhpkgUSkZBt$ZA+f>WC zsCzokH7EEZJ>T404|`TFFvJT35Z>vp#|zow*ZMtVkFv?2x^#LnVPu+Ly2yMid1u(( z9-EC!d~ka{8k2W?(Zhd>Z98wM4Hoed?qn?;fNtv4PX*(2b1lD)wIZI?VWOvAanXL& z&|_5AWgq7`O#ANXAiqu2+Csk+{`x_*rUP&D%v5blCRgk!rpL7_N+_~gh zfKnEcCg%%pXRGitP1av}~gKvkd znrw6MPu1QQv9!+B=JmnoF4sXR*#HkP{{&_;eE?blg zT`pm}a|bH$QBYG6f9l`YLeUk?+8E2gmG{eL{TyL?ehO{n~N4N@)>8#FAEY;u?Vg;$$Vq z5=gsBzxnA)P&ZO_q1dIlt4O^ujuhWTZkfB&DPLoSD5fizFW5OhDnxrM=%q-tD z-j<>chyOqH5j25Cbj}lhtkU zg;KhXYdL&W=emJt2S0=9;g-ET<7pa<$x-H~gGroIGjH~-Iu}}#GjbbXKnf0FgAKt> z0 z^g+4Yv3Vv&^(&^PEBF>qw4Gx~bF|2+-g0YGciDaDIklzo$n2wO5yB632GFA_+d>H= z6$$g;A#{B+p)5xRIHCEWjM*c79GCUL2zX0VktP7Ysh8Xus?;QC`{grTa-!w|fc#KU zQE7}O3lG#U9Sr19$pApi+E`xp*kX~zj;_ABUy376U@%cn|1N9dEn0&g2X3hczkFzh zeHg*U1n5U{oFf_0i?M8TTYyl65-oZ@M;J^(U|fEaex06xrGgi2amh?vxTuua%1U4a zK>&90d6fXwR3!OCsrkzN3?Sk-to>?=un-;u2i*uR57`74#;GpCVv*pLM4A16JL@p} zaP-bP=KtGS=dg|t0yjjyM*slG-a!R)P&ZsA1Q`DmHTE=dB3CxrSG5s(!bk#e;gk$v zjH4RiPB`CO62``SHZwwh){Cu36-M4P^Lh&27c0wpIqv-_H8VTrz7T<1#2z#Gz2P;fcQ>2(YpnE97q7G38lL5{`@Pd&b0W?jJ01rvE^_P6r zHn4M!_ngX}NY^%ONFd=n{#Eb}-S4*H96(fTQ1C9RK>Mg7|LfGM;GY~slH=O^k(`#W zEm02t9+cIe++V@_fF8-|_k`Zzn_XBzSlYO#v2$SP;B%8XjbVLO*awreE&PGrNc3pm zNvNgt>gwrr>+eZtLW%qJxe7p1gpQ*ES^P0)>`fPz;qNd+(As}v!KVo~UBBM`4*uP_ ziK_KeU9cm3Zv36!LkQ25l^Gfb=-Oc!(2C-NdVRe{z3!?aS-M6uy5! zj6y~oqPB?M(E$LoAz+bMKB!h&H~`ZNAWMe~;8OgYd45@Y%U=IVv{?;+F)@1R`)u^|nBX5TddqpcEAUCwA7WUTP?W`esAf^4ivXMdVtK^Ied7cz~QMK7GqB%-TJzcvAM)>K|YxHJhI~a14QBO=$3VX{ZEH#Sd%5f2fao`6hmV3Nh0ZzpzY| zLG_^!OLI4qx!a6l{oupuLEK98hu4tAuT%*Z%yCDV5f3TjDNMy@0#%|!IAhHW%OHx!Em2O__iy111h;*u&9ldAqEO#ods z{Sj3!k)T{b&JRGPX~EJL4ALH0Qq|hiotx6kB@@55C4o2-`u)<)gaBMI2?m0gqkb6> zhYwGwGhSCD`EX@0Yi8V1rF*)NKLC%v z41^{*JuEFvl0LG6JU&L=CMy%&L@m%%k-}kP%qO#p%C4x$t{Tm*In4folT*)?)2Nx# z?2^+Olha<2(>a>ceVEgOlUsjBoqd;?AD|K2o|)I4HP)W1H_ENa6g|uJXKcFvIUg@TxS@4 zhuJR+K0p3Iv;i1r5$@Vy&z2y?4DV;l7i=q=*0|X+6*Qa z@;|Fok-Jz~t60^wSgE5(Hn3QGtXMa&So5gZfV)Hox5Nl-mEISb#Fkiamza;0*xVP( z;Fdbjl=3Cn^8mEP$LL&R>D*RIMUR+0xGA_I^L$*((70$oWm(Wz+1sPC_qgTT&%kw; zfV?w6jA3~cH)l+2dE`oYY&IiAAIy{QDXCEUk-IoOwj$@gD0{3T6U~)sm7=*)2d&DI zF;q!eY^8;H1&=#w1-I<8SJkuns;=y+tl26P;_61NYIX7Ir(V?~ z_f?t6)$9$`6Zh2_v(-~lSwpThM3ObC$u%o9H7WHq3g$wvUOkC6G{u(S)|RlWE;@xg z{3AvK(4r30s}83V?aI{=OV?v2o5d}f2}wU^q^%Q|ZjgG_0AvD;o)JxA19;H$&sVmD zg@7tRem&i<`p*W9%yEsZosFQ`COsag9SncVmgomE2s62v{?`{zyw<0EIQvL2-wfo~ z))^B@Fs%=M5`w##kAW_Iy3AlY!ts%HfoKD81YZCDDx3dWXSIH1 zWfo2SC8xciv%UFOJ7zLY{Aw^ZoM2oK><%X!2Llpm+fyytYqeYJs@j`Y+d;Ekj(C7n zeOwn9FiD^2BeE@tr#+3f^_-_iA{4(u5IO+G2iO8p`6!^a6XD=rGZZ?gxrZMbSr35z zPu=vhLC;N2&)?M^baMsu3Mvol4KX2lWeXLcaDYsNemw8R4DGoe@A-#^{?G@^wf|Oc z&$rhnOwrHm*27BI$Dz|l!3%YO5ppPeb)O;fbjJAwb-?NBCCH^_!3VJM_HoKUWsV2* zwV`D*_`;>VVv&P?s)j7^0l7#5aR9(hpKz_k9>@#bs>8)9z$l&}V5|o2)?tSF_fEsz zQtJpa{tns63BThN**xU38$Y)`qM7 zUIw(he0%*eb|Ppf=UdXmw-kK9dwdjtI*9-d0POz7Srmi{oDn$y0NyfC-}rBdUEkiy zjADk4RqA}jBF3K;8}|wRX6ZI@t_>*oKa3#^ihD-T55**$F&&?AKSn2FZHI|$36esZ zKi~mYkrQaZ5e4_jOr98Do0z7XoVT3(o;&GOjdPz*;08xGZV7}ke3l~J52`07WTs|# zCl?-wmUy8VA(JZ;Zc||Qxkw-8HlM8IDZu0u@No(df-9!;wcK{5?13noZ3<{GwI57P z+C2q;&74}!a8%72@>>6`>t@oOLcwYHl5m;gUXFN~S2UZC*W=8i3#+#HPxR^E`nZjU zV)lg)Uc(8(JLs%}P>p^6i?RERhU;(p1-{KN>WtAlBatZ4dk;bM-UUGjqGXgHK@6je zUZS_?EeIkaBBFPK=p-4P1kp>BIrG2o=iKLc&Wp3oUbEKBi+Qov+GXwiyRPf|Nrvya?*4Lrhkg=7g!A`g&m!bw5OkST)~gD8A_6P&{U zY^)3IktFMEZ^H6_1B55ClBeCiPd|kMUJ5hMf@huwQv`nR!PR}fHAb2C=_>#q&oG>I z-tX_zA!RYG!&M&y3WcnVpVV&3w(QpNra=i}jd!+78YCG|rYsz`-`U!auvN zGy7y@4pTE*Ff!Zdu^{*vywOeyrkY&~V)iH?b4P%m8o-K_SkFoydN#BESA3=2rwK3X zfhkr_EVRlFBGe9f9LL(r@~LASQlRw0;0@_70G|g!@g2YgzNY$ls4zb?Mk0lTObA0? z(ZIIvz;lJWI1KQBIaK%oys6J)YK*dMhO%^nw99&^Cyt3&5l*HD|A!^jgHzkK9htzE z()xkAezpXxO)D09jfL1RH>d{!c7e?wmIZc~IoMZj!hq7G7v(dQqX1BIIapu41hOB> zT3RB#UJ(;qE$gGi8LV2F!=~@R8;4g}^;omVpxsMhw2O}43_-Xg$i%)qryo9`hwQ5X zo0fIwka8PH36HDKpP>Sa_lF3*%6!qVbYXZ-9TZ{+POEV_#@36WP_GbAuWwDOUowR% z;v;q7QEi_I_kkGCPF4yFOnxY+J~T@iw*^w(j7-=(?cJi*2&Kn_ZWV-zxigi*fby4H zn3o`uW-ty#DukF-=5PLutVmAic_p}6=D9@}x&~*}*20Iy;v7UkrQr{s$G}=Nh&L(%*w5?%_>Q z7%s9G1$C(d_a#B)MIuZ$Nz5_(S3f{F_B}v&k0@jhl)Oj&bB~e|(CQD@BZ)B5h%js3 zO-|ky`LZwmb6@Hye3cycIlc$7Zugny;XXqmle*9$>(j$dYxwFX@H(7AJpcrK`T0m` zpZ@h$hcfuL!BN(d-_hfzBg#NOurVUy-qYke^q*L9)NH@~L~A_jYApV;pJv;f3EG{& zr{PZ~eer!qP`U>Nlaq18kuDWb{@f$why(Q-!2ZHv9ZHi#oPA86>OC)*UOhbjjywk? zpXdBM2koC1-u;VT$*W9)Z5mJngDlU+Fj*ac(-Y6Lznn~3%18#7-N9Fiw>d7 zRQ=1kr62pPqG?2j=ey5g6 zWo6n0Gb$zK34*(?h|JmE{F*RnX0Wjl{M+|+`)g$AM$MwiZX0O46UYfxrAK?A$7btw@C&JeA_Q=ICp#rLN1K#Tv~q_?)je~;m_2xQY-({V zD`95k_Wsz+fONK-C9vAHyFjYBqdZIFnxGJIzhR({1q(lbchfy`Xh?S6&gzX6Ewks& zS|zLEVhL*OfSP*`Nt`Z<%M3(9nYcQ*p@8j}dMXPmRi6dWzgbSh!d2H`TjKCbd92Ri3J9;)g#BpG$kw9>Q{fn) z2>V!o9^!F{4{6EcVgtm_%GpczdCOgz7W^(e@-6Yw%G)-9bCvqSWaRZZ;%Bf2X7y({yS+07mD#OU#1zeG6T6N( z);{I2>&(l*T}wKE#^XptohjgyzKKcu+7OO%JU+jDfo5mCoflH1a3!?4pJwaub7kKeM1VCaz_b)4c0>X$cZ}k|91EL-Ai*(yf{?~>V5Ao*V<^M4caeq(${{4H6w+_$Gug{Lp&d%`K;q}SM z)yc{A@!rYF2_8B8hdn$zy!FYc1>pko5|J&Vj)ZhOPf!N!7 z*4J^-)^^&~c8>QC2j3nKw*2iaz3f9@bfPZ4`281w*zoq^lh-Tb3by6#% zqx=8UKkV)8{qOkU`}gnvgCAbMxqtnJ`MLsrT~2mg2EogRcnk65P4!tN=Bk$es*0)S z4GJ$Bo)s0J$hii?Yjh=>RY2?+`c z^7Hfa@$vneK)iYLCIW%r;NbWVfyl(f#PGlULuzVjDk>^UN=hgcN={CWBLe+n9zr13 zAkbSd_&@C7|DSniy)Oif)!{eN$knJX>WO6(ds2NSyxg0JPGeMi#1;H+5AuQP|5gGyU;EHRIT&rCD9ub z{<#L*ueT-MobW6(sr~F^_RUqR6FDfy32UE9h}%ceicKK=bM?L%0;?x&`mg=U`%It9r?x8^Sk5OcXp zyzAB1(cAkbkSCOuO7FKSw`*I{ky~ip6p0x3!)hZhm|7@N1jGIgFQNZ%tvZ z9sPgILrQme9|WLxu?r=>Ol37Ax1B05r8J}CG#!#KpS{cYxMC@i)o*ht3K7Zk-_1k* zrp@J8;a;AVI6={JhG0+uvMWLUWOF4^3BtRYB)5!$z*KKnmZb2IB#ng|EAytM8XA(O zrRkfx*c-69ul>ldi{xF;bWC?$&vGf7%Qs^i{*Y!V8!6lo>N|bTL3G=|ZX=&a58eso zk(bGSigt)BHI9-@bFqk+zqOFA^pAd+WcFmMG}H4oZ)xDZUpti3?mmk6;P}`%j98#0 zwaVrAu}d+g16P$<4Yo|LRL=QP^}Dw9gwM1#uWf4zETx0st9+@8>;jY2x6s!lD3fP3 zrWk5xH8!1)Rli;I`@Qo4?2*Ipv|BWAuA=n7)brhR_O#%WKUMTXZig+AJH_*QWV>yb zC*+mQKFOc9>$i5_dsZEHrVAs<$!CPUC|Ug9#XWELtAs<44!BDu8-dPJ*amHi0%ihC-hjcv&9r-nQ>jPI~B4?gEGf< z-yrw$OIAkjloe34FQ)kVe3hMW5sry0rZG8HdQP4eXz&R<^(idGoGGB^FT3aEekAwH zsd)lM?B(IV%)?RQBm?50f09oE9gN$UTO-`L{Rg8%tMk?r4mCjv_&x;_~ZR+oLOXK zKCPoCL>U1fFv4V_w*$<>9MVfL6-zr+XqMq3dXWgVs-V4aJBnfwFyM98C%1l<5X=Pzd>c9C_(b5Q6jT6lQlwl;VYESwr;{&>1&vgfY6kv3m?+*) z$Bg=*Q9BsZ@@tu1YG7c&#fWdXIG;!TT>f|3xC{T0t=!~nypgU4^<_l|#bX&X4S-6& z4YadgoT&pOcF+=Rq^vbkql$MTSuf5^wEX?>6A5EJYE+*{b-@Sc7Pl<=R)>Arfe}xu z%~yt&)(?t0$U<`sy{moK2A}LvN?xu;DQ`Ok508@q%|%STmzh)ib2z^H2Zxr^;aWGA zz2b;WzP+C9o+0`?Fcvut$u*!Vx3W%#(x(;#3R;&cX^ao1a(dG*<6Y>iX`oXN>!{_(qq&qZCK$DcD#EX@4Qr`SteuSd>)Q&H!R=LZdL3 z<`s_jEE@VaQn9u{ok|L@yHO;*+1=o6)DfKK`B~DYV2_i1uOC24y-8XUY-;X@z72>iS}YZ2 zXzKq(?)!1b_MYh}_eW{I=}Xy%6EV=%m65kEDUEDPb3X`;<_*30&hnkuDupm&b|h1sFO&S6)7vFf`|w_Xe(?udIy3extuCfZd#TtWK#0*Z zHWIpR-#%p#ASKuj#86SHU8Z%tH>xl;*KxdRn&lCi){dJJT_FWoX4##C{M7eWsO73E zyMv!3e~6pE$#84nx#fXn_Tmz^7!CgijJn|8>=oX5a~#q-!RN_m9a`ZBYjN7zZ(9W2 zr2cwlw43D*5@V?-73=1Px!Y*-)`neP3s~{^B@B`!mx+gAviKceI^?`*cGd8EQP7FF z8BHKy&FTDcydv^fF`C-7qFR_U1EO74$hs-|;1@$1hMnW^?4%T@0t=4Y%* zy_lAttll>NIOOE%lXqdgc_5o)WQRs9!h4J!2d`VX{pB;sJgEK5mTh}ix~D_$bU*Uy zm6;q-;QUJdX*;*#K^A53uSc&hu;y^qOK>ExcS_MT;=Fh+Q~B6$-SkP}V`H5njnsrB%p*(t$!Jfu3=&%=%dd~fD&T1wIxF|*c;Hf< zhW}C%H(XTogSs-7Gw*a9&u!?54en%w2aZ*W8a&dl+hx(~A4^WyExyQe)=WH`uvze} zV!7Tk{n8?1x;5p{X_VgBcuSBV352hILNEK*=5J>1xeWv_nw&=j?dz??J(`;d(f>RL z3UR7uja#{y_<38i7Va(B_J(E0MPzPk^tH}Sx|)Fd#@@T0?cn~ludf$r z%|9Pq^!$amCpG)IeXAOWqC; zeDT3B(ml+TdQ8R&!zEUd7u z9Gl^~jFIK^{Ag!)hG}#IU8v%eU$1k7F@ZyC5@4Gdj^K&(!=OElBB?O8M6V+6@`Rd8 zKe3d?=yg13k&N1P4%Whi=m$h4;Lez)%#{tL8I1$zOc_l)FwuroB!p^C7!6E}MO316 zOuh-)lvB936CIq%FnAE<=7J18b1vwo-G3JT`s}3^cT7ohYynlYvSh$(2Mr@kO6atAfU`-XA9=#0l=I9`HypsCR+P6^5c z4uvOiz9f;~&JwZ><5Op>+DdL}dncZ0aNQ5%I-gC{F>>t>Ptd-VL?#0CA~Cs;cygjd z3K`Qf7kExPbQcSou`>qtfSNkkp8|?(=NC`yIhGhxt~e2dH&U<|zBNpoXGO|APNzL= zH0fNz_-vB+IfDruF%qW)J}Lg^wq0WY^F%>r?4aF#@%+yd)Ln(@F-U!?hi>$0+H)_% z%3~!g)1Hq%+)g58E1*n4z$N!6-NrnRGE>2t>7i;#B%Gi_IOQlw8kvlv8B>N&p*68E z={X9#$PHgL(1$Dm-@L%Mb`Y&FF>L|xZ}Sje!Hb*AOvuVaTV^K8WTjeW#WQ84XJuu} zWMzKL%0JJFoXaYZ$xi3ZE~x~5@eq`gW`%#uu6>?WGndIPj1HQ?ct6h>I8K5Tg8#Hr z?${Zp;@!n$XgL!8u9!1Rm>6Fh9G=S^J zDSrV+N*1J{#O>67$F{e_~xXs;xo^>t~<2>3Q_I{Wj`_TnOXk`hLqlDjeKL?SNx zfUhK^xI(H}uZ7mciOd~)w+u`96#Hrwo;t0R%Jnx!$)%*2sO zp*1-sTS=n)g@BsBNUmvz9oJDbO_nOQC^pOcIJILw+p7@X;PlhM?0llk(osL0W3s??jtEA4VY{@VVFCGkKKhQSxe{59| z`oe)z7*Ni^DVm%w6w}}6@WIOrpzpV8_Q+~mn3Lj} z%Z_EsH0_B7%?T&p*8=$E`y`5Ab9H@faaWgX@3>RWR4@yxmrkqzHkIExM7f7?reb~3397Gm6;hAQ=j zLaR4xRnc-eaPTt<@7cGa7WETe^@Pf>xAO=itnSs#Brp;dM>crDkQl3DmitL4d)7Vel9_rQ+{PiP73Ox~m3#s<>o z?@`{T0aXLAQv+D_*loNKI57s>2A~SU@TW-VZUJnt9RwbS%qLMUAxSYfbW`I+LX&n? zUErq{x3{WZL=kJ?cJh|(b6QsfY|&0!rhvi=0rmu7gLp!*4pwIXmM);!+@ljLs24>+ zCJUgTCD3sanN&OJrEock*SnP*&$S_+t&6q|w>IU_=7OG%^gt))LINxn@>UWq9svOD zG{c2poG>z_j$XovJ}C7C8i;B}jgee`&a&Z73iE zk~%?!q`&ZjVjZlw9iYK?i?nwNCQ)V~0k$NHaRht{r3Ii!cd=c?(67SuG$?38 z62z^5;)fkSHvp?ZC{7}vdJY4b)dNIcxlEwJ!q(Vgo!V0Vk@D>hvScDR8NzDTRx^Ts z97XKE97WOwf@uVl;}z+a0Uw0{<(3NB9Nf|Vc`vxI_i}3hc{%LQIASh0a%DZ@dr5_~y~F(_DsTp<@uU;Wj) z_p9gcue{JPzc~0!WRh0vhzfI@*Ox2-nJ}K0=odv z6+3=d9GPStDa~;2ZGrda?zY~;6JOhlfu{!0u{%(C zGT>DK^iKh7#16dh3HpP)%}8O&`S-Btvni{qnTpmaTpXOq&ZH5UPV_nag+K<6M>F5f zY}n@sk`AKqGD3{N^qZDhiMiRzz=rIL*}N+nBB1jYcPGjt-lTF4IxzQY!@c#fsI`O8%ci89Fxis`nUzWobb)6WYRGYj@?i~Qu@UkAf) z+RYX!e9IYJq}W;%-I?#hK^JD?;r2={`tTpXRo~#q%=}f&P#$eu%%`6o3j!V^gvkUY z9zUAme?S&~{LXu^_`MHnvk)rqQ$EQ}L;!mfKR@^VXVLIa!Sxw1`w}VpSd$IV4W;CO zFHpZ+s2stToc%2OymY9$!~z3P*DTT0{!ID31g-tyMe*jx)uPCc?^CQmu#$@jVvePD zS@JiQ-_{F%*@?lh2YFK<5zuM;GFL5D?0kh|cjX~uiAHhR#B-HY5Ykw)!kfQ%v9qkV z>#r=hs5Uxv!*i9ZfcQo3l2zL(Ya8}q+gAfyXQR<|Q@wR#&s94+lX$xg_tBL_=8dO6 zTudQ^M@neVg?l&pvth!xpusA`$pof~+$>cUPbQ1@F)ahuZgS4cZR)`M?o!K}!5`lp>`a=JHYO4lw(@wvdnD}$&{n?4?5-4aC~~oF2QCGAq2yv~ z_a{hix6yFhK$*PTfCQHyLh!n3UvD+@<$HUe^N?W&dUvNWpEp#Aq8Uh{qZDKis+st{ z6H(jDgd(=Y3GSX<#j>^CVt`Y0*MWKOhE3Vpm%|P^^0)5&c_**5*k`vWo`{bHTg^Bi z>8>MD_$qWKq>Sn5CdHQ&h#m3Arj4q$b=X}NI3=Bp62)f&!1(RK@7i)OW$e7*-qY7r z@~HJg`0m5IyEpW=-M%uAWAVF4(jOC!_0b;?md#w zKLRGlq;ts6!vQduvP& z#Mx7b<2dEV9XQmwR^Wa`z1`QzFZ0prHT469+kvCuO3_~|eKiZ`>~ zvXEpR2NWt{mBRjQ9u_K*`S9?EGa43kMpAOyb~o2K;LSr~Gu9Oz+j??#-Fu4xMz^%0 z$Sg0l36$1#vL!rzbY~fF=;h1FT&|26ZyFS-`8OdXb;1qHbn_G=m`#6~RGHS;_WV6^ zHmD%XHO;Bqiic^fr+;TX)~}h@@mXw(U@_mdZh5xzqbJAwk8NA<)in{T#hzVfFm98I zp3=y^H=a#wlu+#VYQ+QIhmucXGZDji3Ly|St0R{Q2>}%k3BfX5DV*c1Z@cmdEJ7+~wVnYZ+n0J>IQ#ov&U zU-Be{e-VrhR++*oP^ne8JZUsFD$U2G-!(qu1xmjS2XQp`LcbGO-^w^(jDoE#cZ~JW zF)Y?A56DiE@gVYEglDQns)}mf%Aoz#RcPfJ6;D%^3jj>_l+i>oorRCNiJe&~b@sa{ z5_R^5F9p%^0nvT*?1zD3J;Yh71Ddi=55h8SA&mw#L@O@Ikl$B3m&1k*>5d7iWq0H5}I%;6WFvfIOOxZH#L8_vpqSA$TKk_ z8J~pB{Pw-23zGAW-bgoad!K5Ntr3xS+Y;v(&Uim1Lek1L*6Kvm>M7l`VfUfMlVQ*I zE1};4S{dmdJaWD#IsfFsH;mB^ktu2We8a}S!ELCA!6bM`tR0r@x8(Ei0mqf04QDA^ z0fR$Z<_G(zhc!}f0*M5ttz$39Pcs9ghcYI7)CCylFgJ9i4(2v1wPl}xq{PK&zzLgn=v@8{S|*GtKnGIg{vjp_f4^B`BmT9^U7>L%f|9*)NhnsfUNr$1_xvkjgK7Ck;dd2% z0>3`Rz$fLzJN_POPg~E{dqVPqszHqCq=1C;_VdxjK8nAtG902HJB-Y|z^l`~=L+dWX)MLZlVx&HD_t z&E1PVV?1IM-ywIodnPc-!3T&A%7_3u1Wd#)IVX>*{5^?-d|0&eQ4UQksAoL%t*>X$ zB7Mz7Px+BBJITZiR{L`GWhZFd1Wj?HpHiHiH4q;~n8O_1*}Jzt9^hR~#8GiZsb%zOLp_8M$eymQE|WSN9;D09eE>(f#ZCHA};n? zwz3py3WiRsY%*>3>2EXt3~?EDBdAZ#H!{hC)=9252h6T;)c0;^3>v-oI70kmLabwP zh2ND?moNRh{vxykSkN>4W&R=QLK0i2Iz)AN2=_8Up!5o#EhLJ)zzr zS%zL42I(Ia3uTOR4XbbI-Cv65%_|^0J}Pf)USWIb*Jv_*M6JXz-QXK%1v(bJs2}jTP%7UE0qK# zW;J+aIJv^QoY_MroZWDPO|$%=DYd>AXjC!XH;s)ponTCDN+J=H-L6cn z5P+8GuP3-2{r>Lrc^V5Ma;`7);nj)!n_M(Q13gVXl{hIIXZUs;SmAC3QIG4vll}nd#wj>r< zb!<_2UT09H{mL=-Cdax)uUq4rhLk*tc8==>ml`!Jm?NW=fD20M+094%C8I?!5*ZXL zEnXl&+bwk+hq83jS-8>EXGp5za5C+%cHP*ol7}l32xNI{xI8;hPc7o)7dL#9fv%Uj z&0D`n4s_gcQ(g61B+*N5rEtxoU;qB0sjtp50dw=nt=>4sGJ0*{9EP4pS1a7b6arKh zyF;!J{E^NLBXN@%lIImKqWnzLoS^hfvi30AHQM>fOS}u#YEvL#lcoL0X>g1}EKOyE zR@OJBCZ@K**!aqf>GYk;R9DZjq=H*9h3t5oZKIxN&2MY zM7s=xR#FS{d7ex;RNL#WUC%`wG3xRas5R419~Sm>y`?hv-`2`5EGmXJnJRj?%jsv& zr!px!JfT{7`lb2Dkz!MGN7+64{Dq&A_0Qho<^rF3GJMJ{AVu9+UUCZh5SV+e$T_R^ zAR@%v`ZfV~bD@}?dz8wgnE4oEo{ZpDRN_am{Ifnj{D6)bYK48xPL23+3dFS$%{Hc# ztV1|Pid}?f0W&y1vkIfGpK!dAB;tUB}{B-G*`g{fJRrM?_MGkfQ4LCgzD-o z#b3^TT3P7!U6p=pbcLe`t zBm&>ABYPV3g9f`9F5SBy1Me?k&LIYFFB0Tb^m3mZh=vcihg`JlJAEg9cxmawk*3Pe zTAq@KbJJDK()3*+7$Clz#Y5oD6Oq*)irkEPc?PKg0p{&dZgyzN*+|zUQsh~97786w zL7kmc{$Bb^fHGOB#h1rjpTElq(X@&Uo&oWOgk}rU)`7~lcNBTGqjHVgvao=AK;&g6 z;GPsAZUJ`Mi{$f)2+>dgl)yI$0rGAoXm#{#67+C|Wu%~nYO;~Kv59v0o_|i96^8gx zKfu7M*i+S74TOhaqr@+XariGVfP&URT+i-i^@sZ+fGj)Ii%dcQ5fPjjO^T!h&f2oz zcV|~}T9?T&%=hw2T7;`a$ZyaH>6JShOO zv4p-!5`+Q7_!o02Bs6Q2;Ff%ZXJ)izz~@~2t6P2LU1L@8u6vr*lJ-HW)pe-u0U~g7 z_a%AxRTstDO*PM?&=_wOmi8z!{Hc)?;ip6ZAOMeoNHHa}8wQfqFK1F0s=FtrvdXd` z6aJ8*(T=tEIsbi!l9>Az90GL>j7Jh~ukxHtK1w2J-`f#n1)!hQ$+%jevy=#&ki@>I zh}~DDq+GJN;%{pAgVKb?UZFz!xL@_XC{h3MsJE~n%>8D#Jxy2gk%;r;JIYjs3(iQc zO%1zljf#M~6)SzAU8;Rn)nsQ1wkQIwg@K`o?)0OapV^w+7aGaAcYECii`x4hZK5Fy zeTBo-X5=@&EPbHY8f1AeNVC|P5;#~`&>esXrxF%@6I99M`@W4Ah%hXwB@}5m4|hir zKeLOxNr)nLiFg)3>?9nTbfdBIL1k{LY*$H3{Wd9;2CFS2xT;z!&0Qe9x-2`0uJqN= zM+$kDWl$^IJWTPWyAanxtTk^l-eMy#1c%5oMJvCZ4*%dXrQlHU z`Nxsq->lFOc+d16Dhm;%mqar)sk!MW)iW8*kQ5bw44-S%dta@)I4L!(d6yFW6}!y( z79a--!h;H;-KB{Ra^mMR6E?9J$TNdD)EG$~2G1U1>I~wVQ8pN2+cC5-0=C&aMvP|< z)5fR;Fu(eBzmO_xTzu_V&YiS~2PupZmR5zj$M%hlv#pJ@ACGeo8Fdsy9FL>rlfn^d z6L|3O6DCdzoN6-+e_PqfK*!&%nRuK;dZ?;@9MoA+1YJ-vq)Ee2&>4Rx`6fDr!HKDT z3r847?}fR)(HHEGm$WhdS%;DBF_16?=)UU@i-_^52{e!?TKNGF}VE{RRUJkQG9pJ*V`X|T)!upvpuA-BM(T!Wsa ztxs>oP;U}?&JsIg!oPxr!gSNUwJj2@Eb7Bm)1caU6?Y#ohRIc!FUL+fZJSnM|B(-$ zAtH=f6TS1`?aTeI*2+?+KBt?uS_)|PlY1gPQOy&!8?g+`8zQhF8>&gdeZt?Nd&$I42V@JX?4hk;ZMoS<7l|%V&Kq zXFZ{7ot>ojoDl@>L<@&6PE36na3Xt+-`fZ{SIp3uMCo|E4Q|%se$P?pIcqo`UQ@t= zp2S;;PR{0UMz!Zg!#9bq>TF0lbiRML8MV2o9yI%H$7VMIfW40(z%a|Tn>>xTHh5s0 zzel{0MoQaEywzjd;gdm9_rqxU`_JR=3(VRaS5oCJU@RtA)cs*Rt z4wA*3bM`E4_vr0kh2o2;hXnb<<^0;W$TDO#P{6wFW!^&YcTz7naR?7F4LvbFu~h=~ zP=8JMxY$m-0ZRZ|BG6oiG;OmT}`X|wt0+zb)7?iGKT^H z*1Wd=`2A7kChCT*4C6`M)=1LbTaU@9sVz`MAsP_>NFwvIaI+=`$;Y!hSC6|tlgf-H z?+ZNCO>i6_S}zZX)GdhCMMfHpvK!D%J)6$QZNnoTUX{D({Rm`p32lomeeVda00SrM z@(_pp{ByqwgRN%XWIVu7H-mG!d6Zxi|MxDOA&Jh9=l$fyWaurJav=>G3_ z>|1laYgx1FeLD`x5a)T=sHtmu1 z?Uo}Wos;_E0g(|e?P$%jCLBa)7;!qi_ptz$Bcrp%n%MbWI9Nfw9 zrpN?y_Z=03!Ue!**m2b@VWJRHB-o4o$6Z?O2s6qiM_2N2_W**k6> zsDj8Wuy>wAd@T(2+NTfrgpX9zk5tW%)SQp*`yZ*jMyqEWX_otHCLU?^9qGJ2(w6cS zI{R$12~z!#tmpz1HSJ1&_)}p=yp|d*VMi?gGw=4uP zQ`>_`zySgav?qqhVuo$8^qC^@!KmT>@38}(+0ekg)1aBt;EmIlr>7w^{+yZkS+}z= zsWUXrKa@Kl-1#h$H~<&%#s9uVvr@l5qS;iW0`xTGaL(`14nG;C3nZjJDrl4VaneT) z|H5Cvr-gGd9-Dg^QO`XXk2-4oqduJH^!a1@&hwlD@;1(2hn$7}Bv1}$RUJDOs59a3 zKSOSum2n97Pm?lZ(9%4gL*xC^=5+0NTGRBiY6{#9g^B!|AxcdU|5<_C97);4f8YP{ zf9-tn;fw!=sK6%kGeHg32WO!{LLfQpI+w-Yr%^s-A%E%CUhiJ&)rMql2M`$*kQ%{# z8;RlXUtfI4xER2l4}Q4JV+i2E8rWKZf}hUIB0yhe0+@;Y+e5a?;j2>|j;a2IFqO;N z4QBsYkF0`F^EOx9J*ku7^1#B4;DWx(pZ)=yK=`aYL}={v4swBimSBS6Qqu25;-6^4 zvX@4FS7chtv!}Oem5E~sQQ8_&SyAu-hL^dN*9Yonhw33{29O3O>N%V+7#F(Ch7R<9 zIr(%yi2YKr1|c&2@&y4VgcX1v`6il{YE}Pweq(cwvl~Or4bs>biU^Y-9SvdurC#vVD%kYUa{w=iPLbk=JR!7*6MxvT&B!~>bk>+IH z$qJf0t(qrkd}^`0iZA|ts9K4Wq5(+ip3rj(esPs}$-u_Pc5t+_$bQ7hbBZBI&x*Np9&#(P-My1YsY4msyin3G zM{kQ`L#=QwB!gCkJ%*z<^%l+# z;azEbV}JN&e>!(`p*lx?y)!dXOmU;kN8(y+Bez&pTvLkjX!fD%?ihmWscW@QiItJ! zS%+|Uqa9Ciyeyeb;h-fGXZpi?>!qc#_Svr5=*!f8f6L8eb$Xu9(yX~7rGvS-QtKoS zWR-U{lf_C%wm<{}JSv+H6Fb$(MIz2*`RjW|)tua3J(i{}&q$x+*Uz~ZJHdW{=NTy% z2*#t>9ZGzko;^eI8|%_<(_A%Oe9GHMhMw-?Au2idz6f?doqdnMikJ&*r?3OhI4+plBMCet z<9JgWM*9q|B|4fK)`{+?9-blUfFE{_DwFTHMWp$nDHRt@QiSi{yfcgJ7Sv^Z@Bh^( zn3`tg>Oj@esj9z73)^JY(9eCxMNmUgvFdOvK;hmnr^k@OX*h|W(N|vY{!lH2yzSC$ zw82Ax`YH5Vafx#EO`{?P(+%Ip97^GA-p!A>HT>3COBa*psUyS&UsE^eo?1VIePysp zo_hrG!Ky`Q@oE@}kNQ0q-Fi9udz?#kbw%{Yl#v9f_R!a7W!#>g0#7W6WPc^cvBB#3 z$oGgus>XU{M(gjnWJX9fio}WukDz0siGba$Zx z-+(ixjVX=ZP*bl^N}|fSbR=S_U}#r}x7@qAc%iq|{00hQ&&3%UUtSAW8NKfgi3we` zMOHFsn)PtZZibVpmTMZk3@7d0>j7aZb+$Q4)JIp_A&gj6;d|q$RjjsrZ#6Xr8&kxT z?V_nJ+wW$~il#WkeUmX&>y53u<@=0fU6fZ8Wee{j-*4SmgqP&J+cW-dP z@-TZ>j7PFqlEiK9#v^|FLUOmQ9$e`wQ#yee*{@TQhCh6$x&sImRrtgSO*>gjFetn`pW{peZX=EQ7%` zLGZA1D9=kgUk-6!SP(H$Lq?%IAxvRcLV(f=dUONHqlV*hdGgIUx1fe|)^(@ioK*>? zS7F)kMi29%zPQ$r!bKFMo82;0p1qySG{P~lDiX`_;zYw!o?PkeiCbZd90CN~)5{4hi z5`jQwE_0Rv#J~hHA;Fg(sCS8yZ6A;M@Iw?E>kbgva43kZSvXRxdI^d*581ElB9(E%#JnVh-M1A*VvMVo>E1Q>@JM#D#$lJ4 zzBTs>MApZ7RIktl`ZI9(c`;7VL@<7nCNpgZF!;zTYW z<7x1t;^3tl3}Ww?r_4eRRVM4BG4hP+RQbq=n(E(tvG}g+Yl%AjxD`7Zmf0@Brue{Z zH+q)P2M+MgdK-5~u0K{Y7PXR1%0W9gcb|*FkE0D0BL^)}{i9PI5-@M88qYHm4D?+c zWR$N1lGHx0c%9VsqBw?O;-I#*T(w5)#V}zuavNqgmia|jV*Ejwl+R|5M{|v6+d-a? z@?Jc59c$xmyjVHrB!EaUpo`SmR~76m-E~*iE0WFypmVbeWoaaUu{rg$q;}Tw5sVgw zJF8>G&zTuugOd?C-Q)|;OqVPXD=5C{(d@&2 z8-PCBe8gHy^0I9MSuVTS8(M~D zcQ0Mxj+9cAyb!vtu`WwpC;0h?&)V`|;uf8kt*mb3ejITWW6{Dh(I;)gD2JPf$8r``z=*m)+Inwoy+6ju>9dD|5j2q*-a+F7srZ0pR2NTJ%A*zQ@1k26X>f23PPW?7eS;A zAhNyt|!-sj2L7g zBu%RHCfW3>iNv)7r1`pJk@@E}J&MOPcdv|j3KwzDAz5p-` zgkr&fi3tl;Qqe!*guF;_jm#^x@T{!Q@q`M6x2%X#gz=q11hm7G7}m8Dsjs#Tw=&18{3JgAZi$fSm;tSU+GeUqvNl*5%| zhFNY+ww!uEGbZwh|soeohZbPZpo-bhgi_cCh6# zLDKJNO>xuPc)Z6gSq4r0iKeqORjr11vv~uO@?FL{fMowY=IT&=+`1sxF3*rjuVZgB(wJVh$vH>e#P9iOGB-CrY+ zT{|k(hr|@C8%5egtZH4N9;(4Kvk~V54)V2#2k;Cp&J6GGjzi59cnX);8Z2SZu7U)~ z0u-QDwAc@&q3|%d)%FLsRK%piC0LhCj2>m3!|^rqM~Z|}O%YO~bn1}?yiGPvO@!vP z-3GKcq8s(gFp_k+CnaPlrIxj7FL%sCuFO%;S(P&lYi~3~;}mIoEEKD9XAyw)-;=`* ztMIJiJwxur%J!|sk2z_TJCAm=r>@A%chk;>vZF%% zf;e54Big?A1kCrCXsTt`Smt3=M`*moX|4XH)mYt+f$Jd%}AcUYZ%#kd9HZ%tKz)|B_}&7`eTpyRA` zSHXm)lFG`wa7MSnYdv<$EKM%cEtjPb$;V#4Tl>lCiAh<7sS3pbl$X=?jw~|?PwR-+ z7HQ-j|1e=2#c-VW+fU41mKO!OrgrBROMfx3U!ECX=2iIlLAzt&ng^o=X$12H;5%sW_<<;gid&B@G<}sB}99wYx0M_j%Fb3E8^o3A909Wy zvD;5xr@vnOIh~m5ich^`U7+bhcB$=^sx5h-Jpp=ewWlW^d2MekobKqz&8ISABP_5(gE?6ubfjT4# zXf5!=T_St*6{WL~6Ra45iSm}r=oad zv&sk9*n};(Zpox?i+iOUdnsn?F0IY3&At#tpp_UWtvei?(&{4-|TX2nI zk4$R2b4j-7>GT<1S@|v?6FImse%AMWc}k=45zgp9lTdORU6WZ+hc{TC#lg;l)NPXA zE2aFKZFHQa29aP<;MlsLTCo%K?Y3SA!Tq?i_c>`|TyPWWxmz6ZifVbZXnA~InDoKV zrOpQUJ!GH|I^%2H08 zuF+$zVf&Z+kDZ3;?^@7xS#g5UhKq}6pHh9u)dh>pIpN zRj@#ROi-jT&y`V|Xo#=0Pv70idS<=px)Be4QyEMl)})?teW)tn@w(A!lYcv1{@G;I zDj-fdkX|LinH%0Dg3l)^Wfru6j4`HSRd;Q`7eRQWAmAMNWIvLA<}Q8=dMg4)fd-su zg}RXj3Ye06m{JRXM;5uKLN@Ytr1lHUTLdh61wuvyI%fn>FuNl?u9UP;{78(wmj0kc z;OgL1=ty1THv=dX5{+~ffr9nR5psQy)MKvzyO4v>U;fE{i%=y?n`+L*6H6$th5ygWwWm&?mw|(WzYq-l z7RwiN-%!0b*Ad`PUTZX~V6mqVaGLA*d!F7v-NqON^PRI-M7@oBOQ3&?X{dMTN`_LB z5Pn{`nAlcGX`{bZ)f@TS4_ZEvB*9$!c3!fI73q$#?zdi{%?V)V$Wyo)|LioXBaZKE z$O}GXWD*AX8sQkVXon(Z$3dr?tSO#=ZYyav%S$1bz*gs&YqA8NiYy-r!*Is2C{*FQ z6eHzSzJt^wmz%r3ZF9v$-?4NDAsK%W+9G~;DH^0HeBZ5*MOg)Otm^EVI~VcW@0}vl zZ>b3lusGK}Dyk2i+(o*){$_xMLv1X6WZqiHgrkqC$Wi!xZfJ9V>*g`)o(2^MOS07v2BFURe8lWrOCHC0smgHB?hQ9*LJ9xNal_HK=6(oenzv$?WloOLMG2kkj)NOMm@P~C#UB|izJ$%5wY4$!LrM5q!1D}@K7qz$O z1rlUTMVMY>h#0d4^~S#)Irf!b1ELH)5qcK8rD@6aN~xpcp{eTagAAs(LbG%sfv^&q zv|l@T{OQpYU;N7CcfeP9;>v|<-cAkUza;ICaW^-4)UM5_cg;tlmNJP^LL2h2a_y;r zr3hb#&!QciVv@Z$UyW{9{~&!h3jVNoJ*xFMHyYrg*2m}q4;5?e6}a8|xzuS+bD5-t z#5NW+374otdaA;dM3(bD;g+2-_uV{_|K!lRg37x3O1wGHiJ}XLJtxhw4~9Uo_t^BK zQd%e^`hWqwxl;@WH~}yF=F|yE3==`3tD*e#%~S2d92o(cEm}>c(|?!4%Jzff#hzCZ z_~w;9kcA?N!FG0I+P*0SB|VJhQ+Kt(L$TSV){XiNzYt#e%ZiNwrLSxmPk;b~d029r zA&XeEM59ss5A%>@SAMxJ$wDcCTIM5x$V^e9h^#WgJiI`w@oD{#D&FR1fh*feQZSP$2>G_K*hw> zRdY<}2G2h~&3dFey=nJ8-2E<*o5#_Qwlf(EsC{tFM(%cp%dGY$Fb`-i3Qq{M90m|zCpSq z^%uiYKHC`Fp$oUD;i1VYjDbm0s%Se35Z%yp+ z$E41tws1tw$8;wp?v7_CrQl=RpMN@iRVI6t&R#JrPuipwWU^3LI;6-_H8;~i6n>}z zD9oM7XYIyM5Wk!1X@du^B?)&`nqt;&KWaa;>GU;DI8iOyUQX0fOg>My?pt6=60$0qXN?*A;*(A3PMZ8^ZF{PB-M3VLTsHzk{iy3=Dc zYK^A4YkQBQZZW zee~TpALSVwb&dHsbn)2^8HP+5P+Zf>(r%&pL6CZXdM|4B zd6m~9mK90UnR-~3>Z&#zC1gAJ#3AkxqqLKrP|Nq0FW;pSH^YIV3x*3AcBM>-0Ak@zP~0t;4KUnedk)Qxh_3Xi}cGt`SIWlvoVK1pO-k~p4Yf;N`*boIdqPfv1&uSgL8CT)B)nzV)ec|Y>EtO+%RdiE6g8SbJs zdG-1UqVuJG+{|S;x)Thv^W5D>ZQoi4Dvq3x)e^3GUt;_+I?fSTkU}!FSb;vZFv^_C zaCNy_b)X^hvT_Bs$&(;mmgMDe75d}RPCed7TcE=6K>CYZ&(@p9LPB3~te_6TYsX3p zf$Q>kTUK~_>^)i@#jkGgUO19jUlA_gD~!3pbS_ZRRfY3ita?@C)aU3g_^t;^WXUt2 z{c;8eBY`9Lke_J3%h)Znf(hrsK3-RnWN*{I#Z<#%R$N$@pG_hw3Q(PXMn2}(9TeB(qWt`Jv ziP-ER{39^{ZT+pW{B#;7g%StP_GxeduSr=du~UXdwOg=Q4Fh{q`N?<>A2pU)8oxJ} z{-3k=z-->b`kOABS|#H-9)oHmTIILWXEAAo>!sYnqI(S1eoXj_Z5J*WN)%vMg?6*= z-wB$Q*m-4QD#r(heKJadbeNH((?Qaz9G$lGv3193Pl6u@rt0dLT`980M<)D(NaQH_ zD$V9nn`=rvFZHm#ZF97w1CJsxMKxWBjH?wg3~w%hDy!L?QhTH6SPhzCm`bB)8#sF@ z&L0mPUO!NYl-w~K2Mg36pJw0djx=mne~X(=d){^|lPk7{LdSaYO4eAbacQj8&XN*$kF4(ZKZcYJ-k zM-J1IwaeGr{B^=q4B{N(I`g<+hF;z}>rdpqr-^HHGS*Nod@?a*+MfL{*NLCh4!WW# zzNtWj7OC>2ocU|8tL!RYf1D2a*ekpv7bWb-_`N$iCXDC?E5s`Qn=yA_?zlYBEgDDX z&y`Jp;s~>{gXEcPld|(JTJ_yQkcykEn9q0F-@{Zy^pUTm-1ll8TBgB>GGT&nJv-ds zPHKWDbi>1&L#6CKxaLIAc`NrQlcQZJECzE_eSZ0f`&jGU35%Bo|M?icJ zq&J`dJem02(Q9b+TFLWw=p%2Un;UPl+~vkm`Yn#XWS@NoTFp5kZyvyeR0$ZA80n6N zP|#z~*rJN%PlH1n3rP3N1_haep(+7j>R)GZ>EKV=6peI<11TAgo7%{q5bn$MUyogF zaT&Qn&}*?sL0ygpuB-8HTSAO}M>s9sK{am#?4YPZ-&6iQNsZvek_9gSiR=NWsX$69 z5P`B8wq-v4Jq;v3j9PpHMOlX04RGJA3N!&K>TML1&;?aiK2#n(z)iT0h|sQ9M~?Jm zQ=);+^m4L3)~P?85z8GbXS9zeAk;syO&7A@u5RoZWLkO}YA66OW9sU$PQ4AG%>@!k z_LD+3$)Mr1%2O8nFlz1C^}?cyFnJ``uNdV+NbYF7j~d9jo9MB?E&8pV6V`@mjcb>< zYY*%Lbxq7uSt30kAOuRoFGGoC4qh-LATb5$cauj$X)9<5u?i`|;s{!SU<7zFI19V&8`TRxs`H4B+w*uJB6ihXU zLUjY?2BWwyp#I+N7{<+pB}<(=2@|BDl}(bkmmte7y;y# zG}sH$2vGop=n)+j;6Xx2a5hP5`rI>hVnx@u)fYt9f-Ey#~5q(6zAfDP(fGe&qf^=)vtU>8~O#sL6^Khq5+&8Nca zg)Oa9?ry?J&S4Zhq#~xI^XN-@kxUuIb)2WP zth2m?mz>-UJpAt7Bb-p#k$I0zjFYaPq8OALwJX~0&->bargU#a2i*<2U~BngAGF98 zx?twr?qwS=dLZJ#7kOR+Mp1)bcK6rKl-DTI79)ouEQh>87oW7xTGn<@y<`H^&m-L; zyt^9shxs_()O=Wa;ZVz~f|gHUYKaFQ&=sY%C;8ANjngRQ%q$~NLDyc*u3&!k&6H`V z4w4un`+G`u`hZi zn(P*2#>T5qZzx*xocD_Gx6ThTH$MVE^Cm40mm-o0T5M)&My?*}QK9I#6Tb+kIKCU% z&iw5_vYNXG;g3eb-Z{$g%Nc7lY|Ufp1t19zBZnW2_HTliO}%GccNqyyRS8X+0#_u%79M^AP7{f z0CFYlA?NR*y-xoKOQ(A;$dH~-!kSLMkA_24Wpnh>;N=VTVZxi{61hM+icNEBkcS^x z43U9={iTgP;he(L2|fIe28pW9TgGA=(b2cvnX0}F1-zu@QFYb3L{^NVKTSEBuJ3?I9!XQ z_#JqZ$8R2(LC;V4Bp(u|W$#qHBw8+PYbW3mm1f$InZU4#MkI*OL2B{1MDEvsgk-3B zKpV1yQht{DN}>?W$;ReQ$zuScI8Byu(wH%&a|(-jX~TKgyiW2R;2ZsERw(IGg30c!@nYxkp3AU`b;F{j>>vFJM;jDNol3VEWLmOXK;iV=Nbx~)~%A^oz@I*y$U{vgWOuuJ(n zcICUYmm`=&mN=3j6;Jmy8%s&Z53*7Q*&5fixJJRhQtRY)t7vEmsjRV!WhkW$>t$N1 zhcjiA3imwB8k{2>?1*Xu#Tva+8+9>>ei$_2(sE#7wULGoCvPDBl2athpvbm08{Rf^ zdD7>>vie+6mxQyxIqt7meJp%^Y}$O-Nb7PIF*DoS40AeymOG9`^^|D&e1cmmrC%NA zH{_7E*1T$!Ypy-WbeScuGbAR4ws!i{e@Gx{cYaAh(zG)j+P?wxNeCtG1ci)`%6cAlu+RwZ~3k_V46l z-S50rH^QR4VVL)f7Vzta-u6&b|3>7FMofx2(hQOi>A{4)zEIMkH^TIqzI2WGn)h9C zG7tR{Eu4%i>=PaAK2RD-8uC>c%1jy0?*4-In!1YV5#roIo3TL$$L}h$MO2MF&4AFM z{Er#Ap}|7E_~h+I1eX& z-%H-v+u#<2YmV}~0opU3EFf0)GgI-V6!q(zRCu4sgWj-319f7;k#(OldNX}MJ3cJ? zYf#n|EgbA3M~l`)TCriyEpZ837jETRnU4OMVIF>3SpPtt;^#yhkA`!*uo~BCktFep z^l2VhSj|$N_O%&>3t8FIlP7q8;_j1h^RLlI@nMNg^q@%SRTs{!(Khk3O}}^7CvmLb z5^FRegk#;vZe+1dcgRG7IbzR3k{^z~JyrYL=({M5bv~^cJx33E1^wNls6O5GewxK7 z*o)ZOlj7Px$e}BNWl_jr=}QdZN*JenZ%w1z^d+HvT|l{%FNEy&)72!$5UU$rzP88r zoPnBUAGnA?L6g@Vv=mNt05mwD{6s6hN6ophaQ+A~8A9Ks60FQymR;+QS%u7S8&L=B zNEMDzem_omf51g`e%?`c(|UfrdA`MQu|QU+=8Sab`sxe7){F_JEo>8Elt%s?L3_?ku5(_Nc zjJ6rA-7e8*GAhCHv|Fh12BPZk-|_WKp-e`9Sozy{I3N5O3LeO6I$mxRDw%j_aeM~| z<$9Pv*V`vy*ZwgU^LMAkEhjBQtY&$2&$^@7>Xps=_xT6EXr0~RkPn+dCVe+yQVDrY zf7{!BESx+A@IpDGPaW^f=Jmym&jXcCPgerPH5Rj+n&4KYWFY{@j6B670W>qek5I5m z7?DZlLa1xgAY}kRGfhF;FVPIy!`%m{B_14Ln-#=Pwp*x)H1Z|iR^USkER;mFcq3l2 zVgba{9dKrmq^LNzWkhkZyAdNvh^t8Dx7yv0Gd3=xCjL#B#W2>`+$+uFwT=z!oe)a; zmZ}nG>UOr%_i#*};0_h0Pwy(4w*C3uFY6L{qA@5&384o^il3wPFugQkJe(~Q8YfxI z@>i*Nm2Eq3IQ1#h3F8G#-&BuX8Hv59eqN)%@IFL8k|ve<^*(){MSC%8T2bS!rGrLd zkAj^^XY#?CjHr`pMcIHN!8W%%)hN49znj&eV;TGc{foJ8m`Rg~FH zh7($Xy<7m+nNw#)Q_PFTdW|D`sL>J)0jc3t>Q3c`e%f+(93#86 zV^VrKXWxQ~`c!S^rh{{5-pou0akz1!>yWP*d-C_n^HK9i+4+L-G;vQe+ZK#VB&XK( z^rM9~{udoTzZE94*ViHI$&7KwkeCnQ%5cSHt9+;`b~k4J>)lTxtD_S3!tma_Z%ktT z_|LdS;pm&Wjtln0eoxRie+d=2EET;jbEhRta&> zf&n|c9I+Q;pOBl($gg10J^7x~`_wX9jCw}3qobZtejU_x#r<*d&Ki22s6^aD`dvoH zEd#TEcx#4NZs=vhi(~o))+1jUoe?;`om5xZuakqsfVG{p`F0b^#=RW6M_Q^l?K0s` z#R;4&-NM6STaEWGr(@pC6+uI~6s7*E=b>O1W8;<^6CFqaFkD2UA|rV6)@Q64TF)a=%)!*BqnhD4&BIWQja3WQ?Z2UfaT^b?XUy6Hv+mCz5I^TZ7RAUiUX7WHL z7e?T&5v_1+5J0w&pWSTu<%v!0rb4Ufgg(wezTCaTv`l8bqJVqn&zLYK(WDnqa{(cd z>B{o_yc=pIIbj%n>O=KHbb2;CU!ua%y^vR;)jsHHdXke$WPa>k->hpV+9g!YnDyJj z$M<2JerPd`(%fc-Csyy=)D(U}-YhbHO=jSDupl7pw(mflbqpB6Ou5V!>h$6tb)82{ zy(&Qf8dGH96CH@Yhbhc1QBiCO7)OOwj5^;HAtEmGA5*U&aL$R*+XZPDR5RZ>_Roq5 zbT>ogVceRE{-FRCpqt$O{=gaCkq;#0(K`RG7OQ0>jXyG!9DgF1cM}E{3X&rQO?Qc! z>VPSj!IWGZ08#7UP?aS)d=O%PP}~*#VxJBbBk3gWltNJ~!+Ow(NvBwM}<*YoZ&Bo9P5cXn1B?k|k@RQc#5G?rR)dGB&7=NZ-fzTv9Jup?$$ z>g4kHhtMIE1s)6(byLE%{YLgo9;nbG;!vAei3vp(!>Lbnu+d2<@7)_7$SQ7UcDfs*<)yxNa~Mz)w};jdBu){mi0LMjz5aY-+mCQOZ)@wNU(5_TUzbPFLv)5F(DpEfT`xy96rx<9Jno+g8DMlrtif zr*P0;hk7{X_dRPlHcDD+VHx3|IGX?~&{CoT;w^>ctPTK>Q7a?*ycbCs9k8O?h~@F` z7wKOq>t=H0CAovauWEads^9agN}r()&6rIYU+jJ$+C2r~P(~|oIrTZk&#NRLL*eTY zTmMNK)_&wC;!IR8Mv#VP(h`ioAm<4G)g8$e>6v$KsqWG{4$cxDU!t(}5y<79G*81H zs$@Xdx}T#Zfz?hDK|ZSFa4)sjdPb~C-z>pF%Li_C!Nk!0Js5d?J|Ake3^oQd41XUQ zBn>@-BxT&QebE*GBu~c%8(3_i1-Bgirha266$X3+^hsMLJ+CN%BdNoJ zz{)|$wn30*nn@RFoc4@^-~Z8 zqd*x1sZX@N?y?5dqC8BY3vy$)H#?o#gvxrVGb7@d2)8T<8`;&3+53NoFICFI)P}+| z_QSN$!gb03#`&mWP@Gqh;f7`5MnmCm_QPK9L< zN1M!#F3J&}wh>m$5gxWEFN1(D_9Fss!xSUKf|Mh}(IP`^BcsY9H6kOmhd@NaL^BI0 zHr`(BFeoC*M$L#gM~2c{n>RB-lL3&sb!<-kP@%}^(^SOs|D{kVWvG=>6e5|~pd8a= z8`BaQ(^eMKZV(fgh#Gws-pw4_>l1zfK<|i*9WIL<9f}>_kDWw|n`VxiRgRmtja$5p z%>qQ_(Fd0A$BntGU)cnLf&-!T%aI)bf z>fy-4{m2zt^K{|~+*5}$QeQQuV(JHr4!;yXfTz4P6gufc-%iBgd*$BBgl9sEXNrzz zu0o`RZfAX9%iR_b9bv3zm*&jEdy*k|;pL+drDQ9DXL*3@w~QMwjGH!_?!uCpNtb~s zo6%vB(Vd#v+n9Nv=YA}ZnPjKMN{ZJ?l)}H9c@&oMwme->Bt-=^E14xbN+AnomgR7l z73rJuH7ol&ep-P@c3qT(mW6wkoo@5+t5!RY%;9vRo%DM2T%{M8r3YCZ%h{^sIUh^2 z$53**4{~)?az3=-&XnWMso*Y%;4ZP?{v^d+MaK;~$eCox>%Pn}mC02e&K@Yw^UTUS z9?mu7&pT(y{gNdVagaUC5`5H_d++;h| zTY(=gYXQD$0ik^XadZJ`MFIIp0p(!pW6~F!yDu40`5AusS=lMVw`CJE<-c*u zEpRK0c`7P-%I(_VS!T;w`zl4zhGk)XWh5^vn0da^ASQbg?0aUTkMJG?1`XW z)k;LObTGPdxT12@zOsw8atxztnzd@=uyWSEY7wJqKDugUq^h@~>K8`!?0waSYW1jS z^-gs4I9cWBy&cJ*E`%EcQpj+2dC}XOrG3&Qk>*+A7864_YqwD*> zf$XO2Aeaq259T}N#OzeXC0L3uKUnrzt{XM`GRObS@0buiUL#v^XzyB&a zBIAN~&v2-?q3`ms@1T&3TH?3l%@#(@HaX1>E6vX2E$(8_j4tfkd`K0yIm2$UAF$P2 ztr;ZKYCqZx+GuuRYoXXRgDrRf)}vC?+DskVLSveDM>S|QX8R{$%v~3p-==<`g7)_-?02upr_{)2#K`B^$QMS*mfFdF zekEItk;|`zxORb(*CB{F8ps8EJ`qJ=9Z@y{A_Ah0T_D>jtQ~G&a5vV3OABZN{-5#E zGZa7I_f56$yD{GnN57w7{(OloJT_`--=r^X{<&J*<*t>K```>hsO`KtX3$Pjh0D&_cVQ&9J zXfNFj4llRc9L&iF6Y%d`YCf?k`+%k60HQ*Qls|wn4SuI?cC(IxqGMl*0w_-(G((7s z#sfCF0}iWEVUKnhc=ko5a8kCU@$w>#uN@=((XX)(LZUYB2KGI6$cU8 zVczi&05FUI55Z<5Wfbj5(-^ZbXkCYW!*PGVKL%9jo#M&1JS7w5HYD*VUN)jQx{}2Yr_tT~r(W$P^tE zjIuK2GqsL2$ql8H20Kn+{j7B(2hS#1y$>q5Zv8b1g(hi zDIkOa09XRFA#eE7wqQT4`#eqg6rat|P|o^ntV20BD5W=uoS>u-KqkQ8pv(FS3viQ5 z%)kl7)r2yeY!GWg*{gluANuAqZSk9I;e6O)%G*qA$4L6?^CXQ8NSr4BHBG|_rG2x_ zh@g5Q0JRgJ$1@zw6VC%!9|$<}QgU;!2UG)XEzTb*1-kPpx!0egFRw!myRb&bC~+5D zDue%Bp2lP&Ph)GXkXhNQodHQ>?7QI1)VBG%?w42o)4{!Vfz+FZm^DHaA%M>S2#O4N z>YdxoI=qD!_MY=QiigqxqLkYgK%659&4U~kLc)rvh9lI?3MD^)bP%`OM$+}K+)O$p#R}Um6*cX4D$8UIVYBir-WfAYl9tvu$R}B>P#V<T>oYuO=(e>WhbgQh?Nr~Dxu=+aI=)7^#O$XR++3IZ&X=HI_@(INr6d=0 zY#rMn5j?(*%@rKNDvZuvMyxyu;-bDh7QYk-ycGFyDWT;}O%g(95WErJ!}}t@Bq^>qh-_203X2i4&8;2SgCxAMAW}vx&Z$PsV;X z*wjMKaE9ZkO`hgu=U+{R=zae_A8uA3s7x9G1wl#{fwus^!nzrx>1wk^;8$sgxe-S6 z82WBL&UV)>B5FL52)Q?fGz9G-b&vbDW4E^xw|sussC@uUKm4G61aLq02R;r@0&BV; zN3~eEdf)ORiKl8FI!+(DYKE4bABUu%nPpMA%HNXJo_7)+_O#$n2Z2w~)a?yM?d1R{ z8UV|&f#Yqf8u(x4;f7o!hEOG~HO>sS0JnV{rNu^FQy`z@N zV>RJnz)G%>%SU=fE~2g9kSh~9ahoBxuai};2h4BAIM9t;(__$W(ZJWM#FmNs3d~m$ zRW?hjD6G=*}r_tjx+iGMo37`^GpZ^^*ViV??cyVMwnhbdJ~?PtNwhF?8T zcYm$?bzbidCl~abxs@Wv&Rf(!V z)`bY--TN^u7>#={Wev%6hk`6*1%}G(KBP!gidC2c5Vy7)^ruB=ldoY>Y*laLt?VmELgjS}h@QII_1+}(yesNx{ zUrc|lutB8!CtZ)(^;o{=gY8&Cz*!h2T*SjvF?W>WfqzctRsLiy6&~`irm_3H=PQ$g zj_uY!udT4$fLfhiAyXraYMr&seU#767)S34qdC95Y!Hl(K?VSoWl*W@zGbr;ZJC<^ zmjwM@dcW~n@%;P7XDiLy#P6u-uSvk=y!YD=57&R+27!ruOhYgQZ%xDS^?l4fl6&2n zMbf4Fm`AfU-a%jG@&UF`b zOnpZr+70~lFY_=aKFX#jMc>b^gpF|>-}Pie5ifij4fV4f;`0_7Onc7w*>%ive=!A* z_Q+VJqKzqsY-VWplg%21athoz|GM6;<8r~@Swt&kdR+<*fEW(6GOskUMykO-0z_^w!Qvl- zXuW&Mhuav-gfY#bp8$Jk{b=uR& zMeNzEnJh0nhVaV#0ILULFHaj6V`)jJL4@Hh{31D}*m6cN=_83=A?24cOD2iC;f(T4 zid)2G6cR{PujGX(5cvNkHo~7C5n?0!{~|VC|4VGV{ST`V{`cS>VK@FuZ$zMt@c%#? zFD{<0u5K?bo-cP1jN^Z~jSr{$|E3#{j-K}RZuj;cwzr=T`c6(xj*pN3JKcDJfE)is zH$JScJj~C-mvYwD*8T_GxU{tNKlDcU^z(|4*)w z_qiPZxeW8U1o@%T^Qn^Is-mRtYY2j9tgNgoFE1}GEiEZ2ffu|%Fpls7z;%AXQ!#Ey zabZD0L4JPz=g*(>^73+Xb8j*-ZxRy`j3Yc*{yseXIaui^B=pJs^|OuQv75)SmG#qW zr6WV5D;=F%b%E^c?DX{X)YR0Zq@;v|gy`sK1lkxD78V>Fj1U_?eE1L$5b*y(8*OcE zt*orf&CUNi+Gt>4pr@zzAL^o}rlzW@>Y2R4qb$>v7=mtOIusP%<>q~6A$z8$++}8Y zq9)m zBO4nV3k%Eti)$n&Cnq5xAtE9oBqYSg$Nvwp5ekJO&_)OZf`x^Ja2x*z)CdOy5sc#@ z7>taJjD&;)27^H$5D@Ws007Y703aHLa&3NhC>lP7$NA|PrUIA2{}vl_|1CC}|06c4 z#Qh^S4$~sUMi@eD6v3k%&k>NQ5Wk%K{}CGvA1w-`5n`h%LTt>@V>c|eo}|+FnvM_~ zWqXxij5KQQ$T6xEkbN`mkO%AHT-*;0T0JX|M33Kuti@BF~~&20iZCi2O$yJt_Pzr zmaT_i3GT0lLKT@e!U*(jH^ToVHsXbJfq(&Tn7S~;Qf)V*m`lnwquHB>~M zVQUBgW!XC|UTpJ~p6 z&cDS*zoT#>Ps^jMHs77Pw8(a1#KY?xtL8L0HDZw$fj7+^CVO3*ekHDW7i{?fgGR#SWRO}w?w6jo%{fxVtxAId$&;i zEr{~5x^v9#@RZjepo`9PK#Rz~;1Mbm&34V3@zn_66QoOJ!VTWU|7 zLhO7mR7?Exn8eS3h6yRdj?aS>s2o>QHoz*Pp_3j4Y&H;2J}4gi={R)+6s(P48|jc5 zr1^>Gn-+!Pq+T!IwtuOaoF~<|`svv6DfOo%&8NkgM~)SOd1{ zvJ_oXILYQ7qh%#l=;T&9#)3h}xSl-LM1vtu0icYz3k0gJ^?`!$(LCQ&ZCXEYEIUoG|rg-z44t_MtUb44@7Hdm(8%XGbJs!e^(oE*w> zn)qfxzZOTUqYE{69e`@T5qr*)5Bq^nrI%O=#b{OvX`nUU;P)xpxmNX?!Yn}RMeeCk zp8y0a7ht>^>LL2Z9gd=n_6xvWpZum8rN}Q_To?wmX$1i|*CX-}#RhC$k}$F=l1Krh z{d(T3VwfMFGLpzGE0*%*0N+3DkgCKMVZSp}dSi`^3fJz{N)(1C+B4&e?Vce4ObTM`7^@I< zX9Hn;Q9cJeWR$;MgM?jeDt$n;wEeL%MRQy9?!V8b9MEm!6}iJAyPH zNZ_(WErAydeu1Q&43L&%9$OEQT-w40p!Ey81%Y51b%n~v5V-RF)k zOO5EvH33ijrXk}TR>SSEyzuRYxzZ}y8s1~*1=neCjv8Nl;ZF3r(-K78A${!BUou{< z$kbeexY)oAG5#{Pz}568#wLw#wd>_ym-lS|zB5<+k40 zIS8##5wt8)nmBo`th9-Ps7I88ypPxjwo2R$cCl-NfdgiS_VFCf) z_6no8MoeC;ewX*|W=^lwc~QCPkA4SBaj|EQakRuQJ4CL+`K&Ar;|bd%!Fih zo3zG<3#^SI`JKgrXm4+rIOZaCF?ODHau+^=HsRJ25^Gip%_=OLSED-X#=<7K88UUR zw{#xcm3_4^?iK9*)|ONNAAHy8{jny4e2mxxAe57$$)6oqVlC%SmKMnwTe!z7S1O|c zlUn2bG)_S(jf3n%8@W%+J#HU<`&Xpkxv^Rx{V4y6gpE&J83ET?Mep2=`r6s^n&0k; zu87qCIJ~Yd)u`6ga-Mrvo}1kFT5ZA?;!#NVNm@NZbe^=2U;!2>C|{RqE;TS;^U?b( z_bCMc1yd&~D;G0hugT~>{4P!PnyjrNLVSx4*p>TyzqBWLJB;`-(*E`tqbD?QP8vqo zBGdi~+tBZ=?plASH-R#_#cS`?!fAN3VArb&!Qd6YIbdzjn2qLT_R8Zf@7oI*Ydgu9 zJ(mcHM>A*yS`aN6J^3*T;9J(_$tSCyOYiE!lCQBZ5-~-0!mQgC$oDS7)F(h(koKiP z&71m&Um#}!G!9&zLD4lGnD43uHJoHf=Keh5b88WxXBxf4{c&js((#(LHkRjA?cs2{ z=ww%i8BTDgCVsa>64MxuwT#D`N8?84f>4c@7k5=3fhGXyVim>d~BY1=$c73|P zwtj~EFQ)D?tjYI(ANYzfdLS*}=(-HpWPkZu%Vz~~NX=>`#y7LgVa5s;FQ4v`W8 z5s>}(eE(1WPwvM%?&IEe-PifP&X?@-y;j)m_1_Do`Bbt*Jf#p^-~sE4~? z_uNER}w2=V-rqi`%^j?tP5Q22PkW$dnxe zUWh_rFsfZKz0>HGa*SB5)9^gTdNkS!LiK)xU~Iv|^vcg%UDI+b#xLZdjRgFC2h~sx z)uK3yGxbA8>L)9r-k$q`xMObo5^?c)n!a6{s4=QgtOV7wuIT5kyoy1#9|6E9i3HoL zSmXBigsX%CgE)|H+|yt2KBNiHg`(INBFq%*D033@YTcA!iEXvaLj{t48^q%Ia56+I762 z5J#rwM+25_HSc@F3x$8(4+h+)9{o@!eWF<(=Zp?->$*e_Sh5i*`bq#z$C(2iOZYIC zt@SNOZ`$gx6ox1z2}8i8PDxySVr<>ARla5X0_A)Qp}61f!@{zG`Pp9id7h+?ao2G# z`@zTJ@GXQslo1GQ1!GS^4-vQzO9A&{V<}BRxnx15MM3r7{K9YfHQfb`-wG=83z}#O zTiptpB?~)33-R>}ySfV->k4~A3rJ6+TYnV3wM3A-gcMKB^EMVm%X7WAI*;?6eudduc|9@|7#1StuUUpnmWbL;Dl$@<)S}2 zQqg3)=07+01(MELN3x|3{wePo%@OLUgic${APD>|a_>v7Lh35QEb`<(ro?`XGqp>| zGp`J%Nl{;l(HyUI#s`=L;=B7GYt~6T^A0kLP1+)XNE0CIX&kCvx6q5f47<{~{A*QbF5v;`& z#6vklgX;BjxDuX@lYj4uHLtH~D+{OZ23bRf{|+#{2hK zGyKL`8jc{-hhONERAcp_1xS*(=2uLG%`DQ*_4sYK1+SrkmJ=vTP*Pn_C(D1nBeDiC zg+JH-Mt1p?d_&vkr>)`YZ8&yr%K2^0T<(Gd2w^Sw7JvZUg13uoH_>V|d)OgsS!Y?; zU;vDF<_zb1o9Nx)*6z~`YQfiklH~cM{o=q1SF$sJyNxWV3t8r|zIdO%R^$0XZ{YZ1 zr?_XO5$Ck6(S>>U>8D>q7YBEb(sWG=Rkte`cUhlg^|Zxfxf^rcZSkoqxS-Q6zg58( zrxFMJ$mOjZO+!51TNkdka*1!pX}fFjDcovRYPm~aj&%<0$oIrtfOJ_ zjP=tEfnT51nQOhn(eBp*!mj236F=X%`$9KLiL}3hI{~<&{m?ZO0cZgD6HXx65AN_G zwiN`6Jq9}o5G^9$!U&T3W^hqIiP!q8`=*;ViGGD=?{>!9NuU%!RL{HR-nD1sbf-j~ za1Zc?5exuu)@PABC87O*d!x_gvrb|giN7KMCuA9#(i#H04JkDYz1n;m8QQPni$fX+ z`NB3TQ;_2#NYDTPsPe!I(uqOSzykq%LL{(pibz8Sd|3*^1%NtE2|X#Xd1jeMe=W*NRAQijwZejlV*KH z*8uq7Ur=mm64)*uP)_l9Vr+7MtRiWsJ*k(-#2SupPV-SA=8@b-KtOiG3@D;W0ZMWd z(HkGAD~ezxormj`s7@d1jv$&sGry+$^u`LlTF27e_^EyD(_?~B8tBB^C35@;LMqfm z+rvin7TkN-@%n$T)w5kr1%tPDJXr>s+EXrCwUKs&*` zsKzmD$ma<;80EIF`6ZL5`@V2b)@Mf6hv>}|*wvC~rWtr281Df@VOTgx1OQN=ig4J$;@Olk_$Ck8%<4qXrv7II(=lAN~RJR3e5 zN#9$rnp5=eQ|a@MuU7lDd~x|>+sa+HN6Z|GuqzT89#?Y1)Cvcg^QyXD;dL$KQQVS@=G6v`S6C7Re-xf*Z)At>@{71G?63 zdHV^Ab0+?+Y#e=B)gh-vx%COG)1);1i(MwtO}~@f02I&Cd-f}r;Utg1Xv3F2@X|90 zz-Iq#Fq3bd{rk>MyponzmIK!Q`=c z+Q*;%@^;Nc0!PqDmyU{+rNZ%lv5Ds`J= z^2LX7Z!v~l_wV17?LaxIgy8gD*6ya#_L0FZROsLTug%H6Ngxj%xclSMTVO(S*4I$DY3r4e5_=D&j1ht-w7-JWs>^PN}j@pZ!hij9|vrmQ`$w`$vKdL z{3v|4@bz`!)!CFCWIPpEp?BTo)m6Rp2TgM0QgRJ7*v(-hjGSCTGW`6?2zU=a?!@wE zV3&JI{$=t1!?OcLrf<6GomxJkEy2oDq@Yed+j@4F*!<|*_*wj0%6k(Egf{dMPI%p3 z@&0-J>~zeBu!Q_>-O!}ehv*`SKvDn>U_4suk7xqWDd)ifNfA8cV+N)Ao63n4yf!jd z0!;T}qb%F(mBIE{0;5JTiyPUFW-1rAJB*yLge8aBdVZMm*REPDkKY|cb9zXgL?PvF z7~?Vh|A~!Mag?$@2uaffdq#aFIF4T6x0-Wbu2@{yTeeev>)^#BZTisZuQ2|uR%J>y zOul};Jqg}CQXDyFBgzv9Z?#UKmye~hINOene^Px_!^Xp%=K9N!fllIlWx7&c59(1$ z%pdk{HYb+gu^rZKT$^{{j)87+=b!%`mv_w{U{8sFn&rjs3-Ri#4`03 zxcscFY{RF=Qz4T}fsG88y|P)6fQBcP6%hJz?>x2AWV_*wh0i;PKHB!wdNR`DQaaOHS%%Seh;kh!I+%b}DnCi(Gyn z(hI?kY|k+9KTxTSv`bHjGSFbJI&UU4aIY$&;n-Y%Bo2F`-tk^nDP?v{nLdztN?U~k zAd~3mjOoy?N}P`=ZWJj~VXuPFX!_xZncJByyLOE(M@zl{vR!B>MAX zSM)znq^w7o@KS7Ge4lA0zdNM?S;ervX=>eL(|>_%(&Q&8wi0#eU>Pyh7Bvh$ zhJr~`VsKBX^50knJbA~_eB%!Bx*%M9cg~gOzKCTuL$%+7u?pgoohlLsUFs^_`Q7q>b=Jatr}Z~ z_0(3IrlZ}%?B3JkUjMe#iRn*edeM#c|K^f*`z^@qy}r03O8s5P{a@={%{=G#=k=4m zPZ_RvE0#2pydvh_{fT~0DdjN`{SK0^n#%q@tTgkB+h3!an&N-?s}Z(0eWXI@RHhS7 zyPE|y{FjF3+>JB*5R@E<(uW1xkZ^4em9J4wV13bJn~ddS(IBQ_9o|q^uqFc7Qxd7G+>r_<{FG)ov8Phqd+rQ)Z3&gD zPN#-7vAD+5T7HTZ1)vZW1eU`Nf4exyC=|VtZLJVAbr&>jn?qDUlmqns7kKTto_PjR zmGw;G)|iSv+Y&rLcxraD^6rddsHXPaOyH!kJsSxbRKXGJ#n~6eCh$;l z!j5;-^&^CREGL1~(taw3$e3kkrf$;T-Nz*ol_E&jJSa~rm>0QK-K^agk5n) zjsG3?P&F!;sdO%3ART+E+VboQVsRygtDlH(RQj2xRzVnlw9fZukV^$SA5M_ow4|ST zC~5-0-D5~!5WofgY@;MTKBXNMsTaOktNvWP@g58Ty#<1_V#ceAZ&m=BZ;VjUp>C=%_xC%g2T-es8EPz`F5quo|4VUZ1%3V7BHB{&JQ<4rme6A3 zvcq#VGC&3aj7e5x*n{EnTEQ)v&Vi>gqU^NYZXY_4c{!Gza-v ztQ>5BXqH+Hw_3#dqieFmbj*pvViJ6*W2z(Sg3l45k8A$-Yv+}dvrm3sx{2*+U&j&ikS{pCzw`ptCn;n-`#NJ3Q4(E{h8Xr7sujccs zlhkn6w3*2KN14!B{O`nGa1a<2z%=a2T(qGp)DDr_KRXc@93&gRUo8~2}&O2#G;y*j6{n)hN zG#=MkuH?&@XO<7|XF^LhqZs-8x5`Q1B=dg=`_A-JDu}v91h6u;a7ng0~+=G+=P-^K5LA&*j;UvsD(&H)u^`1f)m9E zWw`KKRWH?C>0L#EXS|(%^?{_`U3x*{#-*T#BC>&pEl-5&6>b8Ry?g^(pS7D}6=PushP?KUT}2_On?+oEwm z#slPj5lO{?7@zdV%J$o}`aW5;R#hrk$RfJ5+FLlwHB0)M-{Jx={>SHTdoxGFkS&Z+ zdRX*hfOlOVEEYCIiM!D+WuF0NSlpz0=oTZsDS(X@YTG~vr^j&x_2Y$y9bkxG8{?(> zCV$tona_T7)BQ^NdHvyny!%BjYEhS}Q!NI(<{B*`QIRgUc&|bV3}uC#k~{>UaBs#U zmGuXRFtdX+DSB3hO+RkUmE_l*nq&?N6A>Ju!{dEzMpE=ii5BKK0Jwa@6ed6-o>)K5 z00qED#dt})AGpEzz;VqbBBS$Se}U1;A-K0nMKc@k_muk11v~Tb-|A@g*P;Q6C}`NC zJcJNQOwcg>2~U187S9JsCIcg<#x+95GXU-#C0uWFK7dcm(`KkBQpQap-Wz~}35kvv z%f%ockf2~6{HZp6q)=3fV5NnBY$;%=+X#5m@of9K?;SasLM17PR4ob^;FH5ROYy`f zHl-BsBrir734XjD8x|T9(H|Mj5gidP&oisY$HSLNsucWSNLGGJ|v)@41fZJo`U~#A(1frE8Mk* z3K)R_VbUf6nU{bi742Ig5o2+n@sOwoKJOS^n^8RYu=glSd^#zSct6tjF!KIW-RtD; z>9KprcwGtH7mDbRD=@$(T1YZpP+u8Ls8BNn zc=-GE7wM5p;D`DUB$lN4UWkf(mZ3sli)*$BWXQt_zVFaO06g+yg*d=ZLSoml;*6(& zo5FHsQ^T6RucBC5qbo<C!ONxrlB0{MkWQ#bTRjFc@-iErXzC#k{&?%`N8%*rSw^(fCT(+o zKnvl>ev(je7(OzjNA$jdVtdr9NZmjGqo##qkBHz~kxxYvS{TQ%i55um@8OO@?eSiv zL5O;=U6s8L>oA6Y#N*SHhxVvQqJ{v^u#ifJqmt)l-C$!j;`hWA==0p|dtEE_ie^wB zKr^jj!n^k~_Vd{QZ@0+$DVt}q&Y~uReit-E9oH)UeRLk$)I2Vv3x`*j%iH)~dexbu z`&m2BEBc|Lg=%AoyLFEyCf8WB zj&Bpx`s1E;McqNBu#P$tA`Jih^|pDmC#DGDQ@C;xF#0Rp+CznY5xtM(38cC#5w-H%zWW4Vw=HH=yfRF+4yXjOI+D3qkh%CD$+uHNKGy=FvCNXuDD@%wK&7yo+UtGq)M%i zR42jmQ+z$q|0*g97Ya;M(wP35(Z)K*4FNq6j5Oq|n$eKSAh*jzQp_r_&MJz|Dw$*| zsx#Xl$&>?U)nbgPe94%d__pv6FIvBrU6*Ko%Z`qprg>!$bESCDW%%32=#T4HBUTa# zlR4!5S#kO_9ph2{V9Ptqt7PR&*#q5zs^r+hj5BHN_1$?8E;GHIBLM~s`LS4 zkp%72ULjO(Z zlUZxIQAqbXCQzHtBAT_IzFH8km`yCzTSv~U*Mh>h&2lsuDjj?G9dSdua44ubiFW3( zUOQ&XVTqvAX;di~ylD0;P?&QlAp{*G0ykfPP{ubjMqAf?JDhy0t+XVA4|IYmq(|y! zEzCA9dJe_Q_TxP7AIxY>i6lxbFt$M3e@m+}&C^+WaTWP+8%JiWGxe2DlFD?EI#6#a z_W2Z!oP_*GxaGP}Qz+L`gp?)ZrDekTd>RM9wm%L9!xXfCOBk_8<29_<$2>ia3qarm zW%Fm@P=Xfoy6Ki3xt86mEh_`HbKv?;aEKuM%TeXyA(Qrq_IUCuj8{6YB?_#x9{U25 z{2C{9h|bD~%L>qF-nMFxpdR&*9D@`9O3PT!zOu|&2U}0Yd8|WdWaDY4;;>_Y)wRWm zNxD@tuGR487Q?JM8Lohiofsq>tb9E@Cb|l-P6!T(5l)BU!*SLwmIpYCHdLxNt1N%e zuf1u9X$oY{Ket|FT|2}1R&t&nts)Ko-cy-E@W;Z^UU?b!Gvlc2kg35Ve@9Ygf`aXef% zK$g?g^W`+VwglC7TsbiQkRE9mMrz6w1huazSj~dP`JCeVQEy>=u3}yK^X8?tSw?x+(ow|L685Pa(@%hP~< zh*EuN%Bybv`~I1ZT99I$b^ojiTiLRHbdxL$GL>AjuKbV4Q4PAO(vR!x3X%$0)?>Dd zPgZzY1v3E7hZO& z#cm6H-v;#<`+qOr?2383k891be}6dA=kx>2f6v5u2kX(aRbakC)?B=|x)*%xa-f0- z7jOhf0F}KG*C^B?9RIQr}m3ldkbl zhtx@YUG;dKsTf~AgrADr?`|Rk*kZ1|^EUmbAELGdizsavV48M4E6Ig^!op_<7PJ_N znTiZVx`VjPQSnPva>dJ~fS>@NUc5$JlUw+`0Xb*q00(;gU4NUiAJ5>JlaBjH9rh?M z?v2=^@m8J=ub*0>u{r=W92w_ViaS>Q!!pO^?XG*_sJ$pHKyZIUXUOBVm#tL?%*{0h z;~Im`XcD8OEO$Db?IsFb|IdQ-M4;vNp;(z@_ctSMA9ZYErncCZA4u(Qex7%omRrwK z2S3gG4})|ojWcp~$bjavUyU#39BJjp?X<=mIYkcj9X3&F7dCA!(V?vcDxtL{7N%aG zRlOoq69j8xyt<&~`jo?BC0%XIN8i2POvUP=B7+g%gd}jkhwr~9K3IbuC&8zj_EX$# zeqNcLYO{@>^Ds_doD6pp$=!31r&ju|`^-O&purY0m!7HS)^rfS>e-J!x?b;zJ#r)f za?!q|l;@$P^Ir`X@E^$JpHZ8zq)PeDHpZZ)u0mU$%RX z7#i9S^+?C{?s{`@$Jhk+8+O~q;<)&1srUlMe!ltf<6?DRSnc=65j<<3*al^wi^Rcv z$8lw3uV5N$c~?xi`o02t#;@2D*0|r&9q}^zS^!wpRMQ!LoQsZJ!hmkPV0;|C_#-kU z9eFDD@_3w!r#}qRa9AE4oynbRL8r*Z=t@_zqyQTlW`4?RyDw0mnd~Q** z6Dc2P{2oTS|DaJWJ}Jk~MbE#!=_2B;jD7MdxSPnFBL;)OF^69nn+5vu2PdXG+W1w8 zEjS06SxTzm*~VVmj{e~>oGDuPs}&k|D;NI|<0eXTHVPJoQEm!MV#4ajzf%Wn^5b_}{XK%R*BaYu7*m2yK=Y*kAlt!i8=89Xzus zUH8th2kW9=8fVIZQFO%#9UIIvyD8TTQ<0Bn3l0Uio;d40E6@E^Py_2?9!zKkijU=v zVXcz9sqFZaK7R1Q0`|e~DBPgZSULR`vYNkNaKk2~pW5Zs-;a$zIPU5g!fQI?XQbaH zB7v@_ap9#v02;?+F$l!vveNmtLw#pAID86Mz^pG$T@pqWxBQze{LBog3w)1T8E@eO zr9{Ua21l=^-thRTp5np)AY3vY*HgqG2A@huW`Cn3E|!d)((zYX4CsGiV~D_(Y8sPl z6rG!&{l_dWs%nud2bw-L$N&WY0m^A8MbwTQ0f7)P1c z(Y5H|B96}1bAr%co-5Do_P%SGk;yqQL5blH)U}qr2fpB6`|Rs#K%$1%iey(te8u!= zs=QR_&v~`j=9HzTjziN7+F5wxePXj6(%td$tux<3pXKe}A0&fu-uMba5JgW04#s= zjx9&R=0hx_5+wf^YC{x|Y6zi2@vSG4#V;J9VS)F}?6OwES|oUp@I>C8yw)fW-loL@ ztb3#9U)DUkV$ov8% z#dJ^N1M18ev4DMr_2jc}PZM+tD1q-0TO+SWXdm-ZuBHK;RF;XZ2YGkJ0p zm9{>VOa{S0(NX`gUS26d=WrWjvWNPm$S;JHgF^cl9-Fd^84L0E{cTczEGq^NP?G&J z7}!(_q2g&6sH_qhk-g$EOh*U0BD@BBOgw(6|ER}+IoA$NtAaabC9 zh2kxN{W=_wnAVj3uV;?GKW`aY*=Pu`M5nQc6FCCX71EOgzDSula_hOGzUqDADP%=A zhpImpoe!KI#g(6oXG#>lIW%}P)51jL{!PgSkjGCujk9`kT=F2rdnib$+2yM?XI?Iu59RqYe4Lj7pAzP{b-%@|?b(l|az0BzcE z%Ljyix>I}{7Bcj)u}4n&h%QAtXvhESbFroD^*7p`-=m)VIqnU1>`}in-_pQ;*I{#` z`4%AzJD+=eGWB~}WdR88dZ_1c?3vJ)3F_N&5FL(G*ADa8YB1&|;QlrK9ecFE-v$%P zTYMjJ(f0Q%2>`s9=9?Y`u>Na&qaMtHlQZ(1Js%|e)EHilGw6B8^2f;=6H|em{g-Az*{0NC?eejJ<2DL=ZX&oz6 zen`3Gj6A-}t}#SchT;3^+yEIFO%mV0IB;7NFFrEO&aofyGI|atT3z{#AV=cwf^tgS$Yg8RmJGTu2H9O) z^uq}-K)AM2(Mtkuv2M=<8%DrAMbzKK0|W*+AQ^oW@jlZBsnuB8oo(f)UI#{@Bqk21 z5NdtQdgd&2O#(+j_ZJZ$Z-9QXkyMxzRh`+$h$fX`oymh3=X5 zrXZ7_3_&ftvX!EQ;H4pJF!$mBSx0m1y9TDHB~mRrO{1dgWh1;ZKyy56YfhjZFKOmn zRHefMsDi5j`MCbev$i&}_BuDMq@~%-fc8e#x|8D#ocO-;wAVUyPrQ?6Rt`EUdyhEu z#Y4!PNGmPU-|+x?Fe^Kw+%MfraYUOP<3-dR-+=8RN3337I})!*My2rN2^B^kQTR^&CT&3kw5&ON z&1*DSv0{t*S;heUSbrWzBGd~UoZ<}P=kZ$^|*=IqbUFjVBq_e?ND{XRA)NmA<1t8Lbmm_$%zvq+Bl;}{j1^0{f zajoE#?ZTmR?~nDy-~#B()p-2+!Hr5jvq#9@)1U7)K#`?rI(GnI5~n;(p76fJ=E@_0$8UBg2SCHb zBemJGX%9UG5H&=vkjV1+#(%<&fWEPe!sN?w&47MO27A{Zq(gWSFm@C5{x7pg zhQaebs_Go56pJDtQO7zI2cT~fxlIpvc5<^ua5hIz9NvBCsJxjKK^E~EGi|-rwl{4E z$Qea4l1@o*E4*$d%`%VX{;^3lB%unB;ZVHI(~kj60o{>G!XN{PRKYkP^a=<#7Ko5X zWWxaaVF+2=FasDv%FY1OK>Qhf=@HG05*a2skqqY6_&llu@TL z(&UuU6f@FRZ%~^?(xJ;}`xxm)%V=8v*JM&{SHCjETx&;Zo{wWtOwhNUld`OSYbZcu zBuJwi)Kx4ti+oszj@d`bb`27r_VaXsbKuG+RReNiQN+oL&Ht=^@tUzBlvo@Yxe_<+ z1Iip+OUZeFJfr12lT5tx<-FgS_{N#Y$AIM9<@|R{0!y2Gm-Ygb%zOo3n6JuhHxwRe z6eFaVGfB(UCyZoQjpUAu zI$|GlO;#X1HZ+L6iCL05ikyk46u_)nhE3i2#scs|P z3GR7F#qdbGeFb6A=3by9p=O1;I)#bF3j;h$a5k)EszP(ALSuc)X1_vtv{L(SOKGxF zN7GT~d!@3F;*eF8q8Kn8Jpff*xeQ(94qanT+4RGkoT}TFX|06TEhzU_>Y6$!>{gmM zv+6KansRL;)C)*CSajAS$q89SpqXmrNrYm<{wlfD24+c|tbURDe3Cmxx^~GdG@<%V zW|yp{mrka4tf=b>Dh{O))<{MB$OhB^pO+(|-0A%Jw&rPM1dtj4TlD>G&RL8tw=QQg zCN4MDgxC^So8Ys#EmgV^J5y0B%}GWoG5{}u3JzpD!hV(djXR1f)UNx~X(LXpFFy#N z05}aSB$e#@~+!=M|V|rT|d@9)yS8yXmTDFDnj)KW7QT*&Rq#L zmQjvs)JtA$md?j!&4}p!c9nV`=j5)R3#y+?{ioUtzD=VfQ%P zi%@k$H*qL*)auek+Hfi{@HmpXT2Y@nL}%`8|Kd9?(T8*{e&zM!@SkZ1RUTaj4PLCu zraw*C>P^pBCF)=J0+E?d9OWK)syg%parxT;%!|}5Vf}vxqI&sidK4KNxFCJI zPu|?)EC2r(!OTpkSExp!Yr4U*B9){Q*WR)raRB-k8&wczC6ZBPt9 zOuY6$N+|@XDk#}k(#Jm;mva6jmQe-$iMhjnXGwBM2QJAR;k}I(Sv>qK~7 zb>^~o?Lg*eBov~c1ad;aJ&?4AA$+`FH}^h~(M$X8&T7ZbdmV9UHiRGZe4#vOzvIny z|EW_wE)?&kRNRQ{;T^oL?Izw_AuBQ@0=K@v;k;F9*ulOk+2pb4VzCMHY)|zJNaTa( z=~YmAb`i5|wH_`H^2XqCm-`(15uwi!wifICjv_C1y)q6N;A_>jYxsPPWKE}_$bCM= zY?aET)}zgOkDqe<=ds_v>T1r~kN}}B7Uo0pwL`~~Pfq+|_U3W+$GLvtpDa@Dw&Qqg z@{x|$H~kjlYd%O_VPoASLN}uf%x3!?`==}lvAB<$Q%hjy!u(s zX?XAnYsvq#>$7S4koZj*_+~)XDc;WpAokUlSTk*PN3gsA;d_3f_kwh98;O{0 zz_3pt|CDL9Rfz+Bkwl-CNBTa23%<`0{1V@1qk>0PY!}q?we&`2*YOm}ccBpChxD@7Hl}oG*g(xnuNOn7cbLd+?bJ z%=aMhr=GIUUE==`yd`qJgK(f|K)fvOrfW!Zc zhtc0d99-GK(L(UrQXZH$GJ* zdGjt`?MY{KlL9xdl#;I^|L1c}d}&(}Xf}+sa$8*hEqe==Fc;y8_{F~G&yg!2AMDgf zt04BVMp=$aQmaxji3F3WXCxh1*byKj`zCyj;Hhzwn$?lKM3(MrVUyp=Vl^YG_j^50 zoErHKgl6}Vd+raIe=B_QIUj8qJQmp;NZrWaR4*EEJhU>?nl?L8Hm?{lPx4fwYLRF5 zrqyEUVtA#^Co23}#7M1OmWp1Q#zt@-YpAA;zQ<4nF51n+MXok~yAg^7<^-a`-;mQ8 zXfuia=DK*?5MaeD@j1tUAlBdPeKembHHgfxU%JdQsmeW=9n zr@sqY3j;Sle?SjZPun0;dP9rF09=P0)o0?F34FxY680Pt3t#*G@uPV|F3A52-5ZS2 z6X!OP2z-2%`e3!@dwVvkGM6^=5uId0+MkpYOz5LuS^mO)znN+I6}6juP3A)+s{Zb; zhZgI#pexGVS480)%J(R6)mQtD@I;w{*0{=*I z2@P74d{Th*J2oo)DY`DJ_-oVAL-StB;=#$&50%rcf=zo8)h<1$UqwOlzpP!F6_V@a zdP!T^Z_t0vU4@@9N=w^CU`4L+1C(1kOqaS7e*C>j|D%DXSM-Py>m8CdR+1j&D`$Tw z^Sxb~RGGK`XBRf8Kl-9Rg0JV<@4~lF@gD@v#W?xD3GB7Kmi&3$#6J9NVBq0B?3@=R zciP`v-4l+7bSjyE38LAs;CJj{DL`?eZ~C-&0L~(?EHXMn+EbMoQh{yl$?fR4o)jv5 zrQ8#2Hhu%QxM}~>qu3nHRCGH?Vo8We-&iF8V}=~9x+c66-sh9j5)HF=Mbp6)_%P8o zz|${}l&Ajq4~surf2siaR6T(123|$V=E?LgR|PRglly@4Bi;?Z zh6v&HONK=u(MZ`@Y{>`l-YYqoMdIhawhg2JRsM;qC!4kVKUuztTX3sguEJvss4@31 z0rFi#@AZVnPZn^{F&imEj;^3B@jgw&SJTfl0Bxl*5{PRk+V!8Q_j7XC7?1`5JXd>v zt|xzC_Wr_F{!&Z+!5Hv?h?sm%;MqH>pAa3Ri0KI#UV{D&?=T?ibYkXKUGK zUm{fJ-v9eEs|}nZwop|N03a7R{JH2!0Jx-V#$D-lN^vBNLg%Mnl$4XG1f6HQG8{f6 zN2fCi|M^n#D2?6VUTn;C(#qwxV<<8g+<7mH`}Ov50fGCh=yK!CZ1Vuf_@=?asXo z-a=b{zWc?^7UgX>6i3Q#N(k`&TnO+xmRa;K!*ntP-9Bqkn1te#DBRDl76iC`txi;WKp8E+_sW}e;r`L*}@(_Q7~XpuV_aG9HV zXnf2WdAbttAK5sPm;)WJKZwWKI5kKhIN_tnvW-+6B2ggxrARCr1}Smsg$oWc@4_5Y znT?IHr1+9TD0mr!s*Myt7bp||A(dFH-W42<$pat~dk^vt1V5G`BHE@EU=AK%KNCrZ8BJ1aoZHicakynAArG4Eb%|UW z4L*p_u(avp$l}j1nh&?I)4OJ`obe^HyfUsTisCBEOHc1s252b|napaq9mGcqj$VDp z60`!WX9aDZ0&{)X1mFtFfmXl2Sj)3yEZFjHrzhB){u+s=ZaF<5K=Bf`sVV)A7PGXH zGz^$c?&&pM#t`F;7e4^FVvHPn7Ux&|pG{C!h+^=$WP$3EH4LskXqb*W&FqVB&m&K< zFKkhgBBUeKg{2PN5$pj$`e7GYl=5-Bt(4Yrvo9A7fi`&cFNui<0o1w?ZvC4X8mf)< zeaD{-KI4)?B_?x%Rm#&HPm?p^1waE8czKcfi>mQ!U@6yF;mj^ajIP|022LrSCM|^Q z%-%{hyJ^WiCv%>Ahv8x;R5#*X_=5!NQ&P4B>Q2~jDtGVYU;P(rHioW`W7?#CHe5XX z@yJ|GM;)Lo!Rrj^#pAy%e|xkfWtKCP^WbpQ!3y#y44Uu@UmCQ*}p^4 zvO^!^Oq!T=(2x)TzEvCtjd;S3?)R2Y^E|%f`hGWAd3j67J-|-GY1}IbmkN@znJRhl z$nt#hqSwVDVlO@Fp^e% zCN@XY?Nz^ce#=q$f(7TR{}E?P$J*9!^9&S zZ4MQp5j|GBez=2Eta=#c#*%mA(VY+Hr?wk* zPQ71f7GO0@s$?*OQVZ5Fb;dsfX~CKSObn|IgTwJcj2w=ok0|gSSVDH_IM>HmLAcSz zlbH(1$_dOzU=7Vng4B#&w< z7K4%VG_L(v{n;rp&&;1yChY`9YT{oQw>;Ia zH5=y#-e0%Q*h^7H(7!mjDfk0IpBB<0QC`ivrx|fQ?B!2*8W(zeYSdO{6+cQ+JI*D( z?>IKC_U2u6mP`Vd&2F|n%%D}&D_lvb6tj<{cw~lqV_BT>nJQrWhkc|EW@7`W+VyhH z^5^L1Q4dE2R4`qC8m>4c=n%-GB;dtqTSj) zb`#k}4!kAhE^L@E%j%blvL~kC+3jMb{+)W$t4CR6!SB|zUXUNS$XeMF&ogdudvI&L z+WO+_({SH&9&N2GsLF#Q3r-;}Usrr~smjS1)bqFaKWudrupP{XTM<9e^XgLHT0_1E zcz=96Ckxvl7c|u-6jQ-5d7nF%XWf=PP57j6yud7vBPURau8frbNp7zyVa0FIv5!{h z7cs(%M|$f-Wz>&lCBCbO=e}HV=7x+V`nEyp{?*8=MEg;n&1LR<^OWXq`5HP|?|s2E z26|aau~v#JX$b^jih#7ot{;RMdSk7Mlo-BoC@WsCr#$u8B7*1t=~n%h=Hi2pr@C51 zZ1SG?vro=RWnc3BmSwj;DvzVj{7v`vz?1UkdJ`7jW+lf{pT0A9sOosvg zj8`EJK_&U~aFAE2D-p>|lSr&%9+fOAaGp;`#}!#U=Emv=qckTG=>RZTP@H%9rG>xn z_uHaB7X{lv2i}q*c5heP>!yg9k9#=6e{J6dSWBFyh^bc~@qa|imO4Yjuh$=mnaA^? zeA6xWL5%Z0BTFuQil1>unxvNO^NuDhdcmdN6T1KW^*d%`3Nu$yUj$F?!`DkmZnKox zC7S;VC7A%wX9UyAQp7XBz~m?(IZ8#mv>NVSyNTF7g(#|*rHotcA`kB>grf}8gd{ZF zhp4R%UrF68G4Eb(e|lc%*F(ti=k)yuoyV7WlKfha@!?PVSA!%SWu^uEjQS`#Z6M=Q zz<*+4ZfE5M+ zNTC_9D-{3~#Rx$L9g1a;2!J2{szTXX;aA<2or8}4bl8pnbE;v)6RsTX*^&H3%#o=% z%(W2qkiE=~SCdwl(ToohmdG=Jz-&@0Ot=dYf>nP) z0#oR!KP8p@zO zmDql2@Kd!EQUw92o;g3MA@%P+$`}@eeS|ifM>C(^1t$`)T9H4DK|ugfcZqob(qPcr z-^+-P=hJtI93X&MG{d|;7`K4z@fpIdJAbslL0a#dj$Y$pCh8z1 zaaCa!kK*yV`@V$yp$n!D+evW|@tRccuRppWPn>7ah($B^J% zd$E@yVt2*?w&PAzSel?!P^A)a$Dha4oXQqX%2RPFeqU#QxGMPC@!p5Z5mukEC&rc} zI{j#80S*C=3dnthCECXQ+TBFH)`|4F={6&|soWICf8df6)wYDC@+qr!U5gJ~pL4d; z1SwD{)YyUArHif9&qcHh&2M0YG;CWEce|geQ-N-{5seONmsN_4a8;8D+G62nrB;L& zY@FR4Nv6Hx{wo9$_1+g$xyr8JU?NH+Z!@_b33`l7;v1_ua>mqXlQef~rIJXb16S89 z3jvLwP2acg0+Q-OUJOONP#mdMP~urmeWA%nZSb+aiREv<%nPkmtk&HaZ`3O7a=D?| zmf_BxdU(D5(j)Leo<{u;_lW3A!wD6#GPRi`1r?kak1WiI;L@>5Z=_Bf?VXx?6P;6Xy0mwc{2AGW zxQ7NkEOOtp74Swcd;DI1SAFW5B^Jn&hu@s4rbClF<<4@7 z^{h}~Vh7o0Q&(x-N1e&Kz!X+5U8jXl9{#5nlv1{xtg{ zY@ZRrA`fNSKZX=O6xI7E>E;>gct_mxOg!Y{tp-!qXp2z)wa~a}No-e08l9+3V|b2) zNR~uIv1deWpbV-Jtwwjp=MOE3X=G(^@gf!;)DA5&W18eLLyQ_MZFSK&PB8CNO4L=luIOaSS0D6OB;DfRi(O7q_H_g`Pl16 zX-u=Q+wh01Q9mb*a@dg%wf_ zH*cEJOGIY+y^`M2DjwO8)bCA!l4pUo`dI|a#!EE0e*=r{R+#oXnCx;$vQn}IJF_V` zPRr1=SDlzFpuFuZl~`gZ$n z&aZNdQR`Ub3pN7Q+o>i8@1FfOP>M6CjJ_!P;!#XEX9dkD&u{*8!En3Gpr*H;%tpvH zY~xmiK@mkkjkb9mt3reIWhDiWs)B&!2LY`M3iH6*IgS7%cPWREeopQEJn}CXQUI&M zrXH~=KD{iBO-`en%^yf-`#?b9X$o;OW8xBvdnoO!eN-H3C>wEU5i4yulz`tru%7Oj z^{lARZ*ewdbl{(>DbMg*5+%N2D^VgA$7z9m$8-l;WQQ}}jLp4K`vY4NR`GAnNU;7b?d8!~jHP(wTITKh{67jGKVN>k5$H2JoTeL@rV zNY}vOswZQBcR800grY6#_!Merq%qa4F4Mh}(7>2mcls)Kn$dN;JsGUEWeMQC4N!`tc8Ta^a$1)%HC#s_z%#XYUXaS z+=z_`OFg(kqTq?K*Z&63%u&A9zC&yDg2`T`j!cUh?xv>j8^C&yL(cR5^G0a%*LP#z z^Mqb@Fpr~d+tRdZGe_YF&j!_*M`PP8blXhkS{0Dj3EXs`#X2*Fz|MOD+|k*Q1>i~XYVMp>@QO<+;~ua{^x)=iL#t`jM+M)eB+GV z4jGQ!AZ5s_3eKKKCb-;h3QM<>__4`cl=O_I+2LpVu{iwQq0y?A+Pt1~at6j*+yA z-5?wB)61-}_e;MzWX}j0K`;|2HBJ@t;5^AUgV;62bm5=_OE#$Ol9)4m?wcn5x!Ego z@q$*1^?{Ed>aS+>dW*}|{}3Cg{>hjI{v$SWV!l400k7k41_eJV1<4T&2G(L-vw)HV5g%9qalfMHGT_pJd2IkB7}De~VER zVkG=WZ2URN8$D(IGr;HWCCv8j(*Y@?n6RMM+FPHEzXaZPguQ3qSRj%eYw&&PF%dq# z6Mq1cyP77q_jvhk;alX{-~E{-n#>H_)5XzimKF2DyL8;_*&jvBA#$*wVgql3wtHs5G*Zte4eSNA+JjkqZRR`<)y9`?kC}@oDNL%UzA*_TSz=Wp zmp?{Pa%NGjMaSHoei>eHezq2=SrG~Zv>e57g_sfo5UfE-Gji{gxHYqtISl zL8HHG6g0d=QE)mjszrB2?P;r)xO`_YB~>oszN-DfX7Q^&F7gs3*Jg&j(jPcg>fn;- zL;;6}pNfoAW#jbk?ojwcLx?rHf%t{IGYzeMv$h8E@#=bBd)l_YVi}{gg)XHIU+8v< z?Wk{Ht&CqBy;>L>NsZY^QVgk9=36*6{Nch{?cRK?KWs~opJDw|AA1oy_9Y!e*-te} zp7Px$?&nLf`mG0=DsXZO-?S#BQ#*Uh$8olw>)gW-%I@fnyu&SIcM>mSH^>j?`Dzg9 zM)0sy-K0Ea%xvhX;m{Z6YT^q2?TgfIcF7!wTqKdh$;drw*^D-qK3R_+FhOY1q@KET z=k4c-$o9p6@A;>?M&CE2_eaL6gUc)gh#u+a(WoFEOB<4%CccQ^XyoXv zlvc|ErfXHYnOba5O=Am--K}606_No;)~^vl8aJ$(n>720lAE*ND_T`M#;3YMbyXlV zm1v1|Z}KtAo5F;Vi#$$0vcWNokVyd#6_=(r7rEjVEy&HVRAugE* zIH}?8*e?)Q6n+|2q$yIW9cOCryu$qJH)~X2fyfiB0d@VcD@Y>$ zs~1lV1O=Z!$%&X*LIi8?veDahW#3(){yxYl#6y|C&3Z(C_x%aZ_2a_$_5$#t+#-Tq zGjbJ3HTMdsw0wtN%xz1$K2$AlLObhp+{y@b1lIv9|1Wt)!4Q9t8N*-B-g}@Qq>kej zjE+TP4uZiZM1yoIjn4<8qJeQ#NF{h`<~ zRwC-XmKkYZ|Jw}F<<93j-9t3(J?D=#Wh$UkhPRK#`g(Q|1HF2kUt7&a> z<)+(c7Ig#3BY#2@ML%>+(?pMF=;+&HWg(U{O->Ds3Fc_zv^*kUB#DwQ<|xYEXN~DsWAB3)XU;2M-RlT1*~3T^eXw}T|2{Ukw5s&upRSw7q#?q2hV&p5P)80s$G_6#jUU4 z`FS(e?2!&mF2?)9m?8XaWJ`Z)SclDQ~f zp0WBJG3jx!YgREde`5h&#sPG(#4{obVKSqju&+gt5L@G^u;_lySQ3@Ed5PGUNnr?; zNN8W&WX7~a=ld!7dC9&C03HDF!A!hPPRe_)1fQK0 zf5`;&{nX&56n5Lx@Z$KO;#2`LAdji&oz7&}rbGtGsN^P$<2fQlLZMw*0@TEdZDPr~ zPn$>2@)u;6+7w108F9@?eF>tdqR%*>Q!OB)#rK-#-e+mtp=oVmEZQ-vI8X0P3oY}C zSeJ+?IS+oT|LF65n&I;g&627=$XG@s8QW)E`fb&}*~a$VH(xx@e0pE?mH_zHGS|9o z)|P(OZdz7BKvv!w5a&d~j|K6!15d-V&x^A!`?9ZhaM`%<>|@((fGU>Q4tsqcOIm^@ zzsM%*$HKumJj+-L)f{4}9O{T1kU=(me-48b7XFR|hq9nn$-T=(%@&c27aO_zb9r}j z`N1CrxjqV~=USWQibs58@CR5g15G{=GK2HZc0S6h<~>x+W46nC+@FI-8>##A)EIK` zXd{9vpL7>!U1ca)l5g0Lm?Q%jU*wOI(U|V$zv3#ecvoOlQXpQhBGIlmRTUA2h5p6B`jot%ZagnED+zBd z0*)5NG888m6sM#Y1LdD91wU5}E^WNW&=OJdxum2+6#-m^;IK}>6=1Ufd`fv19m(D{mg+_mMXdVowe*-dDfhDF`KmzS2=!E*+NkT zY^hwJ0`CGy`P)ekN67FE6cYkaYYbtf0E`KVNXL@!YmhXdU}a*6Ml5+I*MDo$)LVy7oe^^Ys)i%7hKrlQz`jl( zqfS^FVcJpwz<|oIBqAE1Kka093~TOX)Oe{j26Hnu<9kq@$?E_Bi9@&y_Vo_BUiB|r zQ~;5IgkEnHxVO&n197o{Bjby(xj505qa=013 zmA1A-HkS-keE0rDJPQ7SL`-KG&DuBa4SaT|0I#A60Rkl38X&--VKO&j14&NYfg>nI zz-k8wx0Zp$pPI%n=J--j?tgQQbItfNN}|y(IC6l#4QRm>)^I4<%z?Q6YvS0_{>Sjk zsWjqZ;LDAn(QieQlVFpk1{3B%dws@E=+jOF4}x(7>H+|GJOR%LAcPO$uK)lN83d@T z{fN607WD;S+6h2+Ny&UBk|*~S?I!)u{xkBcJ`W9%)4!y_k=Fn$V9k{LUOOQB5dQtp z;^+{*i2ia5|9C!W2OdGq@WG=)xEBqB(f(J{|5s-0IU@&OEJNR*@g=U%ul3fzI16bG z2A`|1W{_`IQ9X7Lo7ek2d?Xe^V!5#pK%7k9OCwyL-_xE{nQwqYaCl4C)CD+wzZ<9V z;;jtAv#j@ne4j5*PchH8^!a`u#n;$+_#68Hp#OkD+28;ZwXX)ucbPDx3Koh)yuv^W zHX+T}&qyaiI}G`>lX-~-`5&$tfYYGIhu++k!4aOJaR^{CYG_slF~2{w3<2aE!rx>7 zudy|`Py2VT21jLv@UY_*W@v7HXvxRiMakMd#QL4P1!mqlr+OIpbNKM}$Zsan<*GUl z#sR`=g1Xnk?jHuJm`8p-9XVoZ#HY*DLY|7o+c<)q`o(Zng!q&5^#hP5l2gm2DuJz(lqy|=^n z!+JzpY-8|5Y4`h~@!8+NDyNb>ftH$4OLZ~tIs)(%0KS7JmqfBiB$?M&1M8|_$5l`( z6!W^OV_^Yez=cY;kMODz>C^z|gs(W}rkpR48iV$!AP9g@+ zGa%ef2I-R8e$H&mm!I#6o+r+ke>31WRNhk6qCJr52&{H2a9#j9&-b;>8*MH8R&qQE zaooo`%4X7UK><7E3j^gi;PxaTZiGzOsdvn~`j=_ec;@HHm-E}13q;imfU2eK%_V?b z|276pY_@z|@OgHXq0Z#FRnt}u!wjm?PW~AQvwL8aHk_$Tjl)AzKk( zM76zkZ)LoH2)7$yu6<$nQI@e#0J_)F7WIVDgB!4g_C{*J8$%enUYFhGQe|!juVIP` z1X?mRU>5?ge1R5jEcrGTzJVggzC^gnROT2|<`W#O!eHxsh|QRTT|UJA!NDQlFB35N z&nnm_z@vH(@4~oWYsLp#SqFQI2ftW;5w5(ey64?*=RL^40RQrf0{1IP4Y8I{K34)> zRIOa)VnBZX1z7$?>4)%$^ikx1W!wGYi4`h9Y!vxB@eMgGn-Stn^~ZCJIhB|fs=y5x z*t8RFyXNS#@_hT4Z@I`JT;=QZARog#4B)T~4|+FdwiF_E2vh$~kEcI@Id2!_0nI4r zf~NVsNvnEI_+L}-D=gXZ@^F3iKsO(wM+ONFIS();Uu*rzCySs&Lx1p{MB@Srkx5^{ z0B!)RB8tJr#AjgzyxRWZLkG~V$I2j<;o|TFI0~LXF;hqXc#hKxcz_7TordxEEJ03U z94~()0j02)EtQvhH_%!{TH(>3i^t668n9cR8S{0fiyQ3f1!2iw$Tm^TXtkw6=TADZ ze|;RT!zuxdSSY8{<%&rd_aU@?xw_*`X_ql0a0I-Go@+6Cvt95;QJt~=a35HW1LvDC zoaR6_y8&O@@jJDieePK=$rNF(Y41IHpLir{U7Tp ziT7VrSkC;wi;X~CbYO$R*P&E~%W>(twHMNnlA_Hng_{Lnu!6j*MZViw+WVZ>S8=-E zik0*?ms_V3U=uGwn0lhlw``-x0ok)(kNmmkiK;+f<3;xr*p znJiv;9q&w3S}!eLd!HR`d@nRvx_SQ}u@OK><%Iu45;;T>Q9gH)Ct-9uln32ObW#9w z*Hy8H@r^q@gh?M)b!yhgD-)B+i5xwm(ta-Z8KLWTq)2Cxs3`zMk%h82oJnxPoOa_j zF@6e&u-G^I6kC+RRJ9N^#C6Yt;ax??N|gPoGY2O?WT$||Q6lZ=i9i>X@K=py=RlH2 zyPAY(`eT*5qz?wkZlQ%PD2PcPZ8kyJz|U7U3-Z#hdIyY4^R#D@B<3W~A3FCzfZ>bZZQWYmPkKg=e)W%mLp{~Zw)?H8bmcLgQRtg|fk zLG)Og&r?OSR{K{rJD#TWkD+;4=Ul(I0|P9RA$=bN;uc z;Msp^f*0p!cwF$`py0*nDei3l^z`(<{t1Ni4va-Iq`d_%<>@03R=l@3*oS2xn9veHy|M0Bf7-oEYd~9s&$B!TX zg$sTk`romFXT2T&$bvmR=bfGZO%`mp_*Qh$g~bgzUw2wxe(}9(v&PGU=XG_L4FOkm zDmQgP|FD8RJ^$ydAg)XbS4fH{18+*`Zwg^I1td55z_YTnt1^!1;#fQ`SYBTKZ(J}x zKmQ^#3zxzFJ0-Os_kS`4&tqecVq*U>1!K%FLPM^6d~Wu!ItfJKAP{n~;de-X#spfr5VOA6wxklRsh(P%P}Q5c}3u6V3a zsa~z!LVtbfRHbQG1oM-IvYA?A#YUvl@#aVh(BL@r$)}2i7SBJs3wvErv2AEV@`gDD zbVrs$^zCOxZh~u>F|12bJTn{{Ne{X07yAyg@uuLzNEWr`x}C8i?NZ~R=K8&nf(th_f^ag97Z_@O3xZQU}ALX~TnGdGe|No6e-d7_+|oZ(!YmSSQ) zqlJ00J8qd~Q&7B_{@UEr%J+W%^eXyAe;PKGB|twdEB2@_HQR4BT>qiNbA`jk~|{BZ)3yb-X#`Ckj<{dSc=(=e5~lfaqX4W zZIar1#BI_>aRX)B1I!4`E)oiW;imT$GH(-cJu8t5vn$Enoqp~AT}+Huq5Q`?`|^4B zy`P_i9K2svZ2nBgRLN1aXw{JNa%q z8MeF@N$*^?Hoz;_?F>f(`xJ&4#4XL$VI&0RvA3mzfa-mH4H!6w5Eaf$g_L=|^T{Nf zie31-5L;H`u*Ahx&Z=Ow>h>pPMu+o_)E1Sh1eiQg34wbM-^F%b%A0rFB%GFffJB3m zLnyFENSze;_ZB%oaGNp{^(D+)L$nHF30=%eKT?MfSKE)^{~(Y`st;XmduEM3;U8aL z)X6$OnfJh@p2WwIU+k=>#5V7?)(roZ0f6Yh;)E0NqGZfOeT>;JnFfKX8ENQji3>BCo& zhc9X7wW;z!@(|fy$gh}?J1mVI+XTEi|1t$RI|Vp;OqY+oaufaT4C%v!5UM1@ZmLO= z0FKBB&fG_X{$zk|bJ}N#R8*zgW%pG#Bc=uO)UA-wzLx%ximS-RLFFD*gC91DGGK-l z%1C=WCE&1Z03jyoB?foXteic>Yaihf-Q_IdBLtiWR{bJQs}MmzH@=bu@GQ!Llq-zp z4@iYqkt8A&pujHAJ{oIbBM@)gZTv~dtIy8BHJvqREJ5b9`(PW(aC{cpX(ZlHKZ$t> z1}I7#I>#7Mtsp;WJeIK$j379{((YD;iu1AIFw|$aS#anXR0x@xCC6B*gJuB=I1=Tn zyqcyE&%ROPH56gsW;4#y&mkLBK}sQ#3sSRD&e>q&J$}f*kLC<#-|e7$d7LlcVB679 z3`lcMe8zIIt@>D13&Y?hT(sRQP;oq#p;#L@?PmKlrT@9otK)l&KQ$hc=Z$F|jTU19|k*T!-|xqONRxv5neZ;BY^E`t0)(iJuxT@CrE)RmNHm|NtKeG~j7jc;WxOJTS zh>aK`%RCiC6irm>;W@uXsV?%B=h<(cmoi1&pOd6YrNg2J0@pwnXQ`}w>c$yy&1@!3 z&mSvR$M-_aI4(mvNuQ*0veHzCzu3o_1N)|Xq^uB{dV$EE~YzmNjksAASQ)yso5bR%VRTd&z?mT2~O364g7$OEJigtJt$S5Cj7|RF>8kd-^ z4XJ&qt7C5szL(D%F1lx|Bz-a27VM^w=E_TG*IGxMFaQ`^rck=AzY0rFx5}%7(Gtq~szNq<;M55U(InEYVS@~`ruI}Su zjGW`klid=^snGroJ?&4>Jh+e-_WVpg?A&>{?(LT%HM27u7}d@)@cCqgy3%#hBs8se zTPT<9`+|$`^zX)4>5bm}^IztTjpUUQBesr2yV)c#>O6S3%x0bUeHAU zRq$C8^^3*oQXZl^#eM2SoM{^a=wA4z=lE}Q_|LBRE4@WuQ~O0}+VqS2hS7SFpZL7# z4N&m({y=z_JHUkX)}5Kqz?q()$JIpl6bb#T0^@3JxFmw~rrm{;^sbLswSRjPyC5m( z0+6W|3o8y^H2~UrAseCo`ez|jbV1|QtN;X4R|k`)#I0{ROkUHWv@1*_{(fJ3Lw*-B zlOvt?UIjeYv%IhD=7c*7v)Twqk`Hwjq)YY;_gSG$Z46J*qYF?Dd3NSM)!{1F8z!sg zeMuT#62_TkNj3|BA8J5bi2zgpay-V?q~RK;q2dsJ|(D_z%5UwoaX&SkP@W+z*M6IfUCfS%u>Va>^Kk`ml(zcSG#nWVV>Sd$Dnx zp(he?r^>M)XMn#GTn_C)CO{}6p2oe+G43=smPc1_8zXOiEXCp*!nxJahB>8H4RrFf>L zylYDFnMv_IPeIeC`l^r-Pm%_BrH1XKM3^T1;f&KiPi-)d!@uAqOi6OFFgZlBg?=*f zemuKmk|uo;o)y%%ZjH?Qy`BIG{>Q;G;0LZA@Z5J?n@v%rkKCzE@@^4=4Z!r` zyaH-_K2+p?Fq>k$vkke+nYlUbGZL2hyO=qR9c(`$o?8Wf(;mHc7(Jl@T~p42T4&+z zVhMMn!gB&Q{$}y_q*6#`BhuMscWhUk;Jb(9mnxA}Bd|XhaygMKP+uVET@=LbRR%%u z52XEpWUhl}FvUe~yjiB3UM`2~$6%X}a{eKw_i_)n16w4$V#q!!*ij1gM@pn;J+?y= zmD~!Ia3=511=43fl**UZ%p*+8%LV0&m*h)VgJe%#)n`8zr6PDu$@ewjb50~>5;@Oj z3kc2fzex&{*hPs(tH zXlN3KGwh<+sj(1Cv z{Q@p4NY9TopdzAyk}8#zH~V6b$cX*n04_wOQ-y;|>3Br&Btyk;SJ6glxko=8TTfJq zL0NAonyt^esMpS@9olKwnxUaYIxEmrAF5_P&LP9KbKgG%FKWQo55Z?_ z2pa(8*D~xgiUbeSO(NjC7;+&2#A`J4^bi_`y~R-4u+`fDA^$|2Uca%^L=va_y$WFM z{Rx&%XM=#vwsSwikUKjOIxIsQkqG8?SZx*ILwo=lK_S{+CXNRi(NLf!;U5jKtP|PA zAqhCHNxT|g;7^=hYX0G}TD`Pp5ie-B=FNRIgkyqLkI{5z%K{t?g$YM zVj=8^c9>2ZxV3$9pi8=yGVahJBBY(HHS&Q0m46jf*rkI@0QUI~;?W`WvI@R{mH}3i z>|o(I4QTHwG(!O4bO`5BK(O^uLD;(Pbb<#pKoYH%gsu9{423SL-O=ENLpuZ|#yD1> z+f3Ty7Uadw;WL`~P5=Nn*-n06lVB33L2iQ~X>5n`bOIMqV5=&UjzjX075t>GhuAqe z+rQ_w5NNO+>~Lk{7^UZYRomy)>ulc+jME)O6Zk|mw5^chu<*t!_$3z3u|hC$NFJXH z+Cd@V0&sr-Ajb(hL5ty$LGaI~S^4w>6oCEh5M9Im>HIFk-F|7M-na8j(t?2G{KDF( z=EwV#EGVMgr$kd4KyPWDOhz;;2RPrtOe!j0yCm-fZg!>Yt^Lqs!$ex`(Pt z%yzpp!7Q5!_j4$k0Lvufhp?Xj2*G`XKN|WQ3u|d7jDOO!?9?P1%?ZIk2Jt=PLxzgb zdJTv1`KJwx4Ftg?WTum&u7mEIB>i_3$Ochlj%|j{?@Lq`hTi*N6jz9AlC+rGrYq7L zY!!$HO(6w_)7fvQr=_P{)JA6_5oA?SdP)O){TxIn$RL0uy=?~m^CJcCj1>2rqc^1p z(m7CLcJt|stq|ED7F@12Uis3yTDGD2|#)7&8;+FdLJ~De?g#&NOfLb!Ikl z-dk<1+=r4Ar(pw6n$OBCZq4Md`!F|I{-%r9|7+&7`_Mx69;Nw+veMz=NO^Fi76_NI zxC@0T!5U5z2k(9)CO1u)}ml*2sGm(mbp9EqJi zy`GBB9f?A&JXKtwm0PA~S>7-QJKbhbL== z(VWCMQ^+7@!!v6Ox`-tn+srP;vMiLuPNc?PXUm88;5$2Zw*gxYd!KH$ z31&xK<`=nqcX{Lq9d0(eShl{0t%t9E0hH}01?^2e+gX)6kS)8VlQot9d2Tj_^Ikh- zuxe*fPHFks_HxwE^_woRKhWJti{ja@4OsSG3@3P~=ZH_~&%sJF-_MhqUu0|~Yce~h zEEAy>oVkNwN#nys*F&FD5exi~GMkgGeG-K}deyy;wA%%n{1(E+ z{sL7KJNRxfe?R1v+NuCuTheH^})5?d9v`i;DbLA{AXE}znB*HGFc8II)4`UNfyCR%d!s~W9xa? zNG@+6tbof3-&4rJlIm}us1dL}R)w;eY-+i&xr&gG0)lmx)~W3O9&=qXKP85X*jaYi z=~~(loZ}_@a;2D{(uM{-M3J-#!0IeIl6rtHpk*}cnUdeJYa6jUYH6AOtWxdiIj?nJpsZ`RAp|CoZFzc+>=PXq61J+Ss0{u0WX z-Fkbf)&8OZM*$HwC;E*e6+jXE>Egem*PYgn6}xHbz&0QB+t-h4B{(UJbJaNsLxj6u zKZM|aH+ z)#@V>+4L6m1Bo@c0m~uJ1~Kw5ryzY!6(wg%5zP-YnMsrPOqgvT(s?_*ApJj)^~lHK zcZEvvtKO_Rs2ATC{IVyK>vFX|m@#9po zoigl*E|IhT_^Ot|O2Xe0y53DqDC(CCtogtSsL{HCO-Jn zzfxWnw}=+cl(>gxWl3Ge3`xmAIn%L!fxuclote{TBp z7jL8BG^L9k8P^()Q%)y6_|h%6^1u!M)-h^62wpz%$K;_ zXsk><7R=6hn?dP82n8CZGjbO>o(LutA+st120sqUMx^z2(#5<9;jlL+l1-KPK!nmA zHr2cS{i*Xf{7@fNG){_r<^Bjj%V*#jOi_J$Wq zNvS8DccOIBBWmwvt9e$4mZiSxKZ`5hSN-0e%D>g9Vs8%4IM0c8*lp4X^sVJO`+yZL z?EB7_S?j!;XH#0%^kLI&%^LQ0k`@9I4oQBlM*4S>kW!^ffuSZp-~0Yk-H56O>nqs= z)ST?h)5HEg0gSok{$RO_VV{X@B@RWqRE-EkSjd|KjqxqHu7-g~b2n_=yp0%3{qx1t zzAzPH`uld%$=%h&A%*PbEC>{6PMt$C#G1oA}S-{D>#2$>qfIyAhM z?mr2hr~)#SRy}8!@G+)N!F|$a3P1$aUqW8G}{e`95kkrD|qlS{Bm;3@03K62;P|zC3yEVmu00{Blx0 ztv?cY`Kq?@|6%JcnA!@vb^#|Of#AU%0u*<52wL3T-Mx5`1Pw053beRW9Ez1f@gfC^ zRd7nN7N?XVhxeWD%$aZI{Dkb8tl9f{)_q@9Z=#3MPagQ?L#dVM#p?Z2X8p25?X3wE zjYej*nv6BSr#l0-#@p@$^O-q%-z<6;>Z`OptvT9;%NdU!k>R>FUqgwK|9+g|si~Ms zF2oCfV7pE{hOxt7exgbG)fP)GDO;i1|o_x>@hsMSn?%Dc#n!FRt>r zN4=RnQ@*H{e??~7mYlHO3GF|Z`ORX}wpu8uQ28L(>>Z6;v9vjg?&m5yN#yU_gt|ao zujkTPpu?N^-QuHv=`lg1 zYOo}%8KY4pK+0p^1io>87|`(p%^z_rHp~y0p5M1=7WL8H&xW8H(Uz-B@1G%~id>tK zm~X`~5u+4LS1mq$oUYIWQFDb@%i&E-uMDnSWkuw*h^w5T*dnKpF0PuWA$xf=2C)Te-Muq z+q%U}w;(LQp1f?3ZHAt&1N`lt^1_4GLxY`y?ANUI9>Z-OpB7KXgy{jd6^s6pA3`>Z zcjRh3>OkZ?g%Z&L42`vPnuujMK=xhr-JB2+f!{b21cOLL1Dpj7*^4~A{ZMf1f`9u0 zmtpPCvOm4>wQzLEYmVt^XaPz#0~+g90yr>ukJ3f??eU`E(LO5)5qt3i7)aA*EDuvq z6$le`60b!G6~D&PXGCKGQF$TnBQ|l~Wxm%ef4^BS?bX&-w}MeYiJA3P8juZr`1k(j zGaL%l1S$Ce`xZ>=fkd3aW%1o|lF^KSx zzl|C6BvGu+2RzPdS`H|krs4zbl>F>JY`JT!h>W4A6|4wx0N~N;yN&~qLX}mq9v*AB z^AjGQpYC`9ssW=JqOeilq0Gx*OPKM8`k$!JuL# z@xiWGwyH5GSJZ__?wkZ#)r;kel(ZWzdR$`*UwF!M^eT90SkXZxry&U+k>r4Y zN8`zE8Stw~%11JmrZZ2_ejAI@oQS*_EB1{|+=j=NjM9X6TehhbF3<*iQ+q8uaU?%c zvLjhs@v&e9z-=y3o;}*C@zL5sU2u|?Umepe?Bm^mTJEh{fu%;Kc*~9uy4_Z@B1#FtnPG*;kj z+!qok4iXZSkzkp@AC#r>Lql_fTPu&Ny9f%fYm;x3*7~WT738luWyj()%QIovII#~= zqQnr~h>L;{{2GMXKt<(`XCJg53aegOw$z0H=g{EP=hJ`&?ZYCzs^M4H=h_SU#g7>k z2o(xNiKVGJa}zEO*3up9>#Tz!b0y;OOLQ>rG|mhZxf?uyq7 zQG(9l_UmTi%FmJV;FH_weKeh;_?1DKGpCH!7I4L*$eA0Qouf0tr_RBncsV^)nmYMK zcj&`wkQxj|rbj&T!7Y^FZ^ry13&`0q&o!cd%@4+>#{4rr&j|M5br))bJ-x*88AbEmq-OmHH2aOGn~bqmUOB|Z{TJ8x=rUo zikQ7xT(wZG*`5l@Pq4H_S<_9=J<-yOcvH!aq?L@9;s-dAnY{F0OwPbE(**%gOSitF z&dnI^Jhkl&>h(Lzk-wmOv6xcg#(_>o-1YTGmQcA_Ncah+7XR47mWGR;`a`%CdxY0x zzoBWzEt+ArM0F#^l-cx;=VHtbnrr~&}8Fa?|du^*BHeO%-}x!s_FE^ICF=ruUDjBN=CjU=|;QmC8#!oNC9Ha zPE-F@vMa|TZ?)Ek?7O?=GU2~gNQwNLAEm`_ zEP5At(~t?K2vAH7Kqtg<(kr*G!qT+hTVbI5S1YxYfv?WZG5sQsrlt(thY@Jy9pQKf z;dsibX~Ak8-Rhv_T5LXs^`?aYLUce`bJvkG)(9N|)p{J@5i9sxKT^Mj_ieM3?})7Q z8d+aBLGi@trN%+nzpUz=)@~P|zgW=ZH3`RotILa2XYZbzv#fr5W0vv;s-Dc%HayyB00KgXfgb?TV9gb#SZaIVV9k|5qJ`SFARp32Y|T&z zK+Z~YZN*m}@5$OXX!!viHcEzKItM0tldKN3K6FMOv7@Boh!m{BcyZ`a#m1G!j} zyfWgIwE@y^B*KlW&1hvezP@L1$loqY0mK6#@rK4f44oaX6OB~0;kWsYs9DrinKY4(euY2j-Yr_1S`0@BGpY6hlhKibFRELX6sO?NF<;(Vc_^u3N+OFvRpO%eyp zT|!WmR57#oJG(4)Y`ah*v^_u-NEd{2GM%nwgyE>|{31WjY$d@W|EC!`P779NF=JUV z<;hqvV%^Xh-A&g< zLrQ0*OXKcBVEVJx?3@-FnRu7y$s~SxgK7IGxzz?fq&oz2&g> zQHnT<852OHXIDw@{>|$kRW~LKhN*J`wyVLC?Dv2~V}O#>-i^}TmLv@HK$ZegwY;8w z-gZOI8_ASNKKghFKophgwM@VGpuYCAUcGbi8os~~w22TR z;bCjf>bEO$)NwC7zUg|WK-O)Q-f@k07aVP|GfI1V4GLeu>RbgUdjCQa*dJ@V^(}sr zxp6{xdt66)yhFR zdUI+4fXhU#uXLkl>HyFuAIozfK6Edh>Ypd%O#HLp$-BWVzaSsV<*l+&O4qY*L%fG% zn8zs_5bIf0vOPawFvE`fX@7T;C4Zue@!5{+ab@l)0fTcK!Xt76&eaOyMITc}oe_RQ zSF=I|Gq4!n(oe)qJ}@1>tj~wc_WTqnhG32TpiN(&c#fJPffCh%u1EY<`hEP@&_U>B zlx|EA?Aam8N+^#-*tk_}`TY0m383psJ9GzFb?bQPYm*-^lQ_IT-X$>+!A1rD0xR>NrXq9kU!`8n|2d8+?`8jWc}()$G=_3c^1qpHX#%cQ0f^WD#C2|PsOh>_tSQF3 zAMeLHW2Dy4q|(lcmOn9nB{a6(F8LIuRg+)>1IvfRh0exS*aWD!gsF?6ao+o)y1ZDt zZ#tqb=dI8$H4u+ps2Dt_(dS!aRBniUeCXND7ckh}H6f@36R|hAKeIdb$F&3xfR@8- zyWIiXy4R2Wb>}o_H|UMk1=^w!Gys5EzHBi=xe4!WFD>r-qUSyD|I}|exaCKqYL5Rj zUOX(b?Z&`l<|qF}*Th--qC((zV$CuOPs`LS?;0p@mtCH(R0k#A08vlSS)G4=z7PHG zLcjj8J|?3dt^^IBl-$As&_JK<$T8VF#_yX&F8M@`VeNaQg%^pi82>Q^F~6z+5&R|~3Y?TY5JH*;Fw^Ydddf7KLM;}3jb+a~p274qi`z|~nZ-F< zyVZ05jAbfc&}F{C?VJ^v#^9F}aQfdB)sRs<$!vDba#b5ntAkb!MYX%!N43m0l+VxHqzm(aJ;wgH)n0}CIjj6IwSv(fjrBmn>v?^G zco!RiL6$_hy)uTuELUauMPNw&?%K$VeVE`iwjB=xs}=RR+9=iC?dP92>#`A8yu@l_ zhxEMOd)}(nHCh(N6v~KmXUE8diL%x@MiaAeX}2#W znUT$3Z0{-vujq|orhe#o@*>TdbXP+XxuqrBzk+R9UF97ZEjU#K=jr^?e@!D+#Jw;f z`dCK&xod}7%CuXA<5EHBPL&uC5}cB^){L&y_?$aFnvE&?kCx(1r_!4bnv6i2@RRof zI2Q@B?*iu4`2OB9{_eiu3~th-bm1n&9J&y~1L4JuKLwIM=5Ze;YV{-ys2fX!KJj25 z$DZiN@DJex2p{$drQ_f_#`CP$IwVuUekZo(s~ziXiFR_!9u$#y>=xlg z8v~zd$p_MtV^`3{$A^640r}|+Ha=4oxePz%Ix7y1bbs55Myy^>HCPOuo;}RzA1dd=$cGz>iA@c^W7xAj`wpNHC0^{-yg;bmZXTWw2#u7{;gJv zsa=h1tRY@dR}6!7-RDQcuUhtQUxTdl(~E1UssdBi6hT2|wyAEdw#Y2I5b<1GO*t_+ z_O4mH*;MFKTm58swMj3|QuFAu2FG8Ioq83(c*imlNYKE%*@)XxSNyZafXgbYH!nZw ze5laI9W>A{{+Iz@K&wZ~G_X%}Vpp7Nw9K(4v(wQR z>I2@7xVMQ-cxs%97`~`*H+qAkZMZ*P70uY$iGmC;>@ng#SKT4*TT#UtN5n_jM&k+W z0XXL2ATiq^8aIhtTnRV6&js~u!gHE(^eq`x;kyK7`xO*4dlUHqhZdXBUfTq?n9eW| zsxzX=E;1$+OBoDsMvSSfAm^fH%P{(Nv1Esd9^=WPJzJLyfr~k|xk!1F^)HPMqPkd8 zvw$otf@6@01#!Fto;~ppn)UvnG=sG71I;CTj7y0hCJfl7`+WkTqKu9S=_`*}Z5|Wd z7|6W9$px+n5roHB=C99gmtJ-ZdL;Ur;o9U+#J*GrHr})@2M<))BTd}i{8QoaF++#P zVb8{@2&a@V(tg#268RG)(6kTI1OpLRD+0-MctDChL?%Y#U@|qX68_D&5}^W$@W$~; zX8<^(Cbq$~{}z*$?9DM_*PO(@XzIK+hiw8m)DCjZNmww|S{XG?3|*=Kt@#e+V`8A6 z!)=+kxIV}kvSjEjU=W344)6pCz&wT(nB$$daPv!3YI%BAEdEZjc4cCQ)X2jQx`rzX zj~u6X^Ph+vJ>}%}&3q`S5#pk(63q)O`^xu;<5|Hrt)jc$q#^GAKJ#-G0el4zz*fTG zJM38qL@B<_`E@hsMNtchcJ?|HNpf~=C9^~91x_ezE8U%-{HKREB>04#S!3XBHNH3B z*prY!8tYSlZbnSA1!ViA9DzPbT@Pf&#LxpuECG;_xL}58N;J#7pV8D`a7pL8R{{!E zCzZ>wa)c-H)WgogPt|D_jDkNx*t_xUeR>IHDy~Nq#oX~nD9E zDUzFgd`ZtxneY)jB4_MS6=`M=#stS_)9 zGb1d%o?>HLgkoZm`(p>}-~rFBLkTyAutQ*|xNdq?kuWRQAGo<-S6qxUh^?CVYfS`w zNSx(PoU%E`YZXsqh^EfDatXK*>r1K zAEfri6s})U?va6n|Mq_odgq*DLURvGE#CDeS6LxFst)AIEhvV zVJ4?arRqCK?2Kf`fN`XiaiqOsY8|#0A&1J7hnd-XVFL=`mR$3jTwz}rBbE7X%1Bzl zRi)8YPO%n)Mk4M@eCFFC{#uYECGTIxK6l1~)ZfUOw}gJ%3gbL%3nz_;MQ@Ae4tF@w zs6IjN-c3uV4a+4dA#fa-Mu)@YW0k%ydvQ<;sifIv3~*>p;}&6zy>q}kU0=X|qUyS% zvc#-$`zhYlQrTV!9YO){txzd(RH@lfCx4;U7m;`Q_$#6Qj&>i^*Ak1Zc@teC6F5OHKa8Nu~M zpOX&h-#qyQaEjMk<(}UHE`hTzVuUQ|RW0M__;C!4o!pgKWVW2F)$JtWm0Ec$+GJ=< zaK405fiO=-NOy+hlt7m+S-zF9Kn*`;eZDfRnzrq>`G;%^Vt3mYwJo4 z;qODg6o+N(KM(;5`9D~LY3^Mu%@kOtRd*|Ncb(js4mXt6PC%gOSdc7>Nd~L@84DAW zi+{nchP2g!ACAh`B|A<%)1qj(TSdu}3a?yzZ-1h5BWDZqT}|6%CUh)u8ZdYDhfHUt zKYgW!yGC#l;nrNPNfF?FU{EP-Cx}`zJYI=g5auImqZP0f69+yBF9^fjBf;DbDYXw! z|7jzPFb%-C--w1j%Vr`g-PizB02P+fcpivoHY)8+kMtuH`Wia zhDZ2nds~#AHT1QKtQ-kF!!DPKzSK33 zy-xYW90k;FrB#m2IQ0d*`=?)aI!4^!-YWJm(DyDMwl z*OlsfbTrn)sB?xZ+aqCdBDX`5;)nGL9$Kmo^~mTt?$%+v_GEM#xH{}0zp)xH=k85? zcnXy7AYIV<4!DOi_ljor&V&2v*t@RkHEaP1c#5_uu@o5qP|9{At0f*y>*2=gZY{#)Thx_*RrXocG8s2k>>LPV*XYzgIND z$=ywzo|c=7DGc~5`sTAN&w|RE1#O;1$v2o&gY(93mb`hERemixdo9a)t$8}Hh$4B< zfa6ZwlLRa?OGh%=j723!U@`^)!z0Z{{?5~Ojy~nPwbD>LgwGm9hR3@}-ndE6yT#hL z#p}IkJxB}X-BxMb(dONfvp7-RSk#q`03T`^3=R3RkeM0VYcJLdn zWOgnnPdc7VX^M)i^ZJ&=JBCq{71;ogtc`3{lDLhL9OWG#!2IPsvZyW(Yj673&v!f8 zbUVX$w{-lEb&&Q6>h3q+!`1QaR@41W(?9J&f$$V!s4r|~fldi^x!X|Ve++T}fA3dY zPfGWYbkw9glFM&8;#HZK9lc>{hNko1V(?=Z^J5h9V=%}sa4V9*eJR3uNrd^YzIx`p z`(-oA^J!^`6#5NsAQlIY2kZRd7s0;`EM^sGc{A~O6AoVs$)pd-Kc6+FAvnC51f4(u z9>lY0`sVFZxl}jy+w*{vdPmquz;Vic(mJ2BzKmN{q=$J3P?chHJA;!0Y=?89ql7#491HQTnadqXX z=mH**QaD|^s!gl+m5Soi3rQVeEnI%7w|r!j8BmA8*g)W||AowRVb$&P!=lD&Lw-!u zM^VKy6)46%vQ1-BPeEh*tNF0zdi&jOyK!E#)+atejR}$le&ZB*4xe@z#ZjZ@v+;a*M&Le-vyskr5@_@1Oo33vmZH-Hi{H&h#BPX>5)l)O_9Yi*(H(2j ztq;7K7j=9Z)MD;WhtV#I8=#^DkiH%24GnU7?yIRW>RKH1&tJr?`kcg9m9wbhfeE!c zhYBbcp&-2E3O)+*VcYft7x zH^r?syz2MC2nhL?n)N-wf(e`%6CXxFQia7v0ah6E#uXD@f?~{zZm{g?{2$4e^Y}6DFdFS z3$+P-Ys!c^C?lyu{}FQ%ie+&HNe?KBbd{EGhkB8P6mFQuS%<}>pI0&aRX@M6{VCqk z>qF0g8p8w0=meXIJx|E{n?ce+&nj8|!kuNe4-CkHw~{t11r0uc73JT zF}hsBS~&g&ic0n{K!I5q*d4vBeM7XQgS<%4ky>-k@yP37k+>IqS}{O|UQy3Ke1kqm zbqQP|dD}qn2bpWckRt1j&4)g8Vd`Xb9w*uW~3-kPm{PrMy@(^>fj&ZvDj-SY2ul!!<^xe8c|NXJtriSdp zgB;=sk$8r!e6-fCu-d$%>3cgId=*+WB%O|rSU|nIOkVzJI)jvd{t(bn?ZtmgK`Q?p z^+!`Ml2lF5S*wuMW$lQ4yBHTBhr-0iNy*jyA5*Ya7xsV<{;w%$RBzJatX%MG{k@!F zew>qvnul52qbX?Ao9p$hUZ=d^?&r_y)F?+J&a=t|WgW;f(k|tCyR>Zhe@wx?d_RY= zbP~3gFTnmzlX)~6Rd}`QLj3uJ%v268c*L{v`KE3I7e2Ow&KB?E@lCHhmrefNC~>-{ zrZAOVb=S(!{`TD-%f!t=H66wj*9{9wWfg@59xk_d@bKpG0)TshcVIg{n9ck4HZB&= z>wxEfGTGkeMVSlbyWGJ${@7y?=3dpBSa5b;WKm}fl;cUy)`06j@^F|9cRzh)6KkL= zRl_~SuPD-UlK?2uR#o9PmR*<~CehO*LjGz#K;jAB4?e`EPy%L$=_Hb7A+$JC&rpMS z%Y{1QlfpFfs$)+)n8*^+#IetYC1J1x+VP9l^F` zI3YXwiU{msVFQiYGvb+som<0&T5v`sSFkj{JJ5buFg{k#E>&bn_r<>#2DlKJY+c1b z89{8tqQT>K=Dp?^LN->THy^)gE(lAx6u&d#)N#s5T5@kO+Q@5+egvzVhnaA{`AvwN ze%*0L|uPv(5E9t9$rXKumQI!I1i_)t^-kT3yjo&Co(iDRTcdFzKw(=v5C4T8i?YU;zIB~^=YBZ5m zNJz9qwf@~rNu6mXcXyo)#|v~IP(dVnDV|XH z<*dDGZe~)S=&IB9yFZUnzJK=f%44QQjmXDNrSHwdJZqt4i9VATfw&Iu-Yvc{IYP4- zoGJ!Q>UNH+ekTIc+n!@%N_k$S60dFT6;m9gMD!ehxe|xU#P9Ej;-lW|qYU32*uMK%!ZtK$k!gGwGjx4TI=Ns59Kjb<9 zFcS=6TPK{ygL&a{hC1}79Zqo9@T#{TkHPw+et`U2>6r*J14f(<`{c$F2Z&Rsg`hT4 zi6iL%?P^yVt^4PL0*`KT67ah~w(k&pL&GK}sYEw+JXg5UDb;fduA9`=%&G0i$x-su z#8;rbfxCpL!8V?Ak8)gKdXC!!FB|uvH=l}^RS;^6R*@qoilvcNb8~Tyd)OMi-b;u3mNR$u1MQw%{Q}xGM$=Fc>i>wBbCbaAWw1$ z2m?n;;Gae1g?9zys6P6;k>qmksU$3I1NRciyq(7it-vmy^P5wsnW~Wg zI2bzg_2Q&a^-DyI-S3S;T5H#4E&fvTe%@lTw3|D<@nos<7VVj@rB}wH>wy?gm$5p4T^l2m zHH@SJjnWviGA&3CarFi(ngubj!})XF!UBx}?Kzy;uacbj{uvW6O*bigk(cPvPcx(& zdzP|yh4oh6nP57WAdBQGggT-u0)amV{ex~52yJ7bg8L(pyW?ciq zbbbN~s0sXS2$0HIG=Ex;xl`Aeri)j{v+LI0X64PCG#Y$Q&?H2|7uv?8RK~K z>|{#^ylx5o)X}8B;=w=o!2717F=t1sEdk+Ti0TzvRQT8j6I^{w5%Z%G9z#>KR;J+7 z#gU36?j^?YFvr4aC>o5AFKWi2ap_sC{S9c+s9|FlmV=Ockivf;APK>*VBQ)&y;l~~ zg3pHUQxLK}_5|cGs3a2aG!vC&Q>IBCMr^Lfyr?KCx* z)?`MTtU%Ua7B71cj~z}mp?>u_@_fl=S>cPSQ5T_U?UeG+CV8pw@BO^h6{npI@i8iV z-ng-p$ID|?(!?18mV7-e(S((08KwaJB2O7f!hO=D>9(W3-nS53^A||t$;!8$d(+w? zkUvLB<(~~Oh~9)g%>Q{4aIz6DDM1nR`5YJ{d}Al5tRJ6+P2N#F=kBhPW$r)a-5E=0 zRS5gd0%F(tbvd*)-;E*0gAvM7ASSwP%Sf7&q#z|B1dGJT=sv(9M&&x6h{^sncH98|%{Cf%h z+Q5j8t0&7xHK5^_@_lqYn8N zW;p4a_3 zlftScf$FO;i16^PJ>19UJ?Pp8`GgFu6uAd@l zJsos%t8!B2>~2^pcv6{VnsA^CUM%6eY2f@?!A6&~!Pc%L-GHL7EXQalC7*@k`=V$# z;p`7zZRrVs>~P@Q1H)|3DNjx*3Esi^o1bLxkZUp2oG@I;{|5q;E}@Q;uXuz2=S!97ZRtO5vn?U$ zIT_jYeJ;)UID%l>^aEWzTO{r$TE-|URz|F!2l$hi*XF9%@j6f*=F-?70^>;p1-8gs z-J60F5!w@A3op*{2hd|MHgSX6eRCI4LLJSRgWMvX9V~z$=$F#*cQ%P*%YGrtsJCYD zf9M1(4A4hw5|4qo^EC)7lL+M}2wPm2y=$+f)KS z!UcRsQm>WLAyJR@y5w7Ylt>I%-{xb(%uh?dtD6-PdE&Hs` zbveG3F%(v@Qw`0)_XV!XgYLPgN}Y-L;y6}6at&&3Jvoc8o^$0aReYHDwafNsYCkLJ zBIZD0a4V{CQw*`8)C7oitD)xtD}v77TR8#epLVjyf7I{>j=q-M!RM|5m{!7W=3m~Q z3Dhd^%Qy=VmE%~mWl@8$Q+asEPT7@(+BO7d13U#ycp||762wPbE@xOiijsUo$c97M z#eheZ#9H&5AK*esKqAmu!n6lqfAKZOBBb_ zV7udz&}(DBDHUi2=#K&>tDXteJ&QUQ&uaMh$&SXG9mpJSLP=- zBeoNnw3a}M-T}r;*ugo1>BT8Pc+~r@czwDs9~6-ZMdv|L9ysBPeUq@ zVf*PyStSQ1`s||G-hh*HK|$z(gYPN+Z^rSD>E4d>l+kUfdV8vOUe`?RR(+f+o*sV- zJ~cZBP`x~n{Pj$O$m{W{hC*_fWKX~g2O&Lup~-U|<=dJYep+Z8ph}r7L9xvpc<_0* zefFT8@mxqsMA%Cl8F?>HTQD9)@!)F+VkQ z2{;wsDbabG8uh!GC^j$(-9hofP%qO+wPqvmtB^oGSv>h-LruFe$ALa`=2N~=Nd7j% z!LQh>R=|hL&`}Y#)J2hRBm7^;)cZ;#Dh(C37xn3`>{yPCf7a^CRg$RMf%Vv>UvA>w zFNR`}>rF0}tS!n^!A%X%`7>afa0gj32L-ndeMV7?UmXsgqbp8QofUsN^m6DaUs?Xx zPNrvfLisyA4XUOlcc#j;W)5=pTjCDTp(?9!`>EoBo#bLy=PDnA?dl58$^Dx$yJK-{O0HSENbv#S2tMHv1!R=Rgv=H7Ynq#grM2kbv4JE`Ox)+sI%XN z`KNgMZ%gdi$&}g$zUQP;SAODYZC3Ys*rs?+mrEXhF+F)Wj9CnfwIk^2N`7~pJSd(r5|T2}l`?&uGAEw87?S!ENjy41WV%AQ5|Xyx zmGvS|5@=tNWW^R5`Vkaz)!7Ze|2 zMZUnh#t4{L;svM}mAYRzb;X<5XK_d*7=`ADbmdr?vDt>Qq~yC1NpRe<*LnXnI6I{7 zBV6A4gZOFkoC<{Z2<;*y>>d(gok(JW<(8jw;f4E4fzLr;%n#{?kBFLlo&dFS+5!2@CjHbV zx%WokIu%D5h2Fwn{$^XXG)8TP8#4o~@Tg_a;EOW38#Y-a4(297BC4EbGb8v$sb;Bi z_)CwuB<}BxKyy#sd@6yWzu_fjqJGqoUR32S$Z|DxDppka%aR)To?>Q!q8~v;j9~)p z077bes_URCyBuxMa@B(mwL!gE1JD*oi7Gd9A`|~wetLsQE9jUpul;;u`wMRRn!3(H z(riVdlF_emKg=A1$^`U}Z2(!0Dk!I7jNr47$1Lp0q8@4gqb4swj8R=>dei*Yq>(MG zl`G6Gu%`xvtRLE{r;*2&rD>m#w4bIfT^+(!Q6%iMRjX48qj|3Wq^HrYP(fLYU38Or zOP(&k4oko0ZKZM3U&;CVu(uGJ-qMq|sX6ueUkMHnxG66giqcxl3KQsi>l7*aLvdS~ z3k%}PC}4KbaU{j4oehaZ;w$ks8oM@{M;3RW_cL?5mS=l0o=5sdB%zB9Wp=n@vDlHt;$Leg4XWZKqdXHZ*oNJ=Y0{@dR#Y_L%LFl-U)192d&dYJ za`@LFQskeHfpx#Rt57uJXWUCu+SF??(xf<8m@+8h<=8UNg0}DwFQ+73vf{oKu9A$v z$gg8*z%u8@$cP36p{N^a20)f=sdnYKeNj2zdGcxZi!AraF9$El2@BHwaZg9x!Zv%p z_w79I|Iw-~3*@ksr%k)oPzoQ8>zSjGk6NRZ*t$L5l|C_Ez)pgA5Fhg&7x6?pY^j)oD%Y&D-~`5up24fRc6Nz$fggP&##kSR3T zW<2&vYW6|VYT?&Eq|GL+KOm9Fa)9m?5oO7e7u~c8)Vsd3SYO4wK{VK&vhL4b*YU4~+R=XwTVtS5#igAz9hPD5@MvM7Smje(W#B%%`~G9Irj?ES z+beO1bam{{e-w%buSoR6SE9;`93!JG*+iL@Am4$c+@49L1X@8F528ECW$8rYw^K zv2-7@6AgZumn2afdmfpxIhMFGTac?>weC(ANj<;Elf0OjDwxy8TmIZ)$W50HWUz@UBLb8#XCgL`}HNn=HxR1|?s&&9q+p@nE_c<8}eYzw+J zc?_2r-DgmDAeJKa@$A6hUc1Pu>vZOPe~hrMNYe1|=HI^uLR)0X=}*d_!3XTOR?m4D zH=c;II~^UhB+a&T{to76q!?N!I^~*sJ6Du6=F&+^xAO9dYWJP9pfcT*uROklx@1dfb+b4dTw=SHL=%`B<=I8l z(kXf??8H)rt>`6CXvczGlnfD{Kf#k_4fh{+2x6;EOXEd2Yr_tPU5ew0Kf2d9x_2L# zpqXm+%J8=I@+eIkTq=|^E)4Jr3WL;lsxfnJ$XcyAdXH))Dtnw7njW+@ygF{wzAZMC z#dU8IneUA!koR7y&k>DWfF`PnvU+Pni# z1HR~D-;-{}#aKONOnRn+w$pSb#SMLfS%YoY7^T-%#T11#Xs^1(FB9~U*1H-I2OA-ifPCv$shU@Ovr}rV=ymytkJo_YPb*pUG^zw>r z&I`*k{9k`J9A2tG!DJ1PAtTw4c8QR)vju&t&i;x0G4i6m1R|#>f6G6DlANp@OA8U<~6gktVWTm6R63aoUBg{Zrk9$)tu}}%^Zm;4JBQj&ySvNgKw%W^p`Q*w4?*As6)&GCVW^W9PfE9Zvs^lpPxC}GG zu?(wp0E@_Z%dm=5)Gbkq*3h7H8h-N08_tsF z9ESJ~0s_Q`&XZ0EX#oSoze11*r8#`mcY6v@iwZZaeqjX1Bt6w>)!|i@AU7>{Eb~-D z{LBmbpVVz04@IvGOk1LLb*(6R%OD#6$vc0h{@=Tgwq85|0vV#W%n$$^ixm?C$BXg_ z27K>We@)^$z^1heG`Q}hU*4PQYFPhH@`J!^j@fiiOV8KK28Y(?4Zkp^Ka5)KnP9Zw z}f+;SLP{_Ehk|TgmGTmxs1^wi&57#${Lubz?OWa8|V@$goAeVR#Lh{11Sj#J@ zRwLsI#hWap{mvFEQgR{J7ZT2Gs>Ixp*9o%Pcj*y(+mE?ugh(XgqbbNl2ZoJX zKC%AuH^&i>ESn9Sm$So-wwP~DA5Fmx+5*>$yy8~WF@Iic4mtZtMJ5f8&L5vwktQ{E z*KWEtO;cv40HPVKSdWFRW_XPXzc?a8qeKyaA&->y*R&|!Fn-%drYhn{%Pddvd?T%V z19Y*OfLbV9*YRrg#cPgR-9Nx4ZR#4~`yW%Vsf+X;9+y;X@0_!C=HBC3?DO>OOUz-T z=`b#ahwC;bca21Ss4b!Cg)OurL;(RqlPV%8(z|pK6qPEWhu%9vC<3Bj5TvW2cL)}W0tTrfLO?(eB`2=E_Fn7T zv(GnYzLLowkjYHmnLPJ%|1K&B9~k>CZcsWmESDT^{}@a%f+9U^ z$izkjKr0B4p=Kqg_Q?Id>(}1|PcnR2{2=9w{5MnZz5B5M#V^inE$nD^>*3G%tAG9{ zQ;;QGx9HR@@X6PI{@nD7mMU5RgU(L9GNA^SoyPk71j))l!X3d3)!2WTg40-d3zo+* z;v_EOpQhk+gpeFeh#VoTA1RUt$~lRJR7d8Yyf3vDDXkwQD;||G6Ti{s_QMZ#lK;ciaTYG;(=AwJ6t5$iyY2cqCNiC1k#juN_DPb`nZ(iH+h(-7SVM z2BP}{lf0`FeWw#gEw$SR&Jqs{2gGB0ER&kyLOJ^E<$b0jYe}EQ(Ql@4G!allD>*kX zWg{~ssWf@LI_dsWGFd$Jk6=pBfzr2ul!F7V?|G@q9%jELAHKJkpAI}@fJD3%%1)M>HH3l<0 zXr`d&KTJW1f0}~AG*dADuPG=i0X}2ut)-H}&z<|OB}*VaD|^sY*CK7|ZGJI#>Nr_L9m+nke?X^1EJI)^#cR#|uGGOQbM&hmwgRt0ab7CNREj`wCF&exQy50$G2mtJJ7;FP32UGchJ6^MiigBrXM4_+P%eI{CNZk_(t z6J-(nm^7$s-S&7ah}+T-<;YWMYxwx)$0XY4Jws6#igCe|g-l}Dg#uC-#43j6RT`~#h9H}=tP>DwrYK2A zBvlR!>4Z-Ev3$nD3!SQQHPq^)_3AXqCx1=BnkSG5_(w;Uby_BI&s?*YyQ-i%Q4;l( zW(rE8vV))GdzmXgHdnhI(kgkap!4aIUr$qcp3w^e9TXOZ(ylr;@*NaBUv7QA+RFD!k`IvL0bd~e zuF)$ZApOyha1=`}t#4t<+=Yc+Kp_@MAn;WNZ#2Y>fLJ1WK}r#mzn%c5|7v^|L=YH< z2}nf!38Q+>#J^tPDJfK*A2QMpqKk&*mEH(lzEL>w;$Q9{0^n}1=O6a+SEAmyckf03 zPh;41T>@jKw9NQ}j+aaADV~Mr&AOsPOntEz8^AA(- zMkm7;JY={KsnXXDzKU!#Me&<5k^ySF1{Nug4;GeU63Ky6h%YEoZ*~jYApUP?pkNa{ z+-jP6#Sd|>(Hku2uzQbti}#JI+#A634L~B&mA?7?$!qPg{l>CAC8qOL#ena4i9!PpX)X|W?TEB(# zNVghWgefw@lrE0=*AaB1If9dj4k7{~2v#9L+p)|-7L3i9=f&%NeoU`AeYpFQMutX4 z0P;UTL7&lSY3CveOH@1fi0~qj2`CBWUMd@zkp3Q0|Ni~PdnoIN2G0EE9Pb;CKIqrJKhGTC@SPD;%kqSi2_SZB zF!ksrH|z0p+sL5olHURNcK~U!YJc(wHKmw?^pZkphfX~gg1o@i;DPpHe^-M`A^3WR zDHO{(9&rKSm(q1Eod7oxk$VJYcQoJl`qM}LqpPGIFp6=_l;sWjSwa2B@uxsJf%%6Y z@+IZ2bq_L!rgD;*q3Mv_4u@USn)6s+^IB+9>?ep5Vx5=!4gYMn9jaHog^m?85Y}G% z&8+Xy?XGt2_cExi%d>rd+-GHOCwbjIm_+`noJ`T22OQ_8Zp}(#eRU{QmRwT^N$M3B zf`xoI3uc`wkpH}Q88yue93=Z5&3y*s=)PhY>E+3QDY;Thk%&%W79kzpqu+LXJQ3$Vfp&QWvkcA0BPCb)QSrdP_FtH zC|GcHE!=O-uXydQFKXPV>B1fr>M4a1O8|x(ADvoFc!(N*`u3&iU1?HGb@7U~ zy-YrUEcu5EJys8<5}?DH)|GoRC4!9aQT)BbuaXcv<5IvH>6wrtOY0kq2_fFK19PM8sDt%d#V)$PRVO_<0#4axs{D9=S=zZUUIimDgMAW1E}E ztpG{HCK1_6Fl{;=T^O;ops~69aFc+bd_UfVYzNn$4`~SwX??Kud6U*P+F}*>w)nJm zcD)vFxV7)g&HQ|eWos+_GHSdq6eETd4`?dEFUvp9{iZ04gQAV$vc zp~alNIC=gn>b=Ux(;WTo)F$=dxr31u5z=tw zs6lpn-V~8O_~X}U)J0jI=cY)OGdz!Jc2<*DsXX$NH^VBLFWBzgcI_`)lRZf3^u!gm zHaxQ=aP;YlpA4C~nNt7yI7)M1yI2r-?uTrU;aQ3GT|c*rcS3lv0JQmasXux050(3^ z$@e_}@5K{6i~y>wr4}$H{ii8NTF}O^ikehdPJH?Arr?fC;_Wxq1V_(1Lg|#NX;K~%#ZYkZTYyv-zPhNBtW&cg-p zZ<_gL!SDihV{ttK!EsWSx0mVxLZKKRy>d|9jI=N|y0jMVgC4K6`?P;+w)NiD3ayBG zo7@@m|Bop+chsK>{SQ;{870#P=`09FT-c>(qqGB9v{{Y*VG2ekVJ~+*(JQ>jl(EPg zf>l{6VP*UkRT$DUC{p@{6GGMm>><$w!F3a$WbdVgUNM0EYpjCNwZ#x-DH1W;ruaMf@karUt~}jeH=?5!X4OOe4C@)S)vD*z$_i6Z{GKbZpt>Il*2v0w;h> zU&__0lk%Xv`b$Q~5(q5+Huq|Ov=FiPQ8<@Wu!B!klU{hS1O8L zLr#YJb;-Y=W9CH$ozCi_nS$G0Mk@WMZmVhnG*hry4*lh!hzNDn2xVV@S6}@@y zL3u&m|0oGYM@L6QMEn;c7#tk@;K2i$BzX7k-5=gQhwj=x92|eysPCGaADAd_>*@d0 zIum~D7EKbob?cUwmlsVEba8QUbaZrZaImwpqe+4{Zrr$b?V6dH*?(Yy#>U151_t{2 z`v2t#VlWt*C-^T+Q05FRP)z0L*bo(45)k|+CdiJWGSMVK=rJ9{{M>m}RaIqW<$q@c zWhEtPjG&a1l!Sx?O%fCn6B8AsEouIDNsxz!=f5$6C=`l?g$0R3GBGhB5C}#_Mg|53 zI2;ax!Jts+e;I;Q5Qqi{c7Z@(Fc|bdFoIdzS4No(6z%nk^#92S79Gfa=}SdxJ8y`; zs4z$txl&_$C?q00uBRJgr{PPz6|Fnde4uvHmue}OSt5W_FI+Ag^!Ta;rtM;E;pD&J34}sSm zhd(~DqWOw*!j6{0=TfsT3TT+Fykk8PC@&OEr2om(SEp)QFp zM6+9XEW~i}4BWT}ZXtL72O}tw((TD|j_v)yrC96iyIGJ@yU*UHm=!B#Bn1j$j1 zxvUs42;2MQlxEl^j+*N56{U6asxs>u%?L(SQ#du6N?w1~IO!#2-*KHBMW64>m`AU1 zjWAtv=ka=0y|EyIv%Xj1g6Y$SF3E4T?=8H)zpRg$$*${?tdyt<_rLHgB~qeYx^?KL z+Zn4dM!MRkZ=I#KI(97zy$P=(zvZ^zo4hC6+z)L8+L9U62&oUQ^4@;MbbiC{?$7(} zxxCag45``VuXFg4a)Z^RP{Dk;rr<5f>?cQAAYO7mXw^U!>lhD{>wq^+>sv-*R#4k?^w!rCVgY zfx0S}h`xFT1wC}3i0wOABY%X}SUDAl9hM!_HZ@&uEMyGXC~)F8rBf!h&TLxTUwi~U znWyxb8(={t;ptB6cQR^`07eimAnsOAT)>#WNQ;BfftjoT4D>KB6B8}S7-cHV33+nq zNG&$Dn7zjby5Im%A4s1P8;)E3m=r=?%PFB#py2df^B^(;XVdV-4{ApYRQf_d74!+3WO3-0cUa4 zQAQzRIf^+?j_%8uc${%XM<}dgQDrB6V3<65j!XT4WjY<6Y`dx^h6|;jVfYbE1b`ai z0DxpKS7CsT2sQQ5=07*>IJXa%uSueCCC=Ie6Ci@UE$CPxjoO#OYseuP=q(^L%j2+CKMfOqf0d>b|#b#LWG!nP;C6 z693d;Whl38)8qM-yH6Y}>QgO}jEbY|p31Wh&y1z$)`vN5*z?)c-K*(syd>`lEvrw} zu(f!hS6US?y*~4i`tkmG+i#zo!#K`Z=dit~0Q>qmwdY>ifbcK|%2>NRowT0VZz3gc zhTZvQL&RCgR$QLC^L;(nWn+;&;Kb%Sj=}tE!Osp&kc>lJVeST}aR)H#YmX(cg!u?| z%oo{_12D{;Z(3&zag{n*~mR{jQ)vip{xM;V&9FvN6+oXTk9fyi>Zp69t6C zxDhL^@S6#0i{D?@ggCQ>bMs?Gyo)3+S2($eCg=@T}@4T-+lm1Tr#M3Vv z4dQ7s_qP+BsC+KmogP}316{JeRC_fJGGN7I`9_)Chw1f=V>3+(KjvrqwTPPRc3dr5 z)W7npSN&A4f!4dKJUU50^>ENM-{~!VQkyRqq9JhLxqA4$ z=0n?>U%z$h%;leL%{GFgbU{~OhL=;V*a|OlUy^X%POPLWN_9D}XrEA@di{6L%K0k+ z@^Pnr4s}aUUHQ6t5z_XvWZw=A)veaz_CgsIY4fMbbu@n1bee3|*fuZK4Et2HZ)x

7o9ZSA zRgDE>9z1;Z_Wr#e_jjAIFS|kDuWNm(booA<`S5< zD98_ltAHt}o`~GWBc$c*_TBmO50d8uPc4B`J|9T5i{oA$gnD)c=G;q&7)XAiESp7U z$|5DjD#7mHAs5h$KQVLw3b9OqdYCf5Cnl>~-gU>tVsSAN%A9g!lg9H&&M>EKaajv8 z(*P0JAF$d$GYI>!M4(YLM$j7-HPj?1X(OVgJRi?N8nt=;Nti5akzqH|;#qoSd_ zo|bSq_&xtP zdFv+Kb{fkj;c7H(WyPPl!VmS>TqMI3mZ6fLWtE>3lu!FVQ_z}UG?QO^m`^hV%V>t6 zRRPTqtj;f}G+k;JIS7hwxgi@zW~w0;-%?_FNl6!E z0MsxUKl0O7aVb3mi5$P!HI<{O`6ZfKg#sRh4bI>(G7~liKX8`u7W!g2nZ=Kix`a-9 zZ<@x+h~Mllm3WeYbLY4Yw}0NBvH7KR3>4W|#yFM+7fUd1kVEd{kzJ%R+QsV~0;2qE zxdu;+azXjYkL*4k4x-xSN|N}q19Hw}raqLL9*^Az|Ho{WkGq#1i?3)$S4W&^O=DNV z@0Ec@$V`TQm7IM_J_RQ72BmB&9Azym>Qj%;SzlOg#jR3fB663&?1`#C8%kMY(+5SLH0wSoSWm1EE^kO+Ps(MayYcv1 zCU_Bp@OFgwlYB-6D;nh8LjBCsQ`8pTepM$DIT^ zO=N={D%THLE!prA3=#GMpF48qmuj?Rd_ns4{IVd}d&PP(_QkCSh)=&5KNaxycuDDa z!OgubkG<-Ac?s6urCe<+3bXwI}zm{9sEq+H$g6$2W9OrFK9l8RWEsRj7 zT3Y3!7}FTr&Wg4@PHgu6*bpen0lUHECsxYlmBDc+=iQIzJ`C^&(QOI-( zo4dCZli#xuT*pC0$BU0`YVeNmgN{p1wgY?Zxd~5t2ROaZ$QeIHT|DA07IGUvwxUs| zh{#4FgoYiikvYy$2+CM!4~;f-g6x*R3L-Nk0zss7afV2lW7ByI zx(AltBn@{oBZwC3>^5W*Ba$}5hHJG4XOo|zo-`_lW*Tn)H4RaYpywoJLm$XKngK2c zZbdPHOWiZ56r}A&WAmL%6^T9Uu|jsn9HwphrpaOUC<1erS-&I(DI4s2&JTO=DsF!*ZO)vc3&^k7ha{ z%@J0e=OGsupnjFDzli!dt5(yT)C(_n4_n4m>oj4OF2(EPc4cm zdB!eaN~dZ^H|2=X1pq-)<{lD=HcDP2C^Dc}q5;~GyBBx?OeI2TH|uDGVKbqZ0o2`W zhKD7*m9QJh=bOw)8aaH%u0(LNl(YY>MnwGPbYy$~2@4r}2VS3m?4b}E7`i4h^6n1w zn9QJxg%ahE9g$rXBuFl)E4fHX$gs@*vajP@M@I6X^W_=cQnMj+)iaxS6QS=+KW+l$Hm40ZZMplhs=|)E{j5E*D zF;~A!p4WE*E=ryEmWkr`Ai3Fm`mjS&Qs>*u=U>vWXpQEqW?iK8mBBS54!67npO2caH{0WVPOlEd*(-`uv z&pf_WmWruT$S)7dKfhJ~;`p*#wTRu7Y@$c{T->oBpZR=*@LZuz>8#0|vOUM1K?%4U zWWLg_p)vQoaMn7iKHYYSd5N6!hkSZ-+^!g9kFkg&y_GptX|3H55x;z=YT5pHS?bY} z>qB-%$At+(;Z+lo`TX4OEg92qOlD746z(pG*ngqT7nDrcm8fJpyRg+*d(y1>=bccQ zuTPq=rxYU}wrzcn`l`N`{Rjmzg+Ake8lE9i<|f_hl%l;`vL6Qd*!Q83bLWZ|btAxm z1eQ@bpuG6&8;*dxoL?v3wvJI+pB~HQK3pvH-Ka1AroTyFv@h_IhIC9ml$oyEI99j)Uc5l#B@JGI(>X7joI8s;hxM6_0wpv=})FF#aLnBCgj*-Fybj5FER*I-vN{nl)< z#d&*c;`QqEopf%7?H@wh(#Tb|i^`8ibUat}ugDl)A#2_K z;)~pec7g&i&I|&(PPgAFge!@?+S}`2YV$4GdcAvogP!Mhv&Z-{#bfV5_Xpqcy;}Rp zj~aV-xB9d-LBZsmXzF6M$O&v=I`>8P%x zUy-uAeGrpMycWLA=tMDl^S$KCW^(Gft5@aY5`n7czn-x4v|o9JN#8ED-+CLB2j;XHK8w&%+{&Ye`5sw$dRfDc8$>OtzPW} z4jKC%oLtWv6!%|7&`bn?4iwpO=bJ4X=E&H+j^;LB(KMMNKUwT`LDz??QwJl((@VSa zh2uCc2eEtVKQ_`lcdvj|QVSWH@m-taI{8{HXRCdZa{agINZtz>x`@mSMRU)&*D<^| zHjNz9ae3RiV^J9A7uLVk3*|PZTB8x?i$X|**b@3pZ}0BB z11G7lb=%Sy!FP9mOLg6tQ}r!Z<;y~8b)<$Xs=oh9!2Ai`|2{`!1Rail{rI~2xxYl< zVc4HPe}-4LE`ngTXbhO8XB=}7ON11JF>0D(=!GjtuNaOBHOtm7S^IXkviplkvFM4^ z>r}zlVhSRp8S6E1~NK8LGZL|6l~`^#sD{6!Zn-L|*6%r|Kveh~~P!7!(0b zKvKhs8F~z)p7-1_FgSabwH(>5lL&RslK>ejj_bTDv+QGiia&qc*@>t0No{p8N;Up4 zVf^v_2S(#agmMK#J!*ieQL|>M(lxi(0w#`ml4ZNky?c)nHtcuq&DT1!+-T0`BHs^< zRy#P2jDad{Dt?hR%5J#+GWdf;H<+Sr=xIz!7XN6Se9P<#{jZ%H`Aq(?98RgaoM%DK zDtd9z(+B-H^PBHD8ZB=w?-9IeM|0|Zndwb>zBFBbX_JtqO*`YVQRw7$ceFfjAJm`F z`{>-US0@JmP1Q$ph@F@39wKV<43Sh@sx2qfE#`vE&3f~7 z&Oud{ay>RAP5}1k*hj%cK~cHUYTeo|`K~GPD+MR-C(5x?0AG$zeq-EgQF5FXF6kE~ zd$?Wbl-oS32DM%~-J+T|96qk8cP2vL-%e?VW}@{;*ahGlb=Kk5q2I)$Ej@ zxdT!-bnfChhxtGy);SFUlK-tUWj zQ}$IBOBXmc1#ao21~HSI7>c;zx0^7~k1PQFfOd~qr8=8iMaZLH^E+a!LdZ!u`%@h@ zO93t2tE_akM{*W)Hn{YYcO+x`+1L~@j@n|3h`7j1{I9ZU?Fc5k#l$p>^NaI^9NVPG zio4t}#g|XSa<xc3yX!H@dK9<*|*K~Z0EUT zTMb!mzIa&p8_&;Ssg6^35r`cq72bjwaBZfiK6Je)m%nI8yr+=USM+i0fRO5T7M*)- z_U1w;H&Nu6YLYjl!z^DOH*&S>j+d=AyKsuZP(ogYS+%if0HM`{^!YNCAgWgznX$ zxHKMyDK}npU26>V?D2$>RA{)MVY~CyVb5!s^rDVhY&T8w_9X=scjC_zcS(zf=8rGl zV>FsOJ&ZbWFL`O!8NE+xPmOG>eEj}2pwY=3`oytHl-Uv0R{_G`zb>XFBWT7Of91OW z<LiRyED5VTxql5Orpto{or+Xmv-}nWS78t4?zu{N!Ot2cUk0yWN+gFC2`6A+siQVcsZL%$Wvtv}y zTU4P*hpHQNL&&yrV64dZ{XT>E_zXty#)ugdo zeB;)J;wL#zP22l7J!`EL*bcjlX7;XIYwCI5sF>RnYkGXc3j9Fy{H#6y`JmxP-tKxa znwkDx7F5Ecb%UQ4pL%2OG~b$*x1A5EJA7@|$(HOL+17g=7l|i|7Jm;r89gpD({s@= z6Kok8b!r*g3x}3Lom$HIiE`Z-Iy{3PxrGhl4>`BNip-Sg86Oe0=;NQij*EJ*$ak^1 zbyfPYhse)4mLS#li~Jl)IALCbMC6$jY}9$I@JXfeXvkvcn@?( zJcdOsoyA;qX>~ZNGjBsBAe%F65OP|%SC;YQXJzqM04`YT#PfqEvb_*879#Ixj?$bK z1_Anz+$2gWZI=diKr+zO?@W#$gSj*=HgR1Y`uY02%^N@a+ttaxmtV=+%VTp57t@`o zh-v+KbdG5pMuU)Y1w#ZsU+Y^|+Gf6tbKz^y@AQTW#XrE?FPz(z_+~>TSNyQq=MF>A z?_+zl*?ab(Di?pYCRu$g4~h@P#$KiyhmRz(Col4<1oPywC^$X2Jzm zp-Fv$I2DEnT+3^o7qxFm8VNh?y5C-Rwi9zHV6u4Z8$sOe5oVURDat0{q(00u;>{q0 z)BAwFi~x8O=#?y^Y{}5D^qBBzPy{9_oD>gMBhnd5X9Qu8LiG$4n5m=J?oqF%-!U?h zqXsbyKiE3GFSMmngrdzEFb8p=`ykhfj$h3f>YsXahfzGkQf(1 zz=nIYA3%WhOt$VjMDK#qZpE&9H5fy-j?#5y=AM>MPrGJ~babDctvJ96VS9vHpf&?3 zsA{P5K}rOXE`ZcXhl6PWSY<3*gdBvA4ltXJjcAE^*UB>YP+3P&H=2d=5p(4>B7$-B0%)*}AME5mh(Koy^GK;eVaP^F08UA6uO z9izNya6D^OX|!Qq=Fk(JA${wrvv;9VTtg;ZV_YDKo|B8KtirH6)To6o z5vbN@xn^9vVX)HGrP$j3$7-mkXuW~6gVm1FVQH~4 z%7*VkFWa!=QWZ0YLU=Bx zC{@38hmC6` zp4D-@td0j-XU%h@uW2Xu|IWX{+jZ8(&piD}Zpa~mK8gMg{IVC<<;5k9A8J=juB+zb zBY5~DSvSnDWEy9$jVuvH{}>cL2)dT`q`&ych$cPSc|>%HT-m$uekW9&QWy^wj}0@8 zRg(kEbT1$L?oG$RtQ{fO>CMEPTW-*!tC%{>M9+Jx<31!o)wr&^>|NVxc#;Ls*|)&_ zrs>?(lCRH|;4>%xlv-TsnZy;EBm$85S0)%WS6Z~Q~ObeIUchX6EXlbJ}`+OMud=)N^hQ`w~0+uvz|1VdG~C_`_`uj zM*x{*rP?+DJJRfO z=VjFQ*}lWsX{I^qn}(05jXEYEh4&hkfL*6>|nGhwbKc zZI@;A9zV8C#Ly(Ag8AU+vy27&fK0&hHG)w_i5- zt~8v4f*gK@sG+Xye4h_f|D1|~`BUQV=sWr!Kpn-$A|Kg{{c1Yu{d`%*k!ggSbeVyT zAZlKn?R$NWd2+y&Bi;!;F!IQex9q(8fh^)-!Cdy({7d2vKMpXB2@{7x1t+aTZNd_- zJpcV9#YuzFrT4iz0^84@U$z?REofxkyC{cpK?S*GXpQbgl??D3(3Xp`vkd*iEKDJU}jZzc&|D=|21iexCx0Tm#+5tY&#FoOE+-hY?J#}I_kjF5{A5?{+QdmJ5`=!kYdp%1%@huw)?`}{%K zYjZ8=&u3{KU_1MU<@}n=sdy(WeIzc%n0eOmTzQ$UXNx6Fh(_}aK*1=wM+sl!D?QXx zmJ%qAZ^3{zH@W!O&5uJa+Yu6s{tN#(<6&Ysj^$^BCos@CW3R@%xc(t}Vi+i+*sFNn z{nh?TA{Ssma)M4P`O-V5G|l)y85CP$Xzri2Urt7)I6W5)9{$!i4K)soc;I1i76Yrm zx!eEoVxD)z#6WqlOlmDtT}>-tI;GT840P~ln*E1?YY$XbSFpBCZzgbJAak}+rv|?3HFH3%ZlF_{~>-$;blh+G0eC9Q9Teo6G%c^`W zzLPj_h3~^14(KDVMK~zClekv?1f}@B-zuAqNx>{Lr>1wD^KG{K?p2ASet^jsil`k# zQs*6xU&`*Az|+Lwia6L>rTEw@zdStsjMoZ(Rm}Hdx0>RQVNoEPq2k)Us0+&WC_O)< z1trNb&W#^_4(-9<;H3DA#Jk0Qoa6C&)BWiwKm}|-4__!)*`c0c`Ibdv6fOVqe@fG_ z*7)ssuj?V*JD9h(_UyNxj@<<;N8fV7Po1&gplj;7^ndleE=67KnlpO8#1}Ezt!z# z#tYZhyz?X5RejY(w^sV={lMI5x?pUKULc)iTHNL8Ks3u8^XFcX@U3l5Tqma!>*>Js zlTQ-hDjYgEJ{%-$qA{jKDmt5(>A;|ghu(LDd7+|DbUbj|3Q`jYxIMn$N;rK1xf{U} zv~?;dy1MPD5u5`B4PT3+k$=|WG0IidnQaD@0<1Et0r}%MUKKcd5{)9bHZP0)yrs8C z(~Sn$enk@K9Ropujz`LC(3a=^y`@KO&wt%{6CBDy2%d{;V#kG=+;?2vH+v(ns`@O7 z{EFQe9)MHngJF5|{3}YN?iK&Gs0rF^eSeMpcGbJa6 z%bo!L%H8^MG5iq4C!MjG`^t8Xv=HdABVrgOcpRhupNycI@*wx)0@VjQ8()8%CgBz7 z;izD_FNrbC$?MmK0;=9soh>(fWN;mg@;KsQt-!;^(`x9RC)_h=@)>H7NEiEUx^yeu zyD340Z$cth_UakZYulL&Su#yarvKJgzlKM8uU2%z{BB|{BsufE& zGptpbC{yu|5ta7*zkusU8QExDB+DswY;9`Xskz_7Gh*JSnSL6;wj){>-{sZ}S(X0! z_4CIAapVcjG~8m5&eHZxa>Ux#ShP1u{>7EECMb3ccVHSTSCsS3>e5JWgGO_)se`+h z#bi+D9l|9h18|Df)dxaJT^}+bnyT-$9nJW?nw+kyX)G_M);pDsYs9i&gPeNchb>LX z1r1({UH{q$5hs(`n6RCtT*A~`F^L5x1z3QJSiXn#fh(UkOHLGYZ^waJH4b(&^lI*+r7m@l1v2|P#6f@6f8 zGq3i9_KO-38N;rxn#?jIP*9@Z+8-;4d)A|kC$bPz#ha3-#1*FDs+lmt| zzuvLDHTbEG6sO~gdH(F&dEAfAZ70D|3+Pp%yXEzF68EfLT5sH)=$gwipYg1M$E%c% z$m@wOTfQ~8;Bo5xCE3;AkO9og-#>m{B&yNvODh;8xl;%(#wbvCK^d_kzQNzNV*|H zb1va@&_eT+N!nPC+wq|@^8u9a$HccwEaTv>axB0($1T%u;16AiaVn=SzTD14oc^fM z4;PY&3FNZlTFW?l`{{|T5P9#k*#)|+;2 z^tiuf5IUoLQvbT52lkZ6S53E`r)YYo47GfesK(D90uD?QLhLV4asdRrb8hm9KJRJk zYb`nwsDbklOp(Y-fX?~4&h$uqz*Xa*pGnm;4k?X~HwhJDFBk8XFsr9kDTUZ-t9xbc z_$OFy2yt~=_R1#ICpo?cr1rO&MAPcy(c}W|Mg87$L-i>xwq^W30{f+N{Gqu|<6Y3g z`S%ZNVvcaQDXzB+7bxW_*+yiN@B$6L}pIL!J=_e6yLI3 z)s1jZ5og++A$M0$!Q}fSQHC<45myCH;DYms?dpDijr5cyzABY*&;EcK#UxN>ELXww zC3do)+V``<7q+bWLf6fce!njhxOF{~O6P&GmRwSTXfwDQ3zZ^281VXPCcjdPWELM3 z)A_9#S2S@Z`dxxR9EOKor*Y$EVf>}!I`eXfH7Ck-gznC(r`iM%I*^Hjc`Xpft9qDfZ3%F#xAZH! z%GW=w8Ie4rWax79#7rCxyPTkS!SQqgS6FqYWB*$X7!vUPHmN19Ix}KSw zm$x7>O7g{V$I?0G-XvvOUF4l7?a)~bIdf{gN2mBqSHj!!Ajo+j#TMQJ*}&7Y;L;EQ zBc7lsitcUtuGmnIE?8*`%zEvURHhX2^0|{I=Fs_pY&jMK8u!H#g_FTd z)G~IF?@ob>wVQfV3C5Ly0H2@Z6-_#)R66!F(@O`iWI8QI8yz7cK-86mnlW1`yLPfZ z{9mlycTiK|`X}%Jp(Z3D^q$armtGPGy(FB%(m{$K(xizL0i`Kb z1f(h*B%6EZ-n(UXcYd?8ne+FV{Be@^JMDoZ6e_&Qs z)P-U|&e#@(d=$ja(w(}_pCZHMp-MWUEZH0}-!Cb`70Wq`Ooi5NP{JB}`QM`L0o`aO z)NjEzxMjVB{yokxSytR8Uyn{_MoU!4kOLy;)d+FZ$GBPvQwg00MSr-&!;!ErKU@d^0KwD{m>uGUhPo7* zCM{3$F?XMvOG^k@IBRXVWwy|%c4NUl7LpLZB-95WYJZ+ec!MWj!2GCUnz^T-@sp=_ z2IIG>lL&u0G@=C(e&=Zu707ge#?4eksKXXlX}pW*CjvAjCGACcH)o6|OX~W|3di2F z;QnlU9w#b9O;~nJkMbTNxLH*ctIV6Vk^7^mEcNzt0R%wZsi7#=OaXWj#?T-82E~z< zd|w5{5(x;Cv-u89(7*>ouxJ!#{B3eHvEb&ca-S&`>Q7GZ-lP})2ry`Zx|psZ?e}fw z?pP@P-i>;Er@!#b1@fX}oDhJlA`+EF!E}l?L`Y-Rn?eCE^tww)nhAcRs?ZLE>}IG0fZVT0){Ashbu%7o3HrE zCq*nxM|cz-Ysv3mo2wqZF6#;iK>cR6(7$V--6W+0yY7`4vo(GKg+ z=LH!WR?0^AzsL`MiOM1VjlnM&BrRFRkN?s|mvf`QNOW6B6tIfNWXe}-P zIY^62CR(<+M`Ak$v!&?AQW5lEFuIvLrbZSY5RTMDR9xS|XRO3#Yxkbe@kh<8Ol2t0 z7u)|RB8{-6tDysp4eArl8Bk}5>lUkog*}YTW4v!ctz~@@3cKg=K-7Ohg(qx;UWY6f zgHRkqz}LwRqO9;xewW6K6G-LdVV_P6X;pt)Zy4W`T=q5t=Jnzs+hT*Fl*$62+a~$} zwVm?I^^UY+2j&tzffsC$Ilnu0Tr|Lh4hT5FpYWLYZp?^{+5RTiS7oKuT?W zf9Ol#1%zY2>N&9(?s8s+abe2J%Q_IZGNwa1Oj;zU@lX8@XHctya+l~?eUAm2=<>kR zRn146M!+9!$4(Dv9PPAhxVUo6`^!{D`c_hV-3#p42Vcn`dQ^VYE_DS!Qhoqh?NYIxLKjWoDbBvpGbmT z#o}Gpts5N@1#_bSH{>C0l~3J%2IejXRD7`4-RvzIgl6N_x@>xE=|z%p^4m=WIhE)+ zg2knKHN*Oqrc5H#^gW`vp2?Q!3B1z7=VCcR2ORvgt=I@*8&j1>L?eF3fJ80 zU1`Od#Xp^hADfK6b&7^y=wPJm9fKtC3%rU|WJ0`AcCOjcl`-(20^ik#ijq`J2b5|D z(rUK-ey_+LtY}a57Hr088*M+YD9J7yjDR~OuzYwXq?Izpn&6=GlLH93Nun&=v8>?D z8>-CB#SkT`i7u}^ns7M)f zwHKc^*3zl2kgPWQw3VE$`3n9@qSKL$V-R{n-k7yp{I+t`GmL=hH7+uxnd^145Pys0 zuO=@PGwgMX9{-#BubY)$x0>-c-(^vCdrfdt#2TB6{Nh@>#j9H}T=;uCW@25r+(|hT zJD|h_Yb5$rfRBQ?p=mZ>_Z;xQKYRWDmcN&1ug49|y!yJAMWCOn_C36|k8iI>apbiA7it&2a#w)WzmF1JKf_Z0Ky4p2yZch$;OLIyUms-MWzD9WUV6Oh4_~3f ziMpR>LPr(*hhGGLXsRGDJgJ_1pe5%|QJD;gV;dEg zg$@dL9rwJBvKyBA>neBaMSyv>nA!kLFzi-)uuhZ{Q$O%{iT#zp1~ z5ezq-)J*hMHsYQ~1c=b8$h#*3IP9S2QpLdagar9WLSe(#% z6A4!ro9=BgH1g$Y-{)HK-Lh+5j5r9;2w&ksKgU^N`JRZFCSG?JWCLSmg$t2Qop@#> z`A9Pd=(X2;v(S>Du(SA*m+vu4!^+t)^G%azhFCP0_+QjR-g^zil~|sa(IR&ye{%>E zN&5W}+Ne|5_$~RWjt(<$-&BZJV1uq~U$mhGsv-!}u7lxzsgrhWRVuP!aSlV`!&A)$ zvwn&hoip}Tn0Ri5Zq;@YopaYXfe11C(`%4$a{LwkIBCMWXzMEXBl z^qu{{!mp5~UbJEAw6&ghpK;0RAKsO_^P<*wowR>NC(^uT%lK=89>ItEekY2~CztDg z7VP@+%)F?01eXf$lt(n7{f^N5{&Mdt?*5IGit-pr^suD-Xoymh-{0PjlU8USR_x4Bd{j&y(HhqUSlZTSdQr^dQ$G|_~ zgn5!$+yONV2X^gVeC==C?GbW84SN98Mn#z?BgpGK%IlY}iTk-^O!)nm{oMQw%M5Kv zTvEt}0A-7Q$?gF;BZ3=+I~0>hA^66mq7bTc~B`Gau%+ zx?S~@o#>f!^RoeIVPdcZAn<#VY>99cHCV(L^Lbf|N&E1~ZrK9NHYN-Pl z+j`~Y4`sX|*vCT&9gz)?e&MF3?C0+87ryB?iBP(SFYvc7@fL5ur2B)l{E&0E0CPsg zGjJt)lnD5HRo=#(sY{hse)c~h-WPJc(81oBw{@>@@h@rhe;&VCk)Hs`wf>Z!{CP8> z5+0`B)w0oez1-dA*F_zCJ+7VhSy+MU&byfx8RLP5sNzA9S^WHKJIR+fDpBF)Vv$5u z-MBAS3k8afUlp}?*w9@uu|Hla75*{TQOek{l6&cO|1J4#$K5~?n-Z2^HrB+kvKM6mJzt5-?ZeexcvBBiSiE1Hahuh-8c8z z@AqUMvkwX+Mk-WAiol+(O|HGCb=B%_d8w#qhse4sYTV$dEO(KbWiPY-#eGZVc#H8_ zGe|o8=f3GiAIjWo$69f>vdyizSa?(iyOp3Sdq9-c?Le| z+bp>k_5FnXVsLGd&vYZ0M|i|E@-MwVy|D)=b?1n?+Ye)s6tnZQ;+jH-a~%jHouRa& z=3TOw{Eju3&mi4bZSL8dW^-X{J=qG3y`71zz|?$TI<@D@`*32VpqF=!K4hfv3qFZ5MRSOa#EKXhmi)=| zXhz_RT&dG$8Q_spb2p8rOVUL884hjP-S~=$mMp};w=x$KQ-soI^jg`i`O_t2en$N% z=6GWfJ1Q>&w#`qBdQc5ZO_d3oRG}zH(BANd&vc3~dxGQa&UlGn5@|IDZ?~3#@ctu3 z>d$)YDyr}b4D}+V@yX{S?ovHdK0JD-{2aSEa~}oQ>Aws~R5BW&mhow!B^2znLa7)B)?hN(yTVKm?I10ISW@x8%o%>s<<#d?E05wKgPv5Dd9*@@O(f_^E&Un z?|*rRnM3@~)T6fru(j6xw}e4v(aoxl%>DJdINAO0;|kB;Vaas1k6i6(znAa6yWloD z)2xU~3|Xvgxt0A9X!A^;=3;RMU#)5t1I;#Vq}m$gp~asNTPwYEIJmqY@7!W)Uxs2a z;}$Jj_z6SCf2js3N^)L4(0}eOBl5aIPp0?o@Id zx0(kD6btGMq6dmJRU9?zqP;yP<}yuvKkeR~_LHw)O%3wuR}(%&d6d>8@*hNpFNXh| z@|_czyiuA?`ik9&b2>viR+gxq?VVKX-e-3FWi0g2d*QN7;UW##3&dFS0dxQk`J?OC zr!$PVt?L<3=9x`b54HH8X@@(m@*~X0b%u)%5B>VcRC4I>axV8BK#xtoyts`?#ZPy9ZtGeMf|7&*-CV)$EWO zg)2~CTd35KT)i|1u}HU(A8MMP36rDJ?6(u>uOgiHbDpl%36e_&o8mA zwknh3ggnYMRo?p~jxwCHjNQFsrZjxC(eai7>Lxkxe{>b53I3<6knk8F=h8>Owu#Ry zv4i264~x_}v4;@aswhgVMH(!Zl8^`Qf3@iS@&wzOt*CHg>xCyU@GYRaz2_b8a?u~$ ziiU^2pTp)${#tqKOIa=S^Y;fo*YUi2!|BpgV-b5zFC>^INU$SleYyQ?|XSue$NMIe~8bJXRe#_cn=N?KGOS-_Oe@_wL=+;%c=oKpw3s8uRn(S$eQhC z&p#H6pw&Z2%G24wBcveT>1YSv43jIvcCa1ekCxy6Y(}K}S2H3qGAisP31KHO66_o2 z&#_5~aC=Qo0RzF_p|RuiC60wZ-#WiNSulAvF&0)7ktwS1qkzPlKP2S&e6; z90bRAzrh!vX^a+}ZH&h0clgA?k@5)J)O(eW=SW=t^VZxlng{`;j)q0VTRoO$%)EagS zKSV3otr4)z&dRr35RrO|zPj+xNC&bp~^0Q54L^Lf3O|J)EP#hmJ1}VNrB6klGBhT!qzbSdX>*D2NN>@-tm2Lqbn_D7y%1Jb6e)~OB_V9A z(i5@sBF3x(j5P-7qYy-%u0#VRM2?%pq4=ON2iGwC)sfzV2*?HG^#xBYi6$FR)q7z| z%M*y8L~YUvL5yoK6lIOsRgGM=N2-mD+|m_v0p8ply-~Qq_1>v@*~ZFoZ;mN%FzMk1 zitJ{JlTi#m!uQ9QU0e>w6xVk0*_k(YtAT5n9VoLL%%bzOA2x<4#3|*BO!V&65%jsuA)gk3K82Z@fssqvw8b$6)^Uh<49Pwc z{%2g3I)4r3Ye*F6V=38mAZtjXI1PKMToS-B`g;WS!Jt3;c=fIi^MdG_R-=2mw=oTX z7B#p4b22bOGJfEpe82`J*kp{H=1xacmQ|ijQBYq`G7~gXlzITjomeQJlkfGt!U)>6 zjsh=4V{d#o0dTb^4N8hGtb4c<+?b4o{qkqd7jU5_P8Mfwu7W6tn^;Rv1+bzBHbqQ*B?bnFi`Yj{ zb1Mt?XV)rTqWVd8zoB|TL%Bgb?j#nk;Uns!>O z_V}0k^eklh?X#8_{*TZ6wt0*xRH)dR@5vF)(KF6*q#IG_*lI$J*iDR86~h@NCT~6y z>Itjs$!y=tP$nhe;FC7iSIAPazsDOX@gVEY4i=HF`orP_^QBg#* zOrV*(*4RFM`lP(7;#5SiTSP!(V@uy=i(>?ll6IT{cJu+j-Bs{Qg#DcWdzm(Sg)@7! zq=OU<*)D(#bLJpJL&if$UFP>dhsIGM+rgT~$(6?OH3}pdW=9LKrM~YRdgdISZ5u4< z64&N}3~))3bWNghO$s35XbIu*v!+l6L0a9Y(f7;S6gN?@LW!RRouh0T)Gs0exP7&mQ7Qc@qYDleT-4pLE(J7J-1n?lUjX)ueNW%` zif=NgAx*fm+8+OVD#-+6tHuZM!?MnY&Q%W}@ZxZoW34EbK){XRjf&;#1r zb$d)&`#6;1XEPuDm%GYI#!8NV1cw79hb63*&XH^;zPy29;iXiIHbnC%y4gOym{#+Z zpXNV#EO0N(=|eovK1axWP*HzFjm3K;(iY?6I^x4`5IzKT;4s}Su8YS{~K1sPqy>n>* z?_~3kwq&*^^#?+kY*~xep5ot4SK3JUdy#IQV?Ns9^C>99wKH_NBbFw(SU{SLD<0Zw zftNB6;)~a)~I;-ax zlz0}?1Nfz&u=@YL!!gGkSub%VUBHag3!k=xi?!% z1I=4bIa|ZuHoRkGnUsC=Lhc>mlf+4Sz+#v7a~sm$-l&UJP<;sZg&=*vVoV5w@%!s` zh3l3AUm@d=UaW%rQ_xMXb%xAa1iH4r?KC!{O}d3YUkPiL@Ok0A?#X~__nRLkXSF6# zZ8r6%Hei8kZnAJwFHF}lqs$X?o%f5c=VYYZyGM0PnyA^|h6uuX0B&cipm++N%&L*t z?hmS`A71efsfQR8bdO^%I;*wDm^n#l^5^%8>Ul+60k1#4J5d*A8qJW8z%n)wERQQO zjWH_^c1;cbwdsjjm$B~};g;#R?wV%)JAQ6aeZ4$M%rv!N{>j<_r1k)M3)s$9Cf$>m ze#cbsN8Ug?)LnzFmp62-TxwACol?mvs5TNh5=N$Yieru&LOi?t>bw4)PaInejponA zSr$Lcr^Ox%k`5KU-R~9O)`%%kpZ)d3lGU>HHFLIe_xu~n-sA$t9a=9f`JS$#2dO;Z z8?ux#^J$Zu7Et%Muh-hc%TL-1<^&6n5Q~{OU1)EZdRnYn{94Ie=*!T8lm^QuFDy_$ z-_8FDMY4pD_Mo&~3&^H4c~S2w08eM-7{>{>zwKMh|4>-_`(%yUt|HB5A+8Q=a6=n| zFRORCUiq!)GH(_1v?GRj^P|NkWq)p`O-X&s7aecED&P(vzK{E` zAU%TGinkz4PX;q0N`G1`He`I0VcBwK>4tuP@IrBOdU@E2nU`ugDw}YER-EU8T-H+Y z*XhzPto`lwu=LWv?bdMNvZew(HirP99Hjc!KCN=<3CToYALCcew*Tb z#uNP^nSS9kgz@Z$)mfy%_pF{v{=b*|`%ByeE61o6*6yq45qBr5PeIRqg)+?RD(uKS z`TW5;*Jq{ITH%Yc!YQ6|Y;QOa#K1IC2FZvd_^>xa8(oZJ1j)H9Ohrr8BJ`W30RXWw zjZ_eJSAZ@~tb8m>z&u@IN33EzhfTY%EKVGkl#?&=TW299H}ju;9TrkuzeX>#968j)1zz8h%Xb{D4XWH9`pej|CFn4|i`P>22>pc!x*zfd z^VVW_QM_j&VY%INcw;nXxVo$3^Y`7Qu4hoCo|_G+jAwOSn;)6wpNwF3^k9L&rsfnr z0Jes6H5?pDyA+&}HB1*pAuE0F@$a?4@6Q>$Mr>nPgjB7)$Eu$X(gnXXRx=|b%PfMK zXtd}f`Q2vM6A45|(xYN_T1)VoQDqx8kgmJI0;SSJp;|e^L>pawKu{> zf3KG6Dp1A@UY$g&iAQ!ntpZlihRbooEY>$B4PmhsFD&2T6~+r&k$-->^jW<$FMFO)2u=&GhyY35Nk+r~Azo=KF7GuCROTLtFXo z-~bH{@kdv8t6zJyY4FJXz?1fd4gA)Kn9l$JT+2KMm1F?kq;jw@iFhf*+GlNzxsi40 zyBSK*&=Yp!+m{*UjS0hk2k{dHyw_ChSKFuAxA2AZIxDKHopvva#rq5WV*5M~N+24n zwSP!~G~J(d58964=~DlY*?82slySwLB3!Y@WmTVw{T+#xx9hB5qHoF3bA=;kyEV#J zsMOR%)FW>*el}LXtP~X$nd)RJDsJWYM2@sG*VsDBrG2vUKO!HCN~r6+)} z5EvWB3k_l|#p4tnHHrwz+7jxls5qb50S0#)O+v;+6>*6_9Uh0IQO2F8K9v7s{~K78Lk&{`&)FVK6PXI1=qlk9UMODD zTqkaJ87Au{q>}yYK=5oE+??sC7Uf+_XC}^0N`0axr#SYcCGCg6G)-m=V4d}H`-jp^ z8WadvC76W~k)zq-{9ynNSn4nWaP%GkX$&IjermhC>rqf&8ZMe#aTLPS6_32C$5ckW^DeY_x0Z zwEf-wku4fPzyMqaatJlW=_jsJy$<>ypmrRq+Z|5#F=$AlzA5QpqCHbe5rloDDdpLX zJ^5hv0E>{A=cU^w2kYe3!P?8dByTDW^Je*TPLwIN}oQS}oUE_*J& zmw0Nkq~#AjX_fnOHi3Uiw_sqWVNp=oQGDO*OZ)x>KZUQ|bV|>5#`P&qitv))@{sB= zUoWgglqeb!;ys;E%;7%@3zb}@lQqot8mp+AbJbrmoMyFaE!E%O7H*c2e)Ywq%JAH+ zyj9lYB_y##V;_01^zm2I`;Ut31>J2Z9lx|Xy=lA`Z4w3 z&7H~~GsbesOZ6LXniO`4^mji^3kBBj|J^rdko#sl8gTiA{4nSj@GJAWv7UD@cIX>bjPy&Wke6jz-Wt=_`hful zA8}fXaU}8N$ffabrE{6(PhJ`Qa*#jUq1`&%>cO8t1-@B-uD4!T$qbnvtR@XV*A(hm|5I>nv5x$BS-iAYK>_$sZ`AO1t|9rf);;u>#o^np?;&T638DX;5e(h;IDBlM z*uzul$FS2_5%Mj^O0uiv;AhrVoDUXq(F=Nd6eZlf22Hsb#4&=254$&5p_e1tPk(3P z7(rTWfd7WVVV=^fWpv&7>2s?SgNKxORw5B?feQRJ4;2<49A3?5FrPIyy!-0<@Os&q z`P^!cG93vjvCDIl*yj(bo|}(6x7>biO%iQbMs!yr+L4Zqw1`M7%tSFY z%2Ol4eLLERB*y1ul%Gb7hD%H!T~u&YjKWAv=t$%<=}566qE7qhnAq5Eys)I=XS&m| z+Q+e}9kGcNajJ%K+0t=1Mldgk`h_%A;YD0d5M2=uRaq5f#Y@Vnm)Q7{k+{0;c%9;S z35tZ~k@#@Y1aY4P(X<4iri5V|gB11}0DAG?ctidGz_KuSGYo=5({M3t z?8W#$kDwed_`ebZr|9~m6F&qcj&>w|x=5UsPMV{Gr!|tF7C}~kmWl)t$;jkEmqdhZ zGR_=C;3a+5NV?-EF4H3Z=RzDkKzFW@d{vcrBMrwt0$~ko0SJN~5$LV~Su_b?c{^$K zWomzH%8&WfZ5}v`Hw|G+)L{cTStXwX!kI3UQk%kiMKdIV!zFXV-y3H1G-Y&6XD9|| zEY6Ys5+N3cksO7Q0uTVAaw2&IXmb@0VN2>Mf+cX70{uYfAp1Z)sY!_cA*3)-H1i)h zqMez8QC_<4ePB+@oO|01q1cIl`YI%n5Rjp|IDolFDXEF;$}Q&K=+ zhE&Lm6yQiITwL1j5nWhLcI0UG^UG{R8mYwtTM}HJpbe345kwXUu%^$pe~_JEn-kHQ z?dkdwIi15z3P=ZlJiQ50M4+0%xi-Anmq+n^y!niuK`k)&TW=7ckpPPVu9iVEN5!#W z1UeWnepwPOmv0#c?*M=k4fBU{@;@%*Edr9cEC2LL#wLQ(*LZF=~Y0f>DKuK@u$yd>C0 z5PW!45XwP%Xp_yqSR%|&dQA$Ka4VITmG>ti{q7CvOx334LIDSJF}o!qe5IOZrEET> zGO{`srAjv&N&q0-_;I;FZn?T_fdv_yd5ZiI0MHt&Yjp{AF;IDPFHbqQLbaw`gAAZW z2Jq&qWaWdm8%PB+z|+G@aB^iA8h{I2y;z0jqu`sVAYK3-pM7yJB^0|#?#YL@04P-? zgRk0Ps}V?IY^p{KMRkT*^^4rz@_`l&Rewz4aZP4! z4JfQScdS|`>a`~sKz>sN#et!p(@5~CZF;QyQR_7gA81IXl9~%tu!x8CmZ)NYzh10~ zPOHNuYJVaFtdPN@-J~xXbGK`1QfeBm-_k|eKq75`DZP+X0Nf>&yc-DaIRYU?@nxro z-i47%7?E`xrCX8$F3148iw#(YMgsFj;yfs6S0iG&5z5$v%Vftk=JHQL9c5|(-gS(i zMtto?fK4OG>qhXeMwqrr1V$q|N+aH(?!#lcTiF&C_Z9?yGXO=rdX(KNQ;#&n*8j|{ zq5oJTw$yYdqy?GRqI=y+NeWlR!E7)%U4rFJe4DEr^;T~l4}X#Qspj`6_@`FP!W8t~ zEVLU)79X$k zR+-2^FD?SwAR#*>rGL<>I>||&?@fLrk|d8{;w!DpSo?QI?J6T#PD;vg(LVX)7{j`2cwVgXaSvJjDcpU8p|*Y_c@K06awWYOn|C11fN% z`(yt8Tn>KOmCJ_2yK#TDw;*=KXowIsObYKs*uKAb{XQMoNA@TYLTI>$Fnq{JM-K+z z&Z4iD@Bzj^Y#6CzYSZ5%P47zxT)G!w*qa#M&nEx}g8_nI0}+7%0O}to8++OSAT>XY zg18k%EQKQ8F(6AT*3943%)kSup@2@Spr##0_Zi8aw121S0_xJIb3K>nd=X^fN5y%o zkViJaZUkhwmCjpWm|7CQA3-ADNc6><+`T-}r5d6M21Kk9Nf{7t6oC*v1o>e^V!cG~ zdLehZlW4B9{t>&0%1-ndQOg-Y^kGMm!K3LqquGh0cg8`>y+o>0pl{xAiyy`|S+BxH z$HEQ95|&3&m_`92qghWzbHIRm#>OUD#^!Uz*3|b)o zA|D7Z)@7n^6SNi6GnEpgWr=1Ik$nd z1KzRQ)(9^oiH_1yT28NdPb1Q%8NW>XwsXV9Y>ZY0Y zrxAjmIhf&NA1o$5h$|9cXJh(4tB}vAD$H!jr%?x|(RU{C?x!V)&I#$xig|Xkq4PF4 zRX3*Qm`RyR3`SDWw(O1-J!u5kDd`?Or3QZbZ%1UEIFc>(V`_1Un_F2rI#22dO87v< z{L7S0*X(Vot{eYC!%Kog*nISwrLU?<4;t_eHr0bvk(gCa|4(?aK}*JTeHS{<;|O{T z0(7Eqb476KFmj;6LYJ<8DI#c(1Q+ZIS-qmmA-BqV$JitSL7meH7peFBVmv=u002O9 zfJG+lmW<=YCT4gmIsM670E}^=TlYJt9bX~r`%cn#7INJ4-|5YK*LR<>$p)g@&DiDN z^_~i=lYxc|hLZkVWo&luPxhIQV}=j*&I2KBpkB~I5&jSIwU}-E)iBTlnaM=U$qXc* z$s6*si}4m{fdA-gx({gPFWHPBy+Um-p`|TxQYx}>YDFOpJVBnzv?itJPbmZzDw?=& z;T-q{0%M?WT7`HPP5ioIEM=zuPbRX+TgLU;k>oWzCmSMcDyb6;lQ#wN_Z|*jrZXx0 zVJ<`f_JTMSO*kfPcqTtg0|cexxu#ci6aEdfF4(+fqW3#W{_eeyOz}ndFWm=6i#vQh zIE%5rw#aN=htGFryDNF!PV?eeHFpiTrC}JR1 zG$8*f0>&j{ts+uVydmK>1mR(=r;y)BC4V>qxfdaGr))`&?f5(Ebs0J^Aw8vx0mmJZdUw z4+Wk{zS(KGU7RJ|YP>y!VnKnVZmD?(Q(ea?^4QB27o0M93V;*>V59&rhv|QX5&XP4 z8jS;_ke5IJ4*&oV2mq)9jtQ>*4XR;p|K8r-V*lRYvOuvnm)Pr*+w1H9U#8mMC5S9?6*?vZ0h>j+RDnx|HW6E zot>STnfd(r^X=5sCGPq^Q)(x}!&gH?m;L?MJw4~R>s`;~*qf`7imUzt>?dFBfay(- z&qaIt^_%#ccHO_tXl$$S&=Bsh_~XZqV`F0@BO`-@gMEE{@87?F_wHR+S64?z z$D22AT3T9~nwlCL8?m(#*h(U7IpDU2{ZX=+x+V_isMXfiR##V7 zR#ujmmtW`SV+(lyj5&H1_9HOxzk;ZR zgoFeI1>q1ie}8`;AD`bI9v3c{-_|zQ7ILTej4t(LeyeMoDhtQDxZoT$4-XGlS67^) zW@l&j|KO-8Dk|Pe@oq~=-wLp92?$}4w1*t*I7e-hk@?@08uTBO8VNC$2#5s|7)VOW z$jJOJnwpT1(0@f!V`OBcr>Fm4Ks7jyQ~NK2YGeNgP>q65I)goWAO^;+^&e1ed8Day z7ze7wGif%Ljb`xNdpho;hVFkMVn3Fz*;4T-Pug#Hd98{|u_VHf?eH zHumQA*9Mz`cxLUky|3cxGc}eU+v=9uy*I`Rv`t)+pE>(;d@hEUTlIwM-;#Uyimata zLlbmr={PoqSXupaa!c!f{0CGk6}|mngNW&K29)W((tG#z#C5h_sU@2^ugxvL*uMMw zr>^$HmEK6}356v;pN%(itR{u|e|~?OES74>G4DA2^$$?(Huu8+({$f6>?Bj+P0;uc zVcfjDqSK>;qm7TR^xr>KK5WnV`E}*-`#)#dbtW&u2=FgHhn#W#6I9cneM-P-)Auh> z&8ez58qtf_AB~9Sv3pL6z^qzum$)D-d57jo68PDoY$6E*u@-0`BG& zy_pYqeb{ru6>HtG<4c2EobYPBx=Y#e8=tLpUSUYxlff1m@M3%}ijKgsDE z=6f>RjY`|g7*#0F|J_CT)x>8=WLQAliIG_6D+4wYHPx%+8Igo)-i)9eA*k-om{w2d z78u+U{nk2I;(Gmi+{nc9jp3b-)L?#m)g$~og5$l6N&K`Tab+|+rWK{}bGB_si}v(P z*Kg*N@9ctJ=;`+-=UClu?cmz|FJDOGzELiSmWQUUKKeS_vEifs%RfBh9^{Qzu=TI= zt^7bmgD>8r{j*3J0`FKk?;!C>K^8i;WVt#zIW*7K$h}VtB$nwA`Nk)|#R2ix#pDWm zH^2M1bk_7>8)?u}Y2C?>RG~UE_nt{@L3Z~q&z6V5j{(F{!nYTjFCIR{7|5y2=x>W7BX}kdOiV~$MG|(Qr!~P7 zU4^rHRsCYQO=y9#Vur65%8XpV7+Hw|c>qj6&)Xi+(n|5M{ZjA_UxOU;^pv z5GAo}0QgZt;Jh-NACNmmGu)IKEUNcnu#86VPZWje?>nb_wvnxYLw9r2-VFHc(YcyFiHz^D_e5r z#xU~csGow=>IvQ#w!|*IKqjyT6axsS1ZQ#prcz18H&>x&K?DFX(PTuUjnacwUCjH= z#&LNZb9J%Fg^hk^n0{PhkhJS9#_*{f5YF)Df_NuD`lD>Je>!*-BYoflv7lQ+hkf}5m_$*k1?WvU}pu zEnw@*KVM@l)j-#=YGhoWc{R4QYxdQ=i_F4U z-@HD;)1;Uf?_p5JN6JV^JJt!)UO#?*%E2-2_OD3|k8~4qRwo=g$RoX+f89+CeOYqv zgXQ9nAq~Sz2GgDsLa#ujGt1vxg1x?eje0dEk)hig#lIfmlFb-dFIX-H5_KCL_xNdV z%TBXM>=Sm^OQv4niE1OGtOz|nDI#;}DJPYY+Vt$CvZBX~`uZ2|kq z>V5*>Suq(Up3DgRj&1npxU*mG0*~|w!#t4fN4tRxDzI%SuTGPe5>wh4U?ovns=cac zzBp+_y}fD^oT}XQV=6mAJOQqo`bYA=@pRX3O*dfMz*oTN(V@WT5RvZKXz7;jF6k0s zFuEKiAt~J;C?QIhARr|njYvs}2!ib0{XEa{{<1${$M)Th^SZ9{GmvVfDrETJ`Myc< z*_1NHs=+&V>A9M;z(#c8k*kZ$2eKWic^tkb+DE1L!hD94UF;%@6a~2N&`jubsinxf z&3UpkzqrO+AOGg#<%dTRzv|ZiowxVg0XHIn_icfMiZPKF2>8!SWXlr&fy38VJcgtE zaU;n`(Ys4EUnk%7{=57@LVvpf)$Qn~^Y)=*fux=Jx06TlD6=tABm(qaBb$+)fbeKW zIU#ZA$?8yNZuAfcn-J8K?y=&&o;(JA(K(OEiF&?xyDK@>IT`Hzi{u;Z<#B-n(+Lko z_82$lA=!cdQ&-ju0OxI%9CnL6Tq8N58-CgcNKd`*#<2pK_(st>G2$(h|LgY1wWo8+ zW@!==W?aRH6!-O@N2>u<9663khM2&^q5C?Ya6BQfuB4~rt7<*I8t#LX0q+x^P zMfc9VyNtkhg>`JPGJrid-CTeYb>l{?uChG0o95I7f$^o_?W@0iIe*q?NjtV(rkcFS zW6PNFcz4$Y3;|ge<-ArkNJ=}hK#2Xtg^8Fi7@Nspy4abZ_WY1wB4pX3=P2*xxN)n- zVet7~UNyx7tl8%<4CNepi&gh-zJ=_nJq1)#eJuS;p=u{*{O<3Sn!_btOp#xV`^v}riVLl3CA7nn>C-P8gc z>m^aQjr9(Jn~qvBw>lefKj(9avs$E`y0md}jS{V95?7}y>m|XQ#>M4w8;J?rO2h~H z3It+DV?yu~)AwS<`yhFN;92MRV0E|oKa5X$Nrq8?c*!IHisi%kgJgAnC0l+NCz`)H z+O5TY$QF>tlbCcF1sJ&p#Wi8t;+2Oa!1{U8{CEd>*fI@xhjLSBGk9NRxIef`QtqH7 zZ4MlFP8LUc>0U8ndP&MoljB@DO*6Q*B-3n#xttW!_IT1fwo;nuQ>P@UV}FoXF2pw` zSS^JxYW9+hH3Qcc-7`!6gW2Xv3<0*lMjXuMLo9%@8e(PrbcLatVPyfOlaD1O<-{NU zNONlm3pY&;kwg>i36pd%fDyQ&PP~61Za$~@xQx2U2lu!JG$P16_3-BeNlCD{75mF{ zIp9cLb6JC zvoGJ#o&=MejYP@1y(sLsCsOi)3y__IyAQA>S1x%579#uS2&2NVDv;RMXR02D)R zv{Y`4S#DftZURH@^Xr_%rQEdZ+_=tM3=ULF%*`58%FCtHLuC=> zmxkuYxaDWofLWz<*vA-ZdP!n7UWPmWkIhzM7=^Rh>_|&|V50-niEx5Jvx4E!g3-JJ zoTfH`)6}jDaGKf-PE#{0TnH^(%qv{(EL>zDG#@7T#!$3{O)N~D&QJWE{|X76z!0@P zcBa?>JDn09ARzCTUiBpAgpK7yB<9~r<<>40S6vqamh(W;CHZD0_~v=gPsIXIU`1y! zVNyPEQf_@-7F%alfgQ+068v+?rRS6=fEO0jnJqn*_7j@QnD<&KD(0pn=Bw#zE)A;4 zT&AcHhKgR2lgbbMlb`SC9aiM?iQ#=n zMr~Iu>Q^m=bKNWYy3c-=Nwy(x!(OUiQwk!8j}YXz)m|~v+E*>9t5*lcgOED8f@sB$}TQFkRX0Z3EH_Ejk-wyn@8o12o|1In_Pkz(iFejxxy_*ueo#jfx zGs6Cox_H|zD6S$zj3~1XdmfoTjB#B(hOM8X)Qx?FG*E% zGs(UB;jsEaMsx#FixP$DG;K4lMG{sJB83(HACv8r&;iG=iRack}nkXT8<@9E8 zp*ilL`F6P>hL76pofGq3xmF7yo-esQ5ugF!hkV9V1%IXfs*Pvmjlf}>ZgP{XkV~NW zTakN=;>qliny_sEF<6LjSFb^Fg+V`;$e8h+V`Uq;#XHxPHmy3UG<-Kt&3AuFQEht7 zAXXx?n`+iN2G-^{(T(;T{EkM(ma%tl_+>hz?A&YkT9Y2I6NTVkVF=}6&~u+~t7l9S z(lxo`F8P`ru{YTj$u-Jnp7^;P&MVcdgapfah?{!SxM-z9s5Px8& zqc*d(%ee_FdY@U45V!CJ(5;R)fxT&WxOv|t(@N+15$fyr=B@D3y)t-SonC%>5e4Bl z`i~B~-5r`AabKpp1!o$BqsspK8RG8Kd(^lD%d!>Jut9o(AZtK?z`poB8)V1R#11%& z4MBQZLe{RQ@-u++5-qBR{lo6IC=aS1+1C6|8j~%06@2kG zF{GA;kahrpTrd8*EisNjJAx4-aSRuVtg;0xvjTR4lYE84WZ>kl1tD1&a_>`0&UyxD zat5EJ1HbHtPK&5Li%J9q;GYW7KaYXR)e;QBPaq%utMJEij}c{UKBdP;u2OK^n{ z^w}V<1pX(3y`3hu#L9N!hM{)+!`m{w-z|on>w5&F@JO>EUMVdeLd36evmRMkBF@JiGI->XcwLVYh!1CKjpYyah>=ip zKOreR9EMELqDn~jDL>%`(%Tz^V13BOH2J@2Qf3l>JBAE5IhyqmUq=yw&+xG&3E=b` zNlM1|M+_}euX;Ug`z^;_*1wtXoRT@~x!Hh@PmHOhgZF(*N+#R@aL{}&ajh?KUXa)Y zh5xRZbo(5%4kL0Z!S6dI_B5FMQ80-|QJ{G?Sy)0 zo8R3%{G@eea`g&Gz`s}`O3jH2f)QyTNX2JC#g?>H4?>_#+P49OAPM&X;zTg=5pJSB zTwU=gxf=jbQbGzw5+@bFtR@&F^2?0nYX}wNR%^wVl`nw z+BiJ%QNh<}{ImvCF!TAAHU=%Cz1im_NP4U%Yt9Qp;ezcFocad=x8TG1`#G@u^97rL z?nTJ^&lVq2r}|PqT&K*-d;w1FPGvtF!`rO>s=rtul#s5s_C9b8Q@A$rdGXydDl1z% zwVNrC)Fn}(wE`i$l10E@ZS&jbAA3k$?zFq4d;xXs?{Hj9Lc&JIgP9_I02kpf`I;$( zcg)Xc>8U>#@29~e5ROFeHvwz)ZZ%9RS6Q6iTge}`2Kd*Hes1GY0MICFvSR_>JA0Sh z zh7{LcivLo0Up69(FKi*&`(&Kp^0co^4^fJ0|b{i=}hiA>Z~u=trt5zXRd;6DnH~5eK5AZ?Yp8 zGo+6OC$qtUJ64HDt!rE0Qcxhu2m(8N&-`;lhNX%zX(2+RSzy0dVD?SXo_HVL$>;sZ z$q#2=>Yg+oSI!-GrTuW4{CR0j#e^Y%$e(^c-u&ILQ5Ds2Ywa9x*S(gub`mim-h$U5 za6)*p`;E0}3^q&Nq2Z@L3;U}>v2{6#o;`zzbDl@*8c*n|{ zrGBm5XI;XN{3HN-V#IPP_yrhHOm$$N&i$91|sHspT;$9$eUv9aP<_^+DdW{`R&l%-{$q}3Y%L{={W8j)D?+y8)SdnA5f*DJ}fH`ohk%MqZ|-9`umAYoR{)!S5z zBVZV{o7US>PNJcZPjS_^ONkT`{U1+k=_pv!GFbPaEt~F9Txzvf(AR9!gP~@HJP5@q=kQ7ll!2$I-+tJgiVLF z8lC-IAJOd|QV^RqYdL|+mO<|O$i0K!C+aIas@+JlztoR?fJZ0V{QB~|3@T4@kBF7Q z*>zD+nL<{VFlYjVjlc`cXdn z8WfPX3xE7gkPYVVW9CXVEw8Ceri3L|5!F|rb86F9V~G_tc+6eVW}x|KNYqeU;yd-M z{PA8LgMu{YTO&g;ZH~{<QYN#pOFUWQe9r+Ej z*EPm9muOvZ^r5}~Js&k9dmg4h2-;c|P_aW_{)pHr}tm0YLyig_+*QKSRcS3Ay z0D{Tn?KI*_;`LX`jr$L)naj0pF-n(QiDB^C&i-zmzaMI$O6tCVeMwf9<~l)~ypvI(v$r8dWzvdz**)6n+1kl?(W(R( zMbZZyTytd|SY9T2T;y|IxpmLZgjLq-tPx~a|GA^*Z2Atd&{iFle(yWNoB2ol{mH_s zHy@ooB{d0*O@^H>lSGEj4?Zr4%5&5Tkqw-mPx>Z0HSkQXZ_$Z6{4`d&S_vNQ*%V$r zuyVg}&?wsCL&)}uL09mY$4SBUZnm1MY)$pn^U&!JG;+J!$c z6}MJGwg)vvw+f8h{$8IaiBP7JEdYl9`_sc5k$a1^xjx|R1s1*VBV?FDGhWJrc9jvo z*!BOZUT~?NPDRs|CtS@r^kTtXY3SlsW<@eU?eje){8-K6KE)^8gh_kGgY*D=CrKr= ztB)XnL<6i=IlvUrjQF-RgVyPjU|!yddZ3(p>HZr)E*2H1+g3tqwmZO5c^aouPG~@4 zOHgM=8p}#e2vM6;q)3fsNJrT-_Hhq^?SzuOQ&?!+2;|)4s-M|hZ2Wdt8HVXcIg{!+ zz>`N*tIS$b{UAhS`UcdXqf)Y|MKzjpXLVxMGY^e=8qn~N6f)?IZ%hFP{fOF_o`whg z4ZSKrF;8vXjM6u^o`!>d_py0CX_m5b`L%lICsIZZz}>-&X2{aGiT#V%=JIS(ErMKg z@n3fBgWEi2yc+h3Se0NrhFzNHxOMY0A!RUqkzk?Jq&YG(s*`_1z<23=?PC>KJjc4Y z6``!-j61&)hl~6Zr^y3t!~DA=P9v?B7fzCZqJy?c+5IO|W)-+DU-c+?PCo7kdGgYK zw=R$R1RI`9+9#dOu{U({vTg9&zvgDrSNRgGpKM_GN^gJMM*h=GDvxM1Nntj#Esavv zCA9*dF@w5Qt@ekrSaanHx38Ykss)X;N)yddx)qEpB|)$fbtda%To(41INk^rTy=H?hEK`xd~D2HL@@Vkg}?>Jw2zy zS{)ZB-hGwRbp0V|{;o0T;Wn}%n3!R>&5Moo=@pvdn_#Lh3a$`NL!p`5_xNamE;R6g zCwVNNb$e|E5}U;1i`zg;qnA(}b5bW+!Nv1@a{lyTRr_TrFqO|w9!=HfrH-JV{Wy z9bG4vkPh}oipu+yMs@N*4QoI32s$FMJveEPo*Hp zb?;jeYDDP!okD(qyD!AW_9Bv~zJ9H+NU>p#$)kc3h~*S zmpN(9KD$sOBHhRIr_B7YXA^mO>TW;l^|fnK?2TsXu9L_!L3ZjsZ-p!*b>Ss+**yikp@jN9&l~XxyFg^+~5IB2*tuLWjD9= zoY9$u8BD^`Ja4O@?IUa9V^GfpW_G(!76D?$h#95qWiy}ujEjiH)h6kvY zk5z{R3PNF~@!AO}Vp}|K-0$xxz9y8w7Zpn*2(@dL2OwgCU3*6Mg|A=rY_7Bb>)vh= zClmF8U2~I${XYh__K;8_vH=jUW&rpIfwqnEJ&i&0fPD7iBlhr_1QVWA6S(W4KY;Pk zSNK|z2@+QXCCCID3SgR#f`2Fv5^1}ng<=Zk;0wQ&ui4!Hm2xbS|V_vNTt+g&5O$0d<2s(<2 zIq`QgK$6Jlt6iXiI*!9U>_YkP6T!EtUVFe|qzWr8|9V0XV#~z~MgajlC=XbiFb~-M z6mK~*UJn-ic=`iOi%CS0J)-SVWPmv8LMrbzL12&aMQyU!#ACOD;R%N%uqC>!lmhLF zcJmI3%dGlE^|Z4vQL1 z+mFX*#|m!;HM>4(G2UxD(s)cg-c>%RF-Iskt^8I?QyelLV?XNMHR7LM0nOB$I@eIN z&}=Iot07LNzz`W?IzKvUa&A|q-P7_fjdGHnSk{=x)Ew2h8Gi-G>pA7?A<_QQrfTz` z$md{U>hDCYrZ!+up`aH;H~9FY=fr@=_>(YAtbZQ4Yxrk|u9S(z6r5i51P8cv;L%k- za4%PFw3u+cubmGCL~1I{-Ea3l&<^|i+1!`MNpf^Et8~XSZ8wAr;DhI9i^fb)nW886 z%O{u0KbPvoJWs&q2fSac@0p(v-;Po^H!AzLM^4#6pdbiky&|Z9Ok9;ueEK$NwnE6T zM>+OQ_wR)=R<`n_o~E#i9azCig-o~NjY8AMYoK(m>s3jthM}p6fW;m%A0=9^FR_kY zTT6Rw8y*GJ964V%C5cqHYkYUo$KB zeOBH$%ZN~GVrSaiPE7a%JkX8~4cDhq`4ZFI&%iswwmHMKH1n8=^3mHlkG?rAnhcFX zN)Ty@vNg zq#H41C z1QpU?GEMzno4)vGs+nb$i@Wa;jg=EbC25<8eKRZiIf-$N(wN2%pT<*|mLJqxGApX8o`tvU!iOJZ>STFf2seF#hGr3uHqo*~lm;X?h+pSqo1D3N-! zpk75os-^FWWp+qB_K74owgaFoXcZqz|JBh7>9%-U(cJ-!`6CVV#v5eI61cy%F7HX}ufUn!88vPzFl77e6|^CgsbMa9}N_ zu~w8~9$~faSWZY90yC@zOJnqhQp}(J9?LoYynF^Jd&>H09rD zX}Aef(OSpqYC1ID=aj%ta?9s5&e~S5yl^8vw6?l-lcCG*=eJFXar;=wC?|lB+JWis zRr`5Qn_NH~wt8ZXCxYI!!Jeec9?G=+H^w3viZVh}JY-mmOmUF9To%MDej*gtr5jRAmQ zMmxp}s}rjmlJAy{OpEKCY+NFo?>QM0zZN*;+r8S0x9W}cnT++RR-<>=J@az5jQF1J zW6iKZywc$OME;4V2_YrI0bm+MKb-itf$I8oleaioWOb}5eD6swWWs#c^x00BhodGf zAy)?@7KtJqPqp&+*hOhVXq^j*$&ImsIp679qJqe^^}d#yIy${|W%O?)fxQMSR$nx@ zhJM_|7!wB3gJNKypsT%qb}h5iZd)Ay-?=D_#Sbwb7qK+l14#HWh8KmWO2Ho3)|#sNCbfu$Y9HtOfEeK$cs zpCIywHhvg0Ae)%e0^uNldWQ@9cG#A3!5a0mJrxY zL$qP|Vd{=N3qRtQTIGKouI3W#y}{f33~W$6ic_`y`q3#F4v=Av!{3ld`)B;gL>=3u zlPFYz=iQ8NTAkalRxI@J=cj3WjnSxJ+eKjnfw76}>Vka**Je`3lna2ue9~+r%RRpG zfHa#GAwRzTl0=~+K0?q^YXfi3#AE-ZP@M&cF1*Su&HDJ|A!=tOT^*n>8l$xbHsbL9 zheUO7JpB|BC7hrl3IknQdoC`R4byHsm&7v;`?2!&>7R%bHdR8FQ=HQn=Yfg$?iHCX zD(!o4+A6hweRRA?W)ru!;RGPbtvw;GI{vh9n!boJ-K&?>h+n z!LHzkuY1(y?UOZ&rpzb@R5RudpWIA(h2eIl@liqv@ql%fm;C2L@I4_Ge=KM4DS?eI ztqYU^LsXDOTU~TWtNY`GnJ~z95v>j`ygQrzn8&j*A=r~g{bxxee))g{5Jex?BMcCn z)O%3nyT+VowumoEj{+jVUKqSbIrEM90SOcVHAAPWFZ8;8ipX-A#_9Nfiw#KUiLyK; zc-9;rF^czYwzM=fug||V=ohU6I{_(j~ZxxGp>6{t0l6az>=_@ zEWGnKODJE~@0M!Gx*-Jadpm9+1k@fsZQ{+O)La09z=ro$A7NnNhQsOe75T|sZaytf zU1HNcNX!Pr^z^sw3%9_cAF)uBAw9G(^Ni%l<-T=b>eWsx!FTh>*Vxb0x?u{*!Svqf zE1;A3k3IPiVY1(jHc&e`asbBf;`>#q#8pf?)YjzMHt32Qltz?s)r^R*g`kwwUn%l+Xt58v zD5{yC*%Mv{!hMdj!k?fGJP!%Sbk=$Q!A?XL#0rH_1D$xzXrcXU9jO zk;QJ#YS8_%k8jix%=TjGQ3NBwVDD*MMU7u|ZTPstk7l}m*n@~aj3|zh_2lKZK7EmY zHmi_erN&q|LfR1;ko$gt0KmNGHx|hzB0RB7mp=aFXri6%EHhx|IB1pN$KE zf%=z5!o7(;up>02n*N6bSkC4~^fl1w3U>H}>d3|KCrd4zf_6K8g0uy0SL{DfEry6x z7&BnYI+#GoP3w7uVH-}Ndgv}nzr7BlVB@|&kv<9Sv#qB+K7at$(m?M#1MAHU2Nfv9 z{{z)pw|Sh)A}AlaU+~P7Yvc%P{}sX?sgy0#SbhA~eWcD*%pDKzTKtg@-*>Ll(Cz`M z(Ur5->R!vw!7AdL+i{ma#XaGKl(dgW#)}?$?}cGIDiRD`HV0kZ1RYeBgmy+VxOJHY zZ4V7QGR2+-shhF7jG24LuKXCajg<-XsV5~}`t30#{+$n^zY|2^(VE21kv_H{percP zE~|ChF;$|JF7ovFRtliBd@w)jT^x5vguJz(g@K1mu^-4|>s_$XoV2K*>$G0K7 zC&V)^t0}uS3$Fe=aI8NPiUbl#Zs=x@f;H~@#<1yf8aM@i2|8nyST~_Isb&IJ;fg5; z@oO+@Oneptv17^!#6+j{?~M?M=lF7|cW06$1E=y0|V+D^Rw?%OA1RNQ#E&vZPi z`?&Xjx${H?MnR6z?NMC##<%8wubud@IEca#qnyOYy9qfO%jVzpq}qnQv!FO^C>jn^&J#_hP^R4_MNz{rx18DGw=}Yllbm1}43J6@!%D zBn9O5-KWsEJ^WTm_Ov4!@B6m7Hi~|5`(aXoY9FHGr4afGc0d+SnM$Egqu3Yg6GPuZ z5}>iDn1YCAs6q774yYGMF5=jE6rT72kN}{iNG)-}4BxVik@p#3d?qytDG`r}-0KDV zodUoh-ccmw8%&%m2OAZyx&p``JuRGrgM4gM-QZ0|VnI2l$m226a(kA~2oM*T0W|FP zCM$uYg4Zx~OriEob{*E!kt@(gp;$d$dVzK6!{BHpj2_JpGtDW;-ip@U0MQjs166%O zV9d8=q|hbEk#!DKO0PA4p_@y*wdS*zU+b&2TQ11~-bvq#)`DHxAL2I%l2>QQSB7tt zSf+WWLT6fwF1xv@A_ zEfWXdBlj;U?nc@7f4Xvd(2_oa2xswCDbcYf#+O}Xy8z_r_<>B4R9oK@{~BZqm0f$GJ$+!GwmR-O!{fUsM+IWMQ1(W+smO* zS;x`w{ny$-?HA|c=)kGc zfpH$cx>ELMkO%@+ED37x* zlmT2q+rvz`-Z%Rs{lq;yP~vwGnGgIu42eziiBt_HYQl?vKpl8F#6)6>gHV_Bmotd zPBRf6Tj|%*o)N|I$re`^2Ts^=IYPUb_?a$1f5;L@e@Q1Z;zAO3JTZV#7@=`tGeXSS z7hiPI{vI6wB}52%3K)I0b}0`PEvq?+1aA;|cu7v7kK5O{?r+Wx6M>|cNW?fHpl2Hg zUmjQoOe(f>&(^K|CP|m;TI6I2`9cgp2&USEzk(;KkGx}tlOq7VOjajqRxlvy37zu7 zAKJ$sV|6gVT$7WCM?@%Y9bfXUSU^Sd5;dD5EjL+2|A?ykTRO^KNgC`a%5Fs4I|vM* z&|{}(7KCz6`!WD{;LN|6LEge=X>6FO&vumgeHzla2tV9Z5&CLW zs3Dm7LV&Ui*clnA7WDL@+E6tCQ0-pAMhOsrl7l|H*uZ`n8FGR!$Zd2hZqs4PySkCQK9JNi9VMNTQ zeJ7l;|C|O%X5gj|S#(JZg_x)WYHX%M`=-)MU|cWzm~4oMu-3-Vukx@QMgBB|GDRJt zRDTYxD))0`bjWe*tMD=Mz^Tu>~A{hC!NHo$R z`t)SS5Pb&Y0FG?eYuoA1Idn0l@U%?|wo+CBmCS#p$^}LmLw34)o2rsq>}wmkgY%a2 z^H%$FH$os0*Z>&HMo;;Ao6}}TP=%=blOVsjGJWqXDTL!qEQh%Y|EI0&RXgqK1KmI0jq3mIez*M;s+WE zuQwGyJK}!_F`;GYZfv*nqrBmz2BV13Q!xIfgN)*ojJSiWfP;Z!0{48cGOX9+Cy4_7 zMl57U*R=Fu5Ty8;p@fi8@uLkS4i^3*X+Zj!(Zr)?&&zSMYgNMBI1X z4I48JNa;@0AnRZ%5pUwlz4R^343HVJ&jtP$0_&c9r|srqQWI>>TevV-%t59qxrx}= z%bh9JRb9&~*nj@p!lA8L*9gb3feYMqo-(=>yF2JkAWjA~RBv4|(W z;pCDvI#|Dp)3GvnHyMin->T?=dUR!&Y7BnXh+qecYC%>`*KS$;%mIyrxBQH`e;MdTh+4!q3BL~ z&w5zn-x=o8%p3_SBy4^${*r-m6Kq z_jp@dKOoOva-d#~Z${TwC8eV*bqjtJP(NaRn6O)`u%KLj4Ca$%=q8%#?%!$*I~Y*p zPui_xAu1)5tfq4tthqx^9`ldeyU*}>eNcTo=((#LfYa`e7G@5!?Q4cAcxdGtU?vs$ z_7Gys;rt|No$${Y@hVj#W6|yhDkc0)f9nzMb<2JaRx&og7X}XW1FuvEMRBg##KYCs zb)#!uhA09m1lrLJ3ke1BrU(6e64v-$>!@PTvuGdK@sdxuqwi3XYDZdoRh(<%WqDUF z;HE&)7oUeIrD18UPPWKvk4#{QR)CQ5!2HXBqB2VEc0i)-c%@rl&7d(#0|E>%5CZV1 z-mgli^jymDI{M_@#O5}XRx;JcEhqrNb>fo?J)M<&`rWxdx^ zgBZ3Lyl(>v6Vt$^rXAYXeV2`jxxIA(r@v`gJWPD1q6K^^8)lE4^?IwqX_et6C(z8( zkxGxz{8JV?{cXuhu zMl_-mO{&!2?R5n6h`dQpb|=JDpVKH4cc*cA3egQT)0MT5Y!SLSHmcr#;uj^ve6vpl zKG|~?BwRKtO4=98)GO_y*mYot3>>_Ouq2>KQbz)5Bf%J}V(!8IJ3kZS@?@>1; zQm>fji>oe@AjG@V0CI0Wao|8)Kc01u&-`eBW{fBq4^^^XU9Av4@l$$flrE&&W+@mp_ zx<3)vGX@WT!6&Xj=mU{cFfnJR&SM6C(uq+SkB%A+qvQt;aL1;QZq}R3Qs2a#g4NibSD|h(H#g zHPWUvC93_kO?zEbXIzwEv`_O#n=V#V@9TxmpEj+`dN)X*)(aFd!LizafGqbQhwFe$ zH&`sdwuDibegV{Bex}hXs-lE{-#UsWMa(Scty!^{c@?hIH_*%`>VATl#mHOBDKYc+ zVwRb|X=26&zx}qf>AOGIcOOG+cq6P%^=`Vi@7^r{7Sb;Vi{f<nAAiD|I+B|@BFcg(W0Lvc$RzH**;phMy`-YV?_UBT>M2-=;{Qr! zreYI{LB}fXq7)FeV0-zeSH2rCkwQ8oR7sLfSvj#+d5l^MNl7>gWZ(hj<#gs1OXXK} z<~K>bdeuoa8b#ICSuiD4SaN8{70YCM;dlaa&H#m3q7 zy2pTb%s|u&gnMd`XZ3McgJZZmV|t1Sz8xuGB$4I9BK0*{G6ZC9{8vEK!#U!~u?5jh zs``4; z8P@stA0B0t{&>c*DZ~1OS_OdSmkhSCA2>96f=qFDC^>GUBFM&~v%!Fu4~i41AW1!v z!`s0rF0vy%!6_q6blRfL4x+zKk<8Pe@GIEmm7lPxf;IQ#|o z)r)(VLw(Vbi)iWF=+Eo2!tV926qTt_57;4cPJ1*q*Ymkv?f0Jtha_J1i}>>z8vBg&&c~ zx|Au&-GX4ZdNUTcGXxQ{VEIFr?r?N?k^-;+6%{5TAIFBmJ>=eT+V5%EHbPns4X+4^*o> zqE~XzOTWLP-qMogW>}?Ls+ukR7F$CprBUrX-zCOZ`us1%*D4=Rw@^Uum1$`2n`(WG z*Q$NYy+2#ul9l#%RZP#zt$QNXXh#V|DAZLYp6UR*bA25~0^*mS^TTQkT5^Px-X@9p z{}|Uy`zaH6omePshbb{0f48}V&fp$MTb1Up{))U_Tlg0Yorrv(=q(s0X&kjWlFt3~ ze%|HTr=rs2)%%5i=k#y#^(m4eT1+y!uPd$I8@$^-Pn{}z`ti%V^Ov2gBQ9nD+6fCD zLRRNpm54|z*5en?hoPdnNyO(yX+7kR02=nSk9S?cxe2b7Z~+Fj~bynwc{jn~%*a*z+M z$X?Vv=FVwTS7v1AOaH|1`IMki%jA5k((!eN!GsV~t5E0tXZ2|#qH>0gEUw+^dUZ28 znm_yJv%2-$xqof7PVsQ&XH1~$@3-{;1DC3OxQVXit@k&?c zVtvtUqC~-NF!^Iy<8u)K<5l~&#t3%G00RI~A&r!|tzuPdA+6mmwM7&uZMjCFrn}*R zqMS*c!KIXQqGM@3jGVYeL)h5#^MHw*+@CoURx|DfmyqG}*~Na)hFU%ziv8L|Qy(?POdi1( z%b?D29AX(7_@3IP@s25vm&0g@AiF~2U6jsT8y|f|?DN;1+^?Q`)0f7xr!G3QbDe#D zQPOBToQof!V{U+XO0~38Z!W&1Eot^rq*h;ZRbw~ZXRXGg@FTv(4|It5oJ+;Cu+n?$ zbAq))|EAL{v?{Iq|L)hk9&S%`y5xR^K8EffJwO=%G{J!kd`?bTDQCm;zif0rzT054_Ifi~|kzFo=Z(YBQNU+pwMIIyB zo2awwB>rrEKfG<3LPlaWE*w6D#I4urJtaz(IRI=6e^tu=;4|p5{qb2kBR5s>)+11V zyLtCih{O4k!eqz@MwdB^?Ypj1vE5O9{#`}JVp*D8hL2qT=Lw&%FU-K%oCZk5IQuc9 z%?&kWj9+j0eK;T`Ck-D-`tmUXZ$k5Sr>X}gpaQe`f;P+;DwO^PB+l(yvyfHK0sB3S z6Ru|k^h;C{cw^v1xv@`&dvn{*;^S53#%~zG{V;(S+Uh)Uu32<)_q2G(%||DQC4>jQ zu1@oqf7=2vE%dJB;pQn)U^%}E@W_2Gf2RO;J|G|LYMGJqaE!xtH&<3yAR$1Tp3^WxFdmzC zkc7HrdtmI=Yr=Mv{Vti4;TbQcgu+?EnoYIq4a1~epkO}BHxBL>dEE~rn{4*mkin)< zCjL)O`3gdgw1;j}?$WSV-ACxB@?YpyMQtUuVLy;c%9A36RE0cQTcbL@3Wk$Ud5zj$ z%NB-?`YrpE)qQgLd?}?G_0bp413ji5ERyt_HLC)4{oN*-u*;57o&4{jnyF$Ae4dn~ ztoj?XXcQxM&eweQVWK@A;QyzMeTe@{8u+EVZW#L zu>ax4G*~=*fEIKOkg>=8%~%96k&P*H&rG8=F2H1<$4c`2LNPix?Tjd$bH~HzVx=h0YzDO0a`Ommc2{exm+tJ6MV9+oTBd(pmg z(YJlfM7U$qyL50AE`pR792Kx-#hBw-ljlNWJ;pyNo%Wae-6cXq*h($_VL#4268f;B zRkp3nv(-Reo>b*0LNu@^?AiC%vl(5bX;d*;Ym`fXW1a;VzuFfZIC!(YE3Cvx=vd)XfJoY7T2JNwaGDVdF)UZ#lf_o2tqN}ucs zvY%z31L%=(3!M2?+n1bVS;E*V31;+cNhOBGke&+;A{JyZk2^ZCaDh1A@G%#N=$#UM zI%FE`=|kjP9!-&A3Yh^s)IrXwjB>I2xg0O1@ahezTbjbkxfR`(z0_A$oXIOg&!@su zZdmR{)j$A1wA*dJALy~N^b8F!6krc`Pl)G$M%&Z0O0qU(n?fR>nc7!>6+}%T>_+)1 z_9D^vV3HqZdY zqN7@(^gvAMMhMx(?zj-W*YHE8QPH)PrR7$F4Y158bs6gmxZvh(2?i z8rBl3^81D*t=X1WDbWl5<;e5ItY5YBbo}iXG+jN@sv@>J{y`if#;gO34{-g>y>JKG z0KiGFnqy$%edbr6O#KT_KXXF8*%YZ|Xa)o>TT0h7Yu?8mT)pWst=`~O)8foq>r)(( zL;s9VkegwvdQ+jKkwe_XIw>gRf3I?rEaF`;NJcCw!DWDDfxtMw zI^g3xv-I<@D{b;yWsQH{Td3|cZd&KVM@Z7|S(lHvO)lJXCSxmPdJ?A*@n@M|Z)=Rg z@(t^G2O|W|WNYg%wdUGKXD?z3!;c)fdL@rt^=MMa8B!J!CqDfA_>b-G^PjsdXDR$O zZpAszWkv+)iN>ZgwDg0*Z}~3rm9t$r0EaLQ>Hv zWPUiQ(zHD)A)Ai8x3d=7mPDylOGZSz(r5p3$R096z&&Jp6uM19TT9o1qKX@)3M8an zRHepc_aQyT_@t-cW{}qQ+S#EaGU}JaLZT)&2ao8`G(izxR_+ic)DxzXhi9bnWQjh` z^WfvCCe0^wIaGA#-Gw-k!(GT}dwAeoskE+l$oAKNVh2ekJ=WDlnMWO&eT$g`x0o5X zkURRLcVDE`&McFnSXnn`$6h_{)>prap$SrZ!vF@1FJ@6 zJoy1K{p8jvj0!rO)Rl~3+nkRF@Re=c1GdJ}4uJ7`Iw(P&k*Al*r#lv&N_i(FOk51v z&y@Yf@)Nc7Uk`K$Q6cKA#=_9|({jSRR!Ij`ae#QpQ2z>8kMHdv$y0*7Q-+NZk_LQ{{CX_m zoAyA-P`2l>2z$ABp_trX0ckl$>6tj>$4$E54`ps2322}MKBvfvQHb=9$OeMszKSV^ zB+8`>%SmaH<|>|Mh0FKbkQYVY&4tSLc*s+Y z1fdG{d>waTB(S2o)D2LJ$av0?X>&tGOdugUoS~h2MnUdvG~+(3-A&VybCXPzO=$da&(U!cm;eF0e}DhU3*<)YH43@w6MXCwTV~+~S4fq?%I%&thrk zdU<`z_0xaq|BCe}RJQ)Zj&QoCdgq;5*cUPxZ)JtAZuWCt{=Vuj@KjkZ(~BZ-HI?_a zhIdq)cNvd;P7#N_uW$&7SKx28&0V)a9```Wz^Z{q`pOKojakB4MYjd2XF&NobLL5|@8*S@c=&;?%_T4onZ zemwG;pDsYS(M?#=*XtyLnlJL9UyN@_q|!#Duw7PxV)kz|%wWjP>UT&!M=11JC~<43 z)Oo1NS2mGe2E0(_$quOn2K%=r;QC@D31gp#M`d%sv^U|6Y_HCXTGO%;!QeNiU!o-` z;!9c|fQxD2VUQsk+94$g$H;`P2dGWLL{a6$BOjS|wBSBQnd8w%7K6Cl@HlW^Ty9o! zYDUE1>v+my;(tZ1PCyi~R0iLmpTw^)DLpOYteHN5>|H~SWs_*<8MQLs0P+j=AS|od zUb?qQhX0}vt?BHSEZXKd>wp8Ov4*%DzL1(F}CWh+^p^n+2ylrXk1t;$luv;iGxtmBSX6If? z^=)L|!(8^Tok2Cq;6Km|@17YXjWV+@UW;6$No1AafwQw`U9A$tJC?mS2iDNbJAx3vtFiPK%~r7$s03X4f-s? zfD!&fsEHq9--GYWhBY>!>|2`|%N4nhX?3Ag^7ca6`5b2tUId$5x z4Dd-&BSw5T6n52;+Fw`ZiY;?#ug0xjRy&)fLyOP|^|M`=l+iiwdudmfDgJ7z!$Ks-a&wZyD+&WURs&%A=PSYq+89p#i@`Ka_1GZ=HT% zz1HE7iTF;hE+E5WDiS8y(d@!g{_sjkN(FYa6OtCdQplU1OJ2JjP;Pe}_p813grOmD zsX0H8O*zL^p=0-=8hyl8R#6;Tpd@1ym@UCyjBqI)4)87P=pXOideS7VfPV!MrHWcPDJ&l!uY z8Jiu=jd0g}QZg9MSD28-7TjOO`l^ll6(76J&HH$A`v%Q@of-Q@W!u>~T8ao^HMxif z$pUHUhYve@r;Ode-hJR-pRRKUqnKi(J9=hi9v6h>;e~;MP+e;2;Vv0H-J9W)zY|lw z@Bla6>EqIxo!>Tbaz0_+ITEoyLI#AHT(mR4_OG?0t27@bxads{oT%dKdz{y^nm3J; znWW^%QtJ?W%hXNaE`S0IPg%^q%bML@oTV2Wbj#|LT5XnlqeH$b)-5|8B12PF9GOQD zU34RPNip3*JTE3$h`VO^?3kbHBIn^IC-zA(yK@uPZuokOvGIvqn(3Rgl#Z`&I#Dlk z#53P42DUAd^#v!jcXgmcj#Bw66?^OD#^j#7t;id5xnv#AUr}3Jfhl{aB~fiMq^Z`$+|z&6$zEK~*VZB4rkO#3pc^!}P%|sM|5l zwKkq$wmK?U=`FnSO=82ds-mzCPRlhJldWHt>x|u7Jq#PV-3f*)XlRFYL1>rmRhRw) zft8%fhSegil}`_?ir=rS`(N$2$owQwyo+1K^w267VWq{sY_|OVbtJRfAGqsprT%Ae zcbj&vB&|i1WdLUz%zx-apSD=&L3)gbBb4OU@oifDCz>faIU>yD^(m_(0s zHxssB5u0hspQT2f)^f6Wb+WVcm7VlJxaT~3bsC%`ja`#z#2)Uj@V{b`$(BDVlG^!O za76s(Wt2jV^>;C<{2992%#z~BoL<#_)4vHazu7~63ou_8-(1C5_e;2+mT}DSMUI}x z^ViD#EmC-+Z{0rky>GFnkbnapi;`}M076BI`l3h~rGp@%>|iN_mnNODqMK@5*86i+ zVmt{$sa!a%XGR3Sy`e~!;gtPnZSSA)E}NrlPsBpa>fa<=Ef3}X_EGOMXAk_dO7C|(qYF-Bak*^$y*-{Q6LM%OuD4xo z$NkH5hm%gQ-F0ZF($QL+f0a1o+r+ZS$!4Eqi*L_b<@29r>0f$M6ng&Mo|TDxw4$Ie z^D~N}@%7OZs4}0_pnFMRd!^IujSdL_kXK`AWEli=D zy?1CW5!@z}>RRFrDICIU)J3k82AS*6<)r^`q8Qa3^5SH}oSvsWx;y&Zi`U>Gxn^b6 z&=RF&Uu7!CwP3?QW*wi&TCyQ=99{N{Z2uo9C2yzsJGeSR49N#S6@=6W6l$8jr*%_D z*pBOYq{w-OU7T{rYr~ZLZmN;b)05>%oJ(!x{PW^zEZT_GpH zGxDK_zOVI-J4Es&$K?Af_xZ9`^T#r}Y!+{*C#5!Fsok~{93%kTy^L6CNLbw@H@O9d zL=rfarltJyrhyQ!Wt4{GSricugIK{{FAhITd3-;ZJ;Y&&(gLghkj26TdOCKG(}UF2 zgNR!!;J8|nIZ)R8LK6GtvoV)xsFPjTG=OKI??C~V5%9t7*_R|Z6Qw zrcHDG5@{S&D9>f_S*-pz8DNqTYp5&XbS8_Mw5*R>eVDt(?3H*Q@+n2k@L0#7Dtx9h zkEYS(@R+4DQ3yT(7wg3QrKwZ}^cZyQF^}boVtpwcs zo(jpp#3E1PWrSp3H#;&Nv)4+a68yUQA(g6Xib-@w!Xqw^u)O`U-4ft{C`v8Xf2k>? z|N2=kH30v$>%|3UkJETafTX~OD}(^ObcU}r(GrnPkL{{T3d!93`d>5>vJ;C8-?=dE z085t>S%{drQ1G_UMLlHQSKiS4&0W-`uMw;4x#q~h+e`UGL=dk4(I(g=;Y^LRfOC*& zFqJa&H7S6dBo_RW2}BjAKmH7ot^R|_Q;2ETBgHO3QT_^rqLD5Q$&td)EWC|5P_#`= zd|ArL3LVvWKPq5^U`*!*JFDqoeL#O=4yb8`<^01eNP6h3H72fPuDBu=# z?~R1vDT_*lQFmf^mRHfnii0FQ$xQ5{vs`$7rJAtxWc)MS>k_)Jyz1U{gP%xU$tq;> zw*k}9&aDy5Jz180z-<*3e|&0Vl5sCL?n|EXZuX4oh&Zi5dm6VgTve!AKP7&yl;68b z`_2p2Lz@`-gGK{UNv$~-+!*k{QEAu z0wD!^xOVJyZT907&(|M!NP9^guwW|4e?YYwTSUUb0RMbl*d0MI%YTDvA8PD{vlJF1BecsKDZ<68ubYGM}Gx0r2_Bnns zOjyu6sZyqNw+UsXg-4H?n_O$Xv2O$c8Xvn7e4YolIUjD7NCqxPqyKkek(Xc^K? zI=AiqjmP!zt}C(-O4?yl3ms2OQU!XL|A=K#{Ttt)X9v3r!?Fd>(lTq*NL6+RRck+G zdTUv837bj@_+ZnI&bI+ErsLX5AJZy>w#BU%M{ZX?eII&h`yjCFvwD$NzB$t}+k5}1 zpr?>r#{C~V5{si|4xjRN5_h(D+olqAaHoZD#D5yF1o)?d+=|*PoQ>{C_b0q+tcbb! z3AVnP2m>YMQ;Io1N?91!0=1lz6~sJVc>3a zeM-_xb3^Vqio563VqM?$VbWivl0BP&2D2|+0+&|~n_GIw4&4(1SGMl9v`r-)zJ4FL zy8o)B<2#v~hj3uaY=KYLV=`Ca@7Ig(SwzxFkVF(*GT-#*TYKXyk0S(_7NFLx{obp` zF|Gr(41|Lxp+a};#c@g0}! z+rG^FU!dCc-HU!as1~9t`yWt^?t%R84B?wCffWCNZ*r%3-)^w1A<+?U0?tZx4SsGW zUCq4@KCf}>+OtMnFMJOEQ!b-Tza0B0 zdz#C7xue4RdsZO`KB-u@;u3PL_mSPH8cuT@sCKiNa^)~GMSWKB{bt3j=lZ+^-+E*% zb~5$o_CO(Ie5Hr~@>>Y*I|3ILk%F};TJ|9iu4__)!GT8j4Iq zgQWF9?TR=!O9ry74kj4;Kg#t`^qGEf*{yN;7jZ=o;>-Nvt6JkB`p_Rph@1`3BNRED zCis~{JF6%mt1>R{XB?V0z7zr|kBzVXsnkOu*l!>Rz$T9M3AQ=K%`GH+gCs6FC4PKh z3`LXmh=APC@IqulgGoY5Y;uQ5Qg>`pZx%8WkOB#V)SyAKNXThj9DprBi8GX(FSWV^ zR)<2iD8c{$Al?y^#gC^kNRlr^MUd>}kZD0RXfJ>1H~)m}u4sE=`p_{h?<1{kE7N z$Ake8fZH@;{;S9lK$Nd7O-M6S1qx8(OV`Lo+F>%S+K{yXQi$za%D8v_qoUbta76&X z4h2UyWI*)cpX!jTY$WT)>8hb{DMbSwKGK8;$Pp?5UvnDvE8{^nGRi+I4k|ih4_UQ= zH;0M{Qb|BWC7y65y@h6lS7k>!XOVly-%$dXcbHWpo7DElTM&R4EToFr%5BHS-=yP(z|b*l$)t;!y(#g+!&p zCk%```95@;eXx!HKwAId&TC}=N?CxaR#=t(OFVL$zXqUK1Hh0ll`7pLN%684-oKlA zftq3XxW!P@@w)ahM+x5vc@rT2>-YhbAV05&sLm!L?>IgGM7n;{pfC(N4?u9!0VmeE z*DvY+cem>BOqBKr{qq30rxYMB6n=IL)61g2x0gu@AX#EV?1;eH=dAWcpwKYrcMMVi zS!p4L5L+O!p2K}`u2WFRMKXr=53wA@&(+%u?Z5^lwH&k^d4yq z1B6_wg=@7&=D>^UkO>|1uaK};7$Of;+q6C6Z@NOv9(|WPL{$XT!G;D~^+ zb^l7hKmW*_^?>adGH|a}H&A;0ywN_iBR@a$U zZw5W-KIV@=?_~$liZ3O21N1j5UltG2#W9>1IQidzrqFjdW5!(&x*Lg_3CIcb+$a9;4jNajN(veJA+=%4MXlYcm z%R;nU<#4v>Sg`hJcwRlpdZv=M^aeKkn<7JjNLL=aaad_?={gZkPiUAxJl>0Gg^i>c z4gZG5bbQXqavt;=B*KM85q8j9Cn8<3h_#mY>w=Srb-W`sk=1KBtNM6YAJ8sBHsuqspyh-{T9ezv&Hbj!)}dL0A4n002Z-^xNFj zN%^M9(sh!Jy4QK4a$ifvOFa-riO3I%WW&8xAIv5uDW;)H)A=WZqMJ8zT#a3ui{h>di zwr0Nmwn!86xp%RU0Ia+~wzEQCe>0q?WN^nmOCkY&ehdq)qW}6v`V+ulu^H6!cx~Ht zZ6|5%*N3&eiM4}+wIj0cCqmy(AAdi0{r)%U`{f7R_v?x8w+G*GWLSc`SRx%P@hdDi z84In&LWU+_hgbxB-L@V&mW>pyizQE9r>|Yt5M5_HTxYey5{E)*vdDr_$YL`D#s=cD z3tq87Y}7@OkgrsTMFc<$LfA;pY{(SdLGwsNXJ~s|DDSE}egv@fumCSdx5wxq9(5A^ zMUp51AOZ{F_S1+Q05C?RnZ$#jsE({oRsQ~~!dD`|IU6zz3S@tbAK*ZCuwWT1I4*w6 zOJ}EDn&9`eA)b<>zl1KKkOhE*Ml5W0fUHzy9m4)Y6AHm$KnUqftm0Bn`!{bqs3xD9 zONq#4LHt#G+=hPZ0Z90UhC=DcS&Ik+J8sCyWR?B0cCTUK5*!Jt770 z!b#JQ5u9@yE=-%YF0ezq?$LdS3`sjmMuq_*_Ss0m6DM*FIC$`N=+>3A;V|aeVwAC+v1_?{;VBVrS>*@DR86`F88e{{H^%?(VN&zjk(Zwzs!8 zH#bk$|8w9`u$z_nn>joaR*0L6`~L?B`)^ikCU$0K=Klf<8^4?wyc{0B7#_xBVb?=L zSAG5e0}E@s8bV)T3UQ-OH{H&cEiE_AZ*H3(;+jSN)rvgTZ5A-QC@IEUdY?xv{bF)2C1Wk;1Cga1~&@6oxAS+Kf{!~~0 zDGTg>ABo4pYHMrXzkmO~y|Ciq;=j4Me^XQOG#D;Z;wm=wU!=}IUyEXNeqmu@K|ulD z4$IBWJr0jJ^!BMpPk;ONZAL~$YHDgqN=jT@Ty!)(TZs${3kwMe2@Vbp3JMAc2=Mjw z#baUK-rk;`p6>4Mcogin^NVXoxid?vOEbAML&Gbb2Nw@zZxrrz>l?VZxHvjG+S}Xz zZ!gTs%F5i_+}POI$jHdRz(8MLUsqRGM@L6nTU%38^WnpX>gwvMs;bJ$%8H7L3JMBx za&rH~d4GsY{Nrc-!7qqoqdnwg-(q3=Z!e67{2!7O2ZP{1#5f{CGZB&h4;CgQBrGia z{{#y|B9VA3jEsy727{51kU*hO2m}HKgFzq=F)=X^2qYpRA|xcl5diQ%hqB}E2LJ$q z0}w!%H0sd35fDleqfiI+#Q%FHtQsgqltdWyf6auIXxJ5B4mVbPsn9EVl>exy`s@EM z6IQd>U^~P0KbWwV+SLw1#~T$DB8sF;zUzO)i3TF;>CuQ>?HWHk6UNS}0^)1ioTc{@ zb6Fd2YuLe;F}Nh32!kS|NEHipJ}`K@%oiH>6g+0+`9)XkwfEmlnD^RS=4J1L$$^A^ z^;auio;wq6Yj8X&_Fqg`iycCj5M?GdqssMYCiyIY^3`@lfdl)- zlMPFr;s?drhtwvDq+GFVn~CD{PMb;pH%yo&7gUr=?_D?%204&v;_!bmVaj>z1Mi-{ zbuND^LTaNI?_Iz6Bc6Z5kt5H8ga;i~T2!`E5cKDNGhv5ujFu#3qkY88_ji9rvb17* zOEP@?2w+N>I_`Y8F{z3QpEjv?l_j1zdI`WZy`1!#=H36ngt?@bri$1*zrTY7!t$y0 z!ZZAAuh^AJhcatEmA@rX#s5CdfBh+&9XYa`SI@~3vbvH+A-*U4yVZY1$YscGu4W*!r0ZK91 zgM4Dp&Cw8(?@IQN=jyw<-t45#t!=O3!BU8b)SXppG-X1>3lok9%tch z>3U;GsMN!f(J?+3SHGZSvD&L$rixeAt)xzqPla@(IK%$Xm_1Q! zpoqB_6NTJzPf>!X(#)Im!|&Oqu+XU@|AY=86va)efEM$>21v5e z^}A_2T9PZj)15ctbdl>#%-BK`?#CB^y=)2eRI8YR%s`=J<=K!n1B3vv>6mgL2dN(207D(!h=lftxY!Mm7_c`_=|!cA!}&}K zfMSM~(LwtBiA(IM)Swu5{eU`ueVm&A1~reSCZB^SyZJuH;SU0Ut$!aQQT^au05T?I zWHaOU2>31_bWE(f1WCk4%uIj+*bZ>grfP)EX1#4IluL>+WZW_j(x80C!9~LPz_gKs ze&C$lK>n#;^gRab$cs<#G}Siie}IvRS0KHF7n{X|>ocPiejEX_c1vt$Cqyi*>0n_1 zM#d5lYCPom7C;xuAlr*0^Vwp{_d6|H3x!hIO%9+%m7J84m6GId46=^Hf6kLueRLcG z6O8x`(bkO44BC3}{*6cw+2GX?PWzJnvoja*uO5_z@nD;Iuv;=a?ig!pJ z6#NlKd6*JNTopyd+%+t&h?si#hBMAFued~yY}p`!Vzy<3kWt(wjB&_x(hCmsYM}$O zd7?m%2YT5eDu+3PuyGWJ6aeRi0eS~yY#@dJkjp!aFkxenCpK`(ezy2YC&DZ&0k zSt=6x+6y?5qf7kGvXIw^&Eh9m;;Ev=PqxfriG)`{@RP(RvVXg7AHC8o4}7<~WZ&}R zz}4fRFFu$l!gBTeu2@Hz)kPkbe(C{15N)2&-Sl29$5+E!Zq*pYp;GzE|05JXUPZof$m{r zHt?(H1Fp8BmKL(KbU4QzmU69oS7GswfBC)k+4WEhku4+>-=u#e@+pftVQaWo$LCy* z)+$fC7;t@n8~fqqrTuam5lkg9eD5th7GeD3fY*S+4leG))Jb_~Dr(fzwt?-GX|o+& z%sPr>D-a4oZN7+^ZW|33CujSq0|tK?k~{UTdhf8eOV!~%$zD<@NK2@y(h9z;RSwm# zxjO|WP#+Jk@Lgrp3-Pn5XY|fVy1%|R#-QrCHd>FL^F$sOv3~gpXfXV+tLGxs)m)%! zSU9%#Dq-kb0O)?s_u|o(%&YF9SIrld%wj&^hP$;t!2+m*Ltpcbd5}T49sAxva7fM6 zN6MDEZ=ckf$?0c2^u=xX$VS?-Y$|Qgf2)aJA0Qpg<%vd|yly8>#zS*uisik{oBfcH z{c7vpxMvU8_vF%hl{eF#7F=ix=I5tGM0Xt?v`+3l^NRoIu%c09Y4{*PX7yy!7emQ% zk{Hvu0tZrkV;i~upqDZu=F#fjQ-3|eI#Pa~=Zjw^?{$;C#sZIS_C0=Gj;pZH5;7pe zNS>pK*m;#m%%;ofS8TvAj>wRGMYcCPN?*TBcoNXA9h-q4Q4a*})bUuciL;7hzN-(ayG<`fFh-ELNzux4bLg*t%ePTvsG|u!f*RjYacU4*I}lAshE7WQ z|LOOiefNf>HFRnC&7CK&3(lYH4(J>Kb$@T^oKX>7+kjr65oh9l6(FBcH#(p5TS4q6g%iopco+C8d2yN02Vb^9e%=lCk#+$AVf?#ph!{= zAeB!IENciEyB{Q>q&>{$Cc+-hN%zXmm(7~(d7gTNO%~;SKmI&0?SCoorYaXt0m!Fz zPo6s3BU4fEeSp>pZMcDnwtr=eUKXXi5s|kK(6}`Q{550}7@_)H^(its(TUOy7mJK` zpvo#URedKzJ`!DoUyk%P1L+g~!36kbMcsK|SNfACqKQ<5$D@PRA7B@HBns8}8v98@ zp_We5zLK8%FO80$?RkrxyAq&R!XjcJCfF%fzFbHbYr-g!FdmCcF>!9mqHp_2)6uFj zkmb$QN@ERh1>y;;c|drVptnoL-gOiUipG5X91@?^w(PE3eNLm}QGmmAHz?yKgp>{M- zw4Cl7k}vNNrIgXxpJq`>(2!9hQ@?2hQSl|mny_*?Ko}MinWV(_A!#l+?ldmbG*_P_ zOJjTf(Qwh;_<8+wUt7q5MEbZ>2IU?1?LKEY?a$gxD5&TE%G*}3m^VeX&B^t|Y19T_#g{SN;&^kBcAiQy1#og4 zjdg~~0MNXN27K|O?5X$o5-zilo_yI9UZjgC8D}c8(2zd5jQ1n&9{zZDHWM|1O^#R$ zih{npe16CAQ%=pVJGS?@KhWpC&*sjMO7n8g*6;|Qolf#!%)Y+JzS#h%ixZbYqZ6J$ zSCEJk8!}&F01W_k$cAV?4wH<{A?#&CW#^N7veOsmFZv5M`De@FvNOf>qfUon0!;I% ztAy%CGzO(267GQAr-|eNBo}Nz021~C3v#p}n-|H5HqGX9%=MHiaM35anMRPu6m+*0 zEK)rFa#jG;a5@A)xk3?PY)D1Ch*S4&UK0%>DSpjYtn3kA^&s_^W^|9H16q@n7^Tm6 zr>J}}1(XVia7QSkqKWk3681<+5l*FJggBPK3rj%iUW#|L9<`ThFO}+Cm1;aHRVOJk zGAnz!RB8}VX4YP&n^R_SRc12=uwp2GZdQiR%=P#QdRxmJI4kJ92503MB%LZ?8T8G2Mcl2c>bUNb&cHhEQk4k37HRyy^fW@fk4tG)QcQt^4c z#XYI_P7j^>kT7X}r0i~yiIdS5y`%Lgn(K;^UBrk9^p=k#t|q{__KHO#+iRoUEAl>R zlY0?82|xi;v>T8quu%Jz8{O_p#gm<;P+AAOc7az5@f_RVJN^jh_*hg25}+cvJ_cQy z!f$>R02R+a*6q=3_%%`*R@^F^>=Y?qM>mRruSY660j|I1U^;a+RK}kLUbT? zp;`^RV|52UALnDK%r(i996yo;G~g(nt28$-`R44k8|rkRPOj?IY~TGgX|R1?O#5EQ z3glq6=VqZ*pS)A2d(kA|OO>4+BBh`|TWVBHZ*y6GLNzMbpTN&$G&Q9ACJRarqC{V%Wchjlq4K2Ua-zizh@bJ(4yId4I4j^(Ake9+ z)njAcE<<49myq-)P*h2TlTr`)#|DA60j268l5N_U4U-vZd+hG_d^7JM59$$Krd+3X z)u-!@fqCl8K#9W;I6h=KvhQneM*c~P-!A4EsCQAI`Qm+7Aq;TxgXE^7x73`n^rYt= z1qP@OZxBIdqTnPeqW7>SB;|eTLw&;geboD(*cqre0Ui=Hov0SaR%|DsJ_(mLGxrL; zXxxD2O2?^vmk|C{#iHd_fD%7^$7&5e&PF<+5V;tlND)M&$N+Oh#s|QVTKT|ZS+sp( zmsSv^!llEjAZbqw*&iI1Y&T(;N#*U7&D)@Ho8X&)Fzw!u@d3FaVsCXT!~NEnSg}yP ztaMWA%<)g}5{H~EBxKJ5arPtVphQW|oKn*Hv-* zC+>6mdmJK5b2>?L^YcxWKZX<}zW&{(^fA>tUa@_kJuWK>S*g2gGeNkGRVNe$Zqy;J zkIDRifR}aft7F8xp5!_j`t1gxD}_|x=Pa%NM(kM;%=|=m;&YeaRCE642l@mb%OUZu z{UccZq&b;9V|$nfN^NV#Vz6*jbJ4toX3yaiJ*Im zg5)9ynltEvO**sLH=?j_J!4CuWUN@TwI9su>)Z?BatjyQA&fdmposlW_E*QwP8R|~ z755F5P_h;gV3Hl#Al^~)fbL@NldvItwMq1O{^O{<004?HWNH(UQ2oimnU7Sj9`Cr$ z@(A^E)~?|ZH3lEzKli^2GgGB`t*q1$fzJq834wp`njRb8*F)rNfUYr6IU5j05x#9O zQvv|ecg=v6whHup7z4MGGPbk})|l4TyJHt_0c7?9608>`PTF4ks>yn@ zWr#&#AumwUB>jbmq7=K=?CO$3oA_rR?F)ID9HVxIm6mL z^NGQxe=MyD#Jf6s>z1ZmU0Z=V$EC^3Vnu|8L$0$d`!qcFXReQ``wu%N_YZduLux5) zMT|73>n?P@H!&WAJ^{ygPxiWxDeFqcWA(RF6BXF_~WDL)XwEUXBl1pDP*m!@E?!DPjVrDXx$bHgD43^Knye` zLc(Xn(BF50{w~>WdAt4PP#EIZx)_CDF8%Z4cLztR0i06Kp7GsB363Txn8sS?`%nFi zoc!&oOKCan-I;%B=61*;Hda_DX6N>&w6L@3`;g=e!CPH2n~*C|Pm3n&{YIv1NwI4s z;Y)m1$*?fx!@578t#^0nZ)`a8rjCIFN1{Ut=VKpl^>96ZC2Rry$criKWsK0R&FRcH zgk=)Wh6r)nxH>t4JGq1j}_G12nWr}v5cRfy{ukig+LA;FQc6YwaO6vSnmBm_Df(+>` z!+qy%2Xnd2FBVs?ccbmh^Ic6^<__{wb`Es%eERRc%4a{8?>_O39(^y<`A>eg$T4^O z`*0!7DX4l87DKBm^JkV2$@iImx}Q65R_3M5-!qw51&F`&dbZ<6j))4Gq^gE;)y;cX z%&=;ncGsB3{@6XHl?`w|fLPq47%X*$QptGg{{zYByCvGgP(+4}T(zFM1qgfa#wtoc5fiR5tsSI2s?bL8gaxY+g_ z38z5sSsFW8j{i`sEDo3U9#O%R;flrXV1U6QCU z`aIsKYHV$Jzer>yO})u1_jYuWCE-pJfqg;!GZVL-1Bf|5yqBBB$M4b>{p_FZ-$Ika zKBt*?Tls&V^5Po)szpgJa5i8}%ATsb_*41LX%=JyEuv_3G%ReG$iow@$1WAo&z}3U z+m(nXNq#T=c`#~6q{bp;dPi6&B_}uyO|q5A#N;;|F85}G-k!zg!A_ndO=VQbeBA<7 zm>7rDL~+u6|H;x!corK_%xk;31Q!)9Rq2xbr43Dx6@S;|W6U-^faM>3-!q@3U))p( zc#a~lCE_9mg!pkBO3-mMB;(fg_eY0Y&rw0gVGo$6)4iKWQr2VeRz1jLnAH*OF~Y-R z;n|%6sAW~*^}k`a zg2D2B>oGjtew!%|<^8wcId=Q+6voI0{HmzvzWRw9>HpvasP7Iu>M3MNn{^&&KWESr zEAl=k+Log6thqaq6yhUNdC;;+!~A;s^c&9W-*w>%4girNfV+DTc7`#(yay$M*M^d5 zuMl0UOJ9uE1bygFWuI?R!U<21((H^7D9axs9`J6N#O5sJ7(giB6_rMD@g)F`v2UGQ zAvPCgX8HV1?XXXi$n$j@z3Q3gsG6@+6N6 zoikQ4vWXdQ-k8So}D}y&<OxJn0|ehR;#2IggzVlrkdn5(AbZWp(PRFvLF z=6!2k;uls%ODu0UUTafy{nCeehVFL_Mvn$nad=k?6gYf)HNALS)F+UlA;)8) zJ1@vIeWqzkE#OpsHCVm-(&h2u3yX%?C$dZF96ntFYBJ&9;*KTmB-+k0lU{yq+&xBf zSbnz-<~JTvj;h5mUBA%Id|{*_1WUMezhiqxrm;U~24dp+(kcD7Nu-TfReI8{L#hOl zaQyhOF_K$bpds4yN}d#^La z+y9K|WNcvsfW&<=<4o9O`rNq#L{(caAWsU61+IeT~CxZ@LHG~xBQ($c3`Jj5exS{04)A^Y9P8iCG0z&5v-%T9M{^NwaqU;5d%*Oeb+A+0cDb-eJ7B)OxUP1>$tIPg4 zDxP*^*abhL#ZfJ!3{vEN-Tq<8LqZs%$VLF4=LJL7ybj1l0TM>de_wt4aP$^0lLB<@ zt&yrK9w~v#U!_}?=aNtq14I;*!;<|p`6q!7JBE6>TVgXmxVD?LV?p2Blo-R4^e`(w zth83AoF^BO9L?vYbk9eB-TNJ^QL@Di4rp4^Mj=`^Dby>Qi)2;Ad zPE2^cLd4vPX8m5_FVae6RU59`SwPGBd1j~KteiD*`T8XO%io4RGu_6!^{6sJzk*+) z*3jV+I^3CNLze)x6Tdj&%vB1NmC$bIJsFQ45m&hqXfy8Sw{CHuz>wT-_Y}#G=Vh_e z!UGppO8@5b1*UwJ6>8Bu!D`kiw-qV)E+0=2xZUmI?7emMMohD;oAbX9#jL;YT=yhw zBv3<>C$f7s%@yt^$XSM$Ghlnrzk8mgcQi6K*V@R(x;P z14UqG5Aj?XiGQ^6vJwlG(x{AbSf#Rnc3(tmU%N&h^?FROJE34+Z%V^GMx*YMezu>n z%DCuVrAkAkg8zf5yI_kd;MxT|^w2{$3?sin3tk?{YD~-tE*_~*v#?!sWsdhxO03f0Sag4!Gr~=Fp zf(Qp<3sWbf&A|f(5FuM|s0W7c08Zc>TVj&MRG6l5H*_J(V?!+ykQIPp>Ro#@E!DXaoQR zizcHq9B`ljXxJ$nH~=vIkrcXs888PA1S2ewVgSLUU`&X5GEQ8K+J+%7gkUbNj4w$? z!C+)&ZxtrNrD&3;AQY|9NR8>&2}v>0ggQWj0Etj)^uR4d?0r%M2E?Kh;cWraq{oH= zadfGHlJ^J+7T_NeXj;U4$M06REVW`$R_N3`ljvO8LMs1Uy7LbKHXn`YVa*!h$un!j zGhwZ%0c;0Q3jP4LwE|3ZF3~T7)$$&P2?P|mM}%y@X@7hZI$Znerleo#SuZ(DUyOFY zkG!`^D&7E0;DYkiz1rG{_K3|y!#ym11+n#rh+X+F-qwlj$f*T|z(X5lQGjGfBsC`B z2Rw%QKYE*!&OFp%{y|aVl}c05=LO-bg%x^@fe_`2Q*`KiMSdIIcW<>Rqwzr030L&! zJ_CubNYK1FlX_{AwG9w_XaKA%93=omqKF9!hRt9C4EK{_cGcZgn%Fyw$xD~O&3YG) zDqnrxR^Mkd^E@x*oouesAQ`~++k%R}dio1TSOC$PpOiJoli3FF5yTdegn5Iooy!o0 zfCN{c8KP>DNQf$g28a*A3eUo^4M6KiU6X4Y zvx`juAdy4lX1*WIwnWUT(AQnpX%JBAlxk{dGFET^Or#Ur8@a*K`&LqQ{b^{f8iCIT zSa!TMUg9>-dzE0Nx>=qrSBXYTibN=YfZ%%sS7Iy5=gWpJ#pVl1=)OYY>nLM(ObeeK z?MQrX7uiLaX;CLl>8tEYQtIR&Bz)+VdF7*paLZOM5MX|a<8cbej9r&cHN~f0*H@*^ zwJq9AVSs|+(O{qt28d(Gd1yGW*5(+^MwE7*Qd*iVKZ2Rmc8JFl^JkrX!HpUx;86BVd; zr%ZRJ*%^Q0S}tO6*{@J!nodq)9`PMx`%0NR_@i)|+>4`zfn~`msUqX#9zO0|L zCDQ_l%#dh^R!gV9+u4mp>-%;BxKJVVy&u#4?4v54p@_(>L@JBDiogBGp>`DtfUQLs zMyLIKZ^z?bU}O zuQM{>#^onTgD?VIb#XFBHf(UI<}m$>5Y_=OrPCw|ioEA`MTFhX3ggbq8_wXq{X`G+ z{6P%qfCCZiBf(>n8~~<0634d_vw$L*0f`tJIOMnN=xP1TKlmA+(RDL=9b2&d$*>dD z;5W28#4%IIOGa2IV88|ddJtF5dc%R{FGN9ZUlv_$pSb|YQ#I$d_06D%(vG5fM@Eb( zl9&6Q*i>ifZv2C;&lnGd7hMpI==qv(`@UoFjEjnLO6?mAp~`RF0tys=i2=dJz}RO%>PAGo_=!KWWrEvIlcYyj+=-0b zda6cZoJEpQCyf7;HFeBfj4|aY_a3{2S^AVI-%50+BY<4y1XFlcF{I@@JI;&S3#&*L zIK_!O#gH!gRMdW)Qs9_MjR@Sr2_85P1Rxx;EO`E%`v1)DXE^`BeQvbAS*zyNJ7WQr z!jkEPv4UNr)jV`pKf%CBbA3Qs|qbDDDw!yv5Mzt4l671yYd+6eM(E6Mi- zkrmNHwPE+gPck4XMvu8=I zkDg<91ymv{yBofMEyO4tkjZ0yPi;6??aY?&G9}qz;T$5R@NKQYvzWp>J;`P;ipTZK z<>OAG?H0m*>$~k~Vj$398T;};@9U)a_k{gT4@opA9n2xlXG;9X*CB5h7>(~~S=Z?M z>3thav-?p_8Bm2~wS{9t9cYz|rHc#z@dRK>TnI3_aTw6Z89-$_VSbqhE0n$`cR+_u z%!Ed`eU0zgPD5W$T&svQ2Qi5C(L-u0IV9xy;C!qZ~?Cx?Vf4j9`4473JNtx0yeprp$la zu>;CNv2Fwb0|nl7`cYGr(m9=pei|?|YKZ85l2!8KjFOq>t60Q@pY+$q?$=j#su55R zAG~LARm4$H*%Z>##Ml8u^cKRFdTOhIpR_gZD-~K}1L^@0we%~RY$=|+AU$G(9tudt zi@ewcIQ*9hqvCcEM4(MRF=0k7ry!^4bXp0!-J<`L-ZHY^Ww9b==kmDGlJ7a3*cXa~ z-QSmaoNhOlNd1QiyXIJ_;;~NMcM&y_@vhadOrz4`d=h>W+sm{}>(*NsyS={Lch;o1 z{x!l9+?vj$MpGCJYn$uio9?H1InkDu)%bBFN_Hb+V`2OgG64rg#_t2_7`LnhMU`NQ z)$WdGv&W022fT7v0HC*?7wW(iDZ(xqfz6iRJ=gM$-`ft}h+Whb5D%C64u1oztlBq(^Ts!U~HM9GOTMLE)ySv%1WT^U(pp$Pi-=cEm9f ztBSnO_*{|1pf`o1$CxU~l0q`rpebAbltSgb_CN zzuMyxmCNaR{p`SvWnmlI5I92wy&zjo!T2^=60;$EMsi1T9)v&ngkuo_7L>H2Cu5)2 z_}S}3an*NQ;+mKEHE%RjR>*OjH&!vaXvnXb1RCIkg5cn$)nYG)Rwi8TcQ^+lh6~mB z+vqw3KSl8n64_&Uo`_r-5!_dcQr4UGzM)b)nWKLPS9`aNEa0MlITH-1!{7%;@HICx z9vdh&Gx{*uy%io{M6H&H2JrNeNOVR0=OWf#21f824S(0T$5z*yZ|JDl+GWCaG=E&^ zZ;ujEvF4j0Z7crkZ9yolI_7(MX4Gnm5-h-35j8T(ZBjOxQE{*|hJn+dD6(7z7Fl}k z&)H;)vpN?z1B`w=Q);?7O2@?^0jq@*Vc53&pTFWs7zR#v5|Luhzg-bXo6c268~jY# zy)@c(MZo0RGTNtv<^84Gcl(@8LN{bnm$CWL2D$=^G}*sd3EP%6u3{0onU#Ow{I@Lk zz}C3}`U(iv=l|5$jj`=Rmoz8R;PEeVyOc=bi)nzwFVQu59Dd2r-KexIg${K7kTrUq z6cAAPR1QH$CM{n+d zbTSRd5-+PK#SVri(jA%E>(Acrocu`6lBxG(0p9HFnHv2hP=<8EZG)C2JHtWh=`SHY z(T=+lR1NE#hf;b98h{B3Y|C-MBr;4SmU;rN&jkiuQG}wuoQG1?E*ph*%;6)OD{&ru zEzVtlBYN!C@8VM|7Wjr{l z@bf`uF5Snb?DbHy`YY%m2AQ##!-8xbKtdCBY$;`PX7Xzl>Hf^wFv5(U0=eLQz$7Pf4hM`rKaHn$l}?LF-Vy=?kIB#=vtewtSO*fhqD4v!*GQ~qif3fM!AeCl zyab4)0DPaDC4z11CDs>HT8jVD(aQs87C|-WK&Ny>o2br#+p8II?3W-W$xmIGXJnu+ zD&?08Y4lL1ArZacd|;`Hd~KjI{dtzh-c+5|v!?7=8w@i3AKcHa zNY!Xka#ay?yh14k#vA~^0?&DwIgC`j;<9MD%al@H^b>yxeGauK8b?d?5lK+Hy%=2a zFmm~w-w70g7SNx5*fyGyy;a}>L@5vhK0EZ2X16MOjpJu@_A1H!YBO(=G%J2a2+utc`1|y zvpHhIADmODSKxU-BV-2+PBQ~@vR~>PJ<}e1qiole-yQRXo~jrdgK_?*Ib1eGc!0&? zzVP}@nJv*5F!}J7DyK&k$t{Zt4k`ksBn91wS8yVV`zKO`!FQ@iHnfr?Ct5?+cB(2e z^e!__w3gNOR33aJl?N7OxX8j$&=^{+_$S(^%;%-4eE62`CllZcSOMJ&Z`ez24%^EN zW*+_viC-j(9Jw{|)ZWmRe&K>cQ@OUUoL0(9`(AKo?rnQm zc1MOUirL$G*3OPw$7rjPvQMhK$8K(WBEoMo$b+!IGwCN@S5o@^2e8lA-A1(TZ^mWl3&YVJ0 zyh8$k$UTzty#h?aftB9WStD?-WV84?mZ`GXoJl~{*=vT~y-zL~O=1)3^60{cl=>QE z7ZEqFht%n|h6`!dgtEmi1}Uk4*wQ}~i7e?&ScD4Omnp=H1Y)u+3x8|j+<=EGzEWH$ z;QZ23v((Zn6VAtX%*nL?;0LTt($|B>6;}iaB1TxLZAs&EH%7c{n*MwNH9ge8dB$8=wvQxk@=uEFgvRgL!Ca`TkHE~W| zkK!4&R>j!fXns69RVOu1`6$Fp6=}dQG#>_dDPI_XqtzZ(Ck(?pWW*Ev-Ub?%Hy{Bd zPw+`jT%!T_? z$}+_aK+OxN!|B=1-?}N4E^SpVI3H3Qn?{AL6Q&4JkPcD8w1IF%Orp>rbm=G<5WKHg zgwcWq;qbx0blV%eRTYsm!D`QoCO|%$o2*%zbc%7Xez*6yJ{@#BDKuB`XK~!}6!#+0 zk#0$K#T8TcU7qd%IiQH(&1W!v9tJ1<6exMJCT5a=8WX>0a)hf|aUX-39?t%VlcGzg zQMB{r%Z!M_IE54Ql?nt@JN{fYcVc{sBjGS`U4@fh1^e@+unQU91DZri^+GQ=aN1GT zg2HSbY8IGpjz+TKk?|(^X)cMOW`h*lLZ_`&`Eq>?^S;PE#w)qGY2c=C@TL`!NlBGTn%~oJF#kXo<)_OQi+oiAc&#_fHMzIF^(jO z01${65aSIsCR;0vK@BNGfDS+^%U&uU%Af-T4-{pXI}~fkE36%CkCa`HbbOp+#}BE! zu+XS8L|ao;PHh$8MV*%GiStQz8Br(HB3_e!O(*Q=G zLP(f2fif*8rU<$M7&0jvg7F#cnd-BmZHi-KHMZZ-3fCZK%?J2m?Axa;B;&o}L-rx( zr^P^)2Cur$8a>;k(=^4lFDa^M{Epom#t8k#4%8}Y4YF+IcimK`mPpt*4vJ1Ds@1|JUsvFf#PcutAQjM^1OTenskmpe-oEJlhFQQcAD;iQK;H$j^02Nz7 zTRTdR6nn^wMiG*GcLBE*J@Esl_u27@D<>j~J$yq2D7ab3jahL|2%z`0Ve@>!e-`y& zPsf8XFYHquziq1}msymGJDW1ag+@k#XZJp**2I|#=XuQ=Pc?!}jL%f!rYfEkQ>9Ye zIq$jRE9`ltPSnyd?!{8?zn#5L$tp;0P%A@b-oV@&YpNNWi;maA{?$uFo#^oz$g3!m zm`uG_DLnUVhN8D51aZ?xHLH1`V|#&dqQL2P2f7}(!nMU}CW>;8%JPuUEmHV3+!Qa> zRQjWM>SxY^o^tOtv!6`h8V{TOH4X#f&7DLjo}?u>WzfOX_C3VT+1}zz(odxTuG8Yy z(l^tr&vv|=?>T;{LiiKIQBUP*W?47(HKngbrIlw`+*8Mcg(Jx*jFExeYu?#yiu?XQ z99lIxZ>wJ`hZgUElF!tu)*N(>mLMk8PCM$xL}XK|>b}o3skbWpOTJHw30GPHxtHpk z!W>euu)S&iUn}wsbG(4WRf|j?;%;J!`I!BAQmyURj|)4;XDNU-$EqE35db3ODez>FD|fZi33(94dA*-qD?gU6pS~w0x=n73 z8D`}1#V5DsEB=o1EBwBA=e52)ElN0=#3Ir&VFIqHdYfcft(`k2qpvF4Ib2{iA zI*aQuFNTyb*g6?((ueB>gM->)dK)N2icYzUR8|BR41{n_eiZe!eJbhlkHT!%YgU`e z9M`?T+q<|)ZDE)M)4uJRW=P0a^Hu>W&M9!x$Ip{a(oX?orOjMSCsB3c&0@==tPqPKS;pe_arPB!F#Pd{llJ9g&YNYUU@Ac?JM%D zlhVIYZ2|Xv1RQ;ti-w0oT0}%puPZQSauY zCitnPyoY6q4o*;U5F!}ggY!K^?XE{rTgBps#z!KKZ~Os<{Ws%`JxU6lq#~hVTxe=< zA&M$U*+*qb12Hb^P+hnvXX!18F(w+@wtK|X$5-H8mR=23F{|kA48NTGq<8#qotSrG zs$Xx2yl>5nuawqMS)wkpY7TyoD`CeIF;}uz_&Z{4^N0dT5?Z(pnUeVToI6#gUhUOa z`aEz03K5G8&z( z{Ov`i=*d4}ot;x7FI;xXuppjaKZV0B5n(<@22~aNYCs6lw$Izku<}pcM*V%&?SW#C z%0%$~h!@{o-ro73`V}p3!qVYOiR2@3eFAiM{zvKo%6Z1#xE!ay;x@7DI0k~fua(Hh z6Xsgg8X+wf=TLjeujjXa7Q!)y?^@W)+n9$?H4p2mxSRe&6&UoI47y1Bjs8`Ynp>MUPb0} zz;VH(%}O0&*LN>C$|_O6cW{4)X70*IV5sRsE4~kwHC$``39R>i058r9eU6mrc8sxp zuE{fy(r{bnzWM7POj-q^V=fhN{k;ESu(ab^qWTR)B!oIGG&%P^xwKzJI?8bfrfa_e z!>4S8rL-2}L`pyJEDR-7nOrms&&ms|k?w3#S78rOmSLOrsdokO8+NAx0{nRs-622R{U;ot4yQ*d65j(jpN^el294DK&ry@<1{L}I zyh9Cn6o_>T->tle1gSNc;C_M1W>lMq)S_b;_sg%;O+V_j1*&j{E==Ll3h3kZ&Y0=S zbI5YfaJ|W|*%b0-E}AjVkdyRaMS*l>`P5f40#PfhDTKVqzKBzV^Kb`KZ*s>GCkGO| zJNfh>qAIK)0oMU@P6hCMT#%MY$JhikDnE4u;cj6lPVBEpJijDWi2E|2P7isWnfCrj zI!WN~W4rb+Cnm`pOb$8O&no_Q_)%VELdhj1Kgwv6b#2qXsGNZjKt1^nO`#(N*%6A` z>HAsq#r|KW>)5e>aoW0p=o}5`XEXeW6nygTGh(Kw9y}U zvN1~Mao*>TMqp6L)c}l!T^@gYTYBntEK@GO{JTG?Ck|1?*p=I$ym$KkwLGyv+~C@h zvU~RMtX`4lnMv&HLIK;w^?0nJit{M1|1e>7X#&l}bKoN;ow*`3h|Z^M7|?E}3p_|Y zbJV7U|Mps60BChKOMzZtG)^S#2fR@FsJFnUN+AM2mjNu3qChh=7{Q;Lqm4XLU$o~b zLS~qt1f+6xjb4*uEpfC+vd{~X8AOeg^-poG2A@E=Q3Ay$d4(I)gg?<}!>6-8!?vo` zU`HOL(YNMf+>GWjc+LPSld5iUF9|SSmQBpd?&VyL=~!6B?oCHitU6QAZa@c463Gw& zL=1jBV<+xJVe95D*FWyA8JAOoj+>pxAr#1sU+br>k~xMrfcJUpLK zZwTmoNks9i)bzbYN9&Vbz~QpaX`UZSR^H-91LoEovZ~wm?$S-$UU0xN*m6W0sbPw1 z26jFDsaEA%{2sd{+Wsg!%C%F~S57s9elv)d)6{y3!lS{tAhd93I4^It*4a}PI@qDr zsAu|DCIujto&YM?`ct(B*@lT6Ypz1@8Sh8I7tYXTY$L^EnjICt?Jwm@L>CT((r#_G zJ>+K`B^@PrRcYV2=PulOlH^)EUV3kwIY&Fk(e$Ic4Qds3fg-V;8oIEHH9oo(h&j z8GnvmR(kqq3?!uRVACCKPfy8QH_FZ4-EPd%q7=yfe2`50pb7AB(Ei+na~1K*iOS^O zpzz96&h~oGF@3We+R+i$Y~5}&i`DaBnnbJudOrU5FPe{i>jf9q$UbhC zVD729Fl|7M-QPEEAA_mT_6p?sDZX3%J7O|6Qh3qw8C~9O8$x=&lJ2g99&a|VkGtor z*a^szp^re~J5nptEM+B$^&Aj7&q1FLfDp1b2gLS8m|iz9V&WBMV*kbj*{Za#li))# zTQ-60CQzcHCYre4XS5zsKzy>~I`bm z7-!03q?+_)_KVmlB}(zbRPjT@7a@-c8mQA1$g}sn8N1%Ktjhy((BkZLKqEXBouudw zvy%LqQxH)GmVXO5kzSpLKNm!+xa~QS&G>=&qYl0Ns-eeP2=2+Pb(HD=sqRcOYci3o-kLz-cK`4 zBhY43v>m->Y_nztsU*_A2mMffN2dr2B@28hh3+?c37}esgS!%Qz~er>`E#6dvzO2` zIo6kS>ldEuIos%$5`r)rpH z;14VgvUH8j3-D-EfApv-U?qJtm z6O6BYqa?L0y#XKkH7b+n7RDfjcKq*%?EQOP;Lw2XW0w!Ik?)6LUuh|(gk&8-eV0@n zV9dDFxXY~IfzIv`^K^M$k~C^{JZ_W+)h-4A-@knA_fD++10BQ7w82sx24 zAx+=MFTt^NZs;x6OtrL?aG#kz!#c#TlF_UuR1y_x2HeMrmv|2U= z%gy#5J*L%4iIqj+(uP)!(l(NtxnpJ7+1P&F^uD_qOCk0J?o^aWboyIC1eZn?nJ57U z<9A?E@XiW;=z=mGd`lBN=1A;^tma&(psGMIrxQQU;?4c*ewFX_qq??4Y$a2?O(1S5 zqvx>v-wpS)8{gS}9Nkz!^F;?AEGf`ul3#fxkv?qyX)?*e!4!bQ7YByhG{T-dXE<#b zBqer^nZs*E{aL~f+!z8VC#gRrLGoYXSP;EJ4Wn2Z^C!awoW#SHu80{&DPObAJA8&p zWpdiL$6@CspGQ#@*7G>!E)y|edVkI&+X&L+=)7|RBen_o2tc0w0t?5$k3_w8lC=8D zlBn3%Z&W-*UAeCvap~rwrfA|N-Cv)4b$HR%Lfi&-zJXOTpfLPdN5lNpSH7i54+bvB zQd;Ms1Hy5%*tW9CKs_(XNCqHWBZk}+)G+erLO9Pt4pV#quIMZQa(3w%N)9&DjBWs< zNs>V8xAt*O*1vX->sBK>IjqJJ*=lg<%SNfjU*$gTvSpDUA6zWmK)YF4-@+#nf*?v9 z%Ai@fy8}9MI0xndBOJ`}V|*`Yf^-9oQ|drN*gt?2OnEU$2>-6Gg9KtC{%pMYBZK`| zq5LSE`G^{6!7Vs&JjWfq01%wd|4ll1pL%gCv*56Sh8u*AN#zT+CxJYyKlw+kLb6>N7u|lrGch52iasCQ<-E0Z9vo)&Kyc8`Urt2gWQ`jx7bo z8y${Jf!_uGoIM7*EDlpr<9J=2q=82y!3p^KllU(Q3GB5i-(XkB`4Los3C+J_9T8(Y zgYI}SFq8Hv5CA$q=$Q(VHdQe#VLBS)t|N6S z9>5C?Jx!4V9gY67ny!(Eh9oC|AHvY?ME~z6b2ceU9Z9spk0$Q-EY^hdbm?_D2VEaL z`=3X$ljRE_Lg`#_)%H;{ zAyL(CuFq+vq}R`}0b~~#)Q?$W#kssTxk|umUQXi$UXf&_2nM-vVkGQn($*KD@S z^e4ny7VdQI35_Kpva)!>s1q@39&y*}g?rLI$~LCKzGr14Pxn{O zj1!^sI+wr;2k{fKN%0%K-aPgAo7Myq7n!P%e^C14Sp&^b%g2yJQqy(HeBH{M3Xe6p zO|B}*T%)#|MX4Ub$sA*va~*lC=N;&{+F};O`Kr}qPbEyIjy4v}4xbeaj&v;s^X>HVx!FVnOY&y&C@NZ!Qa(3jWxW+c##WPL+6|`W^Q(4F z`(pnb4~E3-yVA^8S#16|+0eDx?4{I!Z_6@~6Wl#oFK@M)C?x3D1QyzizqyiWK!LZn zPH9KhtY?ms=nfP*4m(YF;#d6dJnI!MS$M?eF379**OfCUoCuAbgu>iZ^DLfI^2&&h zC=`@825kfdOMh>&r3n*_?{>w?)0eH2^bGT4%C#5ku+Yb~JPLN-;Wg|zFN@pYHtaJC z=aZDk_c+mUD-QFSH*$9T?$*TOKAPsWs!3N0@Lm=q=n31`*uXP6c|uf z6X5tYAOq}PHNFrOOhErDaOb-b`!ByEim+uvACdmBHjV(aDzc$!rWZz>k79f(zj}$n zarFXb2lfd}`)6ECT)FzKGBzUl!tH#+qvBnHdle;(dk<^P#EE~6*X}#enb*NL{6;DL zE5r3Y3!~P<<;24o-#gO#IqHPh{4RUp;sJT)!V*uCfO%X+P_!S9CJA}UPvZ_i2=5^n z)Og1LJkS6XC*sBkji7*&fO-pxYXRkL=y;#rP=nM0Gu|a~oSI`^NF?f0 zv)^yV^WA6u+=2>8z91P;ws2J8EP8dSSgdPfna43TnxX`}Oxu1$V z{0=|ql*pp9u<%#EO~2snTG4d~c3pV!`k+7!F4g-3#uYTGu>IiB-xiB0hR&j{-!<{Y z(P;zt@+N6sEksr!`to0FbE8pmFcsX2IHMnR5$Fl&E4YEW0jMPc=%OL!H{zN=auEV}J`DIZl|%u+jlRxPV<$$n2Ho>RkPRf#oJ zWf}R>nJU^cLjR$lzHp;n6|Z4dplaI_mwuXvRMFkeD}*nqETz5z3)X@^+45S-O~AZq z{(}w)g_nO+t>%!SE;k;nGx3N6s}^w!3i?pfKUB?y(RxkW@k>f2T#2lcnQ;qB6<4KS zI@s!7(nPY*qz-Cc^~6_EA|617-B(`_NVJ$!zI3#DiTKcnK&Pfx1kUYKy+O0LzV9U2 zc}X$+miiAq!wxVHK(JKTpAO!T^z#)et$Mx_!y!?h@x;50m)!Ri82?E$|Fdm1OvWIM zS1(1dbz$R3(f`$|MN#yn`C#|t24}=RQ<2|*;qbub?}6t6gB>Kzy$(+Mv~vWUGzPzi zgRC20Qw|^PAQOb(XatW-ssWHkuSn!&VLB59rVchnb;1T_oDmL zqQ=-|E;DP%;4GAL2aVfQ$iKs3sA=g(;D~VHW}CVTLC}q0&GOJ;Zq%mvVWucr{h)r|?Za^v#RSTR%*{*sgnL&I$g(M9=IQ8nZOpx3qV?L?hNe6eE3XQr--(MeQzx z4o{cvPRmBO(lB%}d{kvFH+{E&zXWPGeJI-)9!0ZST_0I>v{{KQOy}`jy-KIA~TWQpXK`PLQL(0C@xBVvNH*a^c%U5SVu1=0_J8tj3mHJ?s z|B>$siAJ;V@eFV7xbLFeJHKp2f?;pAd+#s9hj+31vNYTggUx;5t)C8C2PqEF$4_(> z8w_S0e?C~fjXflz-S0Ku7tq76mm+?wBLC@$i#+k78uMe0Tlpos_ndak)UMhx4ryDl zUW3G6awRVN(`#rm9n2Wi^oOu8_9U`mmtF4EbolVK{zt0e)7QLxsuMyn-u%)o?UiGp z%OgV)rRVmv#jDM4x+-Q-y>|Wr|G0!1E5+kfuAZ_r1ayOgOmmMHALrZGb zle?ygyOw=@efx3VRqDnu;-;nR##9S86MQj?JPIdk%m8cG95gHcyB(Lk+xc`5YyH!g zDI>6wW%OTf-~NZ|eW1-pva`_?=4R*L;4imd@1&8>5(pC>1B>=G?uT-;D4F0*Xg@mrw4Decl2nc-!e*v zj;Nre4<9ziwYBdM*&F^k+%Md=4ntKutQ;=4sCE38341KuQ(XF(`^JbsU=%ZwoqM-E}J;6Yo3wb_I9q@pap}noK&qU zbu+XJ9!aS7Sxdgb2Y0iGv`L~CGD9;+Sr*7WXq;?9T=$_QvC}JWdVj4jdNJ& zRu>|itodw(>hF(htP=U=spD+FXOW)nK_$ISeO%BgHD}%d z&P=lM_b+&I^t_l6#X)_Z7NZYZ4Z0PdJh_`@7}I#;r^6DP-J46qUwYY~Zm4;(Ncj$Q zP@_tY%zuR$Guizx^a_wc_)r5B7G-a?@pxI53TZh)RYmYkh-p4l{Jbzn-1;=02 zbJW(o6&s;g5Rxx5m@;yU30#u;KH_AV>#IXs9ne*>Pc0tQQctmZGpYWDi{fHs+-bgy zV%@?rR&3E-=!|1YCZ14y+0GiP$Bn_fN7XCrb0B6fTZc}Lrk*_EFBKyUo_2pL?*WOu z$cDF}mCgv=h=XrLM5f!t<$Q+Zjy??nuk~6Yb?k#*VD^%P!xDQ<%TeaH&rf4v)Dca* zw3$)o_N@Q%4vU2RNYrQpLk5+dXVexcdU4EtmGB|{T%Gdcpd@s~)#r!K-w1R#T}=s5 zJQ#Pr&9AZ@-mwek{%osncwAa(9TPo)q5pWT8yYKhecmC^e66J@KW3T!@~&>DP+|)c zjtG#?{`H!be(WAIK=@s>R)bbQ$FDAbD1m4udg9^G+mMC8owKF6`^_rl8w^_XBPQ)A zs_gHPbr5xCW}`zKg=-2mGL#?|;Qs}@6#ggR!ScFcHL7@YY5x#1BT*gT#VNyRCI`xtAfHUc!kv;O2S7vuGJvS3vrX=UOdybr zd=CWVj}gl9o|?!$%dHiuw5)UES4+)h290gZlo*vbrRQII#e3o>>~5%3!dEItNPtnsEe1Vc-6=!tRe3%CpM}Il*`f9&m()zYhZQ za^i4e3u6XeI5X`PK^5R#I#A#NlOg~h2NVKnw@!k~?-9o3=PSutq0O_!ji$VcMA0^^ zgrF9Wg2okY=@IVQ{_OSFwakfGnI`5hj^TGU!Ce=iu%wb8T*Z+lM4H3c>>%L)glg%4D@*)e1>iKpQ3XWg>CI%Kij zOx5~QwaUSTRf#u#g@`|O?n7-MsLB z6L$QMr&lg1s7*+s0$vu8Zh$yn+ZQdI5f>a;h-XhN7U`wNZ{0Pb~;7D*m8pC5BHM_KJU`L zwf8;4kxXE`48W1{P{d>7?@G~6KO}F7nC9gdqCi(nBz@5!(|~o*|8MrqU4coy)TclL znaQF1GrUX+rPf>hdMnJo zom&jkZnW2rOT9*47MHng5(UlCrK1st6Tn)~e^<+{2u(pT(dmDks*#S%9DAq_JWcDb zOK{(>*(y5`{r^nZu{iiD3&%q+>WK*pAI>(sjCdRU>88DZ^n1qln6J@$kC*+gQG@{+ zyH-vw^83bFr4I1yB_}aGTT2ggye+kNmszu*1nA5d|;qv-B(d^7FmH<><@na*V%geVN|qDEzn|wbHpm z8(0cxE7c#{0{ds5$9ad(MuxT;Gx+<4e*KgFkE@m^_CmL|RhFIvZsB1zX}S3(De@|; zbjtS9x5MgVcVB3GysQcFv*EoxELH8iBS!0Q=WE05O~dxCm+6KhC-eeCBQ4}(_0gAm z0 z$CU0edi}5uYrFM9JyOfcN4=-B|2n@(w+`Kv*~gE6c+NVu7Hki?aF74RVIy~K`u1;7 zlKtZ{)BR$t{@z=~(fr*BkiN+d?tB1m<;7ihG`@xdL$!~lT#X#)8>*hPLp2%Q?jX3 zR0m)lb37p)(M8G8B?BozTd~3#3ZqoqSRf2G!6d_E%7#W%s&!Fn%W10lR%!=lT4OT2 z+apbnI;~$Lkqv|~9-4&UfKyAtzf+_ao~Bf4z_LRUlDpCuJYav`rF)ZPERDl1#nLAt zGCYB)-__yEq8UyOFd>F`(Ey}pq%Fvd`{2iESZ}=it^u>MP zi;C<_uC>gKfy|lv7l1*wya5HW6Ru+C>wH)XS>NL9LkC`DA7Nbf=rq(gSD=bq+TVzjQ-^bR$hdIx)!f{&bp4VVcEIdTJ5if(AWiAXC)LU=_%C7?a@~lc89d z;Ra3f*vycIW_p{aKGDpSbj=i!2DxChtu`}*1rlYVna(wwPF)fspJ#|)IvbCMjuE2p9|+afuqd^4wdD5w7P z78DO%Hb5+OK>;uzY5?2BAiBmtAR5?`0b*wihA}`2WB&uwfyTizUWlayNTy3-parXX!4D{sJSMD}Z%Y*zk9tfE^?Xy#(UGlSeQxHkqwbWSpf#E&iY02Zu( zgstL9h(UpF7?9HfYz=Dx>V|#n$|Fq%9bhOGZJ}p)_e8tmJ5|MZw~8@>B`S|fG^$E; z1d&-dcz8WX14Ti)uO1?)VJ5|7ky9)?Q>?&TqWqu)@FG?-N?QEXpTAXq8J>gX(Fk{B z@|`JtMp+i1h0FpS^X}S>jN4FDuTTyZt-}8l9$yEs$BjMAxn&>G@t^$=K(0nUua|tK$Q_v z-8NkPfwD%AuLc}K)=votU=WXOkzG7G07fTMyq2_~y7R2MTc)Oeptj9dzGFpuNk#{< z#<)%iY(A>pks&@)xR_U!S3M&4pY}dV=gV2mxD3-tRo!-MtG}q!NT>q?3|Ellp zP-&^b=O%gWcchCX^JogdtE!-o8k7to*n$CrCXjcNG)tr5Y?BcTz`y|K+~)EJ$oB^7 zK5k8SW*eg7S_TY(qI$$>J;Lx4u!@5TAW5?Eh;E$mUp(TsS0imbb;LrUAtkVg^aB72 z0@^IGp(WwGg_Nc>)uJ^sw>3AgF$atI4N$nEsD7h#B5oL~JY=fgZovt)rn$9d2_Z8I zTl3fvbm3vl+N5&z;15`8aaGC|)a%#U zA4m;9CKi3X*!~Czcb#Fn!0}y_tVX$b#NS!cbDYY!Y-g%r_vQIVQkpK1B~d@?f_8KP zUH5~?%|cbpsGs)4CHGt(>0#>V22d1>_2uPfouEaMCE1Uwac%q^9|hyPMOkZ=E&FJN zkjh=~Tr`r#y-hd%qYc%7tv9?*5SeRRckc%g1-1f&Eola=>}+(<93Q5X~U*pL$I!BjX4Cbq0X?Pw1Ub zKORzg)ga!PPyt=do-o3DKVhVwEK_XFQ2g8wfFEk2A3jG9E4_nf3nHK74nGqXltjaR zY(kf-n9NE|`UaSCu+;lq@D4m^q+3biI}_RqwrhZx^8ycyzuL)Wg66@ovOqy0{2z)6 z@5(gyqKXPdIfq7U+QJNZHFpi5pdu(SK}@cm_yoNU(fP6%n|H;|uLwTU+N2MluoPf#oRjiy74)n>GPkGTw1gZ(9)C=yi`VGNJ;F zCq2AHM(~14+qQw+O7;tJB>4?IR%1-mZ-jJhM5(_`w8M)HkW%@!%tC@*7}(=NkWW3l zq@F3=k6@myTAxcom53s9#KTG+vARvF4g5D^*Q+s~r0Q-ClNUgV1zNHJ#1kx8CmP;) zi|NsqA7Cxg9u!0Y2mXnr{%Q={z!qb>;KYh`$QW1#O|eo4BP{~uc!4Df!5=pR@0>2uwR8>!$6J+dGZCpeHymp{kM>vxfr%Ip{H2>1 zGRssh18m{kd2A8==}dcp%4!0dC|jbdmRpE^lj#LNF@V29zd_?++gQZ97wn5AQi2$i ztob@)aRDg`zb1;L^IT*UMKXU~WQQ+RNW=CP;O%4g1|r?Fyq9R?7wLl*nLaGCT`hw4 z-MXdR<;hfJJ(m!>%R=xKQTBP-xI#)TN@|(cG%`$b1xpI^OFcTs@*EF+RX8`iXpfXK zIG>45s)4bL^)4Qf;K=%i$7o=Yx)cZ7DWv{f%fu1*{w~V`xQcjKcvTV4M7isBj>@qc z*{~V{?RTxm**UrJA|GY2k}tq6Jy^x)jh=mH`rjeO1jK`{Oq<(G8LSN$I9Pzq_u>7sTBZ|QYLFe}mt7{gj-C)t zjT(7m-5Vy#ufT^w>bRio--*vf0J3Gh-Q|MCMO)a1mNiN~q~|VEy%${J4^zX9&+q&! z@(tl1t)ZK?tTi1&x!zS_)*EdvHcUr=_IhezU>C-bjYh&-#!B{n`Reoi&K3viaqyKL zroXB-M>p20IuWF5o_5AlB{!T%(> zfKD&Cqrtqb^?{pMNMd1B9;bh}^9b-Ns?3vBZIsCeRWOg-yt}(%^@gdf*-h~L%a$#o z2icg(d7^IuYtD%B=sHRkJ5AL;O@DlvnRJ?6cbYqTn!k7Y3UO8>c2=x^R{Hp?Jn5{m z?yP$Btak6L4sqTfcHX3a{!Z*gwC8zi-FfqGsD~_4tm}2V*hMeltW*EuQ_@9>4Ul7- zJBx&X#QTmgRGuGeLKdixG4LTZq$k1nTV+u*FJ!;~F||NEr&0d}s3bU`^R|fJxS=5g zVSh9|cY)fg5R_<3K)4rHo}eie(2&niBrynJ`qNMpcR(T_Z0R3j{QkO_C~$I20VD*^ zFOW4vCS);7EZU3kq`?i~m|eP?j?)vX+F9Zczm}MPThq;x_S;>V{0!}@(KQi zOJzo_YP<_W+v!jHMeb*S{6(?)^nBZ=R=>TqU$e)L7rG-5eAXAvIl=D!!s|4krnQJX z@*uce+u?)LNDuK8^QkfkKphXXoTx`jC$SEEuXFxAe;IhPzdBmJcP+eANwo9k#bkEP zw5R3FO7)Jxd6X>BK}#%N02&l;&$!aOlqiMX;+3c*=BU%2vQBr$Yts#ra2UQouH*%4 z0A2B+aIL``N-LaU5m5e{NJaANl#h!vHd^~AxY)Z@l)2(0|7!508v6|W26wHnyqF?! zO4#UWh|1EsYOpQBbaa>J=~(BWGM`-;YP5se&pp*s-nM>Xa{%mo^klZ*9_ZaYn0!*C z`*r$29|NNIHBf@(k6x4X| zh%r+DAp8W-BWidDBvAz7=jw`Zb$LbnzPz}+yd+$l63!1VE-uc`&k1M8XJ==ZCnu+; zrza;TS4T&eM@NK{o#W%A+)w)WG;rt_h!^X{0dA=j&J zlZ!Tw%Xb=t=9^ayV&6tbzkK;J`{~pFt%KLm(b3x4`u_dfs)Y1EI9?I(ucG3#^g(Y`7!ky)t*x!9s`@X8S6p0NSXlU9`z|LZ=Qtzd zUlNY!<6T5X65^!)gh%9LWTdC3r=+ALCMHHlM@RnuA$W%Yf#*++&OAH_&H{g&T_TAh z-isH3fq_@|)vt8qwjNk)=^I`tOKd2s5@ZC|Wn}&R{fSndudlDSxA*^8c^>ZWuCA_5 zPEP*?@vN+@h#;PsnVG4nsgaS<|A2V9y1H6gS{fP}L=aC^RaIG8`M(;TjEv0x7gO6!HGIi6&dd!otGH$jHFJKu=FkOG|t0+O_|e8XgG= z2~opKB(8)1vxfI#f3H7O8V2UVVH#fd$1zGgnrlf`W`(mV$FjQ8kn}{+&{tUw-McZI zfp%zqA<$IzB}DS^R(ST4a{WxC-^~~MO%>xAI-|KK~EE8l2WNZIN z!}CAb`o$8igX_eCV9ne1*zN+41TH;GU-9MqM2_F_!qdE~>B>TG^F#Po|IzT`*mc|9 zZhosUsk) z+Jl?_(tp(Pjl8);9q&#U%@9VYKD_8gQjb@y$3A41q}^Wr{7V1hhs*Pm1NDcDJ$Ji* z!%#pt!udlv35KfS6NkM*E!Z>3X*UyYGn^$!DG7h-m(@ ziltcL=IF5~PC-Z^8AfMpDFhmOhXi?zF5K>!0%;{@oTBypl4Rw9zM{DJ?!glMWSxVd zRAW=u)pRr7m6CYsA{B=u;iaslOnKhQrR2$?*6f^|hUv0w5s~atJ&UhH*Qj@2+WwD* z=iqmCn>*cu&mh+;s7?tm1e@=E~Puw+@|kL#!Vl1-~5@ZI%~CR=Jj~Qd5?N zx?OOSD%vxYLT{5!6DHzx9eD+bm#W%-@8rOErrs^+>_GnsQQ*UnJ3k z)q5W8;S z(P24eK>IgiBcrPT6loIc;#gB0I4bQxPncR}OiSi~rwOc-QA3LmsqUi0^o05wCCT=> z7eZYWXy2j%di|#j&rK|z-tsqhlM~lrlCWre^-`ypvYETQ_Gr+-jlm0`=o2}f^Zn`Z zY>tG7u1CD-En!TFMVLD@3GLW7o``NE#=i>>=aS5u05|7D$gOsBVRri-GkZa0PeMHl-Z zU){yuk=scZB$U)tn5ybGHN7ECBTXTg?h#Tf)tL(47`mF#H(nTYsP%cJyJz&&KD#0;cF> z0OQ#W1Ns&@{z8iG{w;z5(PM#oclt2a4e|iWmT`ZopX(m7+FXFjaAks{{v?x^{moF6 zM-eHM;I3LayAQ^qQZnhw8mPc1e2hU}Dk<$jbG!L|tk36MvdUYXUERx}Tz96%oo+#1 zp4d{j%qhYE+yFg*iV$+=1i)CZu5TFI9me7ouR%0QYB(u)(k^P}8P3?Y7a=Xob=A{c zBj6MR+!$7(BWifprT_Btfs)YnoJh(xs(5><`-rP#aC+Wj)F7@{Wx@~&jPzU&ylcWi z?kbAWio{Jdlid=(rAhGiNXV_)`j6;%~ZP$tCNs=`q$f z#50ow?CYM-Y0I9Ne(JW~9#hCJ>TkH$+*ZtH8e%b7@Q~5A3strfx$J9e&U@0zW{+ItW88j;8$@YoEy`XpxFG!(#r-8kO1t%L?gqszu9K~qr8|?HZe)#^FK$9cE`#Zs z)6SwZjhX%KPPf|4zdrrZlmmC9A3|x|zPU(i^7HS++2rHrqzhEiquK3G2W}18q7z)G z8h&p4s84(cav$2MeH;v%TcCW_(kJr98}PSW;k_>%O18)$gB<+$%)mp{A+VZ4y`{O^ zAtJ~TL@uUxr|zbRCobEbIbP%a0BwsWHdzLshqMl=>-|m1y}LqBkRK!iQF!gRCI!xe zUY!6K`7p1r8322vUz4C8v+Ora&Pkn;zZ zTV|teKWeQ*HoV7E8Ttyr`rCC2K{EX!=?UAlU3f>7U< zG0UcNlM@*Rf z9RG2f&D2KuZ3Oq39W@gFYdxd$ow>SHmj>$U=zfY!hkVfA`E%7}Rg zqg8Q3dR6yVjxREum0@Fs9Q5}nI7yH2KC<4lcL+2A$jn z?pGpTWIPQQaf#$!hI})ibTfZyNyvO@745jNPck)zuo-(q>>{aC zL~|*7j-yE<8Dp^%k+70zlZQ^es-b*lp%@5zn+Y`yHs)D$)I&3G?kC<%e6ejVbkY0| z$`~!;vtkqP#5JeJfLdaIhFDEGhbJ?-XlgttVHEU5Q&-f-{n()GY(Y{uaodH)k~ebq zPQ_QN#mE0((_QeA0$f+j5*MWcA1V8P!+?I?N%D-qjx9YPRYLt@j3@6wmHiB^IkEQR z_Z`98HEu*HIbp?Ik}fC2o7Iz$L)WG^p1&any2V*Xl9RbZSci*}*`L#VC1HEVi-QQn z{M-iu?mJKjBpQ|Dv<7h(ugRTylW5FSNyU=^!cBD_amKsTsR85HgBMekhEgNMQ>dF0 zw+2(x79DFpC6b&*HQ%|37^C`zBA0rePVTLlI!3*ZL=58f02E2%0{m}1Oc?)ATAYTX zHG^@H2GyP6HjPqiwZ9>q_+#BevodXcJ!K4%O1w@?5}9uHT+;`jxH|@VjYSZz6Eu3k zJuu)wFDe(;_?H!#56m)uK4k-@%=@F$gj!<^rElItQ-8q&q0(97{>a@z2qzX1ib5*j z5zY(olN37onwc4zQ9s9_KxycRf3D3yjH@!2tACEva{~wla*QO~;X|&CX@M63T@o?^ z8pMpIV6F#dTJz_o^XE_V7nll`2(9@)v-6jq7i?q~ESMK;O&9D66zrT9{FQzML%uqE z{%XVZ)roWgH70zw^3^$0;XJhPk2L5-rDxEP*nnf+r|cXe-t-@94xj)GAjcTwP!}b| zzGPt$lSCB6H_HnIB4e0e=5K}N?#DJjWOIir z|7e&&hsC1O#c+=jGT&0VqGYPOh|^73Yh7SRFRGNv%GS!RXmeV704lB)GCb1a_HsWc$|oVkJmR+H2X2)IVQ ziVfR16Bx?j0vPH^XDbwvQx5~OS+=X8=d{(%)JzNYYg);g8>B4@@P7-`PG~_!7C|;A z97A;^$Rf9ia9GcN-tb$H>8E<+o!n^AEYej2m@}3rj(KI?Y~b&4_=eJy&~6fAF(I>P z{88E@t6kxt2s(a8E^pCj*F-shDu?id>BHV_Jz!#Xdnc#%vEE+aRvy% zw6`zM1zcK;L$|Tv7WG0EEhg2?|8f|KweUo@w)}mj90TM@eKk>P99(F0o)v3Ti!Kss z%MbLG(!Lep*21&d{5Zv{eC+<@zork2tvceZWOnekXk;o5-U3rC@b~PL4Jvl)__W>W zM~G|_A16uY$NC6;Fs{J0BAZF~Dc^4MX;pKzv~;fg>?{jxBX+pdPZok#0um>{rjIV zRXl$ZBHsUqr7KIdjhHa=JD1U9!Hb`&>ns;XW6@(^94JuJL(}n+cBJP$d9S!|ALSx+ zSoS4jUN=TKkAf%lGbUAz>XFckUP$goGs_Nj8j^s_IJTWO#TkYSJYq71v;hhK=LK&V z;~=#I_X3DL6qPy}`4~qiJQF5{^PJ8+VqJGI?!~*kj%Ia3^3D>nVb;<1 z%wAbdAP}aUlePByB@ck=jv}WkB|AzqZu~^gZX= zo^$)t@o^!}wO6MDLbMgYWFHlQOkS>i;I^w|nXsSr@N!6E=d}@^6jq}Du z7(2R!I;>tcaprrd?GOI!au%Q-NuOiE;t^-KX+js`%=Q|q7gev9U~D}cIsqJDAOMnb zyey$fa~xzhZrnB*Su5bHH5J7BJznQKzGn9C1uYrYs-)11U5AYoMK&Np<|aaR5K7fw zNJ6Fv-NK4MQHTftcvC;aaEfpNfW^CCR|z9#Sn8Wek7i#+&YC2QR>sYx@vl9Hb&Vb$iUco%G=NePN+N~l$;{|1+$WjrLD!uF)$aHPnB;Ym9m&GkXT!*yxcin7jXh$k%x0Bv7YX>05Yw4T0vpb0kMGQ)1H zm2N1`Po=+EkNwijkG0A-SnXw7H&kgZDA=%lQxWa4S-QKC^kz+*1l$=;Rs~`jXIbjMV;j)PvU#C|+6>bxd} z|117#|3hMx?mLw)n9ax}ooKOB#^8U!gk>Qbzz%DroOB%japL0}9h`AqwvA@)-f8*h z-&YE&A|a&4kN@R;JVJfsR1a<49s+xQ{l*-4wr9>iPv-={x=@#MeB#l)J*Mz6F)uLdRO zR}qfuk83tZ5A=gCG=h)-4GE$tC<$Oy$ud|}iljz}W;JyYH9UF|-f;f?rJm~qYj-lH zdn<$C>{riG+4okpGGLl2x!~eeot#@9^L^Py>v{#0y03Sn8GK=FJ|zK18^^t(h*e`8CtYBK}6H z!{fZ*GH?vb7FwJFmWs==o9dKZmx|1*AC)u)aoG&ynLnBMWWT+YP-9l(Qdy!M78ySU ze&u%A$f}kv^OT@5kZbX@`Ogp1x2~!_1Ted$|4^#4f?Ha`-P4EP^mBVnchML|{mV2O zY~rajcBWT(>1h7nx3?OLUtXz;F-OUZAA__z!Xs7*rk@>cQ=G@GxsLX+Ij6niw`LT`=u zlbR1xv~h&IEHE>K>fu|%LCR8>h~SAkv>6F=;bI0|l5BBbbMMwxiiK3kuD(_HE$D3^ z!s+Mxn#4F;EzZ=r)TDFCY-W*z^Q&Vy+hfylEGNZX6hm~d)0i!sn!&c&-1$|6)C1S@ z(&lN$%vvc6kN4?E4?I7TXFhn`d*l5a`M|B)RvzQ&KOpion^ADTp@+|`1B+^pXPJy^ zQ@%gA?&Fwq@9IX&Lf*y03am|{qD%7aNHh1|*$&}+Hm$Pb-fMbp(Omv3b2I4iturp; zvdv=8&SQ3*XNtWdMO38J$vU-S%#!chK6-`kb^Yz6>AdY^$Ynuy4eW)tQSpwnS_#a_ zk=f{kx6>Dp=Rjrn`g=hVf)nrD{hRIh%IXP?$H&fn*;{={g&`6@Umh>a?ywGwLW2Z& zzh&M&dt$y|sQiV27r;ajb8Zw9z2j*nxM$4I*k8;gPzIO&O`1Sc$(=e{w(pnT-S-dG z&K{sy+Y>u^68BOiT-IT(A?nV9?y^YRSovjc4$?oxUF7gOBf2ds1+DKNxMRqIB>u8o z!EZ7VOw826INZ}N%vxxUw<6@%=1)Z%*97xpyg+{!%c zJo=MU`u1H}sm4RPab#qRA=lDWW$clO_n=&9!)86)DTbUhgP$*;P!r)3`MDENh2Gi7DmyNJi0 zHv;k*Ew}6rJDz$; zy&$KuyiA#LDH{QUMU#5>$_)wuu$I9R=Y)T0pAF45zmOo)x8ejcZOnG7-m@8%?9V$c zvNTHA;dg74uwNC@Y%;1Zf{=OWw=O!fp@wlSjfGTlMKTf*d5tD~^duMoI#=%g6Ggh< zGnG=EbQy*mPorX`Ujlkhwmxm*6%~k7jkKlj@0#64iMbHhiX%VxvGE$xWRuneJxXI%ke!~cL|LzFKoZ? z)|z$1c|`NJjL)|n;ky*UJ~7IHrc4$;hT1)Jz?M5UBQMQA8j_JV++6@7Tu73_lM{6 zyCvcy50wL@2l5%>FmHUQYqQMT09}cOsW~J~pE6AfafQ8!-#mTPHX3vdpABQngubdB zYM1&KFOm{(($)6$u8LqSjr;a_5c8D&(<2Kt)iniBKn0oJAb3s@>cAoajj_izu6}mc zQ(&2~mAY*)7cpQ{Zt>H=NkeE74U&X}u?cNF6^D&!cstAdkZ8U2gi!6V62kXz<_EuG zit4o1_?i;iv4*;6VaA@lb!E>buV|}tdvd~)j^?%VJA>bA2r}yvdLC*k;cq z+BF6w=z{&=_dE-czPH1l%%?*}YB(m5WW%a&e41|l$f9x?kjz3KOg_51vO#+`2HRbK z-=eLMa2V!#pc~3=zjWs{OhoGj&{l=or01D|YlAB&(VO=55y~t68WG~UIQDc%Kr-Ckp z{O}t7BW}gFz4CO+(s##_o>nW+St?#QwDcFpP$Q$H_`w8iLx^I_e~dHZ5pgEM1-M)vd$1nxqi>w<-1BOYUwwINYjs3@Pp2)a8E2U}%8BitX-7o;Vnw8BSB zAw7Y0+e+T~u@Uu+R(ZI(^rj@G5*`f2_dU1^p+{2~Vj!H1Q7@+`ys{*KEb>5&NXaaW z{T+yR3t2ceEV!^B9LJ2@d*%1IIWMLg!$cf0B6&}2m9TB_{LI^{J1y9lVNUHm~H(h$GBWK>b`X@Y>EDN9; zFp?b#bc}_x#0L4(eCSfCi`LAh(l~kq#hg&Q92*K=pm=G3gx`s@^BM><2=~KD11{L- zC^BFy`~@Z&dJ@H5q8i@PUt!qv^lgO^*HDUN-_5rw+8rtyBPtE7pPM#FC3|?Yc(ilw z%C6j0&R76AaoU`=gI4>1BY&i=B1Fr80-*&w=O+Wa!pfzixeGOb1!V;?75*Kq56Pjf zE@04{dN^P041FH?V6zh=hQ0pF=fgWXxy?Mi zajIB-%dku73}R!%0ZZ|WF;W5pxjq%)ZxHnW*B_SEMcIKFxX@s4yt5q6vtq2dx}x-A zB!&tFamIbxxcKCIZ(uG?Aj={$C~cJe_2`SY`k|jka`2!%*~-~sJ*bEFdBEqxXeCj_ zHdn7uP-!t)|HzSr-bDu#IhOR+F}f~qXp72VBThi*@0c*@IE|G-743NLg3i`~{+P??2Q`1wvPM`=rJ0Kmp|kNu35rJIIL z5dy^#k+~=gm8&rJ_HDL;c8wPk2o-#sOGPqy@xzwMbpsU6sHAn5l>t| zH!@VK z{;4~pCmNl!QsKUXA9l*n8jbJ?QlWAdMg zZyDpqv!f!WqSL1cF{M+n{Y=U()cW;IajR2_|E3ZbnS`uvaEs*AWJS92ON8EFJ0)T5 zmWJ5Uo7$U1`$=Ya_h-B$zy7k{+->t`zEy6)zv)Ng=1*J!r-zZE3mHZI=A~8-3V&q; z=bM&l#Vy`5?^I;_ZpRi5`Hr~*;Xr@4&;RZiZu)aJMlI{Ud^A9BZ2GTCGnqPx%7YHs z+f-G{vL3>|si|&`rjSB~IiQV=Re#ji7=W!zQVL1TIzv>cEbB{TGfs@YU@g?Ldjv~n z+Y)a5>A;8+skwy+2Fy2Olh54`P1f9@AoK&-J3znH?8mC_I2^@;Lb_nC=?RkZrsT;KQ_&4y(DB`dlEz&wcY} zBi0$H(D+)=knyj2^1&bUG4vJTo`X>~5VAXSu#H=ELeZ_8A~{T@6Mv}3P3fT^gUBG; zNI6F9C6T%L&gR@gvcLt3rx5ba7qH{+V+frUx5tcyW=rLz%+s267 z8MY+aCy~#)$feL^kH>UdY;8rmjUZoN&9T-0vig-~VZj?Mr#}Uv7Nd|(%`mZ`Omvc+ENM#w=xh4za3BF?D7koVkJjYbFsKqdwfg*WI8zzS)t(4f(>E=Qzi~k)u?^=+tn&w3=;T=)xv{kz1GrK0k9z<_9 zChut39$sTEHy66WL(RKYP_{&(2epTo+GDogs%@A5s5Z!Wbe$Y{pcl>Fr8?YZZTw@t zBXU@gl8c*(Hrjz$!yA$sE#MCj_ zfASGF1iEcMy|p+R?vz^-jVyElG)Sy|#N3cdBXOY-Fxcq_V;@wI2MvoRKu3aIYanUb}sd6a?7e$N*%BA0{dwdiQtGT9nip zxAJ;W3u%h|8u+?faiVhuD$+~?V!luicgm{0W0E(4A)q^=o6G&G;zsY zkEW0WfSU$U1hD7Yyu0-E-B^EPx3TYaV4HuYe+3>t?u`_NEKoC>`AU?tC=$UrjYVw$ ztS#m(sIUPvFWQq~Kbm?P-rlFRaZSfyFRMLq|jVwTsH%emh>9VPoctE+iBP<#C7 z{ZRrx9@(8F=k?I`{XYxBLK@MW)6k~}z*|zjODX&=8ao94_WcXK(n%_3rxt=*>yC=T&uQ#nw<7JbBQ6 z%sC2c6sAnSb|S$4eQ+QGbNnglh41@Qw@*)X_nw5;hsqU&g>AGJl?8qt^<6K3vg1I~ z^}Xv6ffFGf@P{uJPGUqx!%deCkq z@wggLkM`&H1r|cuns>B6T{Wy7j442xIwPN-ooMo&ol`&nQi^NBE_jquC~QqwW5Zw} zE?A6Rp2umQOU<6{w$Bd#Sg!(tT|GtE^)JtGie#B$Anxz~Xm~ZQ2W#3mF7hg6738=~ z9*Fyc*_45cRHG1Uw zbTzu(o13V0I~KK0bR&OIb^SB0$m~FvAadh@)Sg`*)d9Os{Lcn*r%N?*q<_~}c5Xek z+10t{4MR%%ZDG(=GwGTr$RPIqn4&>!M~(qrk*dNwA~ z-GM{|K7Ik>czj-Ic8yB7^(|Mt_^{c%VAsniiwN7*3N|dskp`0H$Ke4)(RznO?cv=e z{~~*Z06H2ZyT&FET?Z`KDQ&Tm0E8G|1%-%}{c@*F(M#8XJlnNO+9|>1m;Y>{R?pCi z1DR=|jzS3%jid}*Aqh?N4O(+_lU6%Kye7EVBRS_ayjG*Y{k@>fo$N)uEVnn(79KeP zXO*5FiT}!yTKi)rD=V%|X(~*_qmd-`JL3@%;Zm+ug>XfIQVQd1hdnYDN;zX0u>TJp4l{wYq@1s*d{YuR4F|S{MI~2sSy==AL-lcM>E-0Qu{uV*H8(2QHxSc+nWh&LjK=D1V{N}RT@Ka0I?@v?YFG3&&eb945^6Rmx=C88(i>j3e-=4bJ3 zOl4i`{zYxcOYm@!#_B*ZKl^X?VMapJh8702Pe__!4X&0wE?v_5%8_VkR_NM-g z2WA$=jzp4a{Ed^d>`J>$N#>|MZ+gf~Q8cfTR>ZM!}UZnz|1l0v00WIRFYX=yQU z8aHlpanPjAe|e~GmHfqo+_gV_dopnK@;HJc{FauS3zwdJ zj|+S5UVm}vu%uawLNKAb?s*uLIJ5li?#ay2-p7-+>lhMJ06e*&&X>Z2jQ_I;e%8cH zrmgfLGtZ9Y{N(!OR%47SRwRu5V$zMYD9P55i?(}E9d&XW^A?jNKsfk8X+DUAEod@{ zF+(Q%Y_SwR?)LYq*>t`F#9&zN>x>sDi>)w9o}1#j`i{%MA)P zs>aSYC?8*E!lXU3`rkXJ8#Jlt=>=Z*%Fn@-&Kw^uN~I+Yfjqo;T1i@}kevg0^-3d( z%C~Sau~N`g?;r|Q&B6NYIjx9}L(I&@nw9kvh;KNTN70>6T>@GB5>e|6~EfJ2o}iv@;$}VZ|(6udj||-?G5J83hgBb~rKiG7X|4 zNdRRmi1RU06}2R-Z~L~eM4)SZwjw5#fmbz6>q(`K?LvHzWN#uFlf%MV*@Oaf8W;4R zu?XK5jj@h0Oi8ZF$l55$oD@rO2mtVcEo3rfA48|v3VmR}^$dCPGW02inqr^(dxK}S zbpn)dznxNBO-rakqZA_gTkw8vhZ<`&YEZC;1du3M<}@b9iY#;|dJQU(^MBcrKYc#d zVX#0qQPlm^)b&UH3{UMnMQ#hj*Y$HPes3U)Ww+&oX7W_^;Kv(a5tnZ2z(Eoq)qm7@ zRRF0pXa~WbsNLK$K~mr;A%v_D@LFLAIr4qWfSjmLYW3Xe&G#+cY@Sbwg??=c9=A?* ziayPD`?ce9+;$zMs!)*}{^#0zP?osTvv2K|f2-bi&d|RJTt2tn@OcK#78&{)aMW~L z%jYf6DTcUhkP@zC@$7eZ3;K7*nT!;22j9?uUyXyqTwWIt4Ek7a)+|y#Y3XIZLPskT zgqLViTl#qA#bb?Xmgt)p`>+^Qh5G#{#JL^f8K4sPta$yJl;Inv8YJpxEA9oDKQqwtMOt28|Tn5f^=PoPUGxJ z`oYWd3VC2>|L2~JF}y?ojH9n*m{lJ(WoQbJhyG3b)S+;EJO&-=ku+Z1GLOQszpbYT z6PkR6bd&BXv{Jdw&;4;pcfWt`4pX5k#Oox2&bIp zKK}gs%1q8J))Lia$NH?$riuECUkufj{~)uldmNNlG(F+}B#f%8PJ8s-VN5NKq5fw~ zD1W~qlG*R0-y_|uXk0k23a65WLk?XZ7wf+}>cUEBq{M#$p^=gG;Knfjt}s+65GB_^ z62%8%{zWF+fSnal%^tBeaFDw!Z3ivOI?ImW3Z|KVPF~qVp^g|$&KD?7znw%K?ail_B746 zlfIGM_*Uq%O(dU^R@3F>wUuby*NC^1fyE1bUAoVj8&lbS5jfD%-Y#~NMMw70{9 zdGt{=E#zF2a3F)4hpEX6@+);G+*Q~i>p36ZO>{p&qK}(8(w5?e{N{=K0lVg&cZ4>r}1PBBY2rWnp0!r^FozSEU2ndKED7_pG9y;_t2k_}hY=(p~Op6-W#S zRyVeW3WTu|FQH{6#xdmBW#()$H1ohx=ooyJ#g#VZMtkT*)~}zySoR$nOZepg6+nBi zNT&GPTHq)AB~HhF7&57^N;Ai@s_!ddiRWcmeXlC~Cry|neM@qvREHg?z(~jRq9Hv} zX9%eQ47vgpNTPpP(O!v+Udjp7r6}bnx0TWk+dU-UZ=gaYr3#u< zGTY>U?=M;RM5rA{-SMOYTA`gA;hkepzym8v*;fjQxLzH;C5e?IFxglYuHC*4E@B{i z0bN#@S+mIc_S!NBAG?k~=7F5C zk@5AxjFCYALxxfjbpVv~!(;?>hzG*SiHQcSl;t2jnww$5l>MUl^K(rl!#RTw2bRsp zuj@=Nvn}Hv%O#QIikd0gU|A*fX%SzV6Z>i1A}p3NE%!5(tOgl;!(kal(8*!=bhrSZ zL_J3=*EymW!**>|h5HI~qyOhcPw|x}g={mY46!8}j8pW0^MT6)KI#7P9VJ%(G`Smv znir*CJtG{8vz+R(oO>9QtTa2#Ov4EhAqz;ZwNE5JRH=vqfGA7Ng%8!`t9P-jMXVaM zt!QIQb%cuV3q>~445~P&v0W)qe^G@;eSi}$_4a_nc#+}zjK;)RmT%+ccQcG%f$uY{ z==@!{2WBBQ0E3u%%$g@nhrU=L>>fNeH0rYC{#>s5jazGun`oz$lKzzv*g}z#Rc&>Q zuyuArD}&q2!_GeUfez2LQrF4S*je*s#IoqRkn}6bfE(&qJD0F^TZ0=)NH*T;8_JDL z6azQZ&el}`dylwvZE#r4(lub?TH5DDV1PrSqPMs9l~CLICy2eW=`WuNJI&h3JrZ`c zpdZx$;0r5srLa>}(A0J7Z#Sj@T4$fOFKWq6N`N10CSZ9YXebkU0j<{~`u1NrzH64) zVE(=U+#-A)=J`9lhG*G3h&hC_-O!q530$8G99jUdqbh?aO;s{+iBOva;*e{j8oMl* z^>WLXJi2n2C!ynaFle?EgD@EfSFLp$zIlXR1=G_F(na4;;m!Y z5<>VE{IB(=iM&U(Sz=4>Vq+M1 z{V*$nezi~03dF(6o0h~Qnz?$v#9{BfDo{Hl88dtbC>6QoxE#Qn@zn9fj|$Dng+FTx ze~WJzD_}3>Ge$@@B~V(5bZ_!cZWhdgZ74P{ZsWQccXK@>dK`7enSQ$_oiL zoJPS;zPw6erc|JtcioV^>XQj_c=g5c@j+p%!u;!ds$n*xcfbI0TL}rl7S%f)=ij`4 z&iCZ|Cl$$XH#b#s)DZLPujeODjaxhJ=a8bWm=ai`1s-QuY0hKokF}6kMzb1~D{f_oQ|Px>2^!wBXd2ZJpJf28La&KX|>myL{?g zu0KkC->DE>l5y@F68O}`c3YlKf<;j62q?7|%YZHKV!J#3B%5(`xU z6P4uKfkL)GQ_DwTJK&YwI~iX#6C#Kh_V8KP{(OHo+wKnSxE3`LrIL^DQ|z3jX!!npFk2?2v8k zXiTDek|Ibuwy!lqudZ9j^Y}|0*d08+zOLc1M>MeC zTe)BRLo{!(E}a7{K5+9FBI4q&3JO|3iV!1V7URmRp7-7|*$rjm;ef?Il}z3JdiQ|o z*H0HYI#z}ViZYLz4ITntRj;*(@iXsga6$5W_XBEvb6!5>>OT0cU!Ptsq)kn!#L}m@ zs3Np=fC>?$jTby-Q#C$P;Y{csguNwW7Z;hT6B{159HPezzUHRFM=+y?B8(fB#STM0 z3NwsyswH4`3_fc33k^Tm*WM8!OLjjxxH%$kR4hqA=fb51yc){9%0ugEoy93{f{8GU z;3SYmFSRNb^aQD=ek$uBXd@fEkR0QRGhW61ks}gd60zJgzly(2!ZjcFWC+o zYP3#jgf!R%DHx%03BOgLw)?)2$y-%JZ#8>y;353=@!|cWccRgP3ZFa}@DfifD}ru? zfeGf^#y5lRqnl5>IMTh=hdx76wy}v3J>1pmhY}Bba8k^i=XOpjxyl^1N2cjbN4Y*c zrINr+us2-|E+7J^h9O0^UJOY-xHz&HcFa{Ul9(oZO?dR9OCR&2r_#`77;V+&+>u5K z^mJrH`1P^8_^kA&7|m{a5YM|?Hp+I+%^?EE#_r;Va4^lo@Z0HNh+NE@TPKe2X5*?` zn(s87yT7^A_Q{;}xqNL-oc6uHeBufRlPr?+@=&WIF^`>3@4`>*ReY7A9oQZE6z4z^ z{mWjQgck;0i+BnDN1n>HaaAecNz_L8M?duIle6ku30$}DeF*D3>&vOW9e7g`tliRa z@6;Pg7#mcP4FuEYy?#FGt!21= zMD4A;Hx50cTl4?^P;>|nniq)a6VvH#N$>SfSin14&r)lO96SkZ4$3=B$lFbY5$^du zT75yPZK>oJJ~}4;dW_&!t8j0p1Mb)-H2pLvRnRe0GzR(%UeaRA0*bm(Th8+*WU~_-}$SB<-6KtoI z8~pARL4fG`L_~~3(*4~ETP?pIWh9^6hpePBo`&6S`ue3+mWQ~i+ZL1pD%mhQ7<$bh zg2hd?KOb9GkIZ;$PAoUlLvuzfZBydehnH^9dq#z8j`EF&XUi`%yr^%H^`GP-rtX!m zz7SJ+7AlCjjnbl^??2B~=2UHMu}3f(egi5%)&LqZ4dS`eSeqwR2i+?F73*i%Pc#t6 z=q;DMA`7|cm7x=>L>Vf#0g|hpYixMZ#5r^w*$?s;)s`aW^uOpWI z%ptRxDfl+y%_={k{bEA+PY}JyrV)tJW-8bZn=SeNtI1TB?fU{(`Kc$2-*3JM{`R$m zP8GBbFjW)Fo?Vu9my>or`#>8(E2X@G$mPu5`Eq!5M?Vv3xVoX{rqpU(Vl|yi-?hZ9 zu*~_F-SorFvT63Bg9PrbRXv3@6MWZNm1#;r&^xJqk?be4hPH=)!%-|?DycBeftp~c zu-;$q&AY%0`0#}-;ze5UIP?3dkl=|0gGFc`U*^K>sWj&OXJ$$%uW_|qDX8^r;dHRkB2q&X)@@#Z`(C3)P(t{>wcxv&C zqIQ$5sZZ3C*_EQ`q|BvADjYOvEVj|Z#*rZW_r0lzeUDZlz2C`|^pTZ* ziE4On?e}CF4bH$_8>t5w_+OKScWU1D=YCtgpCa|>VVUtRTZgq<>#Ks8d*u&W+?VdF zisK%ICP=bKhppFUlnQtfkuk_+*Qz&j-DZ(KcsD`A1PHuO7cXO!Cco|VOwh&P(5}c> z{?XhF#;Ds6tWYxD@QHNlOYs|uNZtKo7oh2OSkul4&TXL>PSyEBnKS%OlD@RjTFf|R zVYFDCea?LKT06*<2uZC~@ZMTpEbIg8Gr54VQNM{z`^1l*AigKwn&!{N|MZ^h72f#sr~M!-d2V&Ja><%sgkb7vZn zn@bOX%;y=Ri>1sb10ZlyQBak3OBeW1E$OjbeJR&x9a@YxX~~DSB;kv10EX8w!8SFy=x?2}~Xej9{}(r2$D15N8yJ-vjpPKjRPBPNa16gob& zwoZ+)$w|ZDp(8=XVi290mh}^K&U2ab4M6k+cO7#FA2BIzVsS{{P^)hd-}{&w9454^ z%=ehXSj$mF_q@GD%7)T8i*1whcXzc@QxxTofJKAF-c<9~1SmL)G{LW79waU6Q!i9v$weZOCi!Wo{G zCC5k3*tU)=+M{&tKfS-!S#A2`w_IkkmK}Zk`nTK1Z{IAEzf_-y&L-OWb)cyEL2-R;N z-WI22x5IA;ZQw1=H?;7Z-qZK@etVWUVPCNey3scODs*@Exu`A?eltAuXg&D+%{`4f zQdF$i{r6l~4?Z})nt!tXdQJ*R8!XkHcJ0u_NRo_jL!xf$q* z3TVP-Px?Pc3^VOt78V)x<%%%qCy3JyLM7MKpp|>{g@`!6JBxce62GLVvR(e za&~XDhAUnSU_Y;>vDQ7xJ3R$(LkK4x?KsBB@`%MbKYq zac~Z4osBi2xW@bvVX8EY`Pdp{`sh`J%%-yS9m8CA4s5kk`3Rk^4xE0)O1fC{uIGKj z=&7S}rr&jKOhM^|aEhCBBur@-ipFdXgV9z8FAlo11cS45d(IFky)YuLc-Yt+TG{jU zb2mB}{1pUwlWa&I5k;&_X`q}#hi;Ij%M$e2RJS+NbCE%@gEZBlQn`lf29s7RL7V(N z-|%pIxkd4MQ2?psUE&x=7epeMZ&-M3F#AE$Yq6k3G()jrjl!o=HljC(oF9|5Q4wHm zQ5ysJgbo)BR$1v>b$_11=Lk zwvPinZi-UH)Ac6V6rq?FjD}lGSY8!HfyP}PDe-4_4~f;LCOWBtR3coCR`m1V3@M*l zfs4LmIlq#xxw$!%+1^78@W!Y~{q{^UjaWq4AxY)tITGB6t^O4>%e7iVA|S*pCpc0T zF|i*`7RT(p(`bjDEv6l()hfOS`}U(wUj{t(knDMPOB3^OeIs%udr(MpUGMTre^fZC`rM$Pt3i{%e@J=}X z8qAK2YT;Q8wK3>7W^grrVz+$SYa&9VK~f`D51>;9V54&f_w03^%=NA@5LUjDdFvs* z$OzERm@4Q75but2xc=JoPnzlqTwUGsX1{;Lvb_4~>Y04` zgCYAHAqblOp77w~wp)uTVS9M3{@IN|AWHv6N`iUz5@iSOBbd53Du87f_5QCI1(N6N<;}^yc_Rn>8AV4qXLY@>f_-&ps)!Jxxu%TJb`i4;sJ@z8kARxqgL> zGHkjHyqf96-Gy2nryhpjRM;VeI?W_eN1aI+E*G$fKStV?{G$c8RFn5;NLW3et%bGoKX7uGrQ;Yoe3z2B$#Tu`N%tAtHte58*ddd!P>6T5G%MDzyWE&L_+}-&e*h@WJFm-fo~tAYvuoY z7)oLxkm~bw6n_-I>*!e8_iTaiB+xbbXZKPVupXtTBvN(JBR3j^RRVJtNy7mA^LNS% z|6!RJ*FpeGmGqCZwhIAVLZ{=FP+$%g{O(eFJ@k0nmU!A4HK0VYu}5M^LK3TdJgB}Qyup0BlQ!3 z2I!GBjh()=;=R^$(q#odvVz7HL6|+((?nhtIh1U>TeS{vzVd*nEg#+pBmGGX?eKs< zNrs+}ohXEAJx@7lwUX?@9*>Ef%MDDjc#zkSdpX1ijfKH@X}GqjIdJ-dM>zO7VJX1i zq$`Ej$sHQ>5o#$+GbK_+=See*dmyxbo3seAL5z%gi*WViv>bm@J$CEXK5f$&ZSelF zmJ+oieD4IHB;BWE@}Mt>p}~I}qp{U;Yqv&iZ!pxPaz3R2#6$(3i6T9zk>R3rOra+g zfI>f-+zL)#P&cWO$ogIjx2!>WtZGJjoiTUsT8#j6ODcc+IJ1}j>6HO8*5D*&?_mY% zWO9FxuAVismY#8gN{W2vrh6KpAC3XV*hAs%^G46Q2Gg}7rX)cYy*Ar(F4wqF8WhU$b3SS{p;4E z!42L+4I58XS-f~agRp2Kr>d8P?K_DM52T@zB-Q@OwL_*y_ih!YHEtlxRsrGI_}hVB z#k)87RXC+0X-@|ZXltx^wGNIcJmD|{=|>IHIbOGxCOC3xO)b%=ze^p}UuA*~zbc2x zc6>dK5r>+;=CMwO9-&NN4T6c(w>W5(XeZ^_Y0N~5>4CQjJG8Qz#1gNS2^yZFrw9dw z2<4+>y5u@Eo=Sp>LtkmuOUNQsncG_}RaMP%>-KG8l@3D{_gbHP4kjf!reJqzZ6o=> zN%g_1TQ}3yVkH_X$Ak-2?nI{F0gaI>tkNh<+G7D$KMDDnbPQ&aRZmdOy+PwW9eVeW zO?$y2Ic8Ply#+?tn$2vo=9@b9aXt^Ye1*Dr!)6g+8#SrCVU66>u3{ERESvB0- zc%O?I|ES4qlh_UlDC+T)f10VTq@KxM2w9H4!SR(3|mqOE0}~8(OJ`@KgW-VZdsA|T9G$DQo-(Ip{(hBt(lsw zSx>AvZaro^Azxo4=Q?@J%uoP6LJBfGVQt<~F0xYdwbAsoI`ny@eaqJPyUnqWt;LBg z+Yx#Yer@m&znf9B_ zF#N9*lq!l%fqRMivn8G&dS%&>ys(1%QplZn&`dqyZGJ+__*kz;;(i|#+2TpdU_*BL zl;pdesGrx9TOQJkUXrI?!neJR8SFESb+en?Ht%<&S<|~1>!>Y1P!uzFhDTh4!bc2M zFNGg6Ha-+2^;KK0ziXnmci$(`g!7IwmS@T5yz%%-f`_OUsu{~P;sp;lRn=`W4K`t3 zVepAR_3vr9{`U?2q!sBH8ab^bE__#3Ud0!b=4-zv;oc(IfqUjGq}_CzusIhP`@*8{ zG~{M~i12mB$tAW44o2_Ad+x`ab5ra~w@)gtv=^b*rYD|hOBypthD-XJme6A4rxo#C zCdO6toY$tA+0Tw~U#ua=@Eu0&meW+7BiQ+r&b`xc4j(;yy0PAhK02&i$*d*P zEh*%Z3Au(192IJ=m>OfY9|FNTK$nFv;E#!pjN4slIOjlcPl_TMJzfO;X4U zCTnEu)aged4yNT$)@MCr7q^oI&61&g%E`USilXK%fI<{?M7{AB+?Ph!Z$cOroj;Q11gFQ9V`0F;2$~IaepOa^1 z2D?RJBt9{n28F*&Q*XM0ZA z_aoltfwAyo;4ufQKiVzvq9Wkdo1Uj{axRWZ56ewTVOe4)7e)H@Sa!VRv$D9h!gI4I zcO8aBC8_~oWyhJa!FG+$&t%7CYT{8`ZGgg4TcbztY*78%@W>>^uw;w)dj7mzp|I({ zL^N6c)nu|3(2iiZY)xot&1iYp6Jd&e@%ncUssd!1ZDnKkq#6(X8{f1w=KO$XE<)*S zQ&^c##*Xe-T%z}WL>^vi8*Ec@y-f3*E%wPPZ^Na}K4`KPCeJ1+jb}Eq56m~tX=ZO~ zD=@ERo~h?wE=3_EH5(=AE3!ZRDW$9UkO_ zg6W_em9`fr6HuP5yx85q`nJH#y~%F(yiP}2&CgQp<*hFccaeC)yX;%+vkOemquGv@ zYx%lzX3lxNibyP(3f9j98mG5ceR=ZNP=NU=nL+BS$mJd1{7;4My=D&+EFOwjJp`&y zd3%fSml%8+%Cjh=KhZpCU$!kCd2P#S;8W`WXl3C1T}$vCcqfJ;zx@QM^w1@@OM5Q6 zLFR+OL(3D{+Dr3c^4Z=cmOd}DK2XC8CRxg?G()Jgh*$oTXZf5X%;ncvIwSMH$Y&3W z-yIFT_tB&eHkYS3Ece_bKEpHU^M3p1nYpifK_8g@__MNZqkgg*FvGj7j6OH|BpHrL zTeK-ze7Cpg)_m|q{r!iXhwtFQ*E{o1o?W)|pnAStOpGIj@akS;+*M<@OQztPpMvL- z`edi@Et4jDlhUc9CMuLpa}%YfCto_R6`^LH{24lwP5LAKh1+N9%^!xE_oQ_N@D{-2 zOZkN6*J*3_p26Uu8oAWO)~{{Pe#{n3&is7HEQ4LKfIfPLHkNPAyO?zzrC_n^Kb0T< z$x`L~bJ0Ec=dYke>BFCgB1@hk(hKaa=g(ENXUb}knjEk2OUucWpw`p}I2 zoCyGlkyqq>Jk?W4Uz}?WI&ph)~pyV!gzWBxI^2N1v zbE(+Bd`0hPx-B{L|ICyJkH6@u&a+I9C4T<~3niuN0qLvYIRZC^S$}q4E{j^OfBw7u zjeb?qU^Vbvi|pL0d#z$|5%8&D&3b-U{N+CA`QG`w*`JrpMEDb~pTD|k7W%kjP8+s1 zo%jE+9u-(_a^kzc{#|_3c@S?f*oIxg(=FR3SN@qiTpL-McF6o3T0PqsG+%A@;!wH$xYWrGg}{SW2wfPpG#792d@2Lkcg0 zkL(pLEPO6h8ZLwvV9kr~FW*TN&H?t1&htX9KHztS^N&6+XpiHSjTHxp9*?rgJ<6by zju9#DjiiJNik1a`ta440+iP-p%9g1v{*Iv+1an+iivWaJegn$$;!z$MpX}7pGj;Qr=uU8%{kHb zb1AK4{fs_Y9pDsB3R318N7z~-j2b?koMDp?=!>MxpXrJwWlURsg zu#B;ex|VCiVR}py{pgN;c@vpADKUgbCHN>jk^W|L6v`cTAjxSe`2$j{i*Os@xF`1) zVw0l$@%z$!cA?w%?-WKhtFxB9uQ0$6wu|7r`dJK5Ty9%7l^a_;%Xy+J3nNFT+PsXl z%XPZ9!D*)ytZ5uWX-q@vJz>FQ8%H5(psSd$7+{i>*&|I~e2?jwLv{>F)2ke31q#P9 z6`2R$Qct-Dsp&0oFQP**c3f*piAO4*)e5t?d2C~pn|>SCv{&-zJh^8(s8|c6C<`o2 zdfgS^h_Lx6g6rfQq2XY)PLSU)y`F|zoL-?~;l&&9IW~Q_9A;}WG`p6UPgdX)jkYrK zbb9%e+gnSqAS1p~z32T8x=x)zS@&w;&wQCotKME!)ExuGD$L8<#1o{ulgld99Ti{G z$bK&(z#K;c#E5Gbro^f|XOPge=IQ5@PY03$Sm;|a13J`LiKPeMwo%xo>MA~HtTw1j zAFrbOqPE%D@Lp&M`i*qC(O{&8ll-Y3VGO2+2T-|c00HT(UjdCO3@A;gJ0fF5fVGA9 z>Gb1dLFAx*j*eN3F@|G|)o&ufprXKr%&!dd2cgUb*Xa>TH&c z#(s0p*fJu-|H$3zQ1$zI;^*JbvETV_CC zBlSUzyqphn7Ol{A2FE|&01*L;Skb6)xfGtqtR#RYXk7^c=)8UUVt8&HJt2KQnSH> zCuMZX5b1S7cA^5hPRLG3fi&6H9>>=bM>VIgssm91q%1`4T zvemmwN@Hjauw)7e{1lVbuO#2aes*#4%A2cRry~}PbV@4G%F@xGWA7X3@~G$AG0K`1`bOJ=B5dsF4ZB3m8(sIfulc{d zU(4+{>N1H&7E$`Bp_>jd?%wnRGuh ze&^;xy5AYM^u4z0_%p!eCPgYYCz@~-3N}08v1#b_Om@(9j-uPCdL(RPkZxsEidx#x zn0RqtZN$1R!L|AcJ9K71%eOwBs-JZiO;zaR+mOFj&Bp`%F&5|BSSDEGs2BfZveLJy z+O@{{QB_QR8gFe#O^qvKpGi60VKz$hmAVS!L~0gYb$>7~LGx1@03toi)u{mg1}9a>lS z_=T%`Yh7IAtEip!5ubbI1-CdnbSQ(Yh#0kcVxQf_u~16Q+~sSzsHu&F_AR7R_Oe9- zVQ@3*{@bEbd=S!+7&D*8bSkF){5R%1(7e_hwr9N(Z|iJ%s_C?{SJ=+J7RH!YXCt~* z2ck4Zt1;VXE*0DdtyfkF;Sx`nwF8Ej`|DDlk6>@$BL{evp1w$A5f+)!9yXo)oE}PN z%U9L*(eXP?mbj)J%ZGq;uUB4K1P$*n|6JYGvZ3&B)?Vzo2-G!6x=OT26Q?4ER(zZLXLZm(@L1a?#e4c<@{ZXd@dCmj*M!%gt7 z;WmqxJHhI#Ylg4eU*-vw5qF}%*Q5PS+F`zlA@bWcEoaliNxtvc<#t@$&t_&7_NhCI z5^sz)xqSb;TiMsXrt~o|)UW1I5MB)z{`z(l#GR$jd}~u^JuuBA>2~)`Hf zNB_4xz8p0Xr0kg9Lo_D|G5pC_7IW2T$0QdKhNraA_W~CKH6*ba=}rMg-2pNKg*Q%}o zLEJryK(_|;5JegjOuT^zf`<3%N#q^>2os(_D`b=w%<&)Xc1guiE*nuEJkj0`(f$?DK^xH=p^%>h z91R8ilqN8IfQ+Axa)%(2O{4uFh=A7UU2*R%R$|BiE|Y}^8-Ph zt~4!QRF++Wa22uKAId50S2rn?G`}|RxoA&5uZXTjwbCQP%CtZ_c&-6 z1R*5?e+z&!is0^J$gSz5J!JBsY4T}y^5t|g9+`qNAm7x7$asLC;v(R*qO>bW>dhoV ztKgAC@>xYPfKC1jNwKjJfs~3+8s6aI6(u)D^6;keo23fzA~N+;IwOI3eF1kYtjZ&W zye)<5JY_pOjdl>9#&Dj-VwQnQh13?2N?SpWsFMLq3dLXwtSyp2;W3;*8>tZ;7$`6X z!c&98`(bhc0{9}(njxjDRSJNmn5RaxQBx+?Wx1Ybc}l+k^Z_4DggWL$t1{dbjW9Hn z1U$4O2D4C0SsuJEyd7V79cSw_sOiy4W;jZkmLenHlF1Pp zR#475qIYOmCKLEK3gjRe16WaxrbG5|DU*%`)8`TaZ3RDh5rlvNsI`s;V4Foya|ygU z%33?-T z|CQJU92QW{QC$9z4;hpDI#A}7?L`I3pp-rx?q*ePN`VJ*ewS7aRaU4#Hqa0iE6A<~ z1f@hex2V>GgJP)>99WR!B6N04?rjQmYWl^C+;a0uh`7|5+0diHMRclA17O(%iE8;(bDfVVN^9M-j!KPs83>QLdZbZSI4 zCU=WMb+9&;bN|k2AJrvJ?Q&5qH>LDJTS?@29XoS9v1C0rKjJ17h)t2(LW|A1CwG1Opn9F%d8`Jz|2F7-cZ zVN;6Im(uyjncPtnp&t2J1Ru=<+=YfYmLad}^mft{_liIiJV*z}49;w!n`23#SXecH z2&*NP79m^1luCP$+Ys)|Md)rV_T#gckQsu)M6Uk^Dc#v8f7PcX*RK}Tui4rEdlov6 zAyr<4E{q{S#`6KeGo(Ml8%=IjGetrg6bhayvx zobVU9PEC=yN!(ovJHxwW`rviZqr()qB|K`2ih0;8YXJWOh1uf0CaocDLd=rK0lGl zw1%J5QrOf&j&ap@SoKgh^WFUqU6sC9CIk=?fnm>) z+7_m|@=W#mFw5({-vxDHr zfeLnJ3aCCWdqBO(m^go$bIUW;VPNOxOcs;P))IFztYKJb@=a=Hf-{*G`c+1^rM4O= z*$#A$QSlYcd~lu9ULsyjffAbyg?SHwSeZc7(9OlROi`_JZ>`K!XagnUoyT+rP4`08 zY-jnf-zrg;+zbcJ-27Por=9t|KZrqjN+IkZ*@!jU39N+|&r}bo z>{?Ky2z=U%DV_3DavhQSVs@qn_{S6SJrtSB7?gh-31?fPwVc`T0Ovo=^X(| ziynIsilaK!hkf^7-b#-d)3_gQMR}Y;DQ`tOh{D6Mwb*!^z+y^!^q1c?mTRa>QfUn2 zq=@u!EWBnB6hTd}hDk3|$mKDRetrb)7{$DY-p&3^y$ez_hH?;1>3}9()~}B$f`wv0 zq55y%zTKJqvI-M{N00!G`qfoHHj0CSG!~lvgJJ=r5GYjnN%ejlfQZ1sKRT0FNW)eQ z8y7zB{Mp^h{Ud*X!X04XtRJ9QUNX`)svK&B7Y06(sJ_cqf@2G&uk4ClgaNfgcr+a3 z4i`S!;}AYj2`0rCk;-BYWKncvdm9v^IMfo38V*FTAqHP6%_Kl@)X{h=2yZv2TK+&u z_-K5P=%i@zdL6|}5TY2f``fa5_j)L~p5i`$zJGh+g)|(oi91jkJ+{E-myE%pi$FGL z@}@Y@8J0p`1hRpHcTa3}KPSw{AR?;t^CM$|?>lfXeC;Nk`|+>AQ$k&O)CTM$H6)Ut;dMu3V_+5k z((vZftw=4&;a*!8P41Vfe<+lMU^yZQEqj;u*r@+M0A_y)g4us(nEgFF!~dg~U7Y_5 zGrJ&YW@l#?r>Flr%nX0De0+R-czAelaPW73>tC4J-X4B;;&5+w@Baxi`}1?`&$n^> zTmgPE_Wv0(yZAi#Z^`WZAI9vWukWg>>y+?$-*qumcQu%LiOs|h+W+k~J#T5bYJP@q zmHOKt`L|Atpr8@1gU`c9pFSP7w-Y3@;o;%`g=9uZY&$wyTU!Z+SzTRSZEY>Sq!?c% zg0KEx8fI_K%B*`UqyA^ZtfZvme>BW8Gf$F}|7Dm(N8{t=HY205v$8TWGE!4h6B85v zXT$8m$MBM1m^lb-J2-{~2NMjlfPetJsUluS_OG%SUYc*u%ydUfdqq*n&(H6F0L)ze z{{dzS3JP*^a?;Y$|2E9dA;(98aJbQ$3Ul97?|-+CDx9UVb0qoJXJ!{IO(jFOTP3WZWoP>_?8Lm&_` zGBQ%aMM44wgFzq=F){JK0W)_3Uj_gWJU|3t(Wouz35U>9Fq> zh58@BO!WT>nC1T)Ftdv>9r`~5X79u)Sl&w?tpQA`%R>eK6)DAs22dlPX3$;kHi@sw>B<&GOKli7K!pAu(#==(&Osyj%V{b0`uJ5!IKPC|o*JWhS za#)Tf0A|;fS+zC_NmL&eJq{&%?oUL+Kxeb$D|--Q9VdUEu`EULW7$$%TvN>I-83E0 zP@4W7-n9&)8)d5);bp1P&>OwkoZ)IOrOLdY*xkQjXJ5i(r>%bf&DTt~w;7;7&VI*V z1^(+Z$oy5?bM80^-#6UZi*K^mZK7{wRXmOtYrmoG`g;&jn1;w0l6Y=Zx%n#pzSbMR z=WZJx6>m_}IT+-*aHa^ppI$9bN`8)?-mq?9GvHRBzgG)&oIi+}gBLgz5%J<`5< zUzgVY)t+y&e-`8oz;%$svPfXd$YK&!?g~Kfj#0=Q@~n_5zo_^ZTUJ4V!G?Pq>dE#6 z)yCT2rd6#)!(=~t^yvjo9eEpQTO2D>InIf`e6CYE)W{qycrp#R$TKw%u@s&BaB0~& znROzw;udS@rv|Zb-6W`G_5=7H0$WB$V9O#Ps!%bPGXh(NMykfh$3r-@0?=Wd`8J(%m+7}n{d{|`i(Nt8jIZ0`h=f5(&E@XV#5}Tr499VW z>t}So+V5pAqV5I~9{e6qppzPwV~5a<2msSXqh7>R;&Dm?17iAOnJv#gD&C^ws#Pkh zvP{3+>u`H@<<#qTy}$m+c3^&yP9OOmK)Lwp#1Fa1v4?@MygWek%Kgf8VFP$lcsfN> z%yGoP)3a!~TRh1@8^i!h|4UhF(G-&mI6#iPBj?)_!%$sm3}QCw*?!G`?K}0uBiSKZ zeVic6j}(*h21X)$m1?A;R4Ea$P6^_tM1N@!m79LT@{iSzSbIrf_q~`Ra^R%lK4BnC z`79I}LJa~E_DKMwHMt%HLsV@|J7-D;Z=V)q5)+J02`$t)8laV9uw|M)>!U1=Q2e>E z$Id3hK&+}-!Yy-<%I8#KpwP@}-LH&-N#roJ4b-5n!m0Sk7tW@6QoT%xfd-r!E8hDP zd+u;@To`wa%^O-4t5SATWEngX(f>^Isg~|D1Xr}C4*1W(&5Zsp0vVnl#!jO6ydx%7 zA`H|M5=Q2PjbLFhfvbV7X)^*jfXNhciD@h9(-;sSrUc_?wR*TyT3)j%t!Dy@NhaG= zRm>g7t8mfZbB-yS$}cf^{rK8Z(J2K_SejV@iYuHAkDNKIH$~m;O(DvoCQ}&eiRWbD zqTP;(7Bux#z7BrEdIFGfgAa(U`&ZaCnKk5g0z{N2Xe}f@>i`ww$#;*u)bRNQ%Bhlo zu@yzJhVJhNNt?7$ZUc`Hxtl_-DJJtimO=kuKTLfrDA6n3JAQ4hC3iK_FQG*+;>MqLX_Ykm%?ze;s65xtbD z#9xOX{#1MdoYrF7D@F6P^bx%TCy8 z3kQBOwQ&V3bw%F#r^h|amSRx)!V32`h#1Y8%yeoL)Ph}vYH#12>YObw2{4@O#wVV3 zf0z?4%NPcx6f(8BAMEum%PNv`{(es}ZZBRj@NL6sDn)r)sQ#@8l^qhmqMnyw1XZj+ ziVQvM_i%quK{8~&Qa}6ym~m(j77rWGZC^yu^Oo>OoPE+{5p~xZdDv3oufiu}5NK9! zQ`CBP!)N1@WV6%CU?qJ~Y&GM}eDJE!;oSlBL+8+VIX1F;TLT8RZs|9{D`)aEcmwyh zvAh@7ap{c#$(En%`hA0{xoXuxmaxWYY<|k&PhVx8_xq6UMt<``DUsxUKy&_$rjIP5 zR7MFGQ*(ln6)_`P+Y!~`2*H`bd(HJ(?*;6{tITxB#3*d3Bbak>npL+O?QVU#_8LTi z6|c@?)$L&XggoIcOjZN+9Z*l>7+G-J*QmfLo#WJ%i zojP~aE-sdTX6}1{1ZlO>6L*#1rcKz%$2-6~7Mnl&4_>!_YX5s&Z~ph-NIsBWl>Bp? zR=W8k$`$0W{~cfi!)|XHt}r%@d(15VRYUJ0@%(GdbJK8e)ahjk?Yl>Vmz5!Dm`>d5 z#^dm!&uasE&xfqtsI{LyFBxaixT)BNc-*SYfaReWf5ddju=QMQ80ClGwGXith^~RM z-ofIglFOEv%jOf!?8FPngGaU5qrP?8-D+{9zEc#=8eJ3|to|Gv+9de z?Gv^ZSTF&!sE}-%gbosirVxe1E$LHdy5!n~EE~x%H5st_P~WhE-}>bDmdqb|7CfiU zhOl!+e!>iX2$Z?u^5CN_Lu)wm@^g~n(Ahet*}CA<{xCrY+j%8Gj-EVpD!3}#ZJqI! zft4yVHvIkoyTUZP1sRV6sR<}1g2cgkHq>|uORTFAer6jU7!_V0zX~yWIcSbK!hUj%LI?+W5QKEMdAwfnTy?2oz zdMBb2Jt84Gkx2C3BZx@s`F!^|d;fIKKQL?7nrH5{p7(WM?^o~>;!lLnT^Z!vWuACy ziKa|?__bq+o?y9e`J8!UY;71UAG%`fM{SW(pq!CM8Zu#6`e^$Z?F=+P=6@tc&5I+oQ(<>@M-Wt~8IalBrtGgd?tQtr2bQZqF-Y z7maKdoDw2s?4qwQ$ugo(kV5ZrlaweE%QYW~r*l5FV3m$Y{5YD})Xr>}Y9{CFJ*DL^ z!|yYP6-s<+v1E}V-ks$HP7^VD#}v4% zKxHMvKOo>8CCeBdFtcYF{U5;W(<)1wRO;cV7kmp4b>9&d9Onj$cZdx8WS2-On*j+= zfy`_8-cmBibz}rJ(TDbDpsF$=#nMU4)71&>jRK#KjiyKKq}#6p+PDZLWV1HK(!gRw z_>%C`RMI^NfDS=&h@j{KfRA#isZY~f<0#pHRBmzEB&wN>&Y7YXtQCl`gWOcBtK>eX zte4GB|J1Wgzn~u@2=N5WYYc@tUN1BJFPHv+A$9r^cNd$J#gh|a!3tZXu!2)J@L@MA z5;{%LnvmS^4>{0P@&p9v3JJqwVfgp;u7x}RV=A|HUe!k;88F+<3?GIKM3H% zN@DkvbQ++tFSMqQTpdwN<6iuk@#TyF4nT}EmMgopEHk%yWszTY)=~CgsmPWX7yOnK zKKW|?cbPd;`44T}I{|+}9nqY#7&WUDdr8tajfJ48!X|;dq7RubauRg~Qsc!y1!d{s zf|dG2`CWI-AK&VfD(k@UdResq48#Fx=%~PSrngvT_E=iygm<9 z_odiJlD^r?!c%uY`$(KJYr?K8Iy;%0E$w4ZA$0V$J-@A$uFKCIo_yF#kP>kIx@31~ zrF@(ZCt$?p$5&48WIp<7GXuBXwTj!1T4HU8o*0k-AD$wKUHV|ZP^uaQZ3Q5A|GhR^ zSi9x(rf3gI7x}#SVgh3gC+|P;WIK!nc)ASpA6=&UwBwGoXxxrRp+|VppH|$T4o%t4 z&}R&f&0XTU8WX!{l6B!5D3bee&{R2SVfnhb*T6PJH;lnZxDrN}!0#~>+UPP%nw zB_9p<4s7=>-g&n~(wj5KFt=%PMbh2>6%)-*h@Y7L@NI(>qJQoL!AOIN_1=(o*PPsG zj}0fVj0RJ+HG0Ljz4Z|7qaWZ*?4XA>)|IxG)C^_?GrZ~xSlJr5B1RzvG9*YnxoYbo zb=`D@L}HDAQ40ywp9WXESaVJ&K2L+10OY?6$(vHO+>oTlE93)6D43G)1DxWZkwh8^ z_r{T3!pY-sRJ#eBR5D~HzC#u{L&nbs!qkT;y6IlnJ=dBYAlIwcNQ183_K|&dfOH`V zl}?~5jU=E`;GrRjsv)E+m7KC4oVE{ku_IkVz!mVbRn&j8Rhti-Qr~j^y?)Q}{(aB> zd--oeDxNezLz~i-A=L-0>;Q7#RCjRrJz@aB6(O&ALP07G`|XQ(+($v#PwYhqz|T5~ zjo$N%6KI%@HYN_$B?ienkozrPu+Y_a{D<1YSJ$BLW9+BK|IL*R2*DHaTp18_&`3n- z3v65=8~y~oY=jXZ{)a2`BQ=Kr;sF#3H{%6VoLtl6C%hluk&NO0-1R{msgp!YH0 zYCzryww%iK^8mDQq6o5wtm3t@6S7?{xEGEbKa(20#R;!qh`?zoKV;yO9W>WKZ6d*` zcN$Ya6Q=kd419~%q(wTW_6;49PJ0%U>muL-LZC4`ROSa9^CfY^AH^$V;#A<3N&M6M zA5<3QHzWI(LS7iou*4{qD5fGf`&wg`>|m-*yZ>7LqmtO@0>G8kYnGU3PKpwCi=)8) zrMSUS@B%@jNYWS0usvS{CGtOGti;aC0$c!7gp>R&RXUt3q^bxIb`N|xwOzPWtv{fo z0$9CI>_IuPR+x|n1Zntw)o7g4FqHaWNXmwSXJN=^N&sibzIxmjJXGcZ0Mt&BfsMw= zSQi)uE6Z42D?(?3SVy%E>(z_F1-E7dO^OrW^DDphi*lxtep>+tQiFNLAb6_`Z3t;Q zA^&^|y}=Qoe4+hFa&hCaIwYj3dyFuAT)^0(+G<%jaQTJj$C$!p`Z{W5A+q!9o-awG zn*E}$<T(0lvPZjtZoW0`O=Y*;ylbFB0P2P3EWYeo9|&G=2qDzVfzv`DARxBRcWK-Wz4G3 zS8I{)z&neCP57C4w*mPm-S_@fNYj0CJ9NzSU6!Z{b88!{hgCR-YyJT22T+5uE0L9ejcK^x~#p(V#}yM&}r4 zZj;ElU^|Lzce+l@&SQ6tXNRJGBb0PYJ&gK+udW_)uSa2Xu%&HkvaLGIs@8T#%C`HZ z_rCNLP`R6wQFl+R8=e1kzbbk+tz-AW(dHYk9mz0i9i*eNUb{ihfo?$8#L@m_a$OYp z!DiS_qX-;2NodSl`t4|^ESWE)m$O7Gel^+RUGmYc($1gnd&0%w)!42f^5gHl=>6x% z?Amtm<%YuWp zBKwNoprnOUr(dU>x9n$v%4f%H)DQYh^c8>7-|n2%pA?*}AyZ7nAO4i^Iek2_AUp*; zNG7}IeXhuU{8ao{%Xmo5;2ib&$$|S%>EpeIqhGLM$ZFe11p6<7cW6UdGUMQ1gl6Yj z6c_3*&uN9Jp%_A%hGT!xW@8^d(-dy^i3?!%FU5~16t6mcUo6~)oe6yY8Qk#87UY#u_zfrzw%=HJM;kO$q!M~=iBS0 zhM|qm>qJJtU_%@Edw&5y)CwwsfQ${D3+KQmrZh_U=yXI45182wVGW0rDH#>RAdKSN z@oqD&SoHq@X2LeTQH&mw@UNp?DXqw9+u?KkM3JEJB=49ethD2ug3Ljrx*5OzKlc*E!H^K70Nq?30Y|3-LlRb0#>;v8Uq=Y z=7GZZ)oxqdv>kqoytHmpU$hkcX-cLL^ysr?0v`d(%EyYZk1!lv(N%lje3$Y?>v!5& ziF;pqUJ#1XKcD_Fbf2q8NuuZar$6w`ib>rou8qUxuMHN83d5&=p6BPqFhXv)8d2bf z>)6^e@xg|A=Hk>Jw2c@~w zwn5b`NK4F{#yN5oT}S~Dbk1g&Z}~9D7I#CcO}Lq9D9-OR;E|xzxEqU)Y!mO63Ygq9 z>!#e6=jrIhwhC?ma4F zO#voMp4&~(TXX9V{$|DO|HMH0fs3ckv=rp|D2QX+)i#u3=L7@%KY*E)$19uGFCJ~1 zt=8^uen~y>t0Q>&;PGcC+=GCHO>-OftewI9usyql2T%8h?=L+c>xF|u3P;Qq)CcSxG7%gd)>!IUrB zOd0F}uDQJVq|q93yQvW(TG@WQ;yXz%ZbOiji;fw~(mz7p%riZ#@3Ou0Xq=*be&9De zAD-fJy*hN@^)XQXL3_<1y*p0bbg9I&yo$@`-K{xxH{3ximM}``ijO>+j%7l@tgDmS z!0?NjF$P)K35`av(x1EBAy95lb2A2Z2h0HBAsCBEAZM}UKT8KcJ=uyLKPdZ;8^l$v zkj&GsicA6MNivP_*2;UDY;OHd!4*l8j_m*dyM*j|jO>6|jOI(;ocKRSe#*a0PHxd> z35tKBzWqVGXXg)s$4WEQYNl7P+xLr&;Lkv3WI5~eJ~#CO^S6o@(ba*|Mh`Qo_+`2J zD@@g?9&R68$ac^9AQIdX2_&xsZ?B4@{9r;j;0wY5Fx8OinVkN$s+KHKYjp&Eo5xE^ zMosOBAvZhvGlbCLG)0vr)Ag0rFG_KP z18|N``klz*FP4_RU2>&L2GT+qqF9o>N}JsT{dm#nSM#Pr+SnVlvWp6e>{DBRR%}XSt&XjuKVeIwZWsuFM!0RcbDS!pWaS7m%&H>^hi_ zS>?q4NVmu$Lwz3qma`j5J5HjAb zGEp7Q3PZf4b#bbp`b_tzKFLhjTa)AyV(Gv&-iPAHw_hQ z5lf4_OUwQyxVlXNvb)Sl3Tz8q^i{$t*&efdAn7(Z@mlmfl+E<@S*QD_BU1aX^T+ej z9IIaJuH)9W%dMA6)~Oo-U*zrfo9O`bAE%@*B7e}5)#hE`1D-Yc%u~6x4tU5>2Gst2 zn1y2xgxo8fx|zsF;WGirJ(0hyf4;)na{K?x_`FaNTAwZ1rT~_2B)WAkQTnW>2$Zv1 zTPr-81v2u|j@+I^C*`h|24Du~CktPA9N2O)=t8LZM|roxlYLhPp!`KAq^x?6=$U`> zXxTQWhra*O3=^MW(e(X-^R12E1FXG59 zTy#4Q%dhd}6|E9}kgNVwX3UfAEmq(R_|$Z5uB%iPLyX$Da_QuWCTGu3$9mNDB_zl~ z1MBZ6rJA>_LOmFu^0vO7HrcLB`gRw7UUk!%ja|z^PH|n4AfL>{c-eWa@RkZPeegDj z^-@Mt=E00`OaLsWZa|dn zI9Bb!521}GSA3IpM3Y0wg zBNNuyGbO$4y&PQqTK|yy)h6JnU9yA>>O57VdtZyaUPS$JrNU8i&(z>?>r=1n^3fVf zTV>*fcgY_v1z&F6g#>*0@htG|eVf_-qp`W)&7|PIWv&=yg+-U5as7SPJ>C06Egy1D zS-GAG=?jdz!5e5gsMSxOc0I4{SPy!mro@wenfW>T%kOq(R<8Rl=>ndezZ39)*{ce> z9qHU#PiLWmbLGuHKi;xBthtm4;M=`vAP#@xk?(%DH*Cs}CmsFBkhto+kiVEw$|hb3 ze+u^dr#2uOwsW~bb=zo4;s8v3mdQour89{9zDjPNXpaClLS&A@ll4f4$d=k;eJ5Y_ zi7C#AweP*@1$A>6GWV{56+YHTX@HgIKVnZ!ut=TG94)Zl3RG7t!X_8Y9t8GXBnZF4 z1XdE@FG|~J5f)*ieR9EUGGG}vj4hY&J_4jONjTggN&sO=QR_?V>=l^ltx}WEW1#)r zCq?oAMqJx>mJvq*Ae7;U>Iz_0+6f5&0Ev?vuB%vf0DyBemPr85lf{JNc`^j*cKIug z8b?-0qUy<{N*K~7*P@0q1a0A8Z$TwsdMCCgAGL5tZcLXC z#~?1p{^di&&4)g7c3QvuEfn|$mWTM2v zq`u*r?x>rb_b2VCMZz@wZU(FQH6LdV$1Z|+WeJ+CdLNf!{e)noka$MJ*u^RJ2sqFQ z04-_oP<1_Oo5M82q`bj{Ro|0I4hr9sBYbbGX?A$v2Dg6avi9zNV3 z&2?4Z=&B5k(md0B-;vQ#0E>Dt8Jm4W7&iGI@&-r6*pI4*TR@(i^uTgsRb?7O7_cN) zgiISl;a5Y|P0gNo1irI8;ilB2w!6|3Wy%sSyu#W1{C$R}q7_Yj5dg>q(B%S*+ERw& zl`?xqtPYCsJpe$EN~i|F$mBAGGk~KY0P`KFgy|q#p%$4t-+;f4TEv*VsXC{`r{W#V zbB`7a)1En!p<0=t<_#!&5L+G#2v3x8@<&()5i;V5vPr0;OypfWQC8WHC(1Y`RoG^+ zi8ss-#4&v#Itv@p!H+(Tgb36Z#tEm=&z`B>*6As%kWOSu#H$5>Z?x&cF_DhB@9YgD z!&Ad;u(1J^1o|{EXVO04hHkVfz_J+hg+^~Fpuu`yK1D&Vx;u`1CBY@P_Q%lpw{Mk= z&ntLApH-PYRb`G1D10us0;lQ0zJAhKPOKg_sT6_1TWde_bsGHD8$P(Bn!N)MIZL<| z`an`^ND`_C(yt`LC9!B3@>>}aE*so%f68fZqwr8&g`k1@LMpS|r{~O#xD<-AVz}gI zN+-kfL?R)6vLB^}v^|OlGUK(x-ZYRZ(@T#2a7xDFwD3lNr7L0ZA_0R;6^XtPotY%d zlQ_T%38(mnOFbU`A(8av4mXS%w?5l#KT(F5K*n7lz>+^!8lnHF(wHMuNxsJfnI%(= ziK^&}2x>9DoNaptdh^O%PGSy6jwi|}fguc#aE6E%K@)W#LqMgeE}5zSkO_+59#d+L z!Kg`9LHE_HVYELaLdBG14`;JWTO}4Ajv&-!sMhH*wHi0o*N+DvqqFughKj0O8`8g{ zDh{nOP4!J?92sKq_5JOH5r$B6)L4xXopT&>L-D+OT~0^8xqrvJ7f*rruX&B2c;y{B zuV3?SVhfMw=zVE(Iw|L$R+ryF&O09JM))#S+MByX&tr!el2-Fx5G-P77sGiLBjy-U z{7D9VjFC=@F;5m#P8sR-Yi^&>_E;7yOf#|#h_QtGnptGcMYL-?$}`6^XnxuY>BDq^ z>R;N7zGU@eXQE-`#=&4(y!ee>^F>keE*}AF;to;+VE788NL^W zK^Etn+atm4UmvoX^<*u^{s)z121OY4t&a5nVrCwnhV~fEk;N&!wPFoYZToA~PTSD) z7K_>;2m!?Ep6K0mZ>bahfdC#e2+z9Om<@NTN#Tg*J51(y)pz!SD*r>3A%ay2{WRg+-M0TmShsb3SI36k{I8tVu;p&&NgQ}D~T&n zS^MBy+6x7$kvWyO%kiTRr^*)j1eZm6vqX6vcFF7%>S6pV8Cok~5tKGxi~;|>xKM_+ zaNqFIphQ-0nn-`>YMCQqVht!~yF}}t7zQJ=qcUCrEAGrm(Aj4^wo6-yRilG3R>rCq zZIo7(A17{DHLY*bZYaKV0-QvJ1wrLkB878@t->DsCWzCij0zov*w;gJR|wdxE6wiZ zAErj#k8yHt6^4GAx}ljumSaVNh(%W-75bJ?A`X_VLTPY9zm-^jeiuIgp?&V`QI>P@ zs-5c=?&*Z+S*Eqvyb;wfjHbO+eg({vD=o>Z9nQ8x{}1NScuyv*hLWF%CTsgCE6?q7 zksrE6uE+~4fIm7+hQO)w8;0B|g>94b$(`~LR}EQGsTJFBL(HU^hPJTZ_o$iMd^olQiI7mLomlVfX>8|I!D1~WJ$)WViR z=$u~ma!2;U9D>Xo0Q-$lj}npEAPsjiVW$XKM3Ad{9NYS?@Kj|hZ0s=Bcn70^TCW{> zlu$ohZ?jV%zhA%kKVlife`1;6;>YYj56_A9_}+EUQLH--2(VtG{I^rM<(38ykAh<8 z`1b}&T#999`;vSAw^cSAp?4b^l6JPzH4?I z#|pF0g#eJiC&<`mt|yCu?(NAQAu)TAlUrexp!g-H#Gg*^OCLNgXVG}y>B;tFOv&^; zU!DQxKzK4dfIUf~y??I1JEh3-EK=mi194iU4 zM;vHhl)Urw>tcpIyAro)Ut>i0vg91Y`TX^GF^Njix6pPurABK?(X+aL-l+_c4^E(7 zxablaXMqZiJFry2r>9b@F*>=xAPX=+CNjWvU-bA$h0YFqFOy5T7>McG^3qfeKvS4!X#rI5iW(e}Cv?*0 z;HS$c1HgvgJyDcoh%li4H5z*Uz1M}T&l`ZP|M<`8pYtjuMI1XIHh2>1l^g5B&`z^m zyEgqx)h2=Xy>AuyC0pAuX*h)vA{@zjVc7O)&($#=Pn0#@qX$6O>mN_7DMAhdk1L66 zcd&!dtN2rYW5OqaqJfStV9G)93C773_n+Rn_&B%{5&`(IVyUs#Pwx;Si$W=QC@Tq+ z91l|)2<&68E)|1PTVYJ86nr`b3RjP;Y#$$IU#0lQqS&#LzJ!TSYaVQ0En}UyUhMzi zwF52AnPByMuD1D-gUen#$!sU^F^mK<03>&y)|0`tYZpb^Wm7RtEcBOt+kT;RFmN() z^2mex6<)XnnM@?`;Y#dt{94_~Wz9Q51s7=D=j8mw829Zzy$jHE<>2vp?_M^T;0m?z zLGMM@?=sClT=YbU+(=n~+K$Vm;FzViM8LKF0F67iwTSnSbZEppUSO6k=Yo{Jz^<Mo%kp9k0y(M8bc9s z%{zd~Yei-;L!wvmBpd1FAxvjp(a+h-Dc>K8s?rZ$9qt1$*)`K3;X6LPSu+y%CMrxC zyn7HoyIy%1Ow=uQ*`KU-kkrmlFlUCdo}Jhin=05`oqo{#_VNTQBQuO)@22(CP#76r z)qniO<|$6kMlXXnf=uoTXADh$Yok8?L32LZ)~S*sSj%FDf*a!3|DN7+%DmX0*}JSn z7mYnxgZ%9Q^@S0Y-Gu^xpvg!Df+Yw?Dx&x#!$XBBm^&S=%|I7DQ+34_+O96Z6AyN3 z)Kf0QyJWW{Av-Dq@g`w>Te)U28`H{e|K7x@Ln6L7-RkE#QDB<#*?NHsxgT#52s~&k*dnwH z34C_p^F3$+p_A^{y_s;B2ES*NcpF1nDlBiOq?&Ysw(}@JLXUbJ%JBT=)bI<(G+rq4 zeT=GHf9(cHbCA||7^^$iZ*2)RC0bNgJ&j$Ss7sSE z^3N#vOaBOEA1ai=!lSS<7A|E{#=<{K+wUbxd((6OeUR}T1q|sYq(5&K7F~c5yiDgA zJ9(|gBc|ul_T%Zxk9K=?KgJ6cmEn*m#TfbInZtH25zp;HVp9SsM%tk?&3vv-`D4M* zdSiG2CL;wIaVNHO-`4Gu->)w(J{3ym!85g`Te%*Z9^K7ipZUG>8V#2G8{|-e`g_(C zdE2l~{q6bREBcmhJ$KJH6df%UxynS1m`#Ud#5pCYzAGogZ+O(zIU(}Tvd`nPVl1>V zfS8bG!`U8*`X}VdTz4wUBkWt(>HLTm6LhnzR&@yz`Ma|v*XNjPd?aZqgASLd`h%~h4ukk z;)8%bj^6N88LTRNwuKkzfSaWAd>ngxz{Fgj7U^<6$oPx}OSud-($bja?joI4_$iP^ zeG}!$spw{$Ym%Y^0>JPn8HH_iYUFmd9w~>!$lG@AeN@mTU*K%h22eRmZrj_T53XtJslI4=EquFTg`;Md}_Wf z8RKaFR%%fD-&ulps}pr8db>v_eA`^3YxxxF{n)1FEAxsZ57(V9AIjS+`tpa0zWw#q zYaWa=JBgsLX$NX`>ZG#WfXSg>AX2wYFuBRL-isd5u%9(Q{+_kH`}bEA0~T5VQn&X( zl}^II#l#E)l^rgX+hckW%$B zp?e_sR}IpVFZ6!%ZziHelC^8Tv8)HZS8%RRdExn0)BZI{39Wa|64%BuH26cOS969B z$>xGFJ?~wjZ!5&oJ+{>{oK?9o?43f+*k9>n?I?|5@_uMsJA>;@E?9xp>iz_)nLwJ! z2Fk(#qhnK@`uL(mL{=|-alAgz`ukBXEhkmB*nJA+%Fn$j$Gvb__^+$lX0C;#!;wfNNm`-S}p!Q zZ8yoHgY$$Gq~i5|9-TL~L0ANl_+-VAHMKxWS<+2TNeY%nNRJ}R6m;s(KXj2K1q+NXF6nR5t1 z8^C&nV8@g^*>hAw@-sVEk?QNu?H4kZxRc_?*0P!llGw+V`yjU=3B%PZn!C4z)ZY!&6c+8UPfQ(B5q$FBsP9gN<#K}g z(jGogeHi%WGb`VV5F-Sce*$B_J|fXB7KQ3d)<>^^8c(1PDD)|pl3=Hj2*majYtF~*t2++_m56<(RS z?*tnR!>B}fvSHXD6y&EOTbp-^2gw))PZjW>06~V+Vt>l01)&LN(n=%u zW46UG|1PuA*oNx_A%Akd@&o3>*Mb5MCpbmS7R1TjxSD zp`fMI10*UjC1b0lM%`9e1&HPj5P^FA5w^J&v_ja*vOGK#l(i7-mLo3JFCjCyG|sIk z_F7M7T|>L{TX1xH2L&2eWaO`IQABG*=d^F1Xy#83k{Ogh1I@NfthVx@+3J=NCN|}B zHcSxOL>4)oC_=A3i$H7J`Z+tQt?SjOykbUF-IoRd$L|N@*5+j>rZIiCQm1AX<5C*| zy;~ktZbp(%JZQ|88g|Py(9yU&s?;dI%-+h8ZoLDk_FBChIm~06?yS1FG}G>>(l?h;j-bnE1-GWb=_Xfq8PV zM1+gcjj6IwWFQ;FlRLp}XA7$O2>pG|Eq`cOxMD%WWR8GWg_SZ&RsOP zanyFz%Rg6(6R&z-${!L@g<9Nw+017{r@mnaE>IfkD6=klhS!A!E!iq^C(s18IKH{k z_093va)@C2pmOEli!p(xa)Ouo0z4YKdfis@DiF1>a6ptmM6*?LwtdKV;+Gn89XF7R zOf+$+HjCYMutRlii{L%8@`PvZ6Atvx7B}_=Frr16bW{f)kur%516yE{T)h=7!tVwiy3+j?-4f~d5pwY=pisZ zVwGr|EfJfici_G^$ZL|fdceJUJ@ktK><*d~l|Op$iD_iGM6kl$Q!jIhQGEy-GWnU< z>v_88hk=S7&boP(?*>TxK?4cd1AG*}kUy0KH?DPZmfrn=E1M1?;mKZ)M3xM`QKPR=`L+GKB_iXh zyWg7Y*UQn+UxUzSbk0HeXrR}jhU3;eVw>~Bnp74wTtHkEvfDX$Le(%^eRTKwuqk5P zT?-r^9(8lhcxZn7{JUp$U3J|fQ5{-TSd5@5jY>Y!`Kq~kn|ydSrtZdASQ|aDks3uf z4js5B%0O9n{;%$9dfj?3elgk`DtCK1C8x6TmL(z!Xk88>sg5TlAl>!{5n`zpE>cG@QYWoB6y^ zvNvGlMk9Ge{VAu=-4@ZXr2v2S%Vy5^9gN7PW3f5skm=&Ku-RFY47`;t_c*? zZy!n_wJS#!3z6&xD#ZT#6a`LH3BoJJWf6VVP=+Xy^J8Z42{{S!x0NtsL%r(ap=68D z=0J2?JhC(XRHgFHMTuCW7bZUTjo;A^m;jz9Jsp``KbjKc~f*nLz>JTpKQe z3K8t3D)|q{ROrt&j?om>0d%52QCjt?F_2UA@ubzy@6(SJbsOK7OEmuO=elXWs}RAB z*p+$JqEYZhU(;94q(QY1^DdoPyO3F!c8~pQnc}g#Mr5W6-x7^N1i@XV|A2SW79$Ty z0}~Ea=0@E+k5wR;MWM*u=qLa>pek%vmiZ1}&95!zC$Dzy>b&gZQUGcFiBvv8S-zGq zzW>%tmy1VPLi>}|>58juY~zPB$+4o_U$5u-4IVcrR}RRtUywKk-Yu5|HatwZhMNRwv?%1%B~xv*IfE8$Dn=1Or%`!GP)@$@xXM?3dnT@~cc`_`!M zlC}#M_g=YjDX2<4NKi(q***RA^o4)W`yri%X|sm`M3>-fIZ<|&v}m16aM$H?z5^i9 z(-KP+{?a&Qp+hdX_lwv-htGkLx06II6sECgO6Kxduzz#DU+UEpleggr+pDf;mocwS zUwq^Vp{{jU-&ART66~K!FU`$Ra4QoD_KUX;+@250k@ecG2HnMh_#hWt=pTt-qJ*}S zpqw^UwdUXlk&Yi*zV9VRzHf7TCAH4f@q&=QY$TE!C0oGPpJ~z&^))E>>kg((g3NSq zBLc0UJW;rQl}a6a#5u(6i#N>F#E1IRd@4jriO3pd3)T+{E{zHowvuN2UOp8Bc4rCb zovTgq$N6?XGLddJ_aPb&XTf8si6AAK{=9ci5cH`s5(S)XdrcS!Mt4T)*-PkCKcbA` z$Ehijf_0yW`>|iX61_l4w8S~PX$EoTZeP8j??AT?a<*LSX<%eZIehr*E&mI zNvbfKHar}VpX{f)!mFvbt2eEeWug**4S>dwgq93{XYp0j&);3|8PVJ*j&I8AMHwc*e}?q z);HKK{tQriUqK}RnE5B1Cgft`Rh8akCfVop)uuzLk%bT^hE;kzVD@hn4AQ`W!hr*9 z(hO^w{|{gm7VgC`78|chI*9BH6-z%-CLK_j#IU1*-?u{tKmQ-P3_ZpEcOkN8`m@rZ zbkE@rrCD9Tdo_$#9YD&vKRvGJi2C-B`Sx@>%+o9nji<{j^S3_AT97jQ&9?3e8Ddu%M)fPQ?H9GikSO7> z&x=>qawq^?Ce=;_518?q%A^8Wp(Gp{nb<}SFw^|CWWJ0c5xWAbR7@=c9x#jG(l7sp zHFna)3TaPVNpo@3`CZPFMXsmw8BpG$&uQc`U5(N`{_zOgWxAPE7!+${b)Me3OlGo= zB>r}BOC$s2d>faYzEemLE$-4+C}(tN73Z}q;t4A@RW^aBHm?k7#+tPIQU49O6yLLH6GcnN=vaVCp$ zb^}#81gTOx3^gh$xt}f|{XC9);?NBXd>))5M86)ka_?Zf5S=zXiXi`Fq$2HK&ESh&V zl7PUPpmw?_a8q(2LgMh}tT7q2ePL+~hxr$$=S;0treFSKby>2L;OdP*#TN*wa{!f+ zR~qE9$u@W_;KRL_PUeCVSK5NqPgawjmINe4WSjZD&yuSCQvcz0)%e?_DfRsjvAL%! zJDDTB=)&*W-?XX#5$Rh3QV zblXJ%y+WIrz1jSP7F_^4N$;MQ=5DW^*mMqNTGT(@ucdcaDfpm(v-UCG4y^L{I3OZ$ z5?y;(K@$!K%Z#^vF)uJ|oAW5dwKp6*KaSx2t(W>y_6Lpo;6HMD`_bsVl2;zCs1PmS zr#D>2BMZqk7wP2+g7j)rj1BJBM#Ba7oF&-m7Zp89RGp z&MOcyi&O%N$Gs4v{Qmd5`Mco*X5-p^T7CcOc(6PsIWRS2a{~ zL}{N9iOUW^sfnkv0iLTy2)}WvhWjck8t4}r>-H41z6qZbi?L2OpDFp$hwdbkCkSx# z35*2fg7sY~+Kkue)MMYzKAL=NF5t+t$MJ?aH!byCyfo*I*e|S})u_||3uO++Dgl6i6EC#tO)<-{)!Pdt*W9%iQBmSki`QTR?HcywB zD}r%iZ^Kw{m?l}WL0dl#2jC+2+)Av3^{`BcM|;k$4vc>2K!rHdhS6**3*Y^u=x~=4 zB3voQ1(GlsItvHo!PyUXB%?ZqaQ=Dx>TiQT{`hSYB0OnhEJJLV1`>Q_C{}U4BTLJT zZxAqree&SUYYnz-E_z!yBUKC%vjE@-ngE)LW0bcf%H{S9$G)-1Q5Zn_3dH(zF@^&s zj`dl5&FpW1MV)SpzkscSxqj_AHa?qad0^_agXXoQG^RJ@FXf~pWe|3gn`!5ys<@{e zDbwC$!gb(4t`r28K@(soT3*ws@(+kipQh?z9mtgM9#}0g=Kl?~5^<@G=Gsv9IZc*c zCad%q35|-v8uU0*8cT6zVD_9xWig zN){=uuMsXGSKVISP@*Jbt(Qb?#T!N>?|f2;ee25!={iW+EMaf`Rl?qloKh(cqoL@MA}o;NKXaK@f%%KQRv@BvR`Wf04PkNeG~;C!SMYYCo)Bqw3O@& zu#EyKtbq82ZYOW!Fbo;ZL@Lzz3+h#GQ9?Ju+PXZ!e|?8kzqu2_NV}%3oTaGtt!Us3 z;Y%8ZkDb+16CF0Z5LqZqep&Z9&u{&&IOl7NWu zCZW4ddBnko!H}s<|Kd4rTCci3vHW+g@&vtKwqht8;HL%@{cOz$RZ8zuaz+4Z;x#si z^r|H$#KHkq&?gi?uOMa=vPIQZfBDhI|2Sm*_{%*;m7s5NsV?SeD+I@~+NA%CqY8vx z`-L~SMBSvQfB@w0k$XrG3}DUO!vJQ)U&UNa8f}%|Jnih0OXnn~?<+hQ_rH7tuiJ5E zj;5x#9UxIHA0^x&u-P%v*e#`;RtFWmH09+Vamls~?EhMD{7a|nK`~1fwcQW}F^3iF z_{C$KE?cM?A@k;)TPL!>P)n=OUn?r2B?I(MTY6umjh4cQW2iQYGfL&vk+<24?6YS% z_piDyrJpHm9^J)}{XN#^{5kl#bxXrCM0qR*PIu!Pk=D@j`IYkTorFghEei_Ln{z#% z0gcr5I{gUiEbkBIz{`OTfpD`=E9(K;P}@AZJ@4du{j0cpD?K{ zVc6~WhSvEBNHN)Ecjdp6DA*W>z-YLEh%dBbLhPTYzfL0`w2_$HVSCI2%y?2LW4O3Q z@ycRShXFyar1r@bzn91fuK8Rdge-thfXN~NpTHC)6~!^BTM>q^gcG;q6YcpGwr5o% zg-9}CUQmbg)ygr6?wZ+kI3Wq=kte}Lx#7jx2~Ww%ihtu!Vxy^u9sXmfAKW9GffHXE z65lrR)HWjI9Kuc-DU;kN|2C5RnovIy7E!QcPj_H(g;J`YsxPMUd8fv8A~_B5_a;*j zSPd#ZFI%P-`W6bhn%$s7kmBo<9 zG%=Q?G13wx>P3#EVU=%crcXVr-j! zY`ase4H)wICbnOGY<~ekQE<=N5v9r#~v zYAfIbw?C)ul+QP~cu^B+I*vc-j6Y3WAj@AMuUR0)m~;n4TIesB=TBVSznE-H(iu%s z+DGhgM&)As!_`m7B=z63Ga<<;7BOCac1QlIGvQTnkqm%fnX$+ZD%acmVxmOjJ1&(( zC4G0CntACBk%TkM<5a?w)bw7d!mNYBhi76Ok40XKix-F!<5xs3nyq{Lh|*U?--$C1 zPLmL2@RCvUQU8>%jN-H(6cczOS&=ScVW{$lt_0-H%N*gpoAhR4MTT#N=kQ!ICQrP(jn3cND4A%-20q;_dWMK z_x^F`nP>iL>8HF|RCBIODvrt`o6pIe4GMx} z@}8$e!%0X%3x+8sI!7E*q75`$P16Al+ChV;)|B%F{^cXf8da)JRq`A0lypd18&yA^ zs&)&g^}DJKe^wnvL5K3xzEG(3_mOv^SwA7wyBkTWQJ~snQ?A-1L;2 z^wiJvv>)s1yXhM>=|4+>0_(1~Xx45d+zcBBeQe<7X5iUm;Cp5e@Yqn(jf~+;?2C?0 zf}6D8DH5XwFq9S{0*Ze~?YW>=rJT?8JdJvREA!ujV5GTGt|Tu*{*Lta~eUq6{& zy@c@(pnjUjVND?*4mM{ z?aOndJ>|9Ixt;Gra~B-?pX+qa-Gno^|HBO=y$76B_ z(t3_3=OG)-J&{dLx)-j;g3dgJZqM8~ELu2n(BhX!gs}j(m{26ixnsa@(uO3btH&N8 zckLtQ_@gg8lK4H-PKc~*ufK4E2Tuy_XEQ-rf7mfVtg( zeVEecP{$_;0dZ!5HA?r^=0iTuIXboY+Md54zpF^jOohk?53JoCVq#XdQoJx=zHWJl z!Q4e{>Y!rki8}L4egcq0RESD9_gosDi-9XsE20L*WVXiWQ6ewg8svW*MEfXMVgBty zch2`H&rfSai6~;;0y5L|0ExR!w(|jutq+(su+CS5>%5a^x}tBoO@MGXR||Iu0&;*Y zaSFZAb#_@l3GoyP{i67~?7~+!2z>e)7ycjG*NJ=7l?SqYp1136bpKqiKOSu1t4RKD zzHh=f#fI)B7ZI=K-9uiJ!(}N4ES`rbM_p4%V?20qMZ%NZiSr_4_2=1*8fktsM7+J5 zxJ6~j^6h?pOf1=0EGaYPSO6i)J?XkN31>4&f$Cio0Aufid=@4`L-_A{x?>iFU1y16 zH-&}Cu-q38Jqm5;mJ#PE!tFziN@xzh=z*$Sv6C4F-1!z!JeNUB6}j~^$M<5!YMp*z zZPUX!=pmOaFm!w5H4hYOUsxf&Y5g;&ml=_F!W}jk!SPbmVe*~JERmzhhx|_I;PVU1tPX3*b<)c?Ua(R(On+5cmNi3c-VZZ& zDOVS*TNe$C*mb{{uVb96e*dCgTMsgFsV$hvsXOyng0{3KvwZQ7m-2N!(_*8yM@w(2 z+b61MLXYHQ06v7|&RVnNZD{!Bl~L86Y17ecpYG~;-RRq4{>B8UCngfrYGUVguRooW zRz_Q=t(H%qagO@qtVzClLwgNnQ_hPHlZN^WToS$X;3$NzrAzbjpO`}0_K*dK+XmRxQG?o)4h6|&Eb6WFbfH}5h3ASWLNg+tdJp&T&jIbJJ9butejMbe={s3I1=+> zWbjgrffW*Y#SxUv@kK?%z;sMRU^pfF<2KFsU;Xi@!10Pih$%m;8K}+BL6w;|94-yP z#K+D$$A;-vGqZDTmnOZhXU4auaiph`bUyfhuP@U@duKe0c}J2oB2p_|2Y z_P#mp<>K#KY#>U_gdMCk!Yys z-$faorI5gJ>xKGH$k7nt&J-Qu>cog|^kX@+lTq|5o6GaGiz`wTtKKh0?wZbd{31>Y?fV}kztj31{A&9Si}`9m zzBTBPta|go#B3)fadh(I^!n{kis!M2#7|bL?PJMbIV-f9x$KO;i9Bw$OOO_r=7}b= zADE7Qx#y>kd@5L;i;tSI`m~MIEUi}M9wntuOGzEmzCV6udK?8k(UjuTm132ohAiDc z*Tidhx<0GF+uzUqdDm~ZTT;5u@8V)uZ)q;7!|Zr7pm4SWiUO8UZ>;^?dqRyGLeJE86q^ z_o3%xCim^Xu9I_nU+%1*$k*6~JJX8pDUJ`@wfew#CSE_f?~vHyC-DPV%Ey-FI^LpE=a7a%^Tt z6gPp6&9@;{)R}wR!+s85KBPNzVDN>g0~0w~kv@+}=k#ed99^=>I>y#}Y1gni7vbS& zW_hxXB9}z)?wXD~(Uzz(@^9g9lyt834 zPgFiFnYuH7IvbKmP1cGCN-)ZxN)5GbD-IHn3I9U4hSnZ)Vj*>o!v*rDsQ|^B-~XI0 zavY@!pa11_J?8AU%nO97*yO8UfvMtu45z^0q^I)aaQwrb;*9%}p{NuyDVeDV|&(F}dlu3LuAP{r<#F6-cKf0$#e&$Mh< zTb{wxCOyH>xF@yX-EiGR9H3# zaFFjPTnQ8TektzymoAMbC^q9~e4EfAVz{#&a&d4zssC?DZ7k;Bl3MKIZT{XV$PDuy z1)ziX8$*FBUEOj1$G#Rxdd=2vSu^3aPnC9<#9xQf14NfRA1AMCxSOmp(WcYwUxpvGwWcaf`ID^6?PO+|)h4jC|2gL{K$gFn?88P4?X=3Mi-^QLh z!nIEbP}bDNjcZg5#a{v&+be5vM zU}~jW%Q%-M=)E9dP@TIT_)cjq|;r!m<*Lpq{9wKlLQyGzE{>krue;JA&7 zZbl#)#88w!_zy5!v>FijL^R5~2ZL5av@#Dr_POU}XT60y5XBXc;jX{VJX5>d?k znKwKrBy}ET+?Rfy(7GhNXDmc2(jXczGd{_iQaMKA>2NGyMiH_jOFt42ZHI9!q&qBC zlvr?u&sKmLLFn|Fp4cwbpHb9U!` z8qW=>eASA7GqQ-AX4wBS^;L-a+{=>sdEA_mx)&7(R#?D{HshQA^xp2=eSooY&xH+KFI)3M8D_9_W`hxhJFJFEt64IgKmtjWy`WnEnmm0y;r%G&Q-YFHzh254^7O9e;9n){>YZXeVSeB?}4@moW60$Gvuc%itg;O(zJ(BVk#3pMf2sSJI^Fn zHx~26?5f#&&1U~>ERiDJ(~9!?T*Tc}rWv!RSK;-gBGfhZFXwkAp+9dWVw>K+RJR{! zU3h^HcX>Z|lkyzWG11M?T(@a@V97;0FK5);Fq?hw>XRoy_GWbK8{d6}q?WJsU*BmH zzu8gjHRx+)a&OB~V|N+6JE%d@=<@OJ8&lP^MZ!dPul1PcJaM$kK{^-h-D7WMuCla# z67Y2CdK{6=iY?9$RJN{)9gWDFZs5Q^_p!M+G29VXJ@0bweU{~zjiSBB!q(>H{&$h+ z^$T2TU6E0fF6Z=5H!rwLN=R=LLTMjt5IoxX?||7P#%;o-kjr;hjZt(a3wl<1_wTMw zP5YNu(q|R+zPm=N?Q=O@ziXoC50q=XXl}`P?^pO9zE&LmW<+|?I_mq=wWeeFSL{XS zKK)Nyn~qgXwH1C*H^H-eJ@c?%zk68xjw7Gn%+vnzsFRaCF?lb(RpW3qY9jGly+wxR zGv4J?lw>zGn@K;Z?w{-;v$K*p!+rl@htW#E)5e;Q>aR4(m$q-uo=tyz>GA%~YKQz~ zFJaeVT-?np;(403z^#7jvRJR$ z-n(*C5s-;v7NjUr2^_ z$kWSUa4OLOl2C{jd<=g8iYFP2Cy?cZd_TfLc7tC#f?lmbws=LDrXio;{>X07?=@n1 zX`(-H!i2hzXO|%s!lBk4p|)Va9*dJvg{5MzXRd)%c?ppg%&%fMeJ{ z<;)|Znkqa?I6T)T94Qke1;$3_AaABXVbZW<^Z#(t(tW;_#w?a1K1oBE>LA!^jm!~D zL0W9zJYwz`CJ9F*X_0g?`~R2rm9QSO#vc3KCKjuG?Svy#Yh#CGV2&t+iw+y$$d;H8 zha`*LG>qL&kF61ie;p|C7QqI#W&4#xMM?y~hT{;_2unvOA3EBp7G}oEcBIAj&pF$n zVjxN++l>Q=f?0>7|C9RSCPJJK#mI0Z52X=p!m;}e3HEAv-}b~JEuhW32*xAg^>|FY z0tzaqrE=^+a$W#FS_^v;k*uFl9B`X0>9snqOfPNr+@1yN3vohJvla3GH}ER<+pl zba@HMsi%#yMu&m6wycj=S>40wHybFt~MV9`whJFSkGSCT~EP7b)`(}rOZsY38H1p+L*HO%SU@?W+x)Rg_=5lp)}6896*+_ zCzNOEzR3lNRufm`jg%^>RA7CwTDVAD!$09G*)}8nTN!dXBbKS6N2R>at}?a|hKaA# zFNA&sBeIC9-irzfNkguMxYDNi7&leY0*FT7*#8KKtRq9e1y4HD|4NdgXoW9*lgJ8p z;*&r~;vFqmuU0?;S?$=+zh>cY6trbZ?&p{PK+6CqI}V<@@q<&8za&~BQcK~@W-Sjj z^&RgzYB2;YS2Qyp4g(~CAcBr=R1&!^nHW%y45*_Stup~NZ2k7#ZIJvqB^f75B?1A& zI_l|YK}(i+7%d`k00Xdp6AS~x9vIY15hX+|(@_ML5u*sC{jYjzv?q1CVRSMXVF3~>;z{&N znoxBOvW^moJ#I}H)nvw2B9VA@c_a%*X3dV!XYAkuG;!m10tsot&Adzr6wxblko_9u z5Y-|?6X!lpEC-KHuxKx>Xs_IFuZ1A$RXduaI*`+lm0E%)YmgN!=3PKuRv;mWtWzky zy#fLRO|{q1b~KoDv@8k=2FqbRvNFSua(JC36(4&SKd#z$vUf+f7}7h{LO%|5bVXre zViP_ts&=krA;xU*_8lRQC_wrhpFUMcrNN=8-MY6n*wG;_22Iexbl*y+CKVfgMKSPm z#HMvegHX^^WW+fjnrxAebb4nS_6!L?zN38$;^R}yp_kH70TKk3fZW4UUnt0lD8fj@ ze^Dza5vP}*4k}6l2uAm+jbTl)KG_4g#x>|68uAEVRWhWHPrUcBPp?RJyf&6JqeGPU zsqDA+BWF~7vuN>{133WJiDukuy<}(OmPLI8QK|*^##f42(qG7XXr8Oj@ zV<(^^^l&JXnnAKcE0*|L>uzP@In@zJ|F1|bP?Ub0m(d+dJAD`c&*Ot{iHLC}zr%1lpqYCW=HlCYrX+9BQ3K9UW8^&mxj81KkkE z@@cfQqUDz)K%waf;5agSQ$m7R?1!)C;{5 zD@oLCQ=`BU@o_fwvx@puz8+Q|Ob>@RwaD=?%4tho ze*}GlLX)=BcKcBOR{=LKni>Q7lyr<^$%{qKh%Di}X=_ldWcLx(mY6W-y*wv~2D;3l zmMAo;@=Le(hq{9n8miL#g6gCkB5t&NSC@FF7>J}VF9zjn5E&WrP1-F@x!G_(&g!g z%d_gsU*0Uw#VmiTT3#GqUOrr2C0!Y=8d+Cg*?NNoIfzoI5q$8FZ7g6$x*C|ca;(03 z_Ga~|HjrM6@m=BtGfjWMLSNyi?7%hB3ts4baYV{PzRQcCe0lJo7HkBLXN&EZ0wf-z z;MHT&Zm(7BaAo_j)G-TuK1I+K4y!`qg#i91?gZC)L^APUUM|F4tn## zej^yE4aOW1EMG~kOV4HGeOAK)X57mJEHEc-*k!yzCvw6?D{LW;h)IU<(s8zAb_+xd zMOF zfV2QVIe-oz!56W|)QsOU%%L>Djv1dXC&v>^UqZ31Tei59vA@JS=CHLqBL4IfzM5qm zoc{~^as@Pj3(zr67zTU0y~W)Ay~RHMz4`n1FXrY7bA9^XrLVtO-s|e>@8vn>@(^o$ zU0ht;{s;VpIXlCgp8h>MyE;9+Jvq5NIl-K6o}ZupKbWtd|7YfFdkM4M`Sa(`gM)+J z-QDf&?X9h?&CSi*_4TcdjrH~Q)zww3@pbcM7PIso^EK-K)A+*7%v@pb)6;*ZCa)(Z z{!H{>hKH}P_rbwG!{#W4h{|o2=Mp!_w)0^N?%@HUjK=Dxw*MHJ3Bi%I=+4T7K?h>+1b5% z^~%!H(%jtq`Sa&yW@aWPCPqd^r+WG~+G4+zRc;g?{F0Wrl6ZJ3#E;=d{@~`lU}M0V zU58Bn%q|Sgo$oYs7)tmpoCE_Q#DEDcb#!!fb+xs%H8nNW)YO!fl@%2gpFDXYFE1}E zD=RH6EhQx-At50uD*B%kn1Fx)KR^F}0bg8PTpS!6SmW#d{rms_nJ)|h9tIZ&0|46~ z(0`I&`2TnE3;5r#FI?0yY#@18HGc@h>djD z7ptanJ|D@x;=ezhB}}+5Hmv(&B3If%_WLmW$yA}zb1cdA|B8JXRVX`A#waKBhk_k9 z|0nkKPNZ=S)q=&ooP=t@C(K(@jp6>xPs%;`rUqg?Wn;5l>PHKbA6?*0!-M}j_9YXH z^8=!=H&<&pnycQ?e7M-^vcEFk(PA_HU`|#Z9*pmpjju!@eCx~`7?_#?dB*Yg<>?-{ z#!^Vl*L%Fzj@Apq$P@nve3Aj#!KEblc>N#Pm%r&{AXr9l>TbG^=MAZhJV5Vpjgyz- zO_-Rr<^kbXLaL|VQOfW{5U>*QX6u!%htj>S zh-{T@=+RTMI|b2#3;7wFGC`5jq^+nK={LA%FFoy<@3G0c5ua|qC`_c;@h<+5g8iv+ z3X~Rts4*%Zh`IoBP-W|na(lOUFE(4*jPpiY)%Oe(Fgb0 zcf{2?Kz3R_|fuTJ5Ur)lS;}|C}hSs#eeasRmGgHbxC7?g4JRtRm zLa$QBs^#J8H{m*sr2R+T4A+a0XKnjSFC1`5SiLTOiWT~hbKe~K)8@iABHz=(fZ>4p zap@X5kTe|zZ7Css-G_@lOKxx(k}e5`0=VOymLx1(eIg}w3Y^N+uj)XZHt@ud9FLC_O4 zK5%3X0oEjrA~cz800qIB1Q1DJx$nCf#_}JEQl$OAkZpN`_g=K-v!2CiV?fy0`PbQ8 z5Y2Ho9r4|FnF+)J_h8Q`8rP&Hw}SkO0$6jdmxu@hQO@SLK&8?EWbz&-&C4I5+%lW4 z-*tn$<_n3$8<{Y#ODd3o5eO>T0)`7=M%JfccfRD|KpdM}i3EQI_6On%6C?yZvSEf2 zaP)~&tb??))O`VAIkpjAknHzOQeY=o*bf~@QLGWmpKZaJV*R8@uZN*?=s9fLhQi^S zld9N>Lfqxhs2O%w!OU^D!1v=g=R5q7;ijv&(l}7x^i8T~!b)tPkD&(fvOY3~PehNV zNfp6G_*>V6y#&r9#AQw~KVDmF;lfG04|rpDO<9|E(ko0HhAGWXiX|_UG1TTgY=%1= zCBYMA@W7XfInthi5<3aFMg@uNr;T5wCW5$>06EH=vC=2qU*IWpT#^85oHWF0Drh9> z#c^4Pgk3;^QLdgP+19+gi#4wKyj`L2cv%V^ZbICxuE_mB3+m@~g2AF6ik1Rk1UnXS zQjMqiB3J7L2W_lI00<#EUj9_`>vS%$z9bX{dso-UdGn^$gQj0f0ihWO)Lc-7Y7 z%gl_`gLnKL?UNY(f#wXJC_)p=Qy><@XLb0?RZ7VL*@LwoJT=aewYt|Nf9W zxL<#VY-P@ckJC@O6q7%@biAm#*Z)R!$2`tLpt0ll%i)XR&+`x0`Q)}qYk$o^vcFpp zmn!|)^IjLxx>BiZm(k`>ZP{NV9BeZA+do5Q7=(l4P4yP<9mxhKD?jlcLdiq@VpZ~v z97L-&@%?9YwqYidM?H4H<;_f(`%M*`hro%@h{r`II*-_rr012ui440%oH-Tjlhv1B z?g2KIhDH>H;u9y;KG~^GkNeZNRp#0k&Z<4eE6grN(q!aiNCVA#G33%r{9FmyR-&Mh z2_YhY=fEN&_(6I%Jo7}a;-Hjjp2FW)qp`3xn*u&H_A*#}Zo=!lA&<1m##}ygCjBX# z>Bf=}_gDb7QEAR$mCXlQe7 z*x~*v1D>bIb>k+IO=QFf>HWR=$RsobT1klMyL?^bZ3=K%P+mX72_Cgu;W>m zl*)>v1Qdx+ZOa}>p9E;#W1%Nf4th{Pw|8mQtV(||DE?P0rRC_|3#2h`-lNtP^%gaS zE-r$~L5QEGZwOTmg$06qEVRa)U!h;^mF#ciJv3nho7AzCF5Rx;>I9eP@pr1lzx;tO zE2}I*2GvV%uTCxgItBY=H#h8@*!JCS7t5jEb-x8W@J#i0p{#aJkPex76|?3$#5Oy@xKZA+mO3`Hwfr>Vbi6BOCubV z*&UEOl%_z(yniPS&faFn9>>z-RCT3F7ox=9DA?NA9)Q41?ki?Y*qU3im$ z>Ac?=$_)isC;Hsz`_-QCMa~3Ug;U5EFy7k;_=SV~C=}@C9^z;~U-c9wgz}X4aDQmX ze~*wvP%G4Lp8Q;fZXh9)?VMr4!WA+UviKozBNc)@R}YKyfInfsuOxi`Tm3`-^a#Wd zW&bfH>Nq0L@UB<)-F(AHeh^DDFukggUmr%rt#l4@m?`qDGihC21xRf_Gm zREMk7mu;zzB5AG>sm?}e9vNv6$26~RX%53_ei^BxQyQt#X(;OSaOKo6ku(9vMDxT% zOJ^qFYqH-Q{t+5>h^_LNgRi9FU!;i%^LaJuz%E*uA3QTlGcwEDGAqAjR$pb-QfJkR zWHlOPHG5{YW@NRuWp!p`Wz}j0PG$9oWVf|}W7}BcIqtVLswR87k)lD?yu^D*yzJeK zJkJ!Pwv?!h^oX{crHJ&Es~lepb?!!4+IOQ|H_zONZ>XjzAapln=PGBSGKRc4WSxH`NNk(;xNr^TfK1px6Idfj zsjl(~+e2tM0%bUhuG6T!zrNxWEfUE{z8_@IPyDtL4!w$pj>i{nl@cGoVS|9Iv`PW% zND=4#57K;Lj*UeuqJDGpVuzH){x*!}#8Sw}@QCye3De;)rI>e|0UE~qarh(&TOX{! zC03%Zoa~-?M^X_3QCyhIypQuGtPRG2qNRt1rBNQGUi>BKEh<$Z64`mt%=R*$OgIk! z+2@6Q(;|r5EogH#1qqa?E0snVmne!>&?!^9DEf2#dBz2YRyh)gtP$jeW>-dXeIO*+ z!mkiuuV`ARY}~7?*r8(D^^9q+I2R$F&hsJv^KiVRa@4r2*{fomvtVjZrB>eIi(MJ7 z_4`Ff;(>VR92)$vy=tZ2qHD@xB{N`*#%FIYA$^1`r(c6Ut$NcgQRavm{!hJv6-X0A z^TNVw%TE^`VoEHpXi(RGDsPOdH%98FTD2||Y8mVkHI9k!^I=lNKpE;ypJ*LLWWe1H zKWf@4{KcSHj8|DKlSQgQkphP`;XXByDtrS?44MXSA?xt*g2E{qri2>k#p(sGYutZO zF{1TcYa4{PB3AD}zH!1!;_GD-v!e@w)hhfnRI9b@OLe^UvK|wu54dj_G{i;1U)I8M z(4bH_EELs#b4nrc1{|Se*kkPukQJQtD-tdOhkbzK#iC)~!{PfK?1V(0 zjw{+PRU0ZgdN@h2IF_MtcxP}$(`XhY{Tk^TzzVdkj9rFf?a2D<2v#TvzFuQ=UW1Xz z5HIk;>uO1e`Feuu6WgZ}?~}YeF=?&rXnVBOt~`zBP=rUd{b}%+xC8)1AHbvXpt$Qe zdq>y}m`h`_Lg=5~vLgGnrod+Hup;;_&xg*lQQ?Mm1QQUlj9W)GsB+c0%&E$nU9>Hvc;fA}^ zBurfY0{Be1g$h_jXA+T zIxLTodyTYMn!pwy9Y-O`$4076;RW9)8gCwsdXBcIj+%Cky8USHrlruU)w&ez_(&3< zL_`;G1iP7<#H_(?j_4SWq~nhFqfpS>Y2a8(AYY3V)D0IN9t0f^&U1_gEDL}77eec4n9sa;K>rCBcQ&3>%={7e z5uG#&Ru0FL1t5o7RBzT`xlqh40KD(sq}y3t9#x833v*)U zbG_a(7JCywloidChQ8vM*54@(`g>Yq>~HKA7(y2+Bo@m)HdoxAEa;z$uUr^ds`olA z2`FF08CX24SePVTTBW4Gnu#s&rGC>zY3Idg=CU!&@)G+}568{)CjE?r6Nt{eX*TD} zpSpZk zh4OJj^od@3PZD@pc(y7od#!=1lP+^s>CINR4iWlmPvm*m2db8(dX}RD@pekqs})u| zNtTfe8zg?@Ga`Ye4HT_ zYap|-z|XKLXSO6_0r=Kxja{v(#coIzY(y6{>gF2gJA7BD-n8%fF5mF9 z9;Cr<<^97X<%i4dy6nmib4l!L!B;!Od)l>Gh?!IMtJpT~-*)I)GbGuKP$TD@+Uf*a ze7Sc8)Y=K<+oE&zV;OcbS0+e*u0P_#KNJ|V)7Z}TlTN$b^-5X${&0m@V>96=f@W&# zOnNE9VgI+@_U}E_4#+<3ojrN8y+<1R4HF10EkjF>9bjdT;2us>J$|3rLA}GuQ0x}U z?|{bw@IX6--fma=t$)<(nakB4sNPzh__?U@lg9~^8oOKJu&U0`tf|3|b6URJrMb_& z=m$Og#eKw020R58ht2lCDw(>Q@yqok|E<=32nnz}^lf{Q8thx)YS zhB^-CXw1GroILf!U&DHm2qfN%JdzE#2!I37aNWh10i@Hlm;fq_`GfQZ^L6?E#J=DK zebMw1etNBB-<1+66jJ4lPOMZ?=?#pdXG(G(*4HDVR4nGy}{%R%P#4wBNfhtLrFtu83 zR`-}I(CmB_L32o(ZjJK{-2;A-ZFu}*fYS4Zwq8F+^i83#Rxlvz67Me{JhomdeQGmP ztp5H{g0GelJ$4t*{VbCORKaMj^8 zK^?QGaMkqjm*@=*=NCY4JvR$#=Ib?hI>+=N;{wCk6Ay5zZQ>coCv=iD1eG_qMq~3n zCp}O?B@}DQ5YoG%^e`j4-OK{FWO8a@dnAws`53A%6vN z#(~U>af=9vuZ7~43Sj-$35obrO3nB}OXwAE9c0>}QluuJVW9$z|V^xse+XG^Bgz*(m2 z`fG>LkkAyH0k#FaboD2S5^gO4%{M0_Y$bF*Y+>e8xn3{UI^C?LU}C3rx-COd4b(uF zN3%g3%{%PZD9ba%aq4Dv-ddCB)IfnJ7uD0n+vWWs0b}f5COR2$bJE{(p#eJZ5L{SF zDWPWF*X{4}P*J;(#H4n|(cYFZIxqm_xJ7MK1r9r^?=ckoQo3JY9zC=8xTiwhA;-T^ z#MxQD@suPm!EivMua@vaGE`<*zs7y;njW7_i;72UDrCKW4GbFUCY5}H5-n5(xP|4! zbK?Ctip+P}k7bz$I75GJt}iAIiN@lgiGAS%PJdeDYc6X8q_fxVPNX(7zjM-3%+4jX zXMY0S8)XpBDj@J?7p^072qa-wqwEw`ln8M0w9{i|$OwnOvaN!yvsmb(2cE39IR(lV zSu$5y4PM4L#d)bQ0D@ogo(r?a#8xshY1=6M%}~D!(z0Tg>l?yYAma7Jw$wetuiKM`_N*lFdXYJ>l6cM}Px_6#NjJu}_BvD@VJ;uAE zy_Q2l)tY3hQ!G2X>?RN(OuG3(0IuT=@70%JwS)!bQNyLpncjzoiJ-}%s2e|Lkso|* zNpAmI#M|^<x|1h(P5AOmL3Bj|mJX2GXy z7>6@P1C?K9HX6aDdNm1AiuD~EdgIYGmVaLa5_dFp$9x4)C!=|--P^(GdIUBZv)jDG7_kDU*N-~fk| zV%vsOYy3{fW0VtecbMpe$7?~ju_N}s;7kceBbm8W(8Jk($A z+#emLu`U}{Mmbtuyky7uX<^)^7*Qqh#-8fe(bo+H5~l+T7^{u^e1OL9t8j@Oty^2M zk(Y-hP4s))f*qVr)0wBJXQ}pQ|=TM(Eg@U}5J3bY%37H2E06rW&xI2QiFz3AI*8h7b8%)PBSSTE+miu7rp@* z5ZjW0X_&qL4jVT##g%=oF}q3d@n!2}^E1zz+RqKa!?2V{xr=pukO@Pnb_4@Bc3K3n z^MIWP{v%aJOBvsRSGA)49m0p z80;ZIxn6!Y%KDZ|hWuV;i7D$sElfs42_!1oj%Cj%JK{H zE+s1=^`$;{mZ-+4-q-UuCJ9I+nou9B$D=~tdEfx-fPFXtKYI}Nx#mZO=>UOGq}%65 zi$9Q8Kj|w`^bvn_T1_KQ%*h-3G*RZog8>|ps74bI{D36b5oCKL^h!7=*dxHwBh1AH z|BD>>mq}}=ocwuKo-Am<2k~Sxt54j1Fm(#0v5v25JmBubrPmPqhX^UHd``$W+RR|$jDI5^inl&FML)fRj+I`mS$)<ZPIXN`zLeV!`2nz9FH9Fu^4;UDlYqWpH!xX*jTx zY`Pw1xA@3 zwGC6Sf%gVSt+EEgqbZmIg5iW}$gy65G0e>O+S%6;Kr6mCn1D21eqCTZw6ps`g6gIP zU{WyNLl)O95bUEBZimF@awVGtNbi*;{KA|3u9bM)M|vzUNiQ>bS_v8}2%Kl1JQa_* zOxD~s)Lb-2IJkUB%+_ee#@gE^4wfch_tGx&;z0^ic=}WL)>8y2a2X)q7>-9+JVo3z zbzKYp{;0xfWBB%7*27&yFj{^2`*?_w)Wng-T&d<_-sBzYm}^&UmVjxhXEBspF$8G* z&0ySbSd{fpn=xm4en>Ncj_pAf0MnUvSSB8NH(LByaTZL``S(7Y}$#bbfjL>@Ny zRXb3b#|#Txdc=Q*zw2qJWPc7eSM%Blq6H6$(2usfo`?eD{SU70!mX+J{~!Kg8!$$V z7#*X#Lz>YcDJjw=-3Ul+Fko~eB@F_C0wRhE4naggNfi*0R7z4(WcNOw-|zn3-|PMl zcAf1y=Y3v#J)aNH3GxGfy=~;@6$%pD-d3yQDr>KgDvdKX|De3mPaQhI;L^{woX?uN z)0yztfY~%p7Hp44mWu?JgQ24PM{bYby1w^SmM)>!pOQN-fp2EpdYan)oUzCafyC{n zMF6BKCRD+sRfZiVp})Dpyo|ge4U#@Wja?sTJWqPMb|acp!7nhKX#`6M#F5*(ChJV3 zI#^RBm~slv@}j9{CC8rT>!}rdq!5sPs<8w{u;?fE8Q}ENwG7GPpOYDkm||y1;_az& z^zLs!Qg4CgR_N?|biXpMT9sI!&00t`nn9fI@9KYB$9$xSvL}@*#Zm8L@5g_TTp6z+ zt*W&#PHTTr_ZEt!CM!me7|MSQPnj#2_-grmo_EXQu^wlKp2@wphOh2J1xhKdFC~kh zw3@vPHJ_#@0N1gun1oWADm_lVMq-xf=EBsirht#IS<={2QjLk^Zkt=3oZor`C=!(% zfoM#O{laqrUYYoX$68u(-hYDY6p$3MmtApm(I3;8Z-T99k%#E$KZ0I!wJ z;(GQ%L9ydbq*0MH#)XBRh)W5(ew)oUG51Qp4H!IcG~tEWy5_zA6Cu?6qb@@7LD%&0p5sLOS{sJDTWJ;4nH&$=A>u7%`B9U-LyyKxW46gEQ(HDh)Wep zT@iY;T&n$pqlaeF2Fe{x&fTvLF1yJJBWdddJxE#7r17vX|604@0@#zV=VYv!a#AL& zzV%75-A}WBzGiDrYU2uN#8t#`a&~vyAGfPhL#k^-k_3xHL%%oMc{_UsJQ<@XxnCWH$v# zB9Lh@d0rNatIc|znlvj}xW(*)nv1}na3(k6QY^vR0%`*=tt$MGtXqp?qKbrr0DDM) zFrXbRjM;ThyIM(7^vRVbX=mj{wk)Q4|BR0RRfI~8!I7EoV|_}~XudcY_Ae)X-oWRj zb;+i-rC{y~`iA7pxa#}bT|q&vu8tPK{4!WQW%G{Ytetnd3@#FdL;k(R2T?L3!ICOqWXSfg zbHLjK|L0`s?k9|#HyWF~mP@^Fx9d|7xHeLwiSQVXJSe*3@OZQOljPJelS@$GmxMsW zGAHM=yvk+pr}mwb&;HNHpk5YaA)X|^$$rQ2`ma@GBsZ@fI_C~~?+&L1wk6Ev?t{Oj zYYBBZeel|ooB3UUyPX0DN1p}7$%^8c_T(XGQ^9>(``^z?{I`1oQgE0@I#A^MTltW-y~K z^4NpW*0bM|r(ym|A%#IVVdO@HtfgBbNtBFt>;#y@cwbA^Y>+7DCHEeE&OE6jEQYn< zH!VZbd~t5RA!&=+!H{741#hoRVGII@S7c<^gzWM z$xrixy%HiUey!RNaKg5CL{cMrV0$-dGs2MufFUFTdgP?(X=t~Sg5Ft54xuoJ3^ZS( zyR{}f5az1K3Z&hsnZU*vrsybPt#N4w(~+{b!>_&G!Q#=QP7#0-aPiddFVkt)+IB|X zvo8;!T+v|1vX50kZ3JVN(*`8O*OmMZF=6JzhP-{~aqT3I91Y~9gqz{UI>DqC$2qiN zVdKyuE9FdAlH2=f2@@ESYbl)X9&qJGi?fC@NQKh*kKb)p#0sw}Fh>{tIKvM>pXjJ! zU2t~xWGvBXWr@jw9p|BUPb$gt?+e{>c`d;U)HbvQ>PX&=Gd~|bXnRx#{ovo9p+rnt z-32B{u7d9LT==)S@Mq`#!9;E47Y91nk47{FJ^K2$FHPWeIdt8lAKZY8GAw!~1@^0o zHNHmmGMBzxD8gpFZSG$RiSx#{@7vDYf9X_XCyb#i!uWRAyD1i_CW&br!hlC!?}&?7 z<%2l7&Ny@P5W;p7_$+~I>!~w~(BJx8wak$L&b2hIORWqRP=rNloOEiSQrhyJv*8yP z^HLP-k2Ai#J4p+2c`PM`#bq)IURuy5u&aqEc~*~r0R^E6)Yy~{%`DylzEKEfbjem`{H16zo+g1f$A@Zd({u+(TZe<`yL|S7mAuU zsZp$QQ>9N>w72;lA#sVwpu?TbqX(uA_)FmbU|+`fXoeVbi#U`USKJ&f==HBR2|n?Y zc>na_&|_C2MGixBiMq1@G-G1W;H^F2zA9LGow?QtXXiDgd-mHZ_oYBMVV5!BtV7or zugDX$b0)KfTcV-Ug?thndxcX7mSitO{u-1Jn5%z)bw!KDHBC@U%pUuXOS&BnS$}j< zFp<aOQ6)v&xTC= zi#?c<)x>Gt(=wo^tllFC^cD{B`A4s#71)PhFPt7={Z&nivA2rdlLFPt3spWoc2fme+np&*WrdJlpMwBBG#v&P{8z3r% z?yVPMy2!JOhvd{t&qb2&SHT=xH6%LH)lVke;L$5Fe&R7hO#bb<$&VQAvqD4wtgx)H_CNLM)IHQ50zftq7%U;uQ!{aTao?=L|U05@y? zT{cIPsUblG;;B%!14H6i1LhmSQ`YFQ7@%FRG(vbd3_Fs6p&D|XGyLE54lJLzE5sMx zSi!-|eug(tT$8I7_u7+T8lkQ7Yt|WBb7g#|G%V}`FZfEQOHS}f*3#hV%9C)XF^l76 ztQUSOa-%cD_7yMFljgS)VV#-Im%J>4_HR+Mb@E9yb$+`5RHmylJ1CBiV^w%qudPGS z43lBqoYeSc2QDMZYs?My<>sZ=<;+4?Uv7|VGsuRKWCk=)a8ta88;2E8L2T5k@-(Sh z(X_#x4G=L3WAco!B5LtQz-C0W!lX&|9-)kfn>6O0WV}&HkE1c0D^E7Fumm+dPs80y zo_;J#j{m6D+%ne@&RhLDQbY!iID?bY9PAo>?*1wB+3H>Ke_9tX>k@nJSOY!L%Ac3- zk!u66xD5cvu^84-`H#^AX7DK0A~y~tW9uGZTSTL^Gg^8Ay0U9B4cECWTp8u@z`WU zC#?Csa5>}mIqUU|m~Yk;S)RIl>^!;*gqruT8yEmAGofS{T)OwICUnP-}B)BKH|_46qO{zEvgF-c8wu%KQ|!qleO z<8wj$ye`EMdQO{-9xbw83u7!7wj$q}v6;u3cxy9gj{!6R6Q0m_d4n|bOVl3F2Jp7e zTUxAZR=Bh;$!80F2ht?61W#UQ?Zi7cSevA=(;0ap$$&)Wmw^km6ovu!p? zQU?`aWFgT%{?Y3)d{Y`!opQxRC~5ba21z!h!VJLk(LZFlZ3_akfBW{2K~a6z{uBPL$Bn zGHv1*AEVy~kt7E3n*&AoQ2)>ngPj_HLaOYIKxc^Ir$)($&QYh0QGJNo!aYm}ildHY z1m2I43>rfr#aYs%+{EGWEbho`6ghAFF+IoMGeL?%z3TIC08b^4rNJkMf=K>ZWeF92 z1e8lE3`eiE<7RH%FW;n>D3I5QsWGGfQg)tBVy6XQW`IST*b^NjT0** zJ7Z*@y&!$Hq^@=Hw7oK<1CC;5F@>z%ht*fKi&QrZ8H8sK69jigyn+pjS} zrqN{N&=qL7t`y0Bb2wakF+GZE*>9f{C%;jV_nl3Rr@-E1JXvFIC#Z3&jQZmWBC#yw9?mFN$_pZ?ntm~%euXYM~JCOk$i z1-4vIAvQf5>a=}QO4bUZ2DBsixaWQRzn^o_gBC>XS`+{M%o9Jxk6#JHp1$Klg1FRC zL31Nkianez1zcCsxQs5T9d6#QYjQ3XxJU8p&7XWW#dMo5lAzf9PYjKj*uUSOsd&Y_ z4WIq{h3Vt%{vW=y|GFjKcHrWn1(G%YzFWH7JbFOzj4c>-Itk1DWoMW`lHBm`$6_OQ z-x=3mfw$q4+7SY}Lh)1oK4VW)^dQE_vjbg~b}QAsLINF9yBR736p#~3r}Vk^MXD^t zStR9Wbx?)!@AXLi?5MhisHT?mC|nFn8G*H8sW-L9RaXF}t;t<@*6THK_TDD{f0fev_42IYt&T$cqTIrw50k~x&pe&EBEPrx^ z9!Abyjy8tg8d(^WbX<`tFq4*iPeD^}nx`*lG&C(>W2s!P{Dx4kdDOPPdL<=7y)%1YfBu|9K~mG_FB6T6+ZY)zI7B zNSn{3s=-`%KzbG|q{gJ%?UBmQL@X3Dku~2p;%lE>+crfdTvGAJVGL7-fc-(ujyLAJ z7Rt7x$}jBa{j#!*AN)xgf(jN=ba9uftUsvIq%-5)=lE~Y`mun8qgX7uvC6cg8n@# zH+k2Lr8Apx5RaQ$;Qj`qAYOO+LcI*5;CW6kN}GR-+U270o;pPM66`A=WWn__(*1#Z zD^`16M^n4$`n%{=)Q5*Fy_Yz5=o_zq6c>i_+$HjX(=`v*>mfp zK(HdZ32eG4Dqi8lD(6(AsQK@~R~+nNpipgy!euf}K=`Dn(R%T=7Utuq2`=IjRf^=V zEZZik`HgIE!QP1GiTK;mU2ZPgN#<-rG*|)^Ta8Z!S!1}$2FW9A9y~oCI~4KxLBdb( zOoz?pKp)c}Z?+2(bXTnul}`W>m+Jx-2yP}xwp=_F(vDk^3aQ6B8wP$6F5$9H_0B9g z6uc+tMyH$P-mxsG`-Yhx3&&9ZjS6~x%mju%&`tavxhw-~FD$Q2KP>!=&Of62ABIIp#o1hh`X5dWm`<;VMK z)o6`eqFMw+vp=jiCe;?tqorq)H-pL%Wu~ZL(V#AN+PK1sa$99vzAepNML8ple~`y`mz8iXuZGw6=Du z;g}%zm`JyA0I^QC?*;BH*>^fm@z-}6QHFz>8_Dky0?JbZOtjnR*RJoTW0wWq4}9=< zW!(|wUCCM8rgaCRr`n(|v__DVpB7DfokgZjatw>mv-oC1`5hk7-yd?sTWw3*-?U9% z)!dtE8&*VVTqa+0{Qb+by>YQ+L}TbCe%V7GV#T}t#hqdCi|AW3<1sQ$`sWh-OGds| z$-gJszt6U}k_CPCrSXL)3)2(Y{hkXfbp;HSw;wI9&*va#PPUm#QK6+;BV#OU!`W-b zVsj-D$!tS+;9P?}{7pA@U8yC%;DQp}>$uM_%x9v2E}HlWwz`AXl6K0IcE4-uQs_br zQip#0eDtfT{ir`6lOt$C&sU2@dqnNgA;E>-^j}=W^Pi z;hpx|+Q{Lfz?#rx?H!&39DUjy=hc1Bi!l%H^8Ea(T^sM`&3zzq=_&{vV2LrF8lqlOTvA6j_TOC1&K4$|AwsRbS9To6(!3JKvx zT^5wcR>&`vy*1~@K~03;C))e;G=L&;p$9KLUKBi4-Vw_*By*Kyrago(~a}vRhA*DOFWrG)CA@1~$hx0nqy{$q6TTr4n4}nBMVIJ&QX?`d}#Q{(+ z!v)j*Zc70a+e`>rMTLosHo_N30wR0(cfZ_z247qHIW-P_Ywl7d(D8jjRr zl-Xi-l8l-jRO0^F3|-aM0Q2|zbp>H;{=#n+wH03ts+tV4Z-_`ga1;OIDO32E+wRG@ zAd;krP7)B*g%j{UyTUn+4v${6t-dGW_=Bd!C22r0eF;ZUMd0~WvSjX&kq_0o%5eal zq&%i0Cw?&G+#zRlBv1G*OFdZ13juxmfx6YKYw$-uyjw~WqAISfN$>=tbw;FRwb;|9 zQ6JAewN=M3EJ(0YGrKm&(e4{rSz0Xh8l_G`$1Plk{&s}fv>YEFif0Y1`LJD+@B`$N z%<{Oq1o{am)e(e3pi4The1(8&8HHe85{Nm?y&)3aX~we<;l$&%swa2I1|9>}MCM3s zUq`iu%Zhf*NG{*n{OLQENfs(y`JGPGQ10U~^M84HB9`>-LOtZQ^d6LOviwx(Av9QT zj@*P$;Gua!F45y%O@BK|5$ttBXr7>tPtuYHXp07fn+I<&hg!*TlSBU4?nP!oX*#+% z0hYny{qpMy`5gZgiGEiI#P{6QQKV2nu}*4(x@+9Mm@nTohi6do|u$`BcB|%2sh~6gNPiGL=K1XehoQMSrl#{ zp^g|3K1*hYpV3d@53UA9g_JTZp4xakwXK%cy~by0?n1?}Zk{%Tkn^w%K4W5!)b1c? zE3N6M$m^t6oIyd`m@cKv5eD@+s|qiWYBR0rw?8^j^4X)IqKbe++Y|Pe9)f?POQW6} zhd1+)bMj(MG~jZD)zF{mV`!m2%1b(OXZYW)=UKOVtA!b5P!&(O4oe>%>wb80a`&K& zc>(Cq9_dIX?^afhI_9Rl>koZ1Dlc~{K{oCB#jlJ*(V1VOVtRSEJCL*_*2RSE~BQC6=nfPPNsApjxsW z<7s#YA%tD_T2{-9eO{<~)!);JK-UolWtwBD694GR{k5OPy9Flg?Qn5O{cXMWYLG$l z(I6KTt24q+jlUP#YH&74nR?-^i}ay^8aVZZ-+fXTr&n@bvK3oXjM2nW4LiPix*GFR zOtktN>cOAUo2OkJw8y*#my6VBo0Ks&d>npHZCr`BwImRBSZDcg`s)i`@c9$+@30Y_5f*S#*uNK}YO}Es zo`2-oU;fqFNbh>k*LSMaf9v4~+OIJCd1#1W0BJMqJ1XJaCxIcRDI3D847qz#*R89fKTJTF;`HAB#&^k{*vpTx4UvPM9+@d zI1gR4`AckbtJlU}q@(YiP@(y7S+e#qzoYsl#}7R6$fUX-JE_%JJnnxV{9=Yy=0j{a zJ~Zl6lJn75iH*m{!%=!v9JX@H|FpXKYVN(-@CZIJS3e-69TetZQcc7c{++!e?Rci~ zzp*djkbz3l|6pIjqgCwygk3|v84u$YBjZnHd_S>lSSTb@qT74JQ@=z?;DzpgMyI9M zLX9B@w7O>1nwauSt=%7*VO&XqHZT4U_9fatp+oSVDG_aV{#^RBh9UMC$JnMKjbhY@ zmJdN>+Wdag8OYF|l4%h%(h~k;cPIT`@D!vY zt=?;A8Uw*9R{s5+%DvvE9_E<#l8;!x+2)&u^|G-is~!4GKBv*#=5 zcSGRc1HHS+qC@}aO-5eRfAiz-(6b1be9Qd1l^~+~z`NmKu+fBNm`i2j%?EKc-I3q= z>!}fsbZB$2j|5q0Rr23AfhYos`u>A`(KE}p4>$FArZdEb`V# z4CkS*jyU{KZM!5WE&6NBYJ989q;0hEN-Z6CcgK?VQ2|aa=oRm%hx|iSAzSGCX8Ch+ z1Ym2}SP?U9lwvGb>6^ysJp}im_8d$9#ij%0#j?kBVLW)0PveZ<)|GG8d~u2~Z8sl6 zQj6N>`*a#GrN~YJv}Z$W9UpJks#APw90SNJuBR#K=Wx#N53^uY>>m_!W2Jvqrm0Yn zW^+n!8qi=SmV^qC+LO1TDL%h#8kl!332D{W{!rVyzDjVK`S_jV<0eJyMmouyGS~Ar z_0-fkOtaYbf|;fVD*H{;K9Ul+yf}KGCd=sMSsHnAk*{8jeF3Xaxy}B%uWO;1q;VNE zXm{>5sn?LbZf%-|QZpde1}1ObX;tJLqy^)GU4#k}0CR zDhenIh8Z!#1D;5W4jCv2zR^T6Ud?c$NjPo<|84JexG0O!L!x82?3Scc0@FBDlJm$HVW|>FW5r>xP^eU;zX6x z>G$G>))2`=@~W*$s*$%`#z;}Z5!w4m&;Ii=K`$6tgzDXh8&gk*7`tE}rmQo&6I3C87t~j3H`6g|%e-A!z}J)gTJ(-s)&qs40iGf@`Q0+yuV|sZC0C5-fU>GBFIB1evVb-*w(ST<@^~p{LO-P! zM!)f_l4^ONo-Sy@xPIM*AFc12$7+UI39LjOHmcD&qY-pGKM))|o(q-cDgKQ}VTOfyFM z?;?#|pN%k6RUF|L7Vts)_oM~38IOkY8z~1uY?>zId9B+;&5mX!)u;gm%v_npfT(nx zZ97iG()S6JH_6KsbKhKHYc=QWOa8_aU5EP&iWzmZw^NHB_p$lcH>lWDfbftZLs9J{ zAJUB8r)^}^0bp`f%eGJNAKAdPUEL36`-4hU6P;?j|3T-mmB+~FS8u>ycpYl&KTG7d zH~YI#n!FHf?vjSRQOe-WF%2tuMkH&vZ7N2Wm>N3L6bvP*6$N`~Bp+p)js(zIe`AsW zRP|b%gF9mzf2`bo{yN};ARcQAz-xR_trk&q8H*LI%+))Ad&V`f$juTc^*IZCv#a8V zC?W8f&*(oRDyqMv$qBnq&1cf zQVRNqH$I(Y+UquUl7L+VaCk8;+efSPryFC$-S2T_j0k@ZF?rpF5PNO(KGa<{YfXCD z(zxv7_u4MkmsCG@d2L$2A`FbkH}hYHW18G{<*Er(KV;?JzrFw2z%t^qw;ub(NAzKM zO`*1fDzgx5#pY2yN#>@>W2J|;6D);HwEFdOFI2Nr#cTXk9I2p#&p}4kjF1o;>rn^7 zG@kQ`H5qlic47I~K7~l1;OqiudpOc0#r)RM<%adw@|OephH=#0+s@_{k6$x2JTc(K zxQtDGCaVM)mVDf~;$?lCay%aDT5Fj*s3JiOCOlUN4rr_WqY(_XCfr zi0|<$Y%*`oC;p}}XwK@OuLs9)S6{qv!EW5ry*nMut0IPYgr`kB-X8SN`80&Gw}Z0Jg7V=$<=cJOKeWXKdg$){_kxd* z>r~L>ylLT4XnqLIb$+HX9_|l3On1<$ar;Q03CeCHoHP_p(FvzMfYZs)k>^tqOA;9m z=)jW{ewZ!1E9jNj#u62S932g(3C-p{!x45VE{Uuc4>dVpw3I>Egd%QsBAnZE>ZShc9gmH0CF{cCx+zfl<5X4Ha1sy`M4)IJ1OA=RA#e8-6+*X8= zr})ykm~!!)_nRoP(7XWyj8+9)y`j@JUEA_-L5ez3!W9p7UA9s+3b5;W@z(Zf*JGSr=Wnq1lVGO^ziW{aR$&<*hmYuJ%rT!htQG>-@w57=lIVqnY zDwb$ulVLe{#%W(>hj0$1I*Oibdb0zGiY~?P)Vxx^6$?j7HAr}Dc{rpC6}xklK8A~Ag$v}#Dc6T8 zTgp(tr(sM-jGKlmB{eF1M|~YnmYz?4sWG^=nR<&=XdWu7M1p89RQ!7cath;>lH(zeArT*H$$cob5b}DBLQ$(!E zghwd$cFQIoTu+oSIhHXcjnpcek)EG1y%{Q;kAjux(Kh3aZ_3<{9?<5oGLMSTjIX18 zR%l*7!ApK@b`p*{_?jb$`U-`5@Qc33{1gFTh*vbi-Lc9TBb#^r$W?ij7DjP3Ym zgG6hmgU;(hyQ&}LoVAV}^y-|iBdDyWeK)LG2gI1|>0E8HTrs8|*O)Bs?KmM6J<}|# zD~hb2K4nU=8QNc>t+8Znv{IM6b5pLw>Ls1S=Ao@Bou{6nGpiy$$B9-U{+65vtN>|T zY`M52=lwC#JMe_sx5qnF(IV=O-#OfgVdeJqBWJxa*o>^U-6T_1BSJ=TyNc;r^;6&A zAcvMafiDX^sXu#~+afAZ?)-|1gg!;YAljk|72s78Fj+DHxq~c^bX8~iK6?`K?M?_e z$R8tXHl75_1DLW)mhl<&Wj0IfeU zwa=nvN}{5^MDc*4$2%$X!^}hw_D;_b?~V~N&pgdz537wG zwLwpQm6c*i77L4_wD+Vv^CK*uXrUjoSO{Zwa@ ze-%s9vnUu8*o&N*zP3X=$l)p|PLY_km3wYZZ5yBbB=zBG>R;Y88%zDy#V~tj{X`{1 zXE)Qk)5WWMnjU9Qh;1KbN}if5JT+&GPZeE?k21_dDebAv(^({6Kc9Oso4Fl!_np1n z=q#-ci!hJv&@LYPtuWhEMmwQ4P0T(g)Gn1+cc@yNd{pXiI*Y7P@*1zRH!aM|M*0?o zW|{}(4?NG2dph8wR3I>ye$IGQ}F;o7phr(3LN;FyT5rV(uYhL5lEV=hEvVam4J%A4Cy(Y}}$II)q^ww-*AghU% zauMa}#w>HWrd2sbQs{kG`$lBgJ6Y{~rW?0=EBuu!H_s{tl>MsbD#H=?nV;p}ql>h; z=Tj)BJs8ERuDqaoGrvqZ>Y9Dl`MK4RPdP6$M#7TGPTQrwQkW3!7-_)=MAI^jkKRbx9zI9XVh(?n>1fE z>6F_R$CPouD2icgjE|A5WTa?DV{R$eCo17yyICv8l->x(-N!Fy8K4V zK*=Wa)aagEX73B!;N3@rGL?JNQEHhTl^-v7+VqcROC+%SjlxUq;tC{kciGsFTp$P+NCHQou^F(Mm(W zT7Uh;5Rz>l!y#L1<1Aq7O{&Mk&iD5Pqm@kd!a^3 zcti?xdEI)kehWZ44mUb}A_Y)O9IjeWm=>3|sPoT8XC($6`a92lbv$d#HwG&Q^)aWs zMg@=4b!(dSo)-1q|I%Gi=b`cQZd1Ca37MBQ8Ni0&OoamaZmR$)3*zqGWz=U?)Mq+b z5W~{Hs)`U}=KTGaoS>)r`mICdd4)*V@ZA?b{bdaUMur27emNOYPI;u{zI>=v-d(IR^e?

{pnHW4O}0aFjvB{zKLePyoBc zodf_gw<8^X9cLLmj#S&>;NjTEu$>q?3$UlL=Ue8QKbLXj%(Yug#ZV}5^y;X#d_5l2 zdeu_wez#R9yu%>&`MX%WLEOl@59GX~&t8pEUyf2}|6UY&_fBmG#>3611+~X;*6btW z9N@fn%vN6^MyL3vI|o&n-=8{;+rx2S%i|H!0^L22I`jCC;DE!{Rfx*=W4D8FURl4ij(i2K6o>}^O!x|sZWH)myKSekZm)c*SA2l<)sVBt5vsG zs+)z{>9d=hj4n&u6Rt>O4BMOF-&eK27jp=r=8(nY&s@?QDG3|t{Tta=8~GZWDg89h zYc}s+ZPsdR_2Mb}k>C&Ggy_Y+4vp=DpzYqp-B(xJ>cPMGXn`k5rNfM6Md@WzYCQ+F z9DcFogx1aSuv=p;8cXg8KS}F;4shIIs=a8Sh3^Bjo<^J0gnc@~ek930>+1tf!U2!w zp+Mqc=-$Qtywlzl!*9+Xq}o5owWr?Y?!2wq*L8)s+!h;`!e&DY0Hgkv|&6R#h~ zR@KLHODCb4r;&-L;RMix)Q&;op04KE-{7-!?tOIiSz#i{*kXg+YamyB?q1)V^64wa zZ;H?E`xaL=9G`bqb5l@~aKm|^wwUP_mvEQX3u3bW>5oSh6^{_fZK~6|udC-dv^Wk) zJ~CMRqc~mZ{6QcAq45|9C7arRC#Fy$_64P@)lQ`ob9kk6;I2gs?E73oWgGP11Of`D z_J6Uj7jYDFO+@U=pKA@uSN}0jB`RrWlVSBujb<7>!uY^Puf~{1wh#BD#kxSS(V;Ix z;o+Bd$CnvH=SBYZox~b6aepSfeY^jYp2$pFkC|?nmZ`qXYmXQE;);{9za2~14%kvK zlbI;C+#I~Y%3k@6x$*nRf3dH!U6;4coMOi&j1fLVxAgwX$CpRwj+7ac1W>E??96r7 z-q8(Yhzj}~q8#;8o#o8tyMpDDNAV%DhwEb%s^%}xB}2=ny=4~cD3%zXGbGmzK?|gaw@AB`dd9`i41jTcD3@PE$DQl7eYx7k6 z&&^*hSb8%hc627u{z}!7DWy*niV>#A@%RZ(gpTJ!z);agBkq}!{ZNlA*-wTZ*@}z* z#lA*7ay71?o_X3dMr&ENH_yJ^S!gkE_cQMLycT4xt-P)ysPb-7(;?`+*FEP13hz?) z93$^C@2Yg~a=%CKy(@zHDQ;JWeKHa%GgxHu3XR#ixgHXG<5cKQyx&)+LOVq}REFLc z+;m+IXl|pv;E-jrp=92Ev$1@*bTd2ZC!=s|ZH7v7Tw}TD_vZck#?`eyEDag3BkxtV z{e|YYINHmX-}|NZU6gM`0-f#MgFoHEaibRLS%YA14ee2HF{tHEp#H2eG^M zfbag5==vb}@W#{jve=;RvD!@5mp7eW@)wR6$A~{;{&YRqaJ3+l9#V}0s$K)c&Cvm{ zs!)ih+@%K@b>;-1GemE068azPD|DD%m8x@?E0OB(Ek~M3*n8I8fUpmugXqH#l8Fn4 zqq3Qo`(ujJ3!xvpFXh0mH3(D@6Y{?uZ%^uTXGcsKOMQ%(Hq)ejTH*~gjr?ru^4kLB zJq91r)LNkG8FEVGyff=@kNRZJ=SSPgyzH~zJ)&ygo4wBYu`k7`>;u&$PP(Ge{LxZTZE z;|G73&F;(7D^*~C*5&fxz0{9ORJv!fxk@V)zrOrgULl3;{L!xJ{u_qiSEv!O@k^Aq z(lpH-X&tJaaPG^l2dWp5d$DI?BS6tXE{e*N>_eV`igE2VjK%of*(V<^pWoKpUk^so zX4RmE;FMuw$?T=b5wgb*im{V=sdD1>)U+i`Y~^}s&dYAJfzdD1BD6U}YX*>u%TR#I zm2Fabkk*zbhX#tJ^Q|FaEs&vsz#**gA})ZK(Ixyhq#K=VlWIT2Cm5P;8t2aV!2Ye6 zw0<H|2JXn))W1gbZe(zo1qH;(mfwLuUZMY%HR3|hUx6G}|V#rrBnYuxNWt?X*6fbcr z_STRqpKcQb9+iDe3V2c>mS@0DH3hvRk3!Zj4cp9!z}$scdU?WA$nRWA+Qi#Yv|9?0k$Cuv`>vY zG9%<2YnsDMy&$62BvMqXM$`s?gSgX{^p&$P)pke^WWd=wSiiA#{ePx=zFSuHFU@WwgZ)xG^fmA*tXYG1n<9zpNXADBjWmGipgY!u} zDJDe*QfKohhpD-{y*==@725L5gZpYiS9{1U3n7nWAh@PpTRxx-5=Ve$l_0>QExq6~ zTO=Xm>>XJ{!ME=xC(i~rgFF+~gk)&; z^&4xVQAnLLea(x3>?#u1zTfe|Rx2-^p3Z!IdFG_2r}+VPdE07X?4Jgd;>f< z?0Vm6E_#$?QlbB6H8j*o28ewY{zKVXLLEIQPZ zi1m)ylaEI~U`2T9eB>WR}d>@}*X!lBs`D&gm6b1+rZ3D&DR)X+}?Fm zMR570LJl-uzTGM*y| zxkLP-NsY`eG&%CYc^MHIyFlr5RO?jJg8Ck$MFlupJbg``FuozIr$s{xRQat_w}&Lt ztf6VF0vh4x7Ff9bKu&&`7i&5^iKXaZxVw~uV|G@_&K90yTggKngcG+@^Brk>rNxMG z4HTT0A(ugdIrMuz>}LiW!{w9Vno3}WwgW4>qIw+0f?NcmjZ@fgrCC-=MMc!4%Z>rm z@9opJ9;Dewmw=$zN=???Gj+K-SlP<~qMY#QhwjmT}ML9wZeEV>;Emav&TCel2rsXQiP3!lDV zjx&b#3<>kZLyx4roG`97&k@`yWQ4qMkQAj`5{LQ_bQ*w|q;}dap?>QFkKmSqP`>>83cz04)|YQeP2V6Hz)A)EyJq zPIQ#+!te(nMNXa3R`2eCFsXh}Pynz6et8wF`pk55i2qwDx$oyanJj@ra7vST?9-M?lc^U{5V<&~j<}CPh#6m^-~~=H zqH)iwcwtzv{l02FAL{%Dk%Oc;-w$zK7T}Di)Gb4Vp*0rZguGjBnYpD1ySD;njbXpg zv>#E{c3L&JR$%f=0{#>W!#|W*C2jQQK0~rMC%xA zHJHO1dx{$@jT>$J8rNK9xCPDj)F?dx4wz%(tO6MX7k6SP%J;B?mr z(oT}58ft@Rr@(T@U^ryjm3kaa=D9?@Lkgt25@?e1z{wLun61{wu!pK7BnRk1qDp6^ z2%D3J*CEY1C#cAJsmWv-!2>M^)=)x6WI5XJ$3#w(VtFU5eNwcYciDO0wSB*a7Mf1g zzSOwlNnIrk53ixk7J(0n61N0vt&Rc-HFq=cG{j^h0ZIEcgLXr@{WRn8c?SIUKCK@f zO!xri>TLfms{VuR(W(RdXU5Hqt$X7sHt7>Ii$}DnK!@5y$wfvdEBiw(ye(P&Logkz z@8Y3yixp&&;)QV=l~^v#wjNvzz79NM6MG^@`LM2r2G;@hT!LOJ0bihC8Yt-6KAR`J zMFR~jc7Ue>v>td6FxVm%ivyONy1odSXiSi1OlZqLe0poU0gR?tsG;5Lpt@=3vj{Y0 z@6&!XXo|%(fk;S(@kD^8N%Wzo1bZjQ4VpeeGwE93xcw|~yWu{H27Uc`%B|MI_K2_M`xkqAS9@Rf_xJbq_6Wb1 zuYUa`Y`rC{KO&sCL#@PFc=_63DVu50s>MhEg%9SA|>4=EmFJt-0!`=$LDeH z@A2DTaCXjicJ_|f6F>7B|1V94`0s^3#>WXj%-Gl%!HB^R_D_8K zdh@9j-}Dau%^yGDjPEfckdXKeB>saezEKF@z)L`6zJC4szZ{vauCC6`&d;AefBg8d zy}iAyt*xb{<$pOc_&P%ZC4;Xh$JdJCYiaS-l=wPg3-WV9a4UMfkW_Uu5dR7%Q=zCr5T+cc$KZE{uF^52SFE3Bq&ef9eR{Wf|b5 zln?U`{oBX(PMSTv%^w4`NjM;U5Ab*Zlz$NorgvM!!1yW`Bgv#T7o!Lf?Mql%Q@5pP zikAnGM1>;KV*pVw*K#axhTC!+e>o!-VG1i+ej(NmD?w0@qozX%2?vg0X@^rQVOrCH zwx)Pm_tg{)zN*z!9jUF=Gy`>kwO7Wb?rZ7hE>&w8RsmaUukAeC8EopKE0rM|Wm)AA zA@joZ9F$*$5}9%fsw63Fi!meL>~Q*a{zDRh-!Kb%x6PthzUu#oGuxXb$u^lkVQep} zkO;w5X8;MSa`P5ki64+vV3J}XSXf<@EtsrH!kkBp55l7sY8xj#YE0^evd!FRz=oLe zT$|=9sFIFYb@khNLFR_QEUonSpjNo`+YhFmdrebZ?T130Ls0!Tg!hjm$y~@V!!QxV)D(KljWU*9)#~C z%Blk%_N&~6!0DKz=0^p))&}Ds z$={7bZi;JuPaoUvoz0?nCZxMdS)~=5=4B_mjB=0n}*a5&1EH z%oz7ZZ&dtkb`Yl&+s}!fm!iz7ex)ntDRw?1CxoDaLAO@Y^mb24>A<6k$xo8lfJMv0^m6HiyY}20)te01eYA z1TwgFg8555c?YKYfrm+KuwL5ZDKrvg4+jh&IRdC-MfvR!uCE+8M>%Z=YCF>+V-q<~ zfWDzVZp1;N!~QzC1WUd8&g6avCFS#h zFAtVok_=diJAF3Vm6?wMwR;(l=EV_pk42pV#=cMnAvM_>0f2NXB0#rHzXZ?@V37>I zH=Yvpkb5t&G%bmBC010AzlT!BcqEgNUR81CDC4+#&3b#C-a1)1g~q8A$r^l@qb>SCau9vI4^2D~}wXZ1_QL(~(BLQfG`N?!2?Qb119#Fj|1Z4{+Appa_u90L!b z>ACzSp8K*@RWZi?8*4H5 z`xST5G}nv07Hb|NAD2(-lTYIu5BUd-i~HUIK)Y&>vnJcINT%z>9tVNhsW$bq#!7`D zCm~7GuNjc{nBeUsb)l)R`12x;ek8zK;l9~TmQ+(G`P=4*nx@GMZS(B4U6*v0OuLgF zY9Uf5_h+}}wk>{f)~tzWS+mej0o9wE_PpLV2Gg;elyIoUiW)bD1Jp>AH7KP zU=#mS+}vwh-i!__``-_3)vQ?Mm|ovMBZ>M7R4O1MA2_!bHGafOPZRWmMB^qcfl_&8 zTJ_(c+oxYyG!kod$OF8s`GY4x$1F>oGQ}Ljoyg2L#jEqcls0#YMv-6gj_f6CKI$P` z^A~3y2&V>x)1F&qc136*qc|tfU?Wap6A|C(J4B5A(SO6L#aT*+8@L(^&GsyjkA}yb zsn`z_aPn*7qrqco?56-bgR#L)p7bH+Ee94;4c-Uldc2VjoxUo9b$T6)@;*p<{x9X#P$T5!}i}7;P1k?28v$FUs_f0WYSitGqAEP0{a{C_^w!=wE z^TM0{;B9k0?;hnSibDANpEA*0{_M-2$d)bs;Uuy2?Z2%5F}TjH`HpQo4<Fd`Kp&&nCTHIr>YV$_0+oc?0n&T+4cV!mMoZk?GG`pI0I;Vd=iZu&?d zcmsrl8~t536xuv4mn#-z&*w&cJ2#WfYnd;PF@8h*_A_pK;mlb3LqBm>L`o)o+7vE> z@kJIU4oJi;;rF7Yg|869@p~*#za5I z7?2@s0zi3iKt{19Qr1avgdi2JbNuMcRy-BA$i=>v`SN!PyZvUw-atYqBSUN;;>`g4 zyUm~p{=^FnIxaP+!x-oRlH^sBwG%Oh?hygd`JKjry#$FTpxtg@~1@q zN^s(jjA%(>AEZnBNf9LmJVz4$2bW2P7&WJeyTn(RV`@Io2TFyX#HJ(!Cb8qsQ|>>O z{HK9{qlo`jHh@}(gnE=i7XTh(@#X!QEdJ3&+Xm?sZ zXYf%W<)1}^AQUB-io5`Y$bZTkWd}_q&?=9!GJ>-*v$C>VvvQ}i^8aNOGG!ObW|uzx zf5e&cY11J9tePOsxMxR=y|(pN zr4LQ#>SpDR3}%cm<$22HO)#Z1o&)>`bAJWDo@~tsdmN>McgbmaoFDn`HMoehLhKd5 z;FXX-KGr!+^8Dq&fb-Qe2GJ?XIxON;gI0Gce4VLKPyBI5A)Hs1z-)m8{^gTtV#Kxz z$t~zUIFo4(6dcJGIO3941qxa3Td{Z`^6Ma5DYs98TcnY?pqIg0AVkODy9Sg$QIMv86&YFx%tf*7 zc3IR=slIqpe09ZHWy-xw;6gI|aWcrxPHC^H{PlK9mPO@Rmi;s4f~Q&tTBb6R`bxj= zm7pb(PiXYJkgEEN)copb3V|9ou5jQ1O$VITL=Z8>39n107)Qb){uT9vS4@yG{!LcTguIi>dbfDLMlSMgiASXg2J_LQoa68{*oB z0^DVJtLcF-Po_-l1OM@LKz>F@ zYYb^Hn=MkZtk)6xpeE$v+y%a_Ba`Z^bPg?XC4J#rQ}RT+abc(lyWM13R3B#f-a4+%BaZuKy{7#xrcEG;BIMNpI?1%Mbx`vJv%GO30b z!v28lu#lo&3o^fCofK6EAQe1-bR9r13wS4I2l+%0t5QJ62)Ggoc7cGhGj}BCH095} zyNdrDJKIEPF~*jWxXiYKCd)PIiDnNVa*hbHCIA2h!6QIGdobS4%RiYiPZ@dzpf9i^ z2Q9%{#6F*}6!z?tr)f6>J3ixTXw?>VwGf@(v|Yeqv^AWB_tptff^BmmSnDWK4ghpw z@TtyDSrj2q8^Ch_Z{tLK;%ozQ!43f3Tvqu!ULCeI?*z!2jqOSBKkNInLr1^T1{#p} zJM@5xfQv|Fpb~hlj`A{@T!9N=g`&7Ppd2x{JKG5ZaY6B&F(AyVs}#CUmcHjQeWMa} zFD|={t@_mQ7$W-Sg5lXdkH39dRGJG10V;&(b=MA%R!J7`5RD?q#v!rfAZI1EJkZ5~LmMkhG65lgqI8k|q4>!|)O6s=i*%^7h>CV#0%ZDV^5Iye*^v zyG61;V-)R$slX@1hq)xKfdytARMbkcyQlCx608r)_pyKCmUWT9?1~CM=W97(D^TJ|kgmne9-BX|lE}$(tkoFz1IKnn@QK zA0Q=MI^9sqx#f@cVQ-=$zWr|5`2F+EjM2<2&FmZ#n&cWlwy-y~!}ff3Z@w0~u$ef0 znm3QVq}8*t&tX|OA*U^R!$eEI_>-`_@4d);J-76m7Ir{ym*!OTVZydIwF9U zVzfVTf-z#o&=3@xPBN@8OZngh-g?!03y){mf-Ian6PvoDA5Z*ajj zUkPozCSUv5K}(zr75fE_d%6B%WRrAr6MMZjLcTrrjrN|{nu+LYa>N|^>z2&s)-RE5 zrnf6Adn?8U>-C~L+j;9Q<*T(fHgEGsgz`5Q^R~2}00Ty*dh@qaI<`KJgn#}t)Ae$@ zC1O#N3KH8yQgX85JgbcL7U(1NA540i_Uo7{E?#89>IaAEQN%@K$S@Cd!ojRe?@oU}eTQ5{{o`)(U6 zNPHUJDYGluI5-XS{Sq z351P`WQz9(g!?w>!*L~(=YOp@P6YMpnZ}?$exJ|e|Gmq880Kru6-|l}18W$NE*28K z4ucEs;W%uUjP>`d|C}P1z|ZaGQ~w;k8r{oy{;zw@TnMG}dbpRu_n2(-{9VBXYd9@c zA(SxE8Xs}ixbXY!5C~s4dassZ$BsPzV03AhNNe!b@9B)Wtm~in*6X>XjD>&K7ECwG zw&|;i=`x73YZUZX@XeZU`uw}sOYWzG9Bv`bfTlvia}ZQLnRvxOjj$B4*r`ECD`9m~ zUs8@CXM2EUG+h24aVFDng|PFf5CI-Ee95eH9si9a%V{R&7rg`rqW3-TB=fdVQlX%W$yxG4k&`O0w4WR(HUXRLm};uhV-; z8?C;uR~{}Sc?!>=Y!?3!XD~hww6v^VW;5SJxBgphz`JLW58o|J{2{eJCmr~=`5#M= z?vfJ3;NOosStP@KxL=>HjRPh(vJB0> z;c{2oCr^q|Jyi>3!)LflX^*x)*=;`m5og4dAXLHzl}7VR#Sju9g3+Q;n~6#A3G34A z#IOFK=$uzAP3)ys0(-icVjR-qFN+xm0St+>=l2=7P$Jok_B^rvk(c0?P3Vn zU0P48_9}j&%D59stu?Qla3sq_e4p!cgw)cm)_BKU)gZg?#SQZNG!I zD=`%-(5Ww1_UfgA8jE$K@gseO^oe2i>jtAAd=PTeQK!70KQZ}1QJE1Jn+cOP-sJH= z@0zGJnL8%^Ofj#*(tZ2Ipx8t`^*uM7o}X+=Vk63SP^+Lm}m;Dt#m4ninW~ z*J)h+ZP0_PsPfcxQ!3HIc*P9&CoV6@Md@7g3B8;dtE$()Y|9|rq=j1vgL(^8q}4xU z=iRfRkS{egF711j;p`%N9v>sJecnIiM!Gv)*hj9l<)q4eY5L9AaUe8Z6K)qTov^i$5F<&P>#wXv ztPuFSsVA@Uo1tmmX0bcR4d0d2p8x4Ykxk>@-vzi&cQ?eLX0`)se{zAd5_{_p(5JAtpMu|;-QyX|kUuT^GkZ2=HM$X3i?z{3^x z>s9H`nX8)O9peiNnMdtoUEXMh-a(X>OJBi1`C+fnnojy;$Yj zaE~}gt!1hv#*f0|PO-XASRZxss~@R3CurAGz72y_No3b20_{zdC{oGUpFMdI2+m`3 zK2noduM1NO;|58N#jLVM$s%iu|4=ZJcxqHa1S?A*hccR4L#jzvZN+EVZaok`KTf^P zrH@maUlh+q`BF0bmv|p*nl2xvf|hug7tUpjM13;sI&O*XVKMi3iJ5S!rMJ_$b2!m` zAnIgI-gTvyK8?!I6jfWHvfwXf-FWe|s~smP=_=ij=^b2I8s}u>Ns`8ZD%mp`WyV}0 z3W`ea^dDGPXblP4TyQNxv-S3arvhIs+EVnWHp~3bOgi3t(V6|KF1i|kB&8O~>_aR+ zbmOsp_}Q_*KUKJTV)6IHZrCeNtSvWAqQNbwyNF7yN`7IBDc;4u;4Dl)M?_1T1UT^; zbgL5BxAi&8tB@^L#$79#xiik@5sn*j+vp(^jluSI4i{ay5+w{SI*cT3Gx!3Jyl?zg z`CX;_w<;Ks`^T(tV@@hgO+_8Xfy!z`?OV<-3jIs*Z@rpo0>77cypJpJD zBo7o9#d3RAYZg!9&H9gaYw*ucJ?)4*%>ji?ynUJ6k12&r>L@(x6CrQDunSEO7zH%w z_jc_BsLhO9)V~+L@^W)#sr#PY+>~u12;>U*d^LU6%%dy(a$VMPnYpsr>!-UPS9{0A zzGhgh$y-a^dvnXCfx7k9rl@OK)4BYNS`v+@2<#K|nz~u+i~>WzoA&wjDh5Fj1^B}_ z?uCE-6J^dnZ&8@`R(NLz`oA+-Q<;`qbYT0?{#my=P#=pq@Y(WP+q>ghv10=?o3f>y zWDU9Fv2gC!(sRC6(Q`7JRIbL@JszHe7U@{V+fTh3QxH#ZzABKdR1z0EzT-zlYF8n= z%uz!4+o(~L7=n$W>zXXOYQF6fGst|W5e?u{fPjFC#&aV3-2@z5zU0)>aWSd5&a$Ykq) zjNsI$U@SKbH%9E`rED!`W+4cT@yL<%c3HF{4bWfn&oZ3LBKKM${Rn8#*+wNn0E=*Z zEC!iyK*bSew?DMT=O8|H&NonLIISUBP~Jk(wCDsB<;tf&&Ue z_^<{zq)gpQ4f#S~NvC=ZT@krj&nM~=&Zen}!bc&NN1srh;|vbif3Lm2p^jUP1Y zGY#M9CrQ_yAF7g3BLBk+-7rY%a$F{In~RjDL-z~TB}2^3qm(Po zag<<(=;x~;D{S~6i7$_j(#-M#`(B=9C6VuC2Rz;EW3+D+S^WPTGiO(k)zYPJp=V~d*Lt3xO||P~-`*XhWEX{pzuF zm1nNZH`kTzh*$u13rvu3)pBLAC@+D?wKs`XfM~v95;3x#+d5srCEb#Z6avPjcnNty zk=4$A9`ajuDcu*!)N_h*9X(mgUAyK=ckjwp*<;;easHXnRy46B{E&cToVgu_$)V>{ zWS8{n{c#xJ8U_U-VB#m_^0e@qsBX}fieiFvRaZ2U5y)E!L5%@0V$rAr;Ner~L+}I5 zTvZuba>Y%Y^Jb3Ds%qg_ukJ*T{$0^~v}%T`xpe0^5dfO1llVRY#(9nd8y7zmz9rnz ztuai-I7Oo!8)wV=(&j`>B3Fza9QN@ICk6w+shU%IG~S|V{IFJ|HU>l6 zZsP0_7$5M%yn}vUGWFn9R)@O}1zA}^mC@#4fP4!sGd4z_zoU+k6hBl*)>Ai-&^wUO zIFPuiF>o-DRQuuq!Cl}7HNrGgzzMI62S3{lcGZzZ>fG^@AIQ#)>uQa!MQOyo(x@U$ z#oEOc(he2z4i(=WDlv|enPSn21(o^_RbYp3D3YvN&g{m)8Zc!|DalVea*W->Kr$?NwBV?V3~2~;o;|CjVC(d-QaK8$=Sql$t3n_ zs30|0y8(CXu&}?%FIIAbhQ?Y*@(oK7Qu~nBINroq{tcNf-tnXXuqvVIMPM1C>66u% z5{4%``p0Adc2i&OBGEIeI=?IRc33sal5xgkz*mw33p(;bPTcEWdPh$2Lsx`!D~n_+{}PBq7KkYH!;DX%h%vwW!?ky>X=up8vg0LYW`GsE==<8=?;J&d{U2$ZjIQk>t17{1=OAerqTSu`!BX}zl;NMd z6Dob3s&CX~*M6u+!*AI!YokE?j6KwQy;QdhkHzD|$Eq;~nD9*{y*@4dyf0eL#+Lr^ zq=*=iCs9(H54Enp3to?xF5=ATU<{Qwizbtt-k*DdlLl))%UiG!2gkxT7Xr6$acO?A8z?L+^OL0X0Qb)V1~#K+OvcHnVD%aGSy>}ZXU5_&KwQ*o}&w?ip->$ zEoYl~ehY5n_RuDIwl#gWrf){F~mQ z+1BayrnldcA&;jBA0?~Dg%ICPh2e9HK4;7RTQen{eGX{MZB&%Nz>h@hIq7i8QbtTN zd4uj+LQ1q%&`g4{1|$LnnbVENKe7XB9L;u_OsJjyD(xJXL|~+njqAv*CQqkIS|BR1 zamsa&_BX#dIw&+2b;ma6P-K=4*1z?=;kJ7?9T=J)6~#Z$v(7f(PZu8mi_8Q71M22? zzIEIU`s^5lq*Jb@QS+U zADOOL>pDBr!;kLS5>gK3bbs>`Qg{_iOBac}Gl|`kV}b`_+K!fO_l;TK#_c;>=tL|% zDvtv`C=z}WWuLxgk?)XwX=&L4ff-{gDD(S8*PZi!IX!SIl8Lg~ z&6%8@q^Whm^L|<{K`&+^fx(L#5k8L!G@=8Re<$fhNBXRs@y=60;f!_;7(~v!O+c)= ztLNluu^Vom6(-__OPF-imVDg#Z1o`pAtmwgkuo6R=M-hyM$ogx5_5>>KqL_(TDTHw z(z%sO;pj*3OP;wKJhQ;Qjbn9w|2lEHR@6PM-?5C7$YK!}+JXzugz&c8>y>X`osjsH z@3gJEq+}?*6`k*Z#;+&{-9tqoAd9g+P9ZMw?3^Hp%6pfM+bu6|R}VO79Dsv@Vyd1& zgT$)tN^O2z-%0rtM|u9!6$FWVx7XbT+2L)s{GwDR*EV1cSf9kjgxT5$z(5L#0rxq zwD$qF?|}6nS2tV$3Mw~M!#(f2B8}4u-!X}%)>Cw(Xra8na2ouD4gcoax zq0&EEo^coca^S!2G2P*dLE6eU?bpw5e;44Z)8Nm_l*+3ic^V`kK@4E)bmP@O*0MZi z@O_#Y;|FK~Y|dfXA%H7{X~DX$c10_v!0jx?mdN+b*|EgOh!degTNTBVJK86tAD+UV zA7!Vra7|$w!LM^lgsfeEdgzPF*-+ zqbK_^Q4ahRe}w<|_Piw_KrZ11a?K?q+%h=J7Gm>G=u^Okvcg$)1b>B3+SbT7?RUqI zu}|+`?Z|#Qvq(A=Ns9Zn(=kf=F`E&i9t5#0#9rJz^B;X&@IA_-jySY11~2dSM1Ate zB=Big@`0{_<&QF;w#(D_cR}R8;%sg=J3Ty)ZF{LI_PO^48w}Il3V34j`aG^c5jf>- zk7{1Ew#j;qGW|S}j6cFG#%Q4ScewwhKHp6~get_wDI7qdAG}=xj|PW*1UL2tWK1mo z>^hIe-O<9jE#llXz^hKX#nKn5uXfY{pLBI-_Ps|~ehT>~ZvJX^9?8+cY}=E69ZuC4JKreQ()IWWo9AMz|-I2md| zch&V_EIA7l-We_2A01{s+~<4M9C#`B{3L=fmUh7_%{ew~8$S6f6kk3NX~>TYMnUcp zUl$1?gxnxLKGD3fLCmO=*LTJo zUY-@tBtwmz3NNZZU#xw;#!iNnE)u(GVAXdiW+3?PRtiT6K8hefb0Gfgzr>kHLd{WQ z^FQJYh(Stzpu+aEB-FFzahejh29{PORX7+`I{1puuv-3ndErF{D0HBfX}m{~QY!F2 z;>_)_LS-B^L7b^n&Aksfn%y|rdVoqLgM~BE2&iV5D|!4Dtgrcnvm@fyoP3ws1#_QU zl({ces}X~09XfS?CTdj{^!I3Q=kJ}x&PY=HHeKbzIbI1TzG$9_0c#$trANx;ZP&u; z=h^tBkf6VREI${i{bC~n)FwJyOHhez_UfjCe6%Uqe-kj~(Q*v^{NAPX!D2U#bnoL= z3MILA!0KR(0a=-BhWLVqy+X8WCi=GlUVR~LVe7iQbpbtS)pkQAW%ck__d!$9iru&#}tQHY@rY~CDzNAtu`h*&g>fgRlv zj>gE`P@nva;d}V)>K1}H)23nII~$~&e0zq_jg+P2f}sWfl$In42s#DQx${o)al2{E zn=(TfC_p_*tiiO!DN6#aPU*+)Uw+^LpsS4K7xwY8d|45v>ir56g^@#d&ytCdTt%Bf zS;)X-do1geY6)72I_SU^fgc_N6h$+K@E6Akwz(D4XWA2$q-fo*Dt)P}B~YHF=TTLj z7vjNRL9SD$sn|D_%n$WkIuNKSYPi@gPwKw!S=KP_u}Nk*S^Dta*_4VddpqVaUwt2Q zsF&{FwZ%B$h9C)$h8%TikD@Ij?Vw9GxdZgWZ^9CA%Tm0YXzN;bsA$_(b-QT$Ufbn< zi(hg!8Rv4w5|rRvx8M1EeQ|lG^MIn*Q#)?>IL@J9I4#z_hx<~jmr7+r&MO^FtywKQr}x}r{Ob+-JO&BTeyJwU94>#bK^%svx{f?2g@_D@=MxVyLq zEl41V=)YmYj4M6?h{VH7-5%-7lqQHF=-WG1^hA>l5bV7xY~U&tsa->Iae1smdnhNE zC$qMM1j{}KWC!@8q>D54l~(lA=TD)C?1jHc zj=5`*0>;{Pu}oxgP&p{Yum#z()FB3-Qz`KrWJL7qoQ9xcdr}ZwmGr_u6~Tw0~$txtr+cn6pR8!+Bs zMGVJ68f^RZXqIapC{Vmxag#4uzm6MW3`Prih$p*d7QdjS<>6Oh8k!edW`2yu(H|vK zs8)*mgyH9Sc4lB->pJZiuMz5m;s{!>rHiEgl?}%<>_b77lOxMYCy1;8ZV2d1hH_!= zgS#=$RF{e97$H*hB!D~qJ)jI$4H-s0gr-4HS}@J6`#)OS=gA7Gjuwd(x5Y_HzzyCF ztP6I+#`!YXKleKQob%l(GmqbQCp+3n-nNO3nmR zg)B`00iOgAVT<;hF*3ORo0HV1)$hwhbu9=_Kv-d~MSf_Rjo4oBXs1=DrWnF7Wb$|@ zZ+|@r)GDA%k(SwacU?Rsu1oeMC&HDY7c|zQrX~nTG_m6%t*cWfl-h(bv9ti*djfbZ z(#SVn^(SRM;X?HtQ(6ubO_j1gw`?hpf{zlT0jx&`))-j>28thiUo=PjvOxgZD;18H z*Tjk^UAHM@R2UF+1DqpWW5mNN6o4R{<7s_TKO6{HVui^*+Qy`JH#NPbOS6*Q970>T z*Hyn4F@&MwA~;n@Dze7N=L%ye(1;J+jWth-%xC~Vy^#7$2jh@WN6fmL0^0y8O(oR?wdCDXv2!+3hc9*-f-{|_>!(y=0$qKdX{vGdp01G<)&P3t5W*+JC-Ac{9fb38A-gz_09*6?^P!Z#bpeKc z{%W1_t59z-jqkjN%VsOvTx=fugY)C1!YiFQBa+oYZ2#x;KiR!A!&D4Uy9^_aQVr0? zy=WsVW@_UznXr)^Q7_#gw)I_+ej{T$Y?BMop1bjG6T*kDDW%9MU5zCwxZ`&+4&zFV#qBwSVIJrV`wD#ld$wU2++Sr$rRPJcj(mG|L zj*IoLe6stNPN6d(05qE_>J!b#RhfvQ^x*UQ!x#Fm_=HtLKNI(|E!AGiaByt>vNb%l zq$K$k7I+b+jo%qbdh|7?<3z=lk`XE(29V6(;sAwxv5ey38Mnxdsef4gRbspnti#S*>DV|0U(h}kW?S|m%fdl7C2 zJ5$xShiSAhHFVhlJUEW13SZPMj`npc9z??57J?ig;QM$sh#vd(PY!|;sMtZclUXnc z+e6@-|C(~j=#~)5y#Tj<`cDP)Gp|UiSt-`-3~F_JqrtQ-M05j0bf2uL)$Le^mZ;h7 zQRjvIn%#;W-3`s#A-s+)FIuMb~?F^vxz5_py|2P!%<9ooFtF z#HF=c#X1^`U{P*>n9|=jS*kMGG(irUg$^2(%YsJvY``xZ7A$wKdhVNZpV}{5_1QhS zx2)HR_OR-{(d=b5>LRM+wnjVXGOn1l6!UFA6gHZraOk`D@xyW~Ib+mcwIz#l>YRIPqVpxEZ+Kp?mKDVHD9$MxGM8yhzBV;t)~B%0 zwgLo`TtZS;oC-c=~|NEAw5 zfgV`#xg3=-W~^O3s(O;3mgEmC7!t*c){$it{MV| zKJRCscZ-pMYz9)eRe1A6K>0Lc9TX>=G{C=@V+(xs-1ZY~wT#{DtTsJ$0R$5y5mkwn za1~wOz?`{hgaM#7%9<$sa6UX(CuBaPdLz8Q;OQAIp^cvX>h{a^O`Fb5aY8~>Mz7sG zbt?u7fECap3Q{~a(i_}f__3w;^N_fyQ|P#77jK{hxifrnURZRxGy6TCRS~EUb_( zC_Ez6Br>9Cr*gR@l(kvYz3&ui?*ZFiQ*Xsuyh&p34IN4$jsX+N zY|a|(&9Ltb#M`}3!7vig5Ch-?GEDr52fqT^?51ZtDd#4yd-!ZEB5xr&X`}t?Pq<$XCjXj)TpQ)p1P*9YM4D~Ym8!aTx|L#6_ zM-&q)k%)hfvx(1)i%$bHmOL{$E)ol?!~Ctgy{_f?n}So7zmsh)3Q@T~J!uItk8zF~#B(Y0-N+Eaa6K6wU!yZWv4lo&Dc zn>})2Z_?iGXEeQaL3E#GztQD{HSH!N&$~auu?2wm!p($=Trx;tJjAxH+^Md}OO(t% zzPe0_I1EngDOUEXj^rU6ULjUei>g@FYF3R@k_S+lV{TXWoJ4w`8s$J}eg3hdK1m2i z!tl3nM4dt{-A#<6&0sPb>3SN)Lz*v`$Ns=}bOB2*5v^-Iy{|Y!V0}9o+09Md4L4Ra z7kH{?d)G|}!GqEzJ5(fO;?|gcsYBHskg*k@M&`uJUmbvwhxp{t<*@*Cos+_$QX9>KMCwzdEAq3;UOC9&U=Id2MiE7dUaPpPI zBVOJOeyUPAx4pW^7%{gGK#T?w%ioZRH=wT$euzI}%0YL|;aKA2KesLSRYmU{Q(%9* z)O!zS*nHc-Z~IoFX9rW%Ej_0~a0EnFj;2U%-MaAO%TZkx)>}bMaJTg24FmtMdJf>67g0^x zRpaN^l(A@AdVf9cb#ecX-^<^C!bq1E5HaFJCPz@B$Nm8!lQRPCf!tG>%KS34^&o9Y z2Sm+pSqbPd0c}RQoJ2~c_$#gSjcy;`ee@o=OE2bDs0wBX81gqP@mJ6Jqe+8XTpp2e zQx{YfHjvcSbKKM2@w!(aK;xC~rrvvKB*-&)_lLb;W44dM-y9;|Ma9y6)7On=WcRQ! z!ro2Q$uYg6)_GUOf7BgoZ9-3tX>N;^m>0VBBY&M*a%`LZ*puryM!KQx|-;y&>b%3Sf2W&Z$ zguke&D&WqyYFB-!JoTnO>&@ll$SXH>2B!}JwvPUe{!gDuC7(rcV8J@R&EC>?>}mdn zj1tmPBVAtgzz3u;qkJI+0*h}F#KKB8=Be~<{<^;KLYD}jJT2g3Q7)azw**@hbNr(& zg(9YrXLpJGYH*uxo@v#bgjby68l(%#kj(fV1+Uk!cY>Z~w5TV=KJmqOcLr$Kl~jiu zzej(TC=7Va-D=M$ZFH$R-i?k(+E%jMDq%@p5Ev)XAKEL3{$p(J)ba*k& z>k%W=(Nca}H0#l3wWN3H^H>fBS*6ZDiS^8>Aer=6g0{LxJ8wYVHBsMzb=@vvV(+Ef4Fcs1H!chb;!^ajjO7(2ED0^j9KZdO&8o3^6`G@a<`8ClP&wgIF z)6XjMGxx({@DRw9(d|y7YD8#iXYjDs$0cOa)@#zrR1Cq(;RFi}s~z58;5jxtu60OS0wjmm81%FS+&!U4QPcT`?) zLvCLz!zBp#izgg_Qy6sk_?i-Gq}Z7ber+J~e!AfAIOWIs7e;WW9+%{gQ^y`}EZL?llvD?C-jq4e(}SHslEh|j&X#!-Li4Zk9(JW=C;9l+^WFB zZ?u5++0QqB@gMDZ`Z($SFW&C@FUt4f7X1wjFf-K9-3`(q&Co5NfJnE9A_Jl#APn6N z64Ho(G$I{CmozF}f;7?%bLO+ZPo3wSy`S^b`6K2v_jO%st@i}ZqjWYAvR&mw4pLQt zPl52_R5&8>gW-Mn4Y~7kY#<1ql*_0g-c}`y1S8H!CD^G&QHwZDH6+;gg)rT{J4ie1 zX{TnFl@y)?9CZM`Crwi{fN8rno~4wbn?ww&ISsDlr1ACo_Sel(}LS+~Da z>O7r0sq8EaA*xi(JkV9N=R)wAgm)2rBo84GQcrtwtTT{B-lwW1wV&mJTf$|86+5BC zHh;D^#HEs#<)cEl+VyH|Ogbb1ghx%7;iZgQ80Z5r&wTf4V>Ak1P}fXsV>^eM8TNB@ zw4+O6zM&*w`s(%g_aUJN{s~RvG#jxry6?wuYRyIX;pQQn1oxg(!j9~i)nb_xe0UF1IzU650`n<}+2_zjw0 zJyHs!9qWHGaLDX;Vh8}lnd5~lL3q-AKoC>fMr=?+d>AbFyRuGssCajLCB7*{FcDI| zJ252GTvk&_=jdDgl{P2e29pDwCTu30Kw#((Q#lfOvEd+My@-C#2pl$mla0o*u-?7F$t8G4tks`lM(oi`5!MY7;}zH?bk+sa4{k%5_IHC{Ik&ymr6fTcb5N~O36%Kh~s-uXZFKDn!uE|762Ts{lS$L zH>kE>gOr7>qsV}dR+X|?E6_Yx=hcksuZ0grKcbA=0%J<8k`;J9Gb@mhp}zpU-d81$ zH}>_u*aU_3I9ugD++k~2b`k~?K3#nFH1!_g!}S$^Z|P!U*Zpes=&;rI=lReH(tdhM z-Ip`#sqB33DnhLFXv99QfBD301KoUF4P+ziiAZg_8+BzPWT$xwN%PY!({0~`2V1ek z&Tf}lhsp>Rg{U<-SDuS@r1@oliGaabIP0^5TRStZ`XwhHwhF@^bUQ&%$o@d{<^G&e zb5j1CRpWUeJ$qIFghl*dzM(^{YLuhJsUM$7>!5w;)I5)>3PMactVFV)jEZSuupN|D zl@}zBW%XfAF)%uO@WbtMtLp&w+W}8~t+01U)xc&)&G87K?1sgFS@e6JElIY?)xfVr6`RfcIjPLJMx2)!7d2Su?-#hX5+XQds8 zlS>eCe=)!!7B~=MbQp>6uI%NKI}jD_ksK0j&Vu_)JIItwC89PS_lz~(tqh*{t(NmW zPvaMrI_;Fy-9lB}_-J~rV9}UkLO!L7p+CGyJl|h%iBfkC5;P_%qsTRxUZxM5Jxr2s z{*)@V1s(}CGGx6ECLw0S(SzfOM1Lh```NI?AS&(wnyuyL`2B?RnZm0`pG)}8ffuZ| zoG0t{#m4MZ;{(8Z((>}&2*Cj>jA%Y7|Apt~Jk3?tO~k7t*&PR>+1z~o#2PjZ0bUKU zh>2vbsd$y>S+$5`umMnL{SEVT3AABVJg@T>+ z`{ty_vqvQlC}pHV!XI>%7+JeevejURo?>3(DU`6vaOHWF6ShY}nkbx13b)NyB1!9I zK&8QJ+jnVD017K$hD(H-u6qJsvreBsd!2(blku&%HwBX@{ciX4%t+|VYrz__P@Ard zd>)&hPv5Q=*%A<#Nom);jDNlR%#c86@?}gd1BHMALlvW+qhuAK$TNc@mxMWOhx(R1 zN6XTt*(u`G2C4{dL|{@(81S~RG9@BB+^}@owT`tlB>Z*dNApOVbJhoX_h>`REe>N- zS^K`J*O{vS`pGrwt&Dzq zGO4{3zp<55$nO|B7p~Z(I<8!;HLm6|(RgWH33B^#{o^qv#Ue_shj6T?V*q7kT93e+ ze;5d&o%NZjMjmNw>DPU!MCQFh()I#8vCc^kQEfHV}GL4Eb zEOQii`edq*>vf4`ON5^@o1DHEGFCsvg}=`X{qxc1*X3Eh&n;9M2MYhx1n8Zu>ypsF zmx>AHo+8+Fd)UyZU#+Bgb%>v^_^T0CTlI~UU{r_v;~YiE7T#s^i92Q-B5(!I z^X0F$Hpe$#hb;GA@-^qp?Vq)}(dru@Z1K#-LS&q0;t6-^7D!9j36n|p4l_>{3STsI ztqb&gbMcY7sPoeMy#@7{w`ZuB?(pDmZ3%oz-Oh+oRZPp13{=cq*^NH`wxM?zHOlb& z?85-cocL8tI15qvbMo%jezoBQ?^l<;N)IQrDcf>`Hg=sFC&L1r-0a6Z_Fg2nepCLI0~>f$|HV!DV!+MnD3e*Bik39S>ytf| zqLlFhW6ssM5>seoPT7WtM<5@V2zS&9k1$#EXn))9T)#+i>9SVG0%QlqgxjUKBH#9w zW?y!z$O9R7*Im{en2i$`%J4V)x<+1CJ|tHGOOOOg%-Bbox!>{l-+D|JX#w>VjP1o% zM0ocqEknb1r4@aPtr3imrb#Uv6}knDZDJb;PLD2oxphh@gFFg}5G>v;Uy^2t&jibk z_v3Z~QQaI!R>EAW%#{;UH$V-hi~d=;I1GOLU634GO2$!t}6CqH=Fzn-_((6yc#Oqbi09QaWfWaGO;VVpdi3vZ& zvkz9C&kJGQ#X`Nntl4_B2qC;E1RgJJjxCN=dxf!q#oQSRTnm$*9*`)GVi&>K3|Jl* zfjY^QuN4T0Sr17ai#Mt4?C)4%-}T8I4KF`;fl>$0XZ6{HS?<2%;!>{S^m66q8c=c) zQ$9BQ8y-&n)SdQH8H|>9C$@y)7Z(v_A}J`9RmnCeN)Bl1t7+IpX#3)6dq~AI56N>5 zSqyB>b~j+ufn3v|N(3p^Z$qZhgVTnWV0(9lQ;~+wYR?z$rI|XQ_$uy~xn)$!kSi=& zZB_b+gw5!2dUO3hXYOq21q^xPtmJIinJk~CQ4lX&Hqkt0LEH2{hOnIkFg@woK>`(T z4X11u+oMBl$TFU)2y}WpHdqUydBkB@LoXuA1{vcFArrAlr04#NN&Y=Hdcf8KWqCBg zG%CV{b;xY4MH_a+7c<1SCCnEkf`j*v=p|~K1G~)z!JQ+TqAl7=><*aC|KmdDMBhD{fLW#{07WL{Fz1W3xLakV6(BIz3RYw=`Kw9MO2BLcAMI21=R5UA^_ z461khW7ey{JTEiVMA>1dXD3mY9 zSS_rII{K1}$Fv-z?7Ql|1N3A1!Whe8OwM!dqg)J9ETFr$R&MA*&>=bb4aQNvX*D zT2J8gK~5)sz4*N?Qg)+qS;13m*B=b5#`_$i#-*OdLlhmmWI|asLiRt{Y;u`j>Ko`7 zE2D=`bPkhuxl$hcPd%2c8N+fB&@vu_1qZq_<_PnREJ>)>HNJ zo9eBxg1oX!$s?gxqhZRT$1SHO?mw&)PnZTyZTrORuqN3j9x<{ek@BwMc#!G5l29f8 z>8Nk4rzWYW^?_AP*;4B(-h)@z?D@QoKkaSL%=IX(Q(m3k)H?AVIV}mZ3+E~e)jIIz zbEVaqSbs2zFtMP2qn+~8>0IK%E7?{|S*@gx$n3Uu$X%puTNeAk4Vfu4B{y^pR6L#+VY;-|1ey{9**Ez4$*++1`5V0e@%j0{9q^Qkf z>I|UR9$=}mpd`N&rJYV7!%R{1;aD4kYVT9%pXIJF7c1QcAA-lT~HyQEVWi{}aju`;*} z1`u|$c-s#%eU2VZBVpWzwRJG%=K0dFS<6bWI@NG}Gk!(8Dj#Ee5buRpn2zmw%b&9< zpX?k=)T3~qqIl7z2z-hskxrnd1?U>P`=t^G9?7|?z=D@4=2@5X2O`uSv!de@#ifm7 zNjiPfy_`EzeQY16B(17@s4~C#q~XV*8Cs+n3jz`yv})6$T4?|j4bW{G_MTSo7(%Dn z!9s{+pjwIL6td|mxZgweoVN3fsybOLHKXTkuKhmm9ftv4Atn-SNL6S^xN7+3cZhu; zne%igk@6#0LsqqDHWQqA4d8R`$UYV_U0No}&IJjw6dHRMK4~hnyehOcD^x)eE3AhF+ zN}%#oW?;9evO2o5a`#tsAs>U2JsTdt_1RAFvsc_(hV2=9xVnR;x_9a9euYeFeN!nZ zc4J_{FvsxtA2`tjl6Li~)=>7_BYGO;=5LnQ-)v>;9DVAZeH`H-ic2L=6!HP2XA6{O zOI3)f;>!BymO(54NSUQE#iud7xiRayG4HzZnM_lvd4u_GW%*oBm27jRc~xU`MeB95 z?ThB5=&FL(_1s5Uzi9zNphnHRsNhM4A#HMLW324-t8sIN;{oDbTarLz+LPs0h*=T- zjr~?y(2CFeh-`bGdt%25li-sMa=DbfW)x9N8|i$;vkx8g^EGH=kG68E?uZK%q@`10 z-d5Uzd0c8kH@#CwuFF=g_ajYxf@F{Jd>7|@=Vf}g5JQ)bZ>QL0(JeurYs;Jo!*(K# zWzmydy_Nw1<)m9>_b7{&Sc@xf@9y_EeOWg>PZ`>aED|H+`k%EtOO@*m$ZQ+U93Y@G zZf~*fx=HJka~on9nwjID^8l%KtEa|KmyP56jyh zw(>t8w{m#D6%M`$`^qr3lR3gFU(|f#qTNXu@_ss^bvovD8l50Nlk$Ehy>%w*b|z1L zw($LIN$YI+?QFIDT$ubw&dtxs>G2<#L*H&jU(3I#?ggxDKn{#kAMF+vEPu@1F03z1 z{eHi=m$e{tyLj3(*)pO-F%g!}pf>k}d-=pFK?6mBGk)krZEQAH0!#I+^tP>3CZ|lR?E=35hh^rfW!zf7 zoyNAE*1Me!h23^PJUm;x?z`P_g}w3Y-C?V}g}c4U>^<~~-~Lwi&U)MaA=Ca}g};|~ zyXS3xvHW+36b>4h2<`&9DdZ1Dx(~j!{--#@+kPZ~KFVSwpzuEya=@yB+7<9(^r2OF2Hs{2#{jX)tfg?chA?Wy>f6NP}4S(wmd-V(cj~g0` z7e0!Yb37Lbit9ev7g6ZTkBS>b)|cfuA!#|xh1S<$Em!iL8|CU)Tpje=dGrheET(YE z{s1NfD+$pmMN=NrQ~(tcF44Qfthvn61gF~%ptm^`0+c&A+)kU6=l}p9FkahS*-n6= zN?x8$jboFM!dYC-CQ>53x>M!dBhjK6|A;f%DcBG?)#CU(m2e2RNed0>P{rGQ4^}MR z#I?aZ)hJB9{lKO(gortV0kM;l87}HFu7mHQ)Gau%?@r(#UN#-9X)TztCC+YC0!e5f zdrV@UA8pYZ$oMaD=2|@&rWLrN9Qw8wkjziY_coB4DWV51O&~gM+bfo4qP8GADuZ%1GNr>=iO14rImn+>jOiJB$ z=yR4ZskEGIY`oTHheavt+f7os2RE-a#|!m~tQP1{|7@MQ*`#jw!A$?q0sU>Q*KZHF zqvAAPE_!UKh0Pghpp7vLm3GA{120=|sTllkBi>rP8_Y{JWW(j+=;yK6jK`M`liH+5 zbZUj$MgCWD25c`-tV*H74_q9K!XUKqBYw1uhoi)#loL_ZjhrVD5~PiR1W}T!#q4nk z*qFZ|7D@;ldgAN;kabTkKAwA~R?1OXdVl(NoKm*xr-a8hdJ@|l2(Km~fKXzSr0Xfru17w@uKJwv68g?LA1}iQDx@ou4oeo#jc zmJYg~cYpo^LW&W;WzMnSK^)LzQZ>u+0jYv*E{_gk)sTMoMEt+B*Q zZ4z+r{nWHn05*!4<mM&iVy+wfpzrO-l z0%e#;Nhjn50xS9RAo}5*6klK_t2BnnOzvFEoa1*vvg)d%%;8Ry+XWB~ZAu(AOiyZIAEw|B-|Kg5Im!ifiJgY3wk5z-Ena^-K zhO1|?rfo`BjFnT|E7xBQrPlON-{nzNrKyfdIcDSm%MT?ggk*2i#*fz35x|JjX^Hjm?0Y2g-r568j?U$$UKm1V#c# z+-p~pxSnJmHBH1cmua@&?1lQ1W7}YnOR?gqR|V4gG8;7nG1h>o0cE>5cZd7!*L#2c zapab$}}ja6-_?P+@H z)hhzn4&&}Uy`jY2f zH1Yj7X1t8Wm%@Dmn3;gDc_cBLs{C{zf*0s8Dz+nt^QS@J8v^gkz5&ti)^zo=DtyjF zc(}K&zPj62x)_SW5Pz^3Yo%tkuQV75(Nxihs`ys!7PDi~RXiT&l=#WeG15&lL0v?u zkCd!ti*}`J0>auO<}9wXl{E`5v62AHZu8;ykzOG`zty)B?IWV*c9UNJwbfguj6-=T-mZN6nFXkx!-Z--6ObZ2sf@ebeQy1FVyW%Co#gJ|elHNs0+!f>CE&~kQTu5AWT(-ZaG}efcyD$XwzY+yHpsLEk=0)qPax?jQVsy3_T=ycMvXD z^)eznvZS~-60Z;IEZ&oL1u_LAP09_{mEyZ~4>k-Bdw&*@2L{%Fuu`7rF3sphb;wQ? zK4v8_93e|}0a38QUp*jUhs!f<;`p!x(gxrk#e?`*Xm~N_icPu`Bv`=)6evvHQyja~ zAIl>SM8p$a#1l7+S>kmQ?K}pfVa9*CZH_l|tCoq;2>)i9*a7TF(g1wRapE>%{JqV1 z5=a8q6nGVuK=~|zddoEwiOX_C92=a#3`t~_*3E|#pH&gX=TfqjB=Xbp|5w`L4TiQj z#rc1uEw28*(-wFCH`-$NztR@y|1E8?hu)v~mu_*l-hk09c6WFGL$~O+V9`L zF~G&ze*zaZ=-E;9Tn74A-2XwhK#z~1CqJUc{V{~a;#Bv)q>G7(33PuEy3YpP+>CC0 zg+}S2o8-}TBIp{f|KKl1Mn*8Y#edKiU0q%OpHPiiMk-8`?z!Z2?CcD5BNG6CJHxTwI);o&UvI z*xA|H*w|QGTU%LKVMGfvGqe9DS{N7@=PUCIX|O_-H)Pzfg-o4pw=2d0AOmX=!OGDJe-wNpW%U|Fdhs z!NGxXEm&Du|No~gNGC3eI77Ssown!+lOX)@4{f0l`7heS?jPEsSE{6DT?0c~m|$oN zC)Etz>YIXus-pibZE^Z6+F#;}pey2YfJvc6tDhd-n|l*API38qI-UY^c`xIvVh-yn z7XF>Kux@?)^-h51EyA|T5}*7*S=zE~dmO9S1DX2j^?#!+#2m}g*pDgYy*=zFd<-{? zTW4$M{XOOXowo4DBi^H{o*pXui$}e9{TI>PM`AMaZ?uK%f~CQK(iZ1?4E+f7#RCj& zu@7aSzTej7c2xg&vNv_fYSUv2Ow>)YlJ`H-7I=$lS#X>dmhLc?P@exqTd+lFS_E`Q z+^gHPix47Y8S`}-zetI>|1&isR`xD*>iq?+=MP0ys{etuC`_UYl#CDKH$p6?JG(r^ zBB1)T<&;5L#?nn7c2rCqYrK+Pl;yRhMHvgn(;5R;{Wsd;iu$t+z{AoF^{0ggVnq(5 zXXiW$pi3z(IMT|DD@xBW$PI+9btp2`qWN|(w8hnrP;#)L(&vwSCIK*V0M2LBC1YGx z{pIKD7mtvgPW(V+@6~SYl*w~fr3UOF{-U6Dy4@Px00NVm!Nj2t4ZrhUC`!xKefF9U zdigEuI<5+N>;2#Hmo;u2nHRL9zYJxgaD;j)a`y*I4>}27ssFY52ebgrl_es?v9rjc z46pKas8G^m_tN_d6D(>vMrJb*UH9sDMXgBYdWN{L<(C7aDHUH=W3pq>@x9>JgdY7Z z>GSsE=@Rtj<^1itCzA%|oLs=wpzbRrY1wbb`fz5B+VQuOA%y?(G%r1W`RAP|9N1EB^+p3KcUy7z>wIpm7M34+U%?a)~&%$_mj_xvFgRFRHW!+7u1O zHa-{8HEsUwx__1PtmwOVS@}j~`=ki>K`-X?l?&i&qR^bV++yUK-CQQ&{zfD~ep(+M z$d14eK;m8HCc!;yAwlBo6gckc=aNn#Srnh1(T;s}5C+KED5J^1NZeIdruqC}3B16_#{iNL9Un%qo)BjY*hEr!;xpsrN06HE zQ6D(>uo}fz$Gp=s7c?RujQFN5Ibp!BBGu8hNF$t__tNCcTprW;^p{@?`*Fx*%l%L< z3HCoR=H?&gdv|k5SWcD`jFc z%?G}8iQ#gi$qdiTL88R*IL;O_!D?SB0XIw=?+sV#3tC)pmn!UKk%LrhEr(x5D>2fW zECg{ZL8seF=x}BX9N-ATY(HVnpi?VMb^ySE!V0F$)eiY^>14nmGya?^g!~rhWl(ym z;l4VS$wE}(G?xB>St^JLT{R~gARS*Jfh1c*;Y(ZP1qZ>E84sm!xmtKY=AXKlW(BfNl7T$+hxCi^H&xwlSfazol$glhdtA(`NqL7>xDHi9%sj5^RRIC$XTS5##9YhGnL~1n zt7Yg|+)J+e4V`<=ugK{ajuhTDxs?c7Rru8IHoX<1!R=+4qZ>!W{%X1C5%8YLUu>?r z|DubC(kmw40)XYx7#iy%ac_Rks29~;##CvZfBbMayWZ|NDfs3*G0cx4sC>y1L9pke zc%*&NZC;2lj&@#YvT4xA2`vn_pH8(p`Ar^`UQOR)Zbxw~)zkFj!w;7?Vv(m`%nPR6 zdF=@waIy~#s7PbomngLvx$FP()pI|t-dBfGB_teU9hzJD)}2cl3zgx9!c<skc=6{x3KEM5Rmof>w2OEObD&E!fTph$t(^Vg#BeMXO3+N$ zpEIwKv_<=@k2TGUw}M_>{ELT)^(}v}mfwwkT*Sc-4E8^Ovy|@#D#I=%?y8mX-^KW`$Sxt{KSP*;=cx_ikK93JYK3ulv30*nprJHsy1$G(kyeEFGlLy&WGK6t$~0LLMAfYd{r(P z(#S`j@+qsqNOcR9q(#%SL44Mqx>#c;cD-fb z_D26r<55blSQ?z(N#uP^lx}!Fl`ic$;d?8mmW$P1aGvL^7U7G}&8>?{6^|{a1|GcK zZd}g;0rGnh`tRx1U~2~WOq~x7%}eXr;2PnCP3FPhxD{Ids>^h)-kc4#KcCbS;nhC& z?JupLiWZ95(tYj%Bb!zU3|?v+zaM?k(*1T=jayb(VLvn8{O+u#Q_i^iJ5}}h&S442 z@8D1wuzPXC;-aB2SNX+rUbfw&DF^y@a@FSwy!5NaU%MhMAyE6=jOWA4YxHp+x@=R& z@ye;hkCDj#q8?O7JrXN_9e4L<;C{}{MO^GBv$dO<;6OiAf%%H(W9 z3-)WJB24@lAaoJX-s{Vm7Brk7&}=89aYo&q?>%$wQ>sBZpF*fwWg)N`ct6eYyeP<^ zftKEmH*GcOVwE~u+4^Z+h=nuNp)sIs8U!cxlcEW6;-RO<1|00T+$KVos<~WOLp`P$ z-9@>pUI)ZVB3~$Bfw_!rO@rY|KEt*?Pff#-A`%&EtU@*6(Nb)@=o+>dnur7%_P51h zmd?+gv3hc$f>lgaPPqg1ox}6fD8hw_4givocmpGH=q?LM#Ta%|KsdH7<15psX;P-& zwoy$|Siz4XQp3%%(kLWD?K8u}0%!s~BmxT>qSX!Y?3ZyAZ6Fs&5R8J@27x<*BCOWr zZ4VDXI=lCRDWg)K*f#|G)4a<`i_Yth-ZiDzvjMXsNjzC#N(UrQVE1dnBkUYw#c85< zQmLNd`7CmW_INpNX_^mC$3h_#|8NvY&>L>p@|Z4$qqt)Q5l>+raT6G35|}O%SZEX3 z8WX4xcvQlPJn4yikVMXRiTsy|!n}zBv`OMml8A(pB+=w^$$iNj0Yg`&*88!Bm}=&THOx(^dQ9sLt99HaCq_$ZQ-2$ z!KLxTir6>LH!#`6Ts?bZX$Ttve#scP91KGqCoh4P+}h_=%W20yj06SkorO zv?PV{T>|ZsN z@U!pD7GSUB?@mV{LdxTb#}VM5{(^w39E4eM@RyR;bVZLyf!>X< z=r2Xxyr4T)EL>ZXGaHBr0(@Gf_QItkl`cEoyZEC^Y1UwgeuBw!H5y)EVvINehvEc)*WiUUgJmI4N-=Nl zlM%%mGL*QQv29;+P?52aJg6TZEW@U(Vf^#jcJd!+?Dlr08DEiJKo-7DIrejA)^OZQ z03wgXKNj{HY^n^Ht%OBZ971w19|OHT5Ft?IAb#MMDc+O~$uD@xYEv26P~}KQVSQ5t z+N}Cvg2?~^hmpQq8J%B{5?RCB98Y1Mg>_vM9a@c-@G{8wYfNO`QVFKv9V<^?i(gur z4XsrPzyhl~;_-iL45@vv0!G8d_+Zc(1Co_02)i)MG?(BnhGK%_VjP7L7|HfBGPe0WtssIPBpY{jJ%SdIh3ba)w!CG ztCk)8*tz8byvhj=Pad zf*vDOC?JXxhGG0)c_|px4D;i>T5wA%l<=EOOPAmdN}d!8{1c!2roOuPTe3UxBNkW} zhGZ}xurtIOMgD_Klp7E=uVT+4Aw69LjV$cZ6)gaKp>4euMHMd2u+;_Rr92zP5$&5Q}011S}*$sgO`E zm=FpEAR$x2urG*KNJ49JS&;Kh+^g?};pUFZ&vEdkLAfp8zt2B$OMo*i6HcOV+J0ki zk%G=xpvp*4$pNt^Hr@>j=DrZO?trM-qbUsria<5tS@ib2`2JzOE4^%>{<=(+w4)2= z|G0Vd_oTeO@hvw0Vb|+VHW~TSykvn__Nt;3*FgmB)Y*_~mL? zrg|MZ!;|La@s?Q?_U{MeqDM6XusMl-YPA+U&#FwC|9N@-^O3-h0LEXQt`z$4Hm|H7 z{CmHAuO|%|r@j%)kYrMDEReJT6E5ZX(XG+Q+g8??nZUgnZ9`BmXLm%_j9KeU=H9dd z|ID+SnW7j9u+7gt1MFO)$=Bb1ei4YwTIj9H`kA*krxk$H#6R(IK2LV|*GbD<{ja%R zy=genk2pOFEEsMY?r=TPLVxS8dZq8*(U$K>Mt`( zuAwW8bNjA~>jG2i9iX=hixuTl2aHPwQcEbyrHh3nrWgvw_{9MhjhpvN_lFkhRu+IZ zPwd#qcGs0Yy+viE+1rDG&a4$(=*l>ojN~U3J`DHw&Nfmbhfmp~VT77c8#Q7kQ zTdn+7jM^Fntw~Rt@q1O=r0c-NAZ|q9P!m@k<4wUInqQa&M(~6qkc5&>MS;bn5!msfK za@=@4#Nt-;gDub4osrb-ceC583p;HJFv$Zv;Rm~hR)6}57n>?Jq?tA{NA@5qYqtjk zyLx*`6~BJ^?Y%78Eg0NAY2Evp4cm0}{j9fNE4cnuX?;`BcH1w1w_1ODM6ssRvA2Z6esQvdDLh}ASLdWT*JM!Srcx4*~OzOd1DQ0GVx zgajE0|HDOS?>-ZRMP8$=@?2uqZ%4Kj4mZPFH+x?0r@TD6?7_x-7iix@{e5!mwRn6& z{3GY3MR))4kGo^Io0a?lNoh;lb`|jt1f-H-fC-tPfXGOFmSIzDuYi`UQKb|%c|M#*go=C6iYKq^?MJ)Ov zp7}CS@iJL4)dRra(j$CjaGAMu=?qCb6QsY`KdrRZj_B1+?+=u+U>ojUk6(jJFd)zvS)# z591g6P|L1X``u{Tt89_0-gXrn7<8@51+N+x9pAkGxgE`3WB+?MNdk)ENF}8vQL7l*g3@kk({QanoJA{} z;~CldU@RZ6^1Gn2CD;dc%b(p(MD2$|MLh06eB+qKHl_bcTSOi$8GQ+&IkJ1|M*lgV zf?gqd`_RcW%6`B^+{eVu?3;|r1Jy%3({_E^nL10adVBpA+psr#^rruc-t=Bm9`+HgCC_Q${aG2YFc{ALc&+(j(|Wv6FGoGg?AybhSXuhJGD%7F%uKDd5Cv((l6RZD=*f1UeyRCxe8lra;rS3Fg!qtU-MT;=!vg-RT;)rDftcX_(| zIaascXM3zNiZ5fqUsU501+Lj6Q#j!tT zAWEPD-4);kKzc{HkWYN91H{NttxB$M0qN|NQ;qDQIxNs_@0iwx6QL6m@>FQ-*CJZT zHB?13S;JHfd$!&r6Af@Ues_a!d5o1Oab`Ir7QpC1iJAiSYZG$pPmLbJAzddigW*uk z-!TqO86MyH?l&cN+-v^y^?@wu^+RFmnAs$K(Mq2rjc~-+a8e!miV&*Gte1KGK!Z8t zq(ttcr@)vBIv8r0`<)FQc|Uf1_o2?5uKPF{eT=xV@nZqXvW|WTJ)OzSXnCs1EA=0wO+Y@XEJqHMlEP_4d17qpS|5^Z>hk;1nUuhpyskvBSbpo z@uCZ9q)wb)XdcQsbg1^HB`HJ!LtE(SHazh?e%-J(6ucEX5jID8VHv9!D*fk7`K6bw zrPiD2;QKf1pFt@)3R|-{D=Cf61!@Jf_POp(8EZp-Ru7(jM2o$AXOD{QmD!m{#PeLE zL_0#CWEu?)x7+!CXxcjb(tG4sz7%RMTp@-_-xbwt_0DB47w`CG)2+$otXAPK> zSXuX;m<;pzmLL0b-wEdrM$^dI&doSFFpE{kl*Dg++{ZN(zqliJ?qH`=SVab>pL9j- zy4at%WxWX%H*qF=Hmj29x#W*OocI0I^Hy!{agivtBwstjabF)fW-6T1)H(58|CTx> z9lV{+>u-D5ql=9!YwtIF_8W6IE9Y!CIa*X?1+l!{&Ug&O-**^&Z?*2Xo}Esb&pw=jo&m6;{x{w!x0*SE%FU zAh#?IphDykQ(eHqA2VdZtiw7~-K(SM#I2qQ!%^A1KBz2eA!5VsnK9zh_6sc%#^*;M>Bc0YN$!y%*?UybszOAy9u6k2ADJuZ*b6-Z>$*VEI%z!|PBk>NI!4(&A8uj2AmtKa z=OYj2wlXIf_Sbr@v5y=^I0%v**uq`yzG9|75~LTB6kneuS*`AHNxMo7)%hNido*lJ z*UUUH7KLWr1@oj%my8AfR88k@EY_onBqKUi5u=yq(o}JgRjvukAywmz;Bqlc;KIzb zm2YYikqH*VSztth{$%de-0)Ld(@TF#gu5W zRfT>>6n}NRyytv;nM~x2L)ZdrEB_n95cRNA(Hj6**KokF4pj-V8mPI!n~YSoiXc&f zM{j?=$aUcDv>5a|Vffgf?n<8!qmDrsJ{e#s ze;_pnVAxE(dN2Ky@Wu?O#>>#g1paUd0l*-Y4Nu{~Jj(;$C490O`UFerUP3&_KL!J; z_Y7cx`bc36h99`fwTI!s7>=6KG#vD4BOsLFal4S!sK)}G*&j)2w?L6j3%@);P-Rb( zouTj}J47rm%UTEc5RDRZAx(tJ;ZU0PEAxK|ST(%)jSsHwRP>WwCCh2>-g_ky-P6KA zTeQ}fUFaTzGn)*);5LfZ`kMax-o_76HDdIbMmD;GA;T`Q~hOgukKlVG&JQ#eo0rsA~nm?z=o{M7f-eQh?QGk~L31~R6p zMuu_qo*r~!L!YQh<00d5`*BDBaF^mT7~nId1=4cWm5mJNBfMTuj&kXy8|(ahTk(#U zF+NSi!(m&@ZEdRfC67^y&d#%g+*g7JuVA~ZP*xUJ%D-M%03nRX%5()fg2J`m2#8?e zP_DTMd4od7vG487Ui97)5s>Sqr@kzBGcvj8Xxg$9a)x=m`|hP7>zNP|+=8M!6b|EE zje?cAq?8UyI>;)J{=>w(<(HP5%SytCs@=WXsv!pG``41~mabHLADm^I$NY_B9$?QU zjq~hYtp}&Wd8S!O9@nyXRRlH*?)e>5fdEUC0re{W=qZYtr#WOwcFmClFek)@7^UG# ziDRby41;k9&z*WV%>6rleDynlV{nGVYETdNVqcHG@S7EviR976t9uvt)POLy?-&-V z(gl7WcjudO74)Se^?M@+n`l1}+f^60Ulu-<&(3HYK0024=1wUv7#T!rbts$8UW|1k zUIa$!Z{pj)0?uE_PN)=YB{glAw)cr4pMVuGoqrz#FotW_F&AOIz-M+wl5%vAiFc5z zc2F2~P;w{{NZ}CJbkHPs(CR8t2P@HacQ9Be(NA?Sopj(WcQ8|QuBn7_W2!C`og8wV z)JC0L^GaO0opfIE+Xd~AHCe-p(4&47(Jo4eok2w^NSLBagriGTyh}{AOWddnE#c55 z>DhHZxJxRzOZronOl_A$G>*X*u1rIh!bz7Rs2fhGqLS7LE>q^$Z8m`6GiriwF)LyR ziX_QQFbXB^+HNw{PMz9r-6>V>weAPHo%$d(a$f)h!eb9tGGypsGU_p&>M;4F#2XAh zO_Na#uEPT3dK_SdEGzuQ!4NKr07%||zqFklUcjO(9}a{CDN?(%)JdzFTSyyvg$YXC zr9XN^X^HNnkvhNK%VUD1PK(EP$-bV%0?Pvr! z^ku{cnWFGr5y4*O(V?FGkYG&=JaZx|^O*))J~WfT0YKkP|b(5xt7 zlAP9#juzg0f5g4PSSh5nCOo=Z=Jh<=mRO`(6~3P)zIKB|Coq_s+?w}7;kdN9z(S)C z2yXNV;?Zmk2MtyEqH>%A)Eh$I8H5Ne2f6g$FH44(dumq5DMtQZtlf1~l<)pN`e$Zf z7<%ZAp;NlMOFBfPOF*Pc${85C8x^EeT0lUQQbOqx>68!zlvH8PeD+>vuYKb8J?E@- zo;7RM{Q1n9XX<_5*Yye*Y^{q&q~j}uKp56#dRoh(ofG~6B+{W8A?nyqiEy6ex(|Bq zXFfM_3_9Y-R}=#khcQw}u(iAHdo#UmC;SjvTmfV}K{|S*`}3#PkDtvHs^srJcTQ+# zj4f0_MX`@nW%pomI&@>h^%q)IzdFkgSaU2U$0IDWltZGqk6~#J<@<}#Ze)A~@ zHq4q}Ln|}0K2B%eNgpGIm@`HY1BQEXcF0Vu$iONwxs5i|FE!%a;ka|6V>_exYH7l$ zz(8zn5>qf74WwW7q)wt&X3%mUXXFZvgxUnYqlJ$+W(XxTb3aU~)+d~Q zCn3&=0vo-?2u!u9C)lj_*c8v|uEfCQk~wxvZ!!#Hu26pn%(z{u1(>Fv1KM4~$Q{I} zCZ{o;xPH;nY~y0w{g4=|99(aE$$1`ARVroicW-lO^&HbdM=<>{KgChcIS1YkiL@wo z;@Ued1o|oF#~X3x!ZDASVzjObj5y6@jx54|^*GVCku*a<;7tWI$269#JF__;=itkFy$Ky1DaTepnr&tE|gn%$P${L^3}r%j{`ue>>1dbgxR_Bhx)dvd(zqjsnE7N>-pYNg z8-^nNnG9Bd_Xd}sIzvi%=;hJ9@|fA@)nM}`s2fj=4SKQbro!D4%P!yvHVOJKEPgz) znv{5usjcYL0RrL+HC&cecFe0E%uBZ{dz3=L7vj3Y(N2bKO_A*`bl-Oyr zq*>~bC21;*?t~p(O(nU9BnjFm()jwNFg|E~8NCn{B)maUDf@fn9wYHOJ~cjAxz{#b z2j^<)Qo#0ap=p|OjK{yJh2mIKT1PghEc>0WTov}x=kb_kf!N2drujcQ+}_<>a`*zx z#EtBT3tPamRIcqzu@mMhJU@3*a&@33u~xY?Pjmx6V{Mvp)a8xbdVi>0aDo!$iC*E; z>Dt+v>ck20iIsZ{4UsN+pJT7(<-B$lPp(X70M|c?2ZJW3c^mA1#SH3ca+p-(#1x}V zVB3s$oTa=R65^+MiQ&NHGb!PFnj|j9Ue=kzGcNO{3b{LKQFxy;U@U;S&6uSv*S3w< zN_>;{a{wTYgpeps+75o(Qoz^K*wwq)d^peIFD(PmqWy<={3>@tSHHzvtqibJO45Gy z9si~k<08}S9F)qSRUM~~tqO$2Jn=z4xiClG?qYgY;z^|q4dG)r+7zsuF83t2K&h~z zQlW%Bkce`#&4Y(gx6E?(u|aNlu1(RE@Ga3FZhi*wz#e){y` zO0Wdktj9$xfB>GDyVCC2vCa9^Hd}2E(UzvpC$0c&wNL$9eC{4PC4N4%KHU~())Ye< zA6HHddF19%H7`{CZ4azbfw1oxfFM8f%umm{JSHi^{RteP;*SpQG+V&@Luy|`kxV=e z4_&|K_&+MT*tI>kHPlw{_l?G^9CXLJec>#)ybpu=3-=kshb(Ad0jfCj!;jP*gNm-* z?YjU|EQAjU+F6~ubr;`!)N=>UCMJrR)Pz}8?}SW(AXwX4_VH}2I&C>{jRAI}sO+iid>MxDHIdLrBvf;FNcYY$ z3x+nVc-y@lkG;|N9rG`Y*5fD%L=$>pH!{+X*xR4vVFF7r4wh1|hWlOZ{5-CKzQR5w z?RLsw|KAPAh#b%lWtW(Eq`1y9-P65M=tj|SlpA0sKjFV#0*Ppf*=dUj&xeR;{ba|S zd7rNK+r-c2j5IKxNk*PMACA(;8VZ&%Z4Ci+onUiIJM*R}XwNrIt#dOiOB$Bg$9nO! zPopV)0*umro^ClLr2EVE;3_Tvf<@<5K_|{iLC)U!&Em1IG~>Cr{U7yQFr_*rtj9gH z$C=EkG#W*CoNoHIE-X$Bi4(l;AHN=T zpEd4jdNf)Zw|~SuLHUO=O@J~zI5NXCUidso=$8-a%M?SBz{@M`shB(im>f(*QMe!; z4$;ep=LnOJw-x>PxV(`y?oTeK7wdak-UVtXp zrlO`ej3@x8uir_`|0~A>;Y^QygoN&z$Lsw9bOSUv(I0p6`o0Cf;f zDL){SDJ7phEXVW4OKNEr? zv-$3|cy?w^$=`MPWdD30w!N%ZM2nK4<6vI(>C zcc)6y1T)kf^%VWrw}+Kp0L7|2UuP-Cx!9}GF?WtT{0XT9&fybs{Bx)jh1uk(8AB1i zE}pU!Sr1BucXO~_lHHUb=V-f@FBO3WrIKio8y{65#{h~Av>D+PyHq~#tEn+|5Dkps zn^G@Jq>^^n7!&v6+R&wwN0#XG^FHoPs_TH>*DDk{PI&xGS+DU@uZV)96lyCyhk8B(pGdL7r?kYjW{U(&?lQEZ`8;2 zMVJVnT?z4N*4(q{iSp_udFJ*jjyZTd9R>|Iuge!hAjm6MONPk(1&GJTq01G{(f zEAK{hoNhwF>zwJg%}i3q@BZBGLA0HlQSM=HAGUf7bCY(u(`a)f6A3sxjADp;{HfdT zQ&pvcUM9=OIO&{GGaczT<;~OtkpeLdUDH?FePV62_xdnm)%F=0{BveNFMnP+r5xaT z@9k2vGr9cY)Q`xjUR=>86t9Tw7$aWO7Gp2P4eKD>Dw7d>cNd>*dui*Ix-(8tgC@u_ zfhmBD!4pu%PJ{4>{%abfm`AQw;N%a4{4)(g2KO4V{0VVD0QQnO<;1}@Q-zQ+o{zkl zL{VQT9IBe~6a+(Kfr7m_5z%Uuz4dkCM|-_^X+s}3e7reV#dHh8re<&?|r1a8#j)EDwtWvNM%qmH`6slfP1-=jZ3U%g!+E7FKa=u z_ia=%R{*y(o#g<7U$LfuS4K`fhKLqFr<52|vrYchjaJ4=v`xt%8t=}P3vskPsWA+M zUlTG!XbDyp+%6+i$yaZmZy#|tdHwv;KF2yowf>y&kj$dY0K^Cv*QBDk;9Ih}K$b~t z*xhK#^7L2*zv%etW@issS=Q11-sIp`HJbZw_yEW#&U3kpJ}$FTf}(aZMi=)5=J&Rw zv06#wnF@FBNFKvoV9Goep1a|YNOI>i@fI4BzK{X``9B#F@~(D zyVbTg9uf)9HOjcCYF-&1V2rmlgu;$EaAQ?K=628Z$?l)?{HmFV_*quk5Y^TgnNn(L z$2(W^{F|%H(pLjGEAGLecon+-Kr2VI%edEZ}4dVZT2+b@gX zYnMD_|I*%#m~KJnsS4)Mjx5cxe+A-W{LSLc+nupq60Szkpjpzh_m=PA?F|X~P7bw) zwA@d124jQ$bOp{W`7~lbWn>6A{vhWJ8AwX=ek9LmSiHru$J)SM9=^;VBs7G$_?f3A zHYE?+F{>e0&MeCOR$2FKOi$Byq_oauZrEPS@ucq2Zo&OK1HnzBDY_JyBBmwTzIGMh z*Fidm&m_fmdNNX86r6`Y*FGFh&%6~Z;;wUJ_I^GSKaO9m-d0;2piErT{iTY3*`2-d z`CPnf%P?ES{uGfi3x@S$oydyG&d;tdh8car^H#2A8YMt=>akNq%DC2m{(NWUC)yzO zsE2WqGr#rQsxnrxF@!`vXjo`<-!B$VIeod97-<(Q(D~-+q4kjpvw-{dvingdwfT}> zjlEKAhV4uB-dSnRH$^O6%TtwM&fimmO`%QfXw2NAtXErRbKz07vt_a>qP_VE^fW$i zX;}jmI7~9`Q(?5pQb+s5j*0mjlCYb1g+r`kE!}wkvGtfl@aqp%n|o^sj60gweW~Gl z{w1~YQ!;4;WqB=I%BI;oWF7moX{l!~q@Ev`KMm}28v9bBv_prn#QXBj>Wn-%yy0#} zU$?Y~M~SeCuct!6Tn_VPIfo6e+@;OLz&Hi-p*CSC>A`}zVBibVmnQ}rK}w-2pi+Cv z2IDuupZ5hR)8jDw$4@5`zAX7ZDTYQ)`D^K}>>D_OEq!RYeSS|Q8-41R<2=*yz4^X2 zdidsk|W0Y8)p0bWzU=5 zjqu|Xvdkr{z#l_h8!i8a4zXi?6-)K}oGOZ}n^=9^mUl}XgoFO>)N^>={?sVeC|QMc zXW!fCMyi>4d}Gb>3FTP=&CNaFejv8qCd1u~=wG6;Gs9)wUSYY!#oa-D z{_~Z2?Is$cXn%aejHkP9fTPTP7A;)ByfwmjUB3#YW(EEHfETF;vt1?Fw#C0giE~i! zTc!xGwJ{OK4DnED^ni#B#n-%vHYlh|mYdf=x9bMN*pYiQ6`vWrYmqoNH-WfMM4ZVu z|30NPD{-U)dafAH)n-^@jk;2u_7K+j!NIbS_2inF;F~(W{ntgZ=kJpl^i>=vYd7eB zW;0kYGkR@6mIstPqnWHsX$%S}6Ky%IN{!Q3lOq_6osm6cc!;P?&cRil%u>+i3Y*mi z|KTu!IyNy~#B8w6+=b(hHa5<87?g0}VH>(b;>g>u#(ObN;>SdNIQ+F^Q(T{IC~*BE zu&5ZdW|U3FaFWE+f}pix*J~>>tSE&TU|oX&K?J)5Z`p>(mIR3g{yGsi?Z@;Q69m0u zo&#np%FU_3*9p7{;!oU?-YgNgC{t=t2P`LrSm%vk0A&Fk*(df?UJirp;x|O>pE7z= z_mGM|*agNnWuCJGM#Cp`8gVYl#?lTF9@~g%Duvn?3c4(Whw&U{WQ5jE!Q|Q*wKzB!ux#BSg z8?18s8*#7rVLT(%4p)ZL_x*C{>bhP2OJk1I*nBoaTLv}T9Ub}t3tL;RLl_g%Mf9f= zfrp*gCi+q&-#EUAxPZmnqN2sYS@L$9bg?fLO=9bsX-QISeo?MhpxmUNKz@5S5RUow zzyrG~R<6TW3Hd#wWF1|hz~y{UL0r4;(WS0TKE6q%v81B{ws(A>xcpGlMffL)y5fue z8;G1Vv4@9=GyR5hXr+M<$0?|kVU$&P_1h<=Dh7uNl5x&2ZEDo2(>~-?9v3bG7wn4} z4&0HYD;X~LTPlO^JTPGG7sn1Fq@!t_Il*45d}fP5u`a=`+Ya9xbm2(#aIg$9E{KtX za+~d;YSmQWw*+@5x?~jTUnJ)`gxqX5{9pwlu&%WIEkYNUW)v(ltEo!_aAvD1Z1>+| z){pGMR`Br%UZ{y2zAy?e_tkwEQ2Njjsv$=Uj+tJAgbbv9*ooy!q_ym4L}GXV>3+F_ zKFVQLsXZgLN;jP!yEus@QdBYct)N_Ou9TL&TriNuiv}mY0D*T23oq^veyEqEYQ=IJk2i2_e?gbE_rg>m`Jpa-P7%87wR8O4m zr7}i6Z`e0C`lMur((Rbg^@+KMjB!SL+*gjRj^(S#t#vN&fC%G>3@h8V+Rz6m*P1|U z6KiYdJsg+$8ZKfQR%2WkCplU_K+bxptfOR;-QS#5X5R;5$K5MZiQ+x_lsHUvoBH`$ z(IBRDL^{r!pjU4q`8!h88Iwy`1JoI5H8s$$x*GW3w!eD&9`j0v*5e*4pTTxN&tdhE zirRBU{t@->t+nVj*$ljJ4a>t?r?c9=aom2cI_vZUh&GyA9n;8ERx(Btb_)AinSpQ-%^4-{H*%DqJ94b7>PH$A2qwLR9VG6(tA6_ zVceS=XUtYIzc<-lBAMI&4_mMeo{>D7)Oj?iUq5^j_Y@dDkdBheMv;F|&GI@L3w;^; zg9GU1LQ-oubobdmKU&wcpDg7W;bSW|VPH8NR&c{qt;Bv-I2|5Itd?0&yYmapkw;b}l>HEt(rJy`Lqks@LMd!>iS5;l+mRl!4Ujes>EY zt~t*qrC#)d$(Ni1ewsA7U0eGv1@riXtP@?k>5%m|(Wxzs$Ab-94TLZv5?2xp@D*>d z2QP+gH*xw$8P6lPh>xjmcR&vsK|)(y1)SWubah^^jRT=^(c|q;-2HUQ*t6yLY%P*jAK(t`A-w zJAqSkb`79#sLc;!V)uVYp47-rIz+6Vz?x1)U`Bdd>dR{CDlp^8aIfk5HiuyEyV7zr zYl_GgjE;<%`2 z<0)iL6u$QJUT3ew$?$je*W%n_SAG~gTsRGD2!Ut93xT4RM1v-2DP1`KEFb_*n~ch; z6(ctk!zt6^umh^%SqyZA<#vS>tD2T;^X_a7DB-tqsPZzCink1aFmy7K-!tDQkN%cMXh#%%6upBmGlxcj;*YJ0^H$9@T29mZ6AVV ze>HAz9Ybz)xkg_H6$K7I-mo@Ggv0~Bb5kRjNXL9!aqrFZ7R$JEdkVj6`W9UsfbCeD zv#!ym@wM%nUq05rIHh+SE#?;_*xx}c;4Y>~G3&L24l?RyK)R#X>4m)wo|s|PpdF5y zr);3^+2N_8pJAiqMd{Lmx4v#Nzsg?*-PE6h_=oTh*ND}$H|szW1Q*&A7k&(q-cc7^ zos+57V8=ffHqqw>U)nvwjfI3OqO-}iJTA#!1wPyrD?1c})Butv+JO%)1FIy>r7q2g zP{p{`U}w-M-V#I7__5(12REdqMj zu>glz6!i(feyHXJV1PDD!gjYLPL(&5?|MUfjKcjwbT_6d%)Ai z4s#)YcX)E&Xq~d)-2wT#AMTFoj;ivOqX&KNa+*tL%B2q+!j$DYbycp-$ODXUkU}Rc zWB75BJu38f&qK0;&4W7)pF?MnBy*N2#4cm=0mSFEIAYGKx&ma2)x>%swRp;8MsxkC z3u+Au*M&|}iQbZCA$B6Y>sw>LIDbjiG5jux^Y>!W*bOJCY9ZOrCpkEbK4?WV#n&7v zO9Kle?VF}ydKut&a9Vg@d6ull_s%hrAyD@D!H!;T>2IkCS%E*76?KMxq`CeM8|qG` z-K?kG)_tHE#YDRjVJj=@s>Eg~N6)e5nUh*rE94DcBQ%Cc4VFemV2uxW$d&rbv4*{M z>o6i4ffIj)lgRLrUc=!sk7$M=6}e*~l2aMnau9`Hi{oLAWx4l|k{WNhJ|SFOvv!S- zeG~F3NWUk2Md5Fr7Ca%uW!@)axh7*h_tS-ERv^gHVJLYXuwLsm$Gc8F%d25Gl)~Y# z^z859o;R&M$3DVw!rkq9_5fqI3MFe}A8GCTW4ZjA!_`$3hO!HqXXS0e?JO!%PY4RavCbk2`Ne( zbCrL5GLjAmooKJWP~`m_X;P+%e^?ap8Yi{`6bO2H^7Nf3_iqP7idehuV+y8&S6Ayw zAMLLCAx>c=`46v~&*H|8jA{F@@b={b{0NEfxFL7=TA8T?BIhh{75x2 zk5zfZI=QR%O9ho%oJHe3qf`xv)MSTjUQJSrym-!mFNR(v{C=hDTvyJcdyRHNsRH=a zY$h#)WAq9Rb#@eSbkp6aC_s7fHSB1${*{UMKzA_4#BA}+{!BHxlK^pLIH&g^4WX4Q zFC(Bcg6eZr%4^CfA@w*qn-fQyM2)^7b41e-#mjSAj@~$y3 zr9gq7<79h`o`PUSYOJy7-RjL<%nXS_LKj05o8S+G8zViD=VTuqzA0%7Cbl%abZgm) z2jE(DgW$IQh6t#WF|m7ncn$vhkQc_pm#z`Z=Z0|+(Se3c4KnyT>!?!bCI3**T6Y?b zms)K?Aqc}%MMqdnomxhiUz>^yp{+kmMMc1V$Hwq>9!~2e1f7w6x+oC;LAy=O7p2Yk zmoJN-(;@0Lr_@@xm;!HS-Si*|*1z>x33MZNw|`r_W-?aVi3g9(-)C>K_;B`MDvhf` zd^!f_gRvp(bG|P&pGSN?s4~Jh)1xQEhpH!{=tm8+G1q4Em{nw+^H^Pr&6VEuUY_lv zJwa$gj1vUgRZI-$s5Gp3GxzhZfTq3_sbnOzy30t*xrL{g(|k4My@Kg`c&ku@QS1{FU$+x)q_iZ0D-dl+#GYH`c%8U5IfB(<*%1H0gw0(@uov+)U2A}(^amtOyM>+f+Dcejcl2$H73iZqE z=4@?u?&cm7NeyKf-dWr$qZ^;!l|jAd*|hhB_HGuGrfTmdHVlTktG)Tw<$m{+lBTw7 zG6`dZhzP6hkwH-s7yxuCXU1^k#ky!iSao;~=@nlo|Gm?h- zR957G-EM~4**5-X>0Qr2_=9vjlCZsIJW`tg7&zO(dSgZN>G;@X?C~Q`;BY2e>UE%6A_*quVFCXtCVg*=}6K&4J7~- z?XCa<nXn zbZ>e;-8lSV(+06`z8cey^f-mH4N?@XI)Wr4UPFF><+m@93VejfPk57}gjR#sAS2Pd zb(5+&UxS4{3jOYg5=W{CY`xbCl5w@^WkGnwW4+XD49;z77P)B;AAZ_CMMr zm7I-Vc`1v~wY(awH5d`Q7RvlPDf`BPe3Rj_0qnTzlMH_+Nx#*!R#nt`w8ZkYM6%_) zsx8UG-OCqKLHjioj;hP?Gq2O}Y2Iva|jr|MEm ziw(1q08uV|~2O-DcFP-%Zq zf8_r(_`y4}%jdLYDsIc^kO}p}`_(pwCQRQ=O$b0KgRs)7I^trcq% zj#e5yY|)D!(jL=0_IAVNd+^8adIS3Xh|(*lb(q+L%R96VC%7(NROF!F!xaz$_x>%m zFLo!t@3r;g&L|DPRs1E&LAg2Ehol^}r(*cr_xE?rIioA2pcR34Z4xg(^L&ivk>UGa zJ3et~Zzn+LC`LtLqr`g!&PHvP+5P&xre!`wF|^cl33I+_&2OBT)ubQSKaS^For;<1 zT({15Y0R7|xWlF8-zFJP*jD-mJ|juji@6bbwDuc5K;{e|lkj*Bs&}n`cGQz|Wm4{a zO(&&2uK^v5wO* zHebAZ!8pAj13$JX!a{f04^4@eq$K+~Nk^;KK^>?IK?{lsR`F6DaSgWlq$^GORmQ6F zCbGMSu}THoI|(7a?CfAMxDK%l4^jixWcQ42`Ac8JlOYGN;ZE7sE#{Fw%zHQHOCIdbvuG1bk^)ruU^>-EJrH)m;NG}?r&(9LgZjS%-hlYlI#BtG&Ca&XTvig>P`h@#t%a_D&1XA?dj_h_E#)7J9 zDS?$l8hnm?;Iph|cl?^GM=gDc)%#x2jfz)QdrJSl1UvzM9OU`AtBP5pgNdfOKtJfO?q{^erF;^Yg6$@C^cd;`S(yL}MSYF`@YT~3 zjN$EXN-n`+ga5MkJd7l{4T@QsHH66cKo!;|_3-i|RJOvA+cz)-@&S9hRgB=~(kY}rNxaZ#IIN1M4u zY>as2?UT5sN6;1F;x1uGk1){@{3iUztN|N@>n^d+`cAAjn~wlta})8#37p@F#P}}s z_=IH02iK5oFLoT3*l^CF3MKjc$z&4pLWqRQ;5Sb_34<@C3m@rPI(yTPv6ss0vp*2u zlHm$drv$zfNlg{nr_^>M&<8&33qK}Jlrc@-Y_RpmuH*3FQ(8kZx+Fa4KAZ+qn1NvS z{VdN0AtF7!B4$gyv+rh1_{Nu-A5Ka414~;VN_}6*s{WEr!{;;JWGPgi({|czsSk#} zzbO@ji$_joI?bJRic97D&X$}D*N7|agAV*;o;Lj(JSLSOlhs(1r^bY&YJ!Jpic;t& zf;m&h#~w$l1;Gfo*1@S!e*6SL~UAYya8 zS^RmtO0J|@4#*zid;er$DE(e4D(EsL6yqaU1t#ovpeGQ+w=N+H0f<^lsNjx}g+59o zfN#~uXweVBR)(gplk9E4;i`mZC1mJg@)J}iv#Pk(%%SeDKa8dG`F?zc_CF4ONL-6b zI%F|}{P`r68G4a41pbHvY={H^8UVxWbrx(60gmnB2M~8azJNWID*{n~{kNnl_r~;~ zE9-(5jI-8DTJl(kjLlIIq%dKs@KjX6j#pR)OeGEiFzZxh0CN*<6}h0ynYNTTS;Zzv z^#-e^8Nvc!6hI&{kqj3OEKQ&Y9|uZuFupPoaMEW8XCoU|iM<%rdP=!QxxsL_LDy9J ztkq=WuRhg%GBwb8f8xf4cq`wZ7M;QXIt6jLaR+&IaYeFz$jcIH+fwjL5LFW^p;Za} zIOpA=*1Hqph}i%wg<`F>?4O70%-Drm%|535eS-k9SD{mzFJ~nnIXYqiI_~B?FH}ix zRaipKS*}!AC;>pan9gs572XdY?*rhQAk4Q75&+P2$<_q*YWkXKz0M-jnp=2@poI4W z!+m6jt>zjyst-uuhEq-OM@En4EUwRVd~t`JW*LC>jA}1a%3c2M$23 z%>1`p$*!LqCtI1Kln#DowIcq&<_L7ALP8Fvaz*PBB)8en}?7rVRJ7|^Tel$t~cBn#$2JlTbm~64<+RJDJ!auZU zE~WrlSy|{2Fs=<*3d#pe^V7ELEUl~v;SD-!)rf^%mgTr~aqXs6N zpvPa^ACI-;_fli&Kd(Ozy)gT^(M0=Rzj(aQEus#opTgZ;31UuK0zaGLJim8931a+#GVsr!C=^AJ zW*YI%y3~_LFy#M^I%~wZX5vb8xY$vP}s566y z`Dlj@BPWZvuq*U&u-wltv7nR~b0hk-Jfui|q>E)>)Rk0he*DyEJa0$T_h3oEtEiIJ z*b3T{YUzZWjs&NWxF@vnUt5wUek9>ZCy&r3<>e>1OCzQhl6)7?M^~v|CF0IQ(h9GV zck@-gha^AEPy0oi_BlWO=qw?^3C9d4h4DHAA@fgt32$en;B}^mOqRrxESb(Mh3hO8 znQVf_#-`}jK7S0*p;N#2vryol>OluUli zll+9v{FLkb44G$`44E8AXL{lFvz4n9GRx;wmKk9KfTKN*!F6ViRa$s`S!l+{a@P=!XD?v?hbmTQHUx<{A4 z17pR^ml3oXgk3L>zE&tLCiiKBxg0)teyH@7t@5VV3RtWPdoJnL>)}*fo$|XnL$)R- zwB}h?O-dJ(s03ONT3gdqn@3+;u~^#{`sxM!tIprA`edQqvUMYiwL@KXQ_pKAWb41u z*L$Sp*I;;%q4iFwtG#iJpn=P_gyk)amYSRzp zv3}vyoGFXRyGxim5ahRQxCSW3y*}z>B7`Q2;XsAS83Chq#QmqypB2%~ z`cI?(??e8sKW_)Zxf{GE8WIVVv# zgCV||d2};RRtlFaAq)aY_f*JEtS7FQC-UT$@SLf25eRD)DqtOt`t5_6k~#igEc5sX zIEtoseH;W()FKcTebn!xmfkTfe`LZRURh>hTp`Y4?nNSg|55_6D);rTl5H*xL@a}P zflq~q%HFkOe~q91N_fo5xUKwfW`I(0?NR|zYtLw{JPcAMxLm=?76%7C2U9j+%jG3z&DSdl{>1 zWKoAyo7g@9OVa?22WJ{iXGaxtbGyukA8&uWUBj*;`z3ii-UOzPpvm@or|pk~ zmp=wpf8;5i()66_L?X;U()>z@cIG`}j12=QP^_ks$+jI9V+uxj?JD+;4i=I+ygAm%0lrQa0F&h&g z)g^WSXXx)MW#N+k7$OGQa9D3IXXN!2G0r5w$WKMec=J}nhmto6gV`3I%@iV1LE#gt zhU1G>jy@BAwAh^>RyAHIANKn%zIgQ{mbRc*usTcakkh?t+EP17Y<>FMbE-DS2TgjX zrBoj%cBfJi!f4lZ!+Kd&%Sm!X0|}^*X0;a0AmOwApVh&C&nQZB+Ht54LlVk0=1kL0EC4+S)`<40x2$?Cz(p#N6 z)4zkY-_a|N#OTaw=vvAhDJ_q_kb6p^&~>&y`|3eYs%b$fI-`k~u@Bt)+K7l{bO55f zs2K74!ngv*{%a)~y{_?Pd?jrDWb1Pgp7OAg2uHv;0>BiL>#5rPE$fe1BAZm2y-RakclkZxVriY(>#j_!<2r(s<%9gh;WLsPKb(ea9>*L)}%MdHo(xvWJ&PRRFBh1`wS4 zj+_3~el@kKb)si{KvK3EH$XTX&D_uh?)_eqjsfe{)ZYm?*jGy01CX?T(0ILw6K$Zk z8YhSEaqV1ffMENgA0aX$U%>eeu&2r$%jcz%TOvuCnDtSjPfL zoq9rf#%)5TP?TiYzgkQP2n=Z+pj+!uog_)KR*9x=Y4Sg@bRjDrkk7}-h*ykK!E2pV zrw9m`)|0vkm^F=N(37y@5J{5gO0_59(_RosLrull3`}a|)r-#n(!_1EW)L`9p%jKv z=Q|eAeX|ns{f2QZGAkuuop`4Pka&YJLTJirgVWFFZJydZnT$w#9PsU-SoTBm{qjxK zqxIbJwlDJ%)B1ro8tSR+3a?K{X_CE)iD|oyJXbhBU&-t7;&+yQ%6&p&WWXN$bp{d0 z%a8u3Bz|>QQJ>KhY>=I6J7!Kk+jH*0XtQBBZAy7GlQo2Y&Vbip)9k{H@(B0EfDEmoars zX5xxetB{mVMC08phB8Tv~@FCvputU-W#hNepqKTWsT=>_{_2N#NW2NYAgBAndl84c8uzak!gGrd^#4 zP#;dM?<-@jACcb+$25YP@&^ev@u$-h1IjrRIEY%C31X~vgQ4+=ASj%`4@fj-?6n{- z&PWt?)S{YTkLPMlD6|79o6J8VzG%e*NPQ*>WVYQTYAvR#bpvb7>T3<{n^LTMi-Ya} z`3hI8=%_Y(z0wdZnvSkqO`926%V9i@P-Gm&e#oz`Y#dr^6!TQLlwivrE%&JyZP|NQ zHhAp2t@|W!KR%kk+Pu`9h4AaJZfUBg zu&jlwGyXSTpo!amft|+Jxn9`N81gyPp{4t%-uo%x@;X6q#|J@dy?@g3HeYb(=;H?e zBEpqD-QX_FY<)vuW75i@NATO_qlVxf!qt<+;O=d~#wQa=t7o;r?+za~hOH5%bA-y=c#~iNNaGLa2y+mG3(Jad=5Veqg%7&&G4G*N2 zvO9f%wzkJ%Gohk2F%Zx+sPG!>L?RCx=}5*aJ+;oGEUJ;1!6{UPQl z(KajLSDy5aSlS?ASXclm;A$8L{zEwRm5l>S##JAycw0Jwb18kBT6_}5!5JY9p?|v& zMb(ZVh+0Q6`cL*T28nG;e||C^U>lF~t@$pHUK*N*4bBVrN|>)ZX3pEkqcM*%m+7Ne zgVQloDvTv8UbDuf%Jr`+utl4AESk&(xp<0v_=NjpMxMK{&hAPHP(!96L^j6;Yw zJs4u2V=G6d@O2awHHeC79YUeh6fJ!#0tPHmpOn@ixinFDPs|)}w}1cCI3)%m;*yw? zu2AH#zIY^7OcuEJ1E56_hnEjf5B?dGR8Ee6`l0T_v7Sh!)kf;m*8D{lmgZq;5E2j5 z7ER;t);Uu|a=xXi%4po!HP=Y8s&4Oq7alUS*MwCBl2$sOv&Jd3lHs$aMjUxQe5j1A zez?W~u&Ypjz(1J4FUTb*4ud^zZ!xzwx7hoe8_doB5)-(&{^z*8I>%fcUR_;XUS9q; zCV)BL$NXBoKKpTYcJ}Mnub)4EVosM%Pfsx?C%=!6F(>mUCnv|)2S-PkquJZt9nAOP z+r2)_&YORG0^h%X|Gy;#zWs+3SnI`nUBIlAU=}j}M^a!4GyM!R8IBqAUzz>*U!*_@ zX2=QC-HmyhhUqiHbgN?8#jvEnjq%5GBN35JDG8quux2h(pI?r%aB+@Uk!nfkdXf~Bk=Gc##s7Z*pz{|8Cn{}m%3Cxj8_#|W}xxEU~PG#F-j3>^iAk^}=M#1O(TFz7#w00fKy zfo_@UN(A`-8xxR{lKTJA6QH7^qNJoGCnqN(BZI@?q@<)IBqT&cM1+Kd1Ox>5`1mjw z3=a=`!-GPhxVX4DI5-dp1Plg)Kp+eNRAS!;006@PAQ+=|Q*mE3jBN4hjmv*w0`XF? zm49IZN&mtGe*Oy+P?X1F0@_$i;Q1`iYgdhY>eqi?|4*1e+kWy>sana$NGv8$iNyrW zv6#Tu2G^`y{V*&hQ0f(CTljy#1iG=9fC6psNpF8Fh*h#X#AmA~?M9PXTIxTTz^|#^ z=iI-j-sQF0&O9;RGLOg$aG7Xw`WGhfxYJUtY;1JV>$t0D4f;?{zW)2u0B?S~@$OEn zNrLrwg-g25|FPrN#v{VwM47shFf4}5Z^7t~W0fp#Zy$x#AHQNYBw;E+(XlJ;txfdw zU@!obXB~+{?Y54BaaFHJ5lQZ?N5eIFHqeyNkh}meF&sk17__(XZ%lxl4;4esQCYp2 z$T}#DR5>-K+AtW1R+&6_qY7T`|DA- z&Xv5bxB_r8Nb*~U+$~doS@T^BU)y%}G`tj~bqo^9w^xj&_Sh?l=c?VqvnGHd!Rk%+ z`5+G3lY1|A$pW}7pIEi;n-sm|%q=KnJEJecjW{7Kt8PCyc-3TriP^wWHxqWRcxtZv z0S7mx)}kgE^gX{Ros9okb2fs8AE<5VI($8;$zQMh`bX%iipZ%?uPTRA=O4STy`=W? z*lM^qs%eyzJL)=Y|8Cv3bgRMJ9^t<9sIz|K`-}Izr~Cyy9|~W2)*W;`I_ZNwf*#x2 z{Z;E%{w0e$A`X7`Gtv0MPpCTae65Df=p0s$VsOQ+D@!$!F*$YtH)_IR^^~q&H5^)dwR+%1?a=GLS2F=Ii6! z8HS9}zyza6~LWU0jTSNEn?V#d5VU{gLKiwltC4b@_iI>%QZu{Nsm@U!37s$1#(= zLRLq%jAM4lI95hTl98E^5gq&3Gm+6TlMp3I$R3$l*?Wa_jBL(*zW49`JwPBHJSAVkbZmYQ7U1I7C{5)JccrN?JFq9!Dz~MOh#DIS3N$q4>5` zNKnyepU&(%Ca7}faO?c&&BrlH|M34X0dh71mRt{ISOvvKDbskOO4Ef`TF63&)R};) zP?b4>IpJpHf^RNk&KVEsS{vin+X=E`@w&t4Wc#O~50$+R`C{B;=Edjo$aEDrDy zqEQ@paw20ZiegirYd^MK2I@^^4&Z5sxM-&36uSQ~0amwYE@)T`gUABQUpp<{yO`>@ z;C?H%5q;Xm&)Qy}pNQyt0hpaD>Fo8fzDj+CTt>{_W=?jKYNk2qoyMCNzdp3RCCU$M z;^}zL7gAKQBuwBp`G1(eH4-LJhoF316ixwP9-IyNXC8(ANG~v6wlT1af55aTD;QfW6DQkyYv*sqhMtp~cTa|q<}y?qF$bcve5Xle!t?I9lfxfRglMOe z1s$+zBKQ`SwI1iwTU3#8?npubX+92hXR=L;Qr)@uedigUA2&|vVU~_H_uVyLDLgG5 zNPRteb6f8YB1bam#e#cYGY9S$8zRPYp^&4}u2qdKAMT&o%5Y79TzvQeojZp*k3GJ2-P|Ron_l3DBNOr79DWAKmJM^~bCSyu1Rgw_xdyD*Df21=0I?x@C0|{Z;xJZWswne8@seWvuu;G)0MO z>gm6anZZV9R%J-Z{WT*0g0`4|Dz~O5wds>3@r>cZM#$z4s zVOuR`i&uB%_J$87hC1SWY`Ujrnn>&dA(H0{l^MY}BV)DSGi1>9)xq4OMx@(cpT;`~ z3PfA=uWMc+>wfdUHji3Y`D8zUU;0ut5jFm2C+$r^OvrfwU{HA@ys(d-!Tf~SAJnjC!s?tX z@oBZ!jpGx0zc==QS9)C_%aiQ4H0$d7m;wE2_GH^Kxuz3ZuQ2|cMa0{>61W4y5Xm9q z%4bsgYuO(ubBFEJh=vhh8?6Xt%ct#se98OzdgGZ5AW zArytZ2sd~uld+_9)AnWX=7(+d&VFb`f?2}M-Fx4BtG{7uzx4m{2s)dd%KNJpE8p-! za|mE8=K&-#TWI0!;n1uoe(=p0C$Wx^C40Zu8W+rLJcZmC3qL&j^BGt6nX!JYWyom@ zA?nuoA|gq??M4+!{gff*r7<64F0A9a@y}QbFqW?>zsHkjX|9V1-+yfMXYND#$rXBp ze6PNi7l--Tg1l4K7>mSi-r4gd=D)?f56jTniVUf#MFN0hbCReRNgI$pOdcy+e{QaP z9gOIF^Jw62<+$|^xxud!^cn76*%#Z3J3SJS@R2|$qjS4-iJ|wC7))Q-_2YrHu`eet z-?M2z(0M0nU>k0^qzl5IKpB%6O2Yuz*BeJ*l*-ZM;0v}Q#44tX#Yn~1;jDdMnJidc zc9pW8iicoh=sVq-cszdl&h8ycmpfN4?tJMTjhFs>-N5%hZ6G|%-|%abs@O4Lz6$O_ zAvcQ~9Up(YJlP3THrvk0XxMK&zESeSB{GGKpDw3A^1cl5pzE*5Z^Ot_$Lf%#s2h&k zQrCbM?BU+M9bbY*7hz@aMR4B@=7S`yi?h}c(N}>+i_a7>4|gaY4ZM9pV-Z3r=R3&k z5Pt1>(3cQqG}F^nYUj0JO0@WWIp^|USUzX=^DE4kN6Y}s_)2M*i4l1x{y7I4EA8}R zF!Tk#fA~kEFwB!MtCTR~&ta6NjE(FD3mm)Azv4fVINU$Ax@EeJ)CSsT zMsKa$1PIq26bNGFxg5g;LoINVErK58LcYfVX3o)^M1Lm2Dm4WvdY&RG&_57%_y{&txQLIX5ufW4)E__{0I(X8 z@)!>W5L8PDsKo+JA2PnI`|h8OyMO%=-#a2d_(wwM<7DLHNX2}u7I*}b{1`<+E(s>$ zA-1>U500WhEJ-?ymXp__8+{X`H#lUwlURN;QrS@);lYVQh(*GGyug_nc#U)-8IbxP zCh#>?Y%*0ME0uJQ%0fsbVFI$hQzeNCX>woFlul9=Ceu(?(}hmb)GgC*>7;9CrKXgU z>A0k#C(|+SQVl0l<**4Sr3qKEUV>V{yLh@C6civ?1}MZ&yZ?9rHFcPC)&GYH1ibRk zdKLKfKTIIx>h1WWkuS+b`OS4|9eSNK_kRXhBS=sYiNg-R%@+IRW2lLgeh5+h< zp%j3SLeY~Pt(6n=C*_V4SanZwBc_1}P8f{o2Fv z?Oon9nrgv|?zb29?quA5!UT`b^i}*D?ffCzjWACe<7S)9&%f2qOKo?KGWx633Q#4itIQcel zGe@SZB>YE-c3FYWu3PU(fp;Kc0!vw*3?Ih8dRyKm{m6bH@(%mDthByNbJ6ooZ0RpF z`0Rgp0VJh426j+I;c%K+T$cA%q_j+=yj-_bd)Ipr{GMr(A4N_H38g!_j=(R_G_vJ> zXUl4NT;8Gk&h<1`H^tZMM^Uxndk8(e2#JWoz{dhBf?rq6D88GUD&hKcx6qMBQ(l%U zmWwCWFkS?aiKwVmE87lC**@u@#|9X1L&9?-2_h=Yj(9-eKqq`1xI$({%fXCqMhTCU}f)AX8rH? z64@`2LHRe?KM@o^X^~ZO1m@7)Vu>TrNqr*6<7p3g;CLiCCGep(|!bx`n^5l`oQPIr!{TmMPcPx@l2!#1$ubUbu^0Fa8H?XgcL+(PX4 zW(l}`H;<1waeX&1-C?a%k0R0ogC+G(dh3mUlHEb}+(FQmR)PDLXzK0Az@e};FDYsS z-7^4qmFz-J527IhGDsvt3ROooqU%=o9gA*Qc6V=3ckDT%JR!`m`Mb1Ur$ML;H-Tn! z0n`ivtxJLr5mcIZaOncvlL2~8fT6q~H2}QU`)dXgoIU-Og1-0T^YEJTs*AJkRlP=a zvSxDYkICiC79&V?K34l?nw@5Non12d1Bzh;-EV+e1BrMPRO@o@`(2I!J^29{>MtAd zyd zRmJ4{{>eGwpK&lR1f@SS?mkl!Iy0I3w6}ktzkhB}`4u5+=v=5e9hQ;N;0q3G-dSW2Y4}=k5#hv%lz?Cg};#B9>0FkcBm6_Kn7cU$t|f z?RhwSZmtpZy_k|1JbzV!oqb@jVr^0JY|f;ARtOG2s-Qhby1ej3DqNmeVz>m?+dmhJ zfWaJjKFF}2dRBbt7FVJ2&N6MtB7NS9;=ni=5)zUDHJ+Oy*PYNe2vMzkr*^p{>Q36v z8*N3AS>~K5k|nYRo=R5$Q;$qn&;(;=D?JT%CfLKIa4By z6;WnGp~(j}u&aZdu@cip1{=D0qpSqza>WLw zX~p35w=LJ^q4-8o49cfg3sW-^`C<=Wdhb!Ah+6DI&TKbr?d)77aQzL^q<)SEn<1zd ztH{XnsXszN<#IbP;dMLPKYccB?xpjnB7}S`CNbJR&CcUh?(S` z$Z-(Inf#AqabM|2Qh?ReTm9x0>Mm=5{^+mlIS9)J5>;9OPX;{H$}B`6BJX z_Y;G6CwZ#>@Z6_&KcpEDMthKCMc-3%|DG6m9xBZp_d=+aNnAiR8F8VX7rHehzFa@B zefJfaNAh+D*A`#!;m3J%5J0u+r3`B!IRS0bUuM_22mzIw=P_VIWf~qL=DhJmk^pf> z@XdMRU%0JTU+oeo5et#CgU;fqCAjxr!U>@U8m!IGt(~*+5Bt{!_gB7a0K0|@C>6kQ z!^$ZsyO<8(P>FCR%qQTO#ckU&jriN4&TMYrtHur;iKHsOW?gnAk z;ve?xj5e>CtLi(w*zsfX%c~I6N_{^OTD;3;ArK^_^HGESX6~rA#-7@A643&{$y-s{^;MZk(M~~_y{`JY`mgCSTak& z%_d=dR4@3T8*O>5cEZdi!PkT~z`fu6y%J}Xfm8OQaap@R3{Nc{epx-#b8t1Q?R2TA z@Ds5Xa7#$@AbWMe|2iseEzMTKmU}9|3S<`o<|#tapT6L zy2YzPRImDRvjy#qG})}{ zNYd(5a2i6F_}Q!fUFnTs2+aquSw@Pl-#>G=wQzd-1{&|=O$;7q+W4mAKZy*N>A<*Y|`^OppMdTu+8Aw`eU)QsO-u{_mKXv;m}v$Yz! z+ty{D_lr-*I^X|T=u+Gd;jq5Vmg5Qap#UF%e)8i-%!y+d9`2Z@W z#TMhz>R&byply^UL{h%(uM5(j<9vZip`)o(s+e1auk2weXYSOTzo>E zQzDs{witJd9qx%W5yhM5RAo%k&__e0`1+GK5N7GiTq~GJIyX5j*}%%!-ZRqWd3USA zPF136d5omsa);Zfv2pwXbw=Ll zZL~pHU-Ir2|MEv?X1a77t9&&K*4x_M^nl^%>l!-!22X3SnvOh8_K)&rMPJLN^ zR=j2XyV_!4ICHw}5rz2I?nknF8H(47XJci1oMMT8ld?3&1e3n@->P#UwTQv6}(1 zA+{mj@3y)O=y0ofkL1qnIm&lL8rTh+WImv8vGRM;`t+^|_7(ryEyxt9;b3Ave?EDa zw1DLRd-C$o!4AoQeT9B^m2@$qZPkF{aqcsP z90~s2SBjn_c`ym^|8aA%*kT^kzRHyIsDcX40LI1a97HKs=(04a(dJ9!GdmL0SZiCT zqP^@mixFWA7Ej=5SUz^g1u~ZQ1q4_3G6PXlK0>9FF!nNb>?2d)JC51M9a%R!7%z?? zuY9H~d-F%%>Mu6Sw&JPtwIkq1764Gy%qK|d?E^gODiIj^I~L2lWq8P=xB$zgO`%Ud zGh!TR>_D4Z(h9*pisI$i&L*>!ca-051a(pQ0u(oPLydh2*B^KchDzDV?{-J_e+d@dVZl7t04 z={V!AyFEJ;d1|!WFgWxnSD3Q88u%K%l~WSHk`?90iP|k*t+gvx5|fM|@vRdU+I~%t z!tFbX>?M~`Xi6gA*BBUveN?*9&+Ow_q-c-{O`jLVEwB8@=yp6aLH_pji7iBh_t^U* z?dm42%PS#Lj0@crvbxeg=^k*jtX%)gX)UVg{rYLi3iP(EW2)KD8`i9@o-&~^9qLyml_?h>67j@0L2jH zGs}LJfWjP})F!+-*=RYNlOjhL@vgMp1O61YHdZ zAwa?e)F`A|m`I;lfG`GtuKNQl)@m#@YVh(Fk|aRcr$*HfS_7hcxb?k|8sb$IM<&(` zs<~Os3zqh36^dvTPH(+lL@MgEinh0kjkb!fv`QSb-T=4#hY94U8*D^B@DG>6frvN% z4#8;4(H`ie+`O!vJe_A{C)o^?mz>zVT6Ltw5Z27b4jb?7Pexd0wBWH?x~)SG#&L; z=lLs6`h(;M*vUdIvCSqo@+RZ*uNW_i8w6Q;>PRmDBt}95aE*T$t8Dc?<-xEo_amkJ zK|&}6ml|24-k8xXnp;er4_)Oy=qmXoQEFU>0IBUrYOk=Z<+p|DeP4`q)BP!oy2D~ivA6B|zWDTA zhU;Z*_BEdM#+NqP3zO4%h0CGIQr!BdsQXfIKd_qp#8L3~vFFt@IVzbZXhkxta8sJwDBICkxNNgc)5oa(mHbXMLG6G5qoiU@WFlWRq2`a@iBgLXNCx#ff9 zKB~aKjx=m7SP>C)KDeLWeX!D%a2(~iK=B0j({m`w%1b3DeUKu!52iIpxr&Kkr)0wk z)GA`5o}>3ie|)!oo6;Sb&>O$yVDx%q0Lec9ftNy(TKl1BFj&dWJW zy&0BWB(uy2zw!sesy~dJ#a(5GvH@7w!X08mxG`03XSE)s9$Hy1c|_sm2(;0-I@SP( zA1De`@NC3BS)<#s=ikZ-@4#BjKJ|Ee~@^j zD*1Vk6{43cA8MB@03brA8uVu!Mm(5?=0A;QOhsFGMOsEidh*o1-59y^spjZpJ{WI2<1>=MO2)$}LQxT`8*DbaNMR-%`Is4^&BI~vXRH!rRx$#+Ia?_I z1VoPx&zYY{(Ug=X5|OIFffm9;r4{)OH6Wqj5Pqk!6F~YTc*zn z`eMidVen%lpx7LR`(ui~n80^TMQ2LdPw)c-T`=NKY{k&sNJ+ZND30Ih3d zRDAI!pfuME*?$#jnWa4bCdV?P92OjmYuxVbDYuMxZje$HW?C2J%mXpgv#QIz_81j$ z)jwK1x#B5)%3Y?rg?1W;Co^`Bi|+2bKGFB)!Zaxu$5qkx#n<|8{(pu*twV%m-ArT0 z?P~WCoEJ8A)H0foPLxBDWsh06T)US^Vg$Uvw==^PTxZ7q2(Z?XtAGG;*09O`d*5qp z?ndHXGD4+%ahIdo3ypJ6Ic+nJ$=s7ET#}&y-BC6sMoy3Bp7)yB7SGQ07E{XzMRyMc z3Ct{9o5i7KlanJYC*)Z&BP}fEj@%0^&Fmm0wwJ#B1jzkpd4t+O9GK?^$LxLBfE^v} zWJ)kj1Q!j`UbtR1&LFV}9bf4GJOyvW+9Gv6?oY|#$*Y*}k9;oCAD?@Y4VkZ=6@ z`^Z7P^Vcq<^A4AQaWWW(0~^B}?!qUG4*NjOjkZ82PCi*?VZuzpM(%Px9zWtxX`&pp zDjP`A=?mkTFtvVZal3OhHleA)w=^1u&Ff#)_E^2G9fQ8+q_eu@xRdwvSRPma`P8l2 zN3EBSF`ZSA{wM3YC9c1Z#64VtJ8L;5TY>`ti1H8!L%JREcM3>cdfu7NXVD!iKSn&I zUU%iX_oNAi*F};hF(ob1EpM&A7|2z$gZkM~IF^FGytj(7b&iyH$>6nUfPDbKfa?|m zF?WBfu}sA$i`KWoSehXr6VY4%U|biG1pUo)W^ZQSkMZDAKx)`^zrztyWGA$;9bH@p zT&@^bY}eyV@R3)s6!~1?uE@>8k`G1ji zl*$#@2t_zLeqvFmnH%G+oXf+n#~x389bdnpbqjV1{Eoqq-$GW_!u&BEO`YTsv~Dd? z^N%ZCyGmR?cx}W-!swhqF^+COJ=_RiKb}oGaXp3gR>CYZANenkfh-`zrcJj&71`EK z>tt{|BUaJ2`4bNFP_}dZr>)1gD7T&vnCw%jV62qFC)_nuv}GN|-R7vLcJm`M59gy^ zi{;&U5>nzmM{pvO%g{`g)2RgqU{o>Vs}#`n zG8p!%R1|3o;LD&+8Gt$TfRcLe3D#Ep_}L!gxtHDLr< zZPIut-R4jnqOg*;wd#&mV0|j=mM)P7nc_>T|NkKw`K9>08 zw1k{`#Q3Qz9)V@@wk134-n-AtT<^i5&Fkd`=8KU zEFaI9O&y@>>n&sBBk*d^Y!F5w5;VOUS_!+(uhJPrtKt4wgBwr1h(7PS$&6Pc?^o6U z7Wa{bjuJNX_7I z9{nurFQYOmg-)`A4kB9JIl^yZKXxO`Lij&SAQ}m&{yKJ`=koB2U-nT92RbU|gFn+S zmU_q60Wy|wl#qCIEY%X37J^fpKq~XF$FYX%{BKXdk|65{Nqep8{g`-oEV`3-n>VQB z0m^efTkv!ad0Kdbk%S5GAT7D-?#1H+qmhy3&B-owKA82uK;r2~T=1?htfRgd%|?2_PZQ&=l@42#Z}8{?~N$7Z@A1-WIbI=MTu2y7YgsO}Ozq zf#)w5_i>v!vs4|$V;+ccCNu~M0+12Jtsl7VFCZy9a)st7XUrV^oo2|krdD6`@_dV- zX$XhjQeEXmE5W|BIZoP{*9xu>sFXv~$rHi4unP$2} zr#Rem+(zgNSors^9|hyv&VLav)`^#YiShu>?jp5A?ID3jJ^aZ;LrWTgw;jhIWL)mN z%hwstM#2P~lZU=v1+-JeT=pD#H21`^Bp>S7@}=K&8ZNioZ~IOs`)qIf_rB23|BDI4 z?!Dp2+N8-%CoGDjyg;#e{n`8{I#ET!1TG$vmVQ4z{zcjVm35!4^X_fRb^Rqud;cQv zr^VI^EeHG=1#!CK&N1>{8}3Syncksxcj5d&`pka+JEI&$$)`KpCsG?jBus#%|C*W9 zRp7vDk&=0pCdAQs;P_eL!650Fcj53IDUFr)UF*%zR$M2k&o|dj#x=7>SRZPt#3W_o0f@$1mJ`*%Zh$f80jTrd<_B=(nP#K4El1EgiKgLs{;Xwnd?ZX@ zB3nAWWq*!&ee|G1RbkCp7xK9%oKC*50b}A0=JQ`n`IW!UYeK8Sny-Jmp*jkR7I9up zweTptMs%BG){0iCkzay|pY-vL@DUxzo2l^58cFi_c$6_qUEPR*xLM`_NNFcs^S11v zsYa*1LZiQMK@15K(BGetyg=l!q@; zOJo?G_JjH6qg`4VSBamoS5+daX+`;;R2f`X7jF5XFd&0S5DQ7HiByS2@KUPW8A|6X z9J2}%uN@9xgaXN%p$See?foBnt}HovU~<(hO#tHtUM*lFRq(I#L2O3ZtGp*w`mFWk zE)1MUVgSH0DY;AcjNdYhiu(sSURO*&ng2&klw*)&=T%oXCjMW}yYMRkMd9eWTFW1g zhyjODC3~d!+@2j=`8PqEoy!4tGeGP`$tS1dD2q`uwHHGzAfenaO5ifj6i4DU@o)h; z(_~6n5C{<^$1SawDleHpLLHbrYb7TiW!oGA3GHokst4%3tU8^%@|6r9(bYYaZrPWT5^r1T&&Z>HnbRS1OnVk ziWuY+;0!Y`Q~M=*I9c7R5>!AZoDZSEcLW#DUcX|n`B#0BGk#9#!dIINdzAN-P%3+W z=WiKXahH5*jX;cir1UU6Mhai(w0bQV=of1?1NyI9I=95ikoIGBukmNW0pe!aCl3Yz z#WmQiKNn|2Rp8mH;#JB-Y=qPThBUpFTWY5u%tJY-$f!1;hmeYvqLSFeq$)1h%S-}T zj?4Tc`paEibO6CFp3{Py?G=L76uku+ z7>b1GhQXfF*a=YMZg1j}JGDt#oT$G=yY?_mY=4B+Z6yId#-0KJzm0%(ZwHr}4NYO) zpF(JV5Ho|97J48q?cd%?W5KHr`EL9n0`DSZVRsYLg#UmBiTEfwJDxjC@D{Foo-hW? zVj^p%L&&}EXuc>Q#yLhmrBg}p=KD7EJTJn(Uz%C?(M_EPrXPibz1rAK?HD8^BC~aO z9gQ2%Oj0x9Y(+dB(%X{k8a(|1x@{?!dQd*UXv_RGbtN> zxdYCJI26nzdy^R+XcVYUwxlDmKb^x$3bl5x8>u{&P5)R^s%`V`4js&7jyIA#ccTkg zHpz%-RHG0k+r(6fFjYXcO4SwgAKx8$y^r`;>ZtslD4F(HK5r+!Liy=?ko-?NdnGdA zKY`{z<>p<=otI(3pYg&kwA269tSj%TrF0CHO>}S>RSZ~f0tw#0SC+y`RF-AGL#r9y zO;+wjzr9@&L!rmdZfysBv483qjSQN@UZq{V~`-ml(iOuDPaKd{7WF4A^0 z?mYRPHRn}nUf3i4qc-zQynXM+xAmSos(V2kXM4W{YHWlZUJ9oJghN&rgf3{7fI66} zO{2YB3D=m^`^{YZ@W0)(jp=!EWnOOLMwh=Fv2UIzE8UzBkL1}4T9`lVkCndaVQ43o zbLf50sHrnOHFYRU8#kdOjnPg#t)Azae$}27Px#@yZDe@J`#qTT$Nf?)_I0muC%T`p;gD%F7&Q1;8qDbLTc_k|i(i60^L6S?#niI*FHM!D{__S_XQ)Lr1QwYC$6 z;gcEdw_OJ9r$79Ime&SwZk{GiOT9mimN?b-F#BTlt8ax8;!G9Kh*(W^#bF!%(ptr= zXDoI0%l)YrClu50+-7%j`Ukq+bWDg=!W8o1TDQdgRXsySa(_L)^F?3w^NkQ8_h%Nr z&8CjsR4==wjGn3b?Yb32a4rRVUc7#lcxbzS>z``R57nlHprRia?R8Glx^Tj1hLyQPp5EcUb-Gr&`0ak0 z_zDiTcNDTqH+LEKs%YyzcWm1v*T$duncaE4?YXAedBcb{)rl~2meHfd>C>1Q9hB7^ zvsR7rJYewV;}aeo9-i}mbD%sho&O9BZVEP-0bl0mAn%o%^5aH;T` z(R&e1$UurEV;mOdX?eGNALyX-{~0a9qSO*`YAk#v2-}>iVe{xBwU9^)n%3!|v3zjB zBE{V|oz~okGR?~88glLV93BrS#&faEYLeD=Mw(d_kUZ`(9v#uXJ+gismho3;Sfb>`C{nj!Wd^bJ#I(_Va&#EQX zprlL2Bsyp0%6`oT%o_C(9&P3 z+@O(VxuP}Bzru`8d$4S@z{Ea5BY$&6FVBH3cDWFtlG) zCVx~5yEZtcmS|yM!8I)1dd&oS8_+XtuYfeKzIa$~bO@R9{|MACp>&Mr` zCDxWcw~<2Lby;gJ_6|e2U1UlrLI~^+OabSBAVjc4kCj}eq3xD@8>@Ak4b_a$CCK5_ z@u9w>Mqr6g(FBqwx>3MF^oO96v7l2~{?%kM1h_?DA)LYDj&I;JC|)DcBEiq<&Xsm` zg@#Tv4N4#rq&%a}N(=L<=L=vWo2y`LbU@7uJ9y_gJxeXlm~_;s0`Yb`IeW~2oVjh* z)??#a1o}c>kT>(yf!IvR#QZg=do=Gu*UbVuA@VRG%4jx&7d{} z!|5Q^ls3X|ftgY~HtKwx6A449H(g9Mf2dlJ=?Ew2SU~PNLmr;HSja>1G-BB+t z!=e4xb0vCJ3B%~}Fp(V1%MChS|A@*Rkq?JuA1=!@+e4AGRzl9JX zo+s+C%#M;;t#p^>Z{CsL)`%NcVdatzZ7zL5)Lra+S|Il^dvOV;cfp- zs^AHV5bOY7P54!0i)fYeAfI?9l)}?j;O8D#tFad?AvCF7+6gUaffm;mO!BPYln>U% z?ouoLhEH#?qYRrbg( z{r<5OZR|7~J5iPzHul4V{)vZVlRJh-1lKsR;P$YB(}PgpL|EdVt(16uy}9oa#4Y^6 zg3Eb7H3}r(J*4}AY|)fG6V+2v@@Kf@%xI_odT8QC#qof|i4~tmkp=0wbA-UD^d6Zt zd3Ih(+!(l_>HPtB6?=UJU9tA}_;mYcqBdM}iU=X>5i0K)2%p=2pfDG{IGl#zG!o_U zV8g0?4@YN2GvnAsMHcv<1n(gqa?@akoH~bPqnoeDORuuZEKxg+p4e8uA)#CKH!RZY zPgoV%8#j2+G$0?AD4a*C@khHQ86qn%1^h$i z_f@P%rOw@B5~cQ6K-gkmFDJ(*v@fdS;2)xHdihkNlu?9tpR1WiBnX>NjCnRC9SZ5w z+G(Wn8H8?fn}39OC%O}V$*fyN|lJHH>1hkweKJC9e~^lOcnD)T!>+R?*?KJ?ArS9 zMjDvn`zjZ=mnh>W(f1yiv?#s}n3$=n)VE#nGYQA;mqK<=OUQ^6X!}%w^<7zteI-}> zs}HHm%0>nM3bLesV&S`~?E2IM`H}z2K3cl+jOu`aT1xcFC%L%Hi#3=?d!=f&l*aN+ z$7JtQk=)#umFiEW&=fv$`*TtBEoFfkYj+R$$bDGfNMVj|+&Ib&Kis(;=Y#&@!#yvx z+xk&g2F13Ht0|SHvX#`nFOAWA3hiYFn~pN+Wf_@Q-Rbpwxp}}n{fcEGoGm;NLnm{m z_o+TN#Is_*gT1{A+0aOgXiM&sQB#(pHAWiNd0nUOxT4`~6}M+{hv;iScWB?^owyxpzkJ`^ zXxL=^Z<&FIJ!YCaG$ji+Wzy^kld9N~%s%{zgzD!3@?}YC`_5H|n?QpMyDiNV;tc6`8+2?P@S;uLk@1Tm7|?e=(ELhGyH$6(cKG70gcBOR zy77C}VPMT?K;`*>&S+?Ip222(`{u-BrLiNTFjiRa$r$A+-suGCd9r_am;R{zTD6+` zty6xG-!mu4@GFr=*rZ}m^KtqhI>+#o1O=pnS-U}xu=N+|TZng~%pCThA2RQs$`r{x zFh(@@4q0OQXy(NwlK$4`f3H`5p$%KaQ05XbR27)GCJaqK;w3ruO1lPcdV4MiKrl1B zd6NKc_{?u{_L=y!)|1D0As-1;$>?8uv|JCpqI9t6<&EX^$SnEv?7(dd>17nw{7tEa)Fo!rN;8wg2mmJL z1$D2!-uFKGbxYd0!9=NtQF)S4C7~U(W!Rjcsd~Yfo#+4EwGWy+sp|js{hH=v_(nAp%KUg} zB_aR14%eSdX$QE&MXZ}9a+OHSOvAt^Lfd1yrB!L8>rHn;UPGIG^r&Wmyx(Xrjmc zpRNz)f6(hc`7*u

&<9TkdD)wCymadvkL7b5A2&DygaZI53gLHq=(SIXL+2=#8O} z>gAJ@UtQkK=*S(v<_)EMIE{!Jp5^?y^10Y!y4Gm?AJRf< zzQG`}b6$J^NNwi5+8f(#;&tsju9ak7N_Vgw{m^#z&o1uJ^d0U(Q&*!8TX`E@tZWht z4-(`Ggt21$phAWZSD&>Szhw(;f6}IadRP?B(<3(07p+9|Q@3Y4!nvJ6^v6Qab%q6W zZ_ZBo^})=;h?rjP#y+p8mCJVveH!%QQuYs!B{rCJXcz)DL+!iu@v-w(c&HG5}L z#MU9!jgoRJN~L7bH#37@QNC$1YbzssD~x zc*U3q=ky25_)BVJ0jLNQUu_-wS>j%?f5#!|8FELDO2p}p&piFf={hO;MTTy|l3#tB zRu(hy+2&wJ3wa-M^oWSD`1f2uW;T>k!lKA`lIE9LByS+?RTplm=9no{;N=6q8wQy* z9+Lf;_$OrIzZOz-B)%5$%I*A8yH6=aQvf*c5171sP-Ll{?b5E$`=WE9stlL7vGXk}Yut2Q{6nXdt8#!~Mg_hFes&vO9@^qY!>gY8vEn4& zEUgtUIAmD6UdeX%TR>s%yMoN@Y^e+3BQeJmIH-l^?7v?Rl57qqU0%$RON*7-9L)y2y*Qi+ zdhv~Mic_`V+3X8dqV375lVRS;`kQB5r@w<<<(+N?cLg7@NB#M>|F`9aJB?x)YhjjG zr?s<->1UYsPUCUy`p-&K7m=)5=P$>=jt5Q*eaTAu|FFRK~_1E~$U zfA1KX+0u}_z!_nO`;B?4xSdcHFvY(}Y2(y5)!5JYNlN`$G6Bn2hKS@ZdO-W(nFfb} zVf3x|JWAItW$bFV6PxrBeKZ5DZV~OH^lWP_T~vICQVVaQMr&-%-LG~oM)#~&GUiGh z>HFx7o}#6fufAv{^WzDNK|dX5+1TJ7Lb! zE4)MvZ^|1pcGR_)XzD3g7v1#)@|KO;Y;4|LIb_54bF8z3T%kX*DZO#BB7A%#Odztf zfa8cKTI9Kxv`$zrU+@M665fo^_wde$XSjAF*CIvo^~d-!=`~3;d--wfPkUxw)Q!`h z(UD-D$DZ=!T-ArYxh_)Kjn$OgGzO0P9WAV|;TzW;Nc^Q@UOb7oCm*fG;s!qwDA9@z>;rFwbjk-j&v}o~cS4=BY8JvZ6r=N`W zt-ecRmJ-%?D>Ht&X7>8=7q(UakM^lAaF3L~jf!j`T4WqU6y*tzQ4$>liyr0{FBR+k1Q*%M>30k94#F*mfi-@H zqNH8Z^3lVVZEm}V;h{6wLl4G#{^TpIq#q73V&Y}sLzrk!d(>(5L>uHPOBiS9j3Bp; zoH}z^#K%uJ!d{xzk^_3mXf!VwXJ%)aw!cxbD*p}9Lw|+{?_gEV@3GMx+%B@5)YPjl zX&z&ipxc}-&x|lY*DLQ4(IiC^bji9>?w%$peSBQi1<_ZUW8@O z$fDnolJTIyqJd>u8BpAJ;k#KT@^9Ju z&bJ?EO;r?J>CGBGgkP3Ty+u~m3WAeH+j&1*=QSNezPL#IdCjcgrIBhttBTy_u-@hH z$VK+0^6V8`46uf`)P2beQiz~!GaC&Ch_thD9X4|mCF-0L<94_9%VxP|uhUJd*X-Q7 zMV22WQsV}d5SL^&;rqG35`dfK9A-qw(wQ%MCMtwv2)0`(%)qbDY2FTnQOhCLqh1n z1dTd_e-MVGb_2bfzC!Yb+ZlQ8KfIm2>?haWIFTR491bqwd@fITbbcTEz9# z@aR*XphDU6<*TtL-|MjtavFrbBZzq&)~uK4$<7Y@t**CBdPMxKc}&tO3{K~779I{^ zA&`V(EN$7@^JqaMHrn0Lx!+fBXGSJ&gXa#CqVrVL1m4y?CJ5tj_E zPZpS}Qk}ahq%HBK;tqKn)v5RJk-sclM*A#OFOBl8s-^UAZGIsC(>%_+HS-tnbeKHV z6yCO*8)#0HpDLG4;`c-isMCex4~gGa2xtwJ9@?|zY$MIs8Rxqx7Gl2gt2wC$Y{LBvl@ms z^lVi0WXa~VjlZehr|4z&EY8sGgks5}-QxR4ILk*qji->mt6`g$gD=yorBOi4uR>u+ z(MdQP%$0YwhPQi*Hv!Kk<&8|QM!uHu=&M%k_ZO8$6d*^DLJT7?dZd)4XpkT&DGxzu zajt7|q1?cf{8aw!+*1WCW%~Gz@EYQ5@gUSzIR+rmG5ZZZ&`C3%`Vwo8= z?0NK(#&nl<7@7917~df%tStA3-9(zb2~U3O9TRF9b3BY?9|{u}Ttn*Oo6J9ooAfS`?3Yi)<3L2g!ETx3eir(NNb z0l8A`Y0*Cc7=V3qRVKSONs0?MD#{Lqd^bMSI=Q9S!!X!m_u@CA4enBh?sAGA3PB!5 zx=$QRV)<=DP>P=AP@Ex4sQ#g6O0TC)P>5v%D7sW4bDt`)BCZR~K7-*Vg|Fd-BHI`) zWIb{n#kteYk!0x#S6rcHaf55SeeLa=GQbLYqscHHm4`kx8Sbfk=%R)@ZHIT-6@9yd zd_URxh#5NFq_#*6`V^gR2k)?BKdk3zxS96@M6@J{{>Xa=LHCXu?wudr1O2_H{w>HZ zv!CAO~xOz*#wD<1s|ja zKD?rGweitMUv-1GdP6miKb{7cPcSQwgn;NmISVzuKd>tKtLOOJYC_Ih=KABW4_Nq; zS-w9CpKT1XdCToaA5Khq%uE+{Y!OzI5@ul;^6q&=!C=Jl)zJNkQ1+{l5)U+=v#MmX zqE$`N&CHmmsgXLYk78>ih9)q2wAk*nP`XJp@d0g!8&ed-GU~Zy_+n$Y)lvAnYt&i~ zf3h4Yb4*6hCPW!v(E^s(0qf}AiO48V@YSXI=wMu26Yl8|E``(;Kr&OB;$9rZ6)45O z4vv4*6kmB1U!#;zZx?4EO>NT@^YI8PbriJvHt zo03Rn0>71#No4}ZP08oM$?qqlbTYAC6G1nWA_mx0s9h=aT@#)kNpdMat7Lm7)covq z<})dh=FgU@(43l_nfhD_|B%frBsfyDTZRchl4l z(!Mk%dSrTfA4^BDXWl%P$2LpH+Y9+BtrPt-1q0ZfOq4OvESv(?4_#g zMW20t{E9X50bBGv`&{TRrA`AfWP7VG_{GO9+LCdiY z-XR=dDS|l_i5jivd*5_ZwfRmClERhcqTLTfpm2BN8C_(kXQY|riw%5V2(3M37+ydf{8}-yuyFgfn#97DX zu+C#jK#i+QFSm=afNO^UEhA9hPb1CiWM;K{gmODTgbq2UPGzTFO|>oqF5p|O)chrB zkgN3Op7g;($+X;_oSB{iwO%+s{nZ&i=6nv{cFG1$4fg9*)XJTkRL2r|>?kdk!*y zE^@o8&HZSb`=$O3?mmBdK5u39@BrZKb7LMRGlyeU+x7?9U(RiF&r@kH(R9p%BCftp zRjFiDt$()+VeZ$NTQt&GI_3r>0nT9ns8DBsiF6YeDS?FrD*i=QmpQ$Q#r@fp2N6F; zW|5YBQn5S+^KBcOoq#xocMrqM<|f$T#%#L)3MyiemgkAr9}_}z`~liD!#P`CBKz{q ziKAqj^)ENu{^_Ji8<>Ry*Gvs43`k}Gec(Kj7u-O^0_2puV zhDnP#O^cov;1AU9#qMwtcLZ+yQl1_One#Jn`xS7(>pHVd#lPc0EvYuY6GgkXAMr~M z^C!@rTj;CFL$JyJSuc<4VBnCP+gx-j9aG!DINImXGThJc!X{F-<^FQ^7jyeg1rF6 zhHZz@Zu^slsmvDS=2BVpbEaqD&C|wftZ2hA;k~0rtN!k>2_cSuXl52yzI8nnxPF0{ z6^zGKdbDb7aJJn|;mL%C!gAHU9p|tAb#-soTs5LK+==jwD*&dBYAoD&|1^`v0qd)j& zB~xjm*()!SEFY|rVV$;)^+@B_r@NK^AT9wI4;VrkCyoy07m}f@?9B+ypzENZw#@=98T!mI38hCy`vg-LRsxY)?5ajM=#Yf!=!M$^8EcY;Z-Cfp?Q z(M-N0DIr~Kg-tb9F?|%J&9Lvl%)Tn;F#n;C}up)m+VC@9H!Hh86~aq6Tr16s%|Y< z-q`JAjXYcV^yTW~eY;c`nx?k@)u0fS=^wp~@<+tbt<1}jA$n}ud)F?GqdGsFN?+x# zVo^u&uBbvJ{~Sg|N@Dy<2w-4CQQFrP%ls2hG35Of<_`t|HYfugGJ`^%vrbAzjO$XL zL5l3|GCBTE0o4syC);QLCxs{Ns?tsQY-b)+j5T2S$y;bU*(krD(w=%#Ly5a(x+GEXH15Pv@m=f^!c z#!!ffhm49dhdh7@Bg7u>&06aI6{Q{geaTcuCb zt1&tjd~`vm7v>-5yeR?ib*{svZi+Ta1FIR}%?;5q$9c+$rq2(n0xQd%f5lI;~0EBq?&NOAT|d=6@;tK7cLH!9Xje`=n@O>xz(&vrq$jJ%Fj`n`k}U?EBs*u_S! zUR{I@H_v`{sJ16?f~) zg;e1Wx7wlCQPGCMq`!S|0qycpFAVU9kU>dT^5Q=3CASzBu8sEB!t!Ns1v*_Y1|DVD zRsQzrw(sdf0M|#MF{(w?R2j`VqR^#T)m?SRTl)PqcRkgM5ob%flfWSg0=H!^t#iND z^x011$G=m!fV0O7U>T*GbSW`B>+Reomzz3yX@}AO&GLUhvi$#&AN@aC{-?y#Q{vfQ z;_08Wv$Ipu`;&u{lav2&{^v*g|Hb(e4-O6w4-XCwh=2YN57sXBc1fcDe{ud7zgPYz z=l^T`Kb-%?_V&g0_lqBE#LZ8{b;5sf{{P+bUtL{YUS1|HE-wF<<-gEyF*QP*c|n{= z`QKUo8N}ho#D4#|@h|_=^6$+ic02xK`L_lV+w_S|O2m3;Vy)1~$jJXc&cCLnhFGot zkLX`kMyygKR^cOor%ayM`WZW(!q&T6htVL2qq_zfzH@itW{K0RaKRhm6eo~{sZ}6x^ziS zPEJNfMp{~0N=iynQc^-fLQG6dL_|bbSXf9%NKjCapP!$Pj}M7N^78WX@bGYRb8~TV zadL8UaB#4(v9YqUvaqoHf3y7mf&8H)$^ZXm`IiI#y#Bl8&q!JKJNZjuEJDCI*RZCr zJAvUIR|}@*Rc|tz!hNt&t*1eXuvJ+i?*40&XHqvlt2GA{4qct-Jmz` za(;!pYW98b{>JQ=#<%kyJ!*U)B%OK@^MsDvFf3EfwKut2TzH-B&g`em%XjAbo8SEy zdI0r!a`wFL##p$;FPk=p`)i*Awf?pIx2GE+cWzaZMo;s>m}zE>nFH@-u+*~4zn1@S z`i6898vB1*{%xv{=x(V6lPv!aVTTZST&K-^#<~69Unvq#!j(_7$S)hBC;vB=zpYZf z%NSf9MXek7KP-R2XQjF<#%UzWU-AiCCjf1~l9A{-;+_8V%IAs9BtX<_Ud!%W;Q!U~ zf3uq5Bpv5w3l5mXLe|o6uLZF-`L}2JX57}I((OVBB&TE@aJ(p4%qn@&`#a0YSCd1R z%$enXSpJ2HiW}>%PQ%5f$aL#anIIvyUDn)n=4cO_JWJ*>>sQapynNJ7*hICEXXG7a z)jdS<%?j(Ah9G(tr|h3MSP)uTZY6s*KGvNYHWfAP4QoG8Wj#|H<#qZJq~dHccrmK+ zf|9K``y^ee`pXWRv|F#DO;z)!!wm8KS`EkT_q#oJ@+v=UO!?iI56#}WcSYC~wuu)sRu0i`et`S1bvx8ZlR(p=`+MN8oDw#muMSeIAp${Bu# zcZFH|6=y0M=R&`NM3JZevHWYHcm#YPjf|YyedZjh(G(1NqS9Dh*u{Rhz=s#>4_u5A zH~`!bJO^C-T|&QfFCI`I%ikwwOb8qXNz|XwYH7WUtxP-hP9bg1_H(MF$F>ToD@m3= z-NUbx`2T77TcfqBDA2Kb{dZA)Okyh|Aj~B8U(4T97UASXvi#Y)QMrq4iEbDX$j@x8 zDFaQ5dVlfV2VbbnZfZs>Uh^vt%_au*bq0eF7!>sqKxEEDP^cj8?Jd{}Rm;Lu{*tgR@LQ}771zy+9QZNtRS@`x%@VT7Yx(-Yew?gL%07fkU;JCHK3X(-j zTNiTtTmT7RiuIG4M?6YZSNq1XQ4!QSl&px8AT1?NV?N7nP$yy zj;D@e-ry+U@yCO1E^Xb(pG{OfWB(O$pkH~20qoVk%p3HeL>4-#0JUD?JQD4d$n?h> zmXh<7_I0twxh4dT>u@F@a8&-F1!z!HFmi0#V^YUgDuS?My33zs#ycSCmYL7r*R=n(4t}k44t~r!zxS}> zW4e^~*;KM{^z{$2)FKZ?zRdq9W0l^jPk8)E$mLc0b@B9bJ=Hz58X$3U0l>Qxf?tuxSXl#GyT0=&S7q>z7Q5p+%Ki&afh2U7ToQz zoUKk3*?+rG6u09GI#Ai)sR5R|R8LH7Jvi?uiO)fPCDEBq@^BvZY7O3(jy+?d;1K-e zW54&ZPW4vV@WNa3;2ViwP3Iik?TKIf=LDYTXgBh`X1W);oHGxID0Q&Y1{iSn3BA-p z_?T*ox!ZE2Uruzr%aGEZz!MN?%=N?g^xmN9;)`Es5w#_Dx{%KvFZTgJ{inrHDA=My zGYpBaAp#>Z7fz{B@7Kf(6verPqZ32=N1%_sjS_;mw`5UU?wqHSeODE0WF8{~D1Y(N z%M-v7Ff`RI|0wP=SFK_`IL4`i-NdM_+K1++qYk9E$Gp8t!0+abkIIv~cOAdV?oNbG zpUxc(K5CPzM(L1Uj>~dzXUt>M6Sw^xZx2QbWGbQW$@0(Cu<_6l9&(i8VlaDYl((B95s*8maz0_SUNvMc> z?HFWF3p$<$gQRQDQ*0;?u5$F2bpM9u;_w>&0>8jhf zy-n+qnfsLVBVq^>xOW}>MJv+WEz%YfSt=NGbB(DIiawhN=J^MZKm;ctidQMXPxz{Ka7=9qAAl7092Isk9Ke_=6LgeRerSjn8H6Qf7LFTWnH-k#8?O5=F2ydvJb>aRiRAbHm*huLE+HxGNhJSn-002l3h&^)rYAZiO5ERq zPch-{t%Pw=<}H7iAe!zG5}~t8=eWR_f8-KZnpoABs11r4VMB}BJ>9}FQQ@J7`QX6+ zVEl5RGcEA&8gMq5d~uWvu;a;;@!;cR)_e+9b3A1;p4uJ{&BD{Lr!c(1(9 zrLZ-p(7#FHG6LN*gmEe3d6b_C8$E-G;jf^>$xFkxkDkH)WAU3)0Qt~EA__5#heHdL zb??J`5NX=VX}b1l`XOnCS!u@2X{O)Pt{$hEv!`1sr(4^n+lHjuv8Tr%Yy$D=F30Ki zAu!3?vC{C=TgnK;F1bDWABH-; z-bOT|DM@QU012MMWflI;s(X`FZ{&LGVZ_hpH;PF2;zkK?*mE-%Aj?tkGg*p{Y_x88 z$iOglk5Wzp`-`QftdUrzyRg{SpSUr$-1ZR41y{PCXsSM9RvZcAe~U7z%}UG-!5vTJ zoIYZrSIVBc9W!H}SCF1H7LwES=_L=$qT0}4PweTR+j(GPrp2bbjpN5B&7lVL+2hY& zkhR=^s1#@i=dQyaf9^JZ$XSJ@XUVB#pGbSq$wFQ^oK!K%UpMLf$^h*3C-x-MLJ zDKvaID^E1LP%%DVpFZ#1>m)cIc{z#accrmMbK;d>9U2viWWQ1=E5La(vGr1Q{wSa~ zMo0p*C8SOqS&E7vPJ{TOnKwl%eML%BMOQW$X{T&?jS-pViJtICSB~PN+r?fjMS-Cu zs1#SLuZ26uFC&)%Cad9pRZXP4bhf3Ly%4;X3_^Hxu4koxQwr}GVv;cC9fNSPM_wu1*WmSBitA4dq z&Xkn}Wh0;q4%N&SHpU1qSDFJf&6AV2fNBBRG2@8y#; zH`oa}4klNpdnZAEvyMHd4xCV_kwQLnR7rhWXFCF#MpC#aA}G2601qLWlasZBiMu|J z@N~2HN!~kimOl-7J7q&YBG9ohCAblpP#65ZCafG0?P~uzp-}%X)0=8I;NL`sfo&iW zJo&U~0EmSEpUiJkbES)|1_TL|O-O{xE!Z#Q^HU7-IAzPYXbUE%vD~B>dI!PXQ2lDU z+A;@igjuh#P3ylU=%j;mgwioZNzfxPT>JOw}1}9dt|> zrm8Z2UsufemeRthTD~oKs>RfTeBB(6ecWR4TfBs=rE9P+)9(v)iz$%nx_zPO3YJ1iBM656>`l z)39tTns$~9w1Rts9i)gmfi4vQ+qqIL;3a%>;5tC# z{l^F^wLWpXKI@jo5~|LrG6chd1F5IkZ7VY+%uw$Vo5#NffAj8BvXp-fe&jy}zxwGr zt<7dE^%t9&4we&8EdbnVP5ht}>*-#$t$!27lB(ple! zu+p`#L9xt1kntC?+`ic`gxPMQ-tf?$uAYjM4C^+Pe->) zM{Ao#l4eG@Ob`rc+ZVfI5Sm;izef1L0L}K8?u!8cfJCN~o0*L&n$;LQ9ar%AVzNC> zIXezP+qN!@SUV5dhJP){8F!rhYE}77zLK1!p2FR)M9BHuEwesv?g`_k6SrrFLHL#~ zG-+pC{h+N}#Cc-6WGuk2#h#0>pG)Rl{{>?<9`&^9ukU0->?A|qB-g-Knimx3cxw6T z2^#h9^==~>+d-Lr*w~6j>9!$o4agfp86x%F#%!|0Z^C|HTwvgvd|Q#BtHlk;DXjB! zn)76%ddM5IFtvfH?134QMu*_0hRROYn@-iaP4!CM|1=Om&Hep7@qEZ&_X)q*EZA@M z9cK1B_r2-LCj;9vvrjAG0QB6ST9`1s?>kqEnfuA@yQv;q?nh{$A*dk7bJeH1oTt*; z=BL6Z?wHNx_{~>v0}qhH5RDm6ziG;sL(~_u9kUDEb5#8tb7kMN}{cW*22}a`jLKXHDYRcE_`j1*i6oUF&Ck+icOjdoEy_l zTIZd62^ps7Tj+jru|^UOj1AUn;#buM*SD1y&KIbFsUNFmE608-FL^BSz(3G_4GG$> zq0+@_32^*;r1A5i%g=5Q$a=wH*=$4b;)gKL`r8jS4ZBcdSI9dAEthL+4h4A%bc6qN z{#DgRH-_9AR-({G<{CV>>?bfrTwOu zlC$r_^`7MHPoUxVDq4~G$*BCy@T_N)kx&7qKNPe`5XI+k^4${`zjyzEtH`(1N$i6 zKjvZ?eJ(4XUH16&C>ID8?PIUOm=5T*=e(LJ%$f&e_6N3+&w26=sN)WthLXjHSI^DC zH|7r3Q{g3jiK!z;_&B@^yv>gzk)7yLVvH^e!Xov7jd$4_&@uO{tXX|nvccRp+f-#rV7WMM}@ zvq<0A&|vPz7cFn+x__PY-aG%K$>KXl_nBC&F_ioZJAXW;x&D>zJZEq*wu*&vmx9Fx zmJ%5yO-ZzY6)w~HCd&|0?_Jc>vBb~O5nQ3bB0xZ4Av8R?ndXZfQMBVQPd1CCt{7TA zp4{K}DD;xJ)gvTfOS~|=kl9P!EX!4rxiFbOVsIC)1}eP^+yl1QH)5? zb?-kJGu5P&i`~Z#Lwfrh zOJRoT$JY!AxUf%#yLit_rgFVqpNz;0)U1r32=I#rwS_#o?M^ z`iGsHFJ9d8UWy>1wU7n5RxQ~jK_cq7XScBe-@R*kX(?}e39S9LE!J|6T2o;9d?Hd> z|DnNybXw{bGiUUZ=e{3_(x-VjnR=?m_4UuDo|7-Ublj;wn9YVEg!2f8iNvqU}&s+9;+pqb?A1+p-*P!zb<8j%q@;u|cHI9qN|9X2x zskp|bY`rh}7!i%V-nc8@``2jWD*t^RL$an1m2Tz8?4u5vCN$Nj4 z8CC`k@SV6(6PW;fI5)fNsZs{QHm#Fq#WjZRh((L#{ynVHDbm{AFa?1%4_Crx==zB2 ztov1)IVd?LNTiKHJ{(3{Cpw)@)3%9 z+PfR2Qk`T4(}GtjL3MRgXykX1R3263|gZK8@&<9=wewO=v+tUx%iTEaJaJeSf^EQxvkITJNgGC##0feI?Fa z#R3>(t!%(O%7CrdQu&j0UXeQ^35C-_6eMASQQT>0G(-vWv|L4-lbA#z^-bHc7;q5s zNpP&gbjx?4wu9RNvjW~9l_qe*=v#TBC>OeB{(v1px^MY_Yl$(QC3=|wY_EOguqN4e ziv}nvjlJBmJLE*|$%#iAvR}A?qD);w+3h8~UccuZdTCL2dt5@yqgMCT1~Ow}+oNkn zD3v4s6=nL1ZJU=CR5-f@_BX>FEDixQYZ*(tT5K?u3%PI0!jGCMezR>CsydTJmb5%@ zlIp5GO;O0aNBhR6l21sI+4(~eEpgc339+3noaEQ>cvDEbtKxO?I{|VGDJ}q@jaQi+N>MrJCe;zq8puO94*Vq)9xMRH6J5fPgH&Lqw3(J5w%IrF9a%&Q( zn4;;|*a#>#1f4qIN=-E911kJ)0G=HjV0%3WX3JsjMrC>RCxW-127AT_7OGnz&?!;5 ziXRw+s*(Qs3SqmK*@A;%2W$}fw0z1(T>wCV>yfU;L%bIFi}(7v5Wewa3Y+5tc{?<@ z2WoELcG!hzc4E0~5nd{JmGu!CB5dA&YucY;*mqnFq#IBO_9il(A4-s$(7hovt@XQn zeMNuWb7y6*n(q{Hm`jP`F+layc$0iza6y*u-OXFy>GfCYJAX2$vg*)^@76Rar?2c( zH&6ef{nD6Pw)6U#iV)4!CtQVS*T)mTzha^v5r}YsU-w2Izdctps(UIPOTVi+bN=m6 z8Y<}@pIVHk>kWQGPx}n;eZY3#ANw$`@>8T$?UG0=Tri(R>UX(UkQWe0q(0sCRx}@Y zXsxH_#qZR~1Gf9$EKc;oqJIx zMX=uWUXc}a^iWc3y8iRv(XWFHtY@86r2BP^9a%izna2cWd$Us<&v@14BC-$bP??oo zihHzezfglgG1J>W>#w}z*E}*v>)uUfKnQX@wKJU4xpU~M_!x0ND~fB^;jnG2eh7FJ zwxR5fws#^0R;vxP@>AfP*OEz_Uo3gxN8;nTzjJ>-LL+u#=1-|g7s)yeBKFcX&z5*2 zkB4G4_HuZ`H?HUX9c$G1WzhyzuG1p>F7n}byJp0yN8Z^F=!fISk>uSEdS}ZXsfiJ^ zm?yuyJOo}I@QqhTUi_UW5}^cui2xELkjWFsbqQc=0>qO*@vr57u}tm`Q@w&GSHTge z$N#nbsR=sXAGd-vkE~QJ*q}T}+^6zZOjGMrPVV#<^*^cYn~WdX>$ITeA34=Na*enD zUT$BH0?gN;HhpdyFxc{K=ox;7)WHeanPe%$-ObD^dGa{ zFBr_eK;=-^?LFQ)BCh|8QSZI>6MjRGGCqn4sc#|KGNuD(^^W%Gi?y$gDrcbbPV8~W z)!!mB_%Piab<|P>LyH2OLivyf$6(O6T@-f zdCzElG~~A3K-?X(+e|uDV*>_7jdk+rep@}}zJnIICaM4N_4@`%zP@AA`-h$bE2e#` zEElbG>WMSMwV0tsnDj=L z6V1sU^kcm-eXZvEU40wW1~0x~xHxbV{!yh|W;8Sa5i1v5ZSxGRD$f?5_`mP0P50{kS!c5V0-W;k8RyNQ#= zYP)4H6%Q2_g$ZXu-KD-ob&#|+Gy^I&ARij|Vq9fl!0)C})OypK+e~Dc*qR4dO;!z1 z3UFsc43-Tt!8oKXb^VGZR0sfc^C`%i$bDUH?Pk9c<6>+jy7m9?!FZ(9{MszNAZVA@ zIFhpOoEdF22?@n_3&jjaaTkV6a@wwc=3tw6v^v2XbG=CrCt}Bq5{1cxe+f^Y$gUX5 zDZ)wEL40vftcJDk-?YC`MxkGdd9*-Qp%ROGZ5_L5r&R>v-;8$pY9+8@he$vp*C zm@MWlR3*fQvl$tdLdx6h-}F0ZgV9ig>5XbO?E1LP^gwpK75+62(nM~A2dnPN7VA0M zU_p{fa=;{(5AFEz=|r=0*?^ik7SSWR>##{Z_2FRR*?&X!WhExNq^`wrJ0|z{0*xOr<;J zZri3FeZy8`gJCXQaAR}=Y}BgpiBqsI$6-9 z%Z^!#(l+z{svVF8@PYNCaOj4!?|&cODCl-BOvjNb3I6f*C&})hVotl~FMPlKQF9&Q zP99RFNR-0q%A3j!EUcO>q=|y;7od-;W5dxgk1W5xt6bRTn`JL{8|9w&5_06am8k7n zG$o0n$C2AGxpDU_FxbM8N>P`O#NR88vk7NEdjU2LhI*k!ZUsZP3hXbKr@2_De!RXO zHgn}f(7mN{?$v`OqT(fpi73t(F)zvEHW==ahnmM#a75)B7BG6mueuYQVax~1%;Afd zS&AOnO<@2sv6wL`VGpUD>oq8VFYHs4Hz1Dxq?hF3yy_8y8a2CWNy*}Qstonu#A%{p zIlp;KtS-GhQuD|sXBO*FM2Va5EUOKA&U-IiQ_M2Rhgz&hX&@jW!C*$Yi`A>GcRzwNbevtEnBJexagnMEmhS;qp%_@g?WgTfaHC9Es=ptOfh{OezKql?wYQ$@VR) z_$T_^?Z_tsxy3Nrxp6!Nn%b~aLH=j-lW&Rn+|zQniTFx(RhWah$3M8fYYhI`#+!)7 zvZMjz0pbHg{okzTbbX}UQzm!VIPmq$gB`YHP# zc&uLiG13#qpO3m$x@;9<= zZ-rU;_Z{#rt2LK6WNEZtAJmEPYrNinr};?)Kg>w!-44aC)eHYj6o^3nM2&_`CDZwy z{O?aUe?flWr0^8%F~8Y}FI0!2jz}lRKB($~f6dOXgA5M>)sruJI2cU*ne_dQ*%qQh z22N@L`~VNN&GZwwk}YW$`=6mb?1FS4a`tQ$};F|>>R`fOY(#!)`KE`OQ z1C%AcSDqL5H#nzL$E*K>-dukWvu<6@^PrhKFl`~$%N3k+`hO617hX}deZ27Z48zbc zbi>e{(m6wSw={^9fHWx5-AI>!v`DvzLn$CBh=sIDw=~Q<_j8}~oHy1v?_RU^AF$V& zz4rCHzSrlQyyfDrQ&75f1mJf2eliOniBE*VbQ}&>Vj`xc5r5V5K8gmp#AO^9G#wh| z#IDes%_GgO%jn?e4)Y=aq_e4Nk^CL_@ud4d>yH${ml(A02MU=%=6b9LcMK_Kq zl2qP)@4Ef*;THY<50;xTR6zyWx9=~zmwXa3uHSu?b=n`1i<$LtQ~jEK$Bu<2 zpb8cBAbucfn4*JFCC-Y8A@DBNv3&XKBh5W7qEG=NCCvq~hn4O*V%zie=51bk-^<$- zfR*wQUoW=&@ZNxztv-B=3O-e~p1app$E)i&_u5>R+7g;a*waVdUILd>>rmC^dZ)G(SQ=+*C>&KPXcG$%Rjkgg| zNKM*4mJh^ylplW%!MOM~n?IfnPb<)R^yy3G(D)cIEf^R)s=)1lO`$n(1!i^MfBWiV zK(H1JLiOORzQj>VE?b|0OqrbuzC{wqi_Ov?%Z8~KpZ*dmCVlefG|nLTbXWvx9+5@v ztAUIdBBv*4o-ZWAH(_44@O@94oA6wNeJ{ccOU9JJSwIOcXRNJFCHFju>VCU#DmKs; zHHH+&^6{IJIK<|ZDeXINE_%F@BaPL8uxaV&h&|IfTq+a=?C1RN48&4HdRxf zzsmoLQdbJzP%@AJ=8w`9deB4Z3IxCk@?Lk!(;1e{r-T6Hcmot6+q2U~vL6Rz?Dy{R z&il0~8u!be|9sNq*+5&Gc6AX&)CU#44L%06@Y`8FkgDbA@1So^o%*eI@08vrA62WaOuLO)SXBi)8)yY^+8KpYDq6tnI#M0?=^m+D}C{KZB z!hx)fyF8nQUnO%P*qCkr&v?m7&sK4SF!;-$>2@ z88xP$3ssJB^ed)0D%T!$q-wAICBDect)a}T7G2#^f#$_iwprtogz%M~Ij?Fv6dGLH zm=wt;rWOG9^yyHON)pjXE>|Ti{fyBXwO@FevJ}R0f~M&;+I3nI&BDQfF{P?4+onaK zIr8=FO46@k`piKl*dZ0ns9-Q!cwTa$BbU9dtGMoUyOq9sV|nVfza~%tk58b3HddeR z*y-Z;KkbdtkybUf_%;rws}#>cl_ff|(NEcxo~A@iYSJxYne&wcYjd4If_~MBvF+8sL<6T#L~K|iM+uiagauWW+pecdt`D?{)ww` z=~n`~t2Js5kB@Y8+{%(Ju?_xiI}0B(B)ETKC&ktNRx8~w^?3KX{_#MO?O#^&*bDyg z*{tf~beBA_QkoBn` zy>7z>$yyF0Ugw42&IUDKG>p+8Vv2(-*zQK_*rv20e`IGb(JfYDl?aVZ()*1dmE*^% z@BTsxxkH0a@W}H9T}&TxNQ<^ru`|1nWlv0wkG>y&e!z`Wpi$ax+VqxvjaSI45z$B? z=L(0s1VLhHY2Un;70x*g(i|eh-&2|vDfu^{M!qf{xs>0X3`1Xo%P@r&%^qv#s_!Rt zB>W3MKXq04ayq7*d{WZkn;7oN_9^&I$m={sCmvSTFwCuF(5e;-X%3m?mH1mn&iGwT zpZHU5f0EbJ^X-?v3#yrkeU!k$3D4k8od}+j0$QRqhjl9!(r5nJ4@)TJZ`kO@tHrB@ zYPO;|V+uTQ#}iloIHFCTP=6+fJM>Ndz5Vc<9ooAJ^n_XMbo;*fvFFmHw2+~NfT_+` zdL6$8H5?3d%6!}6Oya*YB*DF-uiWAM^~Pa$Z`wt@FX;B~W|Yl#%)0DyLFs7AgWZFu z69}}|kmLhi=po9=`a4cJ(qHcJ64K-TD#eS7cI~7iA7#r1mY^|yh~8mQwBN={n_#;f z+9=@@utRz75XJu6y{wn8&CLMccaNq{vc9gY8&lU#2YftjVp*9Uu-7q&*xP@7Lc5r@ z&^_NInB{)6&M0gCM5L{BF`rMI{fz{)wk36KJu7T(xEgmdvm~(FV;H|TlYR9KPtbWk z!*AS1Q*^!|Uj>utoKQ^)P}Y5|-^4m5{7GimtokCdp^J_w<_{&y_-Y4YBqUdx8r-+1z6_ zAQU1b%m!fJMqkCrZ%s1&-SnuW>SaL-*PvI%pK}5aOrc++2Q8&Ep6;$J-yVr5K0B4I zBryB)j;oG2&y@K=nNbsEtVu_4MUHJfDW>=D`SB#d2?rC_=#U}}DF7|o&tbf_c~9PM z$g+_OZ01k|FM|VD?k6rwJYw3fi}JECga&2-p|n^ME01ST2cMB%m*e!sC}4>hC(7=< z+tNyG>FOF{K$-WY@xLLxf z9IPl+z+Xub7mEm@145V_hAmUB*^$!~?UG{Xhe$8j2O3`^+EO@v5;iZ#kS8`_Kr_W( z>GEGkOn_@S#Fu4NdRY+{$&67Yu6{Dus*##Z!udaNkIc%7*uoW7C}k@8Fuj>Q5nh!# z99OFxf{u6PanP7=T+K$W#ZXSWiQK#u6L_nPUJj)7KOucXitWmLR;=WXEJAUrbl}3c z&*OxubBh8__%5qL3XZ~hKLLYiFUWvMucPRva?$EI&{ZMVRJQKu0E4a*rz0y{p<`be z+Huq^%4=~zGHRXsIN#mVQL(mEuU4g#l1^5%LMn+(ZZKJnilOZ`nsbp&!H6wL`X|yJ z^$gqYg%2~4P5eR!8~;N2-D`V^xZ;;L(c%f^%2_ka<1Fe?v2@^}{1PWEpWK4XMXiMr zd^J6#tRm2+n#}x)Ca<~{m7Q*2Y#*uPmogPF*|Hj$Gc0#ayp)wat{8hNI_zdcXz3Rm}K3~+2ZC^HPRbw|^gMDhm@ z9nPCbNpKj4j^LaPb?9bma3ci0s?D<2WGgs;<{=hTwG}Ttc5t*8MfIak+L(qYAU~Ro z0fIL_bnFbV9=z`cRmH6|<8vDAVJa_b68c?zrR3LANfI_rx1d5YiH z6;JV$)FW9=l|^xtN*cEq`E}@adCH&|$e$M@k(D#?R@4u$+zdUF&<1_#DfRwYJzMIdWJw~=C-(Nnr(6V{J=Us?vn z(p@Pf&SnxHm62>a`DeW{R)Z^TfO+}(rUfFsHqk>zDm#5Ke}Z%Wn3O$q8L#SzitS@j zUh1JBPIOVZa-Qkna+|XL?GQ!12$0)@6@A>ZMR#(_BfT!t`^L5J_o-Uz4XC%;@%4t5q!j4%&#K7gg9%e5#QE|0ByduV=^f8d>z%yKzBk z`=%~@&!{#`Px-#rdn&0og&FO4($!cpRo2`ZIiq+<`*7hL~D1zC*pf@B_Q3GPJgpJ=IeJ$v<=a~Rqk3HEK;k!U(8tyVwO*nti(8r)mqdyK$Zq2g+vq1751wm8RpI z2P~lrXlV1L(!mv(&vol(aPgp*MLn2AXu|f9*)E;1D`EtMkf~0o&B~-{bjFW+GLYOs^GK*Xh9}@ntfbBy0em4^@3to|7gXSMR z6|_O?Em3%jP!sr^y8EPE0?v0>62p8H9^SY6j%H;>BE!rRlNs~|!a&dwws|wz4u32y zihEZrt@wzn`Z22`_R5vha{(cOAnzU47V3|}Okci`p`yK-v8*nRnA3&V)Kt4%_OnV* zgA_*$T%wFWFeT>BAd+mX-4-wBC|YAty8Fi;ZL#k-m3LbU82hr&`_2AZN30J89tlLq z9B!Pow&ET=!hd(D0!QTAhy+(51KKGB4_*lt9WdIt^MsRQ9vu6|YvJds8^=CkFCn~m zL)yKNhaydULx=a2{f>`X9b?f0a+^?om5&kx#6I3aSdNw6@x97Fodxp^yd1@in15sp~Df4dJJ=YAS8fN7`zG``p zyDJX^duRHupn-8OgrwMFYny%tf@nuADz04vrwtMAs|oirhsHLcBJnjUpW2G4)f|W= z;~k`B_H04#L4@??PBdQK(|-=(B^r{diNP-(C2qHb(RbYb-lrC7(a#w?xHC2pYS$YQ zvnWC&z*@DRqOLJ@PQicg`o%Qa{#r=p|38S1kmO4%8K zuYbEDJLsGqSv1E#L80TH&ZwJ$foGdI;S3lH{y(_>3ZW9AMkInqjsGw1WyE^v5HCrm zNmGDrm$3SUk0Q{b<*dsvs1#RYCOG6*#@0aPaYSe6(bpc2L56G)Mr+X;rq)XT?%@)&6cJ&T! z^bQFh9x>=2S8@SQk#g)xN(Lk;_tSG9lH}=6?QKH+RYRw9dVI_~)Zm?*H8D-Y$fw@D zH9=REl0GFtu>ffXh$RCo0#lNL4QOV#MI+_-qm&qeaX2ningeIEBgA&!>z>FIyzDAi zM|UXAAU5;(s0k{@O~#cKtTIn^pV7*0^nme3Ec8+6z~I zDtU3rSmq5gU;TF2#K z+mZjb9MAD~p>~mlYbq(rxbqrX~0S)v9xbse#}Hr+u~H|mMB&CLgQw6s4hu>$X-*)e3Qe6+{xgU zt!Zz?m%`AqN_;8b40|GhtHAGT@8j=rruud2%um`JU%c4?`|o^dc^Gb46ns4VLgX0V z-ZzF`+7K7F$@Rze>bljkoy{}zHzR-kvQ^6@r4u|uqe1OyvcJCjH6fy1rK(?W>0Ff& zNmpt_RACV$>+=!_RUWp0wFzd*ujLp<0ku0BtSFeFj-hHN^hR%JKxPPyOYxjNUx}EP z-2xBO?eMf-o!M?91=GaBj;liPsO--R4=DGiF|P8(I@RH4{_brMYJQ$b?hRKbth{

im!l(LFKlQ3HbvWHK0`L@Z^JF=kY%_PNf)m~`Zk##OPu$tQD%R7wdg zKAjwa(X$O#erf;wEfc#(u|gIOlvTc_;^A4Q-yRf*rz{X9cbt^#w6%|lP8g(iesZX} zGBxpfBTuDeUL^2k(JwlbO3mlq{8`1b;kL6@w!mWvgTV4uYMrMil<2Nm=UF0)l}JoX zv?;tbM8k&VXY2xtyJV_stW?B0`PaBFBQ(0tBIkqGU1=Xt+DB;$T3Tu~Mk0SzGFV-# ze_6wyUW+#gRwm|xz;m4Vf?Txh7@wSdv&%de{kHk?Po*jTtZVv?u<^3=N$gP-TiktDVktBFGW!EzM*Xy;&=iJ~Fm_40JvtF5}GrK_Em zY1`|)XvK|F)-fBKnK*Pq^E3U0*Tqh*=TX0Yuul@nMpMzaDu^e1*UvKbN>Unv`l7UTR_iLpVb~@XEndQFuFfg>ba=@G3t2*Fl{38Hu`2 zlQ{c*umo3>7zLXh+@DFXsLI1>Zh>KC(L-fkh+%@7|19j6@nCtSo3*z88vSZF`TtC{ zQUoIT>yHeQzL$&gu4D*(d*?1E=m z=wa(PGA?RPBCU3ngdAj<91>cMSvf|n8>B+g8RDnWG;|sXT;8Wu#_zKb)%=y**kqzO z^{qK0VlJA63*tI~G1Rv-DoV%dqefuA`~4KpSp$BLnlL>t`kA63D(N~YO1y!0D;0+a z`y?f;6PYq+%_;OmQ`dnvGk>YQMsgsL;jv39ywrzN$;iHxC#5-azTvZiF1J3F(x=pO z|5}j~&0!0SzCSiPfOLnlL{XiVG@rW4879Is5Ey+wAr^K>J{I42no6q6ru2oTQ15hz z9A{v_yRr;O#EitC^4v^fopEf!N(ur93%4n=ZQOd!5d z=~??r3CmifH3mrH?kLw4=OcgdU669Tfla+Tg}k9!|AmWZqrVLc=@K*wk9`9NZ2`92 z2{9Yc5`N7f;D{Y_gp9;R8T(2NPS{#~$qO)jWh+m^0mJ0+gxRVdFz!AaF}Db!dK{11 zEJu(Xl6p#~wpz#jp^dyE>Fa;ggu{X@#e`Q<6_wk?Nxmm|RH>p5yF*)0Vnop|Je}tE-Pu z&=UzoMh~@jWazo4nJ9JE$z&ec!jJxqf2;6X-Bi{s7DgKNYuj@2DdjYX-;fSBsuJxv zPfPcRQFX?@_w;;J1pP)Ws{=97#vYqTeqY)T=m`JmKEgovqh#sqjnmwocTN%8$9_UG zx@Jv8O6d1_Tk%(KtRKz~6s>&8Jb$~%n0enW4!@lDp@<5~+wWSoxW4fs9>>-v_2ciA zYprf&a2b{h8))XuFU#ed0t|+fJO(iDx$}QUE#p* zWznyu{+5YMLApYZBLOl5cx0(Lx*Oj)z7If6Pm}q_kd&YVNc`R;miV{SJlNv-q6H4L zFFo1xg<}rqoPX}vf1IP9yMrd~{0M@av>d$6lGHgjP`VomC>(*4d;k_7O`Z0B3^+=W zJpE#~@71qg%JTrHchVHTA+ZUU$0^vlN2(aqi?#Sgm4tI?l`mwxssA9=ZVb=lI*v^Y z&ccmQn^q@3FHE+5-N^hF6+afbsyuRRDbzK`LxscMPR?S=jJx2F72Ni`bhA-Ge&eL^ zYSr70V1c-Aie@FR~uk^}B^0v3-#Z|N4i#x8P{;L{>i;p^yhcF&4 z5irkr<-u|Abo2M={gkPxZEw)SwL90SbkPG*%zB%3@C8C2AeaG`n`Rn_{?=+=(+ES% zM-R{vJ{%J8vov6aeelfZ;BvwHig@P8(ExfNc&FfVry`6)lnQz6%~8BBxrV~a*JmA6 zX0gox!kW&x_t%(67W@zKwqh2vGS~(WMBg8<6R+G1R*0m{T!_ND?;1}Vr}4_03Dt%1 ze(2#q($QvXXz&a+&J4k3_yOfgy^6n z76mrI$DZigo6|*;Mj{Gh`S-gV(Y#F~Ei%M;LCP_;LBb&n3vq!ok+>PwUGZjVqBi4ie4kVizEjkuvL)%*!(Jy5U3J? zFUICyrE0K;*GJH9J1{Ur!uR3y+XHmtWn731CUb9wA5lt1M=o(bTvnulP$Q~0hJ)KP z@L#h$?f=01EO{u(DHP7IJ-rnYE@RKAhk^OaD5uI<5GxF3NW5cvCNd1^`-D znB5WZe|dh2NJc#fAk5+bL{Pdoz>6a(6xcaNvJOVc;6zGvbuBzDnzVY__f|zme97v; z4T29@DJ4L_=_fc0$p{(5nvW!dqrg%i`a4ldM+f-e3bO?O440EaE68eD!j88&eU3zV zgzhc-!Y5j^XEJ$?cfhJ`aNRbsoMx;?haAT!I_?PZbKie#enE%-+We0IfLhA|o{i`P z0OnJBI2DM|m1{W5Si0j8DXN^Q)PbOpJNGz~>_rrmH-!N!i<+8(&La!iB_gQ$n8zJp ztVh7D{NRWcTK95R{uNpyBmug!jIuFuV3Azm*K>tEazz5AFa#id>9>1`Vj@K1X_YfJ zaCcr9plp39%LiY$Ya!XP#a2l{9FjgUmy5AU1jDh(Pa5#eL z7y$gAONNn4#TvsC+ClEv`Hu=y@`gp@pxSO zhr$^iIeR?Z0K76JNQNbU_&$Puca=_$%z7wb{e6cuXvLbKBJgf4 zu$#-}8$hhUV)y9G<*@{9HkV6C=fkkGhmjJlv4O793r{+q59@WVC1MKn ztvENzqh4aU{dF93D zA;|)vBF&+%sY9AhLY?wL@baE~$O=~N3Qji{TsI8)Jo!}Mi}CFFT%Y7ADrjvqkN(7b zQ&{j~+kAKboD$n8=#^hMN4EbTqi1dFzF7Ga&dw3Ud;9El(fa@3|n_fht zky0_L!7-ZMF}fEqhElPn!LgRzu{Ia64pMOsg5%t}<8&EU9;844~c+lr8p%79B z?kw`?=OjbViLkN>l(XXG&VbiPGhn&%~& zJpEw)+|CuuUEXP?lAkE8n$n|z&g#jJ50UVUuzm%oxrg)P!Wb(c`$RcQNV z(SUSuM?ukB%i_t);&%nbvmqtlLJB|kl&pR$UY0K1k}i4EgR%UJ{uC5;tT2B)i3An$ z^dge+{$u%*%9K-v{$u$wUX`Pj2*9BgIZ@bmn0K}G%Q|VV1jI{unL_C+%)L@o=A~wD z<<4cLVPPqT^Iz?$s`>_PUlHQztqxktH3irB6+SzOs;N?{(FNB=f3JC|RQss+S?YI% z1UlX0f>Kwq=d9J=iLnf+s|bcWq%Z_bSUJGd>oB|le*L-d^-sFSUxkez zRO69V6W$sLWhT&^ zMfFF^mseDGk!~1|-v#6GBgtLq07y|YQIUZC{T5_Vi#i7EM|Bn~;9EE_Y=Y?BUExu0 zntwSKsA9codsASn{DyYu4JlUNP|+J*<-T-IviSi*uNC4I%(ke#VFvMcw}>Jw7Vs?|)@2xBv4%gp>BJs{Nv#rumXZ8+AO$}~ z5m+-fhfb6@Q|URttsN)Mn;m?#S5Imm(*)tfFW6FQX`y51aPz;_3N06*C2nAbW8F(T8y@nB} z4}&+`{OGw=A?_k+9!P`EX$Kj@Lr)}?<$hL`e3!I=FO|SM-~Iq0B;4jC9+NK*WG{CN zek;FS{wBZDB>w}n0&YeU0jSS>4sPHZ=4L<+XK?ZH;_{cbKe3nAL~Pe>-onjRxmEAR z3&MV54Fkgef%)MMVuO*C766#ym}>VP6D)3uD}wF{=stN$A7~37#}s0u2zWC62`K#& z#Zelx`yBqFxG75)@0fkN;8prfB{CNIg&8e_^( z_dtlfZ>8JI3i~a#JK6&jkipN|$Q_|OW?1nS&f3;XTfXY0z1Oz;ZT*dS;p>Tvd?yZs zkf@`Q(%(pC#bbMh;|RPfd&V0Cyfs4nbb!jWoC+ERi9iuJv(WYXkz24d=k;%aP)Ey- zr`qUKV`gE?<-ZPgaOW3ik1(|WtISgW;rU_K2bT&05zD8Bc7K!6f1Se5JkYX=Vk+wG zDnCx-=WG>Tzc_6Pzc3HiOl1aUBIsqx4hzl>an`^T%z)gx^YT)GM!O3T7>MAXyW470 zeMJR`Ez02Dn5&l!b8NF~EA5UC1 z4nv>qfeqXWRhZDt1|7UG566sTdIHER$>WXjJZxTMP@>c4S1(nUr2eMbc4@)fi>x7y zOKk%EhDuRTAsc>{5p#troZb*k+E)v+ZMmwUW7xUALC?i7QC^|8ab&hsS(bEYcSOP; zjisk50I{g$b92F*l=B;>Mq|up`;TDAu!0jhSZqKp99S75BQ6}lHayd8PZBt|rCy0( zqztxK#}lL(R&>N2j*0}h2h*^?HfuTlH2CcBNY2n&IFOQ0&IAw+w^1bVf>9O0LSWc> z9OvLlSu|RB5DReLRi*$E`|g1Na(t8W3}CR9MV$d0;hd!{frs)a@b~8cUY)AH=W#lX zfXWn}ejsH!qp48g*;CQvQt!MekD+Xf8A85*|C42%rPX4Us_`5cqEQeYH)P+=e>}u^ zC_KnboA>o`DI&f5r5a^xurjFVMVuB`Fc`OGFO(=ZrhL%xY`Um`9d|HP2zt(CD zO4o5m#>;uQ)$9@V9&bNt9s(Qewu}i9pkRMflw!#0yUDSDy?*+GzE7W@cz3`1RrQwsIZYlJHduH<;F7imk(U zV^Godh7f@X*NWVKoiD5`rruV}n#t$!iEbPCE#+$^AN`lsUES)&NqNrk2})C{*XC1E z>iP;fW`Xk&K_GLH(uVKHC{6IF?bFw}$*6AH8EdUkuQO4D#$XoM;h| znGWd4Z(Q&*tvsx;k^13c89xEpV+owp zzQn^Ki);y64$pflz1m*$)37%CW=QU2<%X$mInGwp;{|Nf?+I^f!tIcvHmqcv^Tln- zB_pSUja1T1HkRP?P+nt#Jf#)Aa)^lp3Hr@L&- z%blqvz!ed`_!IbSYE$;+t|&0w>u4L zE>j~oP8c_-_swZwFC^?7z}Gb5eJK0J`ZW}uFMrQ#G46{^kIq48;CFru8n6-D665Kcc<9Dh>{Wj z5d3sn1eXcJB&Vo6E98W8*fxr?@i1M@n#D8S6^AY#Mqu*y!wZ12mS{&P;Z!?G+)UZP^a^#-uMOn=UT0RdXv}nrcFto8{7jhZfU*wJN$*_ zq<{uzfmfE(Nek`u0k1tDz4|{}{&JNp|62Z3&Dk?4D)t6dBmc4dcdh6>{Hb?!JESdFNYzf6_k~_#P>ezl0P-U_E7mUQiy;G8&k&$Icu|Fy5~h@+ps|6 zZt2BlkBro3-I)jhxSpl6EP8|zn);x_pULO$BGZ@lF#&W;{$-*H` z9OwI)!R(Y#w@l~}JTz=NsJI4N3tmxqDg<4hE&^*sP4LZXI2 z`Quz;%I%1DEbIb+lz&iuhvagB82W0{VMU|Qe4fpd9Zc>Rl%M6k{KKBCnvWjCl|-Z=;PlfCnv|p#~7Ob`0()H;NW_9_j+r2e}8{>clW;v z|Lw2uo4nVHLfe$$uJ)2GwZmot-> z(_@!YW2aLSmlG3LV`CR%W0xO3T)lsP`r*Ur$jIf#feX~YWq<#9fB)q~&*gaQ)oAV2 zaLv_7;q8a;YgF|4n>QC7otN#E*KZ!(bX(nYXx_Fe-8PGEOidjR3`|c?PfSdVkB^Uy zjlF;Wet39zU|`_gyLWwkecj#N9UUEQZEYH6G;hKBR9^2@@)>-4m{T+QR>*+(glosUc4wNDZwEA`T6-6!9OD-BRM%aK0ZD! zE-oe}CNeTIJUl!sEG#rM^k29?ARxfk*Vo6#$J^WczgWMMlasx@{ePu?OH0dB6VppW z*+VVuD|OK$1oB#*`%aQ=Q&Q?$i0ikY@GTefFD{-9PVPH6?HvR42Ap++f$4^hZi9~D zjv97HN_jEu~G$^QR( z{TQtO|1R}on11;G$LOb}rTs6^Pew*YN=gcY!AM9*h>3{_2?+@Z2=MXo(GUQ__!^OqL!TAU4|9?sSn190m)9Cj+noddjUq(NLjfU@kjDDtnjsDS8jL~1r z?OXLR8)NiCX#J`ulbr853`W~({`W?IO;WgEy`br#TI9lOn|GYQwoUnsT3ymBbUpk9 z?w6aJ_LXRN{nzLhnt5e;OXts*4__Swh}q2e^B=D_Ct$x%)#+*d_3V4L$G`CPOS0Pl zPj0baZ_k(1gMh>IrzB@ve_ljDc{j^q{xSNAY(EdgSP=Q6h}dw|P&j03Rn@_GvvoPu zMc)ewYhFxQ(3F1M>fuhSt*+m$S1A~GwFjioK3LdUMupVal2T=`8k3{%e6>9w`i9!5 z%=+S24Vya~`z*kMVHzI%e6gGp+5|;Z(IPQk?+v5tG zj(2rN0)Kz_4DAJ)nzdDFrDsYJBG`A^(F3XSqn-es)J}Gk8&*X&7KykUJZ4OKzw8+A zi|t9~r2Ljt8;DC@LJ#&euI@JHt5cCp;Z{xhghajHhrO#ENSA`?PY{j$^0`xWW7;ie~Z>7lkd%v`d&03rO<9d%AGEkJ^+QwF9UML}6- z0Q>H6$jB>u4w2w7Df}49<&`0V@r*T6C_({O z6@{+=pd0fN$_D#PNRBlfR&q~@BLKgNf`!B?-#Eb1y@>QcbFPriuX7QCHQH`@ zzL4CY`eqq>jfKRvf39IS>tU&n`&{pL$`}5rd<|+=)UPeI8_J`1W@ZY_269t*;xgie z$qtRi0Y8b$zE{p%ve~1o4_-Vu^5_Hj6bCsco8#Z=-h!J6Lf~t;!W`zdJRiR=h>oZ_{-OtNJU$yF%>E8F+X}=$7k7PRXdFb?m?TgXtg^p3({rR*Xq9w;Ug6&nwkK|>k zw#~Y_N(R07tz>e3aBj4;M!xp_;9-75rP>*ixNlvZY;$AT<-fHnfcv#KcEA6;Z$zHT zZ|vjpU11*g=16kr^5D{i?fW+YCgUs{q$xOGyWX~a^d39=v5e1k{!SV1&;~k@3r?mQ zlo1m)!iN#g#eHod^P-Ctm~b3-q!FC@wHxPs_9ZWqe7KfUBsH)IX9ZvK!*D9kj@jZG z>zBVH3MnnA_q5k11w$I7nD)~GJhLrFov1P(qK+tfdUpEDk47iQ`eOXKnq)CUZbygN zb$v{g4H4)Pb06>Qb)Jn7GTMn?rt17KrQdZL87_P>e$PGloU*3ARpRt}8?I#IhU^Xw za1pnM&0BW)+q$H3ag4Y0@41q?w1~fL4&Oq>LC&{!#HPq6kN>2j8a9 z3St$Cp4n``7yL70X;EYA;V9;t-`?66L2n*`0m?as-_Z=wUa)92IBEZm)fHPCVEuYoUD)N+<@aq`@AB)IOvX>* zh+)a;%Q)jc_(!=b13Wt27lw0%av^ctIxU1%W!BC%ibeJW11oOop&!L?)_(C#UprUb z!oza46w$N>T4bNg07R`4?Y2R*P6fkeaLmrm>jQbS<*Q^gzabPw5W>B7V#Q>N-pA>= zUMhOAt8QZPx@yh1?Dthcr4TPsX1z%@(+1YX*Ok+@rEj}-=0`0xFv~+<7YA?Xz=P(a zCx5ykV#_12NuTb*a$xqr)UBKv0Wn@$~#0Loy-WR2s^nRO43Bh zT*Pd03AVqF3i}(qLm4AT!)s{)BY+bwNdgkwKC-y6&QcDn8j?R3sL3uUDY%~ixY3AN zry;=4f!po1SzK`KlZP6VunQ`WTFOTkQ9d;8Tn`?!!vX^mp1^DEp5(`;p)F{MHDG&6 zd~=Sm-jRI#t}zB@aUN&n@+duV8mmCpN9h(x+eXihAbja$JUO*d{*QU$yJCk}lfkpD zZ<=FXamEF?CiUghW=g^CgL!OyIfrqXoQya}@>4!#a(YDFZ%@#R9wn!aaQ6eA>C`4y zeog+4n^;?`A!Euy9mTpPl?E4O<-o|e`K*z-_Oqj&C11&BBnV9bQQgsmAHnI8pA&G9 zcwbkD_l1cVDEX>0hz|@1IWpXu*SN>KGZxAj7Y8!N6L_Y+rdg|J;*bKJJ`XZDlai$3 zE-o^kJl1)Hg5E=5m6nl60YD9$*j*Sp2PeY4OyTB;xf)80xggg<1J>3E>O$Oz36b{${i)i2x-d5THZjPi|CiEzv-3KhE86(@3;3Ac6Ye}6M0HkG* zNEti@lM?6pz=#mcl7}Ss$^akQJYVTNf6KhUki1~aJjz2TWkwzb=#RL}d-5$W(lS4e zC;w?keo{}qzjS`eWq#6D{xe#zXBAEcUO`q!L1AK^;NkO({|lHvXTKGcUm2Q5K~FmH z4*b9l9Q6qKKoHdc3J1YCJt7HjFq^blo3?qIxS5-}xtqM%o4)y*z!{vvIh@25Z5DG8n#UZ5$O*tuN#cn}OA17q+B=zs&N|H+!JX%K5UA8q-T zo4KBLnVIbQo^k1(@X4O?IiKrUpZ0l~_&JvhP+E$R0r`oTgc+ck*_m9aV%wRW3R+p$ zNf6F(3T6oaXz7$Pc~&$zY8Q&3SvY|4P+t~Wk6pQ-BI*>d^$eHrVMz$Qx?l}_r06-ti^k%YLIh~jskHJ7Dy z%Ag6FifhWIXj+kbIuKpxeFadZ9l48jTBtqoi<04@eA=gK|H`C1WG8Y+hd7FjS8Ax1 zdJu@3BZ~T@P}-@Ux~K+Wh=@3;Rw{Xyda4GIsT7i?jryse`lbwuqH?B&@(!on6+TxjK})`joKBsnOc2T{n%UWsMverykj? zminxDI#|HEZ^(LY;fj3-5sy>wsO8FMDV74PkPi2d4P>yacgn4y>8*~cuHTxiuo?jU zHVceZtEEa1A^;AlPzEos2JrS8nQE`*hp&vn5T6hYdg!p-%B+{g zs}ei0`nsmB4U=G<_3E)g{|T|KDy=%Zvm@(xs)n(|bp!O# z00n^$_}~d*KneG7MhOVAHrtChOR_7Qv((y-w5Nm=>lZr0Bb-nW`kvs)V0(%++qc{Jw}MNxh`Y8DyIr&ZL6@r+Btr)Kpb0YY2=E|%Nr4IfATuIR z3fyoH;!p|!Lk7;k4(q@SJTMSzKn?DI4#fZ~X z^01T2%RedB2HAiQ+c2|9K?dJ|4KkAh#n1*Z|DXolPz(aG0qKwmHGl)fU=CjK0!JGI zV-OA2AP_GA52A1bmB0^cpb*7tyatE7ox8kf8^8h!0F4$5HyXXGp{z%-0o|Ym5=0Oh zg#ZAM6FUI_I`9wk#s~XQDQ(~nUI7Z(Fc7W44E*b~{)>kIEWiUiwamM+e|lP#TPzH0 z6ss@_01&|gF$w4(5FC&WoWKASKnmJG!7q>xl5hYWPz=o=5YfPClF$z3Ngs-m!XvuE zE-bajx~>392LC{b0|A>n61i6Vh*(^}FO0}q|6HZCaAk1&p&1JmEpQIEo5P%@tJJUzWkCVd zunJ^g2E~vKv|<9?5DH>|2GHOPE3(IZ{Ko}xo*hudg{+{5yu~)T$YNZPvKnWAE4^~M z6mjqm{4mV_;1B#D9vmPI&hRpla1NEi0Px@l0MH55;FD$m08cy+QGCLLJj*JK!uSQP zy`074tjMs(QnV1TGpw~WJQN&|1Mr*!)xZilpsUjW4HZBTl~4|Wh5+v%eWGA&0$~D8 zDZ(Ud!oLH~-b{kEoXah2&gG0w7cdWx_t1BNfJuQh9Y77(5Cg+w0^(r<_+Sbm!V2ub zCTidhn=k`ozzpC(EA<-+Hjuyj|C`X=ywFhC(4;!JFzrsnd|0ueNNmyhU2xm&h00&WNPY zUVVOGot0cX9^-n1x14fR;A3dbC`ApFH{I3@&DJm`&g(qXa9!6jqPaZ1z#ml%%)Z6OV_z2nHYS@Dv+NFUA3U7Kn}B ze5lr((ZB6YUhfU3^X=d9O&69e4_W})iHqNxq2K$hT>X8r20q*l-4~=C4DVy#5vJY@ z``im|X$=l}79Mb7T^AC7YK#!qML5@zh~S!`;2Z8*9WHhs9)AD*6@YNujbP#v$+Gs? z;-&cFxftT|9pG${0RD;Mn;6ME&f|{gpm*X#UOY4PepT({9e^vi%k; zwF?0-=QLF1nu_7u|9$6auHiB15tY)6+sjh>o{#Fkz-F-e6H69NjK2q%I`K|B>-&*>fc;mkAwa$)uQ3a^h2S?uR%~kFhf9@O4 zUmeeQ{4U;*|K1b>z*4~wr~^Oq>22*Tf4rcX3DvN>$4~2%HX`lRB%sPR27S;xc-k$?j{pbX)#anJy6CLn^~{p!u$@P(Zh0l-qi5O+EM@JmDW zn8D&#Ur3fk0@WlCXq@yY58%Jv?`FXQC1waW7V~<|^L3AHmL&uKP|rDx4(X5$pODW} zjGk^up!b=Wn7^6(x%r0K`JP{xpdb2hN!s%O0(z`it56;@_UCU;cqf{^&oK>W}%sz5?bypz9Bq?Z5u8fA80SaQRdU zu>k<_Zw&x~1r4hB=fdDZh7BD)gcy;af;S2zUc{L3Aw`QCJ${795#&gc1x1!b zS@6Uzd9F5AOc@j7NtrbnB2-~h=T3qh{&nCPROnEmMU5UsnpEjhk3NBp6i}+%jE86b z@qma>A=8gExoY(K^oi>URl!LxlU@4bvUuGkPPUxnN}89-*dbVb_?d|LHt)~#K?UYPph z|3BKbBLQd;EgimYp`JdJe42FL;dP4}56v~LydI$4iauV}G;ENvsb9yQUHkTu)|Uo{ zp8Rk0vgFH)SE_-QywA>8o98;6dqnT^?cc|re{%h#;3vcX3P7d=91y*vxKOJ(_f#XW zzkhPluOa>-q_9E@F9hr-=@MelK)xDG3d9gSG)g`8%py@Q5si}1!U-{iF-93@1mHy$ zITS8M;&eprx&L?+3PI*j^l>~OH-r#F8);;+Nhhyck|_U-EYhzPjk*%cBX^Quy;#QD z^1LedYO%s7pF}fFHS;=Cs41-sQ>-kBnv>2rYZCGZFvtAx&hH+KvCTCHCA83?{{-df zP0Rc&kWUpEU8>HEx|HY3J>P>AsWK@<)KE`91y!R?byBoXM;|>EFG+=3^`b4}kw*!* zQdKq6qc)9j)a^nDB#%&k1vV&MYbsSUT6^s9Sh-q_=m9S?Vs@u!i3JqKVYABv7+C}e zwp(wz(@?BpQN>hQG0SCY3$^r|6y<+Syq z2UxPS-DFRLH$Q%_TLc(G^rg6BgB~u)-&zL_uwX4Y=4#r8)EyF9k3VL(S|!7!5er~$ zDZpZx^Tn7XjgehgV0V!+z%!3Tt_kRVRlcz1*A}=17$;_Cx?7_`x_Q}?|BDhjrK+u- z`XU75VGFFRhq~HkqFrQ}MniyEq-nK7efp!Q-wL~=xJR0s?yn(wAQ*WR>FVyF>h`E% z{Mv5K2w-%HU~R<ZJ3H0V0^PT?^{Jzsy8w40eN(bJ_-7iYL$QvTK zJI@|diWjo_#bkOWo1dK$_z>p_0|N59onLZipW&&d55R!M|1_AZ|NJ?Kd_P(ss|tvc z10v8UCxF$&AeghsOmIFGJPinZ0gSF~(1zTBVODTdz6io8gnv_?BIFT_n5}Sf5*!=; z0>~sr0Amn0gratG2%H^)u!oEKAx}g$1Xx``ZX+Zi7)JsxPSoZf+t|(&CzGvOa4U*$ ze2p3#GC<9-(28~p$}HqTivWBvi?G|=LpYHQ!4gpD4ibj$Pp(E=&X%kQq36n7?083`k zM?c=OH2=6k2ZY&xg>V8MN!!d+>;>rMBX-~7EYNkD-lCvfdR!xl6_L~eh#U|Cmgz_ z9RQ;j7@%lOmts)>U=%4OT@VioDw7_-3K0V(Xg~Qf!40Ux5-U}c0AwLLnKtz(G_~pZ zI4aVqc2c7r2|z65v5SyW^{V0$B|$`i1{avY8R#GZQq>d)V7SDoZxsquuZhL4s;;gW z$%EzOAkLkVDXai!MLF_8j#k8gnS%-e_d)OkX$xyRxZB1E1ogTXZ>5_N-zL|(k-aWT2B6hlz&5s3wd%W;Ys!Z@DPo0~ zZh9qB-8%+Xo2vDQA1rqV4SZ6z(z~zY#!JEG#wZIf8-RKRETR4eC8{WcFV5VX5fBJN z9<$g2AQSwS&K{Of3&;g9WHn$8_oTpyn(Jg2ywSTp0JkY@aK;-mnkvQ$0I3gPkxVF0qGJgIK1{MFH0YS#_4_liY89GUWVHw4*%ds;Q!$dejES* z9FT@HAWjfToPz)aVE{ZF0f0{IqaYOcN1xkW5P0|c-|XKd+(d;0CCULuyR6dt|+)D?68mwgWkwwI2L7!=a*Ho%7|Zh!+;u)_oZ zAb>TZA%-zfqZxjNhfuJAK`S(eIJCbAt2SC7sE+D`1^S<*7pBZctda;)qgsTR8uVk|;3?zsUaIi$c13btq9;8A6nmx7h zl!#FwCu}MxR50_4LNsKE{{esnd9Z~pzyt5%LMe=oFU*bu{EPpB88R%x9E^z_1e*xF z6go7XkLad(r~*8&gZgT_9xMtC#11_43k*{lK9nglB(W~6BPmn@dXNV{_yRnLFa#q+ zX-mRifig>ssbR^4YH$a1I0joI2nR5Qba;niD1pd0w(hGkNJ};l_=T330z61DAJoL5 zv%^UA!wW%z!+9W8tfygNhDg8x9#DpG*Z_h!1#wV=F_;Ev&_&4dMK#Ps7Gpzszy%P{ z180Lky`!{1vX*7E5MToaVS`3`dKeP;2Q;V=ec%Ivuz`OtK`IhQe=9{(gP+SN zl9WA(`Y1EOX`rs$zUtD z3d~26mr@vq{}(8Tj{Hc12uY$8CZj~kyj0GoyvyZuPNi(l=UmR{luqTO&Za!XBTxV? z5I+W}PN=-j@1)D{6wk5TOPPEjzqF9*1BT<;%{LmBsF;e2@kfHF0fE$^g3P&IG)VJH z$xj4;6UagfY)40wlG=og+nkI9d`~zUmcb~D!_dZXNP{tuhMpWrlYB{XEXRfb#+C?x z0Dwa|+)xe$EA)(rY*Y;e{fi3{y#|G%Ve!C!U@}@%2Y4`s`^!(5EK&aK&xI%eS#ZM( z000(HL`FPGcQhfsi-~tgg)=w}7WIqgq9GWKQS}Tn{X{(<-O_Pf2t#nK<|u$re72I* z&>KNf|A>f#W6+0gz=Ra|3n}%BCVC<(wINKDG$ob5BXq!q(6Z4?noBnXytNdnT-K~%0Z#fVD42Y*0^ zPWU}G!BPuhLLjJA4Z2i<$$$vJ)m+upUFFqY_0?YmR$tA4H@MYcHP&NA)?gjhVola& zb=G5DR$c`GTW~`Rz}2?YgCZhSK9vhdbchnT1Z{u^R!9R#$cF!ORhm>2F`QLPeO0&F z#k?3+D4^GRwby&a*L>C2edSkveS>}l*nkySf&JHkHQ0kS*n+*+HWY?DpjRzW%`0HE z|831wBuoiDNCthlhDsRD#Lx%5h}6DtnLTXR@2Seh1r;u*_n;m zC3u4+pxK<&*`3WNCoThArl<2763Mc(DrTqDq`UvPr5O+-700@iI>irv(qid_Kk2ihfw6u1Z6 zjob){r+V~V(gEJ35Z>iwU*%=r;dS5l1zpYksCmePvK4|k5XBv^Uc)_8*fmv#umnr! z2Td5@0XBwGqNeeUkcc|p#YtbKSYP=i-uR_p%(dVPzTCd;CVBV+v)zJ%BLezvC+q?bSz%AP* zr~^E>0^8WNe1zfG%UaW$A5p>6boR(v^o>D1x&MVLBM$ zbH3hTuGqSWT7y`IN-zjYP=;o9X3^?seMyZ?P*D$3>9Lh*n4aoK=H{se0!eO!m{wvY zM%#z((VyC!%9=Jw$uPH4^bl{XxM~Jh=zL@WJty62&q9z z?QOPU8GBf!V!+xKcx>dJ4CQ8N=MH20reG{6-P6_FD^SEJsP4jc?I?zAnGl0k(1vPA z1*(8-d||@qN^kZ44Q#N47H9_(90PN>X3)m#yvF6do@)Gl-y@(_Tu=hC?c0Uk-vIAv zh$irL*6!BG-P1U)2>+GT-~)Z=2XxJZW!UiK?r;y^0TK6MB1c{ya0Ph~hAjB-xXtMy zSX=8RMeH`km^c7F&;(701H)@@eEF|h2rwJ}6xlEV|1o$x04M_+`0@D;at}B13x0Fr zZ7q86gXD$VD2Q0LmGVY>Z5WRU8Q=zZum)>@hiyarC+KmnZ<7z>B)4C+je;d^VuyEkK7Vlo+ujdA27kzheCP*R?|5%%MqPMD zkVg}zxQ0PD`lGjoZtn|{kL7}|V3ZGHF!kWIg+o0UY?yCx!#-h7u8A3FgEo*gznF2= zphtTY`X_OU@7{z@XoqP4Woc*!m6C5Dg-$StPT=;r_x8Hy>%13u%$MI^hlOBATOn9SIf&^`&-wvR_J}MA zQC9s?UUjBvsh48>#{Z3WU~qz%fq0|*|E0J55ZC;s@BQU{f?z!Nwe{~h;DgbR@|Z_< zcsJCT?U+pgY%ychhS z>vNhn{M8uy)er=Iv;OO68BDl`Qh0<%CXqo>HolSrUMkm&O#K?QFV z04-`XqEMnomoiefdFgvEZVec*RpNv7Jyc+ z1RF_Hr%qZUw+kD-y-Lwy%fNy||K=QQc(BUDhkdw`H_y+zA>4+el#qCoqM%ldU+Sit(gu5J4^?%bVS*WRle;$OwWSy~=$++*?MClkq| z_vhn}FL=7_Nd6Hs?9aa)YTs^9bVN-5NI7K1OocntYqWVE$h$p!iGhH*if{iu{`_d) zzxJI!xN-q%WSxM=5m?|xhR7q&As}6WM;%dAS6E5dz1H1*7{UkMLu7n|4S5Nf!vg^6 z0RY20@bRY~ej)e*Ob9H>I3tZUt_Yfc_yLGufCut;n2$gHL61C%fYbyXcx-V|kQ!OY znuhU3=^cj&ZP1Mx(1eJP|2s33h#DE`sJK;)__+d1AZ4n#CY!e1*jbME?f9c{P14zt zodW(bk36pU08&kQ2*D(UAUz4%lG9+Y7e>!F=3y4|n2Ep$T%#Wrw|BiT3* z>6QoOaLzLM6r+tfF>G3DZXomm%nI0g`z^Q!-6()nZ>1XFs;?qesJep1I^3-C)C!Ui zdQ6uQuRLWp6pO*)w$MKT|HFwvEu2Flvk!HkNioWJVnTeUhWi#Hzz8xi#u>NCA0*k} zgAX>4=*5tJ>9&g}|GOs>mokF!&I{5O5H^7?%N+HpnZLQ^Y}>HKc5rM#as0y%(f|0v z&jD;otg%{o08>l3OiMj=#AFV12|S><;YKL%Skl(H@R_XgN$-+P^GbBOY%54n)Pctp z1J=CJ&3)~B+ug7=S`Y_0_?<&FtmKf8H=KBh-_lfrg~7HvDE>I)Zdwh%HzE@R$v0q= z{9i?9yF0h%gr&{np7I`HQWto9@q^r>U#IVd{OXr?fB!rsk)#P(QjI^=SORg?oJOA3 zBES?fJo3r2^&UPl6f^@qn)9V&=b^9cy7eEKEm$E$z6??oc-%3?M)_t2rR@39&f4Ay zpvW%2X?`TPGrRNj*fO%y~E*^pkzs+T=jfo_4jYM^2aK_pnP z4J1RD10J}*5%cX!De6m~ecE>wGhCw|*8-qd7LW^IAOVFge4)Z7#|M5eV-uTT#y;YJ zK+XZifgstQ=YWWkLoCP@KsZUv=s<)GLhvGWd&~M_=fM!#4lHFLMLFQniW9;RDu)2Z zA-X8WF7js#tgwbPSRsayO;1h=^dWMZxIiJAgou6mlS!mt2e^q&C$K}`6f*?E_=vD5 z@tYqrAhChqjgcu%0LCo}(8x*p4}WY4TYJU^#|L6>lbjTg513OVJeI@K-}ag`I7?N0vJ%xB`_oR9-sM)0}R+9^?K;Z^2srKbo7W3 z8dD^eJjf1Gh+`*h_QzHR@|CV^Pa%PFxcpc$m;^BdFcx9XbxQ3$rs)Sf;~9=l5I`-M z^o}My`OK5;b0bNB2|WzK5+o@}dvbiDTVTn}{Djk6wXmal&ppNofEm~W z0553lLr_W(RUG3dF#U~8;b>D<*)$KqkjF3b(2{!H>#jj{QeN%WS75DHSbx=6V1u~> zVDth5hP~~Y-qVdw6yy`!000@v0TIcnlpW~c#wkW{);6l@jcg^{o05^;)cu>prmsrT}CCj6C4By)=4{8}fk-RG{J-_-F$FD6yKzg4Gdj z&_NuuQH`V-qyav=!9Ql8fCV$S!47^fgd;5B2}9TeZ(u?YGOXbZbGXAE{xFC`|NLQ` z6hXu$J~4_-OyU%OxDb4@MHpC|VLig_#4A4W5}=R)3iG(f60X1-D&XTG6S>F=0J4yc ztmGv#*ahQdO20oKEYi6A_NBiP{Tnu!P0+7;tg(o zGo0fr=Q-24&UU^tp7X5dJ@dKGe*QC{>CA`))dCKFhJ(HIVCXlXYfg>3!(ylxZxp})lFu7xY;`i(Fm|u&>>QZ5`r$NY1?Woltb;J>82aAr_7)gke%AD3oweir^JEl`L(P0T%Fp3m2Z2LGYp&MZD>|ncOu* zW+E||10rcyvnnXS40PxN9H_XZyII~`mp^yjblM(H+{(WoM%EW z$_#6G!yG0=Jme8UDY$VDag>5nWN-#M*1-&f5kv;=U`Ih3u?>7=|AP$>8FetvlqRQh z-YxI3M?*{m1BI{U-MNXk1I_*;vt{8IaW%{ZGl;U7J2ACTtUKOtueZAw#f)fFV?sOx zA^_x|7;T7w8oHq=0Bj%~si*-CieU~9Dxez5fc!wrz>iDZpcDESoI@}V%uj`?^X6B} zd%S^W6G4JKmlQj?oLlyp2eFxX5C&*xVwjpJarSZtX&3_{mQRF^#1!V?^ZWax_jU54!?l=AgFoCu zrM%$S%^(fVpsTo;Jj8+$9EK1`hZlSf?dzzB!~8UR2S4un2D0zp*5Ii%T|one(Z4b-q9EiT21FaQpe z!6LCy0+AhCsUDByi5*dpV#G{@5aRzW6x}VNUsW4aWYk7=)JKIB0T~R!Tw(`M!!jrZ z1yI8(kbxN#LpD%Fm<_}!0zfLRVk;I{88Y0KF%B>||4uE=<4=fRSC}4dpxzwO-`O+? z5QtJD9MNIWSll3^4+5NCF(Yd!q-!}NQ&d&tVU<<^fY1;PKNtiJz!wsP7G(bZI6htMIL%ATpJE-Cf{Ea5KLk^f# z1`>ocbYS@1q?YYZE%Z-K#-+HhB~rnkPWqx+0V9I=$Uij)&I!k`8Ai_mpi<&TBSOS( z_113%*Fi{1Hey2zkd+A}jSb*~Dck@KumU>({|`Z&qZ#bOCD;Hbd>>3goC>j!T&5;L z*dtcp<8A1pGxem(9EcO-)I98zVz^B~2_{m`-3KwGcroQs#MgY)*L~&JeiekIT-}=S zg&If$JE(&*n887uBLFl4H{?U*T^?Ol*%yV8YNjS@UWIGg25ef7UKR*}U;!?uom>g! zDSg49@Ma+%B3mTl?Ez=O6`@af8JLL~l|kGiMN)Xm<#<9xdDg~xhE944h;_7{JOqPi z4M#PR50LaGVgBY)PR)T*5-<5ufyQNrE=7XE#)8&gA;#wDKXnp=5A_ien-p64+ z1jSh##%bKqIbB3e)QNZjD|E{WxI$TkDe?rVQIzOwoM=BDX}cswA6Sacz)P@G^2u3!r$|0}4e7kj}5G5kY4$b%A0>#L5b9mXGCE>nZ{2q9Qk zES%19#9pS>39u$4x>Aw4{=^%`;T+asmvY{Gv?^;kpk?t zvP!Pn0=OziPjQ#RmTQ&HDV5>~u|@Y{ywtQdvBSTG%E+(N)O0jqxO!k+8Z5>m}}iqUov`LTwRMc~*9lh&5r$i`I3sx8x!jgr~|A0%!` z^wbjdNZsaV!{Y73D%Ie+|ChFK3uq|AKU`qoD$d?6S1+1rzzRned=`wY?G8w-dQL77 z>L+f{DdApjsf;cRrD11?K)|$H=oW3}rUlY!hSEkV>jnrGxE?Mz!Mw$-?7c3``ligv zZg1r6#sqJBxnMsJ2r?}m!+0DIea z_Jx`KLjVh~-4(Fm9FSdCIpN}@~{Pe zaOt8c5gP_$I0oB&l43yc5=*e03ex=6j_r~P?sgG6o$6XN!2f~*7lSMndj$}?g%ERA z7!L*!IR`V5Fh;O2y)m&`IPoGwab3RgVeN5Y0Re5<)>>?W7UwYyS1$--*5M+sAqz+$ z1Z5#Bh7zxyBBuo-tFj{#AtZ}R9K%pkt=C#`K)`IGCU-F>f3Y40a!bUEkuXsxqcJM0 zaj?>8x^D6a&PVyBMJoi%G37E~Npfozt|yDI%!TrCIIX-0WGN2@rVg<&TP-qUtuBw? z=E~z)m_WeT|Bp0hOe`ZrAGgIHC$csVNAljF!3uNE;ek(yb21(?1$(M8kDyGZg(&<3 zI)Lvxhf6#k#5}V_J)fN~o5ZSKm!)FUU_8k9pl?8v^FSx_IgcO|07EWNlvy}Hzz|qN z!!tFLr!~XdCy#LG7;yu4S77L7zX9|?#w;6G@HAgA#Q7;LgGB?l!#@Z_OT*SnBWO&Y z-b`n6=rG4TyeCivhAG*^lLGQM+if||@JNr~m0_$`oI=1Xbx?b8nS${>8-{|&!(ZYw zHQ|9ZE$v5pbx50YTC<^xaIRO>K)_rAS~Im!zh5WIG&ZMRMSDaa@JTSI#LP*-+w8PQ z_q6o>|1?2|^$1qXOm>9;oYXro^k7d_VH56QLv>>BV_OGC7T}*Oc(YuaL?EgT>)5qr z%dj`KG5bidnmlwDVF4s9Kv#r9z$n&egNtvg+f(ObR4evsv&2QK>`^kUF-nNGb~WYR z?S}AnnI!iM6@XLCD^$!tz@Wl$yL4&W?`bo4YOCnU*ff*+TZ&G>9u?$u-*t9>^>)9q z-Zr&ijrCO^08*#JB%ZfJ`!|U$_iHw{YM%^Mr?7mV#1Pnv7Z@c^SBR9tux?-Wei!r_ z_O-_v#To=mC>r>Ir?>DbxOpNq&Hb!u>D;OmBOon~eDt5d70xY03P>?{tBqxz0 zw~;TZiYq9KFZpwWgc87&EmTn4frRr?2ZN?ETCDP&xAMsF_w}NDuw81XN#X<+0@>dZlnQ#pQHxpspSciTvrM^(iD!_x@2PY6IZ z1WXMidXf7%`JTCnrg@#Oxkpg7RabfgarD&A`lie8m3um$ssI_whee;oX z_qvAvy0?2cE$)x818PD9j5_S1$$!hD13;sz#iOS&kNClY;AXvV#DwEPg-f-*gEYVE z^^Viz0H_zK!-8lF05=Rx&>#HnA^D0cIjyNSP4KUl*2tZgKwjG)mIS&Ca}XB@BlJ+!xqbP;?L^h zYkPsPyvxI>>x45X)BNSzJR{y+8?eC)(10iC0}hD3Tz-nNx6nX{z&ZpB8MMCZUj=b} zwqU~rK9r_VnvG=F=o`bkz>b*9sYIj2;g5FgfRYzNf?b3!v-B- z-uO2|K~0-Capu&ylV?wz9^NnsGL&dhqeqb@Rk}23kvBz{Mm-AU|Cc;hQn3zo3YF*; zJa(pJ6+0H`R;){)WbnC`Ezb&XDzue5m#%`haqH&QYtzNQ8!$UGaCpE`J{%(va|9_e zabw4iAw%o~j507EE&3Hy8JTlu&!0hu7M*bM$dU-n{4{&7J`g)(?!i5DifFgqV6nH~{D-|mAP(-Ozfg)#4 zL3AP}C9Tvk40Nf7vU)7-)YDJT3&}K-01%*@OAzV+A4jIFveGQK>{HfRzx+jm)lW2c@CuJAd@Z(2Th$D7(Df9xv{^>~ade_*Q~{MCO0CVdB4YgU1{hyf&{o`W z$z2HBiZ&2KjDIWj`7BUR;`p2R%7{9{}WkX6Ol(4Ec&e#%_!=4uHc2a z{Fh8+2{qJNiJ_IYp-<3oL5ENLQG?ub%Psc+WD4>Ym_tHNS!GK>o+yp({;5`gPRzl_ z85$y@GG9dZW!UE(9G=w=dF1)yXP}?@0uMceIGW#}#e|qyiY0ya%0?eT1)O})amM41 zMO``N4azA9n#y_!LF~2J#;;}2bbeJ!rx%8rPbI2y#pyG*z@rW+=r-1FFr`+{YD5oD z66?0F4V&?7RUqh}Ns+GiDbKQ%#Po{tNc_Eq-Qr`7o~oe0J%x_#gUJj{Uz z`O}~F$|O7U*bYey^pW^7M?d+Eh5@1|NHPwvkV8~P7s8w12jeF}$k|Dup{x;Ak9Zq#Wu9f{zm+2s>kfa};C^4Ov0^C?g0UE^&B2bPNfT zWWpKBsfJ(rsh4wflqPKYU1(k7#aec zq9FXR0Yr8Xq(Eenlqt(2V)l5XJ~r}KjNFqf#P5mR}7M-&Nq`6X{ z+aze1#u%D2;%B1uNh2QnxzCPVq9FD-NJSV?nOZDBqa{UBH9PXp9tE_a3+dB@zbtprlw$lZ!Q-@^bVLQi{QKwGC1mY;jJs6-7SBSI#YqjfqpsEq6;)kjN z4;jVq~xP>8m!m8L(fV z?r2=ZgF*?L)0Q4Kl8KcRW5u>vQo;Zo1;GcDG$H_4R7Ms9$n0-FBU_7f);^!rWfk*4 zkD@uP35fK94+aWWud>#cicQi_=L6f73D=G|h)pUGFp?|;DGR_gZ)CVj5#rXzxU8&U zuH*p=S_*IuTurTXZ%SRB|GKtfmt^L76Cwa+6oef&NX!6aaXA1l7%}Oc$a?A1-bU8& z5CVIG)4XB_85#_~t5vO+A_^Mp(r3i#(XPrIJV6C;vLI=AOdh@k3@0#{#>V@viCqP{ zSb3GhYs!L~3gI*=Bs5HgouYonYF%|InVl9(>y3d+27MI78j&f$3V;U--`1GR7D;i= za;&@^^Z34Nf~75>`!nh#GR-|Eb98xm&Ls2qYG{q1TGvVeXT-)5_2di)bODUZcA3x; z`7*xbHs&|)?}`*Unh=ymK%92CsvquBh(A-}*7lc}cy6j2Vv`LLfJP9&7-^wV?T|x1 z1j6%?a5+B=*n=MJ|4x6~<(tdACQN%q)75>goqg!(l2YQ0qG=B>@|kL7lSbH{Y4v(u zZP*WsHVH?o0v=dLCL_-f$v8Bt8NZE2V5_m&@B~Rgt^sAwOy(AKT(+`T?T}}yC)!6= zZJU<+GbtpD3&*lFX#Z_Pv3i@yWi9wwoqT6?mvjW!D2O{Ypq>KM0vLmMH@wSTzcAl# zdAJ^&4{RY1SsZN$8u~)hv>kBw27K3@>Ggg&EgDSxqa`9J1vl;?j#4m_49;N3I+(!& zgror(<$%XE9-)v%Yy%(JD9`*do=E{zA~uzv&v-j{aa6~b! z$(i7E4j#L*KV-lVWuyWjtw=^fs1d3BM4gEQ2*r0N zTc0F+D_o-IGU*p$`q7}?fOZqD3w<`^)5dArsc$>&-+pj#%U|3H@60Mj0f62!WD@8= z2nW)E6BvL3NI@IIYaygT6c9ojEFmE}0UHDaCa5IyN=X2o;o-)hM?z{5yzl#{?=i$r zG{`T1|Dfi_@{M7lpnAHX&HQcc0L}#k4*n!c?(E~`MB~Ip!V$9JUiMERMj#wKAt7?W z8~ULiwxRfx&M*){ACe9sD&ZVn17;{Nlg1!6P$7eQWCz*@2s)6)z)vAUFf>LGd!PoE zVu1zwWeAi;4+@C=RBpoF53wr6215e}JE8^7LFn|)_fmx#mSIsSfEreT49uVyvVj5= zA`RdH5)y(56XFRYumdJ=pTxi&3L+Z(%t$uK6*934&Fc#jA`C%e44EfrhUS}m#s_K* zaH!}FVGRabjx*>m{(jB=AR`X`fgg17AN+wIGKd4D!5QuaAtd1(2mm1%03KKcA<*C* z|0qEr7|;PBaQdcji5$QfVk7yIBm^u63p^3PKoKEC@iR!#bsPr1^u}jgk5AgK{Nixa zzK8zo!wxxu19IRVbD$bn;qp3Q8la&96rvK!!Osxj9hxu=-ofe=!ub+H8l+FvKCpb$ z;Hdrq9R5Q|3IP~op{~9WxWW+t#?dp%QFI)p!i2#Ie5MLk2erb;6{QUp-EIcu@jhnJ zb8wF{_OAn|0UKh#1bi}sYyclj;RbMk71&`l6wwoW(gZ{RHTK~WY=9Fi5A%#^1EQhW zBn1R=LC`wVBO|ggLb5YPGI0Lo35G!)48dno(0b6&kzCT=U{VG}j0WqYCY|jj|084n zUIu3JMGd5Z9n`@YK1vl}1{xBg5x5~AobDsOa&tByHmqR;It55htt&C>Bg2w2#*%LS z#dK_;R~Dw^mSzZKr5#D|9er&M=@NPHa=RKcbEvK$7|~N8fZ|5UGVcmAH?D*_Zqc+S zxuS<*&Mxgr^DV^0Y>t=?)Ft)&1G?0u}$sjxHAVy|IHXK3c3>=s5P*YAMJ z6AsTaHI*~wo@|LAs~}oIMzjSBfFW(}v#Ih^$M(~ufFR`3v0(O%EpNp%|H%+FVJ<=I z%oZ`K8aGD<(xD*o0k^b80Oks1Dzv07RLnB;PsVN-F05dhYeP_uKy!@U^f{ z!GJNg5z-w>2!bHeDbflmNb2ZrB&55$ySuvt327vhE=QN*KtOtDug~jq-rvvnoXfeK z@BV}R@~r#)al0lx+f{usE6};{J!wV2B&L?>#X4YYfS|4R`ICd^&CZH}(sQUHf-y}KWA}8+*=^e~Wx57xuTym?Dp0*|q?QPvao>$uZQXx9MxA{L-);6|G?Y_FZc zGOQvAI=_c?GzoP}4~30-6-f5CAkUwv#4B3Y>ft?E=xNp$Ru&4y2d%I!&dkOv+{;`! zEAb=Cx{wz{^}xHw>m-|Bm%s@PW{K?v?~zp%zskB}D-3JUP>tIS$7JTrnjYMv+I_l79t=q-xQA zbIdISH4?kW>-|Ah?o3ffz}(=warFT1Tra}~GGIZCH?qY&#D^vQ#R*8^mU*iX_ z!FOLt-nXBbVJNwkCc8xYtdp4z9wjV~M81rpEKht*AwDQ!PH*(^w zr@&5ywejXzkX5U^ZUF?Twb0i1xw(60uJ{#sk#!$j$ln@OVlQ^HMm%oL4>s&Ul&)W0 z%|(bzmo-hB_aj1ZAZA*SiXox^K|6)N@2p$w^je+1Cb@D4h^|I^yr&#$NPO`Fdt+xO zSvpoY^Ar4A;=X(CZu;#!>91b?Q&%$8@KHC9dFPMjXI}?jP$lKvhDpmYqzH7Svh53b zojuW>ed^6@^vS6=@Fw*=BS^@|n6@X%`*q5A6p|8VwcJ5&cKq~%rRxVc@yT5h!a-Wo&0`g8UrC{ISWa}LV1`%fkINNj}No$Fut z$xs=)QLzZG({Ql}uo?>xmH3-i*X7K?gl2s>-JkWobsBgYSok;e9`N)hS>y+yFvb8f zR6gCO{Cjcg%Et*zL3 z;W#`I`77DLjhU3NC~meb`s_k(!#!3Gm%9eZ?wihe zagl~u6;4m=i}h%KKyaC^!j@62^9XhsVMz_hL&|y!XATVXR;-gDh~@N@!&{T2#u{C6 zH(ffPMnumC#Q(MG`XJLK66r?deBhz~%^Eb5kMmO7-}!IJTI-TYt?EoWQOMuy<|n@8 z?!E@CzJI6zT$Pj^A_Wqrjn9~k$9t%!3}^0iq-Y@obQjq4zgpFkcv9VbV|%@`dAs2K zXv7>+QWyY9 z&0SyG;>Fq}?ApJI)>XUKQL~U$^wLkQW19peN}b531TRYUlq$sfYBKGRO5OL>8c6or z7ALYzshrA}wkJA1*)B7uF_Sv@;U_WEvAoFrp=WTf`FiJC@nCuO=-T4M&(c0x1@o!% z8^9~TyffcmN%2J#?i~)Xi+jg**mLd`MP9n4$2aDxyJCNr`>(G%zy4|Hx9Tyi@6l;Z zK(g^M$b#?IPnbTnTE120yc#eR?_(TqBBE>t;S;UkR@&WE-Y)mcW<4Cp>=_Xo{@o(h zUC2zpL|xR|m7L}3W*wQmVwz9WtYPGfM~O!sEw^q*2zInU`S_>S6T#?EpUrX-R{1^H{$7m-NmrnGac%4e4eS zzV3PgLWI7pdwqR*-n!cn&t*gDaIdt2$*|k6wmoZzxuU8!Yf6poFK!X{`6BwP7?kRZaUx!Yg6Xx zBJFKyEqT-$*(F9}R#I{ML zxvi=fGKoaDU8XBr-g_!@`BScE>jS!VGM^)p+os-Oso%P)L8up1yBogG?c}|F@y;o>G$62lbwH&i;tkY z&yCmGTOs|mHq zY46N&xcQ@wiwX>PN znSD3#7O7158GY~0Rl#S}d~c$DcI`8u<{{pkIIibTaO?LoT4U;4rWdGvv~eA#}sN|?0Y z3nJq9T*JQiH}60Hyfrv~l6%hTjkAz*H9dyzgdNxG9uwW)V#-u0l9v0F)0X_haUiD( zhXv^8k4r>@J&Tnui`^FG@FL(Z_!0!AfAJ~oxFEup>oK;`e_|BsOOKKLzZ?Bz6u`l< z;{R^+JDDhD!Jl@Z(jWI{vWrE~NJI#he=An{Gn^T^ZILYMzNe}~v!#Y8(eM0tTOoL; zRcA7magT_CklbGyu4NN>!lNHYD>l((t^Q!G%j>#AA7}h6!RH_%T1jzr`}etFj1YD! zA*WYwPmt928t~vbk2KN>lA)rfF_Q%&CJ3{EPAUzUMQx>lWuRQB;ty=tCv9rA7cCp+TSlVPO+4V8V z!*7+VPO|%^bMKhqueX=y{Ie6A%LNTQdiMp#;J34weYaJA0^QQQS3iC|VXz|^)LQeR zo;5cNY2|Ss;?uSuFbWePZe5U)qJBCPph8U&B_51)#bD&Lp*Ia+dI%aL8)X<0Z(Or6Y67_tK(7+bGBC2hp{|jbrrRFd|n6RW-V_hlNV3kolSr4;4Cv%=?}; z?I3>?5g&Kjn4RI)wnf=)GxSi$C*8LBZf@^*sL3jlyw%oUg=*C6?8@W|+xK ztSrVl=WHowV>smJCw_)It@yy(W!T|CvrCVZ?la5Yruv^I3-4LOar)~BSi%^685t6O za724+FXr7k4A5nGGvk>yBxyAbr(55(RJ&p-%m3P{{}^yfj9|56Ch#C=AmHnQ%3dJL zCV8j#@AKQGZJJ%G2Qy?$I|jp*pscZsX>N9>JB;&PG<)u3H=lZ4)znyi#jCv4dh6A|_v6|26ALvO!sCdb-iHqB{+J3@J58j3u zevsHRBt)j|Lpj=$b9@+dODa<$=uc#M_^L8yBgvyFI*|U$#7#t)l>h!qmmBMG!uU7+ z)E!`85ZSX(Dw(#2iqju8X2Qb#68kYlS$?uK&*tOQmG25) zQ?|ON;XJOQz}E*bXt*hauhcy<`~)4;(hM$!*1B8Xpiby6hgnm8Mz2N~8}BTnJfPr= z^F1Ad5VW!(sRA6t_O{lA3FBo>isL^0$&RW)gG$=$DUSt+Y0W>V=y%k6IOwz3@-3E% z8dZEOdH4zkDAT6f6Xf8*u`{o}nE0rG;4v~^_G)hao(#Q_LPC}vuVL~RQt(JZ$aGN{ zc5ATR#NPqhDSyu+{Y7xT0CUBP3a+nKFVRQ#Fu5jnw#&1x&x5~v^y1uqIo?jHdJ{+v zK>YVAoY4aSQ=q^?J~f-4vnsR*&MBtny%7zi}?DdhC{`xq;FHwVR?a&S%n@W}lFQ zH5~r#gR~VI$>%Tqjvo8s8E_dQA`*yQk*LGhuUk9$7^4=rsV}6=A+%SG372|EA0jwzVKW}Kj zbh~W4wrq&d0OU2|r{ju(`}|!T0&vKgf`y)qMHnO4h%pEpz!yWp02d%_>#c2wbk8!^ z{od|vh@DJ`SgM(Us#C3rola9Z{a%DpFHuevX}NXZ;pi8VMTZ_&36(gKpnmLPxBt_t z=~&w&3c%O8U(ycfSXzKIV=R**`-Ed0*abOA+sorS|2^~uvhn&UEX9`)h-}NMaQocZ z=fXnv>;ao_!<xAhW*=})rqynn?c|Gp5sAYg*%Ny0R-*}k#DU@UiMG`8rZ`GXXv_( z;IvOg=B%0Om^%HJHBk5SpL2p`{hW{mi~hymX!CmHzPhZ37C18ULRa*6?L1{x?R492 zzs+PKwb)mFJr*)T2Bak}fiL(5h#h($u4#V$W&<*;sCq3xnjvFq9nJ&HmhSst{2>DT z@ji%E$!YL1H9HigKu6F3F;TynYRAE$9KHzVVl(_{@~9JACOv;ZzCn4iU{;h~HD+VI z{0*0Wx7DNBGQ%OY%O&Se_zV-VYgs?F8LCWSgx@hhFo5=wk5ieN;lr0_OmH!@@mBfM zv&144V=$v4N0}jldh!B{N%IH3h`pMr^f{}t?>c<{`HD=@j`F0e>z94(^~&Med0$T- zsSo@HMdW+&1tUSW))TbB?Rz3dt|CbO1La5*;iqnmTZYZnK7Dg5`AF~L0$gMnlGa5(%xihg(&en0|z zmpJ~;AwObm&(A#su?~J@ivIU3{3*lysmuInhyCgI{22)Xm^lJiIs6jPKAGgce@X)c zl4UjBK7isssSP7rUgHB58T@gHr(?@a)g);e>{3>*PrCUJsk2dEr4O& z0TJr1XYPgwv2-Pna1W#9PGy#w3-R4EwofC8_JhYcfJ*CN?9!ob+M!W&oog9n*eL|=qmJG=dGa!O*4@N~xn?6QTW??vd(L(rG`fD#{{6g?%&z1xn%@Y`V9v1hRidR21s&F_4cBukXio`9CBgBsCjidLe;sMlg zbR&_7%h*GL7`(-&_#W{OEJg3P3)4_1+_@`}hDS4$M=x_EIy1+f$i#A#Cmt0fJjjoI z8XqZ0lJuBA=^0_7v`3PnPNK`R1kQ3`CpcMyGx@a=CRx)m`E7WzPIEM#+*)K0Vg8Tw26~Y*2?* zVxM+chirUN%C0@0Wif%tBmJADK~lRs_W5y%lWb*?bZvwb749}AlAWQGldY6JOC9@# zT6&|L^vHu@G@TYL!qTJ7D@C2vQy%$AB);1c6LGVc+wPdy^c|2j1#o$lhcEhoFd`4U zln41Jz|-TwC7plIDjyp)rLM@Q9nGgc04AV-^jrn3$_1=f`OLZnoD~K4AqCtA1&<=~ zA3zEP4hkMC7e3W35Q-=itH?Kz))gZxk~yF;XG)j1DpH6jQmQCY87)#fD0=xZ&4j7w zwQ{i+GZ2F?p)mOa+#JCQQ1T%B3GZ zW}SGHo_kQ8D&<0hN=M2|L#9hzmCJ%@a(tJv!ZOPIm8rZ(OCur#;;hONmCFOT%71v2 zr;V2Rte2%jgmSLRGY=y0rwD&Iz}M<9gnzVv73#3_9;kpcq7+5^*AF&~?MUzgx6p9L zx_5JN@HGUXk4y!&bXqZ5Q3I(2F;_NORpOBlF8E;;Qb@>O4dz+O{*M*qqKL|+idve= zM%~I*Q3OS>2910*6MI#0M)lxQ^@uV8SO>+R0{~ONQ7m7IfH*?{mZ-{}jG8YM)qtMr zVJifhs}|G?s^)|Jts`y~Lfl+c_EvC0uV~5j>R})25eKvsnY47v^;Dh-8F4UM6wnI= zJ7x!bM-ZE+gGv!FT0TUQADEX9Ji-JkdX5;%gLaDkkAmkEC5uYK{m2Hcu?AkE#)>D6 zPdpnzju^siGy#7P$S#gbB2`PKmGZe>!vi7!XJ-S?bp!u(laPv)!I`Gv6D@H!Ej_&^ z*6U^^G3@3ABBieJkvm`!1vTmc@AVi0P>s^uP0z+C-$gbVRyLU|H-Y?H@reKl(hv&( zC>9A%o@$h$ZIaU~&pvEtPJot4BL;dP0BMjm#Bq<05Wg3ML4a^&2&eME;zWSFIAYvs z$oLdxzF0@GXNPcHN2N8Q`nrP!3Ab`URL<%G(7K)69Uz&GlE@B#G@xRvqee`Z)m68= z_)|@@y=QOd)M4j$y{eCR()?uUNr=UnLr^z;GLahA|v0H8hFff)A~h+zUVJ?vxiY7>p>TTbzn0Tba_gb{W%65|Vki-=C zA=M83jN@McQ{!Iz6Wd-B`%u8)%EWKF$v^s&fILDBvW;yD{w#CMx@FAscycFd;$VE@ z1~q}sqB>EXq@XY})-p3sF)J0HcGsB3iJrzIp0t}HR?{0F${GjMP2Q?bZ`n)()uw1{ zr+A6KFJyuC@(6J?zOT_uC`8YQ^TX1_5Ei?Ym~8ms^h zde+b2uFvRG%)T~2XwtX8a)wn}_g_c!yOYeR-OkXf&*A&eRfc5NQdrx5eWwhaSFN6M zHkdDBvdY7D761V4ssa6#+4$>OU!J)DV!$h6K+vrvwnQ81J-Ul%1CjLE-7I))0L!GS zvgvANY(V4ocu|yNYKX75E7SBJzw>krFRM>S+k^7$z1LSk zIBQ^>)et>wseA2M$o|aL{vZxx|I(ZC7ct-6`4Y^EZgCfips!i*G+4q2kQN-nDu@%xVHd_2W00cBmU=FA)N2`piF&svaBDbqKNBBLT9)gKg(e6PvGu+oh;4e z`eVXrB*QsvR})S}lu2~PzF8$EW48rieZI3t53!z=&gADk==8@g4`8}#peWP~)d_4;}5?S&sahY6hI00&A8bAT@KH~QHZX1F{*n-ZpKSN^e!@O1mESH%T4VPBQQBO&b?^ zYEX5WTzlR5``79eL^$#guFwT%qy?%&w&PY>HSBg%?4G`)tw#O?@k7FVY43<6Yj1NN?=>mG1CZc1E*XRJqg{gJ9FcS6`McUIF@=?@J?6wxBHx=TTEPgX7^5r+}IMwFVm$Wjq@WJM=zD>kWDdOBN+^6lfO$__ECC#-WVV^_wuq&-( zS4tCr>+(2slA5@}a3F?VZ|GIq!y*9_~iDJF^BZE&KXV^6E{O|WY{&?{F z`U_~oFX8tdnXN1w8xO~`zbw&TJTV12t)^11Cw`-k52H^f(*lD6a=`-aa1Z7M@pDqD%%vNhsaKY z3yx?GeoHA)Ic+gMq3ScC4f*6z#H?0i>GVSMu<6eex;qc^Nw?E{Fu?egPVF;mAwI*2`dVGCxhl$cDsKG^iW&@YQNM&p2u{lv zlYJlb{Swyn48UTD??-y)fvZXV4)H!cdWf>Vyy9q}UH{-XWrRSE- z_W+e!V;|lEM)^;*oyMO0U1<^*c^tyeC37ODZed}Pq&Vxm5aPiVSFOVXmNO{-~htyS^`lDq@rYnt~#%OP8rW(Ti z%BrfK2)pa@ztBGgEc$na6NcNa_l-R?~7 z@9*#K?*5DZp|RfIe~EuLD=XLY^LI-X|0nbxW_lW{|6!&>|K9*0W@6%UYW#BID;5B} z8XLpXe^~eL@@o$k`a2!(x%~3wYN+J0r{@x@{I#}T)Ysn*2VVCDUw`(y=`y`(H@j(h zb=xF)TQ7tj9sSeQh2{PxCMK}r-`wCJ7X2F@9v&DN=FL3uf8E{PSog2Jy}h-y zwW+D8{=eYAyK2?DDyF+~(z{Z~-^!x?svs-_SY2IRQBm=)-G?bu!Ww{>BEU_N%3U#N zxiIrTnqN*%&P8VCc}mLP`1rd-nd6w)e>}i=`svuX+W?E-fkC&<`nP6p4xL?onVQ|{ zNZ-AbJk-%WP2xWH{h{h{XV}m}s{c znC@t)wrJ`9VF1ZtcQD8ugy0Sz&p=uli~c=-{`}dqXR@-g|GIyYl9J-$;v!i1Pgqz; zNJvmn@PE>O+}zy%Q~zUSW&JG@(!+xjHg`+VS~f>jr6n}ckOatxe{1@9=_vFP7;d*kk8o}Bf&3RxUFynMC7 z7v8$qtV^{{?cI&8tLnD`=fkzHovpur^n6IDQ45L*37z-e+4z5)9e{cE(Y z6`TZkP41+KAPJDMSbGr0_y~EY{U-af!?n_2Xw?7%PyXK!6Fg}>{{m@iD(1}8v z=NWq$DgY{!w(1R{M`J5_S{CcU|Aqe1w@vqkFokfi1mkl&Lm50+N;Wd!p1`7iU|3LI zpx_*KHYVJFmk;3FLT&yB{WF1yhUNFis|xL#K!8lA1^TZCHQDvwb|e?4@IwTRy>ZI` z0r(~N!^dn0+fQAjzO0tvn*LVSzIWKtaU?c>k@HT=&1wzp9plgUY%=43~8U7x~po z%ToF{Il>$g1Tf!CQ@21yuSN5r-cU{Q!&hUEGcC*i_&adt&1hNwYF;p_{MEAJdiX0> z#UIIC0}+o41b5v2YdaaW_$xn+Vb^Vp}v<_sr*_4R^;6HS*zr9nL_ulDP zPOt4*N=A3)28^zJ8Io5m?rwgpjqagy`+00Y%ji{U1%Fg^WWY`tRIAR7Kl@ny(KUJF zIMtuS-$TN?RgD_Vlfe$1uEobM3Gn!TCUPtikdN^Q7pqQOd z%fhM_2*oXn!9yW4tu?YvJh}ZpOCL(|w zUrDagWzVIqFD;zSzvsZYc6XN|C2MmBI8>;+YxK|~%*_#g9D-oxQveWR-SZ+$a)LmP zCQpHgzO9$xBVw4l%rS)8rGViHUl_xIe>iO%kYTh^4{|;oPJu>}(V+l5Y4uWI@~w}H zDvA*PGYK@$122ewiq}kNH_Z~Cq@e!T0dy*q;R+op4J|-mJS_mh!Z3g=>(ZfF9YT8; zdjQ`sgd5NU^wC#ln&1eQDVvV)f5RH6O4cvMCx;lN#tqKve?{}7K{l+J&&57y({@ln zxMmd{nmme|nGe03Zv`Oru4an3y~h6hZqwU%C=dL)gq7yuWg2y zzy%OKAPO+yr@-@=8Cc9;?Ig`QN7GKO@T4Unx^hK{Ofjxqn?=QiaLJg#ZDed}?}X!L zVJ=_jrQ|g+sjcE^t{5WylmCnw{H6_uxI_s=4)Du(0PwpnvabXn=z$ha4T>7oeR`e4 zpUl-*+%S`#Bvf&dEWS7(L02#0Dr)`a@t1sh&k@X|&y`cIqYk}(RxiY#{FUqYn|C7r zJRoJ^+}A%fddlh&^8$dn*H%X>nrk-c{=wxPWA$4_Q=#Isn$;$G&~$Kn54GxV8QQ6!1Q2YG$Qb^S06EHkpi;~9|Q_)hUOtaL?_5tApn4U zt4)S5Bk+0h+PBI>Tx&4}8Zt#xAXPK@p~P-ly=cm#5{KwRJu~H`jE({DY}%02yP@wv zqJNSgRKdch{xCf>iYZSUU);zM@^Z(I`mk*1sStANVi|Zqub{B9`SEWjpAxS+wivWCvEAOLR_n6-7?}8O zy`v|2!qs`v0KN3L8-V!za@d;k&nRBkVQ`J#{04y+9V-qxy2fjHbhUNkZ!c=L_T_~h zC1wz>XFL42$8ba(AWDejiKDq_^BD3LtniyJ*1K<5U_Ml_>8?F<=WC@J?f|6 zJooPrx)zO3msDovcS_M;y*2}zC^3w>XuS-}=SG>??qlvprm4;WChZ)HJgRrGiFjQp z3RDZN5_W%L4^_Lx#WKcp=B87}GVrk?v{P{Xq8)|TMCkfdZ`E4=g*CV z2X$skNL|f>oX^y*RFhaMqHRH!&U!%lyf@}*(-z=!>7qR2q*0v(7qiN2!>>PSN0;t5 zF^rOs6j-;Qb>9RYJ!!y^4nKfAo?blvmK;d8Zi$p{CS0O|Kwmx*06V5srsrwb&KN)4EcoqN7KtH}ppkI|>QnXie5zfuClP!0aPR01UP&x(f8_PD>)`s%Es*Pbt#ojS zV7aB5O~NRn5g$mZq5Y&`apAt2g-{toJZ-hQR1IO##%BgxA~2FZT+fq^U0e{JV>fSSJtvOiWE;8syEc z)M~d&M4De8gFT7x0J8FLo(I1H#}n?=!7|xAx`)hqc4ZIP$pzh@d`!;#Pks4Ke5FEt zuP6hw!2t<#z9b72?!|A>A?iQ=zD;G-4l>ooCjp-EeL(CzCv)egO>>nube(+ypjq%> z7Ybm}4vHT1b#@CFPqv(R;vtsi1)@O8)#Hk$;Nd?Ax;78eZFA1USDi`aB`&m7=I}C6 z^gwBm5Bwz(8p00fOyv~q*xG`f6zRWF>c6*mY`73)Y!O085lsD@oD$$0rS72Z9^~vE z<}e@pT*J{$!`2#;@6$UJ`er9o%8>w^;{R6BcjG)npDHx$BD`HAlqe+#8AchW=>IA$ zLTWv*6K!i#7GakboF^QKTNozzAv9|}Ovy1qG%e6cko8) zJ7KrIfY8H@pzb~8?^I-#*dk(CxX4g=?r!+#MYL;g)YwzYjy~=ws)r(c4_URMtG>h# zI^vA@!K0>JYA-_Rhok@E$6W1EZ@4ohf&rlk90`x(ST{K0Wa9{Qn3Ie+A8y6G-;TpK zBmkd-MoOZ`Q^VHUVre*Ew`jk`470u%WA7X<)n)M3_4;8|&6r`=>ejgSHN z5bbbV8AGkle&JuV!{AR-f=1%0smXr%5i;e$J(v)}Xt=5RN1o7Bgou{MVyL7B&hapT zw068_d-Sk&T7eQdw=2LC2^VGZ1IoZCOc5~k``GW2Jasq@bvO`*{|)_XSITT5{4exx zKeNvxYqUMISZS`BWMCBoTx=i&m!PIZPRds{w!@6S%kzCd!n1YMEO@nAsqb zvrd@9M^m^eQYfgKE%dQ)I=xWzDoeZ~OF7Tj08uElR5*HBxNVuZOI@J4MD~0KT9cOn z=*dX1OkH}NZf%+zzo+9vn3l5`vRPKd5P{u+D8V%}nL-dnhT{VrL2)|8sh7#QiwVdj zA8~%1VWwCD3Y&mMq}f%e;h%g1H!#B+$XyTEP6=kk1fIc2r#e&=ms!MqsIZmF&(3VM z@U}AY>nP`Eepkx}JFkOH_?5{mLVhv9Taaq8qNQ&|%DqM^_c^EJli?Wo1-? zr(@3)c;l8LKVL=GRUjmoiY`e@okYEjMqL9cDuYKVGlkQeD`dYf#q}yjOH3CJWt2bL zt6Ix=|5elwBV5&^T+??@@fZikW0b%%qMTwee_Xlb2Uo^aNA$Ods_fU*nwHqEF4>Z0 z@bXp7*pk<}Xf3TyEuycsE~wV6y!JP4d_xD(!f+{&HUn&3LLgSNr(9ZhVFD3DJVI6p z?$mL6#8PqWjs$rPjQjX4YF3(!+D;)`uH@5iESLI(0CA5BR}bdL^+| zlDDmVv|1XT&8~V#-~HC-haM$-#3~hSoZPJnCH00XSobOV4l zOU* z@fui#CO%b%RWb1bWx$gt*sm!lk`G~vQ71;%!CIz(pm^{C622}?us+b<>=_od+!@bh z97|hgELK_C*(p-mVba%un-7nH0IJX*#AU!6dBhftpcXV(pbm^uCj$23`~(m^%>y;Z z!OBQL!(t#KCgKGq1V0nJJPwrE1D6d)gkN`$Q+&P}tM9n(JM|>vMY?$*)3rM@YWWZu zelYP~98?|nyAa~d8L3eczc?Dsm5P52cxaD;mpMXK_z9wyYg0BG(K_-F|CIYc~{ACoc ztv+xoPaaqgTE}{VC}I;_fJNRvp5P4MQxuvIgrhVmjJQ}NkN7m4yD+S~(ud3(Fybcb zOooyZj-*u~?COZmridH4=?(z6K$0&ENaFE28X6>VgEZJwooL06mjeJRLx9Z@#1jbi z)~qp1-5BsVBkX5)kA6^}*Lcjz!0pn23HQj?EONJhP{FBxP(gJTtn4?TE|iuB!wwHm z>hJ-4ka>0Ac+O#v#_$`}$uqiuztE1@tYYTu&;0!T7YO`<$PV-<8GRjyw+l4SL?jmX zeinlurjsFUJQXAxG1SNpLwpkS#D;5!852@`mn54K0zSLO#|_v*vf7*JI+ zc_HC&X5Hd#(DYaXP;5P7cr$6YE-d?pe1`~N!$-Vw4UOkSc={0^*TLHSK)adUhs)ic zv*vZ%=6SOw)g?anL&-G#;GaN&Y`dQZK z+0OB}*aEjh)r;U201g`b%xURtPj^O}W2uNz^rEu8elgOr>;AuCA)^IyRSg$t<7<^s*S;3m#-Fxjkd2P32?Rs_1i-&BcnJCD6 zdCDO1LFA9#s?~#*hAY*zUhffF>u=h1lc!zZ=A%)gWk1M|e&idVP|*mp56~8gA9n^n z!YWZz-F+OAWQ5Bow`gRq| z>K<*x{JP3HzzcyA)g5i+w7mAAPeDQ>rGEp-j(Vbh6V)Cj!T=x#*La76>zut|9!5E>ZLx2~IB(s)Ct1-v4tvI@>6ZO=5x*;$$xBYRI z0b?u@nuz!-cyh+ia8CSk|DYOA^tpjJ-W)Q6|Jwm zc7tENU-JP;W6x8gavxpF+W&a_o{~)+dcu3-?@N~JK)i|ZBznq+m`0Jm#yw&E-Nbh^ zFY>aTFRpad?xuR;x>@+|Ck=Fj-|db!*|;=zgb!|)hN*uU1RO&Kq~QQ4!!rWu0jYZs z6o(>}#>TUVdpry-1jifCW9Z4uPN`n8$;Yv(WjyqFWjd6AL$xjkHryVMgr|(&k_LEMR%F-1~uE%&u5S z(FG;r9OKI))U%i;eQNQoSS|N?w(gVt$^5sUL+HgmV5}FLZ9kWI>;1KxZuh{XWM{%9 zy?Ff?pZ=n~JlV>7-->KYvozk9en9Q{#^BoZXtnFLloHc?Q((pt8sRdL@=OD>(m8~y zaOZV(_7D2^9^-R&dyB#6lg7bktCI%7pQ%fWx%LjF;xY#D_2Kh}Pl#poG@{u!qi{<6 zpi;Q}&qy5m9N69t?sFDAxl3m*7#BKJ71=RMa(upH)kGpf=ZtHoz~E8H6X}W0-x&Jg zC3qslCLhQU(%HB*qYSkFw-Z0Sa7suO2HB17x)AM)P2s?$~^J{ zUsdmQl2=DnNrM^XgjY`|UXd;RnaT@!rOCn=MZFWCWnSDo7f;$;cF%2!iU5xokj6~T zuj|fAXX#pSI`bsiK&$XTl!r*So~{p7Y;5v)R%idTs!mIv@SZfK@j+cPwo@Xprx&s2 z8H)%mGAzw;P;a*?5NKw<_rt3-F{Q$%)M*dDy}=BgA4{~)OgW5|ViaC*l) z(ro$D#n-6K72!#-cdyKF)y}@27rY@eo7E?c;tvT5dmo}R8XjG7u^6*@^|m6baEY1= z@8<BsFH+m-M}5zq%_yAN%BP6_lnu93CJ|>DRde zm~tl0gyGGBj9@;xiqHz^~faT*WV@+`P42TTZT6-Z&U50 zOaVM9Y{N zL3XH!a+=3uwun!L_;`E0{WnY&a^JUd05rIp_mj3qJ1u#>9|D;u4& z;}{YF0cIWvrjHv_TCPk(GFrmkX<^7RT7#7NiiO8DUCAERd{Ow36h0!7(3ti9)EI)J zQ^UnpY&#cZPE~(NZu=@eQ-lur9^4bgEYr*Mm5xvvbfs$l)me*#DvETYU0qf_k@f5} zRm7V`JziaqjiPvXtuLG;{A4;_`lr6=cKd|WBHR}$Z<#{ZK@ui(lJn)TOaU$c5P>Rr zVxsm{`9vvPmJ*6umelzu;$9WRSQIm_TIxDgd@ufXQYdN7r64#;6vTGMqSeJElT6Ww z^G3;89?v=?hDNGNtEkE>xL<=Xo$rw+_LYZIofGSK%# zXgCzUWlyU%u^r$G-Ja`+%I6vQc({N9Qu=-1=ZQZlSgK;6Y#)0P#?f$Gx@u=`I^eMQ zVOuZd{CQDvtYEEb`?WzU`Fz{;D)NSd1>%t>N7smyaVfq(T>5psS965-YfGiF7e!;A zDWNo_O~uO1dGYf1CDQp6(cT(cYuN zRmk zT5A)%?uqwaCS?n&Hge1Kt)h6B?Yy#TWlzS#7dJLlmTl=|PqS>tDoxZS@msT5r*nk2 zRpJl5hAHhA_6x-jY79S*wVL%@sl#{fu6r;)H zyLhJh7oTW(kBCw~p+0aPwgg!);iUqTme#E;>%Nq+Z!pakQHA1AF)OcZNY(=D(9=Os)d!wPJn(3bLf~TG&kxQ9VXDl5 z!cFVR^a~rr0@@&9D?fY_ua(ii zpOc6(-t~yrcnZ0BMo27#;I~Qs6$>L}3Vk9FMo$om-9fWg002dw`bK0YKI6>PV4Nb({}zN#JJ$aO@7} z6ajJF|Haf@ct!Pw@4}y97-s09yKCs7ySp1{h7^zn5tJAhV(5|-6(mGTR9cV@0i_$1 zR9d=3=J0*b`#b0S0ekJW_ImbOdtc9U-5)$_Ru!4>456Po*^K*p&;p^u?C z2Hdz5@lfE>a#xVZjNYgtNTf6Xunq9?$HNnc z>Kj9F5Kz2~1O))fWIh2sj*5b{U&ukP_Bw9l@}xj&(iFX-W#W?Ijg|hm0`!V$`SNK= zDs<{y727B#L_bpto;8Muv@+hKB?Y~T8|=Y=i-D*B0Fp>DGyo09MVZaxt!#Akn{``G zFgdQi)G7L)yWCy(sn04Xi3}juX4UK7&}5QAFzuq@lOOHSs>WEEU^xV2$^bvn1_D?C z-Wl--7~0D}zB?OY-UaM4YfnVV@3g$ySJC7((;VMWiF6%!Ta0^=nd50U0NPi1r`#c~ z-TfT_mCVO0eikn(jiIauV?(teR#r*?r0iR?tW#`X5M5LF^A8cXosj}xqr3??SV;t} znv5Cc^1^kb!ledGaPZ%-W(Fg&>=Xg9GErrTKxm;O0+rj>myrE6=0-cniOnTcvFN$* zOQNpI{jb?&`05#w0$mbb;!=-_UQdd=*$o`tiy3~mtdlLES4bOeyby;wG#n$YR(D%E z$yVwFYpL(6{jmA9U0m;7U!pdWg|?nQUtKYZQ6Y^%(}t|9>XY6`&qxQS-k0Ff7x_5r zNZc_F-P&oX7IU5{AeV{F=;yNzqZYhSs|4G61#~FN5}6QMA7=up*&zHxU!&P9jt_+v z+5<+r1a$jkhimy>V#%Oi3~%+n+%UVd;xYlycB~K*1oQzsLBdMQi{DdDpC@aCS55zrL@=IK?hc z8;ou?|LEhN@_b7zFjk*cGKfi`!jDF?CK!eq{H-y(Arge98W+P+4qXY3t1*XXhOfg% z&_v^t9{_#VJvd-~B68A``#`5265A4QmZ3y@O!QkjYr`swJ~fr0-(p{ zj;Dl(W(JzFG!ipum`=A$aFZELWvWwf@e#>pQaYK?#7)GaYA-RQ_{WpN;3)*vln9p@ zt|xB2ODt9hJ|*EcB{@S%u+S1OJ8B~%?pUwS>sAT5$wG)g!EVNoZ#`riDRhrhxeO*b zB&HcPrq#D5RNc%q9#3y&033#l*&8P`BFwq_r}Y(5xxpO0`ojq#5-!RT_Y>ZK+CJA* zfu8q)&@IuI;l}trf&^Tm){VoiM`*!$&fOY|Pk+s2h-VV;bf1lo+Le0WLNXw> z%F#QUmc|X=M{f<2tpG&-z)C|n|JoirBOWWjK&=QC0~ip&Grkiw9Q273zy7ri+-zixmobX-9fa`Dn$f=*0CI?C{4PqC|?L zSl^5UYh$#^YJ5lvLyq7Z4q01M-6g#;OVQgoOl3^YK1c>RQaCfeHaVKn1+p7Y@Scwa zOJL~6AuH^5HU%SX^2=hnc1>~m`SvTxv_R)Bh!)27u3@pU-{$Y+VrnSl0V^7d8Aow2 zEF)8CtK{s}bXS&q>>GWSlAtKvt^|jn7{yh?k&eYZqWK)CEt<*RCP02nz+rmD0qMMu zXK%CA=#W{j>*kN6ybW5cUD>j*gGnSt`Wv9((UDduAGSzV9~JxoJFb=ECv1EhF1LNr zv5>h9tXGTO-iop2LJq%F%sEQ90i!636K;urT00@I25&YL9Iq_w^BOVuUE{ilXvJ+1 zh5u^5PcQU`jo~)Lcr}*pFxIvUj|dNmNfaT8XCuY4I{oJaGlXh)L7ZuULfhy_`?Z0W zme<7i0We4u90I3K@bkdCqFf~M&9Ng_WR7HGxf_E-I&Yjg-eu z*(f|R*aJb|9M2PHLYximx*x2DKVtoXt^TpV?HJCwF-g1+QfVW%bmLFjHV#YD#Gp24 zWmJq00Z_Tu<*n;lufm?OWND{q-=x-rhaCX%bjmVnf5106pyQSsoocsKW7ZtiaX5+|+F*s2PUvGu^v zmaQ88U)1hv`kPQVZI;P(^w3K?$wT*2_04b7uVumNp09qz)Prre6YMY#ZM(n$&;i|n zEqiXqtpgVTYSCr{AnV~6{KMT(@mDq=It3R+KIBw7?uh+EJHzGw`w1Sv3I&cT2B*Y> zA6((a=OTQ5Y#>lb^O)q-gU-fVt7XSr5 zMnIm@db2G5KJoF&5*i98eygsxA(8gT!QHzo+AA4_XQ_;_G@cNM+|H9(==5dWMM9VW zDE)CfoFTL??Oxk~r9QRje40;ku~i<~W`V>n?7-|s&A0s|1n6l#o(U|@vlyaFy)vGb z4<(3)vK~xU6ozRdY@|i0#vk=ld$NY?XC5A4igDIMzZlgm4j=x$%JIwwfNZwoAECfn z3wwvWOTXP2cgOJzjia9+(6f38bCI5l6%Q72#gkZp^EsLz%u?%$PwO3WG;;DEozHa$ z!|u?3c3=0u*zhk>A20so&mJBsVu1cX9J;9aG0QHTe)eCy+bR<8O$lQtSiYtA^6*u9 zwE#5zs7ECl;qhCv3wVcjbjP_{l8doT6$Q|4$1uAc8lId|~V1XF&V_lH>7g z0cRMaHT z15scD9i^Tu|MN+%jK)fZf)+Tex6%qKRB)gDJS$=KHG#)Hsl+p{h<}oy9P!=vhhb>k zlYu2g3=z`tQsFw#C`ijTNU$Ubw&0Y~`J^f=&O{kw0)4zcd-Um7NQoAOn53=f&zRi9 z$N8@xN%&pG8gErPZiT)L%@6y?K6uR&0lAdK&|{Q}=PrC%o|3Qwl{GP69nQd7rxkhE zZ?!P)@y{Ms+=#W2cn#n17$l_O0#uC?A}>$MA3hD@2N=%oS~!M2fB4Mx(GiW!y}GAk zR1C4Cja5N{!;Ww}rNX+NoY$SYtua0{PP=xAIxpyi(tDsCoi;ZWIl5Vi2DNl!$3b2m z2_eOJ3PTnBcjwqHo=f6F{qUhcH0%j3>A&Tlx2~NS@=&~}Z3tboq{s*l}rOvmJJCNBn*sk*BCB+~u z9`ra@4oZRi*}xLH2Y~``Apbx5hey?AQfyp&KYoRo;OxxLq9+&$=*qr-7V=5#T3M9a zYp)Zs_#S-p-ubv0gB&Psukk$P{$3>ed^OiTItU7nOt-YLJsX&DLTV@m%^)E zG5@eX{@G6NuSR1i2<=Aa1DwIBhihWyFijR&I$X71%NZg)-vQ%%n*d*fh9*c*>N+hN zP-{~Rp?>9K%SGwZO}%`0@K@^Sb>k`X-M(!waubz<?M*-UBO-v5Bvu;Q$@KKDB zFeRm{21_6(%Kk|+8*Q!!+14sBfrPeUP?9v|?V<`RN>xv&tZbYi>SpBvBa+?nANofg zPp*RYHZxLKBswuib=q&wWSCNYea>NdZETE(Is>Y?QZ0sXn$g__ZRNb7EQ`U)Dnr#@ zr3x-e(~`GYBe)Aat31toUJeBfGx!y=8}aCa!-}4p{gPqGQL>08Rm_4yQI>W(T5H8m zxvStB^nu&a3AiiAq)It=8>C7QM#?m}Kal5FVHm!$BUMS^Q@$$P8Sd}tAY%5km*nTy zQ#B2T_%^k29Vq=`DrdYQcN3wcz1nmtx$!4>kLy97EW-Zv6r|=PZ=5TvsqPRdXeE z59Q9#;bf04ibVAzH80_}8jh}EzK<0e?<`MfWSObOpjK1 zST`g(mc}>aD<<0wTCDcWXPG*}Kft5?j_)onM{>>;(esU{r@KF3qk{r}fKshz`(5=9 z(_T|Y2T6bH4bH#1rp6Z-=hy$da7sl7@B9`8uU&|Fc*3hLcctx}Q{2AFVQ*C$6>dBr zL@mD8f8O`LnkO97$oq_gZ$9Yv2SgvqdW5sI>FHmqrj*4tV0WU3{WmuE%Sh>Z?=dvUN>P8PFQ>gt8zxEvNj2V|8?AVt=v(I(TH=iA!w2l5sh6vI<)#5>!?VQ zbm|+%LV$*xWJreCeH$9v(yQzoT^@x1`JfqAak(&TOyr3PvaQO(N5{#Df-n+pfAZ(- zm|iBK%tVQ5))RRvay?o#GShbU39nNk1(-VN7@&)_Jvu`&1BX;Ng-y)3Sd(nt-`+qx zi}basTzTIyH{6U4Lih$H=j}%LoMDM!%WAO9IK!E`k6mRKNo3FZF>}3&SYaN5q8|kT zL@LWvzr!=EmSZ@9=FY$mkbHo8%p-^iib<40!1%`S`46ng>t2$bAwr^FT48@qArlJ* z|NI!%imQPit3fF{lNibG$6Vinf3YTxSV6xyR9Pqqgn#4TVDc|Hi% zqZ@Cv9tcJ>l#oQg)j9Yk5>2N|@WDVl(W;5mz=l%he{gNJVG~#vu#{baSJ#ZdG^^0O zT*!cz9S{f2aA#8`uY?;0RZS&w2bakG<2B}8oGQNGkRWFA(y#@L6mDa*6bV*jc}>AC zSL;e99lI&<6d<$t9_n%rpbka{MtAE%j7QdwCBjDIOV>Bn`bO~EZSc*tPBzwsbnrWz zR?T&sG`^4g$8X04gzJq;LP>;GYM99RL$F_JA~9~`Ay2>r?_f{$!feQ7BvscgW+w| zNP)VoZjh_O5Y(dR1Yz~!7qByT)fntxR^Us1`}NfIuyQ03k`mA%q$o0Zgh+od-OKS} zs9#MQfQPs(r9dKq5Mz^g>KY)!Duz;3(euTvC|i$Vcp3At$s2 z->DaeQF`A=Ii9>oYJzr9J_MGGEW@q2!c!RTCV&ye5{>z5$rXMeix~$nAF^sQx0|H< zOq;Q7Xt)AVPAR`wRxJ5!b^Nmi0MC zwO)X?PiOG!)I^U;2)T%)Nyv0n^W|<0V5c_%Sw4xA`M<;~nbZZnfn6lt$MJMEK*oQs8vFW!o)=Px9^dP-KUA}_&;y)TG07;5}f4!rH!bL zcj*u;B2U?njZoE}0RX4hmaud3pnTn|-z`1W=3f@$WbnKoD%7r_Kp@aMt8679Z9!wiD&qjdffuvfQmj=wTl8|PEvu;&p zD{GddPAT%SzX>|7OflgrnEJ=tc&#oq3`iG)Ix`gwh53cto$^B>jtqrvzr0f>!c&Rv zvf1us^!Rr6_5n8S1UIZjw_>nlmkL*%y@w8(^qj-VH zFsR(9@r?MK{Q11L?NrfEn*sn|Un7kgFO@)brmhl`y7lo#b&ozdr=-Rb^1`GE4BJ${ z1o?y&`mnHfy5rwnKeO|!nBVe9;fcsfwg$snJ>aGb$InH4Pi8thPl>&`Z&qS65aQE^(uPpD9!iZ3#e zTP15-1;x7FCNvQyv=hir(u55F6vSLj+#8_ck0WbEh0}*-1t^n<6T-WCN$SZ2S9_F= z(Ze|mfL9N0M@cCS+4tm~K|khntxBlL=W%_VqXX8y2&%xC)TlV~DZ;Iz;)%I94MW=4L{kCkyTw-*#GXg1Y_b40yQStqQj~=pLM6#2nN&KZYKpiLi?I^ic#?q| zJWoqCELk;wydW3Q7M+fcv5)SS>E_|HlS^CG$wfYCjFs!omY>L0Sfg-J=cMK}wNT(R z)J*4M{+YG&Kr@gXe&_leTwcW%Eo2qP2DhT{&ZZ_R*SWA6t$%Y_>#FB%@gRcA{A&?- zIt#X0_F!_rkh}l>71bcvy1%uxDlHjfxhP{#j7AzGW3-thlX-=cuJ2d5LIMNl37PV# z2fsEQ+WM>rG_CJkZJw?>@#VvwPb#qX#8BC>r~|9tx!5;3U#4n0Wc595#M01q)1=I- zP#Rk#|Kl>mbJrtsM^d_La#v7){Dl(aE|%|!VPksW!Qm!ZWN*p+(X~Q*h&FYBHZ6jC zh07))!`(A}t9@l0bW>)$_)Amrp{(NX90OHv(fN&UDs+aw%+@R1bh+G3w{+EQ?2HS` z@p)FdhYso9iWhS06>}piD>T};!NWW#e9K}){`ooZV&PZF8_p*o4>8Bw8ZArrW53*I zUIJbjI-~%&{4)rRae!5CSL%Q3w)}SN;;|v;3Kn`9uV^i?*2{^Y^$F~bJLa*!`@Im# z^D8G-db&t!c{zHPN$nSy3z|u@4&u_@hOqGfc;9{(`5mwMFoUE#SP^S&p{$k2H@}hT z1ipA^zRP`CP++k7^2hPZpZ)L^gB)QZfJ2M2$Y`%9luUfLa>BS$*Q(MH=^;7!@btq@ zBpZ&Kx@uP8`Z=&X`&UKOo9!n_W=F)1$8K&bDkyyfy@Non(mY6U9Jjy_o_>Q{_$#iE z-916_?F;vU8Zsc7ScOLWdy&`g#9uqvsynaN)p3N7P2yD#OKkHTbQCc=Z-!F~a{Efx zHOhS7yr5@((NkCxK!;9c(^=ek8_!osP_3()sVYm~M+Dlupees&;tKzx# zSOxB61bSqu@S&Zsd^}Aq!y3um%l{|0=m$el@0X# z$Wbr*X|G3yRn|9qC|+hXEfX5QyW*8g>krP@9b4$G>37W;hq5Iz==~gzu5au69~{;z&tnI_ z^K{j@&)?+1tMqAAtzTHesv+R2S-G08?-cN1^4Vty;hu%h#)=hA8Vhq`LN<=EmS_LG_Ix;9AneQ_U9mqf4GzVoW&iC@1N6L z9XqkJ>8TLqbc+?-n($>CuBaSV6&g{T{9To8U^8Q^4c*$z+&d$;uCu&6 zLe@RD+{do1Zc=i8Qu4r8@!*|R9mE=?58pMK@5%vi{&`yWhx;w)4!(+4*OcWaB|4v= z+mkI==PK&AwBE0nPKOBvbSo|p+^t~O{n7rH0TjfZ+G<&n@1_|s;l;ow$STVRpI>#{(o=2 zVnd95we^kiCzQ5PB!B%52;51{Hc2TCVGI?Wd@3+}(78;(gy_+lpa{|18VV!-E#D8a z_^8kEql&j`{_Y=${%UML?FaBX;%_jV;&+>H*AcJ?5WYX&tE&Mi9qq^KQ9cO{zV$ouRiUm_ zuuZju?b5m0B*HE^7SIAyS`M~H6G~NY8s=eR9cY9dvwf+_#f52uV^clezIuErdTzu2 zn25hg?U$wqk(!HA9~ZXwm4T$?qccN)aWmH@d_PH`5-qs^RHR76TFoKkg3(4UkfZtJ zR`#*{Qb;L&mkb@qv9b?jmuNi^VtDGWgsr{KeSd93_c(I%xymmj!xPWaCePQB@_rwK zr07$$rSP(2?XbQ4$V5!oR&+ocC(1US2b9d zl-*ZitI&{*%Mi#PrN7<@pieZo6T&EL^*X)X-`uM(7HR(1q0{f0)ErRgxo>JiJvq~P zsdE?hYDdQ2q0v!~<8!mv`2FWAKPWR?If(@oD2Zpwajvvnk;8G}c3*kSuTv?sB0GOa zq9yX)dvXj-KQ9qW3~EXABaPu`l@pbE_N*K{o)GMab4ZQLW~U=IbY0{U`qFXxXQa(Jl=ub}`srhJ!FDc$ursnf(&pR#oD2>!F9m_}# zXwA@~75y7rSxTC_G+a;dm%~i5N^1rOe#72<1GGz&qI^~Z;(IyQM*340|F`T|oRoO<+xxd=Wa^s$I zUsSr+cY2Jnr4Xdyq&c5wR?qjlL{&XvB)dTJ=4uQ@H#P5<%v-Ock&umaZ;GS+e;1wk@tAnG{>15KF(}m%Oq^Vg0R1+>Q}YoC~SU4RN9g&ZMNEjNW~( zxYzt;uTyb<@XLPl7n-hUno-5W-(L=!?<&w9WYc#Cf4=Odv-RM29)F5FkjmR}d9WiK z^+=-gl!59@j`E2~A8o9J#ZRLM-&k9 ziXY$cBVWMv4b`o>A&XE9+s4*kFvxZ!Pox^mFL{stJ(7x|Rw(rLXcD|DHxwM^1kpR| z)=qtRE;(G$c#r=1nCUCJjHG}+*S`o2*ci;@f%yORGzW;@Meo3Ua&)P%=5SQ0a;rX( zUqmd8(yQ>W)8F^?d`DbEvhzP{gEWpBbYHaA7e428mX8&2p8(aG1fofG!-1Q8Eqw_sePJd*&JV zg;wT8iT#MLHQzviru;5hWN5mQQK_{Qvu2S;>i{Ce-3~4hHQ=c1rBrB(MiIn!)KHJ= zNs6h-RgB&AgwBzQd(ts|#QQ{FVa!x=uB~f_ z*9^m(WW`PCp2bVq+LHwewJn5wR*U{lPQbqPAf08D{o%~hV+GIo>Dg_pb{1Iz8{5xl zd`pq}^%lF!9*@D5hROIXesUIj)TX3@;7xHaK4ywvN+XT|S7tNF$g3HdL!wAGYizpl zb|lS?)?Ho4yl%mL)AWa+Q0D2kfag8zMn3(M{*lY8nesyW zeP2o5-!;9{9F6|ch#g0=gn;P1PZN?}d&?oY^fpID%%a;ZBh?$s;V=&xFoN6Xu*bp~7wi9b5@Z24q@JU{;}4JrwRG39l>THXP^C1vp` zH)?B#112B>^J9?re}7yI#Y!(Fj`9B4O9K^W(g$H!xs!&d$QkohUaX}_o<3tphlVO) zQ%UeU@~yINp1k_v1B{y!L(Yu9W$UHWj$V^vfJk5{S?4()jL)La}cd*tVhBDLVKbPgPfOTAsstXnZ~5hj-r4xIj>SD~L$VvQ&U&Num7oCag6k zhHh<$pOaf7k=xmsqWN6C&4i8a!es16{WwHfStog+baEQ&Y}JBb7D{p1Tx8s^q5#@) zNbE^R8?de>li8~RGS4<&u!cRCy{L%{Ri{6V?IH|6i-AU|GXcPuLBV1F%#~~BK(C<| z<4993NEg~mdE)B}TJ{HKt6L%_4I^(-0@a>~b6uQmH)yS@(OJOQej@tgsLB0vll05> z$>)c_Ss$W@C<$m+GwE#+tZ>5dGEDHXTG00?icccbOJgP29L;ifznbu;vJQ6VC84uNbjglS=k&1aE^-QU35VhLp(rI*VgOfHQ zYX`TAg=f6mk3*2vvaxWcD=Vquk-=Ad^Xyb|P7Oeo6$KA5!@`?z3AnaJhTV&yv3N2( zI<4&8thDibq58wBMFxQb*F^ya#gDaW#J~~L(uBpzFZ5@gloj_Q2+{MsLvj6Xkh_tjTXM zqgpl8JO%iRmu~k+xszZw^nq%7PpD>m}@$8OFXqLlF6c0=>zZ7YhZUyv3ScZJFpp*y`KQZ%$EkJ{0miT4NVWCvQeahM7%f zs+8~olj4dNe|>N6Z8`2!sxrf|3`b*`w~%0{tZMwjmQto~86<#76k+fX2LtuN|ITGo zaNPvsOL1&U=*7jg2?n6^<=~>7LT`GRmmzGgX|~M6<)xL$4|`cqFRaDx!`OJk#5bO5 zcmW=zvU2tP4DR)K{?joWj7W%pZ!y}Y3@uko8%O8fl^BUw`k&O5N&NG0J0+<0PK1OQ zzl(gJn69b0+NaR}uk;W1A8!*laVgd<6b)bpOq2FQs->+f;!(c7(ttDx^-@``uV@7r z03b4-2Ei6b>jVM`)5h6pnBK+5p|bNeHYN4!ywL=e812^*9AH!)T z*$Kont{GKEjj({`QIiATkhxp0T8AV7b0FZ=i~Fo~_5WtA(5E^T(FAGFOWOdnagrZD z=Ioivr+IE`d5w2FlGG+*96AN(-PkYIGa`cBFDJ+`z;We=qxcm{*KJ$O&lY$JzceiL zN|M@5`<{b2eLeIYE}T~)luut%*}Y5|B;|jzy*;crG+m7EJW8koDD!)|PuMZuBT4i< ztrwKakr!AB3SlLAvP$pjv@Tyv|HcWV9YZm$k`H5LP7x$tccRdZq4qD~s08lX#hox} z14LCM+}R9KJfIKb71G9y^N3qz|99#L<-XMAb&iIvxY5}$LL-A2yNq1q_@S4}pF?8? zcL3Pc1QJlpY{Lc#R;FGq;e*vvx{`sZ2?3)>7Fi%fU1hxpk!FfyG<9LYepfd17|G|G zAa8{6cKJ#5k@}k-DVTaX16-kX(ALUw3dga3=44c6nH;ONRMjqym~yam3~@#D+^dqW z09NWUVfwTKhW%)Ue8FAX523h#rn_ir$u|}#Et+~?`rkX`gj^IK0w{ia*^xvSRsxg} z?inXTloR7a+lP!6dnGtop>K>?B8e?MMw)0v-!Pu6wD>1-nyw6yDemtM0Aj1~JUGTO zz>YAc-`}~cP26lu4a0RLOxKP=x7yY{xpq9^*2L_OIT&`_8KztcGuB4dLAh{!9)ntr zM1A5V*xfHbDh<&D6zj{oHR}1D2Qfpm;z_*UzVaHZ)0c{JM?JE^8k4ecswft*z6jrc z9x}<;@s;P{`@`YMXl`8zSAItUZ5lj)P^ONM=a_L<;MsoQn7gUMDCxh+-mQ9g9FEwb z%@NO(Ns6;Sy6S`bcO(nKkKnjm@F%&bl8)#e315&J-$p#&H#LGAOwZiA6rP&;VW^1Fy!X77wvppS7>?v1gwmwE zU)`6Xx47i|v_=Cscl=!yVp$%aIO-^*{HHvFv*op6RqGradc@+1W(cQUX~HQ*qfhR; zr>e>Ts%iM6MQz#N6lv7c;=E$*A8UG=C=`1TinIJYa_(x_&Q#@s5oIkg8AARi1Wq;I z@f3mHs=N)dc{^MOaJf!Fv2UdWhj^4Z+^8l|^#F5*kx$BcpVXsGW$1XoPh;>_vLCSr z1Ci4hzB9!~97=KSO8up3KYN$gkuNIY+HV83Qz>Og&6z07;cnuVxT`a!XgXaYA9m&J zO)*^w4_(ja&qW(L>Zc)!#|k$eNj3LAb%{&$pY`x%OM8n+EyKQ!bK}jkNt~$=iT>_u zNH!E3G8Crl9ttwcmtQ&qO(~X5xEmx z1e6d)gL>*?y=F5Y>EszJH8bmpDRtsc);{jU>ueH+S)o1s?(Yl_!x^dL5{VoryXLTaaTyz?Ju$kxPW7*mUAr^!c7AlA2!CT%F7oSC` zMuaZ3%ynG8p{p9Y^w>sy28~=hKYE;Bc=THOdpZ-uxJV-&D127)$&2y%L>;&m5&*)) zq3{CZ&V03+w6k-pGn;~}V*UM;_z1J+ss~5$L>0J+*U# zq`)5wDP$OL7j>lBHRo*KWRi6n*0O+8x|m6Njjf|u2%Sd(EF*ZuXVtrryTO|G*!ppA za75w-ip_wvC^6M|G5B8X6TmNwqLX_Y#@>3WJ>b&O)an$n@S01i zNT(^#VkV7-HoZCzuo?W)iEGLO$h5!4=;4GH-u&v=EH};^_ieG_8$S8)+3>K17x+{~ z&9iShB@3eq?x=H1fL+nT(dAp4p2SjKr>!(SYS8ee04=EqwZgK9u&{!>B4L^eAghB* zZe_1}#pjHQH4woK+%F!bBwB7BMqeD!_Q-@@D#n^Op6*Fz8%Nr8^+H&ImT#2W?khJ@ zMd$_%W)+GfnOnJtg2+~4^`^r9Sk(Xl_dLLRD)o0xD-)=2F zwr#GXqD>-`jikEKxV}-pZPNrYh^@I4V!H9^IpljAss_vRJ}j1bx>RSssisM-*_nxP zX!~fe`SF-Cd;)~;O+=1xvpY8{d-Au6OrqLovBAi;+-RMm4#+&aM(qo5ylo;kx~_Ek ztm69DUCdT)ikOU@3#BemO7lXWG^BVglMbo^>0+fBV)KqHZ{-)MDYaFrco9|oSM#S@ zP6*IgN2KBNXZ@82od@&)*dE=~i^d(Qmu$ry!kZmqg-zc!9{fWRwuCinEZJ!PZH{|U z9WB=~Bf#ac%EB$wh2{7h2|<<+x4#G9{vDNlhoJAAD8&x}vP7!94U+6MJO9jNt17?B zY7hembfVAy-1mN_QLCs=X<63j_M>T$u^t}*?V7KC{R6k6f%9jbp6OOr8=Q7dj6`kv z(@U*xcx~uqX&7Vw#?n`sJQADbirT+lDP}*H*je~64(h~Ejk4jLxQ)!o`FG08^ehhz z$`5?qfL`^I>KcCN{y`ZwaClOa^h{t{S*?OlgE+1-1YNs=%9BHABv zkHeOT?TdxK{Is~<*q8%1rQzBY6STK)@Qkc}Ztlre4Q6nM)}!8UuM*gJlnx4R{du`0 z_+?thx(2-ZR=|mjIyy4I!6*1jvB_U}_z#=amy2;z5KKHxWx@KT!q4-L;uo(fwUh}+ zN;bk(cB!I+u+=|yoxXfbDw0V=x^JLF}r zb_JE1>mo&|Uc;LlOo~>M0y`-C(NJ%1;X#Kjt&XK@hK+w69dDI)=QwH0BFUCrFGR{N z9tExBuwTZN;a@Ssnoy(6zZO45TxCaY>B)XWHXk1s;<7rrb4QW=vbgc=Jbbcu__`x8 z4M2zh8^@hG0jxs5-kkw)P+k9n{^3Xykjvhqf6m=;#4J@;Z&lw6q%z8JpB;^%2QxXb zdjB8#r=ylky(1d(uAD7L{Lx~2qS!;j4ED#W?UgZa#WFwNyhp1#C zZiW(j8lXk&I(w_1rNCA5A6#E}ZP`fHE`GG>RHyYah1+EX{!XiT0jpf;APGD9M=0%Y z2p8m{W0(yj!|zUEkc$i-7j`KQWup;z8eHpMY1n4|61|04sMUGAHq|Kec=1z}?R%fU zvnSodAHkD##H%4H9W9S_4~gYNzmp}R>0V3+CLL{!zM!~e$`|e3%D1of{RlQ@QMM_R zcRN52D}+C;dErQK*Z%a(e_3eGhc5DVhgwAT0sg-)cmJT)LT#=oLV`@HfG9jHbIXIs zD4ho;{xh{&vt%~oCR8+r7_bB9)e+8G*v{ihX74`}G)3VV1yFz=G^A`bNeJ()y3-fd zxhz8A9~c)M!NY#m$C}Ys&&|!P<7TXCbV`U6;{iL13Hp)?4&Gc@P{yRRl1k?^(t}F3 zJd}O0wzIS8np=UpB8{nw0>R~KwvNV{HA|442(E3J!Tp(6)s}+7>~LT1H~yBQlJF99 z_UBs#9v5XEr9m@n?#>v>RgZF^K$*EhlDi?E5Q~YDIFD+dMqJS=))SuMvhpgMVlzpr zt&$EW&)4NRPF|1dIPl3lorSjvyn|Xu%6a{LaCq6`BD~jD9@*-|q$AX^^}7N#(_X*4 zYU;o9@%uKoKi{kGPTPawI$hX+TX$!<>kRuZLIh&f>_oII>?sp#P5M?(hZ?=Eciv~3 zq_xyGugqT5)*aN1AOIF;Z5Vc#xPAbVaN|tK_qd9tKO@lY!^7A9@-d_$y13qN8{yeG zg3Vx#@Op3jgct7pk_=}!eaTn;L1Sw6;bsGkKHe`W?8522vO}ThbWZ+H?YmPrpLsk+ zd2AxiM?TMZ@sBIo+H|!h@|q^3I=;5go|C{AWSE%qEMa0DEqs96FeJbx5pVMQ-%6Lo zBL$Y#Xl!3&xmRf|oGNjqqz{ZydNsMm_ra%NsgNmJqaz|Xpd_IiyDEnN(-k&VJMVd^_FeYVNHzOb^ZjhJLff7>SxbKcw6ldQB3v`@p$Y z_AF7h@b7^X0W#u(!y;<(F#X&xcj9#%UJ0yYl>-0d>z~>$JCU8bh@e`AyS9sqpIC`Y z?yx_!SH?~>&4;LM*p=}B&0-$a1zSd#DB8irk|zJ!LO1HFx)|)Iu99{1UgYkP?nl1q zR+0izmONuRoQUG~NfCelsO;Bg1XA5M_WtqWDQu;0&}7iNaaT zW@t`H`4&1Tjq@v&X#q(sBSCF+4m9Tp%7*2rfJKCiGWfz@H|0Y+Z%`wTrJk2^u<$a< z2KJ@J9RGy;g(big@l#wkZFx@J2Y#0Xqzbum5GAZ9M%CZ|xRCu)+a@HIC?u;Ev+-;=RrUKOszKbh?E|n zOmTojDeJEhN8e{lpm*{7G!swx>{&B{G7`wM-zB z=}EytAC18PL$3_|8Z}lXWCEPFINBl@UH-A9UwQh7lnhYJ_>y)A-rxj-gd*S5;PaVa z3FZ%Yr-ih)^x6vn%?G0gHriLK7WLaBD5>6+DW?Kabp&dGB7Yr zb{#_DxK>vgYzLlJVZZfyKW^TopsEBxae#Zu@>ga4Qk3LwhR@>#l>ZTa39dRT%%^wN>MJ~N4bQFDBv={zc{!i;z6iM*7h|{+E!x$56 zQrcM=f5eWyU)xmb-C3nx#IBwnDV}@UdCepHJ@|v`*-ny>y0`N8=-=Ow&#%s@ize5< zd}~>H)N-5_CBKO~;nOGrOlaSW_!Iu;^G__vRo9 zy~va2@7uS8)2~M#MV=P@Y2Og}5F+Jpdr;Qt`1vQ(pD@z0FPu^`i{D88);{dQ<+K7a zTPnva??qm=|LOP>MH>Fo1$ouSq6l3D#Qbmc@5||H(tjH~EH~5dzns5}3McK0{OcH{ zaM{Tc^amYvD@YSHI^z&9(cE#iKgV3_Lkz%)eX&mZL+{^#pWm0|pF)3M>tPd4uu*_3 z)tx8Y{QMXdjl=H}OOIIO|8l$M@vWX;> zzVHB6Qo!?LsJ5d7pfr5>6o^m?QE4=2J9>{MMrK|NFEmDIn?l@!LfMK!RhvS+l3Wu* zuALt%sVyd5i8h)?$it&)Dx(yy(3UMR=2mewm?*pX7>BDk!w|HwcKr2ew9JGf^*uIN zY2h7e@7p4Q>%nbm75^A6@DL-?J`nwEKAvna!EZYOQeqv1NeJ=4#BRqflqW=7C7|Xp z26zb>R~{~*m>gPxU^pfjW1&Cb5#5sbY8z7kPjHJ#%=JhbHOEM1V&k2L5_PAO9-bw= z;fyy3O=`?XC2k89(k8uzCS}bh*U=_|L@;hRIJ6>x_x0_sl_?`bDc`nJ#-OPa@YE^o z)ESS|IZWz8W$MyU>dJQNPiWd=DA^}*y0-1)^!dbXXv!`$dESke#>D3so_?yGe(sTe ziAle%O#eHS{%<=S3(WxXW`J}uz@8b9#0>m`j8biZU-@Y%(9HIsv>y%eO!@q{|BJP| z{%i96AHRQYgE2PPMoGg^Ns&;bQBYFCA&QhRx&-M^!O@MBfaFMN=~f3KDJ6}7ARXc` zklwY|`~CfX@^)Q6UFQ$`2X^eZ-F7_B<8dc|G3fYF7>);>>g+uW-^hThax`q+z2Z z!P2Du^rTC)aTo&lf&g3jL9h{9h;$UwZ9hhNc2-&T(CdfEqs2N!vKplh7}Y~o%|6!K zGh9-_c$`r(_ArG-j+~gv5(}1$)$dC2sd?!+`VwiIam{jF zi7(w)Q;#K6uS=%AV@NyFPixjsHBL`uoJmEsq&|9OoJXU9#K4hQ;qa*R`26%J|Md8l zbc?z)8UNI0>@m##ueA50A3MfmZ@%JD0c=Ppn-OsO2v`K4QCgZ&-j`9inem1;v&=Z- zHG5`*V`kG~MqN~9TVG~FY35tntd6LR_rh5pqcXc3v-)0T7MErXwq(`QX6Cn;mj$8wO5+)Lpb+ODVP!> z-HXaSoXI-wBj@&Q=8}c8Kq7<=EkZ?Kj_AuAL_guNPZ};NCN?oGagTuR=VCHJQ@W-s zvjlFFY>uOcT({HCJEbv*uwgjz1x!*zTJz(*fC3EiHyW8ovK2%lHY8A=un@=+d`TI# zjYr60(fn>mGWtIwlW}|blJW)Do)pNn7Jx?!Zg3P*slaBjsO=GW+qm}ol|l)T0x1zR zMGlnjFSrgbyeWci@X~IfDt>p-HE6HUR;0+$qzJ+Xd?KMp0%*|$#II^(34s746l%{F z#=5`Oe^P8vR!lYe`nd=ir;J!rM$HpxsS-7pSCJSL@I+Bswa=CrbXU- zfmgv0R^@o;6$#j{YTAL>ieZjQ;^*|vnp)B0^nuaZ4u(3SWL>jVP|k3g~y*t@Jy@com>{5p}$X z%EfW6C?hDmUgx!OF4p@ZW4v1WB}o}joz(V3(U zK2dZI0ktp!wOyoJz!`l1V^YJOLLw0pf1TQP92>O(mQaAiWW$o(<2PpuA)=)g!uGRk7o_d zS~U$N!m)$xy!?`$xtp#9-HO3N?D2@{MdMP+*-K)ZZ&oLO?+)JU2~zA06NN^6LPfRr z#+~%$P?O+*fK?XLq*ZKvAxlX=va#2M+dCfnr{@D@7R7+=NiB( z4&>1F=hFd?(a10GZmV{X4ISVY+xNumQ1gnp_e;MWMb@T!C@ z!Ug)&2mXcB9BVla2^zmWIPOn9;iAx3@q0qb*6zm%tLbI*!-r_?`SEhr$%p&4meO{1 zm(ljc6B^m$E~gVh61EB?R2CW%k=gwI2pQ==VSJg*i5_^Qi*}_40+nool&0TQAWN|5 zDEijr&)_#eQ30+oRo_}>(xrKib_zgkyCGzVT%}Yd&57VTBJy`Ny%oR}=Tw}!)VqNr zf+gS^%BZ30*ReHU!pngNmr)xS1mT=ojT^Eynr7P#zMKlZ0?;hu5MVw?E(R)!gEkY9 z(J_U01}Z2CR^|b=A^Q2xy7QB9^Rt8V3-k-oPZ4uCr~)1_KSD<5t2-6%zrp7%Tt?52 z(F6Y2`Kj!Apn87(bbg5*c-82bz3-SO?NsFBw0SxQ9$KIdT>RmJ4ll26S*b>wF05zQ z1~V)|78YQE=y1-VTAZU0p_xB^q2n{Onh3o@f~H;O^!Bm$7g(t6pbI5HaFo58gKI5R zkH`mJ1`xJr$RmK*;9j%q#O|UD_rno$7LjfMRWk<3+s$TFwTg#>hX^z>Sm>l1{oQd; zxia#~ZMfY4?HU2K0?blkwJnqaHx5}xoTb+9OQ|T#>1TV)v%Vy;4%T1y%~=Pk*8|Sh zgRWcqcOx6CHNQ$fk3g<_=&k$2uiJ5M1|rEDkVKa+hO-&wukk?}IYS$SvkhuXV({&f z@aV#@cO}82ThV8m@jSCsmd!prrps>I(YGaYFvwbc=cZKW0e3Lj4ceh{SK!ZVttEVH zgez&FvDva2OxeJo;6GT?1WO_nU$$!8ZmK5S1ceJz)E_L|l0f?#+uK~zoo2=v?hGXp=NzT`R?Y?~HTP*!9pmsXHhcK*jp76zq!WUj z?S^mX5`3AMFk16)zKBdp$fHz@(G^&F%;QhlbDR?5zYI)&z33ppNxkT=zpUS51@RF3 z7yI_&TZ|K7ukN7=yB& zwblCgX`+-#P);g|G&|{G4d|q|Db<;(fx+#Fv!gRLH~4S-&4>(^SJ{{ zaBkP=SZc&#rrRF^{Sm7bCWq|0-|a20>A=qil!2PZuf{E0D|Y?U?jmpg z^(^4zFfn**QXQK2gt8Gs1F$WYFFea2%CUhrYl0H|iI+4X_nK8e)byREgGFZ^C2JfG zpI{fb9zYqXxD~C4A=xUwJ@?eutWy#(G%J!Jga-~FVu}mwyjq8G79Z@TD-s@$*)!|3 zAt;?0TVw9DvkPS@!Qf#T>~-TF+F}-COSyiXu^PM-r;|E$ow-Y$Ie2ko9SDi%66$;2 z%cdFkd=5fL@BtPVbN#z2G_u7I*M4JF1urf0N;$ZtKv_PidJ<&DZ9FkDOQM>3^gYKk zv9Zilc(gAdyTse6!c)W-u4?N2=f2UOEke#Y`YURj!Rny9y+I<1uoRxeIno%mlC$9+ zFha|3XqV}|KU1e^=?;~Ybxb50JR13s^<3GgT7?rDMZ&0j0~JusZBSj~*Vp0}O7@qn z35vMc9I|iz?AHXVFi3V!J=Z&3F68qDVRR*zrfOTA*JI~eZ;;9CA&sJU40rECrka}9 z+>WH_zt#!2&b0_)Kd~R$q!<{sl`U4@%yj7-@kCb zwLgFU{HN@<`{QhP{@=LY>DJcS`uf58`pN3**+$p*@87q#x3{*oHa0f?Q~CS$?cd7Z zF-7^Cm>|#Q{%_@PYHDh7a&mlpd~9s&^XJe1m-u`BpTytrFh%zJP5J!vX@B6;;c)L^ zU*ADr-(hbrMfp4U7xZ_~-F-ONaX8R?^s$qo{GGmg`}f_ugSPg=hQ_1b*GC^x&bmEM z-g_N4MW3`-oHnYT)=K}I_}lC0p(ua<-^5=-LqlzCZFO}uxm1xN_??w;oV}($E2287 za6GNJ_@|ukp*-w=Sbr4R?{8lIes=cBD~Hjnto;0Z0)dd5o12}TeVCB&Z{P1Y)@U`( z>I9EJ^S@2PKi~B6%E-t_O-+6I@?}y|(u)@_Vq#(TiR4$9H6YXlk9_5~wpWe*E~ci;IhslarmDowcGbDlxqb5^mjI>?bBBDk}OPtRFu=|Nl1qI5;?1Sy|7WJIBJp z!owN)LgUNlW;*hN2jHBbs+t!sn4&xI;v2*aqlhd*80t{5(A6aJycw*+LgJ+0B+NL zli9|{ABHN=$^58)_dJtcEKAhA>NzOnCYw+$Vq&B~J6G>?Bj&j{^N2qFp2FXPg|^3J zRx=n}@aKMSHP%tNDDbcQZ{M9BAN;at&pB-${X;%{or6~bvEiOjGxjD2(d{*1 z=}t%TzW$5#^E#1iCIl-uPV+^``ycQHb0*22S4E0Y^~-rY-1rtF(QR}u9J6*YKknK$ zuY!2FpAJ@$O0)F^D#GVgiL!;gB`Zlf(*BHbtK7;RDfbK=S6>?0m9D1p^e%Oz;=+Xm zUea8YDojwB^b*Lp@ol>Jg^<;2G#7biapfP@Pw*xdjKL$6s6;jhq34`7@*)LhLs0ey zgpGm(^{wEC&`Pc3qN|n}ju~klt(%#u{ZYIi@kr7_>3?VawkzrrSI{RrR#LuQE!QS&ayzTD<7;irVow>Ae_;OQK1F_ES=^+N>bhhbX;6`heCD z-Rok0@M!PjkB%?7VCLW0ptlF#?x~=d?`>CRP?0lh`vrX|>E^|?za2MtcN~8W%4$>D z_VEApdi+ji@6i>1Rn`E)C_TT~*H72hcYcpyA=Ov=Fc6pIk<+TVq>fAO^9_?UA*X)^ z?#4Xf9n*hZDV<~RSI2;p9E%+pW)I4bQ*Qcwg<+D)pPZfaRS3k>JS{?tWbCy260tuU zD|2S`&+Cjx_*ceC%UvmRZ0 zfCiVUU7N&1bjNSeKxtK#&UHZa+pPl$o}laGD|`@)Sw4h&*(iNEV*jcHz_23ANYziCFEgAr=LwN%6Bq7~+~#6H*-783=erOV+VG(xT6sR+oQ7_%w2@?(wLZ`AwQ;Z20xM3q9%K ze4oa#F>anQx`@~6GDn4eE;M*i+Hg^-r2g+Mo`KZ!9XBSc(JIKo1V7U?Wh4%%3*gWF zwk-al{$NySzdjme%dT5ejS7$m%2%1^fLxqnu(687f+Vvb+3=cQWYI+&BF%Jus1Wpdx<@rJx*jSy5fmFx;gP0*-ukZU zdu`L%UHjtn0z8!AH~~t9Z2K}{Tk9V)DCF5wZnnNf)hd-J_M}+*;VWiq-b$lLY0iA3 zkNj!v2dgFip1}*RO8z=*+y1z1M|ct7rSfhvKr=u_c;Q6esNndc)^ppRUqRkY-V<-D zRqxikpd6BPaOf@iw#_WkWKJhDyz2|KzPm&f<`*O$?ydtz#|3Bx^Zoj`celg&D`W0K z52H?vt|49Wxh7U3D3F%7HU`Yy!aLthsPbBIE2Md52xsPkBgorN*nHa zRL~iZxN;Je6gWn+UHi_}nnLa_w_@lOe+Asv-BGNWz2G91RPjcAn=9mC>Z^y=CE}yo zg16dQ>{5{#F@r9G+?f|9FVNaG^eFuZy7O%1DrJ1L{yr%78wb^Bx1d<(W~S`ZPg9ec zw8b?jNulYBUoaPbJEGX3)5dh;i7)egk;$(rnN%aE_Drz9`c%Zob)T-$yc zz>52e0Onp^`h5C3FdODcqUPIz`PDmhHb6iA&9JulpRo3l^*$u7cE832WMOwF*>`bD7QH zb;*z(J^u`i##eTa+ty@$_%tV{WM@#9D{ed9dG^^LSDe(tKAwOIKn6Noe&HEzdUN`L z)X~@Q8;hm<4-XfTPk$;QfZ>QcCz+4mV$PpFvwItTcce6>2*KVhY_}H^tHW*E(j?T^ zlEcVIYD13CT_>+_|McEqp8LBIq1P$nF;O8uSNQ4cBcmRZ$vU1w#x+fv^A$IK?i^G6 zuWL^)1wHH=agG-Zgw^15SFJav@Fg{Y94f}C*IY>&fW>_*XvLVoZ$cvp{)5vv(eP`4 z;-kXwG<$x_5saV&y76;?7dK231#OYCA!VSTOL>l$+ylfy{H8u*V`S(pfslvm9uWIL zON|gsKUV1yM%fZZ`EbeM;%3h}`;S;=r?=BKr3j8xNpHyylJ9)y;;2YMPsD(-~|F@y^R zMU31FZzlVOV;F!Qz>W_a9N+5^1dHhXh!3BRk_(Cy%!?H4h`d=85#_^ZSdAK!fPx&N z^YWuQyQ6YsW27Xn@h)E-Fl4%LAy~*SSOE64Dw3gW#1eWCA;=n1q8`)l$ArBi-q*#H z4`VzA$Ks9RCZ`!NXfuDTi!oa)m40A|U+92ryojXeZ!6K^qu`hs2IOO)LRCof}53y0Z@>^a}aaycu;Icxqo z8?SP>t90Qkw0stdBahi6lgT6xeLIWoNhU{YUj0m7Gi}P48x0*PlXWXkz$v5DF^ikl zhxafSEKFBFk`9p4y|og8wZeT%@A;Reaq*=FYNnp{=7w$NO0>p)a6`Br(zwf|$;`%# z`^7%h@-`4*V8dGbxIMj@Q4s3L5$<1@tqFI=sunJy+$3HuFGB6H^u~vUrcqd>4E$q` zM1}qW9(~v`n*Pkk&+K-gxlrNyx`t5 ze}j!Rl`jq1d|k9x6m(Q-8&Z%_R**QG?EM6-LWuTD0E(pxFFS>b!^;S>f<;>|)o4?j zZZnjOSRPN81ss(vv6a_yl+??YC1sTFOTYGNWjKc~dbv?vFk6%jFZpnk`!TxWo=DMj zMkT8X%)dW6VZTKGNr8iLYK-6)W6N5kIt zdbGc^aH*83JcZ>_7>9OQ_mhfqOO>C2D$sHHZRbJ4pRMn2Bh@A?~Wm@I+tfSQ^&N{v?`Cs6c?xY|%WPt_Ql(ZU#HV**qfpyBal$RweXlfku% z^uLsmwHPoY2--P<+yUrpB+%|S`X33%HVgzZ3Z22B76~wfO0Ba(yh~<{+d$>xr>%4~ zHsY78uf(7WM~XRvpi2b$YCHaFy)CFG9;T-FWRl|T=+ zgzUM&mGHEO_#_x#Ye9Kz5oeS3_QUz@x2)vRx;=PJz!p!AK6>5_-j;xz!P2sgg1(ZV zebQ(ze%8owManFYj|O%CNO>-z=Jfv&_F4ftc+lG!g_tiftwvAlT{BzJqxDBXwcnT5 zln~#agmzmj?Jtt{xgf-A%EaXo`egzVyad_;;B;6}%?Q1RC1k%EMuP#jq3OVhk75>) zG&&8mJ5dOoQq%Hk+Dlz5i5?cF_N&J{dy?qCn6_H9Hwz!^3--!|3d$%z6TAmm{Fkm5 zeG&Z#k31xyCKlzs5@{hS+D)=(#1UvJuTe=S=0c#%p2-~Uyr2ix3lwmtY&l%Wc+TSheMXSz7xQP~NQ z5Hu0aTa1Kq0)V1wdPpJynuUfv zVvZxxl@SJWy9PxNL#h>{oZJjljVR`w*5_Gh&wsgsyX6ec$-`gp5am&@Z6{@cAY#bD zi0>pW3Z0lsfY<|c-$;@p&TvIH+KILguVb07lIRBUy5~;S*amAW=LV4{M0(3Ew*6MI zAO$xjwhRQ|hNb_WaKlR&9h^Ws9s}48HZHd$&{8 zlj1jVL8-n_A2z%Q_j+jS!#%+sFhw^Jr*%pL z?j;;0B)Sy*{7At(EOV}{aylj(9bY*|igS5ApIe&E{D4G9QS7(g+GPz+FVJ_@DlITb z&hlOwFw&hV(+7G<&D`d#eCBhBP&k7R(_l=f2mx(EH)dEy{dK=Zf4FQ z=r$t=td*-T<-T3>HeWiYhhAtxElw?5K~9%+z=ua*9>{A}Vyiaf-F1V7c?!j5>$?7C zdabB~hIn}{tV%FqckXNXroYk}tcG&HPx1YhG=^BuS243==VzX6$|i5Zc~-NK+coB^ zWqw`QvvoQ#?sX;FiiIt&z@@0FH9x&YxQbB^kY3=rhH>4}ddF-`{F=Y8oqo3MueZ~o zw~`=+e!8&!;`)y1^=10AMH9^Tr{A_D-)(eff1k+lpbgv>eYf+}eM?*ATZ!`Sm}~vi z?(X64<^uiJ9`#DU`PSaTjy4~abUbK(NP67$yWP;nLf{(pUWmld4;1Rh6TTm}`G9T` z-LnLeuhnj#*<$1Z33&spbZiN{+1o@sR#L zEIbTg6(o$iBY$b1|D`Fqz5eb8vp6~iO5dBa%OXx5%PCDk~>slIyL?eOa7mgnBRQEe;&Sf9vj*1-2Ib?+#LmhCv+iBycZs!8r&@Y z660$u_Tkrueu=)|C?DJoAj=}2A6Sd;qr?w6koA|T4PU-16;(u=>JRcME? zKN@+Dnt2cTZybCY-oO!}14Iuy@9ejj^XlQ2*%MCu$Q`uPZY_>V=q`ZmiE8M;4kp|87=})DL3GiJ5E~L=8SB+WbOT1eL4aUtda&Q#k1()29C3^M5}!t@YRg_>hsfCeeJyq-;_X-06r@+uNnyG?jeEw5$EyB5kSr;t=UUOc}dJF-Mj{$)3m zt@IqqZ6dWk@JfTi`f+$UPEPkuyQsq{f zk3r^~Y2kM@HhWHFu+6@fZTFPTc+E8)1?{R2bT^*3^}bMcSYzjiwW-w-gk%{QiBNe&G(w|gNzNiTd1t`)aAs>_cZN7%FY3| zbMh`)JSP_!nyrt2kHY29HPSAHuHWR#2slrxWBDqjA#L1FJNp~E4HwXC{o)t1(Ss)! zc;pt`wWVKSw4hyh8-LmYzu6cqeqy?P?5V7M_EkFng|uX~mI1Y!oIdxPNTPH=%^7D4=buHEX+ zjKKYya8?TISIF`H%Q{iceipCwf)?l5uJD}0%t=eL_R*N{Iye9LAH(cFGp~5^WxBZE zaEcfL5xi-3Gb%=T{Bbuwm+);G`u8^?fu za=8BB>(TF?_UGF_B+nG%GV$5X*UM+v7*Tk zTIkh{2(rSCH3vUzfkbE27N7TxJsFRKKNVE@%_0#hK6jVbwF}PBNiqyMHd{J*Ngctd ziGNnB1I9DDu3|0Kqz&m~j_L?MzeT>4b9xi6UwUgTcDgGzg&|1(cN#jUBQ~{RG=b-- zHFZN|yTWy~5H8w|!e|Bs$ty`dcc^UMQQ@v$=lYyXzP&poaCEj7pN_EAM@Z7G|`kTTU55O;8ghZ`eCrAdF>yeV22W;NyjifQHe126p%g-G% z)2Rd}cO%~BsfuXH4IXj3-N8z+T+08Y?&$?~Zf4DC3vxk@Sj3f=EelcvZw}nQ^LUFks|XB&q>bN+MsDWD-`i-p(pu#w zR$rhLgg+>>430ap$>E4%7qB<3l+UZq7jGC*)0M;O2c{H+v3JH{-9J~Q)Z^&*Er%9l zMAFYq$X`+8*Y$51YGzX|@`B;6)n(KonxfZF@7HCjOg1^wYioBy74sc3UD<0_Z`#F;|SruU(RkriHsdkVI8vtr)-SYpbgnQ z$>7_!fljsp*)@rjOTkMUTe2aBXPUQ#KL>f^ta=TZ>@TD!+9gTI)m<^Pf7WtydCt(d zU!l14J_rYw?p3Dm)a-%3GrM*@R3y*_S`Yg3)LL+uc~G}T?D5xUt7`Vf^)#blayypD zhoKI`_dWoSFtmf-S2sSRwO)c6z0(uvBfdvD;k&h_8-;e%&Hi^ur6#kECbzmi4f9{S z?Ky8?kTxq8WhhnN(LZ1E=o_z*R*-1BB+8@rCKa_xh{S9M5|@yN0grUa2+T(X*Yk1i z0~(D2jLrs*c@YijzOy@mJMCpN>8|X6Yf+GmOx@Gko=0$w&OG{x6CA52v4fNRt_Bh8 zHgisq)FCz$#9%wz0ky|NR34#U82kp94x5uyd%uf1Jmj0-cz4b6Y2|j}uh|8mnH`QB zrXHoct*c!=w`tz(g_kQ*q4$*mV2FspoLry*HbB??NC|h{3NWoeck`XO8mY3AAhvS!%#3FyVG#2!;nsBgBRcGV;2xoyTmvwypdx|!oVdfiE* zBY@zYYn^KFa$8&sQS)rfFs+SD@>q-FJxfHLkw5SrQjk0n-U$uuA5ieZh(P~g?eJJ) zL~sfId1P}91bEBDK+aHVap$bmzQJ$$Ug+t2fn}vk;GGRAugU4gk+ur+Z~1%@o)_Q2 zON5$f#-ggBR(`R;#8A(Jt5o<13X&%aFa%>lzC-YLr^ADL!wScmi+-hl*d$6GE2B(R zI?6hime0T50HR~$|X?=tOPwt4utD+H6I-I$sLq~1U4$hOB`Q!#rZ99qW^TciG)Rzmaqpk>#sXH60| zydO)MBt1XUgs7<>-!yCM#4SgIn-g#Qw^%W^oJ-;VxOw$}R-F=I)lleulKfHd7=DXH z;CJeFk&-f(y71AMU@sf&^i1vMxY~hJ&$p0hgha`GjGTQ+t48dlkCJ?8cY9V^yRqdr z#F={xL*Nz5M6(nAcODtfbhvnKhBNJGOdV-haQ2cd>v}?DgBJX#q6^i!K4{q7R(qb9 zZ{Hgn`K&Ukq9^)MlkZNHk5)Lsz+@1M@RW&n+tlxa9_;`b2j;40^Zn&#&4SX z9I0M^pnJ1bb3X(wqIq5k=q)sBIDUFfai-bnP{9tSm_>CSho$1hgjldeATg1~mZt_mkx&@oA_JLn1kD4A=Vcfg!wh|6j$2k8nt%;`yGLzV z7R2p1w3?zfMi|;sjW4?>COF3qEg$5aO+fYy&hHHFWvc$xO!$3o_>ax-zSr{YwZa#pzNIMhfE>pPd9`mL;K4M=56SnD5Zy}a-EvX+ZRMmEF=JJ4mL(H1(`rmCBePWghV znSsxj8mjqDVYT(~<-b`2II=Ii%pq%?(6}S|y(4MN9fArj>Ru}RWc2%U92<~E2We_I zaP1mM!qb?Rz_&1C&!U73RSg2~esbFxb5GGq!hdqC4nZ%DY5dWYScTo#2zz=Eu8aS$ zDm4BqC`a}3Yc;jrDb+5K$|xoyU2$ALhDAl^G?HZ`)P+c6aS)Ql8H=q<{d;)z?jXMb zORqY=ruJ$i;6~lp8$$1Q->RYa#!Ffq3WKLfqu;AST)gij*W*PsiOarwZ(hy%``a80 z6{;5Uz{Sx0^z-%4Lvc8e?nby@FSU#^l`HWBvDeUPrpNWq76omtry$Vw~mbD>5Z&cT6r2m6eRE|_os|)rosm!o%zQz ziZWXIjk8Y;FI_gdao;$Y0J_`|!r|AQGjEbQ7#TQH7pxf+C=?r;ohmfK*7L;V(yXy) z;pcl{UlJVfRs?2+X-K5bR1^J!@RzjDVWz=uLH*<3@`%*_(fPaZnTJ}NlX0rBUAOY z$QoNXIlKR-F3xQN795Z+Df{5p{l!;`CMj&;!(8F4;Y+N=xUD@sx*VqW*CM(7B9M9u zZ&{XBbuFWM#{z`HIjSLwxJh*CEXIeaFd*r$C>3b16kMV<--xg%u`=HXbHjC>eP5b5 zU7|)VN8vv?5Q4}`vNPKOUtd04N=FBMrwD@^=EeALj>g4yMx(+*Xwz!y=OfhD8>vke zsm4v;AKgxy!+Myf$h?IQ5MZqA=RN4>6Tjzua`%yFC0=yhQV(Q>7&mX zX-Y@7#F@jIL;3<%B&FLAvLn4WKp~4k-n}cEl4E+VN$}ndw%*XlWy|MkD}7Xp?W?eR z=we1Ta9fc!v(KvbOPiEP8jJ)ClMrE=nsfh=+QY^KTs0NI2J#Y$@IP3)d1i$PT+@`c z4R)Ikm=2~-H!r)icH4F_i4AHj5osKGHzRvF`%ul5htZn^0!pY{DBi+GI1Xxbx60g` z8nmGnO_soYow@&Q{LfOD4(+vc8moiQJD70)MT@}VT*s69_$stN+na~!Gpx;ap6Ay5 zcRycCU4MZK3y_7nbR62kik zhl7OxDRtw6qDS`K4k^8$$B_|_dc*xlP;I7#zyA0OH9q6f_&Ep7WOW`B z@^G=sm$#n%5jN#Xra|9}UDsUY2DtGyA&##|7TB8_ebw#};J%Z`N)j%-(>s z^paC>ge~6Ey+h)=V1&n5>JQ8K+akV$5tt=Vr}Nu2(!%afQamkpdWhVC92u+jvsrRZ zfHgM$jOwl%jWd4H$&H3DX7{ks^U@tHKD|jRp3k)ef=7bhKJ`j( z97E>rL>R3cLV)|byUJhp9tdo|h+HyHTf#ob`*H0LQ8vPW3Q$vy5cd6}n(AdO2BRT- zITeUJTL>Yad2qjX5cak@RPt;oQ;^mS2xs++ zp!~rOC5kh70UF6E$DjAkH4-Q4X78u)y22TUK zlP2Dc2hLM}qa~yVo<>?2{r0T}fv2g1KO8al+qR0cwAuenUn@Y2{FqE}n9)5ZKKILb z4hvY8i8=sz9Z)}=4s(^InSdVf-egpLdGZFcx5{`lly<0cC!35|CuUXs&HHviXC2me=HHZwA8`(O|!;_sttd65uWMND3 z*?i{gJ`c-lD!;_DUk={cTdE2T6(3=cEUC2=cyv}xwsm6gy`Y;J!OE-tCzf%!H%ZW- zijH8843*!y{}Mh`+c8W~GZlFFN~A1cL=W@Z%KpwwZ?W)jju~g(czEF1>h|fd#XAVS zZ|G6DIGe!;4b!E^RloYL+R$eiym391Z_^iwF7qD0*r(V04=|zF(?pa+jvtur`g1>; z1+zb+>sbL2VQj3bH&yFUA~0%9IJf1=T5KbbJS!py%2*=GV>(>IzMAY zR5<)ECNXCxYD>?o+=UwEbd+SpI^W-%cxfsO^pYiy>lrguz^e?MG2Fqjs}2rVQh3#5 z#8k7~i5EYsc+&{@XQPKDLOQYojt=eb-pyby$au|SvgS?4R`=p6KgI?yapDtM$ooaV zh0c^c^wbp)#W)BO`e|{Wu09K;uzoM+8@6b8B&sb_jXs)8RA47Em@gdbSgYNv`ksi- zODh(BJx=L(Mjae(gX zkQU3&*h{wM5BC-OISMH`glTlsEp<*WZE+6UxxM}*eeUtEGAtwT0>KntLz8EZVK_a}dUk#7Lo>+bAN{sEd!WCQ@DTJY#Z67yp%-D7|OrnG1wI z3g6X_N=fg&eotTZ#!d&)yW~9E2cd4sq?%ZqnJSHKew1HIKCU=YL*Q8<8!Pf7=z0s7 z`xjds=lP4=saV+IuGRJ5rKphb&|D}gszX&IDLD4gMRJPUc|!?&z}c5sC}y+wrjtiv z*3OE+UegU^w637GW4}R`fud5UjiwseieHqwKHTiy2kIN9A!-L~EYI(~;d}ZE`?Z%z z=l4jJkf2+5S}{{bq%wf=DFI1zthGfeiwUHU(%GM@r370pQrD8Y6?^#*3|v(7oene# zc$M(bl|}CF$}mhj-%U9ko0m29F#3J9;HN*wdvhznpuQ=K#mLo*o0P-iz_&P^CW{QAMe`zW}av<(y{qe&TSS zsHAj4bo_gi2i)SL>N_HuN&vFNXLpqQNT)%?a)Q+1xv5@eB1>#1*G)_((WmlWm8h+W zu;-OL_(P#v@J*u3!eVg<(8&V>i0lc}q0eo)F-63%^XYKl;lVe|Bq8ipMgK$?`exV% z&dW~o=U;FHvj8%^b_5Cesnnr;2@v+<^}4@vIA51l;mypzZmx7OP>n?MAyeQ;e1@D%O4mkn1rhcl^ z(ItUB7Js%uTY4}^vIngf;Bg=GigFZpGs?bD=%bhbT(C7U+_%CKy-5rWh=?gVi;n48 z`RT3$tKsp!9QtsCu4;-=Co#<<^uDhVhj-l zbBo$2D^h{*J{7IJ?Z#9<=Tr30)B`cW9M4-+5_K7TZ8H*+bo){uXjhbvt@S-+`%90_iEkBgAx6LK>I{T$=z!NtR3anM`o zo%MCOXD5Qnyw#N3U3j!k)^a@zuMzolBv-F}nMQkgN2LrjTb4650~4;4)Z5-m3|UJX zGXBkyMfmx$u6o_iM zjXT`pv*UBT-mmxb0b;Lb#N?B(BJDnGIGhZK*F4EXe>r$79`KS@n2;UQcK8abxC9hE z@1j~b)Xh_;B>i~aC;18!buW08)7oDcjy<6_rB{mkvqW4RH~To-8k8bCE;HQg=5A)K zYY}3u4(QBh+&7OB8_%PV0K#+rEDrrpZ8<0R^NQQUg3Rx z(ch$&mX#mT<(H3oY;!v9Q^{Qlj?gkrBiU3URv1HRHHi9#=A08;pS{pL&tq>tS+zdj z_}+1gEbX`fLkVjUPr+f&@E?V%4tugD2Ry+GU1)a;KS8`XHF|SqbML~(YCd65k^=wg zG2Em%*P+w;)(3v;V{;P%2i;~ zvY?=^Y>fcy4xoIP2peT;{#v#zF(aPf7AYr14lF&M9y3q<2&Ydl*bw#!O^yqHgI%4m z(i3qQMlai=*%=vg8Ch3WxC?HUQ&lw7mcKEvn&7e6vC&+T|HXq$?DyUwoIudLWvjMU zkp?~o74SzUw5^A;3)roRa|kN1uJGHr>;btb7sh6~=uRKAtk{;#EY}Xe_5Eo84XNf4 zE0?w1lKS2JB2URmI1DRS1V!wGv^Y-;o-*9h#Zo_EE_e&uD&W2>5PQ7xg)2|1@|PH7 z;yD8+#zED)Z1E8qAXtO#C#k{L6<<|`;f8OV(v&%Z2ZhTPs}vIWw6$uol&thaOx%H- zc*l0h{L{%vg_^xn^7w#|^3_9Qczu;7)1xP88ga@CPjeqesa!r?I^)zOMd>oKvD;?| zGOI2dqa@c07WWI(DP#XEn|b1KYWGgZPfjOTtQ{VqNcSP8S)JlVdZuQEU*)X%U%Vgve~Lh@u^tsoz_A zl!a4~dKCG%AB5n}W7W;Jau9>IVOTV#nzGLJOrvt?DbLjBy8ayV7xhHNX(q1+~ontj<&Nmk4Fqx0@N zqd>sWQ|03l@P(rlU{jZJQ!u%7Ng5A(v1lWMww2ga`(^*Ud$TMdfuMSk%pCIMp(bH? zIFJ9c$B|q<(Y(4Dr5u!eB$Oj0BCLQ<1534z>apD3I}zUaq&|ZT#|R?REH$0qMXxWx z{;d(n#1iXcheZab#adf;8vIrMXJIm>!R;Gy95$|wwjtGQm*VPv9GW^qYEcT@$egU< zBtD`0#b^%fVl-neXZ!Msaz2ZOZCpEVct0PR%36HR-H1=`>uS>pc{J^B!ZgpEp4~bv z5IQIQ;Z92BUwmIiF=Qt!z)Iyk#!Q(L*6sB6mow|__jjLW>bG4%4`z%kj#btQEPjtHLc@Vq}I=@7Q}1}2+;0<0+tg9>}``87Z-1&);#F#)`C;DDz;%<$*O>M?bS0db#6>s^}dR5pdORJ*t z{`2s=LQfY2O6qbsJp@WgQAT?R9TT+y(!Bv9+iyIAtsC5)E3{NvIi%f!Lu%zi_XUP` zhQn`lbH+>VdF%*ohXZgbU=a{Xw0}${WJ>KC!0P5yAiQK-m@JXgBjdcL=_+R`s6DyY zwjgx1&tIz2Wf+anIY&;v+8j-^9ZTK*77BN!#cvgJ`CicXUCni9++||CBHpeN?uhuM zhSi(y*HF9$!U?LEOfz+8-IG|Wi9fh4x^;0i?yN{xt$o|K8?Vxy5pK8I&&p01aa1+r z!Y>Q09*A{ECRd{~+;5B5sI3gBG#2K%T~@oQwfHwq?z_D+bdgz5rQJAY zsl8Scz3%2A$hAxL5|FS*YMvu>mMGcYxIxs{A)LbWOhT4i z!jezjRMXXTqUj8ukBG1l-s7yi zmv;E%gF7wFV#VyDv7q;T*}7A$I%Ss+BX(P=9%?$LIuCcfco)}sORMOihYyLQK0`dO zVtwxZr~rQS_BIrakddO_*==7d1&3>hxw>1W4L@YkG%egS1!LZaVjFa1S>q~gZWE*p zQ_loM8zp5ONL*dxd~lCw&mWaPYZ|`B`Z6n~zHnfX7+89h+bif&TH&LlUWezpg!E&M zKa!)!j@vNR+D}%`q-xz8z72j7wOpkMe|a=-M~}>Vwrke+$J`e?ttMG(8)oa~B_L!X z=>?4KL6C`nk$hP_N}#a0ntHDkp_feikAuY481R;v!)&xzDbwS{E&p2I+aDUKa{Aox z`hfq=Z=4Mp_B5?2iOgVZ>6oVh$U>ni8s1ac)nxdUz%|!BG}oZGcW@k^NWZ|~eMFXwGV?wmhT(9aA5#?E`Yy~am^Ca_`E3A2$s8c}o~U;ce5 z{U6Ru3jhld7@q8PaFayDCX4&`(Iw&Y^v^A6=#2o>__TJwPlE5coq%z-&nN8iL0 ziZbz7qC2y!(OG7fw^j-zW~02@P=1SE1prg}>%VlQ0O4>AIr|r3g#qYkgTEOpfIWOG z&hU&F0*d#r>dn^b!^`R>TPctl^`t852Ja)?=UO(!I^HYleB*blNceP58n1485Hm+O zf%JgHZJk1L^W~k+*2<26EWgW=pDo$ytu48Vxlo1HkJ!&GKT%?ep)IR2pQ&1l9$Yrl zp-UEnu+g8}wJAD&LWySxpYRb-bgHW~s2?O;>V+-K-1P8TeH>}UH+BiCsJOUO6L7a# zKIz$tA@jurPe1`azC=v@nz1aSVN0Lab(>q0@u*H8T0>0?0m;JSFH&#d{MPW}Jt<=7 zP8mwIQ>@fcu@9*GCb#F!Yb3hkVbaU+uh8Qt&Z@@@b!$mdcUkIT1z&v4`A|62J+e%~5@q45)V^3!Y`RKXWR zb;fR|?DzcUnYFwoSL+zgNn9^E?(MA8l%r+&iTgcarJ2(<_1sw;!SGzHrRE9@Q< z^A5bpqan+tNW=6%ULmQPCt6kB$q?{YqR0Sv{O3SsvDzCgR#i~fXl}obI zjH45Gr2cbgErdsEp-dG+rmppG)-TyXFHMxB{rs;QZoDdH=90&$sdF#)4(ea5-&n5h z7MFPITj!s7rdj(B-c4Z3(PF+Blk!&SGHL}zkLt<*Nuj}7hvC^Gz7xVnP1I~!!HQ`j zhJ?&ma=S8(q5&-*JYrgB;@L^H7zd_bBpi( z#7(AaY?(PK{zGv*eNUotI;e*4Ad=~xG|9cfQTP<*JE)CJUSli%mE3U|hl#&neh-fI zGlt(p?*8an0|aA}1ixpYx)H;%m)(g<&1g?PP(;0$I6Iir3r_aX)v1T;NYRG&%Sy9T zq~m45n{R@(1c`mCzQ?cz`ZoJm^cLwhiGF_TKu@A*_ufv$K|HgNVb_L+#P_h&FZG`x zzn2G?X(S4YJ~}#%{v1``oyFaTpYz@u(u%mhk{&`Tb%H4P&}>M?2|ptlSlS>HGU?nA zf*OY&D?R)qjoDc%j5o9?5j8QXnlyb!O*qnLm>u}mEZ1m;I72Y_xRIBO+8$$uo6osV zwB{67Onh=RI5X`=@e11owu7AOYH=12#TZe3S9soC^FiW^1=CeZ*1RN7;LNYA#TC6arRo!!)<&xpN8X$p?2V;+-Q_%;J+e7{zH zNjM0l9a_@Z>+RajABBsP8#514|9q&qf9}o}Za#vF{9DWXXDv?M zC5Ih57p+5nSrKMPjgXe(fU*D#v_ve;U-sd+DZ-iX(&K9)7f++Gc9G? zKK~MxziRI=WeTC(AS`9xDuxHx^UXTozC1~MB(2u_aAGZw&{Cly!PjMjnj?hd%cELC z08H59Aw1$2=lvkOQIyYgD6z_PpS=4xiE$Yo@%yc>%mf9I!A=Fl1nvSXlNqx zDPboJp_6g`aM;kGT8=@mXz()KcRviKudBwUaPt1s4!XqnGk^P1Ye81K2E|++;K^$R z3Yz$*)W8e8e>JRoJK?CBC@6s!)B%5qa!V|lK!xJ*dn2Eqj!r%9$ohwlSvK|a4|UA9 zk7u+Zeu-CiruWC+A3Ur2lkJ%xoV_6U;V%)4M-)K}BS@Y?VgK3lgX{g*p5M|U;y1+` z4Kj@upmVh<0!5c-)a1(+O|0E29(rJ9TC{NHq1vfPcl0UdixoqP%6TVsk(*1Sdq~xy zD{1e{r(P&_;A;YQ`Asl00Ki%nDdsMS*34UVB#VxM6Lk~$+xWp_9V(xK@gHxyc>4%6 z3urIo<;W(l^*r{S)>iiv)N|*IjhU^NiQ(NC3_Ujiq>V#shfv!vV zh5wp6BL0~>J_I47B<28b^r(Bwam8^HDh`7z5(JgMg?k`@P5d+J?(b}nBg_81VhP2* zEDHphz6KvO^sS-IGg30xT6odyCmmKe;Os=kV-)}KNjmXax+XLjH=J$;07zIPsx8r> z(JSgyN`O91w&$Pewhr0O5eFgX7_z5Qc|R9!8Z6cJ3ymcSNsVLX?*AH$7$L8lta&AV zZU05JX|0hQcXu3D`;2mFc*@eP6NYfNePJi`lLi{GE&H>cz^!9 zsHNBJAazho@SVZH{4TsJ?+DOn`Rhj8iTNgM4++G?`LV6TvDfQ4iE|k+1enK1H zp|hqj7W(;a=99Cd>S3uH)?5%l-C*}{N5)Cb-fvZ9wpa%V zN9rP7^p>!ULc?0TZ&5`^jw6VB;}t{!$bZH3aj`ME8dJ-Bio z_~c8ztGexy@kxpJklGFBXZ{N(PL;Gn(kLX3$Yl$Cy{mM%>66`O9jO0{kc8 zb{JPsl%oy_zY}cv2MLSO?Qe`JeIlnveocSzPL3*x%vhL$IJb(i{G|v=!H_Q41{sNf@uMc#50!MbYOgmo#$v#nz5Qj z<}sQ~3R?Cf6Z$+N`IU@E{Ul3HzM|$mJ;&LKY!3F2O_BUv8mPJ?cwLu|IHkNKG~7v* zDEYkY4L;a$@fULC8?(;~GA?@ZTjDcyQF>)ia^@V1Yq;~iE)bx?@TQFUrzVll7?U$l z{^?KV#-4YFA0)dD9&?P08zaa0E8&s-wY(p^+I~~Aw~SBHo_x2#81i|D!Z?Zq?n`)< zhzhTWGO4eIuG7z!^WyHYqm8(LKcB34v2P~BI5FZ64T*$PIK;;2rH-V(5lRZGNw(Pi z&O?g5=8)1(ky@1CW2#?^JpRmuxyz9vLxK;qUnhAhsV9Wy{9?=Qn!@4nQm{W^RpqBF zo}`@mhSX;-xs+;=LX13cox$seQVIceGu{m4vsc}fe?7d=TEff@17eEmQe$;eX_|t@ zbqv^gaVDt5;|Iz#E1-ih#6tq=JpJ312iF^tQCbG{^;=@EPXsPb%&s4B%>#3Hfl(vtzc0hx62(`8*5;6oQ ziEhwIIMqp#(tYQx`~FlXr9e0TtxlQ^bRdV?uPLzDg8cg{Sa@h z=Wq4Lqzt~l)tYQDn4i!ZrZ#W@XryRpOr}sYxXI{EsH^}eqT!Gaw#<$t@PZUhS`>sr z+L*@2n4!^_<;<8}`aZYMeg4M#!jt#;Rn2da5O}_1Zzohl+CwU7ShTWQ`Jgxe%sC!BIzTC)a4 z9iPH;-)on{+wZQvQ$ZJLR-^FEn4-Z0mKX_}xmv!Cy2ni2q>Q{^a@sotq*NOg%TJK3#ca9DLSZcx;)wMerg+9J^0d=E)*c;2G%iE)<==sBgn(qSp>i;s-`M8 zqbE{-crlF-UyVkIU)EPtN(}XK+g{QM5)QBxOX_~7&+2qTU93Z@bRI|rw`4sRU%-n` zyd#G+q{-LSpA6*wJXLIX+C%G_Pho8LP`L%l_KsHb!%L28D)kT3nrC7abWACQnu&A$LQ1?P zrCy^E)0+78S94Z2@T;j8)49)PQ{d~r1gB=Ed?>$I}^$De2}e!-EduwW$FD_dp{3QhNO`BJ2xZaBl~)YU6KGoJnwcR@Yq3}bRY0c4Q6cKA^os~#SFevFw(wvuho;F zp-E$&eAE7_h-dmmC{Uk4qV_>dOiJ4OqZdl@t%wV_qbl=|v~ugYyd*q`h252O24+N? zfuc|Sp_y9lG~b-(o~#ux{5{y)0*2>nL+I;NN}v6`i)iOGojeuVc^+zJVY@FMfnl&a zm47qc4{ApkU^?NA08FH4qF{@$h`cbyKca9tz{UvR*u`8~o6qU#=8SmlHVYH`SnyCi zgFG~&G5YC;rKEX!zL5{~i0_#zp6^@s{S|=n6{o%TSX@7sE%|CLn9bLFpg<)^~OQw9m?t$+lkrldOrQq&T zD)BPKr%?Sv-f+(t;@Q2<0Hr<)5h}))`;VNT!9NC=(OtBPU1z`nSHbCdg??+`AvCY& z`%3g9#kaFu>4D|4E#;4!eL3fx!0-w;MyP0}m_!gl3GXs&FEoS9Fy0Zxiiz*S`yPx z>GV*yR*Gum>taP?k&I^&8D<}r>`vfhZ~gc_E&0VpHqTsEkt=j=mO4qB1H77H4NC;U z=WUCjt$6Sz#VduqJjkmczSzL5yL0k}ik$bE8nI@Ujpb7!`R|Dw^WHHq*RL|UZ7Ax; zBb$gV=NHCRCIi1ne36%7=2XC)!Tjz~54OK|{dKInDF{|JX8)>VCss<(<)X5@)@dy#8@dZD9V3d^~_GFo=xt?`deaghqLaiC<+8mMRkLCip3u6 zjHPgn3)_u1W&h&88Go-h)0bWUMOjigTaff-lqzIm-PbA7vhYE6h*^kW?w6sMUq8Mo zFFp+wgqy%V$BpW-hXIX)4D2BAkekCm#Cj z@(06A)tfm7*xv_CVVj%-o3bfxBX>`EQuk8=cl%7Iv%f4CGascqK5AOoK7{YE(7nvb z3*V=i(;Ywl_Gy>lYWJzfnmo2mxr2XjVdaX34{~+Nzu53_5hb2Gc}BnYwBzI=8%e}+ zs7yoCLaSZYR_vX-y4=1>d}sS8=f&^%c?uW z&tCH(tWQ5L@(QWvO|f1sw%?X^{9sYJDG$Cu75qUx1_4%L8$!av>6N0z^1CC*m_+o| zcw>5Es0B^ms%Zm}IMy%l8YEFPki?3m88t>o6c4`RFetDmk=)Qp6SKY!VwWr($>zeX zopwr=jppN)Q-b+(KXPWrVE`H$7%jtgP?r`C9#w?@reDb#?TYyG)a7KPS{D+SoWl@HG?f zbll!tUtRIG%ZBWn!VZD8{>9nYMQ{ChDsD`P?Xk~wgQ?X9vzASV0XN+Q1{cA$J z_(e6|h852aiVw*0{HcYwP5}Z^D|M44NT?vVn}DJ0tYPA97&+N`lo1+gM`&60sniqWQ4GcY3a$EItv>{t4QeZ?N0 z+s;-D7iJ|+#gV2v@AXOQ$O)fk3?z}R#&?fFmrj4akrj8Pj(@{+fw>0-{FVf1r{$d_ z5wHn8Psxv00lPJfV-25g7?g(g7pc~bIYznV+c73lRPL<~Ho2l)s?Dtr{HmVpFT8V! zGi*abU`(~&#)zk`kM9#sErn_^;*RU^0Bv3bl{LMLah2M6*Ff>!k^6d{eYDo`8HLvl z&*7n@C5kYMM`R`x0}msgA3xgN`782R_yLWmq2a~RJrx=3>OB==z>=zTcXR6)#}-8m z40r^>N8|+k!4<2S$TRlp*reh-Crzyrq)mR2Hj5V-s_{DvKGiH5ROyR$gS9%zHh8@f zy>s^If%u*EE~qaSNiK34VnZ&@>>d719^W+_pwu^VKF%kHpU0^^dCr&|VsXzfV4c>Q z!%%suNIbb;4?CXJXX?9Vygf^<%0(!3C1w{mz}KW=Ja^tVPra`{Tt$}|{31*p+c8`x!9q7I9p2H$op{qr@fcXdmw`lWT`x=;>Ng>NF1<|IA#QVVX zr&Q@jk;=_u411n0!kG7#oU6s-5-4m!*Hdt>HesRS{;sO$dODQ19`PZ01remimf*9g zEUJUUVE3Q4B(*&9P*Trm4HHt}@iK8D-@g3D&wHTm(RWH)U8F{31vDR{`-EIP?P7Fi>faUg{}KbY1FX*y{l# z(0d7q4~ZGj5b#QhcP-*%vjA4_Jx#`W3f!VG-}GI)QZnPUxQYOSMzLORi-d~#@5Kxn zWuPFAI>mz4B;OxY-zRueSuFe_Mo*2AGVROWy0FjocN@|NNu6uOWCZ5Y^0S`rhpc#5 z&zfN>3PZ?$HfO72hFx7=X8ztQk?n{XR++YiW(k$b{|GRA3c}CYb1hX|B>CY#_%i3T zvQ+sn=11_(%iI|&0txYwAxBd0JX~0wQnpSb@%jjeVzy_GA~Aka03eV|?_#sD35|Eb zdKWV9mucT29Y=e;g>Z}_b??QFzy07{EaXRpqSrwDo)R&S@HSzWg4G z#ZWG(bdqY@y0`&@sJLT zTS<;JjUy~zjoCt-n;WUg@@Q7;zu3uc@Qxl#*%hPZBX4t1X z#^$)9oH;8BG_PmaF;mK{Kgk?tPa-#V4m3 zX{}cg7C|V`+y$wBr$PBg=cBof+ecvL2{reyB8&VYk z!>;c2nTuqba^C|+ysPW8592rGE#KEN9~?*BTyLs?A92f;(BnOU;|s9K3&gr(Pg5B7 zw{&fBO8n7PqDGcSo73XUZ!#ON`AGDq?vpN?Qo3 z%jsM<--0h8d>&C(Ge0PsoJ)kQ>8M*q$*2#~N0I6O$T6wf(N_gb#W1RAy-Cu>7?>Q&+h4ULO)*xeQq08l4p&L@=HNJ@Ny>Ez@W`+7&KGfBq2hjqz_z*&Xu zaxCrkwA?ym*P88W=A{N~u1s4&4Wv3~ULw^=r@Sqz7Cc%1inBVZZIA9}`d1B}%Xck9 zhpI1bmJ6R;vBEkssQ@}`IO)`SY5hXN?VB+bKQ%SblF zKynCzmo=~r6zdM2a)EI;ms2QTS*Xxfs2E?Elv5aBiDikMbqx>jD4lgzmC@Qi+^#I# zema~fiR94F2nT?5BZxfFkcRFs6;QaEToeZ=Qb#UQe;O8Kjs(N<&Jk)UIb(1`Oe z)o8}cezu%uw!AX7f^@bb^VsV@F=h1F*bmWG?M7hcT5t;hpooF0z}2=#Ba)Axa-FbL z1lbFZASPV$uM>t#{uM6A*6_tOIK=@FfaY_UMonB8JM;wxCV8I|;K5mx6wd^Ut2d8p zN{^$EN)Y0Z6s6>xcH)fVWSj>976;;224MC!5MhcK&rzrcH|K#7XODS2jtcy^mGGTD zaRih=Wd0^;3sx^i)~ypSKkg6XPpX|HS*Za65JX!>LZaPqOvaF=B^Zkb=`uP&#RDR4 zgiwqYP2PfNI3>}SCjmN>n2(a!<&&lBOk+mLH)_BVDMrC7yid-P8CsHlZY9BIU>v&1 zN}RmjcD()tyi9m+MFOx%8vH3*Bmij=0P`rhHvo{tM;cxSlfgh8FapfAAYt8iVis>% z-oMlN_U=hJnk5PR+cQ;FG6@&#e5MJ&r8m!)pjkCAQZdM9G(H)C9zX&}1N`HDvGC)~ zB0(2)@c;~YXba2>10|$l47o@{$)`sIq{lc5C0wL4)sp;OBKJfSbuW=idx>>W3KcHD zN5;GlcTSJKfX04HPux!Z6e`%-Er?DLYuHZv#E{XVn*qQ{T?{b|dFjj;sJj1q=KOzh zsb5Jl0LaY3mdxLqSw~-C<3M62Y1`#F-?>2Ra1a6s+C_tyJc(wFBs($Sj!qay z9`N}R7Cf^gP?`rOH-EoL0+`}w+`q^i%e_G6Ubeulw{vl-X*LGBP67}dg{sqM z0*taqc5*QMxu+L-u-4q0i`?oJQ2?hH!Beqb`Am-1Jno&mzwdJaV#G_M;XfF%f8r9U z0ePA7jHGu9$RFj(eaKauEnFc1+(AQfI$=Z^s=Lm`W`nBh9wf}mBzx&fYd|$NTdBSR z@*5k;8zaelk2E29#z%w2PXzF7NJCh}OOp8zTb-4#>(*Qx^jeFSl>G_q1psWn!R(z=1>dI@EtjDc@{{kD%cMZD9@uhF z7$n?Zw5ASZPFhj>NPgFbgt?1k5d%{gg)+{UV1db(P{KxUz zfwc}+ke*d6IVFVER!G!AVpfZBF+wKKik85tS5j4|2Z0eUyuszmxu57>2l=#^B`XDZ6&_fCPDnR`{1t<& zeTIo(z*`>Bbu@Tz3da9F=<{D>As#NY2-yK+0UL4c*WcT5rr+@uUSlU@w-c;Gqk2E0 zV_C6%J*a&~oAoM&!54iHp(9Nqm4!n^zo0 zP@OQwmo4;ncq=R_`@Gpn7lIgxiZzT|*yJ(L(I zu@4X{_UbwQ!-soCOh-hw6mFJ617Vd^@;DNWnehkitfGO9UTJ1V4Z=mf0Y_lC2&N zA@O58wG(yz&G;Aa4FCuKqWH!+n0F3~ae)ukm=BiP_K{+8QNIT#nJWZ4fisoEGfG{H zNO06;pAL2Zl{k1ES#z!`SrRL$5XQEO_?~J5xqy9`BOUgQ|H`aN7G(8fmTkJMlnlM{lHCr(}TeVMZx;I-Z zJXf#Gmeovr~oA;~cq@B>Sdc_ZjTO>s}v!tVZb_9(fh2QbzM>e?Ch*P}7i zCaBpDOLVhDqL>HzISZq)A^p9iNSHE@#Vjb>;2tD07bBu2+&hj9%BiktB?jqKujwC%HQl_^_10h2?f~S0_H6>OVj#yH;3nC|YsePmHr|=o z`)Z|?_bw}ZtOn2-ShmNOCj{`)Fi+8clgSoxpKm66lMa%DVXp~W>o zlo14*M}IZH7=wG^5(i-rL;^-Hhz&R2S!^3d$0z~_;t=zhki9N8=eMqQNgKg?80fU{=3o8yZxc6}aA!tMkX{UNx8cG16Q67&$VT;^Orjj_3MyJ6HUF@?6u? z)Bm&3^&g&VJpLc5YZM1_jsDx_x*Qt1`j^UeIy`(a+>8DC^m4 zj^z5=)_(E5;c}q-vOn*ttLWzI%jC>l%hKB#xTpylc%Siv5=PDt(Eyh2uD7vZQ znf#FSZ=S2Xyu7ru6lZf?<>cPJzk8CASyJ#Hm@6kICo3!K{D0V7w~0zu;bAwpxNUgE zzOP@#|1-=L6cps|@9*pD>*eL;;o))e-1Wj<#$ZiOb8&|1UO|sHg~z=i=iN5D?(y z<^8wK#lgV=hr`*}*jQOvSy)(@nVFfGm>3us{x_iu27~<<(na>aB3=KR(1nA!uy_C* z(#3^)9{yi>F4#Xjm&E^_=c?cAq!A8nz4+Q+`X8RFfnSf%(e6w7-Np}-73TFW^Mj2Q zQy*=5Vp;S)RnFA^o9C*stP>yNb2{Id1C;)o=lW><#!-j#|ITwgUx;rZkN!bPp=RE+ z{qY~3tK!LH$^JW%64c-P=Vbo4&bqp-jtB?+eKg-bh7Wz^D|b}a-$g{bN5T#d5i!T{ zTy3pqJEFI3Heyj-#s>=>epqeNoNNEW^}ZdznL z;;##VDkSD`q!I%?Jd{LY8vPpFSM!7U`k~Wu1ij;Vo-gUaM1B-x=QKZ>eMQR7kT=7; zK#f9RjYQ$4Gv8{w)UW1@*Zi|@3ljww8lD>58KEvhDZ>^;mX>C&_ z?sFr${>^h)`ED1dvGy)^rP-%CJEoGrrHb^Q_fKr-z38^!Lce5uyQcc$x<2e}@Sp9? zTsGtFd4R~d%|ATXhpmEmnVl`D!}Zcu(Oc7uGO!;Fb*WzFr-|*mxuK7Ele87QOMM8x zz}12)Kke*P)bwKo{tuq3lSpu{rkD1r0whWePszhYL(~YLX$iWeF;{kWHB9GNph#6T zO1H~gLw8G>y;4aFTDS^6kCsn+ZXA5Z^a~z-IsNtguzK0>r zIijm+=Yx6u8_J-J`Vmai(87S!7z( zs6lft?R3m0YJY7??{7ujkchV1&k2&lA1b6gG z%}UoE{QwcDRwePyfK0%mRJFZn=?K7S5u6+Z?kr}l>PtpXt9*@U82hb8qFOqT4P{OEav;pOqrRk4y@m?HVl9g=T} zuzj-iSEC0#W)sSqi+a@U=Y56Lo0}ENi`SQXg2nB3$G)1x*+er#033${%jC+RJv^f2 z4v>W1T!`40Lp_X|@;W@@us0Ub1)hM>1vVTy>q}4w%%RZ7C+==L)+BqejL)v$PY0t^ zTMHie{Nrl&Yd7tReFR?&8vx$}$vBINlpD&2Jf}y7M-BDWTOZQbqVwTp}Z1A)e`?jc{Mzvkac%M_{DPzwWN0M0>@SNGw{{dx}jsq zO2p`9bbcv&MV|mVI}u$8sNZ&Ufasn(YpMnTYn*g|vJ#$o&uG-!?zaFPgxE@coNiI4 zCwh)`nMYPzq1{W>hk%3@WJ5uvLJ$#Pvdrr94g2F&V0ap95<9t{&S>ayO*%em?Pei= z2o{VV3Jd@J(jOfbyOBo-sM#XLabzz-sQ^Ho9^Qt02$P11-!65uGE3cfWP>-mD2)!) z`4JhVkwGejYOV`l=SR*ZHM`P!G?^_vnK_qtG#SgZI&t!6mTPr#Fl-(1;b;uS)ybR= zKnm>@8g7?2WWNLMuJ^XK_y?|0-^ghxe|u!AMC6uxC!xZMj&dS_?2NmvIg-po?5z&Z zWIn|tt4Q||F;kW*m1n1&GG%SpJ%3m>K(2>pkOGMK4TJ!ud*%G|LOEL~OECmh`V@eK zSEII7jv;eL$Ig1qBWI1clGbBsFS9i4ULND=x%SQV>}auCs$VXMSY@OZ%)x9=wG*u^ ztc7RDcCE(p2NTInP={~R8^-6R&wn_*qj-S-<8!axz82Bg8>etUDH!@ z{XQKxPrJ58XW0_ct`};jLFn{P1#A^tqW(R*rpf~QZJ-0^U{Q(1%!wwR-0b3Tb;}e= zOd*>EMUB6rnRa%GV;2d;a}i;cL^QY7B^84~$+#-fz8>X4Z)r=CErv0vmIb3I4F#TZN1tLh87f@N1vF~-sg5aRSNhr2EGEbJ_9~`j2DzdX`4S!i3#{3k@VxQBB;e;N$rH3;u;h9P6i%}%J zqQEa1Yu{|JwA_!(R8ogxt<%bFCGI5e`Q~4)=3)VS2o%LA5+oJPSE)+j=Dor}_w{}2 zXT{UFbPrgK$jeq}B0600dY<=GQiK5+n&#oGW5*6%CA@^94eZA;(MUFnQk%B_r9!vMV-Rs z?&l{L6>*D~>ly}v0l88-GIH$b?5A8?D&K>)tdqlE>4bsFmT`wq%Ih7UpWNY}`n*Kw zg?cr8`=|Lw+kxMUD=_>tJxPBWTGYW6cK2(pN?DjjWaDPr<<#QUqWbN}cI9mi;lQzYQ}062X<~-)yf+Dk ziom+mh_A)SA@2W!8AOe0am_F+x_)aIzjDgRSjlg=iiHX3vEs)t_AE_;`VN2AhXKA%Rgz&s_4Jw;Lf9{}G#AishGsE8ovh-ljmiQN#sEM?Q5wnPev-dQIIBbb%il^v{PTn&)@AJ&h2S`fjwlH-_JWi6iguEP zptFztIFXx3jxi)>Eu)JADHAc%i}z?p@Q4xyz+`$*g~|Al`Pdi#NRbq|l7jLt0i%&Q zaWDYrjy6eYEB{f9(V&OR=#aShhb$SCEa8%7(<}f3E!mQkW>PKJqLfalCEL<1s~3_6 zd6OW)jjiB~4SA3cDUK0ok@;a$LaAU9Nn1rpD3+3zYWXOUvX*YCmY6b?R;h7w*%2pj zVR&$NC+U;Y2$AInme(-=rmze&FqZyQSCpU)@emKyfLQ=Q0kOai@~{gm0C7br5LWV( znzSDajljZ}$~>)8=rP+np1i_+pkfDFzc1>2cR@s$99a1TGQ zbpkOCmv9gg5FbA94>G_3bHD)%@SqSHp%OZw6k4GcdZ7@?pbm>Hp&~k> z7#gA^dZH-G04AEEEZU(f+M*Y#3V>DvC;Fl=dZQC+qaG>))A?c5$r_U243e;)xHMZt zAP@TR4wxkf_dpQWFbW5eL4u(Ob5NyLdZk#JrCPeBT-v2x`lVnRreZp#WLlK9aplN#W2W>j1beg7$(4z|XqpJZ0&VURKK%{*%TM&=~WgrUb@B>Whq)=)Q z2mksR3A&&SildS$p*lLLH(IHd+M<}6sVTatoJyjedZVYw1t=P-pDLoJN})VTpVSGM z_fY`G;0#^>sC)!s!5|9)3IGIpp4G=rtGSi!DR;q|5zPr;TG^B7*_W*9qpo@%k>Cud zK&vhUV!}`h;3=K}zysyUtIBC+$jLL`dN(LR1?5GLdG@Q{SZd3fr_FjDGvEx%AePd~ zK6NDuYCuM!un%w0o8!<1Wk3zX$*t&WkH!f{152>OiV@m(3=A2a1q%QviGzB|8m!<9 zg)pyI)~-+_4)>rA!LYB784K+&54(U-0{gJZd9ZkwtOk1$B+zkoAZzD3pFk-ih5z6T zs(`WdI}jpvlq))x%ejbqxUH+T6H&DB8M=*2wlq=&eQLL<8#b%!x*Qg+uREF= z(Y0UOhj@#pPp7f>fdKf~1-m<9O#5SlJG#QEx#}sr7*TrCfCsvJx7MqyrT;r4&uR+K zyJ*pCYiqk*qFa;LOPB3y5s-Kci)*~!n~v+6yiXzo@QMND3pTx5zb(tUzw5gNaRH@e z2hjOl>)SR97``$x0I|9U{d+Y33%i>uz%7Qs1kr-CtH8BOa!|qu&^p0JQ^D^Gg(obu z0K5=W*b2oYBdktG>WHz$=^(cgPQT zP;ed`!{V3%;y?>$U;}Tkb{LTf|G+va01Mtw599y~CnFGMAPn!|4!|%51Mvpd5D)6G z3o?eQhzJpB2fqa}Ak&2(oee1TudczH+pbP4N4U>Qo9pDXaFmVH6S#wba$U_AG z;C6qI4+SF!``{g;Kzsm@3%{Tcd%F}Q5V?hU%Tkid)!WOyOu#Ru5yc1%9ZYo62_K+Q z5cV+2WH1T!&`lO`3#9-6&@2#>pbi4z0qfui5KsZHzzuU@1NWc^2_OQw01N^_48{Zi zi2x7eEX%0@o3g3SQNqqB49L5D!AX1&Soy+Fe7ww25cm+V0RI3B)nE~Uzzs7~&?+zv zp)e3Y@D2O058a?j0@DCX|5RD1~*`d7pah=&o(oka3D!kIF zwZOir!ScutdEmtM9K-l59|bWEvoH{pa1JGw4#q{$8!cPb;0xhV0oHH}W^e|&zzr?a z0^TqRWS|Da5Da(W)KD$e1tFy*fz|nOpZUqvPvX@;o6>@e(z;9$3W=J=_Q3^_3ydrf zr9jgX;RpYq53KzU`=AeL;sMkU4AP?r=}<5bFb{zM0HAOU>1duBJrEtusPS>td=jKX zYS}h|*}SaTA#}v%Q#>OX%%Kg%31J5Lun9RJ2=gEa760J@KoH(Qa1FNr1hQ2P!@vOq zVF~DvDGDGD-c1TTClD_14`~1Z-#ifF{Lzw~AAIVk%3UMOtouC6`@C)M5GO9cZ zJx~d+%-?(htFjv4G&10u-Pt_e&YUd~EnRDgJUy&qID-+#0PqIH@DA-D4CW~ifq)J2 zpbosy19D8q;Bdz@&L__rtvD_tI{w@m9MABKW*Bjo{lL9KPRz)Ai6E^S?;5XPt|4Lm z&IOLdcOKmvcAAIW;0ONT4(ucqd$DtlA$5-6dH=5G&`stPQLL*Vv(-K1jvFO6o3n*} zA%~u|4zB5cp0WvEUPl}0Y<|CP-rxG+w9X*Rm(CxV?&)K0=C8iy6CtB64C|6^yHaAd zs}4ACezIk5>xs_jojwpHplNvt?3`no>&R_)54tu>Wdqhm_)!ySLeeDk6=#Vb!-QMOoZ0h@Qy2)McxSnM`yXmg} z>mQNsW<{<$sp!@{=~7|^xvTH{9%ohS?}i)f$d2s`A*07|tfHRm^sbNgt{=?n3|7GK z(hd{M0`T%q@tMu;3h}c2a0dcl@V7qle*Y4r=EDTbBlTzeDDn~B_izQWnZ7up7TYV_d`F{Si7*QzV$ud^`u_!M#IBCT=#ZQ z^8K#%VZG>p-|n5;aR-R!8bA0Pe>8hc=!nm*XHWH2kM^Grz(woQ6VLTs8R$}Sv$nkX zoPYPAzY%&b^#U&uSg)5bKkBF-CFkr6>CF0s@A{q(`+Lu}jvw_Ap}l=x`hkD?2=6B% z?fa$P`B2aE?q2=b&JbvI3|jy8G5;TaV58OA3H?mb>TA#V25$Od?hqX3apjNx;M@Ft z;sE#w1>*npO)tH8Km1ca{b|4a0)cb@0SyHJf&~p8M3_)vK?ZXeEQA}=*Mfyn_Lba~lii16BC2Z4eV#Wpw7<1;O@np)CEi2w>6|P~ze8GC=3VN&P zrl3#tJ7z%eMaHBFBEFn*asO<#k({BTom=;A-LsW$X5E>y@ZiKJyIxJvL9~8^lp;_5 z5jJm+zNvGi;cOX+>)pM7Z)%+=@W#-Inh%Per+S>87xja-;rVd8$ftvcC?0=MR?hb9 z2QWYZKhlpU@>-*hE%w?=aIFPx@+_)UN^4Lp`!*U-p#n3UsSsyW;V?uI1>6v)0~31? z!V2jsuD%t|;;V^%__>0@78QK4Ck#jIDl;BwDuEeiPWZ7%BV#M^rW1`TFUP%{{0z#` zoJ<8Zt5U4#LXLh+@<@_L=Y|}=GCSZ<^E8~dE&wEjTs7`Uy(Oxs!b3{~4EyxsS zB4IXKX)#(BfL{>#VGLi!>42bNWN9JXuNJx$&SUR9_fiypP4C4lW~8CmCesDrz7VTr zwhOWln6_Vk55l*g75-7f+gC6ux6yfxWf;?lR_Uh|U+InRuw+FHxYP!aab}8tKkheU z0CM;T2yfL{hZ|8iNJs(@UiRT18911O0|su!IcJ@B=DBB|f5w?+n}H^}Xrp@;`e>z> z20Ce`pN5(Nr~jj-y6CBSMuE9Ks;2sCuD{;dYolej_})%IPKYH_&}O^Tj0@<6n1UvG zg9t&)*(D)QW|dWuIsOJbaKQ&Byl}%0M?7)G7iYY2#~+70a>*yBymHA;d&UpTH|M-_ z$`vV_Ly<{c!Wm^8XghU6Gmb@^O$~D69~=;J8D^Qq1{-YLbN_mG-mCWg_o#yxo@w7V zc%~myia(lo=9PAyXR=?%_-xeycr3E(w?8sqSjw?Mp$`6e1EPfUVz*t2fn8tyg%zSy z8tx`;*kbC<9+!InY{N}||MCCG0AO(r9V{db{~&_-HiD&@FtCB?TMqW4u5B7?%n z!!c$lK>>i+F#=#jhw15l9o!=KJOrXA*6}(@3`rN+xUMpqv5z##;Y+H50%-JO5nj|F z!a|oJJbJ1G&TvKv>^RBZlrSfHAEXiAkr(X8y#nS$hJKQY=#bPl1AgNWuqD_Tktj+A@Oa*0ZX+7@}D z$)z*RDM)piQv>LsAJ0IYL6xdZk=AhvWKqpfwMr9~+UlrFP3k$P8c+b#K$nl8DOj_~ zrJ}YC0UWEsR^=L#uGUbND7hsiXOHlSe`ViD8Y+Lk6X zo{HU`0XQZF)Ap8HsFjID<)zk-uJ)EFXhlDYQCa5h)V4jHBx8L$-H1e1Q-1{scC)+J zXCn2QU|^19T-)5*R@IJHAPYpPyIz0+HzvYGmqzz!To#=GV#y!?c{^KP(AsfhCuMJd zdxTq?z*k-Ll`4Y02!@*~Sd^dT6oI$rENBUsz1HQTYW17o4Hp+j_I;|Q#yevEMwpWN zGRB}ROkE5k#K4e}ZzjDfDJ~=rtqz_qLd|PO2ZYK9D`v5KVe;aN(RRN_&i~6FoC=Nk zb@;)EH8CYA4CLvy_#i}PUyLtG+`WK7muoXJhn>4)J2o`MRPL>nkyTDE=a|GuKFbE2 zDh+Ff*~4S*?<6zeO*ETU%>}`-`)2%P9CKw0QR$zZ39aKiPm-RE=yPfR{2C3vSs4t?J2}*F2FnnlQcO_G7{a5LF!w;^jBlcP ztEvuk1YZi%Vb8MIDbX%Q3~+}b7PQt|hB89-Hmh!YN7Y86rGYf`Hu*kIK1a236k z8YCAP$JQ&l{rV_)dV(7&RDrd-%{F3go7=fgEt|(}>wQC8Ez2HaB>&Vc6z;-AOAGNt zHUM<(B9TByM6$O~fz4`IzxvV@Z%Vn9>xY2@w&UCVWhp%|k8^+n7cr1GzPXpmh)aCl zDEYP+!yVse6NLbL&|1NXJ#$L?;AJ3?z(L>u2qL_J8sqSQcNkuzIksG-6W4d9#VvK3 zuSMg&BbGmX;~gJ)oY-A!06;xOV(%2c+m;k-kU<)Pq5qB*eEygq%)scwS$fvP zxcEgr%jEMrdxKVI z`6wULHel{PE5G0Gsk=J-U_q{O^9y^`gPiN|tcgtchl5E0Sn!5=AO~0wfr2mtVR#33 z0ERIrhylO^Z@7nZ*o1;$18lg5Z=j<5C_A<(owA5O`3u23qPUAw!8>cUtth|nVu=3h zJJU zK)4450Dv;s5hD198~^|x$cI-sh*98%g2;tm0Kvo4AL#Gciz5onQZ6-I!^ab}Tf2!s;06j9#atu^6&Qz5CLr=xCJvf1OHv%1{RWqf7k(nAcKE+6?J4scRYw` zn-zNesd~ysC)!7UtiNNtzot+|S}TlBd_I~?zfZggKllfI;K_g32YpBY0Pp~62nK2- z2t`N-^@4zT2m}E5gnTH73LqZMYq$lI0fA~529_xZOF#z|Qvi7o1ORvg*&&EA&`1CVz1%&=t1s-wS|D9gX7vw=*@8eGd8qzO`F z11XXjf_MXBc!zcnhBGJ#7ubb(KnGf|MS|GCdjN+IR7@_Uw?O$#{|QcH6wb-~$DpWz z6;T%7gqzM7|q-an(%{)HHgGK;~sB8n!?Ge!U zgwK|&%$ulzLb|bo%uh~iPW}X^dYjMyMbB6I(3;##aBEPM5CDjI1`NQ@`z**5Rnd@Y zv~Y5`At}++sZb0hP%ruA(QQ{m!1*Sw29IJ%~1D5)BlF$I}wQ59Bkm4cvv zSYQWv*aa5ws;H|{DJ@hpy@?Bw3Qz1(`wUSq4JRkHQ-7(JYsr>v=@tNp1#)nMGN=Y> z7*vCF)E4DTQU!_l=`|!ZRV95;I8rGwoz#$dxq&Gd5x|E(Ac!9L2kn$BLN!o0mCRtB z2@FUcVqw%IC8N${%Y{49wt1wqi&a@QNrE65lZl-XD2Q>m1iP|PRee)K{Z*AX4JHH8 zRZZ3<#WkSdedU_y@z^kL}c|LyNw77(4|$_zjFOnM2*vQ6{<#XhWbR?LaCM$N}+Ih$5qL&y^{hD1sq!1pj6{R@~()&JJk! z2p6b_SO#OZ0imd}hz7vkR6j)bGM1Dy8R044|pC>Rr==8LXoUT*4+(A;Lo z13QRdZ@y=HHfD+-g>E5*uJ-D#W@pEe(4p=rWOij(R_cmIVI+3n6aEM)=!brA1Um== z-+knrW>FcY2w}ihVesp}_Uo{oD_A9KoFxgfCWsw~hfP*%1_oSf2G>tXhJHW=J)r8X z18L0GYv`J*on40DD{R9Cfqn3WT`+B42#3T}lBK@pr*>_omIzenhhzW)J8)sm#_LG# z>Hm}vfszJ*6lmv~kmWLY=Xefn{P2o>$OT$pZduTTcuQ+3M&+x@nG%9Uh9``YlC3pet3j1AZ2hqW$B*o ztnP?*@BxG90d_!dxoRkxWbf|qiVDEX7`Oy2TMxgtOdU#k^lxu0DuulhjOR~8INw-<+dl4Qj^eT zR+s=h=xBj1^6nmSj2MGl;D&3Mg#uFXtr`ntSm``R5|YpcOLzfzFy1mi2ga6eFfa5~ zH;H|Ih7;HVy3T13uW$PH-g%xYpmt18uOtxo1AN#A9@d2O7IZat^g*9HkWhjl8iWs+ z>Z*qH5Z7%+ONj*d15V(CKM2Z9-zs`iC0@@Bw`c(}P_HxS0aQ11>CJ6?9zzE}v;e5> z+dg(R zCUFx7fH9BUGEJi6DW=UKzvG}%djCN~lzV0G2b3VwbnWy(OkMxNc0bbaLd$@;v;DrSwjNvYnXO&UE zZw#;4_s|dhqi_6ZpLh|Ei2FvX4XA@gcYBLY_%(wG9gqV#07UZz{QuN}j5hUr+y?v})^X}@)8HZAq;eczu2P%wy3m<7^T z{&^pN>Q{*OfQEQE0Xw+tm4Exf*OZg^>iGxj%+LK&`;hHtXL!JLg3tk81PA~E2NEo3 z@ZiB0|6VYd!vG<~h!Q6vZ1|8O#*7**YV7E-qQj3OMRJ@-16sdD00M-u17>8#k}zjZ zlu7gEL7N#BzJMw0C(xk6a1tE|;va~jN|!QiTCjvOW*D4Ot!niu)~s3y9tD985kW-h ztn$>kwPwh(8`G-AXtpiHw*?y%>&J=!fEsq{Y_KX9uED>63I7U)$aC=7u80>ihG@*0 zmBx}MQ?AUkYo>az3>ktoFB92?g$Iu&&DL^hz@s1adsYI#0zP(zTulwvc3a#7597@7 zrUHNgmH{XpZd|J*XOWIGZ|d6bs&r#oe)(9G1_<|js+#C)q=)_=+}pg z{aBS?sPvP}Q~-csM;HNkIAUc(QWf7qH=#2I04f4-ga14(CY2+Y1wB?pm}Q#T+>TlG zIGmJDwb|60O#QV-KhiiM5DIqKaYBSaE*9rfRQ5zuJUV2FUm5Ipd1jcVD90$IkuH`d zR%*0^sUFW`v`StOx;- zjxYD?&-5GcHpjy!F~UQ-1>pSE;eucIs`m#{sI;TdYAdgFqA9G23?l_v!Dy z5GPb+L>+kJ#xUg~B*G@S_!5c>!x4M$a05Ix1^>w@t2~inhj3$$J=z>nEJF^9D6q{p z``BI)(eyLOKwH?shXD;stXj@M9$k<^K7jDF1P9$x3IG}3IP%JqIoe3pU3=XXCi9FU zha98Kb4h45FYRp7M7BNU+iq%i!7=@);v@hc`W z8XNSDCx$YIwbzUJS~=zs05FwD&2wif`KG$5*f^n2*4%ZCMEaSlO%>&z&Jvk7hgFT_6PVn{E&mOSs1PxLr z6$9m&#|MDpy#2$q4|$EG_ys38@r!)?!FuS^8Jiwhx*zJy0d={{K+vNe4tB4J9RcA%dKZy1 zyaFBb$VCfh*p@;#14CN;Vu2J>23%kR8@M0?%_cY#HLg*J5_BU4(_)H#G~+cH+FOU1 z7(^l}O??=VqCxD3KmBz;Wc>r9T4>-5WKau{j-1>f71S>$Udn@e1OT1*(FKCM4sYh8 zqyuLM#g6R58kb-JB){}Xtsnpy&i|mnDq~rht~{-lAn*VLdXHs)gNU;w#u{n-U6u>DB7x^jqefP!qGAjc#&;SK~IL=C+-$3OfqkXjh-AHR^u zH^tdbaI(n{syI^Xl9-o|Tb>_j5r3`xMYwjSw<9PXiwSRCr zuOJerr4Rlg0}jlA0}Qw>cC)M9?Q*xf-u*6iscT*ElDE9(?XGywtKRj3H@)nA?|Vs5 zH)V(*yBSa?eDmvF_v*L5@|@v$(}Beld(=EaMr|xW+cVF^+Sr;~me~ z56EbZAy&L3Jp6&jMm{oSRzOc;_(iG0HPcA;07Ed@>)s* zAUVsSwv}s0kN;WN13#AVg+w|qhB5r(5@U!#2S{-S8Mpx(-iX?$H4D^vvsE%wkj4c| zq8Glz+SDCYZK6eTzyvO^AmSny0D!OyIpDwz-p~~QI=~KE@Zbl!KnH^ua1CE9TOeuB z2PS*~3VfgtBGaa{7X*auY$F95Gt&|o&>;~vl(-fZ0ERm7Ar4ufG9nS}H@!>Un9yFx zNgPoa!+>7zrK>gIAF&}0b;v`5SPWy169^#gp@7Cxj0pdbour*bF{%U{U^|LUMue2H<5RM3qXig0}MM?DJkBqU5XOtS% z04b13sQ*JC9$1GbAW(rrtf5o^h1 zxVAk<-r+Z$i$#Rp6Pj0BA$5M~Y$DAoND zp8y`;;&p^AJq<1q#0%&S?>G(!Sc5NILtP5~xm_TeF0CeB?g&#qXSVNUx z`V9mZc~J>!RaXqaCdh+*)I+V%UjXLb45|fdNW-KJL_;VMwhW;C`Cw+T9pkA4c-|Cg15G)cp zrJza`2L$}U85B|)b=FAe)f~!U9r~R|EJ8p0Oke=QhU5_tx)rPiAx-R4Kgq#A1=K(> zAqkbx2@yv%3{JWTPY>8bEcn0= z+`>DAOjwj%8sq~e^nfRjoa&LF8b;GJt>PM*V&0KjAaWKS4$)vtfzOzNT@8d@4FA(E z!eTEH;!Jea^n}$|8HCl)T#0cQ0K5S)yhA$(!xfc*8wFo3xRm`87g4iQ_nW zqYR#7YR#in1Oce10$v!z0W8cqX=Fy$pgqC_Vks75Io4#f;-gJLgi&Nlxg<@zB03Ht zJ)Xr0SV%E2&p`;y9l)JQ=HyVu+fC%wZuQo01=nyj22FBV1~7v&{GLo!(^JBPO_n4^ zo|;-IV z304_|0mudy*x^UeAxRKsVS39imWf?bn6=TRRYGJ_;N`!OWL{w!mA8cE<0l>GlrW!&8GYDmDI?`-DmAqMIWftX9uts@61gX^3aK^-O zl4o(=VRDXy%N+^;#2j?0;mK5IEL|tSji+0b=Y5{%Vd`h9sYGY)MPJw_MF{AC;%9+^ z)J@PGd*0o9rXUQ3<&~)dpPYayK&X61Ra;PI-=(EiIz<=Y+h`%g2H-)`5vW9%=!qIA zS|BJ*%pQB%-YiKb?43X~F~hHP#6=~86IjTNUTCn;r{ZNNcV6a@-v2}qpad#>>sOs4N!ghFZl8 zG=p6T9z?{WX#pRVf`opKCWlUp(|H67y5K&*;9JsVRA!koyq-t&LE-enotP;+p{Y`+ z=_l#sO;$xYNlTI-1k%xl4&G@_c2@x~1=NM_Ndy-RP0@6!s3K=9PHK>zsYR-xY-Je=W`rsfjv??UtzxKJ zNNVg*YKIa90z}I*z*0mAU*Gg!v6`o@wkg0VYiy=mmMudXQvZZ4#LoawsD)Omnb;~u zU@Pq$Yql;${ux!HLc{^6Q(%B7hs%vaMMwW#mMu;F3UM#QRD**~=$D*rtdPJ(tRk-TO zxE`#*maNI94|b|7WG08RYD7K!!!5`x#x83)+APOT?GN6B7vP&M3M|2f>d-#Pxhf#T zGG@kNTYzL4GN6=1^g!WEqSMao*w*C6R;}FfB2hR2lD^|lZdAhN?3&&z*!C%-&}?DN zh@m13MWn+&OhVgQ>sjdQ$?`3--o%^Q#jy75@a-*|_Wv!_o}}ACZ3+TVmJOCfR6^k_ zF5^m))Xwc*Zth21YB6N0*4lxo#6{2&>(@qZzJ_g>2yS6HN|uEvL`VP^#)9c~ZidD! z-DWQCj)V~%2~|P_Q1&3^`t9o`W*7EuJvxKM`UJe zfU87^Yl@a@e%@}sHl5KzrXm^Y^A>~$6b>weZ>_%VOgJvlqO8Y$L~s74L}bwHR%zD) z5#)ZF?t;nq{#7d(YRDo4FBFdF`ETF?Fjkf?XKBC#j4%n8unC_q3a79NuW$)#z#ND$ z3&*ew&u|L6Fbvah3hUv|%y9IsXao0=!Y=0SdjBw`MN^j17DCuS;g}u=cd+M9CI};j z3tK@IRIwFbF&1aB7H=^ZckvZl!5mPr7mqO+m+=;Zu^5}N7B2$6p+XsFfgaew7sx3C z6EMyyF9ZW_0TJ<|(NmVeCPI|MKez+hHnG?~F;fUIR=DsKEP*3GG9*W`Bu_FWSF$BT zaum!#6kIYVcd{o}awc!`Cr|Popad&;vJ@-~7*xRn_^=&o?)j$dqatz%E`gy+#X)pH z;h>QrJMrb2jfYKP&S! z_cK5P^gjc164XUASOGP|u^nW=5{UEr{;)C0@51VFJ^N^2W!becTj|oXFJCJ@1BN~a zv`AO;K##OZGjmDvvynu@9#C@=sIm|=bSpo!InOWk=5hVTX0xgsL6kw^5D!Q1u{{@s zB40&FpEObol^EWp^OgnTPlk?-^@kHk|WLANpE{_i4!#{vSP~7TAFvWC1bD^f+sER^Rki&$5qVfK+Cg013n_6wV5i zwNU>u!Wx8HyY)%KHDm|0WHU1r!2c;L7=cT}bY5FE?ZWSYN_1b>ELTJ3syaifxKG$|K7xa-xfm9F85frmt(==8OFgXjc1oJVaA#E1{fCzA* zITUhh(-3lFXJZ$HY}X%4zNY{Av1RE3dD79cQ$u7e_L}~KlL6)H8o!WiE_a)oA+l!G%`u_dQ10Erys;- z85$H$8`yV6zjk#K#D4!bcL%tK^Rs^o!5*|@H5)-o@WF4Fw`Wf;>sD$_|26iSDa$&; zH2gykVfcM(czy#whle;yga0^?leCaC^EOM%ichn6=K*;qc#CswjE{CKw+cE#xT7lf zG~j}cXZTse_G0|_kSFtqhq(}Rw-NN-6jbvSYzTrQvx2+$l;5#mKls(Ocb5gom^uS= zZ@G=AGoNnwK!7=!J9Ci_I)GzyGfRR|wKO#!foz09lC$_spSNF2dGh8iMen$e&cLhQ zgEJT|pR;#_Ypj<`u_hb(ha)HU}#nT!AvbIg}5#*9LKw*ZHW!-T?GM z{Df|(A9t_AZK>z;sjqsFtGco)b)g@#6qu7{Cv+Tt!7|%=!GiW)qj#>SD`5L*DHP5$ z9PzM=I(}=rL}F%gw#xJ86G=brOy*oS~uCtHA$OF;t;WM;8x+ng5QHB)10a`u7-g(MAyjb% z2PmLJJp_YS{r|baul?J@edf1)GV5?5#JVuidfrd^-`_kC$2ix=$l1%&92AZ^psh)L zDeNl#bF^Yj-PGe}!aK|X5%2;y#H{7}{XsB2nLB-mJGB*n3MynX7VM3+PqWoOsqj-g z-=~h18U!V1Lp;PoHAEY))8!!)4m`l&K(Mo+k_qjLJOG>30H6bFGq*ipVZ5cik7NGZ z8^4Dy^}8QK5>&IJGYLQ#5i*cq!GcSwJOHqeVZ((C<}h$Lkzz%Q7coAJn2}>gj}9S9 z{5X;%#gHXm{CiX;Y_9 zp+=Ru6aS~qn*aPPyzy@gLt?KcN&qp|$3Gby=5S!JmTg3mOxX^Iq7`L%#lb0V5_bc`s$*TUO0(N z4em0?&_fYTRMABVLShai7>!iYNeyxo(t%9r2O29TJt7P{!Z?CbArMjsBSAq#HPwyI zRMn%Dw)@AEi6F?K3{lisu+EC^+|}2eT1aQ8GB{$TI7WU=R@r46>eZt>2SA5S06?%O zkUv#&wL?Oq7}eWvD}5B)alN&4pgpAN=MhS|umg`Pye%~&Z8@a3URKGp7o(K69RI7! zih_}aS%#b)*x-q#8;XODBq1PV*MxS0YE{=o?v#^H(Q^#E%fEJ!@ZR4x6RG;87d}i;to5&0GH>B zh-R*DztQgSZ-AVQRV-cULxtRWsCmZ8u|;iD4Xqyh5HIsZxPrvM#1xs>0A zTinvwwiMld7MawDPx%ma=Y-}BJVMcv!yP%@0VtfJS;VVy7Vb_j4uo!o5i+I0__LLbuAI!W0L zZ#B~!?Ru8L4}owhOq2=<4Me>Y&M-FxnA|_gQ8k*(;7uo>;uo(r#h=`8P-^Sp4o`Q+ zZ!tj`L2})vE~7FInnZ+vQ{ocqXh)Pp(S9`qV{=k)j-g;@Cj&r6asT%4M@1S>Ib>9z z8Pzx{9!649nSuu0B-JkTt!$1HaUxVc3CcV!2Z}4Ho){Mi6gO zGJPezX9rmtLY3ZYs<+E$G&$GPoiZd1@E8g&S^$+oIOAbkH7jzoN|K*OD5yd$2vIf4 zihdk}Fds$K%`(U~lQyKEOzEp%qbgOG0yL&)B?$+Jv7Hk^g$B;hkYOP^m9&mzt=rS3 zTib?NgA}44(vXZ&4OJw(y=|`y`Rh+ki`u|8@v3~J;qfB-5jbo|8zhs8A)WEf*zT4o zll@3#AJkUO!WEq|>jx@?0N0Slj7T5hQjfiO@~MmXclZ zQU$xV0WO1ti&^6OGE>cvLUKV{kjm5nUd=TXGNC&{>i>!|zxwSjMX0343m&O^9|k~bdxGR7m$)g`g{g|iI{-^; z#}XA#4pI_XV=eRQ#!|`ga(1lI9-na$o%KSa;!DI(71_C-WHL~c%#%3p#K|eHaSYZm zlyf*wIgM~e0Jj|IW_39#Usg_-FFIx&K4E6aMYCOn@H)$ol+E|WXNZ+EXPaocCUt)8 ziVF~m?ZARTN$4g51fA*!bHvc2yR2q29A9*{_x}lR1uat8WY@fYGn`LMSSZKV z2kaP1Jc#fh1ROF>sSfn2Gtz40AbOpOX5fW|_-KP}AZizO}8<$2{Y`Lp_})vv9_O&phwBDfdUt4V4af!wtg#i$ef$58;%- zKt%XQ4kqG@S)iyF46%m5LKJ#xf{vxkV`e!1yL&64YTKJYXF>0Rpg&8~DsCNMRw!;Sw0)6SP4^ z#v&yk?x6s|z(zn$8fzIcVEh=Y{Qo9G+IS=6d@1eNMiu6&<=SS*29EwL4XS#NwQA4? z(WL*HA`rNNWCXAwRA3zXXCZ*#8}?xzy20X}PC*s|ADnI>Dj^-RqiZrSoT|b5=wtw( z#|uPoyhxC6&M%kJ5B5~>WmabpU}g@k;BMATjdm|z?hpUs(APdLz?k9%(jnOb@c0%2 z1gyaqM4|$$;TFu`40M4Ttc)SrU>**EA)JsQqR;|C00Yfx1@vJkh+$#sgg5}L3wi4c z8^Q!Z?(Bw3)_SO&+z4j;VC6=NlHPDtZg9F{vAS$dD*WId^dT4jVITA%0RX@Qs390^ z3jh=$9jXQb=HXfvVh!YB68{<^0w=Hnv#$zM=>>veDDr_=d<6X7fGLIC|x8*rcnbkY}lz#d}32Y%od-k~}cQ51Bt1uRE8@&OZi zz!N+V^d|C)ct9P7LLQVbS^g)yIuf!zvf(_=?8Z>vN|IbSiuM#`2sn%j&36#AqJQkkgfqyQU#<-S`b7^8U&<6K)Pq>Zb^ZmQ>3J0 zkVZhdLlNFV^gQlbGK$RRA6%>o31w33iL6zv6IB>M@f3n0qDKL zWi=7&P08;hV)kURceTZ)qwce?^L;G@mdeyr-S2yE)_1E_g28pe@Z*Y1N64`Ef+z4v z=WRPC2o#>;3zkL6Zn}!)Iwanr(M-p7&Rp^eQ~doL638e9&Pqv@lBHDQCpzScoC=B` zp2==IkPSY6$h;q~xlA0M4->Y=HdmiA+sPN5+*Lh^Nq5r#bqzxmZreVn-s@FfCwO)k zrx^G}wgx08zDC;clTHlf+GInE9#z37R$WQC-&Y?#C!n#YOu0{NZSH)dR(CI+NA>iD zCcC@(dV*Bhadedu^BlrQ4WbUDRPz5UT#~QuzNHRXS1rl|lUWKxM@Y<)Ybpywt_d(X zPK~PD0PdTK^RB!~V83p;qiw6K-jyW%`h$cD0p)xZ9Fs7K&-m^h>`E`WR8NuW)9|rGEfRCmS&Cb8L4)m4&5|jT-=7Th z_Y6Mtsiob;soG+G7LV|8GqR4X;?_ zD4B^Xb$thw;x!FMtLr3c>yYTrSjB$1L&9443sq(}qs09|v}9VRZpPqM-LsN#oB`z9 zGp(?Md~u9`t+kD9KOfKdsNKtA9(yNv9E$(Q^d1J*YX!r%zEOE)T`$`zR3X)%CWf{R zlO?Nn4ZGALCPu=9@Ek3b9DB9QzIzzuG{6`4{dUjZu+Mf>Hz+m=3Hs02i*7%bb`1PZgS8a#)Nokay23*-)bJ5sYmF>&zwL1Mjf=I8_bxG zQ``uP>Gh#!DKWjU_Wo&9z-mlO`0`8bObEhndLl$_&Qepa$4lpRTKemUb;} zT>o0UCGTfT6KhA4@7xKY709l?$>?@2XH-Np>mq@o`GMhFEZ?8IzfaZq82|7A(w0%XC4@<8qh z;<7YRtn8gnSw?0VxG;8|w)mSxm|;s+k&ix;1Kx6;5JNsne+{MLQ~25V{4#&?k~hVo0Ml(yDc4f9mnkSO_EF*W$Dgc1C^|zey14bmqGM6Kj|TcW zdvx-77E&3kQO$1YQ`rW2Z@SsvO>brxie@f(JC%uQQM9s#psNjqiDX+-8=6?eP>eiX zHF@*VS4|7Nt#A<)I-aZAkqp;wv~J?9Ub!OiFML@o((7x4n|f`dmCZ;k;G{t^j5_E~ z!t@Q8MkQBYjcR~W9MVpABZTx`ShL zqAfC_4GM1>LYJ*B@|e%y?g!!~0_uiFRLL0!eW}6z*Vqn%;d=?^KH;*|=rWPZv2sG-y(isvTMTcJxZ5Iwm zihPz4=?h&Z)_Dl&ST3z~bZq(tZ_CP%SggY;8a3A=gYsYgq<^^)>8nF49l*g6$4k!N z`nt1*^!3nP3H@oa{VUgFNZHYQ!yQ`cUa`wy-Uvt)oG24V(*C_UMTcu(qoj19zr1(=ffnK7JAnKIDM$rz8j$BZja zI5IN^@1x&*6`#%hm8Tt518m-HS1@%^r+l=S_`2S@8yaXX#4xUu11I#z0@!L&1r^mnF zT(6XUZ)9YW;ug@c3S}imQAgy>5@h{!|KTH$v)h+p8!f4^k=i}+U7c;~GsW%qm!dPa z#y>3m6Yu4$(y~(ZAjjgxH$A0x@-*WE103TS^lMDl4~mzG@^3ElpaFU--voYae&5dO zKtIBz!VGnR)D3p_q{e+a7L>DDRKE{Tl8`vx{|dAGI%%@~*tffje#0;TZQsrc0#J?O z*!{ZQ=ge)Z4)AD|dQ0S%q-ZidXkul(ag!9VPPw#KlKsQ~2dnuC9yqi{tPnnz3#+2_Zr_eYDioj{|(Zvr`KphF<-E(`!mlV zF(=QTjEVbSf5Dy!;v&#U?Aa&Hzw%tfeuuyDgGEUg4B8?N^TR|nLcIQk=VHUCWa33y zs8LCI>@E(PuN6MkzR??O<9vLN{Jn(t!?L60)t)F?Y!&?3Vd+E>Q8>SU`Ba%^#3PhJ z`%wL|Or=q)&keCqk9{^jl5EEUqLU~WW-5WB=mXqzN3h_sze@+gjDgu3} z&DXwUr}|Zo2_{wM7XH2uuIs0Le{?oJ^knwjFPFu2M>qEv12M%SLjxIs4j5YkW6$4= z4Vo&Rekmd>Ws_A{MpEli;CPmQxN3B}O4_Rtse=QFA*LDL2*_(lQRqcRD7K>lWHM3U^(E zsB9--)t~VCD4Ag1Nz~UTKk?J8&o+vcp7Nit8M-gbv-x|Q*S|{Td$Vqh3L<+}s%e-x zeb1AjS6|cX=R7RTn>o)miSy=8H%F1_X!BUMjrZkt&R}GVQ3{gDz@{8Ka=lk>aZhX^ zEygEA!Q`QT-nT;M)fD;1H#|w(RdvK&WwNMDcb?k9g+>QC{~WHn67v$^x{n@uh_RK2sQ72O%Nv$qp@HgwB%99u}~3T_Q3#6NEsGxvRWVyzN5yVtlfP4{mt+zpz+@~uoWVnC*_Gbu0;uq#winu`~Wai{Uvtq!x zl5yp{)jEU%oZ>uoI(p|^<>ukmR!{tk+rU-BA~EYPlhZ;?MrcRf=~QzA-;+11QcEs_ z;h9(@?$wJE#pB z8l|q%C3gqSuSW$MDwOdsoquB^)a*9>_3inW96#QRCu0r=9LvF}hl+$f@HkM2iU!kD{~fP6s%8l});>gr*0hli>tyo4g3y7Ph-!)gHX7ByPT*PHBU^xw2J zP6!(=R_cB}KPJafsLQygr+DplV9mhILW3bxs);z{P<&59F7r0zkp!70q2XQ1P~Og+ zcFwq$@9!qTf-VD zVp}8O5f<%#&B7T-G<+wN+>m{09rvpe^}PjTq?+43N>033b|p>1`s=s{*&!;`HvIfK zcNTeriAJ4?dr}l+EMIHSeV7{t1<+`w-?9EPkg1=fHh(fC^eMcX^+>~Q=}yTLW#!SB zbc%;NDr>CWV*~WIcEoQMy9LTD7QuUcXnu~Mze|?HF(9X@3SGj+CNDL?hQ2i(+5H)29LZ-{m{B|bb?c;^ALc5vP z(Ri|eaZ+DrAQ=@-+0&19A{D7oF?X}0mEYFOyYxnCR;R2B=wH&OT|N>!Z(E_6HxF~R zxmzMV7s}wg4076%g)^EGJn%XI8lwtW;nD;T1E7RHsZj0UjP})Eh!J>UNq4K?|Ar027ZE4Bl{MfY46SXaJi8!MhY2x%{Yr($&1=wjXxx z99o@4)XwyhUmiTe0W5M^kpF^45X`I)5o#|}E^h5T@Zw7ly1t7KfcM`69T7Ql$m7Co zc;)?+zY~U!wSZ|k3>$hsr%5uv%7IvfttjCAAZp}^R@O=jU);Yg1EOxInN-}VdJ z;?$}6zbW@Mu$e_(?-8jo~&tNP0~LYJU;LL0R4RVAvUC>|B5gxHyy! zQMI^xSAUSmtU9=edtE*)cIf^phReGBQhz=qwatbLdj`(3ij52NxyjenO5E5A_Rj>H z9CklBLH-Kdm18EtZV8scNNB+Fux$>6G@LhH8h~9EXL3eDcoOiQQV&Hv^jM*Zg@Q{g z1>@|L3;93TChX=hPo&EhkGIfM?7*gu_>VJeeW)M+vqkBqz6bZgL3Sj;K*Ab4F%TSz zKk##)_ujL&Y2S>H>c9aKnT8t7gL_&!vJ7X{eY6bu4(l##-ExG-`oF16vW&z(HQudj zZIVoF@GzKK4vY4aF(q|eM&YwLxkGkgVCL&(s^88y0C_~5;WYqytj7bGNPwuGped3V zh0uXHFXdlZG)7(^c`%DLxFcc-w5)RN#Gfy~z>p?ttnh4k7n-&%35u66V zLWr#R!sCq0X=R=lYOjuVn%BIfmWIaL?SD9UI}zfYtb`*EG7sopC;{xM`5#D_omM)v z@4SLs&3y?ttBn85oR9Y524KmiB>^cX_Gt&g=&as-Gc;~T03xuIzivBYt zNE)TE)pHzn0Fd{9fY%h)aVyM;Fx-VB+*K*u{UXe6Anc72E*(1De=9tYFapUD5iAnH z%1gj19T8a?5j}u-trr%5ftV+VOr{BlQ;JNni6j|73Kse4ZAFGocm@&x@Zp}%bbann z`YlXh+`rdFEloyAoJ3WpM~OeS(r7pc;-wf=kQ)fbJ%SZUJ=<`_Y`TBB%H%cIAIwB4?D7yBg z*Q%Go(7^N20h6N($Da|;KXJrfyTxq}#Lv{k5tYasT==eC#GMR?<8JHV&%113O_NAg z%v`L!W&FNU!Z}Uc9euTi3)Y>j1jc!09YRU~tsMntBC%}}yM7{VMm#QF64Q2)Gfv{3 zUJ_?yqTrwbwP-Te_VcTYBuRbvgTXtj^Nt|z1o>@ukw_E8!Ki23Q5Q|gQbg~1V96zV z7%SC586D1OC2we#133vp@jhRo=M!x@|oIW)8{_CH#QKIb0jI;^m>{U87XV?@7{5$(}`M2b22gvQtd}l9nj|P{$Xt)@<2Doe5Td95KZ_QiOI7?Y_0I9D_g=bI*0eEd~`(^A1oQTe$%k4?KW0jqD7S9Ws=5CMo+ z)FI1gq5}|sM;*K=4e3Myfh^!h<{Q5%oknPy+q~f%3F1&izT-{*zwCCjk1B3Ao|IjBX&MUT|ndNS2XXCSEfY(42V1+ws!`GNkcSz z8*Ez}9Jx6jFE9+Xwh1q^@m;o!b+z^IwU=qM%T9r@&B;~-7*Gww8~_m|Wbd=IF$f?~ zhNycPwBZx9$O~;g0B0q(fBV+HMBh;$(m@O}+RVb>o?ts88b7mb(Lj+=x)~aPK%cdufqbBiG2AvV!4*8F2OrWeNW9-_bZFnT;EO)3 zKwo@mX1wl#M?-7iBzspKT-O!i!`)A7{vif=LEFw2SK`ohbuiI5P7xNtx(04Rffm*c zJ@D7qRHqZTM^?25VA_L=?0Gia(?1;@jwJ>Yz@|S#aTQGy4!dO}dK7liChvO)YkHpV z+FcaAx?X<;xDU1SYtp~&Gh)EDB6|U7oJC&jhf^ymffQ&4#7Khx(!D^lUcKEu!^PeZ ziT?2S18rH*rfS_Jqh8&`?ji@w5UBaHQ5c%bi`zclkeGZ2vP2Ow)G$#-X?04fW) zu;KFIq3&ToHP4rNhc8W)UjT^LVtucr`kWA9w1X0(!+xV*+p2knTWbL$Vb>7td&5AD z;eHa@leXbrv(ZtKky_MOfnmKr@K&7X!+m~3l#b(ALkTI37mg+iheItBNK4MZ9m`-K z3$7Rn)Q%wKRU~dk*P(gF0lZ`B$Z@)nai%>(mJg7-#uK?f|H0$#T0Gwdypy>)54LSJQ zB{9tZeB2~^TrGAI{$S>w@r?D}m^6y)Juj3`a*~R4PSS|%9WV5~dY4qT+swg7BBcG( zRMLuK$d$8QE_^6Obtsu{F4TYSQQ92VT8{nRs*yw%{jRSAM4Ryd8Wsy>9h)b{S*SnD zZYs7fYVRv~K3CR0Ur7pxA_aT|%wMAHx&eTg-GKz7d0dUbbmRg6wQ&FYLPx9}x*hVF z(PG>5HIQ#`z<(Y&^8MowSqd*SbD5Ml4~P}9PR6Q4q~Ao2`6+vT7Hy+lV*K$l8@m3W zm5>EzD;tBxRA_A&JKc$)J$e9Leg0#^*yeKY%@mi@$qd<9!+b2uGC+Fy)bYmy={M2` zkW^D3e>+5(p!r}q|9AH1L((5WwIxEcC4lM5TIvdY)zmgGF%iou0MHr23akTs%!Q+K z`JC}LJ@WI2W}%SfA>g=+7XN*^e{cVm$y6T_({cKf4f`J( zPE4DwCYzo)n@pqN#RQP_7?(1(2sVI*;1?6z;)Sjez*yc-t>sWZ2FJ^*wfx} z&%S*`?fO{PHLGSjaBSOQe*@J4ZS!q;dJ3xCX*oXFL!*$azono0mWy4PJ)Zr}OX173kp2nOw$a0ppxQ;)OZ3$dI|RV_8*|)9R?DhVd;jY29D4L# z=14sLNV4;&e>9Y9%VJgiRQD@aI)Dtd;)!7Q8mqy@pg=tuhK-?XC>G)#I3sloI=`zG zh#;fn#yvyX=d278x|Db?d=GbW$U_|D)P&~u_xB`XDM9_RLleGKx zpMjr+&(~1l0|>eAVm99ea0PTFT_5rLvMU96F!m=wBj_u&e~$*B-SoU{#he#poo@!g zhM50GkP(ylW@CFSDZmj)d{7n}dF)HKZU+EA1IY;A)-Rr6h z23|GID;~FU5<1UCLZ*13)#{{e%(JEsE@Rd)*T3m+N`H@$pe8;*pa48FHodWBnGhn% zhZb{VD{>LAduoMx#RyJM-K zx9+f5xV4!pg~FU|tDq@XoAiO4*^lXJjEa!&TLk?tobDs&F?}R#XHn&{6?n7<6UD1L z`t`QcRhHjo_6(a`)|relDr}7GtMRCK(`@$vdYf*;j9WMZX7JfJI2l>db7;*e!ny(h z_2kB8GaM4>aAi25FY<>Sh&S~c@#nIaAFaMGoZ8RTJZib18dd-=I^)cXugRr~Q@Orw zHw4;(jt>N#)DN^K8%aOJo%;Awa05U+^O=~95Aq^Mg}uk=BVDgmGq0L zS?{BH!TIgh|N77A?@cG>@h1Ra%$FpW{hAGu&$uMe#I@8c6|y(G+g3?a5?+??eb7Wj zQjK%!2e}49Kzv5up!vK95Xwr0FbKx1;0ev^6cOB6Dc2WLS0~3``ILcf>at+L6LogU!7vmRoAil>(%pA%6E}B? zPBc{?PrFTq5|6RH_o@H$8ZO#V^E4eJcS|dSdeYSVl;JD!rIQTcvpEcE{;S!F;Bi%A zKlKz|W+6RM-s*{-Me<9X;pZ*hKSA=l`al5v0ZVAO^sojcg8yvAfJ7d4=}1NW zCb$ZLrY;PL`=_52$)7=ta4M#Vpcupz`eTuzwedSVaLq-Z$*&RzkyeP8^xDutjMj$C zZ=bHz962Q@hZ4Fa5=!&{Y%MeUm^836zAH%eu`B;3_A^)T?U-0NwN(`@B1?C~dozdA zWNI}-Z;==P(ZvTOdSYMN%v~}Kqh=-L$1}c89S@EW!ol+6R&aHOFg4L>7YI5co zssTU95alYeef4(u@$7q)`iv+Z0YA@5O+v}=(sOTM zDUKeYyj5dCz)BwJ?z$Q++_8l7a2v$z9-z@}r4^dDmU{}Yq0Ds&V^_j8Ui=f@^^Ijo z=NyUGwUOfyL3`?T_RaIv{PQ92z<|r0r8e@%Z$#Fz)pyS^fq>%5JDb(v!XkMHz{uj34^z`)9)YRnUwl{n_F`4T)4skx z-QEAIYFKjlIUn=o&GqNE*Bw?D4GmX~zBiwgF?A3BchYeE|AsWIu)vfO{Rh$z@4TY) z<^%ix?ipU@@#yuAOpYKS!r|39gQFv#DBjEwC62h|YzS2aAM97yKSDmNOe zE&7ti`+DfTa$WIAmWb=G#lgCgzp7!wpT_^G8g4(sw{-aLRYRd64x73Epc*d4S^hVw zVaC6zhH3w%8a|)w>*N=Pe*dpj!(pO4=6_QS-TzSy;s3d62>+`ZUPS+^YUuQTR1LpZ z$N!sZIFJzdpR0yF|E?OA(uH#`q^v#{|CL@4k6qs=OxPg(gT)XjdC540gtoD&;aSK} zA0lp57}u;i&0 zE-wNseaG(KRYN*FS{VVZ?ZOn+U!RTfyJ(Y(d0l=bmE=x{CYN}a=%T@_Jte=&EB|ZN zus!NP7Kac2St&7P`u1*}(c5ZVf-xO?D|{{h%(yte&z3E6shp;&NkL7!+TLU+68190QwJTIIx=XAQKO{kkrM)QknD_?Acn@jhk(lO}GHFKkTKk{&&?7 zl9f$(aoZ2Tm)2f>gcf}Xz{6jR`*OGE5noKwi0~vs`7oifDkC8Vaj-cik0Gib<9!~< zKP+)WfACzT->Aw*TUQd*thDOsHg4qkeQid0^PBP1^ST&{dEkm)(gM6@FY%kxjvw!c z)C+=!S+7mwmG2KZF*mi(?XMr>%Bb1*C=20^*M5<=0poc-jd#7%teC9z(DSpKwLkNc zkLP~#cbPO2lb;WXCZnXG^@uX*P;0j)X;zZBgjK>s6K}=F*D0+Et;Yd>o)y{!FmC2j zJGH&)`M4%L$(xa*zC+VK3f&`^zxC~w_?mH3I$JX3tI)Mn;l9DD7hg_33fl+K1bP6acfw*c&TkI_gy zC#+G8YOM5tlS&N-!zgmxCp{Gec77O z?>dOYS+D;Q#u*kOve*s5O~eZoKnO7^jp!;2QtxKNf+1AY!eN1nDD1x90Ig^f9J)^u>yV=Ky-=%PwB_g> zlkNJ`{fmBs1Hr)}+vyEhewDM_C+(022B24%kCcifj*wsg$8q95M~}2(jWU1@ zKyx^tz^0kd)cf+c6aJ3LsH*pn;0zuZk9XjlgS_Kfyhd?IB-LfFNyH7UL~ zMojkTfU%Q7hW$vHFKwN2y%m4rgtpWhX-&+adhlZ)y$T5m=*zBP*gj}jd3LJs9 ziv!z<_Yb;hSrX_t8Ec=-jA`ZY#&XJ z9t}APb7U)w|2EqB1c$&1jmMC$7cX~$qR@R`LCY@#qQ6*Saso)-?^^*<;@PHb)Z1~{ z2LZ5QbTY$xoExh16VvJMDpBt1)_g%aX(xaA!v3ot3tB;%@i^Ik`NBLfD~5p$>lYF{ zkkxn&zxeAHg6;)imxQ6cF%0j@t&sgM2L)%}ewkK+U&3Nj$^~klUj8ENrd!yLbFZi7 ze4vK1rWjB=YfCB`9XPg7=hW z?g5KGx#S{;_F>-!LnKVgDOi zA=VDdV+gYP2O+Gd*tBRd+G0V2MaS6qlXdUBaY?;V)v4y2H{$bEr^E9 z&W~Xpy3>0`9_)JeO9$*8X76r>-#O2-#CX;5Ks;)0L8gm8FmXg=?sK?}eP6?+@36vRBjf=biIHj{ ztTG`75Jtj~9dU$ri?y2TNkb3K?sMzW!GHwcl8r584TZ-?>L)GTk}PL!h#%*p=N(r! zzkRG9%X$oUSFyiMjP3#CW{2ANB7E%-B-=W$f zVcZ@FYm?&%H4#mko`#rwuPUFP(CI18aq< zssu}=pyldeVs`+K=K5*IQ1RhHm=>!|^Kk-l8dLq4W&6A|n*ss{svzPK6yZ-@mvvqC z57@wuCz7VgGw3O^=z0Kr*5Jt}5g9>kFpMN00B%o!y-SmE=ns0tXFO`^I6E7Jzv5BK zhm=Yr7*Qu#r$T-X3&w-Jf#>Nsth-6z2eK&XdW7owxI+`MyrDE9mxxDts_jcJ@*cDa z1p+a5ZoN?QnkoqA%NWVy<>2q25Fkqkvx`C5smoIi^}|h(8bQNP?$EoYkcg+=+9C+c zaI*(2z#BB=6$)YO1tZ^d{qD(JI7Sk08n%cD3u7sC84xlv*{~Z;Ll`LqGoO$bCcG4o zj>t?8a|Ve;dNJyZk@O<~aTmc)2*~X&$nj>$xtnBk=fb&G0AI%-G0SEddeN1Q{)JvF zAZL;hb?kj7YDIU zKo!UGLL+>tkpyM2b$zjg)+|7E64%*yx3l;pLg&g<3Os$ay{#Z_93qDM!ACSng4nwa zdQs7KhP@-3a841S`Fc6yLMxDSgJvNUf(lmmFcZ}qV zIxe5S<>PtAtBFTK85BSuB7g>=(?mW^NE#gBEvf8OUYPXIJ$_~d5qyv$N%ihW4bO=A z184pF6S5Cn^wac%9xNp3Kh;kV&v2Z)h^s)jD*j29QA*9ROr3@ij-ZI`246dHa)fAd zCW&Um9C0MdW~6gwq~)iD5XBnI!+51lJy9OPkx8NY@s@*0=Q6mjX@IfH<^uPK7NC$r zb<#+Dz?}o)T{xr#jZ4c8e`%ifx$K@P>-}!d_juhI#oHPB-sJE5NanWEd~JhE5@V#y zh+{4?$rQC*4nPuPz+41G7VDc=OOrWDgQlfPJ84sg{$!*zy!R_3$4js;JFuOY&rq6= zrJ2AN_ex$+);XUhi@;)tV+6Q|e+P6**8CT=xunENBY$8jRHUZpWPk5miL?~j2|y1a zK1TUf!8<^pGel|Tu2)fcBvCS$SdRQ_5b)dz!u?hQ0ituipw4 z+9Y{JoA|sUk6#n_HAjFp{R9g!&vuq_~Hq@)(Af@5W zRgRrXG!hJ(q9XM`N1GZp^7uABG-MPT2==o#kEJ&;X!tZISFb1D1VPr0D>p9LH3lLZ zpC;lAjgcrrn;}BY7cZN2D?X*}NZ!z?{nA0mHP=U8HAmC8l#4S)>lK%ZKMk<2H=J)7 zrmSTjgc)Cb%Bg4`+N$3r{`5x!zciw$bLVwyw0Y&1HU;iB#FutTSfeY3+b(LS?E$#` z0tx7`!Jnpo+NDw($nD<)ZXN6Mo^U3Z@@*Xkw+y(pPaIaQG#28Qt61{MxUGEsfxM*{G|4>&;&fLAHkN4E;y+#2@Y){YPeeq`Vh}G6REws zHj=x#E7~)_-M!ynyn1=_)D4&VcOMcZ^B74zTx_T3iA@*pX29tXPwTYU#%)BComP`t zpjyfOm{sOU)aJYUj=K-IyX6@=SsGx70f;BB6PrU@KfNti2JR{^*a`uBv+PdeLWFS^ z<6I{G%N{Nhv)zSSLjSUdop2EL@O%c#9-_dxg<5~-%@|Wc%ihjOWU7u|Z``o!_XR7) z-LAB2m_r?!RH9GB4~pU?LBPlsoW6k7ahbFk4rN4>)hz>M6Tn-`j3TBG6bks7 zmt+nO72$>C1MpH%5HWGBxLY5noxG8Bn zl!?-mv_TzYl>lBu@jqB5&Eo~x!b#B1)YjQE_Qp`RXXGya%nS=8Om?#-!L#=CBNIGR z&Bib`qU@cp5qu;#p9flio+9u1OCS#YLm=8<2}A(Na4_LE^e=%J2ms_bljfJAcrlVt z{_o|7IJ3U8#r4MD#IudxE#|bee;d0VCWoa=Uw`|Vg`J^7GOB?HUI;=R#>9&Ukiwfa z1~wokhB zXz|A{8dD-hM@S{qrTQ;{xKs%n)tX;G0cFNnLDO(cOGjKRsc zj=$s`0F$MM89La<7f2?#R^{bZha*=x$)=97Ua2W_PRSH%>C$o9<}u4_M8Avq!Fh8!D9frCAS zRr}j-_91+gitXEfsyh8^zN#hSytctR-Df-BZ~3sl^(XE(RHo`v)n5F=2H%NRB8*_g zC@Wsu@9Vhz&757RO!YW=7tr||_bWBt?>i-4B%c^rcS~S^QC} z)B$}bUH2TxFYxhW*5fq#oyIp?cOWpOifCN*F-pk3#!)Or<%IhDxKnS}|HFyO??V!1 z?3?ztxYKc`&7p5n{1(<=$l4j6^Vs;$fwd{m zY5!31U#JIO#C*IgTf#0+MnC>~T)2PS)xn(LaCwcq^oieP?L2QBff|3?LopvnemqM4 zNH-XB)f{+TqW|Yz{2!O!zb+y@%A_+t{J!E8z3O{)b%`1OimANT%(auu-fM*%wLKXl zlj+Q*zM2cn^#95(OnUnp@`iEgR)7CA%n74sN#gzDqV@>}fFr#u{jaLwifkAuBiZgm zr5-Yz@_|WDy2ek%xWB3)ttOic6eAtu@Ygv6y`@3n%^%$xj_0?Xar2%mc%Dt~E!G45 zkc-Lz22%BUo#YKsD`oTZcpq(RXOqPV`pUlC(Wx?S59p4;aOIAYh?Kvc(S3QK$5JEQMAHc+86L_4xGAT7y-RZL<|?RVmE|Gg0$;o!T$> ztiz0Iey=9PDih>P?CJ$ielYF~`#x5Wne2ajH=OD^qkO-t?Qm5`uQ0csE(dwFE-B{G zH~*!XiesiS+V$7;hZ0AVdJprZPRFI&oGUMbFGZKMk4+`~me;sH>JHyBZ5LP-uPycG zGF$j%e}j2GB}V7t?M9-rI9vglc|P>a;vm$m?0D%WJyffo(PkR_a}~Dvu~zH49nhqsfOje{xYM?&~<@GY3@hCie(btnm&% zqUFlVurh6`d-0^TmZFf)Qi7sa7Sm~vG$_z+zm;-am~uQ8ytT+X_5>nZM62*{y?!!_ z=hR01?!6BV8j7=QF9+|iL+!|vGo4ybh>}ltX}@GVo5rXz z^7e{eBEvq3n6)eE5C!ht3AW74$kTOf3>{*N=54;u0QynJ6(1!g$2>VoYzD1J+fNc z)|70Lw{vU7x2I>8A#_c4#3h)L{gYY7TUu6g_n8&Y9Wt^c0A3C9ViQERwv52}G;7uB z*tirX{-$|WN_?;Rcb~XZ)6Pt*Q|IQ!l~WgiHQf0#r2pGNqXv`<(gV@Gb{YI0C-IwJ zt&h)Ajp%WV-PfzaPXLoJS`KpI2yDjEm~55J*bSC=*JIwgq}}72Q@^C=chAjs&!s>D zDX*1q_71O~@$5e|tS_WHyf<@&nP9_?4wuKsR2xNFg38U?rv_#)>+PV0i>Cy^pP5>B zhuCxd{Lk)rV*Go4rsXj9j_ z=7IpmKahkPU$YjOhZD$%aD~vImAQz`ksAV%+`VHy)I($7BClNOu2n`mlpdH10AREU zA`y-NiYPU9GkX-qSncLPCQD1%h)G!l6BM7kN61rfjrgk7=fvUiDM%Txt5?aTv0!7< zX4TzHON97%>_uHHC6EURxyCF!$k460@mh|dk;^?lWR0qh-l|)!~zbIBE-mu zFVYCL8^&YD&CRn9E}A6-3-EG#EbV2>>K|WP#ByvGJu)uqGs8U=i7}nQH_(3;j^cgN z+NNC$N>s56!q}$X&=$2Tc@J5>NrtnVDq=`_hf{iLHD^zZ;Lb0fdk}*%M}~_z+smH& zB-u&^IaB1ehE~j&_#4zc{?tWg?&fe} z-Ih4qUnt(LIgw`D!7zSpxDk|?^1hfRU52X;bGCu}{Rxdswe{@vH8Z}SMU&Z@Zbc{W z(QMqD6G{9%85hlExeTZnE1taK7dK$lr{ojBzAblq__=`gn*2RCQI{Z;`z3-MAx*? z2d;SZu7e^ zI{b*xQta}clgc;W(et-ou}i1}ev~ALOXBno)ZV-ya$xz~h9f+AIS|fNt66nJL%h2E zuOQ0B<)Ens?SgxbuEHRuhtBTpfR3v0D-PbENWBiW`w@{UrRJyFdJ5G01jes;evlP7 zH1NH{L{vEp8#6%U`}Ii=;?65rA0B*!X@tFvi8V6afAEP`QI9`4{yLGJ*<+wXvd-jE zoxmzFp<7LG(@GT0h&?=JZ8C_+kNM>6>Rn;JxKJA_a-p1{x z7R(CI!AGN3=6-3u(3cWUZ!9$M&(F@kyt$_lAopppRp(QRH|chLwRl{-(uLZ6p10nu zDHQWwRz1d4W0Ehg%c$d>70e$VCl>In2~m@f>Wo9o4^}o9GXBUdP}r*t|72Kh3MGZ_ zJMJh?t_y~GkA!CIQE1(8;*H7uER;G8#Q+J-fk-^!BhV9Q7wHsDI6+nL?}si&+XAtd zUj@nC!pGWKJgf`(kQr7I+8JJqs`Q`DsiCMx30i7gs*iq1lU$ z$WyQ6@Dfe~MD~xU##?04;AujzAWOhDF;=(bW!&D{b~qWkUh zy|3%{xbJ^p+hhGcU&nboQP>PD*o0UBh9a;50PFEASPl+hKgq!=7vOy0;EGi72vmuE zj!&^d=s?24-c*5WW=+4xk+#hXMsdAtdHtJp=;Z z4aa8%&e$362L)Sb0+BR{+8~4~0&HfjaMpkY${n?cRC8)l;p-pjw;E5-)CdNR#p%Oe zdcrkcC^(RfRo=yUmjfJk)sgy0|GRi3O|0(AU&v7x&AX@q^ zNstY44Fu*xG=8`PY9Gf2ykN78SFvhVv#w47*nvXhK7>#x6fV9KSj3~(1T$W0W?al{QpZD5)NB$603a#HwL8>6D#r(Dia?5zlmH05i6mq_f&dHQ%>eP0 zXKvq_hV{{-w1s8qD8Fq!xMm>-{nCiW9UtY>>dGZ5(kO>Cou zJXQvCVo*c?2;diYNeU6=c?^Igc$<%!>OhpPbDj`L4+pV~Sbu7|o<@(r@hKp68<$fN zPF0bSDUSbB5g8}gx*mWL2pkqD)_*D@0D(1-XitMJ)}Htj3VB4Bz+4os0Mf{4lw9{> z*?@o8&Fxkdz#s4LoO*biA>P>_GbRbB?jVI=n9NYOBs-Bfq#w`*1r91o@S=dQ^n?9a zhF0Y@lC8LJcA0J|lJ{oPCC~CM3Ii6z?xx*wIRbEPl4(jw?Yw5*AqgV88o3a(VkVQhe$ zSQM>z*Bo{JJToO8){3m--GH>Dp5witUKMXJo8BWq8u@f1MP~yI96Vu~?$8B8nW!$6 zzjYanHMAziK6n&v`do~{0so}A1R5SqiH&pu_wcMh}cF z%cA@`&RU*>!;qt9@yFn6ekoFhEWTg%YySH4f*Okt#TMP78Iv(AdVH}%Npm^+Thi?gw^^eCdCy($3yIf(beWJtE<^eKH6{UgUZKJ*~(ie^|M*< z$sjQ}=14(EItP7L*YoG27SHpoifg|0y?g#*^xM#zZ)m*ut#d5E@way^Uwb*%`Wda? zeEsSv$ioOz?r14te_lbyhVmsc1Dpc`7+1n>1d?hLO4|{Bj}w#=%;KgO{(u%rEaP3y z^(Wrt@%2>-3~8FvfTdWlJv5i5CD+xRb-C`wAtc*kaGXa}lC${F7tBF})3+1?7L4!u%h)Y(< zLBhuEXhUGsm+jpR$0|G!OX5{;>elpkE6Jysn{hS+VBcQQ37l~6FZoct=x-dx`*o>5 zoGY=M7@Hig4}~iNQ9tFBwcbNfwqry@u|Ev`h%rkkAuA78H&_Ov|x#BfQ7%D+b1ci^mfYf&j zNv$F!cXfgZ5k^LQ35&rA4#xEa@?oTM8Cz=V>*+MxqcppU{%Z#N7N;V65;x97I4)_3 z9l2SofhN2AlfElwjDq+c^VJI(Kkber9ay%J+wN9-&_UYxI$16!X5Vyzm@iqgv z!MIku&%WP99iVFP(cvzR>LCshE+}=o0=f1$>~mM|vF(@{lpiE1iUpia4EDWC2+-XM zP8>~t=7tj5BdB&YKC>wqL;c(%jB4F=tetbZMcL`=Te-Lw+HVz_cB9Vr?7EMhwjQMU zA^zDU$N{kD6Pz=d4j#>zyq0sQDv+e0g5Z?XdgZvMwjLV$IHdt>T?XRhpc|!BuCDJ4 z(x5mf(gcj7)@SPWQO>cIs?`No(~Zg#KiV_A)SfR)2bSe=(c+P^zrMGMvb$Th%Q~4X zIO)d~*#2Yjp34Aw?g=3*J5b$b0UUJBe`NqDvRKmAEm=mIHk~7z6T=#S+vK#{*n!A-`?JE{H3%@>{ z9!s#;JTo7NPa-(^lQ2Gbwl?`OZfhb|&TsFu%cD2LJN+;LleE@4#QBKZ{BGu~M%8u| zdRk+8Jg>MHAGRCq1`=V}-}d$$8uLhZ1GBK8nC-xS{_&Sh|EwXOrmqJnKAir;^{c)8 zIp>4o*_WlO$Ce9o-lICp%Hp|$ib znr2Wm`dRRLVEX)ekER)Ch-~M2VasP@~gDq(~Nq3IqO3wdX&GI zQsA$Qz?D`=q-g?PFLt--xmw#bKZ1E`FsMy%%6%WC(SZ> zz83OaFm+BCICMn-1+zRFyB)QK19Xzy2gtsGX@d2|@FG`|M91RqO@r8yu8Pn6;`L)? z@Z*W>ywzQAJ%YV5H4%!lAl*akF3?TKs?r@%$O;7KJScQEN^A($^frbd zcJ$7)T`!YgI;XDyeT%?e1Bu~>xDQuXN})&o%QY23qQpHRB)%a~4G4Nu7Z-yY-e8at zZco`B;mpGXTYY`Xl{;Tyes0OTI52QsDtz5G^g_?f+0|D;@+A5Y3n+5#pdMJD;cxo^ zMa2!lz=l~#jq(lhtY!o?PoG`dh9s~couJ%gXcx*4zc$ChQ{9qo z7$F$juq=u1AN{jRW`cyw8?tQ4b^Y3N}~z0eJEUDdX#2R3){H{h{%9Q{i6wClo1WXQ($RVkOB20Sl#ztV>3< z5=JK6{+j>wtJ?P$@zPD55(@aCgQy()F|*I}&o|8R_V9%u@*8MqsR6=5s zN4+NoHeA#WnJkOi%Z!L;0q}AqUT?;ZynILv4VwCS^D%`ui8%TRF7OEpN-qm%@#)`! z!iY!>6cueTd3~Im+v$W-OmmEHYVVKxanH{`|I#kxosFZPP(zpikT3x5f2twNP`vQJ zcXljEupx|UXsB}tbr?;fleS$uyr>#YV$sMr(Gg8=c{F2bLquP zOA1Ajiemy9Dsg)PkD((2M%5M>ZVN5~ zAEhd-;)qZ;Mrr^+x?GTydHSE*^6wvTu+bVPyenSI!zt9|5FVQFsdOZ zMm1y-oG0Y{pK1u^Ecy~Vny|8*l=|1)#IE)_ju02y-(Z~j|Eh+}sxlSq|EY#q|EY$2 z|EY#1b2_5-CE>M!j~u>K`57wi)f)Lp?U^zC)!Z3T=2jL2fvClhBj=$Bg)nj{2c*$9KLhmBCWBn%2_^r`Q)8zqT9|g@8 zO<2FJIA%)4+x4A{wCy*)_D2etnEpo_ZYoWZaXE0Eh2|r2mbjxr-Fw3 zBjE=BeMN+078*G#{eofY#gYTF)PU%;0ITdi_pr4->sC9Xbar{tdvTx2Ck>_9lbUi_ z+E1%*LiE~q;GBzw^iHaBaKiXtm3-^hpC$7<^{sb{KR7=YkE8j}|H|f6A4+l?srT$V zrP0%<=e0Nv+?1fBWbo4!>9BY62(w}+1~h#AKhRJat`M}Xi&p$VAtrp4O2lUJ@2~W# z2^W54vbWCXXE7g{eve2(^YT(y2xj9NZC(4Mbw%{39x@|$=6_5pn>2`q;OPmajUMHntYapYU2@K3Y& zL7%XxIh`sjnA+1^dT~=s1@z4({0O}4cBmYCi%;Ch)J0AG^qeUuEH&pyT#Q9k>5uiH z$t%2dq$zBg@~DSH*AK*bCu(L+sqLtnahOzHn6AAMF;V>l{ZcaXI=kkNb1oRGly^3V z7@O9uefr~eKtMD{wdqNMuzpU5m`ySrp8^0#&vlttfKHoNrE%l?`2`r+QdzxbTb!L5 zwdq+}nST(Qm>!Hnz#ospJ;TSHqdkkSLoy4jp5@y2K=C{5 zw~`&*0My0-3P0Y|FbryGJfjULW#?7ibFrICXXEExW<@chR8T$~yF_J&!-{{trc$*_ z;9wD%!v=%(@n3jv!LzYq~u z|Cpl&yJA!*1@*cJpSRwx$=#?=`DJxShE~pXEt-Gf*`yp*Q>FIwM4HF-(wn7f{&F4& zPd^YK_QH|P6bB%t&=7>)$sap~@JD21%6wY)e}BUJVzKoPRjA8*k?Q{}vlt$#h`?JT zN@xsjpx--0^g0p9o47EwD|R+dIOgc#-tmk8laPJtXu-m0AD)s)iTI zq@v$5%`3fJwZEMxdh27-kPQVG5bybb+m zZQ54&q1i@KMHSzS>J0B%9b42_`jgjE>+|nk>oOR_!HZK%=1e1NM!{f`oK;PnV(S1F z%1P8yjynlKCUOlgv0!3{9t7A6BV>8=DOzx)DaV|GB9q$Go6g^7@?;V6nJjbKkQT3e zEVHmGrd_`T2*fbau78;E!+;?y1ezI2F+#H5J}$KZwc{e8WBoI%|0;Qn^4Y`?(_IBz zm}?#=irQk%hsF`fvEZY{*UE`j&c_xx(pOA#tX}0-#7fY)<@BG7mY1C!JF5|q`K$!8 zU<)k2@sb4DjKIL&=ZS3?7&GM45LjgbM~-F$;dvdqj17xZ6aa#rY+}cgZZ((XW(_&< zKjQthFi$fpnk@-0qN2P@!1#q3=0S#R*!etWBvQpRSyL2x#}mWHP|?tF>kjf3EoNJq zVcI3ABi-8_5pA5inkRaBaor-L*H-}ziG|~UzgAJ^` zAb{mvWB-eTf{?ckecFUz!fJMPY*jhf-;j50lH8WNmDCL`lGWHOWXCj^QlddjDN#A) znw=bA6+ql(hc0D+;VN@?UIaT7ma+_qJvmVOMhW(8fC@VNss3o={^dgra7jg-UbwRE zUCYK=MCk8~;(*=}RvVn1I}j}Koaj#w_8>qXC_4{8G?9at5iAoNBRN*aLL46|G*CQk z%&V<_!-N;g*er`MJk!;eH-2bsj9*ApN;bkus!6HiAskZ_0e?XcbLKPCg03Cu`QreQ zlGj-3#t6w3722Y~w-1R(BG464{1vS1ni3TMH}}Tb#m>)v{*w!_ML1@ZSybd?$U&cmnE?Zj zR?wS@^`BV*h&@vHz839`zwKf0^s>{Y6(=qTgrq$ur3wFX61GKcTA+`#SGQZ81tc=} zXaByi`Rz`rM-lsIFjs!g2;dF{heIJqWl0D&m;!`B3qN4cLV0GWpFY>fFtj&si4-Im zwmzz5e_)^|PJ^TrqFmX6e|yDBF!jQ27a0C22c`@FNlwyr+kIw@|LYDHi8P*1rqH4V zEdk1<4guO-fQJW!!T=WLJ_P%*ClNSH6);8fAre28QEyuuQ#M1BN<$k5U8hRk4JPjQ zqZAM#-WQaxT{Wk!Ev|d(`YpJE45hIar3ocyDa$&Zwv3)|_)({-NYNln0&O=RKCIvu z*Uri=P6fB#W7m*n*Hzw;C~#0NNg&L^=UW?vF(`X|N|bo!s9Nc8<{dA+hPml4wm11s zckJ0wrp4z~YVI6bfNE9zT}>YxLXP3CSwvET*sx%$(vF;*A`KHO2nu$ErmNKn&5?{W(LhcB zjRj?xvn-x-JuRnZ(VhjHvrhS*vJ9e&1N$puJaC}QvH)(gx@T;-C(T4)kwR6DS7J_O z^t6@Is!`2$32skUYXL>5D8v!MM@XUuY@*=~QzK4>`#6*Inlxy-N+6>0rkIk+$_}54 zgURsNpZ#z4t|16Pr#8&a3NP{3bT%FFn%{SRHlhz?d@V~4P^NctDIa5u!%yd8C8{<3 zvJYo*4cMr4@EG;T(}0(!SnzUNi_|$YxfuRq(6t*L-_n@)TZ@xoBR<0EPn_d#yVqM$ z3#qL&@ydLx33|2$e5&uNX?I|0>1yS~r8kScx|Otwti!=2)5-$yNe~j24;dA>TIF*Y zp*Tk6Idp7s`eX~>UIUDW*6Ujb7Apq^0X()It~vY)agSU8mr z>jji=Jej-t#isfILg_)ZfNi({|5ygbdtBoxtyo`_GlC=GOwT!zv$<~Pb{IhBp55)y zJi=QPc4UnMsZPt$sE^%*Vx^UM6nc0V&@@&bA9EPsU`gx;XpWp*=(cQoL_2tP?;pad zD~s=rt)?N>&|Hm0l|O_7$V=Xi=%$W+&}&8XkLM|$JsO{utB(NFsO?r7;j^w$0Zlrl zd?kn#cq^-EvHRkzS=U6$+vk1~` z=sZ9H!_V;^0o}6*coKgm)dszc;PxUfrMZ;Xz@gPViB-OAWJy zVLZb)!Dg@F+R=}ES>r=q20^esWaYbU{+Zj8_xsH=_di;(PKrS-1`4rxIi6|{h|TMY z`3`}Fm$f5I9^X9T$Yh5i-TOcMqB@@;=nav*YfVc1B8=mbE zbL>P5wCzJy=Qt=MK#duG4x zWA{(6njua~EglTX;13h7LHI7Gw7~#=0MC}IF}UaZTDYIl!>G@N>HNZ(;0>G4t9(SB zRGhljh!BK$_riDJv7ZiM8@5^N#aKLTER&i@+vgHr$Xj8!i_gTf^Kx3+YMv+XO~j@( z6F5eYFcSnh$ie?3qNT(0#Sq=JVg92Z>L3z&;<&Bq%Vm1EtWOi8;CJ{VBE{OSH$058C+v(i~}UoL0J7SFCU-1r18g3 zJ;&E*+Ys|#VhG65Vyj;CnokzuSiV?&*-EV{{9p(we#NY|=1J?@#92oCo2vcvvWAzN zwj4I)ND88b%$#=yaD3 z0>+8G?Kt1QVB&xE%@iF^4w;4;d2;V?0W*CiR8NIT8l{sqWO)N%6S14k1G2(_a>E@= z9|Hu~;dte{>rU_)QK#0FfYX^v0<0^=P$qS)2D~2RrumRE`L(J3CFf5u-SBvzx%Ll_ zk!B%4MouS=!fS<}HH!Q^m&*7Ygz*rL3fcY(jUIgwau)>>5gmeHx~4htdSNxUD(bI4bf}9k)RR})c5r=y1G;l`#sNu0V#v2JtK zVvMemW50$mqi{W$uTGO5=~5SLMHTYA+X@|&qk!=EsVZ&` z3&WNUNRsjz4{^i3gJ1irx`OcQX&tzF5LdU_Xs`2v10KkX#M;MbjdQ0Mk?_}ikEDOV z7H_kA&)}PvSl{bn`0rws+9N%sqp(-FH1B#%ds&}`X}a8v&~+!$#|JKZstF`BN(d*5 zhdmuf|MIm83tvT~s!oZ?1JcSuVz7S)j~mbS*QxUapYYtpJbe>wDdEpHssxF{H9nsd z`i=DJ(TwZL9hO!x2iQ=AspUz+xxT=KJ?g7_+t-GE z^!E8%%89|=p11vpFT%UN$*jt$y20NQu4?Se)#o@I#Ok1kp5hmBoa#z0+Yse=7h{h$6LWB z{4T8@Vw~i?L}^-q10p9suMI4G=Zasz3Lz8nWYzCh+Z4X_y!-Y+VQu{HsyLEC1iAKI zVdFqyZQ8bskLyc99-WJO8$Ff8m+N=`chBA$ugqB$9VfAU%J)QE-^Ld1_+VLF*) zT73T#t#}Upa2`{X;p~I;FsJ~6?Tb4e{=>Y63$V@$$F-k_z6GG?ipS(2q2_3q4lTr( zc30!Qe`yp2T2-anj1=HmKFX+h&I33)_$7 z$>zG~J{ME?`^Oc}IoU<&`Dm|fo|{3HMmCp8-y)ZGp%nUJu4o5cR+K($UGZP*H?}Nc z5!)9Q?kU38u5+~}Z~s#b-LfZOmjymHZ@qVBB()pAi}QzOA{wywC(<}gm^f}Qh2C?c z>6wa&*2b5gTI7NQ*zoMZwED-fI#exlM{Wys2B}`zdfc@6qX^u`3eQ8lzxCJ`B=S)X z0D|O!i1uF^{L53lx*38Ih2eoc;iVddK2-N<^7HqS4l^|~rTi`=-0II5WVJ5$G+t_a zFnBlBLM2)WqVoK!zkYL3r4d&=tgWf6HTh%!h&S@{eUThgH7$mZbQl*Ps1NSw)T3cKDBmt}sEyF%dcMB&naP8~D&9K;xbIAX0~3>-;UC7rY;7!jL$ z0hBYkuiS3sI;r0w=yYK49Rm)J2!8%{%iunqtE{zy%clHwJe^0kgltaDkq$srI;+LX zMT79b#Z?!b4l+pzJwkfx3?+UTMuUE|+vV-fWkDWgl4=8#L2UjWS z=BT}hSOo6t>uPx>uQ=*9meZHE8YtHSGk|;~P7N*H@_O7?d8Yc4e8I+K?>NO?q>mu5;=Go6++{EP^6DLYGTz@mE0v&+w4e>$(p*?T#aQNzZ!lim=G8=lu(aV`PY4Q zfHsr%yn1Rsx3eaNEq%!z&&1|5e!lImL%;0vzg`_k%jHTI!{O01 zZHw9*&rXs5@LISn^TVd=b)u&k*kF2tS z@c8?m*`*si>lZtWccg+!-v!xGM+Y=qC$UB|l}CCnclK^@FMp3!mRUrer?SO9I~<{B zQ^qH}#0)e)0T4t^i)fU}`}?9NQ7(p7ILq^>Xm}j-$WzO zhgfRQ^-10DUput^>*deUdXnlQfe%I}B5A3W6G2KBC9JH;3=&K5^gVla(irLy*tIHM z_{6S7s~=eQi(01SR@LPL>chj_NJ0j`6NmRD?kBe$m0XybxD&Rv&5TPWZkA)Cu^=<7`m47u%Cm!kvd|H<2!fjgy^ODH0{~0u5U279ELWB2;psi(YmM2?;Y2 zy!=sR(IGHQdjnNWJIS!OPbr2$iq<+N&5fP?iYh>V0S??9+(q!)Gz6U)D}tAnymS&q4#6Udz-@G9&Q%65FfQv3fXJ_IzGxz9e+J0A3uA<+rP z8c8d27pfpFFPbvVK=opEzxyEKRZm*74qe=jj*z>Ippb_grteqd+O!fCNhgbQd8`bp z%9qd}QZQrZApM(JP4J2+0W*Y^8Z$lOl1Jh)8aprxU<2r`?eSQ`u$WbOUL)9P!Jpz| z(aMgIS20Fu^OV|WZ;28G_E_eqQ%)^}2c}h$uv&6d1G{HU2sPF$)n2dqwIwd%*F=)LlemAqmUAe5B`n>szbdAM0Jc&7oBJ zq@s^cXuT*hCzyN^%5>*zmiSidUXAhq{JeAEDvWd&1DN0m62CK+9zi)N0?uFXKq^D4NM||r{idQ`??T?j_*)?}2`SC-AodLJdGjjjv<8Hv zmjSN$ZY;goI)r}T0F|B=#qOf+l(mR zVFG4Q6`1td#32t%E|dK8#;xJ}kv-<3?3(oN|GzmMm}ZFuAU&E82JOQb((7SN+0e-e z?dZ#pw!aa=fJD8^tr8xbPZ6C5ji-_hp{twkLZ49^SXSAOt;XV6CcK1K-|21NfdqeF zx?j-gNyytlIQ$^3gH+Z;phg&t?Gtt$AfufIa2I*9q|AiovgerfX0J!CcQow{)B#k0 z;)ys0w@ox+19D;m|ETcM0A;jG99n1`Ezj|JqcSifT?abLL81SZX128;v&={$8Y%wJ^@l8lp$VQj8u5n$`$xl%7%J^%mQ0rnTjvA(`k{)j6o_){XPa_%Csdw zGAeu08~~W|F*tm7fUap7(XJ}t=CD?YYw1KVy9?1~!^`x+gB_nke*z6uw;SQ7{WC;~ zTa2r$G@q2&-C(Ej_UsP>^k+!=39rBA?I9F)6e8?Y&AtY9! zJ@X^gWT6hu{+m}xVlWKm1=CbH_T-ccGMy0IZ7#DlpF^jC#TmZUqHO{7!9fn>D_#aJ zoAi_@iZdwwh<{-S>94*YB%}iU{R#Mq8jn_n##AO)zjz*%h_KUU{I2$XZz$?D59s>` zqoGPRr&A_9%cAo3C&k@j3Fc*`CFPv;_g;J@8+}%{f))SJ%rzLtl$}CLdd9SsaPbl! zA%~!&Xt3-<&_B1QeSeW{J)dPq#^dS0HJ8YJT1n78{Bvo$qlBj_ZI-*3h)y_7;G-eW zU?aQq342v73GOjv0}k%{Y+}3s(q5LL5a8d3kQ!T5;S(e3b2OfpiB{7Zs_9UDoc)c?S`}q zj-oMQqLk!PrRnU&A4Apv;;j|fkTLwTbEOxT#KL>xuv`Y#Bcc2c{75M(+ULa+mvTpG=0|JA z;m@9Yp5GqaXjDx8sYorNl<&)qKAppREAAJtiFs!-Zjw3IZqj2GbaYN&^gJrzEehxk z!FhbTe{8Bd@H>zYt%5NgtP}W)oZ0;~`~w%TRh`>S&_i=m?E@*bGex9Z(08uR?|hxA zX`677YXKgy*U=IJ%c+{b12rc*buv478WJJ>kP(#~Pb}bL+8~{}#gInhgVwx*jvzS+ z2wmc-fbs-j_!*)g7*pqHcAys_`XuJUsMHa< zg{NPjE2kZNMa!>l0YB8PyQ?lTX%(Cy1q-T1U#FVTg4g)Y?h?)2e&!-ECdqYTwH|R~p8mTwTfsh0zxXgxv!+VL zN(Fo2b$by}89%AEt}yij{|Zo;@}nj9r@Zm_?Cu%5^oUtHxB=|T+8FR_De(EQFR<{i zWZ3)0$VaWmB)Gti%_umE+Ta=QsYn$)!#vZG(1?rW zXaj0a8CLodJyy<6g~1M;Zi?i^P}kKS?(b%gcFb%Kdd_sHBYsK8@S4YF#**)2=)Enf z_ud?aXKZK$W)%#;#!(rsdlyfl0-C_WGw)5Xxl6E@NpucNbYDq0Lg9JHBsqqW-UI0@ zYlyp*lU(mG4d$q-0elHS0%vS|es6N=3QN&lat%#FRai>P3TxwCJa1+6O-(5OU25B2 zwDdO70|K&!pc@;+p4B^r!id-I(zj$X_QEobdNWS%GA?8?Z^ANv_hzmak*sl1S~`(D z^kxzL&LWk~rVP)feUr`jJNuM|l+8Q_bMX1WrA8gV1l_t;HjjUOmjaVbFzZEWy~%Sg zLg^MKO7qgqj}jREPB8eLZ-0l%mC2*s%=MdZpC1f7B3-ZJw_szgLPxj- zzoo5EiKpa!E%Ra7@5wOjp=xb4#&-Y`x>alQXD@w!z1*Q{Ko=JI_cc_+2ait$=l0Yr z3_%=1_!r=n#j`JY`=0xH$n9%F(-%b- zmo#5kDu22^o9#o_-s1ZZlJwh!O*PdcgOKC%O@Se`q0r_Vi{>l2j%vXnPUEVxN?#z|n-15T_?D(@ulq`$TC#^d zqt&8|{y`Ue_0{rLw#z7@>#siIr&o*BF2R1SdkkGqTXB!}Bmao!$cx_`BL8#vLI%M@ z;Ev=+{mw(ZpI>#ki)p`N(L1*zFs}YJf7{(qVnZ5X67#LH>Cr1%GmgkXXuLAvGkb=h zT=PV${;QIHgQfnq0J-!5g2XA}j4u*Z_JNypeFqW#2PK_99-$fN0T_%AJ#SYv_eC^_JUwV$hls^)Qld?L7Pg z;;=-_vMR6=Uth6SUsE{c$uR6|y%!Y8VFzP~eXfZs|4H)MCpGNRt+#^hn`67xqtg!f ziLTI3W@DL_GpwaEg>;;@6%2j|%loy@e`sg9RcDDF36>xTgj`;Kt$eNYXml&Gk~3T`eW{{GNj7x{(#-52yb*;xB6#zkd9 zg(pU0>r2D5%k-+tqoae-D}(E7EiVV%%f8O-tgVbPe*JL&?8_N5A#mh_^=eJ&>hRF& zUO2AGUx#x9L9~M4YMpkHjZSLm+IVRn^-a;&s7E%j-dn7Zc zeXgoMn(sliE+R<0|JAP-OUtF3!)xomJ3i%`5_b&Do|fb4l?tvtOz_(}R=$<|`E5ve z?Yl0$7EJNLtbK%A+PCIDvUM}*ryT)qn_#)!oQ>j_o{}#>#hu`mop;s;H7_~f(Y%}Q zRQK1Hi`iG?9~~wCokQE~c)olj8gg9s{y2a8xXN+M3QofCPZ0mk89n{5N6_>AdGt<& z;HK#6$>)tt(h>zm0s;{B>wXrd=Z?AM_T~q+M|*u!Kci1f2#>#%{+wny%~d)5$#!TJ zPh9XYWBbs5^it1ZL(Xy422-ofsC4<{`6b@Q9>A#y}o=__w+v4?58)~AF%D8)Yw0;ze%zm4#9VVz3&*yVt$#t`}IH7 z5JW&Hj}l>pVOH;XA|av<@I+!xGR&YeVKklL(K8OnHZv;oKh;n^S*&I%U%;v_5>LEV zCzVxWMgnz#Gy0rEaw1uby?(X=o=T_SaXmpL7knJ~CYBWI!^Ln^=xy6|Dz(V;5}VPI39``iGy~RX42T>oUn@{R)kc*31)(r zypE5O@(e>IZj2os81priK64-|lAh-uK7EWk)5Vqwz`d)4L)43A<0Upwju~?I&W<{i z$G1kw>a^Kvj=_i7qtVy$^+Rzsg*Rjoo}St5f<*IEti zYtr}H7tsm!FS+vh$X|{A`?}mfmyOrdG^0pxYCDat<>0sPlq*bN%HVwSvQ<1@rm`(N z`1nOTCoKVa-w~S?<6AtUzMamw8ExNpLX#1OUC}llzfqoj@lT@Gusih5-OeCr&MW&z z-B@sTTyv&9Rm+$2j_PTesLowUweQmhhb0hojv-%ltEr~y!Jt9*+ZS&*)Yiy8i7Lsn zOv_YEd5zNk{1o_^-rL%6JTi)KiPYBXkfN3IwSaLgpV^+Ei%<-Qc>OCA?_iDdV@T&` z+n8yOWoEp0)N@wOZ%=Cr>9Td&o_H3t*OfK6y|ytIj|^U?-jc6fu|pHdRLJ$Hb=$hI z@A(=5Nt&e=#0lB9$$f_fcNg7`1ee!?q)$W+plI*Xs_)25y}r20K;tmmBx=gbi3`Ta zBa?a^J=qijU*hNc#ttuKe*zF0J4ZDnPvpIahV!$}xLSnr<}^d=FH4QfUw}{5)k=%@ zJb$0n9ZUv%f2T3MQZ`D2|>d-;X+P)a)~hZW(xEgzl>Eefhqp zXLA032SX6t|1%hZ4lAQX2qW@_$v_vX(kHLdrRCvKhx`?IUsQ$`IYeck$|I|U{7X7Gdbq2h>FH`A>l)z~LR2_*4Z z1VJ(&&|z-^^q+DjS`z{yx^D+T<&l}JJRAw!URCrKLt~*WS*TN^1p`az24Ulr5Py8Q z5@yMcflMvQdale0(JLfJ1<6jPC?j>A2l{rxXutv}=CcX_APaLj0L4VsUSR_?D;c3s z2u~j?)cV|kWeGJ(2mUo?K9wWvFHosRbCi=wyXB?}#CGzd;WoZ@42k_zu_NQCnR@=y zxi@H1thiwUTS1Jg8?zb8X zgxyP;SCaxilb^g!Ra-b9U+1svoSu&a9YDiQ`O1UZV z^fJj?AH7+U&w#=oyGTY7Zqff)(UA6G$$Hvr$O5|qLjed9WkM&iBM}JqKcvx%Rq-a}_Rz*sJ;;Jrkxc#Au1SL;dneNbB@=cJ-6ZV0qjMj1^v%NiMnA=vZ@&}$4Eq?daqS~5Rt-&v{1Nf};jHHan&>Ex*JH$+Ufr@#%Mb_3kI;ne+>iMuu+jd7J#wh139m9q6_X(91_wgz5Rnf=DeTlX=(@+25$X8cx$p3uvIZB8~b1m`^F5EYV&dj*3=8rnk z@$FkEBfhEEU?gQBc{!n#akCXAw^${`4Lg5!>J=Kf<0SkGSI;h%=6Vq1<@@&Acj8}| zxbj(0(x26JJuITbsGpHP-+o6E-wl9mK><+YCJFOhM{2}Lif?2u?a#XjalmDculyeM zKYtPa<711T@|(9O_)5dFlesS&8xj;ww4WSYlS_s`Kj^$#dlr5BXRlxF!7ft;FgPK= zqVS`s@&3zOMXs8{lXLpwXF8rtI(Ieiu2hBo|{cz81V54?tcbYo_KRb(LVvWaL)Hyd&Y4^3Ds zK`)YNB6bcd_8YhRg@!xFoxX&dJ3A`&dz}3$4(p%gSS3vwVV<}(*H~Uu97Z){G@8D~YN&}ya6=`b{-+w6qi8Oak+4JxRHC~~awsrPv_7$= z4(S+6>a?F+21%*lNvYCIsc}oGL!~s-qf?qDQd$mE+90W~cv4?$rgpidb{{5+!4l}D z;^7mCId`eFZizOUTsY@gYy+sMBJ#TAP-@(1WHM!ua zR)PCufj4h~=TU(_Z=o=tFwniw)uJ%8q0p|lFyg4t>T98!1?~%qe2i+yD_Yc3Uz9po zlzvo{iC3J>Tb!#^oMM5Slw4dqNs6zJD~0e@J}<0j$S>n9slmX8wEw||(HPh;ybuE$ zhWrN`7QPNIkkZF3t}cE%`8;%=j!lc2L-zki*nN1j{r?aDe?=l<$KJ#&HA;(GCAOkU zsT!?@s=fDah`k!ss@iJrP}CNCwpIs98>6VLMNyh7@Av0>UDx;g&hLD$bMgnsc{vi# z$K!dwJ?$M~!c#K#J7b3vu%mO??|$SAikXkkrPYISr+%b0@#hK#=gzj~uBQWeaJnOa zE~~%>z>_t4(H#<~Rixqd0Nqgm9VrDzUP!jKPcJA9cSY0w-lvVl64}0S*+4=5`H%b{lR~n@!pklNkg3;KF2n86|6+T_)?{f# z7aXyxX}M}2a|2Csk@6+JCM5v2#4=0p6^_o!3mguoe@;q77}NF{Lsj9_E0Z8H21;iy z@FP6+D#8j}Pc4<051_%n5L8GcQq_kw)sz{)bBDp!;21G0M>$2 z*i36bWY!6kDYsQBeH>Ei+*ayN1$c6n`Chg%vnOg>6l+_BRG_pT1=Lr>Y*xf`RzgfD zrKpN1akO{@)U$vjO2I?t%bswSXPuSgxRmE-mA}3Wf2&^%kftgHP(>u{5Lp^BS{6Z7 zZudI9ZmQ<%W;!7;eVK~u+a~8)8|Mb6K?f;wSV;XA0B-ElYY-ea_bb^B>6N76&k!{3 zUioAUR14DZ76NrpPwg&M-B0~Gz!*4of#(<3i6QCTQSc%&eE|M2z#B()PK>Xp7h-Kg0c;c-`I`Kz9V)*CjNd{Snja}! zeT5h;YZ;-%Te8lYA!tQ4RGUWeE?u$lX6ZPuCP!42moA^;ci=`&9t}o+gr(& zS_`rpA>Pz?p0~MvX*L~e?;K+z2dMsF>HnZ9$$Eel^gr$%`62Z+;eXt{EOF305~grQ zVytKf#NnR%^d67d@Zuf)t{uZw9phUalU1!RN#Y&>>HyFz8tZ!v+>tu!>{0HR5A7If z?;uVRJIG`xC%8HVwC{*KcKAsR`1rFCLc3S0y4R?IdU)dmC-udbRw6=UPWd13(6`f}TK7-&Mmt`RbdB)%3~>ePsWlg#eb4Xk1N#_aa^JFcr32Dt&Tc zeRm88RB8G(I!qj2n7e*7_k8@&PGwN${-AMkpVD|A0H^qdsAM$k;YRh$R(0xk^aiL8 z-VPfKS?CKt9}<>;YZlODNyBe;^h+g=yxL~`E=>t8q!f1@&>M7wPFY=jL8L7xq5p%o z%*D1>wYLZKjO5XbN{Woa_2DHnHDT#=c3Lix%GSONV`K*-5Pq^I!_i*|(+cv`nj@>u z`>nWzkzSRt0UDrafvUWkK3|vykZvmpZL5)hSBJ9o&;WhgeS=}|a$mgrgL^0Of{tGf zUdi>ou6pFiZ9=Gr?wK?^lRyjY0YBuveMrbxB0Pu#-1S(gz7XC7rA?4DLGpu%fir)y zoqFaZByeGKIh2i75`Mlt0fgUUPOydc-BK5XhC@uNd@ zWbZZO z?L4)p*O29#_zwVq!W9elLD01!;EHHUdlc9SPrZ$vISuX%<)l)Rru-7Z7J1_z-Y}ta zHsxYA?Z%u!C-njvs)?swAi$-dkFK&dxGc@t>d%rf%qPB^1qicP$+_pWfN+4FShJnv zv7L2Q)b)3;S-frEUVCN&gx&-xopWP-};4jxnGLh;S-lfnh|!A=$Xu# zxg1FmPibloEZ7@M_j-~|)7)OyfwKz*(?AfRodxB!ky`qV|JZwPP*4Q|G|Pa!e!e2? z0GdBZaWj;14?&@Yqb7J+1x^v@>52pZng{~efn@K&4R|N1RuFmlUiHuawfFM8>ZKSFYKtfFm7T1|8Uhz6YCpM@D?tviS%}YrHO9Bo|Vo*tTMCvurN4YGJdw zL|Y{O(sUWS@*BQhWk*SvWGfoSp`l#j`}EEP&NSJZc8hGJd~d^41CIgwgc7hJT_}K} zuWMp!qE;6Uohamek&hrQhk{&$7sjgU!NdZcDwA8>O`HqTRIMa?Px?!kNsE`b=?l6d zMbc+xR$JlcA6ON*JC6R|<;{`5VafpgTUE9RR(BxVr^*EAfd8mUGvQ(}k0$YZ0M$P+ zUSJ@4swZZfZ6Xm$-2Y4p`Rb@_L)AgEK;5X(ULyrnVL7R8P4*4m7z)}E{mqF((8)Nn zJvh3H^WZ!|(t?+$KB9L5s)svNbv9LTyR~e2?*WbE?W6Yx?M-BAz)ybqpI3Hin}O8Q z_x@yQn-K?8-_ajR>n%6WEeo~TS0?wKdC^s=zh4X6?fkoSAhFFxKSG0}o-ZKdd3t!h zPWBZ|?XN`K=(PcgblJiCRO_hEr9BV6lH1hmvbA{a0Mb;{o}A)~(>JcbU#b=&a6iJ* z8nq^9U*sNo?*;#%qmeTH`YSiIeVtBmiw(C==VJVoYn$`SF57?Qa?#^eQ;RX3Y&;04 z-9G&b1T@!=au-g)?6DLKI(>HgR33Tw9RdBGyXND0mg@k^-(Z`$7j7B8n>W0I+1m(b zp!k9!{oURUFE9o9f43(7?(C6*ro_he9|yOIM|BrD zNMaj!ifqM&c(F&Ep@-)*fDr#r)lfTC$Z~r1=5w*Twf1wXt14dft3LonYNf6}ud3T%cZRMC2DZS%1hC^|FoO z99mu=LUei4r>argeG`Za*zz8q z49rSX8lVZL09gNmqWgHfa9;mMHT)?{zs(QfH*ORgW+Frj#w$c${o&p{V&TW2!$GN} zo6i5gRl{+Fnq?WBXRx4HwoBtj&r_ej3?Q@&)m9<4A5NylD`SR5Uj1$bA!z5@Rk|yD8Y86P32gM-{OQ%~$j0y`dL%f8i$8WEn*G zd4a@@J`$`KTmR#ZP3Y0lJrqXxTDniP-0?rEVZfZ!B{4w?jjyNCmM&FI$5xbJGJyXS z0*C?tAmK|g_4py@|AVRb=g;~1`JX?3h-b%VXJ>y;PX0fp-r4c--;iu6(Z))mvYKk}&F*P;y_dmGa z#Q5RF#M$`x`N+u0$mq$)$l?3DAeF zHd6hkCyO}Ze9`szr1|Zix9E!|J>nb5iHV7Wfr0n$-;a-vkB*KG4-XFv4D|N);_>+I z?(VLxu8xk5*4EbM=H|x6#)gIl91cgUd_*jRkz_q$F>p~W{I`PnZz=S+s_J)f+(1=y zU0q#mZEaOmRYgTbSy@?0Nl9U0;Yn83@3d!UDJcgjsU%SEG%1?+jC~OqDMpA|fm-EF>f(FfcG6Ai&?>-^a(t%gc-8>$$nP z{Rh{xx3{;owSD;Tp^c4=wY9amxw)ySsfmfn?c2AFjEwa4^>uZ1b#!zzH8qh)vbA2L}fm8yhPt zD+>z?6B837BO@FR|NjN`ILN>h6ckV>l$@L#0)c?RU@|f?A_yQ!8p0q_`VWAS^3X7D zJzPN#2F7&x{xGhvFAgrKpQBg*dLW7Yn#;m)ebLZU<{^@)=fnCxn0o50Qc+!}pZ}Yw zXF%>`kI&R^s{B}G@y2Cww5jTI9jY&p$Dp}-?v2w-<%6;28taCulcG-S;tN1o(67zK zvA1>K(w+VvrrzAG_z6b1hDF@}HuX|W2i0V+A>RE@rXCGdAtL;Wg+abiXWP*hfI7$Y zpy@D0i`^LF?^M~a;Ga70p0efhhHLF0RpVgc(z92#PkwEEo5(K>*xfxUwh7%nl`V(_ z{q!q9Q(m4$X%Z!c`c(Z69hYL*9m)$eh>|VoaeS)fO!0z=@k|Mdg+Z?qxINy&MK{Kq zmXc*ZIX!aWX>dwUynfJ9l&Z$MQGnIV(-n%A5-|f5s~0v%rk>7-Y3jDHanJuY^?sDR z8+wOB=<{&9gSB16i0I4YPYcR2bw(S*;u9e@%D*l1@f^`+u2w{bx#KG~^$IoC+l@ zyw=`K2F$5b^Juy5ykf-xT7Frnm)FyTquO7$tZ*u(ReW|Hn)~mj-ls7sno$on8!{wr z(i9{ll$74=%*gCwK=I}|PM`YPwqzMSb#$%2pxeFe|8DBV8CC}fu2LhwEP!oKH)!1+ z1ZVLx@OaA5{Xts)`pW$`<<|sdz5V&mnaB#X*xor#YW^v!3ltj~XTpJ~Zok_H|zCl_MJF&Z5?9-bMtC5w#xA zUu!y`r-Z22Fo@2<{0y!zf#{G6JnHY$Ryj>i-(!aeffOvd8$tsL!wMnd2jf zvSt&XpYlH4Z^N?VV!Qljdn}YsuSARrdj37tc`?EGOJ-3ZQxF3t#4G!TU7L{NVZLgl z+`uf+BfgG}lS}l$8We+hn^D@!fN>|%4a2()kEKBJvy;)ShAeE^K)Yk)AntHGzUQ<1 zXc5`NSNqYbCg1dDDbN5n;XkIHULPA2!7nJSBN@%8rb`fHcf|H75u*x|5aUa{QE)xU zZO#JarY; zD&$_*V`8a{j-hD5{KwQgcp9RD*2tp(dKl;;lmK?g)g@3QfMEr&AU~);@?G|Rb`gen zxrSkdYv-C!@`^n5$ys%14A#-vtw?KIo=185;05kOytqk}E^_{7Mkuqr2FzLSbOa0l z2ISYFQPeg7l8zW3cXcI={sDk`g>}>Ahmuhnks(06=piWq6S4uB_aPXXY<_{eT!ag#A}<7KMu3PimREDdqHfC%NCdL;DfuA=H}q(&ft z43KCf2e2Y?HHxBg#dchq_(*kkHlwDLbay^~YrXI0Mo;x3`KAESNBtjgbN#ZsU&$4Q zlw_t)ad43yYz#6)Q7w|u57D&MqxK00H>9&q|0d6&Wh^`zzr+ zo9Y@G3lZ=ge!4JX4u(xr0VeVR^whesHwy{GDs3Oo>cgVRd(adn z?`J;^Maub1!A#>E79WP%hS7oey;vG=ptRzk*Y%A^{)?7 zp9C%^!3i7}gy^h*@fBv@-2q9Xp9fN5X*6H#`(%Ge$J1`xW}!jt;_N<8N1W}K`7K9K zU%ApHmship!6J9)rZUvq)}D6UBQhU$7AB}IOf!7l8N2Qbus6fkR97C4vxr^0^O@`L@$42rygZsnmBAwjBWwwki5WY-@{@7t=Tqwq|jH@lb$yYqkokB^A4c&893P`^~ygqBXx%MjS+w_h|zr!`PIxkarg1SSmePdj5}9Z-p2Vv53Ry4;&n0>9~?yo-IG)P7SCExNCR0t z-xi|`%^g|Wda>#iCzV-s9>Lzv&w3Dl)9*4s?OmH|>;l+bz zG-s9RTMT=(9S`+Avk^#+Ny4@H>w64M1`A)7XaK0r?X&6ZzlY^~ojDA>W4vTGX~}*< zLc$}GfY~%+Za*5Cm6}%3PPw*At{Rq-5*=Z@LfxmP5`A&Qo6$V%(kt|!sKV`wlpvd* zZh@T8v!09HP~sl~y&Cbi%;ZGw@&3ym?owo8@VLFyn^zNNB0^WDQq&WQ7(1_reZC#B zo9^|Rue^Y4>=wb0fljIopS(~}w<$3|#%=0G_qG69_pP2n- z96~;1HpWDs_#6;Fg#{jmDXW7g2{f1Rv6=DaFJ3a8oHppczrLgfk*AFs(igiEAO!%z;KRsdm z)53VMA(jFQu8U_ZLq4>Ao4Tx*j8*V_Hq3+ zWMJZZ{rYpH#q;7fS0#U3l~zor`klrR2_OeyNfuah=jZ%4g9S&JERX@T_!nY7(l4nC zpD$mrRg^{=OY@Sy*y(?ssGBOrkDWm!xjAR-45xo%d8r%;3^4oe5%P9O>PcGHV^MmvN}%{h*|ToD{L_r$3nGaA*#%><^As&v3N+0R1Pt z1wb?gy}{ER;HWQ)MuP2xi{|pI8ATo~=j~8t);eV#S2&2Lk)9!BY%XIrh*MjPL3tK4 zKN4IjN8ybJ-@s9wz#)J%_4j?KBZ_tq9WF0wG&+}$b57&nbf4A(#vQ1t0^Fj1MDgk7 zqT*gEdc&M83bL;|Yy*^nX!=M5T#a=4hl586U6gr!x<5L$bI^2lOVrI5RG)Hy;Z40NU2j+sY_d_JyogQ zXsH)xnNL=!hf-NUNST{eSrEz88wEnUAs&=m^0HgFu+5l^)VhZJ0{ zEUqlMzgdzxTAs{VyWCd3YE>Hr!?cQi@G{{Z6Su zISs^q4?NxG{YZqS5mf@9OO&!+sZe2Q#|pWq7$B2DHHw)!oVhAP)q5M&ini{rq;Y@b z9s0beuUQq5U_OO5T-zzmAh^D6q`|K!%o6?Jx^w+sVnsbLTCZU8Y#0@Q$aXIspmHT> zSL5it_6t@Cq^C;5QrW=9nd$CqB)w%RDnkVf=gV`|6P-Ch`V6$_V2k}X$f`GFw$v+L z^qUA8UFE#*V)Px8#zxk!k2sP}IO=6W8Ab3u$^Hv+&5^xegLsw2col`W3yX~UEc;$x23dufspl+C(k32UIdu{ z>6Wjuw;Xe~8e(9@S8ujI*kIU_rwu7cwH#}({=@dbnjsODUH8SYUc9Y{tEteno$=sF zIl8G_x%El*o5(Sy=d&~-#vQf+9m&}p!%23F#3cCD_|&j3?c+&LpHp{aBr$cKB+XaZ zFNAi{iFd=fx+o4}rr@n>q4|tuZNc6td(_=q)F>K*Zpo?+GuLitT70Qjo3=>j-z2t1 z2UpO7-N9IQLMh(uxD#p;_5s&EliBuhn2p-9Miof>iMA=6K`tBGvQ0R&Itn9DNol zeH1-Zx7rz;5OnisB@G<4Zvog7ple6KdGU131h6`edSm||iLa^v>|p$_#D}1-`&Z&~ zO@iax7^bd=H-?!9SC4hxZ~qn6&TgB!q0rxxGe|i_i^EZGVrfYdA1^@XiPVD>TKIZH zZ(fBEkwKAIda`R2fA)E53L*e$9jf~GEGCfI)AtT66Dt-I$A;6tLK(=M2d0JF-~55^ z^Yb0bz>o3o9Eb?YLwGz(BsGq77;@uZhwlKi1yI3Jp!&&w9X^1PQktv{PD5r(Bk&ux zhns3nW&&?w5I1b@-EwFdANoo2NwBkz&34eNbpl!~B{aniiKHKppfF6 z`>Uv%Wc-jN62nKJEf9jc{mbwTN-GnLIms9(h(HFoz9hep$H$FXqB7Q6(p2Eqgk8;? z{o)+6NqVHpuvX3|BK#jXaMk!{}o$!sfyWad=si*JR@$-I~wNx*lwO&=vObklfRy1`qC#^X5SamIsx z_`S7%`90^Kpg{!9J22%BgftvMj{$&6FIweSMR#t%&30r_)}|9xO48~ zjlqFWkDOjjEJ%(+BcZ2gN@XPMClbbT0MfuMX?T$UM$!kwmw`zTX;8m`6{CXFv;U>? zu6ac)fC7{M(0i@un5>NjRZz{T4#Cf!a3gVXu5;|$%8mHo0rAB}sLa2k1?fr71C=+O zv`TPhDXfSZivA4%QO8p6!g)M#^!a!&X<)p9yShT!Qj(_JaQmq6l?kAx)yA*XudZB5 zAyDkjp~4udf8gWq4aXa#NFAs|U1Kk&0lZK&yF|FU;$=7nO?yy4*R>C>$f2#?9(Bv( z%`8qs9Gcc?Mz?yVLrY z!0b)dPn8SYo}aO9b@yO)+IWBJq53Ccarf_TKJOIs9v%@MW(p^_SQchHKfGcH{`?kV2u?h(yDyz*_A?x4jq_|TZ|u)ODu)T?8iH^)Cy50}0kJJB$dRK@${AJn{O ztE*+`iy#lFyB@Z;7r}R8{qTe?t$kSclu0d`f^TTXWG7`$?kVvw{po4w{WF@SjUfGqXc;`jU~&ZcF4?GP^k49gE;068tMR;Dq@)FZe3&w*kr$<%8U zO%ouQdRJTy+3yHxUX1)FO$@JKQ z7Xn#kKkk&?%2kcw{D?BHfCa8qkHTF)#aOqB9G7P_>4=}UA6+BA+x%e>kS{W?;8f66oy5|z=iNW`S(A^^ zef+NVt;c**)$iQhMww?3AKHwc(6;>ETjS1udHbY*L-x|fVs~8K`T5L7)En3Ch~E)2 z7Y1B$Q6s><-B=y}&t+?;t`qr42U2b_TDrG^*{xD_wpe_>=I{BKaXlTi4>BuaGu}nB zWDujL5hEH#Pwn*F8L7?TSbQMD`m({egP!BdR6XyTt7+u}tgn(Wj8AeTRdVlCGoZPq zGyx7LyiGU)hDLY4} zi%QizN|(A4clN6c8LDrX7(qN)61YY7$A0)0%P+TDs8g2Al99oc82ah_yRX z6DD1r`DFJZE<>K5^RP7HBA2z>t!bx80F?2A;#L&3i1~e$FEwe*PK=gs?UM49SlM-> z5G!mxDx&3?R`(H>w_8V~Y3eu@Fc_f|Q@G!3PbsqJ}06Rt~@)1m9d`X+%c)yd4 zQ7QIcQ%_el`1?!8e@wkN)sP=$WnCd#bwjG5TcG4M`kihHwXkjen-{m@T^E+MA$E@4 z;g=@(oHM*zbT(3+`043+wC%{}`c41&{cQta$B)xu(J!tMK>XK{bSg!BS;mBAMt1d~ zTX3)PqHleM=7L0sD45gQ>mh7RN6Io2OhJ8sS0kVhWszGNrlFi4P{UXyzp^`)zP2-0 z%au;1^o;x%ZQ(Hi)u7>JZWUBK=U;CKt4_4b&4gFud9VSo2(j1?R`DR?DSDH5eOI=* zIgEK+mVn`9u!h!3TdEv&ATH8giu6^(kC1R}97VSzI@pyHq#YSvZ>qRDqv3%}i7@O* zLPH*%@_y{&pvB+C=|2*B=`TT89AoGbgDP)>=7=0>B+3m-#3+Rg(FbX2A1x!}=?)C+8Vns1@3ROx zMw2-qiD2@!{?gna4g*wdarRfY(y?C3H{SYbhRK;U&`js?M}yMIu=zD-p=MGP_>KO- zcKnrxry3FZ@AAnlBf)YE`T=X>xs$RPvW|yu3g%`ClZu7?tY8L-$8QY2%ic8V_Y&=@ zo_QM5QKs?udF0XTcHyP(uk^%aO_HFDX-~EX7=SWvjNPKF{r>xPAPSk8#ZhCXw^&KsD zrbQ{|QR#!Cs%R)eSTFC>+lZSryqB`mhNIpz6sdTKr7MqGFi?#=``ucqGPXl3_mz?7-+vlS_hg@dhov2 zhbCIK*l(}RrrD~Jc@l67XW@SFM@g=GlLhB`v^BtTe}|nhR$9+{>nkS*xfnIn+m!SC zX1iTxchftsTLT0|Ci={_?OUR8&d* z_|D0rWA*ied$*NSrAZ6;%QoRlb*9G$pQzj_mbv3b9@^YYts(pVw^U*5PID^N)%H07 z-O~Y*^b%6g1Cjnb=Vrt^>N2Lh6mB=C`Ou3X5VAdG(R+%cZSZ}qEU<>z2)1>X`c=Te z1oP8>)a5jInEfs~aFF9w(&b1+x6WT( zzh!QpT0`I`5n*&kOXRA33~Fx&uB~!bXI^~CUNv{R&;Q%tYv;i4nxBN1F^3}vlI=HP5!|0J=ou#pN8z+QMA{L!M4V6+2T(}!O55R zWq(u4oMfv#NKm6VRN}`_|GcL1ZL8fzL-c_{T&Og~1AP9`qYN@E<7E>(`6Fb_mTDo_ z+e#R)j1jsJq@?0j`z1)aZ6t-b+;gU+{(9^>b8&ZFIc}P(fwB?Vo8EK2(p^rH_)uBQ z*ci`(I3H{bgEUMQ4*dr;Lx3?Pi4P#fa42p|$IFu>K3JTA3k(dQA)dT`&iz4s-kLHU zgXGK6Dg*ukvgFm~=Ffno`o=%#!m*n1LM$`JJ+6U-9?_L_}}LaJHsM~4n$ZHn-03H+^M2;wcgwOUvA~h*rUBA9s%VXBV+t^o7m55M*HVX8vR`o?bqM`@l zu8TrT)#H&Z6yyN<8tNJUNgNLe8=`# z0_%8R1fu7LO7F!l%?WUS8J^q%KtC{y*E5cbIzjsb;NsD3Ff@ zIR+l(MMC)YW1GQ%6$#<9z{n5B+KR%w@DNNq=1F`JW-=ch6pv|q7Hl^h+cB6nJgC|> z%y(bA)JZ)tsmI5#bM;TPf+2;-&tVJ<kU%eTuc+!VaglM0$AC0&|q>FnLq!DA5khg(-*l!8pm|DKr2;p(Q^G0d9bx&1a#QVR9$trow3K zn8B@9t6TA_M&^e4B`{Gb4UICbuA=18Jk(It0+c66aDW8xWs)OcQTM&#{sZvYNn@_z zVo{>;Mt&rK4`L!aoLJvkIciijZ?rc)mh{KyH4Kg7n&_4t#V1n*xMB1gvZK%{fhY=F zJuoIH@&TH{4;S-90+uPODO+vSQq8zI69wt4Bp)#Ny#1cjor=o~VU(#(95W8*jVTm)p{09TJ}2%$aq+#RE6)$_{dh-A1oBGtF!=#FXWSEc>YyuB4MusW56|_9?Ap^z29*Xuhv?en@eC_$Yg%WTAItevF5E z>>ao2MyfQnVEp6#L59UC$=qp{oEpiG{;!(6xbOew7ZB7Cz?^(WlLLGRi!{l(9>%-G zukMM|UIMni<`ogeb&D=*5o0zGWOOuE-^*ZIFinaR#{C zJ;sC?1qF%-)Zxd=+jsBnJeZ}-qtx1nb4De7V?uowAiN+kd9$%$C*(+Auv@`)ra;8e z>kf+u7p(T3x!eZ|9!gF)gXtuJ_Upr!op-a#A)&Jr{(3QlZ7EiBh61x?2F4ZQk<#q; z-4!;QSAarHL{Kc(pe-HmLweN&)|O}wY}|b>j0OQp+)fgZPpK4N5msGcGk7F#zWQh2 zTfTJkE*=w;vm(Arc=>=5c|smG4AtMCjhY070kxX3*cJ>lSaOx0@$q8G3h4cksX!@{ zmxbvG*_7+|1A&L>K@?Unu=!Fa!V%eq99j*&aX9(49pY470fZH$Z!~qx_pY| zmZYb-pnCvLD{rmT%+dUqQf!b`8B1wp^O&dWdz#leCI}Rg=@_nqC2F+@hc&Z%t$lr* zin=rig9NQO;=zK_WlwaRl#k;{2wylJl3oij*oY|y(}c*|brQ@I9axj(ZS-x{cOJk5 z(x56N!wvSsDz-KH80HO+3m2s*VvX~J#YPF+#p}RrOMhg=Zpw_cu{(UcC%leDk`X&G zT%zsTv7=(0@wTFoza-a`UsZbKZQiWh)KPYL{Ar`w$RWuKO)XEZ!j4&zbIO4_1?YTj za9(UKbxF6x@JqqSk*E^U(dr5>q43HEUCf{oHwUYBpj@eIhRC_T{hU&>6K6tM8#PZ5|k zE+%}E9Qu~r3Lm{@lsFjcR{h?orWrPIl&XwgyI^&J|K3XlVs9$IZk~{@IPh)yE<%PF zdru(0VyLKJTKr`_Al)L5n2nZc0sD0w3=i6=@lXZ;QJ51@fU)!mvjL>;0Uq_#ou)Q<55b695?X zD0~Yj6g}P9Qr*25eA%0QNFty!B1)wNjNSF@=5@x)C)i?RFq!0A7vJH}*b{?)iSsA> z!~Vndp^+Q08?`>k9(J_4Yl(0tt(HjTlOJDo{PskApBjThq+@TNKpqvu4W#=0{&5vj zbLf^E*E~c1Fcu^?@$1IJ6;-u>bQ~cu@9?PkEJu_qIT-GZ$Y*Y*7?; zh3@+AOU1jFL)e2T-dL&6n5a*oIrNTSWGMrXff!@35ML<223}q(Y)c?iAtucJ={cH< zoMsRW4hq113VGk{M5HyPyibUgCFy;7821+PUdMcpg0%ka@a_i}_Z|g051qw)_tLx? zr92D!i! zB%FT=jXuA8uQr)|naR+6uevkj@ivcm2IYUwS;4uNoR6zIQD%pRLt$0x8i5)r#(0tu-gr@y&SgV+cX6VVpZH$I^OQPpPjLD z!&bzpxGVjN=U)}A1d1s|jSbOUk9_=t+t;nTw=e3lxVX0hNz%6bf-MEb`**tEBFk^x z;|byS|4eWdl?C5ofLjIe$2zE=M6@rr3Z>Ik24WF|xV}`GC@&U^)P%RH(LNOSS7f(=T<%wj}@Dk zUYC-14P3Kw6H`zaMot&-NkitY?3HU?4O>z z64ry!1hsA7k?u1LruKNJxHbN)@7}IXLtQSk2T3WiarbYryH^=h)>dG(XDb#TL0ezQ1y{;rt%s_UP%2FU-qt!lK@~ zp8fDE8xv)mIeav%?v!ea|5o1Z8oDDw1Z%-M4RCPMSzr_RlXd7;k_g$$qCMp!niew** z-Scbxd$I18rJxgt)rc<&nHT5yZ62r!z+5>*6o!5Jv2BpoR|Hj-a`ytBr3$h~2hr5` z%N={C=(hm!r@!(wpT+gEB#y}*iw>&?q3FSP;D!`h1!VMgu;9l_h~s(9$nkrcJO@=? z&{I-BwXpx+eyWom{T)zh7(^3YrpQmt(%UWJb6{M$1QmfVC%8{a$2nA^$diidF~jjX zTWw1XtWFGqWCXBAOA)*_jhf#~h<0w4Vy?}JfrW}>xLv)4I0Vt$4kBYe1++M(oHP~X zt3>HGCZ5>6ES0;ppPX*US0TEr9#_oIx`B<8B6HS@bMt;tOLQ|1e2*n*eu8Wch{ZbN zX9f@KuH5O&VfK=pdg_Q5HO=1qz$G>!ycqM7zsO9Fxy(YF-thh1x-b}jUB#_)6AwxF zpW;giFkO~`B)%Kbh=%7MZ{AEye%iGx5KUI^yW+9NO}oFwi4h8Ley2O><-A$X9?%KDepmdFc1v3u zEl>deiqhjY2gR4Fvam~?xKfr|DOIORlzLs=F4CKN>Wl#KXDvVf;9zAD*o@0op?!YM zh4ATJ#(?Z$fhZ6pO%D)IjdV*@>K;?n^=5K8m;7sN@ko(bexayMZf>{VG3{A@#cEt) zNc(u=3&ojGZbe0ycoztLEoX(loE%ST0;hV8N0CPfyPEco8uXt%YZvdaP=jYp#^_|= zw7%46-I{KmJ^6%{^@7UgNH3f=_uuwyiIaCB)%#~3(E(UUzR{K$hQ^Lg^F;G{?LmLE zUO_(cWQaxy8Am5w@ZU{6)(q*G8~>VmL461*nMBj=C8nwt(jKX^+H-~|YFB)TRF_Pg zW%3G7lEsk9-}>0_`^y}~fkJuU+>J`bZ-QyP?uX%5Z?<8;=KE1>)tNooc}XO~Z-tf$ zq-{n7Q7U0u#~oC!WzAHt$-QZP=Mh1AixTUKGp+9fx_)JYB5BxYm&g54oQQpi4Rxlr z$yn9HTz->PtO9+AFP8Uc^zmGC9!jGo@@i?W+3hqZ4*pGSv-oT94mx#%yR!9#e3sm8sxzf=BSlxM`6&?^uyXykvFnnrBII@2 z-o)N#*Yt_8z-TME!-?$Mece7TlInF?Us|_uhDIhvO8(+=zwTrRUFmp7!$yK7OOUMJ z3Un3iWuhg>Bty3&;~SRQ;I4~#PUx&~WZTw~x15sQ>p1(M!z2p`@ioNk`zK~h{0 zn#TSlPIwprrf(6Ty%q$P#~-wN(g!ST%ah`Rq)CSa8DPW!kL>61@W)IGp_m0ZSbUnQ zK}cA8CWh`SkopRQ2XEtI=%Yy0?VNbf=aZNo+SkzV`(&_6JOv-u^!{BDGR|StkN%nW zimnci{61d=EAdXpN`LDm>oKNK9W+S_R*EjJTRgR=1=|?elZ%D=7QLsaJW-Si5lpym zFUVJc?Gq+?L_jI~Z!qH)DruMaq#;OgpQZR}Fu|Lm9x5rS>ipIPSax|59#XAHFY!>E z;y^y}8`Hx(FU!aWhrIB%8Fnw`F2WB696RbY1q`g_8H0L5OVtGm=`dj^o&q$Q+-{2Y z9hgA74C~pTzmuxZEyOZ!d{G+nh1FgKIIg28cv*Kh-UH_M8~vp90Vn*$W9FGPWc|HU z?tEa=Mth%CzvK2fl8+kOcbPjH9^IE4grQ-FP(KGZ$KyzivXgNUB!~!ixAmc3Vk@5m#Encak5P%bcA_Sp_Y)nyPdf z)5kO!nC3YzMY1n_M#D`{CF`WMgV8a6~F|6sB;=K zNjbl~vw+Z=TmE01-Dg;n;hO0CKmsHLNC4?AfGEB9n$W9s1O#bPRHXNsK&T?UcaSb1 zO`0emNU>3*ND(R0J0eXWC$5=Ud(GMV%*;OdnlDMN%jvFbD_rn1Mtbv5`V3ci6 zA&OpQEAIQ2CoO%54z7_S{aJz5C!Fo#BtmzRh%H&`GY<&#NwW#;pzw})@@A2GKaDb& z(0V3A84kPQ7D;iL0hJ$vee2@~px{3vr^AW9*&eL&+GRRz;#NKEoHWl?g#~ZvogPy;APf7` zO=mKA7+UH~Jv`U$m;U7Mbn-i2bAPv{E!}f%$E8e<9t^<KkGAYd16ZOezpi?K(wmApIT5&rA0x1i|IXUyS%a-_E3?W zH0$*{j<>n%ZkxBPhZEioAmvsDA)o5@$q0bzJ>$b4sYc3jqm{XX)NZSTBHr6E16<~t z6mqc0NZJkOdxw=on7O;rP7b*sj$@S^an-@HuaWlsPv5yT%ra=vxkixV4iIwGQ?OmH8g@4b240{xs#ygby3o-2R;~@MjL9eDwnIn zm%AHj8Q*6h?*jz;ZkWe&=ks)wJtRo2g5RlOsR2>Z4|1okDi_b;dB20rYV6TN(ce~D zRS0M&f{cnc^wmPvR=@2=~Cn)IVOr+AG@{!@ z*d15|?=#Y!9_^h*UcNQ}KOGODxGO((ttwBI{%zr!?x~ut<-#(vn!854+K8S2^*$#_ z5McRZU(L29VZ|L@$Uu{UhAY2EovNVl7$CViC$W|;qt*bv=~7dRs8FR4q-~Y#C-|fZ z=fL(F3A~q7owTfbpSshkY;n(Zr??CRs?rBi?Y?K+)hytr6cqT7sCsKir(XhViZ*4t z|D<Opcuq(r*!7z$@J9H?3d>$Myee%e4iF{7RFs|3pZL7 zoYH>cTxp{Q2PFGOQ$Y%sDuT>=Gq>u=Y6Rv4-9F@k=s(Rb%BoI;k+p9LR9UvHxZj z>^yVd>Zbcu&7MsrsKZEg=g#g=!I!@)_E#6&Pu5;~y#Fvzs2uhP3-Vd!2OS(z9GutJ z6XdyQ!EfJv^?be}?rXo$Ui^#8FG8yeJM4xHvPVL+399^6u;hS)?r~vlxW{K@;a`b3 z5JAh%M_JINnd@&$UFhqEy_1GbWeb9U{((dd%@Fj(5Fu>89##Z`!y3m+UurVDM98W# zi5%<*icna;1PR5RIE_ua?NBu zg>(HH?=a&^6L38JXdFI)0t%@eA>@MLQfP#b!vXrxM|?@ImDizBk}O0bDlC1)UF zcijvtbEzWtpn*%@gSWY#PO0Hm+JQP*p{^*%OH`w&#*_KI@JXi#=j#jzNKm}1UM&E9 zF+a|4BMNpFy}kWNP)e0JWMtn0WKS!~!*;|7Z6u=`5qUkC;^X$m`Y-TDqlWW#&+xW6 zY815b9={LbEo@N3HsvKYu}A(API6&d;g|n)gZ#k#zzB-~G|1^RTg{7dK%2*0`fCr1 z33UWAlv{Kuy^$jx0xArr6(xT}`x&bAAp$LW95U4_Wd{7zub;&`uV|Ug;qkR?M188s^$^Dr~y`> z3ig9Y;(FOf8~$5K$=Cc|KScPEP#)ip;znwRW4nwaX@?;uC>7&TZHPoalY!{nqL#b3 z2JJSVt!oLDd9g;T{>Fq}LhP2V^YPK!-%50UpXrs+s}z>csntxM7od+OI3}$we!2{;58NYh$q}nrT=5RC5WVW zweXhTy~pCb-nSNyT-|P|!mE;)Mo;7(`^kIx5dcrv_&}8O8aJgtm9qTyPbKu2eDBow zIc?usC;hOVxT}Or^`1Tv|KZo!|7mqa~4YMwLi zxfAG$WQhM={4ImHc(2-J6a9q0f03j~QiHN^Ym~Gf`>xQ)yE}xjxX6oRbezzcfmA!s zO1ll4Ds}r8lyN^BF=g=m0LGWn!U~>a%BN`-9*nd-_-{D#jgFLH>eOvXUw2Vu6VkK% z-+zpVMJ?JhM#=*maFvVlVqCf zaHB=?y75Pxb` z3n2U4IjERPb^ACn^*$C2DlYwcQG42!IQOAi>WK4hB+cs!z2|57#xJYZIa;iGPO&3u zmy*kq_Ra2e)$Ydu+s;rE;D~G=mQ#+OT<)=9bE<#qhgQwI7C0<`pXBgOg~y z&R(TOAjY|^{rTWG9vWkE^W-u@+0jU0v>CFqEx5bwF$NQ#*%&HS-E1S*RoU7Kl&*!* zu~a3==KpFd`}MZ_LKDvo6I^n&16i0cLa~uctReAym!&W%<$UzZEjbnbssj7quI95Y zA?!_8pnOlHgl_r!Z724s5xD>)3U@Z>FJ1e53Q(+4_6)7yiulML^6_=oGEJvRh`Sm; zdhpnxfBiDUIauWriWv{^)e?eXv<>q@28Tk-$*;U2$*y?cTm(&N*f~AtL{r!10V= zpRW6mP3h=1E{|vS>Q)b89ykYkqjkNn1nx^BhG?m`ZoLfq3d`Q^dn-7ks2pnvPR?C( z2#YFEx)4KOJnv4_Lx!glg3_}|i&yJkg|DuJUmIUvKoxOm^vF+VBsW!25CHrZGnIbP zYiS6(db)Iqz1mYcq3AO@LI;f`Hhe%(CiSMKDel@jcZkGN$3<8B-%UL!&$aaGl$B56 z;qbLHjazn&=CuDYLzT>t4Yd@*ZJE^QQ9EtX?e=Q`9rhAL4q9qVa~wYpsODw|5`L;Q;MPxxT=7yJ>W??KaEN9%pCL(v@_c{~b15;} z(x#8{lswn9dNcsK)%b}@hYKg#IN1FbLigO~Z$$ikS29{i9hE~cI81um0Nq()<(g~9#QN0)DQr01B z+DT^LRuY-StzRiTtYpbFf5g@FbvhRP-A@*}oU2lH(<*{k&wWhqZkgLxD!)#LUwwYv z>L$PyPST@xm4x$z4BTCf$4kejKT=xsvaEge_!fu5Kk=Y%8d=FY0J&jC}PA_-*`XsH)Xe&}`B`iQhiaMM9^0xP7~D#hAHI|IL9&#@H!$<9DuK?xNY`RfluyLM${rPKS3fy}zC!_}&X|QpT@UhG7>XjAfgH z@QeH?v#n=iiDtWlTV=Dh=I_JEBCM8;B5$o(@~&duQii9y=6_mi+zZ=x;zt`_7!pU& zJ6}fpXo)eCI2t&L?sa}kP2vg)G9Yxu=CT@8Fu3>$TA%RKbypu6E3rw-s$Aq$z+XYk zy%Qu&_vQmSy-#t5?%7&J3Iejrsh~=-zZ;d;8@n6)^4z*51AC+gHnA=j7Ff$^b!-01 z{3&PLp;09*%hGQ1spd0(gRS>O1vO}O29hnhp3TvuTi>DIh*^`7M1si}a-T&YJAE&a z8=3-~zDOjJjUvu0Wg9FmCgLQ3G`u!RQ3hu_YI7^XS_nPZqHQcF8 ziKo!)!cZnwqsq5>{dEdjV7KSHv^I>mKPK0*3w|>wG1WyA^(QD(#s}m{FU6(F4*X0k z9_A7|%+a@3H!iyBzfE6Z_}2PJEZeR@pRUkDk1FU0TW}2K4wV=Ij1zLH&qC>E?Jt_c$9UPc3J$zv-m*@D`j zjK8fOACN;(ViXc)t9HVrLP z^BK#Z4bK%)>|v0ZflSl3Pt0mcg{Y_x+Ra%L^FX?QnVHty(YghdrAu8V9Yh0=>wrGO z!KG(x`blYlc>b+iI;QRK3Eo`v|jux+Ni-eDjI%Yrum$^(0`nXid z^z};@-epl}j0`bBy-EMH_ShE{1fYxjPHX^M?zf{gvo`{I?op9i9mf4W?Qd$U--cM& z6kexyaJ4>>M&+X2im@!;3CPuH4Bt3;q!Uy431j7q^oO$P`YyUWl7b;-kI+k5dR;k-ziMkc&Xw0JQYdZ6s?*f(cTP0e!4< z0pKUk@2NohIRw4v`5!dReVJ}Frd)V+=<1n3$)XfJh;&*@BL9pXCQK{N4*l$;()E)v z+^prMVx!F{0v}XY`;S?oHKPBYvqWhk>KcPc3f@MTCjk;ie$ftsn_yt~mum6+Y@Qq@SU9p~cTZ#x`irjl=m6?af=w+F`DT z0Ov7U7twfWPxB{TD>7CvECv1;RLSuraYJ~S5WL}nsn%b0A=^P^F@Pt$X$#BJp$LAU-)Ie~WkMx6CoRe#*`f8@xdT zI9nuBzLi1|hmKHz`WH$Nx*_a^6lUanFEmQR{9IIGw#>s{_TTLso zn56L2G29EQg z3jG=mcMisSktY2=%-dTCirNay5Dp6=6@_+0Ywaj+AM5I06$<<=Tn1uoiK7-7z3is# zU()Bo*m((9+SLh`**_2PvvRX@90;%{V1A@x30_tJtk?xF%9Jgi9#XL<3JMpB3g4@L zDJ^U8r)Ib7#%JT$xVcmq7h)PUKZP-Q!{o7 zYXlKonf$1iDhzPL=h?K`5Xl4q*D}FAZ$G41h!Va>y2JzJvhq{ot@m`+3h_R{Qy$+!%H(bP089@ z?Zfe!Xb9geqGbZEd3KVfvR7mT(9BhaMgtZGXK2)O#us~xOdr)UF%WDVv|$5=9KBR` zXV!7QGB+5V)vr1*v~D8iQe66y2_lmJz{)Pf(V@ZS8Oe703)>rQ=&TbZc5?_1&bR9y z%fBF^GwLqnV~G@TokDkBm(bg4a{3-cJBgahkBcLzmQ}r8NP{aPv>-jo&C)41R^Bte z)+D#~A}@Jy+i?J>yUFI|b^8^Sc&P|`1*LF=*KBlCd5`U{h~cpvKu4w#^GE}`9ToX2 zIPsqsKJgS>4NLU6Hc=s#=X@D4U8T?7$qQea8NCsA&85(;ph)G)ddmD2E+}-!z8=qM z%|!%~5?Iml89z`A}@WDFUH_X1rv9`Ot%2n!7$gxJBSP{I0 zt&9K~0^zX%5&=yV?zZr-Q2X5f8d^&Ieqxnod6|ZoOy@BDR!fVP5K52q-hxlJ=Qw` zm>NrH;c{vXKT`6tP#JNinY}85|6F2I#N2(AQ4^AJ6Fpg`NP~>a$ZlC?C`4zaqRBY# zn5I2en3=F(qQ1XkbSKmi;DPdJm9PoUu*6gt%LrRVd0Rydn+L|_s*2=HrJ4>e>vhN3 zG0~dQN!}?jvEh;QJeja-B(((^+eQvkkN9Sh(Mn8bSls@s#xQC6#z@jSN|LYDQE$bb zUGg^e)jR2vEO0BB%uI$-((taYA{=o^7r%AV z+IG>3zo$)UHS{3KdZ4uT$i~EnZu&9HsSgp6S4S_*0`2v~@0Q@*HqmL9vL#aaQ}0P} z&mtPnj2r6vw7!^WeS{R#zzZ)O4nOu6?olmll1qM`S=qGW_JM5{tG`9ceI;K@1iZ?U zI-lf3qFBG6n7w)_sh8JD3BlKP#Ik4#Sv0}?Y3Pzv*s6cnW?R_qX{ZL8;)5;ZtS$WN zG@L*hO%#BJdVA~XCMcV^X7}dsN3`ROODj+tl zJ@(mIY>ISTMnGH+-qbsb!66>#_9|X3#?_t0H%dQ!74Wp9{VBdB(0dlkj&fv^igrFr z@NNlKi2yASP{r?ue9ek74M^OT3O|*Kz?*t>0TI8=F@esE2ez`EMO}7_SG;z@_`+3%r%C-lMW=Hqi6D9+4W@L06%;~-? zv3^3)`SkeK1#bDwKqD=3I?%zt4P^y1VsX+~Z+utd%BcB0?A2AMp}jq>r|6bC*0V!0lJ=N@uF*>N(r z>;lU?Wp8U=2z$MIpQw6h~-i_9DZ@(sDba&)Cc2$3a136wyqbFaKP;><})k^DOm; zRPCyeNp8CrApM@^Rwyu5v&jvzQc>3vuuhcFg&=&-XPdGZnokXz|D-g(lzsRPQ9~#P z_t;^%9OjE`QwRfdv(DYjPRw{`lxViXoN92KSHiE?uV<^CF}(b2QCn0erM#$k8_(a_ zO&7mznvtvg&Lj<-)6wdvOIw4EQj=YGh-=Ap>&f*=$ah&pso>V^IY<}j5>Ty_^1T{C zy;se>s0`F!@0&`rlyi#&n<|0h~zn(?3l+bP*ZdLPif!FnY@25Vd#I) zCb0#~OHq7I+qG?3{hsON*d5wW1SHH{Ls9dNaa|hER?)BLjk`k}I$-ZIF1gv_8jGwxKc64a&-=jUMLUlnzf3-D zQT@1|Z~yDk<}@UWD-p_?{V5VsTe{>xQZQigwSH!P)R@)?y3fXpdb2A(9_c?WM)~&r zQDgtSh1;XyP>5ozk84R+_tUx0YN7Xsb0^E^CaWo@P`|Qq;9&K4g!z#V#m_My--6M= z&=2=IMos?=Zg=%Zg?8S(O7ooYdd4EZSq$xY*YFzf8N)Mx^O;VY?G6r|7?jOvD|i#f z!r%91Q24vz&LXruF}uF_iL|@L9b?c$+?_&GbZ=9~0pIB!v2YoMp z^Bwy3^Abyrd(e`=>!mlpmhgKnc30jX@<62T&I=VT{!nP5R9G^#o>RC^Kq;E5y=`nS zp8t&?BNHtOsPr>sov@hrUj2Qs-0)>{=-TF+xfcu%!+qYKT0^2!y}Ya!@4g*~TbPz$ z{kCeo`LT1Y_tkiC?fWNNBVWC9xI-ioueMY|w_(?-Dzn=-PsW|TlQrY`pIO#<8Jlg1 z>{Byg8)AhM(^kNg`%A0WO*yOu<(4E6#eekUx_r%ecX?_wtf*h`}8`4^5THf zW-WZu#>RTb7rJ#`Fm_8;_c;nNeSK7Cc2K9V4Pje@&HwtGyZ3u)?=WtME6gG*ZfoVw zzQ~UaDfttbx4)kJsP_E9%ZTH@3L(o5eK@^cRHCpEHFqY(b|S%6u%dWA6L?-(dJZ*N z55D&(D{lYgy)zq|6YICLx9=6a>8|c&%kl}&UJHi3wOuX`x22hT6Y=BsKTSQ&WC9jq zFq3Qun6gAUnv&15OZu>M;29O27xoZFJeYzv^;pRcg|Nf_Vd{O#5q~_}71xZ=&XA#u zz@{{=50LxR-jInGuO2Vg&Eq|{U;n})VwEdtt?V2(Sr&7l=FlWjYyQIgReWgaDrOXe znzqCX2^{n7@O86GEvfx4T_JxiuAtHli@h|bM^_K;3L8FmU=q?B=SrH8w`S%PkUKHy zHq4ZBe;*?GWWFDxm35*i&Hm_Ffbm!H9a+4o*YbFdmNZXrd9s==*zc2Lf{B7%>Lu|T z8nW&%+b}u(_z*tJS8jT^S78PIk9HJQ7Tj|Fygobp`7w`x&>s;;2YFo;YMY=@<~gO`Yu>u%=-UvZVI(i`fT zW`tWrz3&&h;%_SP#);6_`T|Ka5!NE4Lknt9qi@Mk(tAS=Ns1@s4tMAWD(vD@^vq_W z`Mg$X%z1)Z%Zvo-B{(yL-UX~al(6(!Ng^cLbi|u_S`})x3*rxg)f9%KLj2**R`G_c zRmztv^31d=$uyU4w5ti}IT|JDy#^&P_j(cl`) zZs$|iCMKC}&X$RVr|xfsW}wuq@u*pgyuPTC{th+Ohnh;`s&)tFo3xFBcRntNi@e|G z2xyGJCJw)R%NkDBq{8z0r@QTJG#5{KreugmyUyfrlQ~So)w8RLH?J{42Bx}SIu%Xk zGpej2?xn*8^z$;-!j|yGinLu;8=1R)82nn);Y#ya($tE2+IoMd^fUSIPYz=$Mb9Kl zonHDJ+h_^BuWK_Cg7Al%rA0}gOQQtxrp3<{jGLL(eTJ190m%{kKSqrc`8mn3(ZYKz z)MN}m7P|z6H7jKU!~*VHvmP_7uE1}zBJ0Zg{*ynyC5;Gw*pc-5s|W~otbO@1@hKR} z$h0VW&YHH!@f#a0J*>;kzaOnWlZcQ0nRHr=*gA_|HN;k#Pq>%LE=>CG;_T znuxs;03aV@pmH`y0YKpQup<$*2hm8M!>1T?{4S3b$e%m0%4X$4f(I))uG)9*YnR5`jxy zKF5c^HModVNpVl;RSDU-IW={&--*|VDDQDbetPh9&Kbjl zNmSXcJz|M@N_B`EpOM~d!~pTL6El(jn4OS;sK}^DZ{mx}gn$E)Sd1xwU>98G>+6e=eKAkowK2&QNk%Za^&(e}}z4EZ0%Mp=_Mu@F) zWw_4R>@>Jq3{5; zhQT&sxA?2I2>QM_bQ%}C9g>rkbEt&wdB=ookVrHjzFH-|FA5KK{tVvA1upyqDs$K1 z_u)SMg=(f}L1=P~iU2U&2v%$lLXNwM6h;WZ0!5;4@%em7i}$US)T%~ui%p=-Z4Xp$N4E`a|8DuAwJrJmS=xA?-nqQ$rRjJ8Y3b!WT80BIDWAh#be(c(M z18zx9VRtIkRRcMVReMf)P=Q%XB-@Ur+3E?zJj56&42_9$> zTTy{GR$##1C?WgT;}f7B;-DTNE4NA%+2epd=Dmg(C9-As<8P#xhKT4k#IrDF<+k3{ zIgdEVN(6;|PmOrPGxz*)x=R&upl6iCki`HTu*4>|0br5sLEq#H9M*MfN-H9B%Q- zIxuS^E`8#nx)S_DZ%V2gSMVSlnE!*YySdbv|5h_q@RADW%RmAH^k-B+t3XM>`#;-1 z=;@>y!b2JpK9+ezKV^PU{Yrx!jeI(Nhj|6#5cp9>P&3K>vOA1)$Mg1$qm*rC8`4UU z%wFSEYZKktC0EcG?qMR=bNA1y-3~zq2~gJwNbtIezTFp737=;pR@(r-3myJ1R1Gh0 z_CVZyCP&;lU#Rrg31*&8eZTKr_Hlb9N>pxkf5GGR9CkM%G}z$HwQrA&)uztvkb%uR z4qbfrLm!2Mf5=_?_nn#?39Sds3v{1U?N=Q>-M?J>y--!#cXjk!Uv_Ps_1rIl`MA(M zv_-nx>w}W@NpqH5F^J7?e!cL77%Tg(4-`BN{UP6L-2LhKSWOBY7^jb-$d6VYfz$&I1b#L&24=wdMpRT!or z49fnI!fEK2HZ(XpM5rq0fe}Dhm=Hi8uGAZ; z6dSGx#;Qn%D{EpkzJ;mBVs)~^w1=?!QiQ^2Lr_4-jB}KDd#I=;vQx_Mt-sL}9i8n4 zt$i$0tv~AnbEYIZ@4GIMma!tj?ZJ!FXd9R4{<|@&m}r@ln4o}|2c^-WTrme!v4QM< zw+v&sP=1>&G185(Qe&|ahq1}uVjPZQG}fctrDK7EHuVle=tlo6&Ghy3jGegflw?F$1P8>LUwxpTZE1mcymKf)u)i#v4 zD^0&y6>-R&^h-18w@cD#Y|?pE(jWRHm&HUJI61Hczrz-&LJV4sP400?h72b|hm*mZ z$uO-%N}iPOnkh8H&*N(Iy)D30M2g>X~AC}Eoi#V-Jvyf6;l z0;j-3aQOBaQSV=G?xryO3ErE7QzVYkY2>8q%%tlxWEfjy+|9|jCj(Dx_{+^Td&uN) zdIn-LwTIIQdozu+G6?N5%&Rk!Ic3rvWG2hAw$$iCt25D%j0g+-DN8aO+7*BRb_>I{ z7D?G50DG-Wr(wF}^Q=2EIc{3;%(xsv6mh35#qlUPI~TmvBJ&Y-dR0bVr%XDsDNn>O z9RSaNcb+FKk}n?t*+!7yuigg-YQVq2QDQ|T^yeZ0Av@%;FwkicA0jmXjzPN*G6*ri zql15la{!W%l>Cn~`6CPkUo8rz<50811q(cX#W`#-P(v6;VpFOxzoHO0R`_W%9{?yA z*D9EbD>#`cfYB&?HCCAB%qN&t$XBByx+nxQ7D2U(&Up%lG68c4vIlUIEr1rl;2$2J zR`G|2#Rt{Jzwqw|UP^cfZtNkJF#!KULVi9h+^8;$v5#*wEK{$E*VK;J=4H~@V!V^f zXi#&f+ZKv9@;d&(&7nN*Z^0qNo*-N?5XcUBe?Ytf0o3)7<2|~b9y*gp<>vTkD5>Xt zeB+c9z$FZGw}msbpa7$&K!Qp_&vJ{-a_ft7BFYK}SyZ1fitcA6bD61+NEN`K$~(Ra zh$3EFB&>q~JR4vQQKJA*B%JgL@vp=2YqU=9+|< zn#JxlOXW4oJ;v4I$+-mp$wLI$LIdi1i&jB;3;%YLDqpks<7OPX886Pser(43R2eOa zR#3o?bUJOORz00o11O-y07|%2{mP>i@&{Hb)&jI^(PX0Y`Pc#wZqitT74mwU08 z1{0KRR|{_8dD@Zlm^IRtB2pL>)kA^gL(L=`^c+AtWeMdQh~J{gF)53jol=DIpRzJ3b@cmpVoXWGK&2ry7UhR*BgZQ4(HuSewGjz508!PKE# zOi_sc{qNmt&xQ67=rXMxJSSX&q*+?<0{~O#ETR&_l5}!%yf~L^P>pPo4r=s4^#DD4 zKq7>spL&Q7djJPurZfthi5dEPtHgbRgYYOh7_2-8N zTEU%nN4 zg|ej?KoV}!GLnMPr_6M+yQ83u|!Q9mVE?#XY>dF!j387%Gxh0Evt+$>sqm zro^&#)e^`;-?IotA&I+tit7#K2h$k;R%8DWjV0!zXACMvQ+sVK^CzHe2Ay#itn(&p+Ae$UmR3s*ixJ!DQXTXg%1AGb8E@ak5=$;#>^Sv z+)&g^CJRNj06h2eOrZe0SYWp7$?Us_(A^%2E@6kMS6Mz|vsnc*dEaM>SZ1GF&jJsv z#w4r*1FdVVXZl&@2K46i3v%*ia$W**pA^rw4b$~q&AwNd>(PZ5K6+RsPEq}4w$Tf+ z45wf9y}!xD#D4&LyvPV?!6Cme)7RRPwHQ`M$-)v8`C0n9= zOPYE`H#lVrqh*pifUT!7YP4up|3{4WrR66e-%DVkE8d-ZdcFi@?I1kFlb(5$ZY!@l zf%~@0Ates-x8RDjOhgAzTmfTjndTR9`V)Nq)|NOG2`iPOkCl5Ju~hx&0Jhs@+5lZ4 zHYE6lE|;QM;}|Br!JP#-AY3|V4B27EJsZ+Pg?L3Y|5WjJvZfeonYp4E@3I14ieW2%!fepzFe4 zuqYGtC=+Hu`VNov29NcK-VcsD>)=O=HmQqff~JNqgj+tH-u5|4hUhm|{yNZe7u_B8eXyz%r4s|5h3xNA(vyNUnZYJmsowws9i{)I6;v0 z&eHKDX}1--P<|t(PWmPDw_y59VgHvB>=-3 z^xIhfx2gN@yGg$-UjDu}@>@@T!y0yCCv;K{Y6LD3>d2lve0gF8BX#UPafhAC+W@kY z(`VsepxxUOVX`Q61*V7mRG5O~KAa{=+i4~@{uX!u37Z}Tx_FQu0?3+KA>VCb3&If3 zr1Kn`w8Bwx>s|0k4>4~%tbP%gFIVW?04p2?CXNn*>#fkDFU=eMyHjb!%!Z0fD*WQ#a{DYN*xrk79s z_0plaZ=Hf35Hu4cz0L*!d{a~?ixfhs8q6TB{{U?Vlth7Z%q$y2ENEIB_-Y=*x&E)F z-s+d~d((U0Gud`%QimSRshC=M69sR?=c($3vl+dLH|4tvxKC2}3p;(}_$f!ieQkc` zm-A?eTBX&i`eX{RjI-sQ>6#dXH%=WO+&p5Or2LCn>*kFlGAINhCns< zZuMZYMy9%c<^As$z5zQke@(s6WwiFfK{c?|X_49EBwFj@uAMEy?QBRZi`(w*>+shx za*`AlM@Z$Sj+g>_z~LSeL~Y`MB4+YA=pB_8A;Ft^EeFbEViO)J6f(J>XUwFY&KVRs z;)kj?j7>b%XsshwnS*-{RWY=WTMpHky^r}3|2G&No}&BD7~T2#`Ptdo^~uTA$;tmw zqPzO_>wlBzR{tTUfIo{|ciM{jV^(URt4u*7LUigwZ)U^=JQg7@gQBZkIFOf5qsW z{u_)ghdg!!2ABO8jLv&NNlg64*nfr5)k2mKp~C;f=f=6~Z~jucoG{uyi8+9QC!SD! zzJ-?D6<1g1+%0;$(BUek4}gZGO-kjxUYNF}4sc8Trl$9udQ6zQ_p58$Zt{$A^CyWZ z(G~Giq+(IJlxA=+Zldi6lCxH9Y@%1dnxIDkB}CR%i<&n zC*OTkO#>eIYdrTh=~S>4b~W* z2*M#*Y(Hg`ODYRfe$k`cQ;xsBd}~x)e=p|sBMH@Cx{%hG{o@nC%`gewH+&XS>H}ge zm#EM8_8Ufh#`SA1c?@kRPtKM#!X8z{5_9%zAeF9?xYnL(34kKO9|-`I`>}me8zoQ* zW_#v6v|2A~PrUahAcLArEY~0e@vgb(q@r$n=uykk`m9zyJt#Ij)tS-GuP$&L*1`8PW%mJOs}2;~iu8)eb= zsq;AKI{F%azjRfuy#pzve8z}4OqDb$)y@t;D+C;+6_b^7Yite!xo?I7s`5WDwgb__ z_N*-MA)yBZXa=M+q8A>8O0c8CAUKnXIQx{G43bY7Kq;~hl3|gVL+aXCkFR585ARTt zYuFy;GNsogHY!D5NJORfqF2-s!vcc50J<5omSX&*N zPIuo%S6LcJax*D z@oSH^#V$(H%jEHlp^Yf?!6=$Y#ez$RV8ASLL75pd)XN}9Kq526NvSvrVug~T#c;M9 zybk>_*tX!e;RD3=gfn>Z|?6)ua(CKKOAz}ahFfdcbw7I9Xqrt0_euKz+ZhFr~pYp=e52DYI8|sRREe z$W@l`MPdh2j*3zZYO;nli+#je&*!%hz>#~elm5JFSrtiPX7 zL`_N46MjRetn~V$pf3mIGyMl=1K~3b>aq!G_{mcHmk^JRNA?kqk0YT1k_Q+TCWmV4 z%HR<&L1JYs9g8z|Q0mZA4_*7oi7M+>{sxISS@HwWNYZe!&yg?THxl009XKAd0dVG% zQpa46^N*-KQ9Ur)O0!C9c;xYSPMg~fTkx@1_dDW7%ONQ;(`8@8I=o{)f>rbpWb zUvn!dB<~nmr*?$Ff~ZF@bGR7o^;Amelw?j_t`x=VJ>9}Vx2U7x&j}OYan5B zeFuH*fdLgWTpfT~nG~0Uqym+S%q_d6zNCgLi8T|(Kx9NT4g{FGzU$)D&Nb>kZ|0cW z_1?>F|G@O;(3<3MVX~LdSLVyFw17(m1c`@^0i?^l=nvPXlYf1d!mpSFj>aX|4pZMJ z`&WpbcNQBRQ*uY%vFS`VtK^5qtW%E>0@mM!ASj88CFh)?H)@hXRwZ>R4ovP>dj@&I zI&b$60jjU&k$T4dCMF7O-Jf&u4`y!vCyW70~Gg-DOc#m78osLp?+DZ%cuF39f`O zH_S13jE-I!Lx(nUnN(ZD-r2ed-}!mx;HLiZ1N}o)oyehX-V7&#v^yph&YkTfCYKsbT-Sul z$1RHX`%VljKDF1VrLCHlCiYClZYTzK+6zkWTLdl7T77m5s@Ab^zLF zBDh5;cUGMMn~AMOK}~jdG<-j)4}^2-F^?TXyJa$$0!3O267jn~cmHsmKIZW=aTS z{E%TXE*WF78C0~HUnxV!ghOpQd^OHh;8pP!t?4OK={?{Kmn^D0gj4RfG^rdGB5*td zhaBm*EX&iZWC-T};pr~in*86m;g4;=$c=6oNOzaS=$1x6x?55~0T~P!-Cd(wK#=Yd zBt%LSRHVB^KvZ_~y?^)f`~%x@T*q}C*Y-Zo&-*1@o+9R$8~iM{B!nCfKmylFOxDV| zam$&F%~`;4R&mRdkIgd~7P=eG15to+qfER$XQ%K;yVYjcz{s}u>}+WAEa>7_$PgfK zfgD#s-v4wv(W3u!JLRI4|Et^Wpz|5_i)haSC$Xs^)wOBQ915Su6@D7>MvoUV>=yEi zaYsAwTw0VQ0eR9LN^Z4Ea_5V7+~d%bWNLWnlaGsWUSypIv$7(zB-e{iC-ZSd2vz~m zGhgB!TmU8PK39cyuLGgdaI^Fxwr&o4QO*avWnEf@7`puCD)IyZ5)F)R4^Mf?xFKc6h89ESpQwY|Aj2ijKqGh;Awnj-RG!-5GIm2 zQ(HnGzia@?7plDe;vTgNafU(REK1ljsQ4g`|KPo9SDR^BoBg6TH@`N&yEc=sHvN4q zhQ6*WzqVMmuIfcyp=DjoJx2E)Q1|5?qpNG8uP=B(7#9tyzgOwH>vQVr%d|mzUHLCx zFs1*h9wAgr=*#Pqy4SDloL;~nr>8@897zX3P8h-iICz$@ zalWo5@t~&veSPn3Gpwhc{9#LrWefFc9c@8NO?OM%tr(N;D+vFt zDrE$J!Opc^^>sj%bkt~afwPY54@_{ecJ8sGuCSi=@7hw zmY(QX7~11&{CKMMZogG=s^bX}IY;xe7qF+%e{wn9>2p6*#Ey4*9=0*Ea$^{}TUV`| z{=kyprbnIGHT6w=4;xlQJhHaBrSVG4|2!^S?TT0}E9N7^@eQpoNbP;uQ(NHJtiv>* z-YezOJ6T{5^DyTvcJ=M|KPil4xI`}aY$4r?hdo>&eG4M-->dpE$NDz;p8oP2u;T0Q zScOSScPf7F;a%+?OkkR#CDDctd{P_uqti1(RINWr#yS}D!mjdQs$=Pprv8xPCwg$X za`4AX7b347mQYv@7fDY+Ho&W$p)BBiYCq$VA@kaxkL+-<`Uoy-;(WsJA;VzZVgG_( z(8tsup}(dgy}e?z!?&IzppUOU!O}l2^nFWcE8b;Skr`Dz8u1^m676lhUTsxx2xR&= zAoqLJnmBfBa%B18;7uvm+I@`4bky&~sCKWvL1HiOa~yKrp#{&Oqty|QM5Y&$IX-Hh1p`@C{zi0t?} zvwMz}v^iDI1x|drPC6I?2K~UBfI$y1MB>6Q&(!~B-sriA*K$nnC*Ny2P5N6+5z9>h z^2tCl4U)E{HM(6VNb6N30N z93~?SZG?d{?oYTS!019LkKAW9P_uD#?^wMj*saN!3DRFQj9?03U)Kq{F{GcHA+#TH z*0FPV_ENAe2^!=_Mb$ItAQ$8}T-a|A`n`p4?OsYdBO+}1sNRD4IEP^tP=F^*9Pkgv zS;Y`6Ll@^JN)jjkKh< zfS3?~v;l$VE=)Y+OVd%b+G7n{)FvNFVhN)su`yjs4p@6H@R`(Ve&35si17Y5{CaRc ztkd8FV4bi?o-E=Fdh7cGI|#i^%vHPY1`1Veim=OWX zj3CV`16)LGHKuON{f4^TCt32aPRt^~(4xl2rX{saAIHs%qBW`6^}Ix~y!IvWj(Gwy z{I&a80DOTyP2oo$$;12q6RDgCJ7^0Gtc=nm z$Sl2JkFj%L>RXa5wj==|CD8ri`OpY&zkl~%w!`n!42TWJ{C{{BvUT46-CfAedx zKka!LO6T~Q&#~c~&d=Y(S7*nnlMjv`y@NYNIl-ngaw?H-_ijh*~Uzwx(q;Pw;r-_vg}k54hElz;Dpey$GCZy)`m z1>P0f-dO8n_dmcm63_dDE>n-Vm`Jby9K<>z^8d%^NC+Zt@P~h>#seMymn_CJ$&)Wm zoNrFVvuYIwx{+_cNAX(pGw%6sya_Lc40?5u?LNw*5E@^hqvTYLQ%+*8q}{L(XVCl) zqcgp)2N8-hxLs z%+h+cEBatj?9yjrPo2IZ8A%o5#apHL{3jh69~!i}CGXziw7MCmE56A-em1JlYMB0x4zgG`@SQqWiC$X5{DZZod=OH4S&${~=x_&_f@aqcLQ ze~v=Tkcwg%xiJbe(Z_dS&o}nje)~AvYfNiV$vNzomg!@TE4}Etz3LL)_`VZeOCj); z8AVy#IM}vhJG;!omi%hYv4f$b$3I2+vT{tWC2`s*>le>^rh#9VnQrv^lD1*cvgeh) z4Dua^E<_YTd-$9=foVZyM{n>6yaWkT`vrYIFeN*vjO8fEG04zmt=RexAC_}3}bUx@aT6~O0a3prAa!@($3{kR+kSfw6oH zzqShe>APBVz)OVscF^>(_=HynVI3bTEF}z;#zymda*Ww^n7=C@>7W+ zH?EMD|6Ds$Y3V&2m<@D;gCD+wPOW|To_;@|zii>_$&Pa>kE zkIhO=wWtn^bw&T1d5IxtuMY{VJdV3gN{(BC0Zq7D^~d@}586xGra@j9A# z+y)El!EGak?jAXBD2gvTCwD{ns80=4KHJCyWx~uo7`8oqw9N7Q41XNV-LO zMK%lT6m`SLln;7uROSioqXk21b-m*=-fg8*F$^n~umS-h@c%2@nJr>J!d(g(IG8?Z zM$oYXjx5yyXzF*`X7BS~O)b4n?V9~SZ0w9~Wt`~ztmmD40O!?Ydmw$KZ4L}be*Uof z`|B)$XVl`tCk+g8lU*~>RV~G-c8j=IbowFv3+eBt3;HhI4U(@2%JqkKhUq;%q{+_1 z*&@^xWtBeIa!%O~|J_?+kBLuSHsOb4Z3@VjEfigd87lmuRim>=P5-6hLs7I_AxLj9 zz{5eW@z&ksl-#%iMd>V{cOc!Ool2rQU%?@;r6}>vWWZFf&h;OqY2TK1X>v`Y&rF>V zoouQQ{D{!DkxRwq7G8J~CtjuGX_qwr>9U!sf#3Ow%{gHNfu>*~HbJj}F{fJ%BD_lw zImZ78vI?tL;C<~X*I2{(2@5G>3}SbzsILf{_w102vu=$ zjjCT3CA8aJNc4)f0>7Uo?UVPcdr9- zFK39*TG&W}*s_7SlckcjCDQnz5Rq*|Kfg;$0vGOj9IR{N&J@dzB$5*qhVyH%#fZkW z7QEX4QcqA&i-x}Q{C1cv^)8JZ>G+h~nJFjZ-N<&K^Zgn;^9Xo^EuqD&>qt{5^V#gO zw{x6*{LVmL(9HGBg+#~S?S*u@4;IMzP`rEhJv+?z6 zdT!>iw+42a``Srido-uADHWx;O|ND=vhDJ%wC{w{ool@<{a>=P)clgbXnVT+DF$NT0QlBngn?_c)T^~r`$|mN7`Sla^ z@oSVY!k2xfTAqWoAC=t0b$$tSx_yhKtvMp6-#+%fV&ad63NM@&(EwMJUglP#w}rl6 z!Fx%;Q0@r^FcK_98^y@%n=<=6b9Qpm`h@-S3pM9{?0%X4HePZNU@t{3xCxZ;Dqj;q zuwIH@`EFw?(P>=l@pSGz(Ew|iE#!)-?BDCZY5<2h=4&#xyB0v}Ws^#na%yS(j-oQ8>l{KoSWEr~3h_5HkZ1JtE4^AeLGf@yrNFU?GmX#eQqtMZDTKvpNuN9#b$k z*tR}+{BtmBBKp3AJYXW4PIf4W9&qBI3=aJf>t#GrNPQ?4 zb=&g5O9^k3vF}j6EI~?Si;$syh-Z2rWvT;P(~Np0Tu2oW{j?_5KLVGW79s|VdG3pE z2WLmpMrZ?KSw>O!C!xGLV|{%&qf_OXYu_xaE6ZyS_x*er>^NK=tjx8F;GLFBNf62v z{*SF2p#xf@qnO-4zH_+9J-{Zw3?xJh`4R|+;jY5Ve}<0%oxTc9;zf=E>p1w@O6u_7cPv1pa+Uf>ZO?5nUU&2whRFimwvtg8@B3|bxmaA2r!(_xuj_`>u zF5pZ(${ZX7gFwyk^?V};gQKxNv>G}$G1{v%@_(XY;MknpHiD|z=5!a9CP!JoWFFjLZnHl^icIR8Xg z=1^U;2qVK(2TCc5m=JM;9|oU!wT>UA2>_e{93e49ln^yde2u_}kb4?^4i!p^CZv4; z08AojwXpP}@{LE_^##+vYNvBXr9;Y9Yasx%ku;WKYIbWB&yfI18+phG>=$Q(NypgR z6(KR;z+7?M)Y$u^QYw`di2x3RBc3xtta9J|1y1?U)jZ*w9gvybUi`4du2O4&%+wa{ z=pEO6GE!qc(X$rA1gl&G17D(};V|HnV0>CY1aJb+;r^yT;Mu_-)=s$aGc~&g;R$e& zL%06ir2d`PWco#BrG%-O3BvB|~$N8BIBE=o^+zsDeItm$qV~xfS#Neh- zqLt-FRWtR;|1p3^%PGe4DZLH1O+HRveqc9}+*6$*Ju+hQdMF+V@KoBtiR8$*}3>Om5-bMKv2AoUZT=a>YuS>SR8{U+n=%py0`N#BMXsV zlohh*6!jJ*8t3l<38kr^#GS*k|8!$P+y!3>+yWL8kS5wxCJzNnGgp8p5dpVLU9YXh zmN&H!^LSbkQy;n|DtXh#&XYNCfH7uBBw$=<#zeJG{9vo>_aeH91*?B(wU(Hw=4C8SU%QZ; zRFtS;`0-;=D##EkBl#e{5)1;riG_!?1W_&9^)1I|5fW>%JuZFhkYrYAX%ZD_l=O8a z3(m9<$NG>G;$MS8=~)O`f6lD`l#E`0N>7z-cMJEeM2ap@jec&Jl)X_}QSQW#M8uc^ z9x>z>eF-UJ2Cg=57jv_%?$E8aGL_voa&xS3$O<#Jnm*aGU+uDH?wTp$d13i%xGcB8 zvTl2Yx{R`6$?~OmGMzhp6gaW0c_Bf<*0v3(u0?hg98 z{?>Z^A5&kWMU=AEM<#2t!*WG7NGb^!d4o)+vW%Co%nMpBYL3Wc!?jDYi0RV}(D@cg zh~w4raA%uBAIM?&M%x08F9`=Z3gZQtn!7MsmW_R@ijIF|m&pL>`!i-+AZ``|GhZ|x zm7khB#JvJy?x{Qa-@<701gH>NnY8)40w@i$JEU#FJiQ}Hd~h5HDz zgcfoY?{xw9Ws>YgI#QEt1i&^Lk7{MKeCFHBMhIdZHxz)cgP9xBw3ENTg>1f4af)Oz z{lKSOH-CW&uZa<^Q6`?XJMWu}aYJg~<8^z{2wIInX$M&uTWq9}gKXT7^S8Rj+v~|S zIN#5}7c2H8E}Qhu1lrB`;Rdk=H?zImjjr(0Edh6Xv6|q2aG7veGlJg57;uYq07EL>kSD`#T64q z6Hb6_Id^0nmtvkq=JTNZ5(a+K(@H ziN=7nSMYUdJ+y1UHWPSR?YncoU2?+rN7i>=Re2bNImYBVc&tasN&|)u_i>76F^?dA zF#K?C{5SV<9RM$bV>9c7IyAP}U8mFc zI={8X7kkuK{iu7rALj2cLl-HGeqYsbdz}dL=sS3>W7+t_>{qM%BA}c`xd2KdL6t z84x9pcKYk%JE*=F2ge!4i=cAzm^twBnatw;clxW7&=P|iK7mVFjcd^fu5~Q%p$aTcuwN2{GhpHVkJ3}eW-PLLBQ&}_=pYrmcL^M_Sv z=aX1HNR&L>jp*Ic^Rdkow^%qFf`!}RvqKw*2dRI!Ts#^sAiSBS!+^=M1b909W1T<0 zFx{Q(Ldp+hWT2R zZm`vWipEb^pn)OG1ojcQk!W0$_aW4l1^euBPdG8?UWqUVdvgPn2D@~ncAWY>ZMg`N zUBHYhpoe=N|Gr(yL671PQ7_;zx)WfBn%IRMm&ec|vXmf;cMLDwdaYJ=Xbl2wPTigE ze)+S+6}aRRbb|WZkBOdMJC~qE2BUo@@GJopY8reTAD-QRoi_$W8-Xtl0Ei-Dx3c{Z zjs7=P7g4zz?!ri{AjWITtmjbuiWqu4ZS>R4?q`^WT`$?aTNkU}k9t7!+^8ftpA!m53UcWv?{wmSu^wj6BIK8YJIQT@0L$z|w+;r3W z_*VEDVtag!NT*k3>VtKp853iJG|gMgGOr+EB}BhI*Iup1;I>RI#O zn)f$JAO2#SN)Cry{~0xnLIxs0kRV31YhB7qWiEmz>oH>YLY*|orzZMK3UA4Wuwiq@ zXxo#c=ckeD)}D}-2P^jv^XuA@bKdU`(Qq7__1Kr4v0>}c)~}y!5&k)F^=RzC{`qt} z#}$^E{kuaS!jF&E14yoa4gdlEhtW->A{p^Wx$ZGKKQ`4k8Y%yy+!n`S+It?jV&%aj zMrMx3Z|)@n7Ie0#>wJTID_gl+iOE$gkU=^3@LNP0K>w>(|QV!PghKaU7O){gL=s z3PCUFQX5pOGS8x_&Vgn(ibJ3DWiadZP#%Tofkq=9fb8W}4Q+SVse6Ad%@^;_ml8)+ zIb@v0-Uan>ZXe)lC&z!J&U%F@h7U`d@#Q8=1XgX5KK-`d^VeU+ET@n~0PL=US$Y2* zUpIY!(n{%aC-=g>-4p+*egL4=O?_>l>FIY5??5yqn|8Has2Kon!YTkf+in4>x)dYC z0jxFSGcyFct~&!QCBA81Q%MxYFxdoZi-!eEv&C^dGAZErHRyn5ZJu_Vd__s`@&iTx zRlVF@RIp7;aUmBl2n;&%8;zEwj&XdVZlubrC)a6+0|2d!7sqkN+<0q0=SMobj7j{PM$VDFT=YYvNmAGBBE2O?opksiBOerG0SFzw zL%)e_beL)YVR@Q%ottiG-u|wQ`&~t?e&Lm>1!U%Ofj}8dCk`*6a>(DWBgA>1E-)|( zODXjURN1d!;w4KG?Yh0?voU!eGI_9`M1u7U`C=Nkvh^PVLe444jh4{eHr-CuVuVF zbn8u%q|>BglkOIg<1f@rWx67VEtJK76(BUt7j+lm% zDa>Wm9 zmoNoOOP-4E-dWSFgxU?$##)K*_&o1^M^X&T;Z9u!XuoCKQnJL}9nGAEPpBEKK9~$vbh9D{t1KJq@wN=+xuD z>Tm`XmQ6D@@@9h|`7SFqBF{HUchok95r}@ZSDt`fk5wQSCS!2}GX4gri{ue?y_`KQHx`0HqL)%(UHl01MgLq`I!*O+p})DzR>`q9YWS6Vrv`TVe|>&JNhV z=@xMl;+>qo-{hk!C&FGfPEnx|X3;e^hR>b2bPgSbPwP^1mm!6j!QEkCd6)qCS zlVsMss2md3a=MQzICG}Fc?twL-OB5;Ay>{x%0E^m8bfkd-8uLlO-CwM;l_A;^pC6S zg~&)5soZ0J$kOs^y-czs9zg}xtJo{Q&0J~{L ze6#9>Y~Ww0)=ZzpnC`n9)_)3q~#{3^lg@U)-d$@Q`V$qCg`&fAr2(`>jOY&efs@Sk|Cu%+8eZv{@ zb4z9EAsH-AbC}vj(|f}g>OJj1{iRuh5r7qrQx%YU4PjMfL<7)1aFs-&5QKWv8I;}^ zLCRk7#D;^kTTMBUm;YU{c<& z&7v4GWh3aHGr+&Y97{JT4inNb`_%oZ<>xR}mr?fGk;~N<_OhKGqGS zBCho56}K{JjDmO>MdO~DSog=|aPf)<0{dFV-SgS~;#Fcy?g;L3jaQoDOjo|K2)FLV zDg}u;@m&jdRjy$S}jz`Zxpcyyt{62Dw^z{Zvsa#bRZ| zAmdC;O;$KYV8!N-QTk#;4Z#|MCROs;@6TJQc1Hq-uGPX^xS5nq^ zxRJ){$j1PP!6Zl@VMx}`=m4^Vq?UgXkZwe55^V&rZ382#+gvP1B#bar^Fp=#+4Irn zh=3PDybM%e8oD{dGznsCH#HR?M)pi3*+QK1$mm*j@0ynuI06N*C>3s?Z>=j{+tiX* z6L72L5g6tBvu5?I0m$wPo4FDF7VN`{@sJ496(Cs{K0@$C8q8@Tl1(hOVUE7#rcfxJ z`2}7MDS!9}Bq;ab>wpd<{|f*W$}TWuEI-QPvl`HW%9}-1{lvJ=qWG1WAm@X!;y)q? zd&?O5@DU7X5QNrNITOUej^cES`pNX|wfp?#{xTSczLRmdkr>w|+pkvY ze~JEKY?s{EZ=J`m;JLpz0HV|=ZuU_a3Zx%0LJYsh>qh#?;L7VNtn8!gH}4XhGd0^* zH~y*F$-$kLu;UzoBXol*^pugZj2K*hTfDmO*I{Y^X(9=Bq%r~pMkC*&iXmpDD(uTI z+!xh@Of-98%F`^6qat+^0DImL-5yX1K~T&JCIv>2USOb-;}`?Di1!3U!*O480tfQ0Lk0C=)NBCuVv!eAS<(@(!Xa5L z3dJBbqt8>~8#)p`;9>hu)OSi!Y8zfj>$H(<8fYquF{DLlmSs!X19>C%u2B)<`}5gY z@V#62jXOf_$POk=&N(;&OEtUTK#7Q#{J>$GC75C0c<@NxR?iCasiK7aVvKQ=04{<8 z1^=)NEGH7a39}Q#|4`Y8rZO3+k+xEno6xe~l5%JF^xaY;{^ZB_*gvUa z#^4)fpAOKeB+{$$5Hdn1tjY|G_|L2xESwfue|=0SHo;(^oM|u%HZ)>2p{gRfJmh_LA)GSE?XgJu%Iyd$x|| zg_8ekRdMZ2{|lFAWmOe+yLvL&L0>rad6S;GaN_xJ8Nec1bydi8Rf|@J@C&P7Xgix^ z+v%+^^ha;?w>%NOSiYIr4f?k8z{7=WgUbLsh;IR+ltKNaRecdT_JX$>83Q)8RD~Z| zeTbu-lc^CI))41Lq8_=0oy>&Ua3@>V7{HPXb;0j_H2^4Xjr+nEa;zJYZBJMFTL-Q7 z7Rkbf;YuPKMJOkEnvH6fWo=p{SaDxRQS-a1(*~2~M3&iTZn}GRyxYrV)Gq<|PPgy& zy8F5_Gn_N31ck#Xxr01tgG?Y%q4MKAhtWLhee~4=+C}L!^}VXsAX7#0J}z%IDenu} zgYqgKJ#-Y9o)A}-XO_%fPkKsJ75V4yR`CXPwEB--dpE-!XB~EA(9O0gc(4tH1f-T! zN@qE@)4oP+B$ngaAXt8|tEyJ1BY+r6@NwlXMWAb#PVWk-WoI_eGTi z0a{Y6QIY0|{8y_IeAuyE*JyO03om06Eql=I#wr=1TAHvigB@kr(^tGqXmy}!BV0;4 z;C}n)P)|3HM|DaSV`K91ps~#TIrDu)2o{rdB>j3Ajf8ZYxN7CzvvpB&!k&HU9!VQ6 zLxdi2W*_yf0Kt-cZYM*(Il!F?s7@o*_jO(YUk=A5;oWEPR@q?Qy$>uXk8uUh>3okV z8;5rAin}3d%}UYd(J8 zaI%?Pf7UM;*r>CjY%(*`u;CAe?di*1o$TJ7tmJ$DkbSDBiVO+_8fSZLc6++Pfi#7Q3F7JHO2@UPNA=C%{J-H18UxXM4M6D&rKt0u;xoZbiOb#y7cd(dd=WpnDEpa z!EOIHq+DKI2vPZ=({ihOurBK1B0t~MYd)gajIn-rA4D`$ZGKCFL;Pdcfc`iPXZ#~4 zaH2GB5Y7II4<5MaPIW=F;{sPlROlM}28Qp-)evL9HD=vc>AoZ7W5 z_U5PD5O+7@mhyDuT^qpc`ck&z=bmMty5^b~umHi?h75PBWA$6N z4p*ngqQ*}~@%5sDjldo1bxu72uFo&HsN2DBpE)V*Oc!4OLZj{?);zH7`rp9@Kd-br zh1Gm(4Y>}=NE@=hNN{ZavR`UEopptdJynJv@0ykT8Ls?SRRgg87Q4UHDUm^;Z7RZ6 zwBTl))Akq7B`u$$Ef+FC8X&PmmhX2e$5~QhpMreK`JcIVxZ`m}`Hn8L(z?ECf2?yu z@aGxw!*26z166Ot-5L;C(1G;qV3paTicI}vhJx@PY^3fPJr@gqCFWVuQLue{|8`e2 zpO58xj_#1wRrGc>iK6huqHrp7Y5#KgBy@V%izgmR`5sd5sH=?KMM1YZlT{?2>5FD} z#8F(59$2atp?Ct=x}FofiLP!=w9O^M=w$ZbWIgUO%MsT$?sOGW^}YC|wti8Il1V9$ zAQS3}Ig*mkdz{(fS73WnFwmYGMWdD(EVk~W*6dBN|NF($j`SQERt+A>y%a^XN9ntp zWc^$8V{6wl9gV-u63jQ&r!p@=VkMFxPGbn(+bEyRfNIan>ec67`kv(6l{r2rcy6I_M#ffrvg98h5@?chGhbwl8?DixSb!kO^mOTaD_PjQc;9lsyneUBcz9{LLyy%Pd&S~dXK!TiON)! z=pknPIT%h7v3`ov=eK z{rmO!5W{5z6b)2>C@nl-=h*wOz%!b`*S^$&zg&=8lBA>zQ#ru_v>+o|(h551=r*Mk za_t$mJT3Ahu#v9ZL+Q~w_=wd_{qS_H{#_}H-B^W`r2gc*RrR(gwzV);(g=aQ6e)30 zW!i;l?aS{vySltA``0Me& zFBQxB^8g@hSbn9ik!ur-y}x{+%Crbj-UUGQ>{#k34-|3oGhBIV_>@m|Lr7sS<1Q^v z;chec?(|iT766fZAoU&x6opU5N$KbMAq@p(RS%s|BE^rR5ph`zPAwZtVo~xqqD^<2 zL_N@&zo7xEPT>RW#@X5QzxPOq`0XrqWw`2>D89O1Q3bjgmTRPOns#UM%o||uEDnD2 zU@c8e67$8Ey0bhVH`xxwP)(U|8@|Q@h8EAC>gqZ)g^u6QMBV4Kjswem37_h1`ooUL zLl>Xs$Ccv^9}zeLn!XP_VNzVCw-7acud%HhU8hwIVs|cHe03XJ(JSXFJD|d>;9|1^!{LeeZ)9* z*d8jUn(Fn%s66bagU(WbY$FQ!+7;s&l+vUH(AeBGim%ftK2t3 zX`01xNdx>Rf>zEw?+(69xK?2on3vI)6K}p@xYL2 z7{v)tY0xXJ|NL~WX2m~N*|_G9U)&5!T%kvOTb z&6oXS9d)DS@52B+X8tc@9K|X>eiPbdhG+T>))4rAqq`Z4x(?rIPg*vAdDO*L%3L$Z zima!DBrQ^Pj z5o;nUCzQkz&Ip0DIP6q)Fd$o?eX{Zd75Gs@ly}_^cU|G6aJfi_&v}KoQqtMPG0tc^ zd#YU{>JgedFv(d2p^yzAo4>&~THSnu3R|w)I1TfW0+-S71;mHvDg$8;$VR-3RR<%| z{JoqCXcTLN1RTh?7~wH4c5rG61HDZ^mhaKa>ZDg-!$)Rhm)k5aJ?K?yg6wO|H=Ob5Zj9vncW+ zwAwAWKneO@-z~c};J9H|AN(sNY))Hrh?kB!`IkXb_;#@-Yej(BWL7Gtb7S6b;E@{F7}-vKq7xxMeiHWVY31+HZI^{Z`syB2T#BOD`uZ`AL?oyG|a!=3hAzG4SMhE82Pz)`4js zn=xv%f4gh72QaeM4XmD8nKI*+$iBh1`Y)x!{uk5DvFQH4m`*cdl0F!j9O70ElO{t+ z9StQFV03x|8wUBrLHP5?oRLj3!E8#tub&0q0a)TW0!EELwfW)qKPVQ`{Neg_AXka; zOT-i`kSvy|4TrHiLJNOIDS-u|M6=gP#HoyoVKQ)FVFm%{FYV*tC?Jap#@8p04u7Vh zY{Z(`AR4P|eCNp9g?Ab`=E7SGE6K6(55o;dKquwpQV z!gdbG*|n#pn>tin9BQ6CJf{oqWpv*aei2~lAK>@g7|3+t!xc`(O}|aFs~q1wU)>VT z2k><*x{uq0{};CrJ$J-5Nb}(F*%^^)kE&99nVSSz0)bt2bg7Z%yRSHkyo@9BJXty4 zdObB3Ha2;?@Jx#*@Yn5;RF8R81uIyJyTYTeIfAhaJqa6bNeK%c>5--zl~)G=Ld9u0 zGc;o#iJ!B(K+kAX%&rD<^p3P-3Rb`D=#a?izIfKYQPm>$BXXo<86odRzYUOHHAj60h9N3xf8pHB7^=7zqv_Ifm~{Z! zhV9WHHW3GNhSAldpCZqnh(_GRDq!xQ;d>A6pV0`B$d6h8ZZ;;Rph3B05QW6V2ukFm zL{nJbUf75r-VioITVXmPpsPfEm+C?AXj*uFrI|{foFAg*1Yyz3Wjz|D-%xnIfn?rLXt&@3r0}nd+;LQmeQ%jgd@3(NT6tsR#bnWXg-|F_@j564?iLR3Hzjd1A?AY@&bblaD7znS#-jP%@qG!H?V3y1zYgB~{9<(CqiG!xRY5d(0D zIL;E@q!K})9X8y77&Zz?ViEyAzD40jE534TFqr%~1&$x|4~$YPjkE>voVgShpibNj zzoPeBY;PX(nJNUI1kDe&-r3V$?2(6%Q3Ravok1mJTPWjNDAihM6ATlxl?aY}39#fN zq;&`aD#PDSAI}*5I-PWr!$oXm2Wii0Xofz@x3};`o{Ptj(S7^~O%Y*IG$g8vB0Dl5 zP{xJU4MHl;sq7PhLcU};gG5;z6xflK7nOJ;E%3)KjLvQp<(rJ3TUd8}nV9CGQLiaa z&WNty&~^anX&TEagykn0h~eOc8Rk2NZJYRlJq-w-N)x9QWn&^|vz{kq+M{n9BxUi1 zcEU-e(&_C#($}Apxf_P8A;eNkK?WDxAt2Tc2M)e+4o6WY`wO031NfsM(hfWOUIgj$ z^xvFw4@w(}TF=un-@Nd&K9X~r7_kJa zv(6;7&t&4E%yttu5f+8YT++WJR~>0x)col{Y|nhhN|6|-i-S=6m8O={ti_X|@Lg0F z^Mhc+fMAXj>OZd?5U7J=tn-VK0oRxx*=B|}NL?JOo3yBli_%&WCoQ35Di5UCnq%|3 zfHqxn@w_!^&D5XCFpyZ%f3Bj11sYN;{U65eI~uO|{~!F-r!YnDMu|=c(Fr1gNJ2y; zf)ElCC3-KTcSf&KLqr|DchLn2i55nS7NSNsJNbS;yZhVU?*4Y~nKNh3ng8$m-dA}( zK=gD>-4@I^S{P^TgG>8I*K75SlN9_PsY$y$!6P+w-`uGueoW)?I9yyygjWCF3REFZ z-)!9O+D(4z;(hx)f@?`@Rad+%bz zMrKH)W-ys(pgC?(ssFs*g&FVUv!riw`|$3-kqN%X2v1_1@z_{p&yaJ{c;V}FXiRY?kXVLb6dQ5P&Y0V1xW4L>rCoqT>ktM}Q(OjD}Ch7OSQ zXX%Y4pZ%Y@p8DYX{<-!0OP_&ur0jOqkTpD4Zh z4zHw19^-u;S!sTo-okCdbo-0t<)%fTtMz9Gt7ui4UyH0gi}WkkdC_Ip0&pBwz%}hW z+gmS5lQG~GSGx@YMz{UfZcpmnQJvkX{kzM*b}Wnj>!_!Asdq{Cq;paZ(gC(~^$vV_ zT&&WL96z{u>K&PmxgQf-x9eCp);YnyT1PHXkrILDIvD#qNp|lq(5k?m*1H%VyO>G4 zzH)PYQ}1ef?CK!x=Hlk|i~-RfLaWsScXx9SuXm3=c8`#O*aV{sCI!~e#aRij>XqSVopM}N;a+wo^6?y(;?IDu5d-=!mIK39zlJSip!-0$fMc`+ z{WAf^haaVkUM0mKp9%aJ>3 zjbl5#!W^8F|rJajZYF~;|RI(nh#HDN|cNDaZqOp z_Up2k+=ghp`7`B6Ckuzuw2G5t61|{U;@Aa8|9Uj%jwuxKn#q_c&BHap>4~M+U%%Yb zOxxgy0dYB(?(~93udjKS_2fX(0p_Jmffs2evT2#n#)NIU_e65M&K{f|jVVXFDFJ}d;6#?zp421GYkWZY*vtjYaZa4 z%cx-Z{z%U1wCVk2Q;L~0II9l!gc0_6Jr;RhaNJng%~YE}r>JaN?xafJo14reRdM~f zo`k$~gdFcRXQ<=rVsAZISx)MzW7(@`d3-Ys=Mef~P6|wLiM71QI~Hlj*=s`Isu^Bq zY-2Nys%pUB!yi7ct*GN82k5`#-c8S_%l6XFKbI<$=UTpjW$+AtLtD=3(m=z~@-e;g zU>4)TML(}X)myQG`rP>Kod3tH)Xe!c&a~2d7N7RUhP7R8glD9^nrZ$tbJX={;fe@Z z$J~mCD%?@LcpKWpPu;@#!vWl;T(I8(^__(UmKQ8Ib_q3=F%&f~8rBJ&chj79=;ilJ z>(a)hbJE^!+p_;;*HmUGf*QlT{ zqJM9!vQD9QW3DUV*|3mN$dUJ`V*O~w{%8j6rxCTssu^!Ko-4I`XLl(i+-l_*m`fI6 z`FbqZBYvScn)H?PaF8Vv3gkxNccm;RhG^c8U%&W5CqK#YbE5vqSM!8P%Y>1=ju8?1 zGCXI^HyXi-G=(1rb7?+`Uv=Ln-(}_Zo}(dAY`f2#`v;3XU&Pw}ta;Bi@n-HD#bI_n z8`|GTGx$l6Ol*LCr4-5Y}vZZ58;>HXTpMJ--kYO~= zU`!*#z;#($l1tt=-(MHS}{ zFb1t`bFx0GvCXRvK67SmKjM@=#F|X#`@C>yW2{GsQ?f7Sn=Gzj<|k>_t?#WzW~}2I z+qU}jH}<$z?p}>}m~1a&7WMYl%G#!1Ty0kRZsoq;q5Hnmw=|<`)Zd97J2v^gy}P0} zzewV@4$a=JW&gd#zW31QS3=@@2e02mx?p#fd5QN?__4LwtNmrA12Vte<&zebg#!k? zz0X{oB^|&20NW}Ky44+6n#t{0XcQm!(lz$eq@^YKg}=7vTZ%3lnjG+w4k-QW)T4PC z2K^b;q!XdBlWE9BH-4Tfd*OZiPVS4t0|QM!Q})E4=7l2x*1zJn4lHl=jry56 z+!CHUJtTS=n<}CXVO9teTU6n7OyyVTFIuSKg%dEkR7?abp`Pq{0lM*_{~t!@Yk>;& z|A*1Vs1dxm;k0XJUkMmp{{3|EtIz#lNh=)$UKynLAB;}U2XeD`;*(Z5bAeoyWz_qp zmTxh)$?~6a>v#R0b_$J*uViGBt9e?yAW-Mr_jY9}iT6i~$npNGjpK@e4&hpelFboz z>2nl|yf3A!<4{jTEw%5(O`D%V`YkKd34KHHBlJHFhaJnZ>A#jr*dvbu; z$@n-r`%vKEib|njcd^Hd!PrLjczd`kn*Y>sO*mC>gd@Ft>QnZo&B;H+A4eFy-B;^B zM@kwQ75zE*ID7O(|MC*>Ee&y@Fr6msny?Q)G-Mki=cRBcK?Zz1l0 zV7>Jo%3?9NIHs;}c`2g@*SgYrj0wAU-4|DzyAHS%tM zf1X1>haZ*e)MMM<6aAPZBTT0AjAnJ>3cGVelC6P-Q?7y#`Sr&hw+hxDKK?fcsuo%k zCdcN1jp2no-qn)Uob8IdYjaUe46N!b#qrJr9Ri>%{IPS=R9@_ZGaZv}Yv1PY=f2-4 z|09K_%KckT9alO(55Bld&$r4K9cUd%-2q9{f=p`e3S+nWKhQ|OxUF=Wn-b%Dwi&ACs`uJFWI^SpFN^3-WxKIX(NK$ByGoOE zpS#jxjbejquW(iBE_+vu1mDv`Al+~e+9vlDvn?^XJkDA5eznT48Jn_e59ea zn%PajbcDONAuCoxqgN;5tM+S)0iIqnxJ70zkClb?Yr}d9`J&Yr`<@qbIx0f}EB4|f zkF~D*oc6V_id_%1#!0#E23QCpL4U*UAc9OI-8uk(M>$j^NG!}ljS{fx|5pS7NBKJ> zt_ZJTwBE$4%yA=CQ-kFVmE)g?s+0KberMkW%8kD7qn@pQ+jeZcw{R4f(s}qurIU6T zrS!_)n*YVA)fiHmcA0G((JLtbNZ2bA&;5)Y*(1HPC~Orxp2;J!;WhS*+M*+mn{3KT zLC;O+6DtmsJ>BhmC|e$AVJUw`$-jFjqZ2@`pX0Ahqjf)G;zNMV2UQ2O60jI2{FR`Igy{tm2m0l7a+fNrgA^$OP#1yZtQZo)hU9d=mTOgFS?R0mUeCa(*O)HXOD%6f zXT~C2Yd#P#x?8i9f<>;irM6|(FQBtiUGz{#Mxxj6B4_7*)m6q$mc8?fd_GU?*3k35 z)IKuO2*=LQAbG+hpfdeqU8`OQ?@6U;N--PP6=2~F(+^^8BVcq9ZY?V!6&|Bd6LFkB z?MK@RuZ43HYc=B5!?FsWKamR;n{MqF+ZBFzC=P%=?TE17NiCNDNh*|j4RjTzmpg;} z zy8q(0C#@L8oniCu`^k}m{Ojr-BQ_=jiHbKsUaVZ8D*I5VN&2hn&~L+@%MuG0ziDr* zsf`7aJL~PvtVjuYj&r%-2YLD(;QCeZ#mbj4x!|HTMN8(~j9)bc5@loTt!d*QMAwS^ zH8$9MJtvc%xRe-2zvbn4I#N)66!1`l#)JB3vgD;pg~v}p$+e{Kb)v4$4%^hmc-pCt zn}@lgRN9t&keP9M*SzTH?dLSl1qXMkD*ULnOeMT5bEL%LFz>gW^X+F7wQe>ni0s%) zpU>`nscjq`uyfgxPh1y`YTlyS^@wc_J*0OpjZXjLBQzIuNk89C1$!4paq;?VmQd|h z`j{8=(<1awL%NL8h5|ej$Bkd?5iqg$8%o#U*#*CR0Xs+?^8O`R(Kzxh<{)#+drjd_ zc#BGZ|Tfa`z7@TPSAwD_1QA|)AZwC={3^l zx5f45>Cu?KH6=dVHt(8e7huN?L&iHoc+9u_2S*?885imBopz2tMl)hi8*)D&i*OF- zZf@T_1p|d;j(1Ldw|)0-q$sR9JP2UauH4`nm7nJ>cN_D&THyuP%BqNF2X#{%h3Q^u z8fO>U`JFDg75JpuUZ+)EP&;n!^GO>rcKcA(cJ$!;*lvp4*3!d!f6;UDgoh!U(et14 zozfe7aej7F)oW+oi&yrk6&r0CnTNimCuzBG>Tf9rMCtAwsZ)P^xjJ85ZTtCMc9Z)C zrnirt?zmK#5fU8ybPq8vas@0rzezLe>LsS@GVJaJ#J$bjK>_ zZdj0JQP919g83fw8VJ(m4`$5+UW<`L(2>d%1=EBDKVJ_vUJo_|g_yYqnrnoJSrGvD zfHy@ULj55q8Iso+Nj;5F7ei84Q0ILUJ1Y}7EzK8+GkpiMR&^2Xv`xps3Cv;Hh zGk_(ZwudjGL6QF9>HXnZpolz;h{CXl;{FJBf6%Ncd=mlfc`4kV$Jj{V=ckaZG7$w+ z$d9QJB~wD})WQ%_fa!D8NNV_Ke`KyqG)f$3+l3>@0SO%RFb7sD7FwkdSr-<$*bq6c z5z~HxTuY5%42J&FfzOZKVH5wS*K>Rfd!!Q1Rf+kXfPtK1bjC3#@i%=FpZo~mVJeOuXZ+N`mK)fgzAkh<}ND#B= z5`&S5%YTY{a++W$kjSA6UI&?hJE%Iv$lv9_Mo0k3HwiMI5<+#8l){sg8r9bOOL%+3uf-uP)x$5H$uIMiCC!5+2h5T;V9+WCWzU7y1Ax*l zT(#rTrdU$XK3slRv3rahJB2Lipkj}Mw&ySwhNl+~q?dyMG9ZJ~pS1d!(BT+4C-SBq z383%9*fEX#)RMJJ=}cOBky<$b6ij8KCkWFn!;h_MTmwd~KIF{FMCM-ck(= z*UQgn*~s|jkv=JqIrS{FZyJx>n$FrhK~|zD8yhnWoU+4;a-eTjQ^jCPW6>Kp#rwB2 z*vw$H05uy9vIM+WMZ+Yu3~W>9RyH?00e_B986u05Hr!r;~mU#()yUM2NZX}Pdnf#IW#L6s1OdQ zBBos6hU0NmbZ5YfDX1ze0{~#&Gst(la7G?RxAc!*Gavn!i|}GaY~tWx&muN6@ClB} z&Yrvzho{oZSDDIJOp5sE3Hd~c`-m1S3VK`g`b=S5LUD3glhv6q8B&s_Rg!5KeVUe9 zJ@)C%8GLlVh@JCO;u%9n#3uk%l5SW+aFKcibEp&Ge$%CKa-UoT%a;emgG^yT%A_G3 zu+TB2MGlqPA+!w#Wmh3q#E`dQsQSJ^8kI58XJx={X{cHGdU5%02(SbBhtB z<9Aa;uyDD?VgOg-Cyw1{D&IaUKSNX;%pi|ED^4K*Qc{J^S%qn$q)d>J={c4)1AD+s zffGw4fOxFf(iq4mfTdi-tDM;y3)-rL$XDNNF1wurOT{7a%-EI9nui&@zYzE|Hh=K4 z=Kb9u$^j6y{)*xZ7JjD&uJ!?J4=HpMWPG%R)IUe^plc1cOb>91;kyzW2yvOFJAVFk zkF9HMpujU0Y64QHTjQbce8;sU-(9{I$f-M=sRMQ)8Ww8jVw3=;fIW`HNUM$wSr{5u zAJJSNeco{A100WPWJ!d1P9t9wH@=3}mTfgDcEQ5Ez&Hf8qF80-ZFqeHNeEB974YzA z8rgu!@k2JVi#OMLHFG95|Cr9Kb!<+aK&Cn~ex614L8vHa8O@{#Sc*lh zw@NEu+REYIO5m(QBuVkgU|9fr4m{l7@a=#CT_udGUTy4g__i%;jU8w^eFm%)p#B@# z9-~T9of8>B!t^mwi?9ilf~MTdiMR!@R>dpC5&b6$REMAGi+gO0Lq$bV3<(0Vt^@B> zj*ign3LgNPWZ`S3&~G&cxeamtIk1v3WB`_24n?uNTPSA_wh$w+8iW28YiCF1#mmA= z0aD*jj569Ja>LyKu3K5ShfSqNJ*r1*4%yN{WhF-1Iz}a^d;dq`{h4XH$2Ol8FS=C} zdhU4lXi`2LUeO-ox&Pk=pPn~Nwx!#?^z%Cib+~3q*AltMMvsp0=g`I8z^Km-EuT5# zQZ=lh1Bb*1_Yz`^(qi_>YjEUp1UB~q&$!w1V5g=hb`KhcBGte_jXYS6$$}dZl@6V#XZ2m@4-_fNnh+_V%yH`3w@e_GmI>yym_I?NlL{cvI~D>&!QqB$#lV3tV7wUoAsTE zDO?s<*8y`{!wn`FZO)JiC-^2p0OK)CyT-^oQZ@5U9B8HPF0=*-NaDY z{APs76)G7{AP9nw7&&`xQ`F)F`#AZ9X}Dh54=+V(1psb!$?)UO(-0RHvN5O%70YKQ zg+Oj5g1DBaOdhENCud>$+Ek5+OSRgCOO{CA>R#T83W`17Hoi@e-|%ZW@oriUU}Cn20b_kcCDV4^snriV$krD#CPjuem2W zN#io{-ZrC+;ldnt@QiB7b7Y|tAW8QgbX2!=kW$s49^h*}^n(2Kd>Q^yizxur5@TZ{m5G zo>Pp9i!Q|ccWfyz6{Yg^XpWI;RfjR6Yuyyy3FJn0{#w<8jug09o346&S@YRh^MkGX zi>?PgSP!;a4~qhQo<%6wSyA3jXaC#9{01hc(4ezoCMKgnb+QXMI z6Da@HRj0_yDWgCg$|E$Tk}3H#3f_k8iR=)b$28P^+5TxVqc1-gW(t3cO*!d++)@Tr z^b1*F;b}OMFl-BlE>UR*)j*KSuw9WIg0v4q)rBUv0AN4#Kx+t)ECR%`wGFP=EjtGe z(8homv;py+LaVXC13EAW`H508oI#$HgVc|8JjMsW(wAW0F}cp$6wf_n!>)myZrIuV}dDp%qc7veYpU? za$Se4nZj`x@E+sU#-BMNqW@7qQwL5+&WS?tgzM@Ge|339_`bZjyu8F;oZ`<9ug=f^ zCjsq0_89>}J3T!kSZF6F|BnvZ#o^&U2kmg_=;-L+;9#HddvEza4%(k@|Lve%ZEjxu zmxH$VzjV+J{&xrMVs_?yauUB#h@Xu8UpQ!!lamt@6W_jl`}*}Oeti6Nd>lXSJ3c;s zH9B%SHgY~Pa5*q=GBEH@K6?dv<~>pSc2zHDndCVX1kP6sP424l`UQt<{!augi}F7R+Na{ftmu}Kr2jt%+HqVQK|nhX4#r3G{SFREPD+Z8kB^Co z2@4Ag2?+@f4h{$iAn<3tzP?8u9;Z%*hi|Q~EadvF-xByUFE1~GfJVU1{vl}E*YT>t zS2FzD&kVO8KG;ydJFlSR;^IOO(B8d!XJcdYKk;WKCMHHkMuvul{}X?vp`r2r!Jl2{ zT)%!D&(FTfCxAyW?{abd7k>s{VP?hC!>_1ecq#}ULV+hI2x!Cv0nLz??>_>XsHm`z zkf5L-A0OYfYuC8Bxlt$-2L}f`J3AX28!Ia-3kwSq6VrbSXdKkkbaZsIw6xUJ)C2?# z4u`{FFe*w)C=?2TK)_%y2n70n6VP7#1JD2vADx!0e69CdwVPj=-_S}rli4YcRG4;0u-&UGovs%AcJX|uu57m6 zetGcyz54Q>&F%-AKZoiG^VDb(D7$t8)~w^58h;jAjJWxp75BX??Z&Frp;V%Yla$_G zE|w>sJjvNSH`l)w-pWt*^gR0Zz5IPw%!u<}-CA1-PM!}B)qgE?1VT9;C>%ujNiYtZ zp`OVe{2JnuPhnTwcU~VYGl+Hf4tt4=f?wg6^jlg^57xhxti@c&86N+s?;BO(kasz= zT)d^AWNsGi<5bFrLzB{5nLfMNFh~x74yI%Wz805B4x&+=Lixh>>UDV6tXy!Rs1W|8 zFvK-0vtULO_l1a=0uB1$mz}AY5HOwC7k-{!MawY?#g;E!!B0^u7&ZDgD{&gUX*?hY zbk0hGj=H7=F=zmkobGa>nTR@jo7Bo}GlE#*V2Uujl_;ig{WRH$x*eXqb;rt|kV zYwz8u9mtXHe>c{$od$9GDn?%(6K>XBiA8xPy;JK^{ozkLD0#gtHwsc;7jG11x^8ZK z%n1?PEc%fAcJotFVew{hY2Bt^(Thtws3Swv2(?<)z_rl{WnbAWNn~gc3wjr%cO6YK5Tsn;djb#qTxgfb|3#DbufbcDu;Ir!c+mB_Y<@_T=( zXe(LFhL`8;b>zeZH|( z)N3|U65q%1!@8)SM8zuygb&lf@s2s?{TdQuIOgtQ%y=c*^m05?JW@n%wtDp15|nFD zkcOX3a!3Jj@KyV{)WK((W!B^`zvEeH`UT9W;=ezCKEmGzO0z+YlhI=+B~2vD{?1s- z4Fi)m8~0+tq(4h_d1pXsL!vaDcoD=84x*hn94peK;m3}rh^xN^!#YT^2rF{BBB5yP zq}|oPr9&!CDTw*Wv?ziBJ9F1atNN0do~V~tPspiPbjQfFL_jaimPzMG#YD@UQ9at$!|M8)^(E4!2RVX-MdgcQoF$L9c1=xE{~W-x zAH%vZmLEwG7PkCFXzM}8pzHyw(^r+G4>YmD`N~=QM0%% zqV4f#V134jJnFzi@4bB`x!ih2lSc(vC;fu%rBc)AlVi5tR?Bs)8;D)G13 z^4O!loR5{ek*-m%*!DpEhBJ<_0oou=sp`c;*(x0V;o0^Et}(H8yydD^^Mxn*-g<-W2BTK&cc-XTxo zciy}hPh zV|Eey86>(N)zp}g@k%`($Q@K~Wr+v8*B86J%{nVjwF01ZJF{dif1bSDk2C-UrEIcT zsZcn|5vuuA(8d+zDBW>?o(|ST04?0VJTi1ymdUU3>2}Q^q8vt`%yiV{Drai#U+XB_ zvFh;UREB3Z={w2?hYQD;kuW5#V2H^IRgx?t?LjXo-eT2Q6Q9EG04g*(E4;vjJy>$W z6miV>`&uuOlmTa%cwK*7;7tJf&0!#oIhEzoFtc9o$b_=KvLVU*pkd+Xqif1yiJ)F1!)rRh8O z7OsXc#Cw>}%n90-F)JRNeP3r|dGERPkCMV45oFGK`Q@7pv&ah3o;Gl0g}|9^L?BMO zy;i6~KJss_hH^|RNGZXqoA?FR)U|r0XGg0gg5Z~#L$3<{ENTdurcs|LH#w=_qtRYs z6=4*nx*81B9asVd2Ga=LR1UeOun0u*m(2!-aA*yiBj2A036u{+h{(({ygA_{byvTo zpj*J*{H51cp~9b;DEjf?$somXE!~hPI&q-fvH%M+I&FelSAO_Bh~U zp2i$_)@aj+j`j?t2V>(#ZQ>pscGF(Zbckbe{CRVLV2nG8Pca-%(8Zgd`GQM6X3 zXLc}Oo)Du?Gxhl^_PaUuNhF^v%Bp9`$;2dsKbUiEh}FxC-tg$rlE=Q$68bQfW%ael3L zCpAH0-)8U22goHh1eU32H|_9rCg*C5?s4R{=RNf)c21r(txMaKp!27hqC!;$su8{@ z?vychnGbR{GwvK9qK(@6o{@k*F^GNCrQJaLH7jfMs0HcdIt9Y4SuwmhVK%XRd8{`~5=W5I{~ z;`AHy8FgwGEl4~%T>I6HZ)pQT7S~$L#_c8DcAmVyK2hI%dDfQY`O^}FkIGgd{t=q( zQu(eSMhBp>%EA5JrO@07e270g@I7g|;L|zK(wQSh%%Moi zG633&K^F3<`?@(VNF%hRskUDGO1s}hhdv2#L*=Qz)L!Pe&%izc0KLGORqOhG1|Lk7w zNvY8E296ot7k^$U>?QfoGd_xv35Tp9-(w%innrwdM>Hg}H@Tvoq8@^<;dSoT?^AuU zH69AOhTU@aRQp9ug`(o(Gq=(R=RLM#>gPsKP#M@qj)8)BR>CRCBVfNG%fbTtpCZ34 zQ(P)jmGwm+8tiw!a|?Gnj;F?GHBdA4QQy>1pY4w>SPvAfd{L<5yR?pm?nSI4BPqU; zHdhmE6vZ?$-ZbBfv7(K|r9?A1kTkndB;1W%K5?V$3sJlQl;oI`Fhy?_QExX;g9IK> zf@4K1!9tUPr;Jgb9>*x|%fwa3)t^XGn@fB@p`+)HIKcDAo$=evh5_R!M@#odvYL*A z?%|5mFaJ;^WSnp>sftPtMBXGc^NQl-Hynf)qX}HvwVR1PDX;06+-(`TK6UtOH74S2 z2ra)9YOhMxtrBYOO16K-(|JQ!(;(@|n-peU`+l6W>L<*Lr-}S-ym^0BUde`5E%Bn` zQzO#&ysA=TKBWdcN_i}sh7F;n`wsW&aPv8hB<+k{Ta4w{4;e#~1UFj6W2yEK@Ltnk zdH}jj;KcxvAlGDKB#(nfhI$vzgMf_sM$!1wS2UlZg*mN9a|jx4O5dAse-GYrT5y4Y zr6Ypk7C=hi#Ryr2mCCSp_T;_Fl+_zj+?w%=_%zJ20Ft!B27``$8yC?Z@ z^v&BHEQl8k4@4nU2?YXdY)yDd*R!nrYdHw<*ORF5foEA+Z`gBAIjI0KeX(rEWFXic zt_HXgi^FtZA!v5lZWF3qI3gz;5v5KZuV)^AdY)iYp72Z_uV5a}X5J0Ce95LfF~fYB z^n6jze7Tu?r9nX9EMHYFUq$YNNIHc4BZ;En2lbf`0)rnU-;$_US>2Z55;nJ`9yGs; z`e%y;zWQg2^>sifa+Pf>K~9*$w@rmMGlh0%h4#!J9pyec8-8^4{OF$k(X;8J_smD% zvybS(k7!dfFBHh%vnXulW29I?BmPMNmnxaYGVpBB9El^bL_vNllbQ+^S`6m0L-KSs zKRh5HXfq!^7#835EG|0BFK#N9n<-Y;$~4C1V>gRs3`+zA3tk8WnF$CWr9T;vQ&ysL zft=hca8@T%&HyB;;}l7nLwWHzWqTm)T6Yn4y@>0j>2+|a0zGAoeRco}q0*7vCl@hu zw`@f-2a!nqWY-wch=IHpd1O7C`KNPW@DGy`OxerFAXW zG?H7)Uo0akG^3%XvVk)`90Rq9f8O|-r6DoHlcm#nRHr6{rNY^(%vGN2AepjOrs?C8 zrXuSmbaQiY3G!7@Z4#(i`1Hm|7+FI`Gv1@AJ)>!4tC_CS^ZRaHcXL&iJZlaM*IH^z zVPW$qv{eD`(V#qw{B%OO*x%UG93`GW+MG``*K9S<()KvxCSPRLuso6p_sl0J3;VIo zI!@b7vrb6KP;AeUMb05jZlTQl3DmST+`)jBT;D$i2~Q-x-yD6bMUak!R(tW zuP6>-!dc!D$=D?)TMywRsT=#}iCLL;R^Q{29P`y|>{R&PIXKe+8}5dbAYb}K=9y_`2vowWPOFB;m8LUivw1ab&1$q@!^t`YE;MWeni z&%Yd(bgWP!|Axi$X?Hg2B2JXC#CwolQ)F-l6=VLWs2D7X2ceD!VCPu){H`YPIQd2n z9Ir!Ja6pwThUk+_AQ{h%aA1|lEGen2w?R>M;OJEEPvA`_ zh|LOZDkpgMbH?oT9{x1c70J@O9IVowq&JKIwdK=jWNng$s7Lh!V-S8tBtiQ=)0z3F ziYZ@1=}>mq%SK{gGBiX4A`Ac^Dtw5(@ocyvf_nRtrtvtBV?p%x6!SS01 zj*)O9Ngi{N{so}7bx7-WVQqWl7ich{N7RObQIiaoqDbR)25F3oD0;>|caCKf>w*Zy^(`z^72P|7?X{g-vdJ&I0h^SJ z>65aXGb&%DbV!?soTg=MKG)~WK1=soM5 zY9dj46477u4q03b)o7Eo&1NZCe8yU3&6?ueFZ=mbRuLq*CoWv(m+QRbeW+!`gS$~m zLw+XfJ`Zs8{vZ0W%Q-vi@1J!>KIjX5XY3o&JHM($Cu#hNQHb$GGepfEiliWC)cB*yH{i+Uwiw~|-roy08vvfD0#;Sl0Aqo}XCDbs&Tx=2Q) zfDKAwkG;ge-JSV8_J_YW@K*>TpsWCqc>VeTwbzEVUPnmZzJ1c(`OfO?>suEO5VqD- z+oF4a9{iHB{-v-KuY5~Zw0(=EeHRjoL+t(eqPS1Iu$2&)s5dI5|L5pg#gW+P8jQ%1 zc53(j=z$GQpLx5~tA%ZY7aNu@df=T+g;@vdZ3leUWs4P#@9Q0}!8X+W4#h_iQWa_1 z*?)fsv7WSY=Y84;f=h&q?#Z>EgjMWOaki#Q{q~EU-HmD8pXX-qITcSheabPtn)NsO z3j!Z=P|WklM@Qd(U7v!A&w%5)>o1A&9ubG9G!{C!OyNq06Ywxog`T&TO5gY_cUkB%7NxiUI_fc7HLbT{rJ$AX zp=b_wcmA9U>~jh~uN}1wRiT@sr*4>6fFhj_nI>egO+H zZhPUQtFDLKG0Zj)IxA-Xe*)U!P$B8*4CXcw#f4ZaOkfrp(0rvV)`M3v{G)m-7Bm32 zdcp*#v%Ir-*gpO^%36)u}+i2c7Z_`@QtgxZ8CS3BI2?;T=Abyh4p*S`^mXS3n_OR;lt;5CCK=u0;tQ75)8d zaa{Ob+^bADDYbesBl`#>Z)S6N`vIKE>EOPW*FAgazJ1QOM_BsI{$53jk$$LEyb7Ri z@Z$4&u-}yFL{j81CF0wCS-PV>9)ID2Y(4MGq&wth3Up5*n4glT3nd0i83uTt^nui; z%|cmp6=bZ4k!@^C94rc{-6Z5+?noQE{CHJw?6zJ=QvpUg)g2g zmB^2Tw_)CY`c-ba?>c`fE|4X}{b%TQ?c!6)ge3ah`z?bF<_1t)aH>C}|1#+I@c3$u zb`PafoUBQR?CUhk!p7Gb?|Nk|-@E;4w9NJ+m$S+ZUzG7UQW(dPE;a-G!M zCYlJB>%*pkypM158m@;3otaYPgYE=iQ14W@@;3O7lrDNk?QcA~L-RQ-o9{1wWUp-g z>DQtzc!0lxbjK3xjf4urlQCc20CLv8hQ7^2@ff`iFG)S7{1?-7W9r}LW?@oQz(f(T zu{JRrq3-?ckElb*7FEwmO*NF4Vqzj{@-H9X;nqmLAr&8l+I4?AK>Q@fAAYec_%XhJ zMdYh5+=`x7yK(4SPQ0^qrskRg#qbrv>HY^@Rq(@p&1a8-B9Hg-mM&_*CQtBA;%z)n zBuGAK=`-U(zxFdrkZmX#c8wIe0AS7oh&1_YUP@|tfv2p@`H&vUZH{00mG25 zz92C${fz8bWy^uvoLZ5RKOdUI&^+WcaY-q5{o%PSWj5*OB7Mq;4v(*T8GaTj_D}gn zW3?i(e|@mJEYA57RaYaxLUmt(Q|l2fnA1l$Y+YteW?Y;r=hR6J{+QGCvEM?-CkJ*7Nq=0R)jNO0lbxl4lv8>&ft=Cr< zE;Nr1#AR|JLav01LaRPYk1n$=Hr%0FzgR!xgcT*0*QAoz%wK+I7A9>7?7Bc(u|zi2 zd|>aYR}=FO=rKdwL*EwfB_iH*p7!u{tz6%)LZijByk@HGuBVaNyeyPRAUa!YCo{S;h5<8|=w|X~;CcG~+E>6#=RX#0t&x4rM^D7P&N`S6I^A0SKDh3!`<3wgWIHtoYQo$myaPoWfmTSi zQ|}-mFi>aQ3f(-W8}>y^7Wi$-UdGtPbEx7&(b?*Iqsw%2*5mlyn&LMLeE6e>ME7Pg zvReeNPPCMEqoqOJPsj)A zyYKDxi#+MvuvXvH*1xmz%*|EVMZr%1;9LTvZc0I*uw46tKn;MwddOu-(7T)c33oWLdD;e2N$gnUD@2ql=9Ov9MuFOW5 z(G4X^aCO2BK^9QmJ&>vqff)*C(g>Z+RSiJ+o3E2)HlWRmf+ckVjd0{!alw87vA;~9 z-!An{i`&w|VZt;ta?V*vS|P+8w@tp@?vzl4AKu2863KFA1&H<3gIZqD)Ss|~|I@k< zz5mg=0RNXjhyZOELF;-#iUy^Issh0M{!sr0V1NkC$_irVVKK|-e*2Q%3P^e)Szxg8 z`RVU&Uhi<=gp)=h%qXhQn6e(82}XzocuNMDW67+MMCJ%`JEkyA8H$=mfQJ|o|U z^TcRtVjj!3)_}Y=L*<1vOKTL@$)twcy{9QyZ|6 z@AuX&YY}tZPl$S~E&g)2^l_ik^1X&t^^)gn$02;rCEKSxof0fc;udWU(y(Hu!pcQ>x19I4_+AE zbY%t-Faf_T^48{t*Dv}vw86wO!I48ki;|-uk@ve)KA)*5?m0gw^ltrFqio{@9!tA1 zDBcWguQ;Bi^Ij_!dHV&rjqJPx z5MXG3lX2(OL}g{IN4Q?0v4+>v}%&lm(Vm1=Rle(A8G1Jnmkxm|U@3S*an2-3rE2 zUSB~`t=g8+)os6P>f~a#VtMp5dn$x6N@FPsWrU=P@-|owAy|2uwCw(P~j^RY2bYxq%;Cf4i1x`yzX4&lx3CrcA=3n$Ob-+aI zXUL#WKyk?7vjY0dRRAjAtvPo+p_~CqvyMM@WxZyQ7dVbGUD#sWL%|J16xT_pu$C_rhSgOWF`&eNf#E@=HzAE_Rej*C>hM-)JzGF*`I#-=* zT^rBtzIq}al*DK&M%c`ZYdTM{0yO)dDa9IZ{ z96#1p*m|>v6{_OYp2WH2e{)ga(Oa#!;$E=eN}=F_QZYB!I5`=8w)ath@*zkyw!p&N zAMn!m@Gm&Bpm;Mx*qy@fAuZqXMGgCxoZ4yaqJik(t8X`pJ20kwY)FF)g*P}4b||+n zUR^T(CWt98{QC4Wq1Alc(=FVT)i^6Ce)5@PRG>?RhqDeIfpM?2@D_O8V?Rq_&xwS9 zV&4I90lB3UhzFLXB}pc?B%2rFMvUN=m&cj4#mZ_1z-xXuD!4))5(LrW zM8l&4w|=BnMbrKL(Tqhxnm}4x!x=4xog|Bf@oupiTShY=g&8njgj+Sq_j`;7#qfRJSz(q-98N?9 z<6@%GxODd&idPXiwEXj)gn`^R04mml8?C(Fu`GDhsqm#f|3^mRW`qlbX)8vq#lttk zr2sEUqAtO9CRT?wK6Kylx7t^(VwW93!cct)OGFRdy!-cfPx^?jo25(5Kk*Ig0QoI& z&Zl3iTn7hMNg};io-5wGuZbh3! z?9EU+t*HwdrLBJmKQ5xhqFnf2x?`JbyvjcvU%&J^3y(fK0h62UJCJz4PCpDXNrJ$! zC>KOoS{?6R-H>%0l~6LRG}y%$%sS)E5ae)R;)J*d#fR4e`_Z}i?=saNZ@z?LSgztj zX5!ro@x4a+zmV|8-nifEA?OILz9Q!`?fh*~hik z_l+j^l*u5l+J~m)pXC;v+&G!>zqd~jb|$7oWB+7&%5Aiz9*ed@-*6?0WG1MwaC73I z9(X00qa-Wx&&}(6>07sTGOT0ov;h})=D$G^p-4$_yN&e;(-TZ5l}`+j`>M zBbj3o50gf3w0yPc`T48mM{XOgr+y5G7LeG&d#rJ>F(KyU75JRl=@<0@zoV;LFb;s_ z&7BC{oi9Z$e`N?qS^Y1~wI26V&1-A5BG1*=-IPm3v(P#-QheyVqr`zT1}{ zX!)z(DEy0|w?Ua#Aeqb~95+}v-bD~Ect&Nc#g8Q6s<#=6 z`wXjj0{X+cjSb#l*2eC<_{VsN6W( z${WM-6l>htdE*Bm@Kmk{oL`;S;S2I*ie485{an3OdKNZIO+W+1i&)2J2GHiTVNx`_ z?oKd_CYqFm-0}o7#<{sFtWv|gdz&arr7Jf8>GaHVFFN9K zNf-3{b@aD$y4zQVUESjP=t*aQm&W0xMg>|pyw_jXYE{yF(^Xfp>FoWZG3$z|U)*Ru z8t2)Hf(&;^GsU0%#ach=pV?33m7hli0b!1V_u5}#Qf za?U?(Yzd4_bE=vK8ou9A1#!5cg`sqaB|TnckWw^rc$;v3j*8mjr2>rEwH_B9)mR#? zONR?wx=0-FL$M!yot9ZmLqD(jHbMo?wte#_D{)jzmzYol;%k<=0dYOCOzrw z27Uz=FfrX)+D|G)9>a9<5wz`{WYg<*NL5#t z&Wy-BkAE9zT;`#!(&+tNBCf)#>Gw_k)s_yLG2+wV%ic((qy3fd*1yO@! zrTe`p3)Lmw>Uh5Ib1~WrI$?n^>GD5rd(xcOvvnn3millsTWL33?Rc^r26qVlr6(o? z2V~;2$ka_qzbJjf(WdIl@Ktz%JW^>l5^W(#CN5ofCws)fNfPow608;WGxU>ork;{V z`oLh%7nsz8HA5V5ef=~E4e$I_yZqU+B$**70*R71<|caeG@GY+^F0^j;EmVMO$;5` zJNmSK%gKctDgyEC0mWAstA9s+ig!1u&ox1!e|c;#y4Hq(n(vTVc*z%Q>dxs6PxLs$ zdhdq^iY-?l`uaiy-a>SuFB(U$0)fvixJ{D56iYlPJ*|i%0)K4zgJn3AX#iT+jaQx_ z9;Gqa8vW>Hr^tLb5MD9KQK(#b?D0TV-p({y85#{|qXnd6rQqZV`cSqwz9ThQ$2tye zzB`v_X(cI7E`_Ub6r$iwX^VV9qfn>-`oKO9p4Ce()%`F%uu1d&Dn6QJ9t_CsKUZnu zhCe>CPH@-0sJ46Y^MmOmK{{=)zbeza5Ff zEsuT-?{X!1cb)ouUc;P*yR^oWhvIrpcpGM;=YjihS-}0J`^RCtj z?mVZjU&54~cGV6xi*tlq#DDp~yOuehi#S4Imy>w7{2Ox0=x^QRWeCmE2m{-w1)6M$ zfAG2LkGB5e0Dbe#T#sQ3?7+j8DR7fFLPIH|8GNXk9MnV{-UYBjgN>dTX~QMgt7ye! zAq(i+8k`^(0iue&LNNbE%peABNj)cQSxbyPROJc2EE7gEceG6#b1kIA zg`;5hSNNP$`Z1(!D#Vh(s*=OXH6NK5qY`0-UNUyLZe2%Qd#_dT5lxoXYU?QzUp1x` zFw~+k6V3{NaJ1mp`538iuncgeBFQ@c)89APFcTig!A8o46W76w9WFJ9LndOmB<7JXa;F#MC>Xv+4%k#;`khSmPiyNkfKRsqh#;A9c6R&A!E=$CdR)cenuyN;YfsliF{~7H^_t^k<~+&uL2y^1-Cc}+d0fJu9t=azCmila z&jF7YuXCZkN7+P- m2s|xn|fc|?R1=gj2>)YRG8f2{i|J4{3+n4GXU!WipU-8Ny zW7~Kzo~EbYT(X^}ePUAUd!Ow315e-gt`iY|2fo~0o3_Oqu-g)W0cbKP^&x=+*#SBb z^34DW495Jt5iVo{l#ZepEw=2~q?Z^v<|YzEagh4s2XGqIY*S43smc?iH~Rs#5|aAR zW-3_Km??`mP@jYawhi5W*I9lG1K5P)h2@npHB0T40e!Umzx$AKD>i2J^{PsILzo(c z`9`YH4BEu!-=0*^X@ykx_o1DH2g6eccxKw~vAe(f|nH9 zkgyRus9M{koD&jW(aOq_3s>QaEp@LJvq3OuNcWyU14tk>?L~We8Ro_yiDPnKVq^$F zaas29Pk_yXuVnpa3oL0Y-Z~o(UsD1jAQ7~wa9xx#zy!d?q&C4}eFY~3TZ_b70CfdK zz2apaE=iXR1O=P-cltHRLHXem|0s(u zk|xBAG5K>T2kX)hf}N|J-Gmvgvi%4Skm!QRIbzr1M!4uF`4@MXPb(P+Y>{pGZubq` z)2K1TTjcpWCuKXogIO7U)qpE4i7g@(VXbfeY>3q=b&Xx|Z)~)7$fuu7BYx5dlRu~D z0*i>2i?AU$s&*ckC3Rc zT%CIq42t6{QuYV12X|J>_DFdSWJHyq!bI1>^KM5Dc9Pu(TbZKBQP7KJjeb4N*~$xL z8(m@0n~G=>W+ZTy4#a*GxVC-t*bzw&QIkcE-?yC5Wz=J~qf$~8-K>02f&S0C+D8J^ zoM()jS~Yf}s}sb?n054H6?w$pd5-(mdlF829h=pv(oD;mOe^R1Jc~+WGO8Ay5QLeQ z;#r&py<-ejwG5Y|2FEhbF$SqpQ8X7^s-pt2x!^=~l%f=3ca=ZCtgywDQHu|LV<~+h z`!7beZO=iS)G|HMCUC;#!!C=H(z>v!J^e(Tt)}IXlkV&bWc=qRcZuAhpLzzl3_Ov% zW`qdXp2x7Gqun={uk!;0x<@nSkb9!{{;W@VwP!vTNU}CV-g%LD#!Y41+d5W&V-7%9 zYdC#B{K`ekb5AyTLi7SGq2Z)*yyZ@d^m^yulKd@NVd8#rN|>M}SbxGTB3m7aei0iT zVOaCWoJ%?MySmwogm;-rDm`hRT8tzznwQ&`%ekT5IRm*rrgl%f0_OoO(G;`{=`!rxLxuM+mE6BsCaBQwHnK$&}UO^RaYQyV> z3mY~QYzQ7JU4i-Mf4t!Rp`vlvMgOBRG##wJ6HZ>cQ8C?}&zn;2YB}s8*^pd9&sc38 z%V#$GPMPoM7_-k7<<^VGr`%TcDDArnyuRo$U)!SF;7juyW;e{E%*HWSRW$m=VD!Kg z$>2`*D_Qpk!q3G7vCP$G_9HhpI=>FU~%UH9Q>umET+A z`~XrPCm5Tz9@X=UZ(7jx4Phf|USoY}z@~J-pyXDzTM#;$~LcHhH#yN+ADsxrMuPO zeOsALdawQwn%YzL~uy~SsRCMEgGA&>fT-MvHQ(Eqsrpb)ay^` z4D$*PRNFA)iaM~ZY>!3yib#46b@cZhnb_g6pPSa-77bAl$L7_kS~2%Z75G?Fpy!t1 zVUNnMS56al0hX=IF4OTXKgb0SRq74}Z9Y%kOJau5nxgG7fId-H9`!QwM zyixAj@bdeK;FmqoN{g*=MKt*Av*1)!-L8Tsqk2@Xv5jh}XI0Jb5ZB+nnx4<`?0GzY zipm2jGtn;wNB*h{{aVDmU2Q!kgix`~eqcu8Uj0y`^nS(VUGU5O?(;VSidm01Ud;V@Ybb0e z8rzD(%&6|asK;sFZ1IFY^el<^eR|@xgEN9ftzLN3kRGOy`kBGL{{sD(l$DLut|=n& zI)O|#ze#5z)^oz+^P+Hol9>@cv=X6?^bF!{=jDZv^CPr*kv>`UPuNcANZl@{>L`R* z%m!-$Sa%{{t^{ zb@079<{KA%ZEGzdKdMTL_K6xbVm=XkAP6VzXvh1*`WfK8ryAZc=6(l;3;T)Xh=_wR zqCyN46dFk?vaxH9g((-J&$LdF(W23bryZ&9KXf`Kx@)o^~~46=SBBj^?2_Q=Gt|ViaF;Xjge93@c#}z$A|f#zqYbsM&}M zMw|+T2}!fC5vGc1*vGKt_>(T3Fj06hQDFZSi6Qxa+4PG^5s50YBq~1m$Re%6%h9PQ z4d(S~)N4)FwC~ah+fhbps;EqWwSL|w3eea4OWSL0b3XGnX&B5`$Grid9%QDo0rPDp^1dgOs~N z*5h7qml?FIh1yA#t3X#>W|78O@SqgU{T`C3(Gs-TbB~ACbA6j>*l9k{_u^f8F;0 zpIZh7!k?q9ezmJ8nIw3hJG>D!`qRYWt|~tfBhs}drT2~1j1W81=VcM&eeTOXvEm;V zk02hAp)4U-AOHNc(kDgO+D{UIpnJ+xD2?2?B-@Hj&U{jW$i?oxpH*i32f(oi7Nzo2 z8ct3#Lg~yTmNTgoIhP4s*>bO>NtB-6#YmmelXL|~PV=Yw#Uq+W z6=!TJw{;hO8tbLymA;oLTk9*kp+soBz9&qD0Psvc$yDI?SCGn9vOhA{^~9kZyAKBy zP&{wC0}D$Bf+6BXa?zOb5a;T@#iS6yUK!=DSLv!Ud6zkP8U1p3{q;taxUs}MN@&IA z5gR?~2BW`COZ{~vp_zv{N+HIbi6hZu6J#?n3WMOM38(5p4BTc~oU{|drlAz5(3&?_ ziu1i`LMPF+{xPJN0cMHfsBUGmPA5!TJbp)T0g}j3OBsnKEyYA}w}GEC+~~5{z;u2n z{_{{y6f2U#p;VG9_M?cRDS;w-yD6lwDY6+6P+U>poaEPwACiudfvAh?Ru+gb+(waQ zAgey4j139Wm*u?~B?hEl)v86_nxZ!>ID5yXe0qXn0y#(}9^)H$Wsil62BRttb3M9s**O}{gSPhF^7W#@}ulL@^bX1 zwD5-Y!y)IAfcKbI>CJIjVEjYp?Wq-7%1leLqUjS0hWN8v82=?TK4bDcjueZ_sV7AQ zoZ&8LO`LT)tcw^e>EN=5dAm35|MJcART0%s_aNfmM8i_<;{Svn+`Bxn8hNp9a#$c9 z{9SA=i~ylu=pV#2H@ItfsL+=(EHxg6p#u2Lv}B|&jxlF%o^>l|{D*E5?-$33D z|GE4#T;tpO`<@k1#k^wh^#w)bWrEaM?ej+=Vakx8v&L8Z>GzcYxO65;`9A^8xHq#> zg$#of&y~)yQ%j){c^LjD!@dSYryNfylkK3HbI+iLQD*lG49}0Yj^nRr&0LnaNAjR@ zvrSnNmRnrN>O?%OqDy0*EHtiHtD!J|=OVj;VMR8Wwp*uqr|iCxFvkjLa`{bf>-64` zAWKZPK6HRI&b9HB?QrG7`yqutUh;n#7T#b!D-m`@RgtpOo479_@27v!;m?;Z@^#E| z25B?P2a1`=-qwK{`Z57p1zQsRpRhoQ!?|J`BYyWj4!aLM0`CrHp+R0>UJ=_fH}?jt z?id+hr>fk6DxBe`nZ2Qw0e<7ljid=5$b;2Cei{XvfirenXtx(?O>GRX9FD@83)EJA zQ^sB4njdfHfDgl7++hZU1dg06GAe(=y5?eR`?Fa`@mW*bDlSkg49(l8nJb|ev)JyVW=R3&qAWM?1a%0Oh@w4lDlZ3!EB9;j0fa=bo(0I#&vvQ^`4Y7liZ`CQH3p(m4v$n+=GS<5yS zeHceL=%XcAV)wk!oqT-hy<+R>>6pxG^3LkA>yzgKAiwzxMd?o*XUN&|<&P) zpKgsTFX_E?eLbJ6&Uvo;!th|4a%f&BJ68TmKl-&%?elIEP3Os#3R#aq%H=G)!s%p`u08}?u4%Cr}$jQ zM&sPiZ=qnP>y21M7i2%0RF1b0)1~4u;IYJJ?FI|7iYJ7>Xf!49T;GoRkVmoACCMWe z6V@Ci*ssz>M32A4It!P0hsyGKgFz$~W9l5fD#y{=56^v-ON%f$O@DBPigb6y|Kh1;loGNjF@HYbr6@O(Rijs3u_-gNAa+Y|m2H>K4ga;qwO2fEk+N()0xqR> zKs!|T8aLe_MZAucW|MnW>9a5?681F%Oy)rGj60f}`X}!77F0xjUc+%!BLxS%XRx)H zVay#1iW1hPy*}4$O*#$CHYWJ(OP(0HA5)6iN>CsN05~O>R-Al>ZLv}uK%$uAXf+tV zj+R6r43czoX1+&AfKlEYEG}l>l+BlQGJTewdVzH}$#FnSO$SAKA1%}fjAnDuBTy!Z zF%fr=0vW9;?Q6yvj&}yKxHI5P&&&i4LebGE%H3!T$K!Frk>nPCY-2DkQ{{;XW~#L7 zR{-Gxh~*5enA+f3ualRi?iZ~}#%RxQKXLTY63_n~)iCC28(2!<3Cvh4aI?nhgp*>I z`c?YwSTp3Wb6XBUuFJ*6*|IYk5d^l|`mrBgdRU*;KQSgG`GnF)UspnSBh+`JEAgV{ zRocgBXAr|ar0+t0)f^Zq@%6K%_^;-59rW?_KtJZf<{QZf$=GT4$<1nA{o2Aijh(Yr za6-JlGRbrQ^jh%yP@`|iF>xPSl)HeA4TlOvp|}Z#2wL~GF8gx+(HnC@^yNKb*$cUu zyhm>swtoq=aw(6Bd&g%IE)!!#oFt#DozI)EgM!v1+(*5McqK7)M=WFB`oW;1l9P1N z?guA3JPjsraN!gQ6WS}h(X9ch-8VoNop#Y?6if@!s$GakE&x>wy`b+>wC=~RZj9>INoziO?voh zjL3+?cI$DIzs?ATl{#Wi_xiP+Itqx%YXjm$ zYGkSv9GJR-WmC)Ty{;0Jh$VaaC0jsN3yeaV@``{o-xp&9g73c7TQU9s3fVO9M~grC zQo9;6$kt8ZDV4CEeS@5AF)^A?r$1rxXkRZL%OgpOuZzNo@vq3KCy*@eadKb&kgqjs zqK8BOmW*Aic;l0ODD!R` zESVa6cW&@+KI2Jg1%e1A{L{Giw@*q~uY_RF2s`9)dY4K$q10bv+7<`z0tiScG&cHN z%^)_lc$uX2@2r59r+1XRG7N$LVE*Jw4yhFnPiyO2ukxHB^<5n>D|+~}V!3GdnoYbm zai#U)d9^8IgH-g=OTjy_WoCN-DHT>{S#{oo-OcsD1l@exW)A9mU-l~?QV##yNZ`Ql zPrukJ*4RG}gPt-K6}!HdT_nx$8@>BDB_TT@e;1Y1saMXee(yEjH*_4Id-#EPPMs+26N8cYi8d|B233!WMcW&gzv~b-8V9!m&eO<~Defp2I(4o>zZ~^&&EU zhtG}$MUL|;k`ETJ5}fy7Zcm;?-u}i4Xs=$;ep7<|^8#)&bgDswN56^Ac8My0e-lEt z96SG*GcT4iaM-pD*$@$eEBdx_2LaUzMtqKU?Z zNl!>&=f`*H!UVa;u!VWh%KU}O5kaLlAxLnbDU*chM2fJUZ_t+Y2+n@oMtYt}D&hl^ z1Hs?IF^l>+h)le-Ok%REw{`P}^e1HIS(2hr3^TL1+*w!DyW}DwFo|~3*ADazN|X6; zN&*AQk8SW5^KqYrse-(yEPUuV*(oqx+g~{JS=~>l2ZXUVJ_yj&6#du_Pl&SClQyoM z(yNu04u@n-m83|7X_DiP&T@Og0un{w`Xc_e zL+bQka8Xt&Usk#fR;E){Rzud;D3Tcjn*jEu@{Z2<4Pyta4Go5pvz%ukG&?wSMGUbvz^+OB-fXx zsDr2Ml&4aZ_k}NSeFtyzDQ~+dU!EwuxROOnSrJg?oAl*>-NFC%lz%}~V8vHp!;qIo z`QH1idry4@C&wULwqzJ|67$a!F1HRL&?4f^78|agFo6+_tAmY5jBU4;{#uE&3t+oX z&S4?Sa@!$lkS!`8CU%)6B(WqU(<$b5DyAuVkH%o(Lx!M1jzGF{x+w3@krPBs7Jb}2 z{ZQuTOjgpDBbY&vT^QL+=#mssVz_d_%b!?aLe%ie3tZR4u@GKu{(+w9mQmgkg@U;E$ozea4ZueOk{~q*MSCtj6BsB z@c!h`z7}~)`+N7Hm^|(>mp9g58fEmZ#CP(!pOSICNkNk&4C_IWURSd01CZZFUn0cb zw~5JNa&Ga&k(l2)GQ`jCvrs~|{UF^+q?Xf^D#EJD&8kuli;Zu{A7fU6N|w3K9KMAsq&W=ts4)C>5uT^(M1M(%Z!wg_V~4 z^$qNFd8%|jiDR~MF)sn+F^Y&+olgB&J4;7hw_T6a;Cp$lzKp~@SO6Pb!T>|6p>|9Z zJx0=jg0a{d{xMc9@;^b%tj{gT?R6M=P|;tCv8p^WKJ+p;(bGN$!%7hZFgWPs40oK& zXkg9|Ba|mcvp}BC%Diez6OA^(JvV7zF@J7g%9LxWHgEb9`$mEK-u64oS_*S2^Hw8s znOv)nE9MkqG~|`gDKyPg)Vujzxy}F^+#MrMJJS#<%N!*l)Skglp`C_p!iSlL7IEgc z;yRPd>U2A}cTvQPsy2TmEN;750Tbh=RA!C11V4oY4M9-4K#QF7N45cS&s?F=nyc_J z{5w$iX}5{kg_Bf1tE{8}O#sojV7`s3=~6!#HFk8Iw`FC#z2H%Yo2H8s^^P#iyCWrf6blm(Ua}8Cl92g$?O2@ZN>=HJr){YpL`@3?DaHP@~Nbmnk2^f5tJZE z&q~6CREkUh#){fz`hafoG}A>X$1FbR>%3+c}HeYS?Vns>8RBfVb51QS~+np(YH4muBtG+)*9X$x2| zwYM!0aJWQjw-F2j$OcaL8$H#QQKDq;pjScW18ZRt=aFFPm<$i}QWcto62SCScwTLh zbODg*mqeVs(HWl6JksIH#xV<~Pi=Faek{P$m?~n)u-JT{7U69W9A>cU{YLz|L$};p z8nkV%r%W%uyqV;7ftObSz!y&!Xcl%-p!ewNjoFoz?qysKt*_%cqBxkMTPbQB9i^&| z8+nx+RuFl+l=ekBc<3sHJt*n5UFx|o5wb8A%o?if-CD<*{Cka9({!)HEJcX+Rc2v& z!CLw>PR7u2eB~}tsS@fiV@;nGX4IQ$dX?#@WB0unIj$lMJ@>uM zaJd0R4|(TAUe3#hyjKb_QVYptGUwN!gLb1V^}uNYe@9L;^Amz!VzzoUsZMl)%+YjR z)K3ac&&?Dy%nYoGFr^6k{N2K+Uhh9W>RxoS!tj`9MFr18WNJ5b8!K*3(M10ONjv|B z-YC=WgrpJl<=^)&O6pAs_*>eZmrJlyfIm+#tdutjr0s2F92CHYiqdlObIATvzn;CN ztEiMooD42w5idO7P5l&9{)aT*(LCo>Q4qUqQC?qU37wKis10r?0vd{G2$}4vNd8M| znPyI!RrJjCacPRQXO2&njjX)=V}uhure>tJxu;<={1GyK zSq=3JC6zKg+UyKf0v~JJ>D&Ikjid_c%v*1>r)iH7Zi;zSsRw^p*1Ab=%Wj#=3i-?7O`Zx4Mg7ww479HjT<`{+%D~6WskG-RG zecu_N9$`^lWZFU3)Jp?H8w1bU2W+|-Lf-d`6c`N0dG}$?$4N@%DAZ(w7Cye>3s=`; zoV1Y5l?Ydo`3IR~s1*@WyL6?mR+3~d9lP!CZ)WH$>zhpL?;N!=J+$a@6jR$}%kkNq z2xII8hclXnw?&mo+mr${;Z4NB<*gMOC1TU2fn%>2=Sb~LGJkGN(-emQoiku z|6;z=X-IWC^=qrT|m7s#NdB^=r&p;K(C3G+rHA7`t(#6jc!$#i&8P z$%+H9qvRq39JCPp8Vf#UvvKl#c7JAlmd5*lWiI&{#4hR7uuxQfGf00e2NByWGZC_y7bb16db{|k>|NC54vjI- zYF*k96R?#ip*)oSi#sEtvIamy?`)w!MFGx}OhPvDf#?CMi0x@6K0%Qww?awwbL7VT z-EFIPF%hPM;V6C0yrZWLmYN8ZX1>eod|>Mb7oQuTl&j ze#sawsYq44-kiSkWq(Icd2#e~;5FD{H{tViQuK3q!fIr4wT>1-U+ab0j~|~ZxsbLW z2bcgC!c77jd`@M?qitG_Mv08Diu%@?*1mWedW>NlW%$|mGM-6X%TodQPF{tNECuU&Gk`sV{VAp{e7NyZJy5y^SRh1J- zlvn{RQRMkl8l&9*6VQs~lSKDs>|3GK(o&f_|Jw_#IQacnVack_mfLeSmy4-X9~72bwXe=9baGP@>vYS`cf-IGuw3z*Jc{_tIfI} z^Shg|{aD5|?d00O4scI#vw0KeCfD=p(_q-mot6I7D+ye4CO2v2*i%-FdvM`yRMgqQ za-+qo^!s5K#HcI8A-=-k)yda4C5jmeL%~j1@i3B9arocgUvE*{6=kD;_W$18U@|^M z0NC_)AP$B)5fy!{T#JeUGiy{3i-QWtJ^z0Jt*+90g3Q5EwdkKJTT;qglwC4!%Zy!$ z;4sua8THj5IaKm!rlJ}XqpaL>dZ+F*;;~qU)d;pX|v<>A8I=0nOO4} z+C-93()!LOjgAP-d7#^L~_jqPlebC(hYu2rmhs=(YO?6_21XjJu!ROWWxx2~g?dtiF1o6&E) zUfl(1uMai7WuP9lrYofw8v)COH}%}yY5Po4o6>okuDTAMG{9?T+dW~=#ZOIH z^m4sgDQxC^-v}P&pETV&eAHnkHcj6#By)Il^6pBZ{^zU^sjmNm=j5ivTgOkS1&bUq z0_4jEVsH6ZATQ<`=heO52CN}iKef*(ym6A~ax{{=7=KcG!M{4-`ZHkD_q`Q-eL$0m z{4?UGyW_3ZaX+rVm3O#C>ta(X|;S2|Ma||1j+5%P;9+zxsc_3;R8cAqhVoBh?E(nPPc% zV_o?XPx`@Iud_k*1$*)P=e0DJ7eAi8Gq$_@97!5+wUeP2f$arnU+qi;4S<+1=rph=A79Hmn5?t{_o?Y9 zkt;liZnFaa$=c}G1IG{tRn!txLzJ?3F7};ajgOv@q!E0Z_&}$M=9LB#)9sR; zL|thYKbOcVZm5yw*0mGY7A(UNf8zNVsm=6rW^(#IY{ro3gXc~ z;)q20R@*bPU(UQ%BM(S(-(;R%pVo2p%?YU=Ra`{HsI8;$s`+2==q1e>H~8i?@jG%q z*qAk&_04Yx=M?ZtdSmiIv|#XP4;Fav1~rR~74m=MO?ootP)uIbsWYzVI`Y~@%dgnM zr{=aL>8-n~U&-cCjnpfGcizc4$R`ywGVhZfW^f~jB~b6+xdiVG`^C!7O7Gp@e)2wy zOYGS-C70q2-CQJ2R{>6*Bk^Jd+Mn0I64qVG5HPOZffVPbIM-5pd4tpC8n$S}8hnS;;qK+|T)u!<9)+^)ly78U`bN6^&YD-whv^fS%S&zXPCL2XOrcj9%b0zV9hvJ*Yl?U~xRXUG$6Gkhl? zLdM-Z4+Cb6p5f#nR5%;3KM;=^9A|n(8)LrEuv)*k+-&-`!ID7~ZT-()8>j;b?YEPd zaO5H$#x)q9FPb!tJ!_JRx*Vhk}JS%xNn0;Xuy>9Go#PdFNpii#nAH$vpgfo8=F=<^$a+G0Yw?4UXG z_>5;`7GH2odnY6Wee>Q}epfN=hg43;z!qXSXQB{nSdT7Q9~vsmCbWI);hkWyxyu#Q z2e|z5doK5hw9B4anOjA0J}T$>v(&4bJuk0Y?a#oof{~w(j`GPzh*7DmBu8*u<&J?* zzarMgc5b~wa8o}=>yM2?3}X2{jKrwUtM;z12nL;x(yLym�O>WD$foe1R89X@Azu zdHb5koDxa%5<4ruGk_E{Js*Rak12-g!!@D1#M-!IQiRb&Hv62jMlGj#oiH?xyE&UR zo*&Wv30{)M7!w&{hI=rJMv@|S)?}(9zt4SD2n-PG$zsM7!vXaDOFAIZx-%F5r<3Y* z$h%632QVcfwDi%qSyudmXXZXm(bXG^9)jYfdvkjt!Su_-QEI|-soyexgsu(dzu}w! zL4Z_Nrg#ATd{igXcfN|1#YIh;OE=bUd4$*zZ$#MA0IoIy9vq>TY)@<6cMvLJeH$SO zpyQxk*k$;FjyM!l#1NGfkY+FyOR{*H@hsKl`bHdmp)KH|EB-TjEwTmaR$-XxNnlveb~{w zUj}Y$In`1n2 z5GoK$r2UWxx>?z42>>Q`7Ax{`Ke66r#EB0f^b2G^5_tsxBTR>WwS2pD7MT)X?I&|0 z`{(pBu9vl|;d|T@WF!kDNcdOShpPmI@P!m>$_a=f3M|xN3j(@uXmXna4^)}X2ircM zw-ww6T)e_I56cmQm-mlB-bs;7SGYGRL@eS1AZaxAVOo8Jq);DD zP#4ND6D4FylC2Lf1Y8C#aR6_a;|iQim~^s+_@;vNx{dT@EdgVJ2TKAC3vD#J##7GV zX!6SF$r`9q4#|z9_wfbkX&{ZX2ApjM&NULlJp)&S0@#Wft`eNr4Er011<>A7&}i+t z7+@=w%gm%@gjA@G6w^jJ1_0CvKJ*V_m}_aYpn#4>v;!1yN{n}%iQg(9;WB{>nA$UG zB*v}l|2&QZPy}BPWQy}o$wfeCh)4HPkUZL0H~r{36Ku!KDI_Wpw>>fKDshH2DK6g` zn8(TJ#W-8B655*4Jkx+zuEW!N?Or zSEM;@;L4YzoMxzFxJI!Cyp%gNi8}?RoC2UzU-zcIg#v1sBu(@1Whl^tVvs}-J$gZq zGew_`Ai2;N9Iz$8*7~qHGv#9j#WkP)|62oWV<w1;VHb*Im=k)Wl#aKJCohb@Q$Yk71?PL?Nwi@XI!Wf&jaTxm{>!UvS%r>f zF%x7%M4;^E+4l$lp1y2>zuAy>qRlou^%0^^XbLWrjhYhl585Rl3zH*xoW;74!|^1W zyFQ!$Ae)o>|Ha$r4{|T5@{Ba|n4aXx@nkTM)1;ou~Kw6G^RFUjyb0epD`{_YihtT$=05~O2`MEEcLa3)ku7;g}6Kkz>d z!dn*x0R%~B1)dy$PwdQaD`DMAhF^(*c9{_T7RJ|ZBie?ChZ=EEW!N^@eSr z9wN2~cTq-_!cTJaNv?!RDukbi&J!J=N%y>ouGit(YsMc?=3%3y?+8fdHQ|ezWviO- z_4=~SgR+lRML#QuwEaykgn2^@%HPwKEtzA=){4qLZj|AI@F&_#M^St1=o3!0md^4q@hUo-FuNw!byB-=9Og9ZfK$Mlut&cfRa zLdT@;BMdCZ#9jzk-Cz3WO0W@D7eL9S59A8=CaL9&zsQWMkMa#Z*NNY+*1Hy{tSGIo zlWRlz zc@zLr=TI7EL&oV*2HX*%`~3{qwBaazO}{NEw&3VI0zKaf?^_5gny!JgV;8-%8q~wJ zw4wkMXak)ds@3q~1H*GTM!^Ob5CupI^6AlpY|;G;?FbTW2L`cB5^W`TN-@KgJ`5LI zP4uq2Sqtw6xfb=;18AZ$S6b~^;8jp<4R7;OGK~-dvXw0G&=bVL1&y|fP_Pddi#`v`u`u2A`LzhJM^cb5Kt zV}}v0w9LunP0AjhI^AJOBo_c|^d(K01zQ(__46*CLt}5so8Gj;-VCC?EWW-R?Y=y> zzJip#qQ<_GH+^M?eb0#cEBX4LYxlo!>#t4euW#&ceAAB=&{~NG+W7`LZ)E(n26|Ek z`aTL2dHdj!fi-FdM)?NEQ+Nio2d7g8U-SKcjNNxo6XE|a`Xvb=Kmwr(h!A@3h=7#P z5m5n=-jUvsCZL2CLJz%3M~ZX=sUjsHND&1Q5fo60fb_1CoA3GEd+s^6oO@?>_V0aW zc4qha%=>x2u8`YNUT;H08z9MCY5Os-PyGL(iB{|?;P$WhxF3}8amAqF$G&hh{y#L) zYak3k5FS z4)B$P4C4{~O;8tr#)SgF`qD%-fup7{2V4D|?A;8Kw45NI1(Q;acL$JEPC?YEZ>bhh zbi2qXF?WJyLXHB|=Ak#s?VT2hzR9_@i0;Q&MXwwd}R^0iYoBF_N%2ty0I zjg;0$!maLFozYHJ!*&3GbC34OmvDloQTH5nVefL^qxD(>du@X~n+bQujY%V_`=Z>h z!-gWbxO}OKNao@$<^j`@*ff zBJ`2#n8m7Tip(4x3buY` zWp@(_(J6s_6?r%0IWBS&$Xr64HPQ5<%jsY=(;_6Qui*3TLV^{N0skMQ=zHy3pLb)B z<*_TGMLUx4DBtm4b(4uESEJ5#A>R`N(eER?mtjb0dSC$HC7SPL}H2>8=D*I8yXs3 zym(PnRrUP&^RlwCl9H0*;^LyBqG!*Z<>%*TXJ?aSqSVyX%jD$!lvEO0w4ac;mzZ=K z6MGS5ei9UP?sNCd$%$w!m71I!A0JQBi?(fTQ%QW${{a}0#3B+`6ciK`5D@TRERmO& z*MG4@PEJnt_V%{6w$|3xmX?-gW@bl5_s{Q19O&Nqt0l6lqI#jkadcghD8@k)K&^|4 zlI)?MLc)Kz*#8H62uUQ_LvR=o2DLCWG%_+WG&H<-@1DNC{;gZLNTiXLmX?Nw1{#f4 zRaI3|Qc_S*kdu>>m6iQJaUxOC|Be&!^73+XbEE!epNNf(?Z0p$l1#+F!0=x(5fX{~ zFPsSeKjTD1axe)$A_Bky2=xC56#@Uhi6YA$mS1a}|5u_&rZP%K#^L{yC}MSClr=u~ z`X7lRSD~WwxBp9`Xn8R5E5-~?RvH~p{88_JCyHdspY89$leJ~*jQ+7(92tMCycc~} zjOqGTRfFx#WU&IF-{l^QDeA5`PWZ%sBZ_)D{F0?EhwLQdA|I|z7T+i)>4!(HpPuWy zeX8tmfJ#)8C8}&BecAsHQDpo6sq?|=;(O=y-fO?Z|LjkE%PF>vAYymLNTJe4tu9NE zF#hV2$lc$j+0nF@I?OQ)dV1J0pThGvXy61E2(Ix5Q$c;>98hs%-8%(*O&W6B8t?1sj+itx~*oJiRS_8 z5>G!l-Laiytjv`PHLq0T;655wRYCq*EASoeEJ_35fCe&Tt!BL_{69nyhRPm`#4x*W zl!gtEup-BIGp_ony^J*#E*}})@~N1S8X^BLMA2q#(=btZtFCpH%>zyzuC-n$>WN=% z>{A(4qh^PAcxGR1LK1wEO!W9unAE#VTc^Lt(^XRP$IZQ32-^DHzJwLo>G+vF<^}H( zrmzO7HTjy5@%|LfZn317t+{>rDsxxw&%st*Igu(xED9y)vh_j`A_HfkxUs!Ah}03? zCor0NHdl>C;>E+^nn(h4clhQkR84bAv`riezyC(4d7z%xvI?x4|kd^?{-HtE#;p-MS*yVrEbK zQ(Dg@I`fr|$4i7vukf^|-Dg{_sWC|h&-&AE{U3;88EH<_gke=)N%=JXk_hcxsuIPaFx0 zZLFk_N|`aZ;e5)XDi9!vMH%yP$o`?%-1;=D(ASlJCU z<>#6cLe&7KRh-WCyZ-ol&wgBMl#g8@VaFP-jvSj9Z3^vWW-1!Z@O2Gas^V4Izja7E z2}ZL6`U=%Nz=5T;ub3wIERC%tCIW!WB0(&38(JUa&L0D`7bKZ;k3%9Hi$y`$@)FrVPLve1QeB z9xJ+38W@4K9_WLI%OG8I2T(J1L+BSDhKIA3Ib{T4XYhfy%m)HksVzqoA9wqS5{&YSg)#z) zAFxpnoVtFQ_Kg>sce^Gt3_W#j+(IWH{G0sZmfq5a^civV0Dzbm8Sstu{o`37M8ybH z(cjnT+xfI7pk-Gs3p=A;F8oh~W{Q?qEOs34`F7FA=*&V5u1pu^>l!QLbEqvCQYc*4mT`z%R2LDzS=rC`|XAFm<$mNd=X`BK|qc%b)L}kyupya{V&NiUDkdIL=J%hYq zf8A^lA_|vAlW%fm8nk!pQXRufItIdZjX!HFX38#I8QhBs5DBLG=YC^9wLI#& zW}Yb_?bKwPN8~qM+fOM!W&*(mIr5k2)1qB|N)cm;G-^Q_nXi!#b1)nyCF<(Ai`yy;(qcDS zV;kFlyEOW3`w>(u;!e>s$A@N<$ zS64s3+4Y9J!mz5Xe}8OssYCi8;!TmD$950_SLA);Xw(;FvO1$gW*$G^T}=a7v}?|17bMH1wbgg(SyJBTMWL(LCag9zqNT@xPj+5B{}p-=;z z89dz=NVEwFYU`laEQ#>A5&u#b3E((}ade}t`h<=Y4!@LafjFBhzAISAd7S@3wWCBD zrCuP|MLq>=n6kc{!t6&eSmL!Ef@kBxyGA8l<@Y`6h)Sd}5lRgP1p~22YH70!iBXqKU7u`M=Ie3PhZ`9t@ksP}s=83Brg`cj40|?0 ze|-vLijTYDmU@jcID?DqK^3{_dA2?;MzuA|dkt^0mSumQRkKEaAqdCMrHXap<*UOD z-I)C;a&Whh=0Y0&FlmSTS+Z)<$S;{|&Kbj1IUM!?0h87V%XK}E73T6#FT228r?Zf&KzG|Dug^fhcvs zUtfyWYXm>U=h=?93LApavlK%)g{`ca(L(vLZp;&hO3UZjh!fbCJ(^uKqKzD&>!aEP zXh)Yoe)62UAD=PL^WHb&yW(DYOkX?`@5FgQx6KbXX!6Zu^?7X;pVy29hh`!8DSW5E zDt1&CCQvCexxOiLE9(zb5~p zI=8E)=%NNbRa2t)B2)N9#b&i$4z>JJO=akdh8NZK7B#ZSe5336E@>(Lis{U=Rz zzYQ#Lcv^@(Ld5~e`;$3YlHy%g-S~XnSTm47H`WcJ*+0gpA{QCK>`i1%WZx{7T zYz>Q{F!TvU460!xzv0_FtaaXx_?VeCmbz0oop}vVvV&G)Xw;E)gBEq<%T7qEh+imoO&^$QZSQoz>SpjdW)uZB^iIWNCCQL*-)dF`${GfDw2C)r5q z_MKXydQ1g`Z9cy~XRH&Sd2k+rQUiL3fZtqA#r&6scIR4`NWT=PmMt^a4*<1k{&Qdt zY_-{<^1D?6fWV_Sx#nPgM8SMtwSzNTcKIJQ#1orG|va!2V@F46k0RwWucb!UC zFEDzA1{hgqeIq;b*#Hwvi#j#PveWaJwHhmV{){zO;&X+bmf z41DdD{?mH3-~XtDf-SGTsk>d7c(XeqJN|tb=EK+4W`&oswY@LT>7;V0LlS$w*Y@O- zB^8At>8x?xpn3wq{sjTC-z$4Q`1)(-(0=C?sjM5O1omJ;re)_G zb+)x9odd4(R%pK%JE2c4aBwNxEGf|9?@(C$;AV8McaK6S3eKiY!4r@wiSue zeV-fD*BM58B1MoijTorH9<)7*yS1X~S5{ivp==tyJGFH4FV zc({KP*n0{wib7s1p=sO$tK;EoOY9`)ys`=GghG5qAr+9cHAo1)j~17hm6gN{5u7M^ zHucGA!m@7S>-HPEe@JGb;a-8akHUlhbs}o;@C{!?3Wo056v7(_0!vw1*h3Ac$%!Rl z*e2QoZi-9d5_?rsBuRpwEJ3~xr_<_-hS&Q%gTG@?E@bkWVW!I%wtL$H>t5<-A&;cJ zu!5#Y((XN^YsOOnn2(@k*aiy8fu|{709z|$t<0Tdqo9)+CVGX(lzJAKnM zUd*CwGhgLqe8NYt+n;M+(dpH^@NR$EWr)1!dj&L6B`DLyl_2;BKZ&Af8hMc#dx(Ei zv)7SIK9|52Y5EIC2R}B!&zED>@{3{?WF@>l$fVvY= zh^Zx}3T0$f;XKH%&P#0~ovdmA_O*EUbMeCGHtT`j*T_ZoM@v@7my(m9G^*rlbkTdX ze}Vw3jwZ1T*faQ1 z;~N4Z0~7I3z?W)X5~=9*c~gvaKXizb!*Oq7sBmFb^WQ4HeZlQTcSHSJ{}RMmAA+Zz zZvJrLOB0x9A7lxFob^$up&-puG;fxnmn3@206K}JK`~5K1CUg^DPv*^2T#}o^CD+U z@eelQ-vv`980-s0lD>;g($CAt`}mCmd(i1Ank@ifEsTuwMeJc{#sJ7j-T3(SIF~nb z5>spP<-^o(A??@ZI`6JA*%z~XdCi*qwof3m*(0UdhS{3hx^3rS``r&2cYoP&e5aKv z+aFtT>g^x4Sxx@{1RsWvHLSk%cIDyt^>K3bgZB=teFfw%-N&1+L-lhv(`3lceoM}7 z>)zSfu-WObp>uKX?@{?>q|dHgPp8}T@Q(H_gYz!m-4%h$?IUHnninIvPk$eIusf}h z8Yiu(zVE>!y1G^N8SFt**y66c`{GvYxv(NuTJx*B`xxtk!@@xZVt>~snghUgn~Zg* zU`^@w>jSe-2QhySwi`a|T)x?yq$KzJos@LAP;=;1>an?TsJeU9uYE)=u#ILrl>WXC zR%<(2+SN!szWXPDDS{p1hBvxrh^GCWK6&g}yi1+-LgCM@73ZEs)$dHH7QTWLCavQe zb33M-{eGe+zqU@?;?h8SpKquBR!BX~Bx?=-ewre&()xRkcK77flZm=NIg$~FN#Bn$ zBv`Gf^U@kMJc`dPRL`PPztXGqAWwl8#lOPpI6TkWpMTe_ia0-``L#azhq{y$eLX9( zJz4+ow*8GpXT$)f&tY!kU%Ipxj^h{nKEoS^-MzluZ{KT-zB!&C?*6Tj_(#jt$MWmn zV8p@O{vPM-fAhPi?1(cA=h;}}(Y5zo^t6|&_x^2=xe7O4p1%CoEOGSTi6X`kI~s5d z;+jg#oB`J$j!DeoS%~2h>D(R66_V#`uba**6P2_tp?xb`%rfeXVqjH2ALaq4HYr=X zTcrHt62fM@VNiC({+(!oq*GGHt?P1up>*yu3HNK%TSFhLj3nx9f66eDtu={p^s7j=bY4Zh<=#KMXO+kyspg`=_DZjEf1TpiYD zWhj}mQQ^YfEg{wG^RU^dU!^v*j8y$qQxv`!F>`t+CC&(39a&9jB*{ z6+fJ7Y*D|aWxTF)x4pagaz`|4K6*nL^os?WLk4@;q(<>WTC(O$aO~b2VEx5j6+A2< z3D-EVmn!plAk4P}_NAaN$G%mtS?h}J!Y|D-{(zlY-r^ znLPwOd@Rk%&%j$8Bdr&c$(W$M>s#lcL6fMTJT@Di*~bzl8LxM{NLz_sTX^iyA=j1- zFMU_R)`~$;gp80bE)zWevQouG5uUouay4CDf=JHYJfxVWQIca%$dxg=_0@8w>gJZ_;@@Pa%Ch^#(Y?@{z~0 z*0j>c{bq?T$*PbxPOrXd}Sf$+mJwEJ&xiNm#k&+X%`_BZTf3x((SLT-I}U>1*9 zWXjlP-V1g}hI%(GPwBI0cf{)OcM7asL4T0!2fB=ECsoN~|?m#Wu6pC7m^ z1}z4!KM7h0qfiO?8gZpJT%?+=i{gyaZs_Mn z%hdH(G+4z`vDcNpA^ZfD*q)+U9OvzK16VYd5QaftMN0FfH_Eh?sbcQwoAsNirLdza zz@+9#jlXgdrOC;DN**w#Z8h4$nK9=Z45sv>ZP$5g+!+jF%3qdT2TU@{DG;{?RfkKo zvRK43QhAJ51jzc8Fjvic)l{aT7--OZ-|wqHI6^{F*Emyugeu!*E8jh6%ueArFBjO z(C~^!Nn-P&A=Tp~OTMKJu9i+sv8`dY*om)UnUza1UI4Aju_4%zz zzbvB~=j9di^x%O<1u}i0VWM652KoYD zNOdHW{c~aUM@c-d1ssfokqbd@P;t7+$=V(&J-c=9g^{c_Bfx#Od{u1oV?_2#N01lY z0wbeQ5j3FUuKC6aO7Ff!b1R%_?9_SCiG*q z&hdI{S2>xMH`GD%`In3qHnu&5UoU)OneMt6e@t``u5(D{V=7sX30cfay~kAZOm0rC zgIP}2BXHA%r)+L0h>4e&G?d`@`xc%;F#XE1lE?i&&eLV1ZJKvtGVQg-SP9;*oNb@* zy5HaWJpRrfWq@R`y09?a^EF8?5=(nwcHQC|w6c{YwoW5T#A@_z_N$lV7&3kfIOWoD zN5lgWZ_dm*JJH(q&xKBNNze4V+tLHrZxTD zL=2BKI5<}jcDdy{R<=ZLnwyyPQbT#${x;Ru&jTA-Gmk(1uxA646RgT>BX(qX3iKe|8-cqToY|X;xT}t(nvipfj0+iLR)VHCB`uU#r zbet9A&isCktn3}Kst>ujo3?c}MVz95Ol8MPc*e+8XO$mXT|w`pGXIEd9IUueHBb1L zy-(y-Qgx;t+#7;iD7lsYJr_`$$W08>-?$cUS4MCZ&(^y0kktLGMlOHln&9hAP+pfn z?j&oWjF`t=t>w6!rK9L8^#nLi4SlUcU{lpkcXM)!5055~Q|dKv@oa-#{{;@to?Za^CjQ- zP&(n=tL*nCo0yKuq=6s>VeD`z>XP%Cd-lmfq9n z;9hJK^uFMmj~eN6`{dLHsU5=p@M=Y91Vo8HKJO z+C}YpfO#K{M<2piW^$~1vzv;nL^(`12Oa~b2=9}1hZ&oJ*>u6K=s0E;H5b+<1}oJ= zN6MaPJ}UizhqtMy|H9Z}253BS=7MqIf^p`$r6|vAM6ED4p@EUT)67xbHzN_isU;+; zGgqT%=zC74>1lr3Q^$;I@%{SUx7aF+%1ctd*h?oC8I?_7obqWt1~I!#s~#D z0LaLvi=X|cJ03L`mo0?5KZlLXC3jiU^bAi&9K^bO9Uj;m{uQn4tEu$@28cAZ5dXbY zOH_LMd$7L@7i$b)f@NVkXo|=^OaKcx#T@Wp4jP(CxC_Mj`o=OLac&qLzzz~Ds2juz zwCm=_%GP0HMttNY|K0y3&9z zCPbb@_QpP8!6Ev%fs)Zk(gDr`<#yxTakTWb(!|tH#b4BVQUN2rJqe^RA-5z>R{yQJ zCnYUQ)G0g214lkdM&^!(eqe>^N>X$h0wHJ!5CUeT$4OP|1M=ivNZlw;*yZjd&$ za<`~utcP%W>#(cLAd=Haq3_`YbCSdh;1;qP>p2&B@8AxqkHQ27;=;uSVaNbMj0YYo zEg9_|0*%CI8v{`~)x*z>Ssr|uf@xJ#wi&$cnc`uhI%F>|&X}P2J@|}=3jYx7sD3Rn zB-+h2E)WBiWr4BiVuK~)O!2oOI|%v<1ahrAL<;*}amJ6)+(z$2K2pWrFGEU%VFs@T z7(I_Ms%B&5|57g(I4!%FI~z9AEow~lkCJR7+flIm$avzD=#4<$*J-!1J-{>eq4#;S z?%z>1R%FUJ`eE>SoZ0-SZ}MQ$6JC7#L6!dXk0y)8rpJ_8ZE+6Og69PjhV>IqEpz2Y zDIW|OtKF&7dGKC|N&f{5ykRdPJEm*tbm!J5_1G_?_Dv95CVrDApFDogD3DWu3@WVg zGR{m7yweBdc=IA|>$(r|dQ6zy<$J&Pj8bSX>&=X=!}E#$nNP7o{Y9Flf{J;W=ByDU z?aPil5EJ*%HxgoLqI1VA_Vok5LRIh*&N5_(hz+bx@BSRChPUmgc=Ck1Dw3_Hlr7RV z*3TC#Qv!8In}rTN$O<%jfn*HzRS9_bCBa&+@ID(v{>qcpx&6+9o?G-!Bq5PNRK$`I zJNTZ4muW?^Zb=`;VFPy^ZkoS1-Di}av^ZDDR6PEL9gyduXMy=`#2^`Fb+q2)eZn_@ z=pE01>SOKwXBKcvwrAI%g+uf2go+R8V45QoQBBzUO?R2~3O{j`vC=Q}7jp1OFDwf! z5GG28oUC{-9QsSw2u@bt{TALKINm+E#+%TQ);!%Ywa-$A0JZYWbY)8hLjF z`@{~bUh=k^#qqnYgDig@zm0`g>;u8dcs4xZ?i`I`kmF4bh4)Y&XGN7qPF>l==d;a%e-p$ zOq3ge#w z1Ce%-Peb6|-;zPT)OEG4i7Bqs%)f#genGe5*^n7lbKsb}8=|k4ZxvBS$h$>iA|IRm z$_q+EP(d#f-0m2;3-GwaVrL#Td@jsg5k3J6vM7~6SMo{r=tkTsfxd{n*XK!$>xpTrQ0JZsw2_h4fo(-w^Cjkc#uM~R-d^0txUPRS}xI6Pp} z6lb{?EdpCIx!isk?Lt(!R?Gv-%e~_z)C|9V<``*!;igG25;du{`2t_Fb2tO5b~r3f zdcCJ{NY;&gaVz%s+Rkqi52RwMD#AM`iamoLm&rl3+UvgN{Ut9DWZMr>ZHnR;_BzS7 zaD~RZ?#;U{?Ov|!?p~ri9H;k9Y|HpzoFQ>X{Ki^Oy)fRtu`n{bru!=Roj0$1#J+jG z_=i&E^F7F>bTYs`b%i2Lu}%O5`JEl|_U*tsKbhiicbX_{szIuDPSo#RDej5n0AwGb z7$!-tVmr4V)sahQEi^uZrXl1Jx#YYN;M*WdZ@6_+x=u`KM@^Vz^gd@CXg!Nb~V`a9acQY zEDnW&p$y_=h^RG3MLC~CMBjT>9K=I^zx;`B(&eMsSGcIz*sFWdMI67nvPpk5@gW5netvUyiA$RvB!}RGI+$ROSzbQ`-msvLy{kOlK)qDP-7P}^)UdW zj1Jz7+@MxaZjgK?@2z2A~lQg2cd&ud}tH8lD%Krrx@?Y z0_E`#Nr)jbR()^6n1YMaH}m1|bC)NP((-p@0Z`^?P(i!5L#kI;Ni2{HVj~_@ygfqu zP;zWwLprb?I12BPfuY%u!1JF?wyB>?POXYVZ(f1XK(R;zGO=}k--t6jb6~P7)|ur# zb4PdsMJW_*Hz1(wbmmJh@T67ZY_xIrY6QskF^FvLP$f7-g1FiK8fGMblfqCCCn-vk zp1V#7q?Ct{|8zW9jv${_z3|t5`a;|?5$Ai89JqUW)Oqi8b@(yfEH0fBCu>HrNJMoO zN_`Ke4U_1|^x1Q040wJ6M_7ublE)~KT0=W_4;#bE3**h^NWUByGBnr=L%u^qJtD`^ z1JM7OC?eqK1&r!k|3ehftNjI+?mHw!NU@CD@9kHprSluMKu9&YB%aqa4(hqMa*A=`IC z+N9U=Y_Q}qY3DK*>R1>*T-`dB7`Q-lop zl{vX!dp|N&r@d$V?_*61+tT}u-v1PVb-*f1Sa*|YJ8ei!;EJWn_IZ5^-wJqXe&D*S z2mj)mq?`^Q(M(VE4L@NCfh_q?xvd!yNmB1v?qCq&A=d;4J^gu7l`mY=g4RThrnuJ) za=Dy^K+k{b>kqV=fxG4$smXwarMDbxCAf#gbSsnD6(dzS-jdwXFOuVuyIGz51*-0+ zqe`{B=_A7X;r>4p*g`vVGQ^Hqr;ET&4)>&r#PD&P20yO|Iwrj%U%RE$(@X|{aoWxW zxn5DUU$M-4GOhI!E8N7LftIVjo|wrb|x`|qMQtIgg%%(8ofsqS0<>F>^Xw*6dVDx1fbX#z5B*lt=5@1DpXr%*k_6Gv>IR zv+Lzo8R)#GSeG7xgVi;jP3x_r-^a4F`5<-8rvG=^C)VEou zPrp|l8|w)ugW%rxKD(Tfi96K#<7;ML;1E7(ey5WzUlt_FHNPpT&%`~ za)ywBYmg6D`Xh}oS58XEhcx>rRI352R*#Pq#j>ptczjH`{0LVo9T{*Y!S$VmJf;ZT z2ht;i4)$>%9&Paa#%R!y8$#qc1pB!x>ciJWV1pPsP?YAjCWoxU3V$x+pJiIeg@`VE za#@O5dKXpLgjKDhi@%cOj8zOD0p3>+L)<7hGr4qW_qYh$lZ_94bw?|2E<>WWlW3JQ ziWz^qD!k%)h$Jpia1)nlpYo!)R8U$sPWIuPQNu|dR=DG+$idtG^osLeh6`cbR9@q0 zPb0%0!2TJtUuEHugb>a9nCJsvDVBZo9X{+s`YS*@2o5kBH4@it-*s1;SI3TvUwTYX zUSn^NwG0_6b7F`yqDseAW|lxIG@qZIbD6$Wa%$YXQi*N#<#IKMRalWqwC8`xr7dZ2 z^M`r;uRJwo_cSfmVF3=o*_7<%7}OwcIWH19ENKB=Z}hySi_JVlr6yI#Fn%EWb^Ue` zLaI_rCY1R$DAxB=1&{hUZ)U;F4@&a*IRcIQMCx6?XIJ)hu5&MgSnu8|r&0j9K;5Sc zowaU0s4JsjM^9K>$do2HK37hukx@OPbFG0es{T>X&9UIc7S##eqvbAabZV=W{E*Uo z!8O~Q5Y0%wAxJz|PiQVnXoWDh4*h_FZksD!e}QVPg)!+pxaTKZZp(s|;8^=a+D+X| zKhf2O+HY+r{^A<=eEI=I} zRVLC_T%TuSY58G()}H0HE81)DHr?;>!56?rq!NISJ`#`V07ni`R|<&How}qViAhCgqD)?QmgaKw?ly`PF*6 zNdHsf<3%7^R@Ry)NA2QFhu-!jfli7;%jzvV*d>5|uxV(EtK+1!vYV<{N1gp5@1NCx%o9J9HU&K(q8lgj8EGymqFH(j@O zJ@I_p^Qp|UvF$ba>AXqrwm1pxrBw<7Jyqc4VeUG7L#@huDn=zB7ct??CVIrZ_{Zi< zucn%Csj$yUBdoMozxRWjzFa^M{O)|ddrUpO8-gK9xwgW@br3}qu7@Dbl2>w z-s=sI>bI;9yFT|`UT^ZdgR_~7W{JZDqW+dps6)EHOg@!sEf@2$yHWOmNv#C5+J`1m zn0#z&n;=M{(|-BU#tg$)1J$OManS~>5&t>LPA9f2Arkrx*U=*8mO7*J)iMU|2Z_bgB2@=D# z>#Cy$??;5Yf@$DV!P-(U_OE%oMIQK)tKiAwoh2*44^e}vifUNa0D#H0B=Ty*hh!0V z&rWe~sc-u$kP}L6{N<>El>C!tV$n0RFBz=8h3eiJGECFwZ4AI8m z;g14vWV5c&8H#l1(-3ah^Qkxqrl`O~_ehz_MaAg0M+nZSI?|2+cGVb>h#&=>FJN&Z z&RzIS3YFc7#j*GsQqOXZCTZW??_5g#Zj>xJoi~-ariQQT5vL&_&kfMAUuI(?dgy>E z+z_`qEyi3j8uiI_NZmx@eFMClzR9O4=qH^!{ugFlgG*(shS}9#8)k+V*9B~0^!WKn}wRboAfApfBhM@|qwuyt*8r zxIH$9CFCD=L~86%3$BeTVdw#2!@kodc_!ql+k;UXaoB+W`w3jB>KASpq?lC zI$?mdByz(bL0Xdqh~WZ~>{*NK)haBU>q|ox`z4put@@Yk+};8>kP^w{8P^Ej;Nm{8 z2UdnkrlN0Aa?=QY1IQTL+QR#Ms03&{TxNuhBvQF`V)c?`0oU-Q@fC)c!|Qr;O` zHbv_}!dgjv2?L!FE@{y6krTn5FPmM|#8El>`sPRRW1}F0Xjxyh8ahg$Ck508W`#zI z#}C|utNAx`su_U)*4V%kKJ&#`Di5#RKKP+J{}~Oc08GfQO;MRL#efM$daRBTvsR00 z3z|zNGyB;-*J6kU4szRley`CyWMnE$>PVQHXsgB%GXCOuze)fInFQMGFA+|-G8{Op zAC&dijX+DYgsU+&7bU|9a;jV1x-az5aFg$yP`PHNX-viEPzAn)pG7ZX*?^vY+15ct zG?pVx6rV z(rmRMF}GM^&CQ%cDz!eSiS%;2I5T=j#VpeCX>d3^$nEQ3w^Ik=I2av0Qk=Qv>^;?E zQpxi0ba`o9=1zZ|m2P2_K05liX9k%-TonZ*XsS#Y?FL2Z)CqB%5cRt&6|V1`G@Kz- zkJ+kk&Cd>1bUdl@nXM4tdG0&#+)Nk!0~q9|iyzb%iE&oLG?Gr1Xc&nksVrK_e z>_rtVRKPFaG{a4u~zdB7%kIqJryptRe@ z#QDY}@d}K)mfCEjdQ5UWq>tny<-c&tFoIM(By2w+;ffqL?b(7S%d`0za(Z)fpfw(H z>pDHpaDoI$y~%tPLMgXuY>B4$gfX}G+|RwF1dhMwM)@m!RKXJ zII_(fX~Nn{WPb#i)EQ?E`P?-+HfzOSX!Zzc|3pYG$!k6UvAfg|En!Cscp*_)>_CDhnc9$a(WnTwW%0}5AYiqK~y%&r3;^@ zAkZl#qgNebC@Th4`!u@rwyO+8At~-Xmu~NEG|6=-C9Aj8M3?R%HQ(@SeiW`BvhjR% z*R%WMY-LHjSa^&W-T(y=nLKzf(?aNW*ct(S)JFk6jNo^?5c&o)13S_3Y|*)(U!yJY zll0T@vQdOvjHuv8z*l(C`*;4hSipfN=3;xvgn;MJAP5sk;SVk#$2`2GvA?w0KckWenYxSo|d2l)?mfWlqDd+uAxaM$gCY|5n| z`i@dc@t^=dmpNZ|AdOpq&K82XD+&v zX^#(*=$gGX(X}GNUc&G9+_l=0I`rAPp2>~GWfE<A5`^){=P`Z-#(uU`-gFs~ zbf%Da`gdQ12~_WW7~Z<`-u7pl-eDwlY8@IQ3Gu)kVRSX-h)3-pIsF zk;dQRIa1n5zciMpz&{RnyZ5i&ehL30&Hj{(Pv7g(DC$H`lLn7$Cshqo?;;C`-rRqL zG`6iT%Gj$T(ZrZCfBWWTNu`KI13>TCkXb`T;*g;V<~+UW1}zi)y#W&9SYV z-j|eMtThQk%O9a;*!$|=$`~fY4n1TNs3Wa^i%*jRZ$K_5i%<=?jo%0RJkq}p3FQ{J z8a#dd`%9JeL(MDFx?h)=4b*p14xfubNN5>fbHMGFFS$-zH3wzX@%3yB^#}aR+CLuY zI3DXT)ZUIWg&9QgdF~_|f>4qHGv`f4jgJ7GRyvLA_f#P$6~e_gX}+-lxJMfwu@x~( z#-~e>578h!2_sJ&jQU20%%Q^x4@5ag6Iu7)fIm9kq*|j zc%sg45XCYctMYg72I`eX+@3?up5;q9HBqwfY6Ko|ol~tYpUVmHp}(nlA1_QsEJltG zf8B?MAc8lbE(vm|J&{qBkxi}hvoQckXdZrOV{nm?(>c_C?{e(Ve+|+e9CpgzNv6mX z?4K%S$Qs#d{X-tEsX5LhivBu(%o-M8^XR(Ed|z-x@WW_~LUy!y#%Yx2iCW*0 z^-Z~bbwUY?29JbhZ z)uFn#8}t2>*ZUCF(>4C@@_A2pRP{4br#l=nIs$D^ai!~W%9=l`#k{6Zoxa}i{tkq!jfPojnKiC5$^+OAZu zLwg2QVbg_=I{mj4L>*5f*Y5_X#gO6dFqJr$^2ndB9Ou(^c++N6hLbh&1M+x0t#Q}$ zf>ZbVt@X917csh;dodh9kyc1&<>&UG=-o2M`TvcuyYP$h?;3r7F+&Uk6NGdO5`v%% z-E9yGC@8Ifh?D{X(lT^+mkiwqNS6bMgo3nmr_>-Qsk7&I-{-l{bN1P<{qRo=*IMiQ zc>`!LWxIdHH(4X5rs~A=Tsl%O%Qy!|UAI57MUg@|<+Q(OFN%vml)gK)_HW7}i{l!9 zS1SEdz9clWoK(6BmfQg@8q_AnyjoKtK$MkZO*)>bFT7pyn_mi&davEORp%VkAuW~J zl9cFOBW0+5sU}8x+QF@!nOV^WmJjA6rNQ)J6J+$J#iA_blhp8Cn{T=oQIr~LDcbUx zsjbpx@?9^aRCJZA@0_SsctmoxIl3tHYrgrdRhjP=ZML`? zL^<40C9$<+^aIuCHQ(UX6ZZxZ%4XFOvDRDa49^9O3X=k4zJkTmQlq}Ncr{8~RrFVw z0`JJ)%FXcX>%A=EZu#~h{>zIAwm77$`sH^-*d^I_r}*}3b=_=HouWS72UQAR58A$F zD!20yzkjLOa(4>)PGtIXcDb#(<=Vg!rq*9_F3ovCl+E3W@Q!}_Aa58(#zVDvIZ&G6 z^_rS@7X{$B)zvQh$@ISepx&Pi7w@E;3O1Yy;uIsW6^N|+YkUVp=?R{%dAr@(k&w*7 zj0_S_do34$Yn7PmDrG(m^~)t=J0qm$)%1$6b!Im2Q>@LN=J;i%f4uB9y8Nz`HvchI zVNR_=jaynt`Ts){S*V2~xbBEcqb5K4&C#omH^o1@8_TKk4^dR0f+Q$oE~V7XGyKrx ze3{Rkl5S^4Z>)_sC%(|hQSv9hBAaCMApdSW-=hpMq=Gj#hWzL1HNx=2a)TP{iI!yh z@8!|Nr}Ak_x{6%9Bck%@qAyJv9n}tNY=`L@VQpak3CeQ;>jekqQKbq&T}9 z*v$r~M&11vQS>EM z6Q|^oUJh9fT63sUl{EIdGY!l@$76M(&oJl-8J(zF-)=ZTuk=O23gLRpCbAZJT#4z^zL3HjH=Lq2@hTU;k*CJ^092+j`@DPc-Ws zTo^*W8VWKziJ-=q;&l znA6?OiVLO^Uw*>I)Nsk%N7_@}%ezHZ5VI#7^yh*F(zsc&&s804^g8r*%3;9On>BjW z)Ed<5e4PW#VGP7GKC-1N{7Tdjp<>4?h`aosXldiak;^!72hlXqDw=!Rq?GiClb(I~ zPL5x?UD-c+%YXaF#|Bfae4R5SRs?uhUt6wn5fpx@w&M<8KjcZ`zB`JEe6FgpIAD%p zz_fGRaZ1c0wPYeGRlmg%L~2t9;l4v8Ny$dJqfE^>8}m8M&9Mp2k)U3y#=A-bB5r=; zS^SR#kP=gCELPMTBAeXVu^qgjT!$enq}rtu6zX)Qx}jB44F|Egox>kQfjI!c|l7 zvS;wSopB-J@@*7vT<^AwcXB7Y@r>l21%d8yR8k4gF9B0{*%vdr(8stEK;>0Ix2d&Q z@q_UVN%!lY-?6wvtLTQ_UKk0^i%FK{g{^9i1WeWyxpI%*V$?q>xP4RdXBmHGxf$I6 z&pQyl%lT(jex07wU4;*AA0`4>v(8zcVeAQe>^`(pU{0>A4Z9q zQku-=>xy|S95Nx8&BRLE6Ju3RV`KwcN-O{u+*g(z6tWg9n{M-2;Vc7i(8nXuo>9-P zP|JbEXFB08qEt{0h9NR5{xD)d138BamCVXVj*U8i%d0img6d# zxgLk_rc>b$Rt&+;cVy_mC1rX%RPHUn5HWY$&C0`dve-4ouiMllBjPL#7H5Y%I^Z+* zCbGjYDfR9~GLc(~qLv|F-Ih7!(duGPxZ;e^&xlj6;1C%>W#p}HzF^2<^5VmV#9W4+ z$i3RsQauo>>ihQ7<_!jWp=T`R(`{1PT0##=01nnqG+W3pict|Lg@f{yS;)3>kw4Tw ziklY9bz7498QZU0%|0P0KFVsg?K+z?TV8Epv(gWgg4%Uosna&ACWRKoKX`s|mkE+w z6MqpTs8xtuq`F7V_M8&sUsy?pi^3^@xai0XmHGgQdd9mR%tvxZC^lG5sM zLFo>!y_3RUy;{GQ++$Or$Zn1V-M->I^v5Z|E3?avAC}Fgepgfi91OOh@P-@$%uUI6 z(edN+BUL4jToPK<83@VNt-K|9RT4(sEk%&al8(vlzUJHBtGBq?j)lQ@9c7<<3&jcF zxQAmZ65t}B2A~``5>_M$Oq=Ns;|FJfO0+nh9AOE9<$)D!|EQ{txsudE zx&U!V2U9h7j1zZ)F69FxrAzN1PaFYR1P&U!>VTxE(S2S}?SJVwep6G}0VnWo4+UCE zd1FH<0fKR>!oF8i%78!?x~^=4SF5-#YVmLiRSK#AirLQ;N_i2Y2jL<^Jjpy7ruKkdNrdc|Z8@+BbLe7` zRi-t2fS}By4(#P0bFGsow(+J0x@$F|`-f7c99x}R(3P9{G+N*ZTwIgI7@yr%FG!JO(U9s#!Aog7+_GxFToD!;ZIMaN<)_Fck9Md3e z!}+I%!f%A@sS{f&uFGvPBB`ZALdHN4k!jJ#6pzsEFNDn`Ue}sWc2x5 z=;{?xd;X_2{7PLsj|TW&(B3@V4}o?8lg~quAU5`{8_b}as|i9M4=K6ht`Ry%Z!wv( zm90bDMY;M%e#O*YCqdt^j!hvC045WVvk5m{Xn8Nt0`5-NY6`FI<$-BC?a+APa8Y!7 z>=)D+?MNPp>A)qqD)1^C!Sq4I`R5Jx4_s@nxh(a#KG6t*`Dj*_IdA!kwI}fO(0*0b zFfuhCvl?rJ)(_binDogDv1g-WjCzfOOshXi})-tA|^XQ$5AXgyP~TI zOVZnNku-8qR$39dPY0YH{T>xl?)|A`OD8LwBujOyEK?Um~~qFk?I zu{UqH${5s*G3noW|C&b5^-e2~iioRqiZip()5hwjuqF^_*7xn#n;3&ORuk9UdIJlvb;&6sdvnmsn67V zjC@%kyC|kn@2VYrUz^07zCq>45V+^4e=ktvYDz7WDpr0>|Gu9%$;G%1;b4F6L-=lz zHkaGxt}A`@^8N1do=Nem1IHndUog5Wdb7uz1aSt|D=M544Ih>(0mDj;7x1gyxLKsuL8^8-doA1Ly!-pDu52$muVoqQa=k4QK&XOy&X1Y7Vji19aA z3a?sD2zisreg{gSY<4|z(~#bR2ysjAP-DtgtaljF4o;_;YXAie(G^F9?DKS5Ci5iHt*e^x3 z3Gkx$3wKEe-YZY9fUZnp$VUN|;aoD(eLYH0WC!Zi`kPnV4X+4$zh50nI_|uIA2&E| zOH#k?e4bjx&^T#rkaGY1xMa^8XSuEl>s+>x&qREzohPfe+D`;aj8xz-)Rc+W%AUS!gK?Y$0%x>V8)oG;6sCuXHE7Z zqR!97Lkp!53Qc(Q>FfI^q4lR8fgZlG7_aFb${5V$%}z*?M@Tvoz2Fq11e5#WL-%6o zr|wgVULKM4O_5_#lx$7VI2`101+mW+b*(8}!chNXs(o$~O0kn=frLF}nL_Bf&uWvH zfHS5zKW1+#^ibL>Q`zA0DI{tMa?_eFhdDB{KBfQnwpOc@DNIiXRlym2Pz%2bXUZ{8QWB*hI-Djp#D>BuK}Rd53@VVn}7Kp`_=! zwa&@lpTV2yBOoUybWxiq6_$vBhJ_%CulfCM`>*X@egq&TkHEC6Qnu+l= zYEU}&{KzB;Dkw-#h5t~e_L3{jHg4k9Yi+!+uQ_gFlxi0CY)+po-b7IcWPIrL^3*wR zp}1&l&aBJyV%4c>>dbT|xS31$L3OlfW#WOgWaWW8%yuZ^fG>%x~I|<9)qKxn<(y{nP87 zh^&sySzUj*ruNKFTBb2#84uiKGW#<>CNh>3UquusBNq&O1^SrMlt0&Ges;X%$u}LK zo9=KoeWBwc{IIP!8|Qz5!l}r5nlxl(w{_>rcQ{{mtFXQJcroxx;>$0~FO5b8+X8u6 z<{sUb9z9rWvioO^nz}3UpIE&<Y0`#@^Pu}a4gLyVCMiiK^IxC( z4)~AFerz9*DCnd33$*fhueYi{xC z{CD^9VpYUF_V?Vrp4WUA%*@6n=ITD`4PP7U+@5Ya%T6FW?LCqqjvOf`$*`ejo(~j~ z3>3V!6(%kIi0E*v=XlKtbgVd^tw^zWNGK*2&JPV`mdSi z$+y9E%A$9h_c`Vw*>^^acLIMH-cvjjd0Tv>I8%rnD#y+f-g@>nU5=*y_(Qk2`WJsYXZWQ3&~|)r{_1Wt z&~9|Ots(tQsr6{O+Kil_pvHa$;)64 zu?rm46L!O;@ZX=D%`W^%7hhNMW6CF7l7KKce^M$I`7m^DS1>iJtPeya?^YPx~W|VO-wT3qJ;y=7FDN*F1%j{(#7rHeG;Y68sx_9n$WBDspyXlZ!{8>7I}??ff=||vXt6PzKvBMIU3bYoLwUsyHx%5gnd!X-~R4fHrJn@k5(szOPakt@0?#; z5D?~=`-kq2-xLs>4Ggq|du}}m+!#zE9!$>tp0zyech7xsQd)0e%nnU@YDBzcgaU#U zql5CR6+f>4FOu?$C5SEPe>DSM*Nwg(-;qg&ya!n)mML}-ZAweZb ze3T5z-#kW0mF;RQH>j{P_L@pk-Zvza*VC#XL0eP6I4+@n?alqkV`GO86ORj%{Yza# z6?&OIzq8bcH)1G%)_i_FBPE*f!K;wjB>FP_ps1c zYW@3yu>`1*ZT;kv$d?aNW0GxcAZ2Up9&Zgro|HUNETO&87H_azR?9-M@uE6H!qKp< zOy;prDS$0kiNSKmQEW%8;K<7yj_ifLP>+9B5(LoNJmC0*XcZ&|b9m>5^%v(}4wtq{ z!});UH#DK=@pqYg(!KYS1w@>q6x^$K3R@2cE^hkD?D!m|D-@Sb7>3%=k$h~0e+rN; zq89%o_2;;IkQ$`0I-sn2NkW8fQbYGZlcs>l01G+CI zCXER$H{!lCJfjZyY?~9~_2XM*w)EWqgJAPw;Sp=8FCIAsys6^l#^XDW&N!~%J6VUg z4qtH%O`r()?n|Y=_(bBoLKl301SIiVn*=0-{Kf_Ff35CDY6&5G#!@Q1h(wVi!;WeF z9<%*&$E{a;Zx)|~DjfTan76jG#xg9QMT>*j%x~HCTtQG<_^Val5n>|)*{KJDN&SOl z$Wcf#T%digYJ@-<8SnxY#4@TGMzq$u=*xz=t_4AOy8L79uqs^m*{`O=aAVS5&)XB1 zX^rvck=M_3c*rhkNk}|WuFg1Ig|KOTpqAMFeOkwQ#qx8 zNuw#?X!8P|8>JdL5u-_E`h|$<08V0sGi|`NNW8N2zGK8#)(_Vr+){v!A9NfGohW{C zs!IMiVmvWGzd++nFxtf8&+M0RD8|6lYYLkJw z<9VP?85mTS8zp06OS@DdM zYPwJJO>I(T#q%4pkQ&YFl`r-xUMO`>2l$9(ftWXyC7}T^Z^aADUcS_nhyyYAVUVKI z{x2OPXXk#rX>8l8baa-RomprgW#+GPj*XmK<2V6T@opPrQq9LJO0^KGvTwSX*w630 zmS|On*$-D;nfVss-j-rlqE}V}HCcI>y3S)`QZ#)pXhy5U++X<4uJ_Y(_)vT3MOA$l zQ6Qr75Ck~-xbV4QsJRic-JbWi*e=cgydvwO$;GP)`B+dAv~&Ni7kN@puONF1abW)- z>7QI`Ec*!`IYz7X(Yr_{sav0uoDcDabCzs@>L22-)`a;{uc30^D+@}N#0NinRy=IT zrDgp(0Ty2~VGWXbq7?R&dZ6I@|xlB^5(|V%T zgi|$!tZaWiT)4a!Zs<~Br2Qd>Ahh(VJr2dZCVjbB+5Sj zj7!#Eljf`&Ia+u1rOT#~lOrF`y(!i(X}Ya%Pd7o$?7A%9zIgwO@mTQZ>HI=sL!#X4 zdrgw7k?Ef&4>uVn=@@?By7dxib!~Qvro$~%u+aXAmR#`2EA$7hyxl&eclYeu!+No~ zJ=SmMn5LT#Z(Az2xR!g*@4jkmU4$KYeDPj5Cf=DI5bsQPycaL`8$S|=xh1Ns#iB^6 z>PW^{ynd`i63V43cNedrnE8;kv!F*f<}k|MXO-=ssaFa9GcM9+jYqh-Unk~gQn}B% zkYn=~Gezfnjg6Cv_8y;Xqg{lx z<<7og*-(7@V7=XSX8tCsLycme1YLu{kdGL`yKoBq_{1~u0hRg}~ZTuOf{h3Sr4|@IC!`^a20yeJ&a7(}C4f7RqBLCQhxv>>c zoapI)hed=xFkdB*ug>%3rhAHWpzv0p5`ZL;_F< zz>n~-Jd6sk1gh4B|6HP0KqIU0u%mw!w#Yg`>v#mue;RVbOb?`kA9(~DH3gfU23tsn zJeNjB#t}dA;q^S4QVHD7T%r0l!61uJ)2(0-Nr9@-h$y#&YFN=YL#TRaL`iUz zArd@HO;9!_9!m_O5L+0i5QG3YY=t=4ggp!kbDIkHP)B0 zKQY1iEQ#Tlbo7Kr^mJ47{Ao0Rj9E2|840}R)phOd%58s9{$SPEk<++S{`d>ScoOD_ zf@EL@fLQ^=>AU#uRt%m$mfJQKnI22m9}6C#6cj*4RYUEu;BXXTQa$m2DfTGs#(OCi z?X#p0jLDT!gyaH}IVT|Mj74+Ak76*tZY+k1T-fH8p%YIWjyora9GD0GTV3 zk*|)dK*F2^Qr}YsbqZt|{H9!90t0Ab5Kp4JHU*>tuhvDf$3Yj((^SpjVon-6(y+VT zkbULY&*51El)zWw{~|hqvd0A!zf0j*gok+RnfR?dH z%?vUwsy7L_MEa<^Kko+AlFSMEw;J&`PD_sq-d_!ZFHsVJtXKd+z`+J7Nv7i<<)Bgq%l%m;M>QW^PjGx@jDoF$AB8FXaxC1eYw z%kt%CBn)S=fMIbRIte{J39BD6+AR6D*9-M$ir#NS-8D0+fGjpVLOG!TOhR#QhQWrV zP;#K?@sF^8vdqw0#J%(qP)*7GA9>k7O0C@>YfcceILHqy1Y|)VpQ@H08m1mZM=4;* zzdFHgCqh3gMc&OQ)fyHinb#)pu?JOrdlK`!Zc9fQLn;6e(lfxTFQ%B z2=j+By!_x8ViW-AjB^|V~_iOPSlK+Zz zB3Uxh!cu6;ZKNZ>y3h?YVt6>rS){$7A8=$vtRtz+c+8FYqk}Q*KNg$5TP%mui?Tn)GWm z%+C^T?h3J_$E`bc5Ko%+E;P2&fmxrI7?-`>2SO^|$ zqYIlvn{!~HE6Txz=4o-t@N*PALI{Z-rryLN)=*TROpw#f#AZm8vqfLnB`l5_h}!MT z6C(5{IrOLP-hPjR|G-i&N@y0Y^@nElMb7obI;0hw_NU4tv(_}QR^bIf;dY1p^+L#k zs4rsj5rrNRrA_^nQ%pT<0}ZAFEn3I|N`q%~@NaYdHmj72)y#<2)ExZSt^n6_!mx*+(`L9%;(B5a1Hb&jODlHc&18*=HPh$ z(s*3wH$AR$ftM40uqpBpkh1br@cpUgIarOZ8#zoHa)YHp8D2%jGSDsm@IrpGiFpN8 zMXZwMj?_X~n{{9S2W-?G&N2EDf?pwj5Z`qi*GY4kgvYA;-Pj&SCbTksZ1RDmxcklH; zip+O08Sgrwd)4H3+sbouC*L`fU*IX_F%U6U7RBAplo1juWdb>2n9>R*@eT)nJxu1F z)oT~Ocrm{yhMieMlizh1oPjM*wL=&;nfXF2JHCuCY)0gdEWG2Qn86_CfU!ib!9029 z)F6#v+x86%V%RAw+JEI4n9Ab0vjcKjDrQxtYE^D%RbhWs3BIOsb4^Wq?e?p+yD@7T zRcl&9Yxnopbl~d`Zm#QTuRnUVZVRJCq0v~D)E?!C8eadYF@E9QLVT<{@CUt`05 zXyfHg2J8I|=bM|ap8z@N;AwLRxU=dM35#$l2&smhA>qSjNIFGHCyz*r=a4ZpVsZ)m z!W@Plras$&D0IP!(A9hgMIY<0;ObXCK2;lXj>V5j$)uXcOit`f~52Qr|_y!?YnoudHNH>U@c z8b~KaWc>mJ>?SGbXdsJ-!p$CDflPMLe0gptOU z7#?BdI#7Mn@%S!L8IOZU5R<|{G-YuH_}mGqXbxFJ@jS==P{cy2w2@%|!U_i}GuYws zD^PWezq<`K!$E>#j$a=9hDrnRIM_J`K7<+C`2q9!3n7>*VD|gEeT@5YZ~|saQRlbH z)1M%J$jc`9s4m12aTb3Nn5PU+a6C&z%*HyA-=2mSV$O09=R(=gbqr!21ubJbFFjZ# zA^9JLvOk1B7k~czAzWS%E`Ad(j{gfOJN|D-*%9Gn=ig2lfvA!F%OfK?WrSbbgrmi? zqrKzffi8 z*3{HgUtj-kbc|3fTU}jEC@Uirn-Hp)3FUNzQYu0*IiU#j4>wi-oR)|;S7s2cvC7Iy zA~aT7TKaEmEI&U#H#ZlH#S$_z2=VcRXh%XKd@9B3f78d3lamt@6XWCKi3V9@WMpV) zD3KTo4i3KXwG9jm#9%OfetvJ?z9lMSUS3`v9v%c|XM&wH!PJys#!b-CA>3yss0tO> zKK~Cu=H%q$=;-)wgUrUp#@gE2($do0+?>deJ$drP)YOzHkr^2oJ%0RHUtj;gwu5S?tc8JGXA#QdLz|{ueH$sHjMg<{_Z35(GF2+-w96CITbT zCW8@R5CRlJpaB0vgMmQ=5|TfRbaqmbM2t*MPLAl2NlQ!r|4A}IK|!KQCLkbi?beblJKnUG+)4uB5?ocGRW|n$QUQZ;GnB81oO@41Iy+ISx_BtnH9KT+f zX@6}YF&gn~AWK7RBS28p{C^V49x@v+h?DmGZ$jCV|5+$&^)VD8Sq^lI{BJ^8(&0hG zM2R?PY&}?Z?QNc5j$`-wGlcu|UXp-qv>Zk5HBqZrVIe{Eh7W)?un>e0s9?z4&R( zpDyN$q?!c`DTB?DKluFQ-CL@k-%)QSWegeKUOX=_SB*`}zY@UqW@|YVHR{S`M6U>0 z_Ms{ASh>y3Vg*Pi2Jx>(iBHE`RSF zd<0@6<{+hZR5(%Np@|gU}F};SLsEcnol}v z(Y#m&79Z@$trwN`lZGEcU6De5Jv~ZdO>-mMV-QzOAvzIux7PcupIo$DKIorlx`UU* zyv!U4dnb#Qzu6N9%)ix9@q-lbs!(f}pax}bY~1h+q*=xR(cfzunf6b(Hm9DzYPZ@>7Pz)=rr#VBc=bo6fyA#(EJX6S z&QgVAv577s5l|o2kU3Iz8C40#(&-2!7QldA7kxd1T$2Mn%w!h9)4KPdLxI@>Ay_BgX|fiSeH z^q2WCEJ+|w6G+2IN*{*nM&;2LZ+#-==Wzp=Os1n6!TwQ}9Bjz28+S+m=3{GAQ(TZr z7FUG7e15P)IcORRk_*HShkAT{_UAYMrwbbOaCPbeR5wUH2^}91c5jWYG7TwYN8@?K z1mUR?LF%`G0L#-*c}am-pK1`0#gi|GN5|>l9^7rh+!Z8^2i4cyc%u@Qeksl%)iN=f z@*$|7782K(wDvM=LtqURs_``ia>NbLn}bsO?~y&BaW;xtk|SSfIjo76Qd;tt^jrb~ z4vAy{({lkGN(_k=3GKN0U3i62v*E(%s{?%v;RmAMVvt&*lm^OViB9_kWh zDbR2XfaYt01S@l-%iBf7W-FeCGB9-AkxFnuK~WS}0cGe<+`|+Vp2s&`8otHq=W%{4 z*}VI9yO-pOD;6CsaO+7+d|+1){Rq|{+Jd?t3MYM2h7VzTjUl@o)*18*2tuGbRSiG@ zRb+Jl^@dX{8Zf6>I`xO1y4+Qa5HENt1Bje=QY3o?6*eEu?OP2@HdqH0^`6aao38}E z7+&T4Ji8)J_VE6c1VFohyDRg=A}CNumHkkf?3y++sYyXM#|(dv@?%V-N19dWK3nOS z_2$I;tz6E}IE;~8z~o}(L}khSJ+&oc2?t)7P`Qb*b!UXgAYs3vfPMS6(oGV~$m@bS zHp@!8P_28**8TOtfj7E`M<1d7R_j;^sED5X2QI8I@ZfI8Ifs9l=YIA5ZC|$FeakO% z)2|s?6zHkA&$*(&hTj`r@4V3Zel)*7)9C(d@0myP<0o|lq5kTv6}MRErQ98 z#)s}R7qV%UXUSprdt2vH(@&Z|2MFK%QcF5KxrAd0c@ajoqO*GIw3DB2CY(!jIX&)s z*WVtem$rg*_m8>hsC?OW z9HI)lYx-%bKjpaKMQ!L?>Q&Nj4Q_SL(a-HKOl+nU!y5EPaTG0B9+NC{GU2pN*c&9k zNxclwQjg=h%#Q@Br4b9h7M`4}(>Kq0UQxz5-XBX`3?ck&90;zkPvbcPp<|oBzR*6( z=$7w=I9rhl@83p8#79{lM=Ouo#Mz3gq7ppF?=1ON0e)?Kx3(xmv&@k;Cbwq%9L@$B z74tEyq!`An(5YVS-?f>4b}c{R#28sR)uC1i$!%7AGSmG!A+$gk?v6~mMOdM`Y3vbP z{+^KYGa7xfMT5I%b`Ht9%r=rj2^py^q5DaijwQE0YIyf2m&8nPv@%Kce_e_O$;P=;~U%5$?u#+4QSWcZ{orQJM>X_tQ*JFj@MRD3`8=L1-HeaT&k zFw{V9jNC24K~hL&e@&!E@RlSU4a)n^U7Gr9Z^s$lLbiM<3}x3hY2Dlm7AAFjPxRg& z8~95Y20usgnPOs_0eiGG3csmsi+$p^V0~}AgzZHpOoE<(n9Q{gXT}fL{5Xf_?b1; zEnyJrD}2_co2Cy-0>vzzrJH-WH2J!{3H2c)hI%uFKOYJ8Itq1X2=kN-3y=yflM3KH zCGRTsmFe@P`W%qp5s{)2{;Y}iIfUVbw3t1F=4D?<4L?$zpL&`iD5}q<(8k*$ECL5% zC_9ya=9^ZCF~Gqhu2WX|VS%E~zyRP)l7{@iL}MBj`jIJWhM%rG?8e;6jn8QeYY!t4 z52DxAW8fAsj_O3q3c2AC^JXfNyeayapJ84dSw4Ebu{Kues$gALEFi31IIn$Ak6_ChOzWUbSKhC>ws%4&GF8n*VxYDQR#eM32`*dQRUVN*97QB z$-K#yVvySjho{z8WD-SG^a7P(cmja@g1fde2W7JBWU|IIz%lB#{L<6s znvqV=Nq=Gy2L$s+Z=4XMG_Wiu~uE09n$F+(bOVK#KKi|-)*M9Be%$i z^v@{M$mSc!`0AN=y(L4SCGXly-c8wTG)w-VOuqO)#xFi=U z#s#!BW=+aatPC>0G!4a+98FoMlR-lYP)k{Z$ioxf7o{567Cae1&K6P?qtjlakV=>| zZOt&}?X(Bi3k57}KV!&qPveZe>_w(+r%wx?XzC?m$wbA8J0h~@lyIAE>LFZ;9yHRe z#W9kg=`Ea|8hsrZluCIIh<$u!uXY~hSyp^oQ?C#YJBfogp-L2{iMurDd{R+nUwC+n zQL-nEF1a^{dFlI%mo(=(bOWX7p7C}wMK*@zRRgp#EM&E(C9X5Zsioxu*O6^4Wl_^* zjaN#qPnD1?QAusYL2WA{!{qu~Dq3bL$~Vg+pcNxCwCaGd?QlZfd0JV<>xHt4r5`E7 z##OuL0E=KEi=Rb*NZBcY)8-zn^h-ly7?rsej8>%Zts9&cwy`%E{DNXs6Fic~x1RKXl z-(G?~BW~lWVU;K(8xCHC2dfQ3H;FoyIU=DN{0K)iO4PB?h<8ZRU@XEMi%dFgYh`E; zmTS)}Z_cz%cm(mb)~f%mh5Q)+%Nd4lqhJ9T8seVo3CaPi^2peNY{rt5Q0?pzhgcCM zzg%L=GKYaXp$+D^p-7xp3GT3`IeQ0p+1ovBm$2i}7z6#3l+L?AWU(v|r&?qIx(H7v zni4!Efa(HqL4FYZu4;HJ9=HNPr-&?;6T%-0a1TS9P{=mmKJlX-Z{D38**)yt&Hd%W zPrF|Ji+cLQtne3~boynQA0SViNP?U6>HzSN!atP4DZrP}$2m8LGyh)@~F@i?6c%?YVY_ON0hB2N?;x z5RDAfh5zw~e>CZFpawVrSUr;c3IHo{A~PI@PGZqFt6|x?Dyd{Aa3k}5V%dxkfS3`-5gjI^Fkjgk6k$!W=O*+{qFz%ZaBRCyH3hAZ-xoZ!}Z| zO)$XLn?;qJb@5_Sq4` zXDZ<7F!jMOyg4on^nhX%h1f<>DLb|Gx3&#Z4Po{I0(?h8vaR%Q)CRpo3R2d+DVy+~ zRiZbWX?CB{yD`x`KT|SDqt{$mJ~+dm5>$78rh)x!)1Pi4hS=6V%PNxEI#C@lKlAAZ zo0jh!B4sW#d&aGA{wtx6CjP9ZrhRHYV!pFvzN~$2c7DLWoQ68Q(&+wzxcx$^$?Vdv zfr_Zb;L4Gj8HyjW3*!p2lP?#KD_?KT&o9hdcfM@jZAZ!&mkJ0h-Z5GF^>WUwqSws3 z_etwA?Sn!o$#NQwr6^bk{o4i7s;B4ei-YY8uy;tOnHcEJS#IrS-oK64Zd!m8r*3rM znDz%44;L11tgM@@%J{4XC9Jl$uU5CM2)&{~A)ouA0F|n>M)_4A`{i5vjueXP0#&OF zdvlEO`OT0yQN=Z*m>?65RZ5N(vv+G(Xn?B}7|6}FBj1e`hc%&)HS>iH@0easHkwU4 zYMrUTdZ8vu#-!b>R+64vg9#;P7yt$KZLX#*PUAeH{4QHEpwbv80 zSKqc#+OaeH7g@#lBkSh=SPb*}tNrev{oRT^yQ~5jy%`Ox=Z7({J4H@r{jcrE_#6ARx`yXprt49fHyl z3L6d5p`ak$-7TXL=@KaiqJ(s-z;1r`d7kGyf5Fb#Is0DwUZ3lFzgP|)9Q|PYzCJ1J z?@)WPTH6Lz#KhU0@I@aNR~@}yKUou|Y`i2^!mb>1VEyUy;%Spl2TM+=#*ZkcHfUEU zs6Pn&DcEIytUPaZdrol9x8W63rZ$uFKNZfJfFl#eu2;CgV(yR z_Tr37cV9d2;(5!(@8t_!)^mg{#rAs=R@F<1qaKaAOTwJXhvZkb*sCzIYXWbBPk`Oi z(95mKt6)|`kM9G5y@xuihoqFi@nQUE#p9sf>$t^hrRw#xu&Y076t1cyWL|%qlCS)0 z|17E+##4}wcn-#@L0pDU@prT@dudc~4gj)N$1sQVq0_otH8Mcj!vOa!bZLX4>g z;xrKBZR7Mx9U4En)(`tz&`Tku7cS{_n~#0b5{qTLP`D{@uo8giPuPyXX1xyWy<7Nx zl08k{Q@`bxbg^mcIXncy0_KdX$$le9)1h+!AQS^7WF^7-qgK=hi~dh2qtoA1CUz3k z9?a4&8jh!Z5(@r2W3QgZ#TX!-oyIwq%$;!YxJZmsD_epusaoR)YXa*331upYIM>HV z1Nx;;a}}Z(jQ5NxjcaU%-W&fmskP4Iw$@xgS384nQKCLEs{;AScRjBe%g6r{%GQTI zm>$`DdVPC`%Vc(p=#L_0Rn1vCE(smjwf`D7);C2r<&mE61a|9`yAYaK0`1`%ZS~h~}%sqaHws zrmoDt#=nP9T-yJHGFCtSzEV7jk{p)EvCTY=X~P#?z^~7a(Bv(Qse=@WFi3i+2(V^w z-^!yBN>GvJrONnXP*jb%tMa5=fBjoOE}H-V5u;k2Z%6VxkWEvS;^znQ;orqMNn`xF zf<*X^fAtGh1aWWD&}1*gE7ioNlpjBpa1n3fZO8lt0q6qlMp&N95Nh%A$djCDQ2rCA z)D*#`<_8R8LkZDZu-j_)DG8MOnZ5>3NwdK?``Y*nEs*qlN=0@e*)UHBQko|ZYievZ z`oJ`2pe+<7VPft=y0`E}eCYYYj30HPsfxTrWm;%#2f$e0SN<)Z6<;Lkm@-wUs` z?$yq-o(Gu1P3yC@0CH6+yD5^%c#QQn*MS9q?T&V-Kuj-nD88v>Y(t#hM9MK$?Jdz( zm7JsrCYEnKQ14BY&t{3RWkAP_iGW15WA4jeLHRkJlJ%BJF}2cT4jg)vGcm?Coj*Qg z8&|qiV9QD^%JV8<^p-{0rP(tzG4_Q<@+QAzoXR4GrS~eoI)B)%DjN&lY-|zkl#P@3 zr9>$(6e0KDZG;BTwykh?d$}!e3q9{Pm;B&*KZ9Q>V?>u+y}0ji$mk9{*?zUyS7gxL z)TI(*^?Zc&s|m6v_0QDNoDw;c^`LB7&!w7T48Px`>i3@Wq3yf1(|Zy?3bEmve0%xL z)8$hTlXsZr)kI+4`pa2V?_D5Zedz(=4_h@B-@bP*KfOAmj$G&46)pPs`gh0(%iWKs zdioDv_a!U*3ID8kFO)TC*(RKS6~7^@d0r0Eq_Sy@{P&vF_2ZB4SWcIPOsm&v66f@?IG)|iWP7#t|@iZvbFG-cn(rVZwbw%IQrc|kBN znl{6uBQ;qOXf|BiT=#~8-=5~DYnPOd`m67Tg;W>iYUKMhbddUYm-A{WVhi3$G2%IF z5vQuPuNo5V#2r{9mcV1UjYypCqSNYFb)8B5RH)sS3DY-qb%nIVLP0LR0xHx(%k#wW z!7V~rX)Wc@Q=WqPF<$+kF>9OCOdPxLctIe)#(Rob%VH-n9#^eAjF>>@xD$Vfxwf7t zHlO_S4nAe9dH;=*PuK?|XDRH+_(!RS0@JTb#fv_F@oQ|##pzQzY3)#33Nn1UMdhMU z6s3#GI^*AwE0g)IG4XuYQ|s|#$P@e^wKg;tW0Z2K0+*(2=vZ7z-juH9dcnr#NSO5wdz=$uQr+oGIncTqN$nQv)0 zFZ}j}mqm%8Jn6ECHg4I~AaQg$D5Hq6Dy2^&u5%%ii2AWm&6t)ogW-Eke3ftF)ySI+LLRE+=^7kf+) zY16Z8I>x_ELUN-aFSZiy$#BbNwujIDpi*0k(<$7lNNg*i_)OEXuFE6@kw}>u#G@WYw zagL*RG-=Tn89zg*Nowx+7kjg!j{Fxxmd^3scIIgeDnfxssz?~)1%(=~sz{2!)+X~| z`%pAk44~}sgXO2|AhaEl7~;jD1ON6r+@I+^-lMBNpn_Kbo)rRQdKi=2fen9B-mt;m zZcie+(=TbkMnP6TK&40r6PRSn({pqnk*@Ej1*b&>-8WmKrbmLRFPE9yzSVjB8Vf8j zusQwswY#I{@yDV@8-yI-?SzV#i&Q=7qka1Uh3o-&8UR3`e1rgt0RqBPl38yeA1=}n z2za0zq`JP%k?%FQvN72iq&tt^-jfE~9@}zx6OYTU?_ct7A1al@A@*&G_er8bF%;4*B@O@p$#r6`=BAtt%UamC%cp}DDr+UHni3C6r>82sF_(tbJ)Wk% zrDO|P$m(<<3Th<$0f-Oh$z?;b$2b&HR6p{#S;WDbz>zVYPMr>Wr&RoL@E2&;Te6vY zGG7n$cZB?^0on02nalOVDz(j)zHbZ}_0+Pgq)S2m3cFTzl6K+XuYqHT!VB}Y&eMw$Hij=y6v+82;70(L*06#Q+ zyLuZG2So-V*aDuFg8-1!WRwwx)n4@y`j+%V8@tu^ix`fnhQ{;am=!+t-manFlexev zjt_w^h%niks(G>{AQk8<%EHumcF0fqu6n30iCxmY0}4E?2LV1|7*I^8p8$-q1YTqO z(>nTXFSQ{tI~={|2W&g-J-b>2w)Y7^&MEXqaC0iUx(hGJhd9zw!KeG~`; zkU&Un^!kXV&_h|`f8$qK=oAHDm^XS+w6}m)sQ}vRAk#zas8q`fCBK2vMYhkhqYMaX z{|2J(mlU*NCuu?#wMQSMJD!#^pG>fyZZ(0zBf-9}kC~~PX{(R1uxq~@%BC#O-drC$ z2a91OWeSXIppSh>LL>@~r%K4=Z|-j!fMGd(qXX4r%*w@4SpaB2d(aJ`n0ArE7O13xv^b8wFL zD{>A`VIo4Icwyc{%H2J1BW1pGCA}YT^NgV?b5z(g4uB5$Dhu?VgH*04A2;kK)^A6m zTn9ke?ZjyE!d*O6odtVM2jT9;YUS+=EY~r^&q%502)v{s5nwUdt$zD`5<50L5?8fA zImMR=YOdg+o63<`!E`q!Vl1LLB4j7d6$5TfCyjC?OAky+zKKnt(nvjyP4i1yfqssG zgbQs%{M7rL2_{U-(8!Y0$h?>2GDdSrp!0g9sP@r>)zSA3iXB-AMapBvMq?$8W2G4h zQpZuD1bEV3W0lQgRo!pK0@az7;2&4(atM=8C}LmlkA$5QM!*S@t3M~?e{S)MZS~WN zMt*6}`SM)^A8vQ;mMf zNB$U%ly+2!wo;E0R|=9FaO2db0cW!krm=NA@j6y<@ru@^QkC?W&?h0)qC4E5_6dxJaT7vYO<$NqB3eR?Yxl?S8tFqZ89i z6vP`PXqHlYGqGqfFzTkW9XVbrg|yj;u@ym0RKtJm^Hsz~n4x1l)g!l7q#-vt0wlUi zub$os>eenrgo@yaxsG1?4G=fQQ$xY-qcP?w5h@(e@8eVZE4m5%YF}@3YwA()!HnXfl8i=eh zir90YS(tUby>W@_YcrojBBEH$r(O|!ya49;C5b4rzUC#lYBC|D-j^@Kbqpi^{NGSQ z^JOVdopvH5rGNx}X6d;m<;RiM=aB_m%LNyU8UBNNybFd;jkBoDtexf(7v{_LaC$=` zBx7-Q2Nyn;e9L=%|EX%$6e|tXD@7_6nJP@7m|D~^(Ajsn{K7m*$gB#0LLi`$t`X#1 z-(J36NWUEqm0!_Jd~X^U^*Rf;|23}parA6gW)?GVZInfaCy~|;J|Z?;a&)GsX!3WC z`J3S7!5lL((5hC&5?Wq(LIl?kgKwg4Z3w|t5vgdaG1r$^@+pb$QpS7i3X&{0z)rMG zM($gwR^q~T;*|1nn&9mRIMdGfFS%M z04D&tzD50XumV7xi-J=$X?t5`Z?1pJTrHHEw`oU7>VYD=rA80dt#jjpM8ZFc-~{v9 zp5f{Y_C+ZH094Qz?{a+Hw`+e?7MFkOSEkI`L&Eu7BV5*OK1nPFW)fKwM17>db>>BY zXwZ9RG50)?Qa&Ci3*_PTeJazI@aPDv9-i5zCy{P0>3KoAhF zvF@NyiV+khBD%)KBLVQDtyaVwea>wwFhI{Ne7BV7pi#UV_f6wPg#_wfa!FQ#G(_J> z@F+x3YX{b%WSg#+%jNk|78ph9@+fmXCl?#3`oO3X=xTuT8-Y(wR<#H%?)b_QDInVB z0QcAPx8K;Ji2#Rj94RrrsxGb|V#Cp@MPpaPd?)v}>$~!%*urwl-?+$sEenmC+at`s z%3bjfnPLT9@x$*&l|pM3X}|8|-NfD!jon5OLjmHhASUGZgpY2@ALEVc@dWPyB6PUB z6mBYu+mnc2p?FT2rCTVp^^sk;WEKv%e0Qg23)whETS-@fOBIQ9BZcZ7H-9BWh_y&rb{5RjR+_{_U9$sjiJBQnx}_xFH~$57}_ z0l~EWF)gKQL^qdv`6oO5fcU~p&!V61fG3v0f=3u7BlU60i7XSrZgZv0QW0Q8Y?hZeC0nP^_DP>TSW*`;o z!=kqqOOrW!G^=tNk--E}vh5LiSux5x&u4`Xj#)hOQzjJgknh$pznq`HIMlbt1F=`g z*;%^ z5?9yj7+=wPg=U26k@u#8w-6Z-h13wIzOwy;ypIy*rZ6(;n;jg*yH@K6Dzt?FH<7ImbXihmpFs;qs&+T`@7P zQjuHZzf-@~?bYLV|MCnmyAS;aapbw6Fh-FwM-ph?pzR|QQ=NR*&a%0f@((fv$3XR^ z=vU~d^zQ-1Pipt-qg8g|R4L>KK3-MS{cDnZj)DS6@8+Yv2fx|&&6nyPwCo-hAQDW8 zF7xHe3?@cK_a8b?ngCJ2Gc z>v9wKmrOtp*UgcW<@aKf~&*@R#9)KY9AKrsie6lnkfQVMiW9Qfoet$X>`oBV1 zH0hZ5=*|g;I)G6&TF@F!~Ug|-xX{xA=Ps5%yTl!fuUC8&exxI-;FOexkvzYFj z*C3kp?zQ^fIp2J_L772~`vt#AvDOFv!NY_W_yO3@^TJI$$#3J_atHE$?&uJ0#813=ENJ>=NxZBIqg_^7lJ(*5z;GDebcCo_=^}9tNUidLK0W zr7%71b8f*ndU4f0}a{fKZX9Exx>3*YHu9A6))tA$q|K1V`DKe4U_FV_HDLn*=N8b;(Jsl!eAFeCADLtai= zd)kvgk&GDZlN0`+M_+`xZhX?L_==lDWSPzymL#8Ka8%fD{<-@;rwQFNdI?ittgp?-xqa6N)KW zl8Mwr`GrVt{ZAtQZl7RCOnC6+OP20Qwy0?zN_-=|lPNZ%QM3||*)%3fd_^6hzc_JV zRyd;;Hfc$(1(};-AzKr1z&nmg`nF&+H0e9dZyvD-OEfy0re4?M2%xM@Xn@nMG#66f z?`NG3P}JlYnuBJh4ccJlI}z#>sTjjZmDl)p^4A+LO>)J#M##WneL}mK zGg2&{P(t~S>ADaFYmisFtHwOd1C)3(5I-e5*NB3S8XO?Z=`$T8#4tl(xdkU9+dxZp z*Aq8LIFenNp`&D+BE!6%vgN1`v6kZlOvdfmrs!0zOt?SM&(=r3tRRzj_E!Mxpr0AI z<^NVylVOX0F2kj#swl1mjFBoJHO$hWI8#$z+I=L`Vi-ql#762?9!^BAG{gg_SBfEk zF%#{gWmry-L`WP)2pCG+d4i%6R%SXjAmA*gglB)NPY%6tctiA0#E?(uFim?70@4pYeBklFMc?HO+J9rbE3`oRNV zb)d&4m|rzLwa_mAF&yXq$A$r#!PQn(E2v!O!#Syuc>J}&-NNmJEi(D%OAv1yzFqj*&t0K)?~ALgBK(017}S5r6(6tT_E8 zT&$%+f@&5NiNqx{aw_H_+I_-hLA`;&htli88K3JZKehMgGUGl4X?yG69;D_&> z))MFsn_}|72*q3aXC^{2`h|Lz9HmN$?q)wyM3*xeWXlupPkw_#64(jg>O->6hbdk= zv$4hk`Z-$L)J7k)wO^!pJXVt&{6eN)WuOlewV^`hjmD~e;SvattyoQe#UuBFZ_0gW z_|xSC5#aysGD#`t0kR?_5A70rNWZpU_SB`O{2Q26HEK4U5O%hpO3&Vp1iHF{9!BCJ zZsIa}=~F491S8p|c4&KPK8d*UlVmm-Omr|`zLlTd7L=X76k7%zHi8R-=b&)I}N-Lrcr%M+2F5Pi2Wx362jw1tr8J56i37!=A-ylmUr9vsx!CHrFdM9Lm8r~ zD5!*tm&1^Hri23|Lyxpvx_E}$0M0ce&ZgGy{z9`2i_Z%jq1B5mZSuKZXz^ zxtb5fm}PDvAc6(pLWIws^}VQd!&hraJ8%YH3{8ODQA5F{{01tL?K36JDr;{0mV<%-M z&1IT9T0R4a5KY{pXiNM-72e}b9-K`_i61ds4zcno)e{V=g7zFT=7MhrIn#bfH7ax2 z|45N@Xc&T7byG@oVo79Sk%aLG^3F~9e*5n|D@`Tr3})}8eiaG2J4n(ngO&^Fe?hHQ z_2tGmU~jXzPMMWtm<)LPc8ill8&WY3M^t>bbE%JOLl zwZrfF1X@Qs@UVlyiEo+(Jyr&+FBE~q` zggY5E7gMBROByf0_f+n~r%DckEA}>E#GRAd-ysK%dx1%e!f)6*< zDfodlld5xMf>oOPCii%1iD#&)W3)NnATIHEsk;5I=o79h!m>qUn>agIi@7qGiB1Q+ zZItBn(q7ry!0eg9N7_MLb`clfMQ*>+JU`7XO(ygQ>UA}_zW8iscXnroLg!HaU+%MC zyib=12&kp=IfMUh2U@HJGay2^e`+d|h?3-~Rg*Cy(q13(I0(DiUT$~a@I;d$B?qIH zsdyb(Ty;&HM8a9rvrx0=9I6NakZUO_)P;16cbjv^&ub@&P|3;<6+6j=h~!bXclG-i zNve#cO$bzWxwQfwm!&lFB;rgM%iNbkzTVtM;9l&+%J3+w?ivVlG(~|4mRP8qz~2@K z(iJMioS8;Scph~^t;%uU{&lql@aY!rO1@PFWLdFW44P7>I7n86FIT{)`KnS}(Z&F| zn*oKvikv;%g1d@*14ng&5z(bwH7X?4@yO&ZPyRB8_j38xS|Ls#-0B)ow|Cs#~^ly z-|JbM%wF4`Lk&%pnqFl|F!*($O-l5$=cQF@Mgj<{D#QCR<2(*(tf~^j+h?-V6J9lO z!mU0!8cD{9CUa?4*w3Qhs}~wl+=uCi?nejjzyG-NE}jdZhfFiyRtrSGS$;OGvpu|6 z73l8P-vYI&#{b;NJ;_p18UMSp&;zbKZtffjkV~Wz=Cryz`o=OK>m=QaXp{K7%2DPL)x)|5LISw#By*m#Zeo-m+13P$_WW zEUcWMM0buPSI1Ex>63|np2ZBa@*4P+UyCxRf#;9Z1g64{`^6INEmplIGc39)yiyaMAmIe2p8q}4OBF}H(lIWuI zzu6;&YBVliT=@C)VdKYiiQGL~*GCiRlAS?p|(aMkDbSSx<0a;{ihS*V(N_fy>{o=>Si#yOI z4)T(yZh6s@Ss2U;&YQObm-4&i+aL1Y9im&OIHU$a$4F}JaG7?moprCQ4m90e1a_yr=>C`}Gw3MpLEm5luj;6KPte|YXBq3<4@Iw&tiTgE28XZPYgNeWf#xY^ znDP%fovl#-fHPdyLqiZ!%Po7zMBD^w-fuJ+6qVWK`@Sni?*4YSpARiI_Y-B6Ata=G zq?z!}O8N29#|U{$cm^9wO!)daDv6BWm8J2JP&T3CLFW$LG=;WX1oN^Km)S156w zRX_sFDrdmc%6E_K_cwPB**14Lq;D75s6v1a)ds$4IFogN%*Ygc%Itr#3YWp)+>2xF z#!$&Y6>&Nd=!#b*-Vy5xBQ83U3kg=sWLEy*_rAY*lkA-9y=a{#=r+->XdQQC(`C@4 z7M6APk-cds%SZWZt+wprr!QjqqIGdcho*M?pdr5v9=j?H6vHU`cER~-%E+hZwZ^O$ z5F3dDql@3)nhoiZyn{nh)AdI01UVSDM3NsjF(X^5#nU9u`J?>}x_oUNvdtaT3_&_X z^+SqGQ`tD$RbYrx(hGST5;-v$eGM3&TSk$Da021T72&9N?7> zFP&32N7TfB*HAW_<()e{YqiH;233b!ZE3qsNe1LYE3i4MG3p9O-Tx-LVAHtqG{s9yCe z9|x77mEtH^HFqZR&ABsg8;Ze5a^j=pa?(|Z%djiRfQEBV5e;){d>L|d85nVuYi{@` zfe*h`GGa=C$1o6bc1buap=1ttG^zsPXn$__BsyIztch`j9bVkBgNphQ>C&of+3um+ z78QlE(t~e?w_Bu-LO_tg5>iy~X=G`Mt**4e zN{3XscycPtYJWhrEGUEcJgH04l`5K>>LolDVCKp5E-a|%-;)nlQE7~y0aW2ubp66O z!TE+4`5}K?>JLPV+f_t}!bA>=en@)^1kNV~mRl^5RKu+@BGjJ+hrbCdV{CEJLmqfO zfIm_-V!x`fY^}uFCq2#ts)t*};?!U#-Zym~;mPXJ)i8Oa*|+=UlK(T4m8n$?9x3d& z1_Na?YAFR}o05YPx~_9yM3cV4p8me!{>jkM`sPVxQDf7;thNYpPR=gNbXiZLzuk|U zT&SWS#3U8g`D$ZjyWzn-jAb272{;J2Rda;ENl3@{kY%CnRal4)vXgW_+D;W1$s^Zq zE8DppWQ0syN=f{d|J1K3aRr?S^Fj$`4ajMODg+1Dwn*s}2a8$NakuQPVu7xPuWIlM zhZ&zZGoh2G3gG853k{u@YFFCxjoO+srb|x0L`upquEEZ?GH?u zkzcx!Ux~aO>K&&W#pR*6C6<(HFqB8Xi1y-zr)#LT7`nEyzGfYf4SFPu=SIP|af2U~ zqMx8gC^{&JI3Q|Cfpuf`UW+c^?}S@f@vS{BSo?4@_ux){y3PHuJiI+*hgc!*p+atW zs*Hp(eXc%3jXvW<@MFJl7#%gsF69-@xPj;bQ@B^bo5M|S z=O4`_^lrPS4FZi)>MJ$qILH3~LYd%FzBVX|oUs2IA7rl*D>BVY*-lK=M?UQ?4b}rP zR0^0`m{&pTzsSjfPQKBr6XYrpvU+LWAX5KVD7$nlIQrh}OcTy++?nBKSf*Q`nkhq# z-HQp6t+2>Y7ky?B&E6$^%h2iq(7qL+WRj&oWk?!AQfk^wp6hk`hpi8-7`~XU@%eEx z_vD&Y@ih^^&nx;_KN`A2LhwqYZW1kY3Z|rb=?dX=C#tbuleOR{u~IoRXX| z9S`a4-xvE)q@FzcE5RDQ_FVIuG;|n^58~_|N0X$`pu=CEqaM{Tx56oZs}z>-<6s7w ztkv-u#GXJgI6-1SuT;}=NR>G#HxcKxf6(g)JQ?cStD(>^EEWj%lKfg~dDyW;HuxK0 z`?p|Avfj%zg7jg|o5^0V?ZC7IDJy@ya8i3n^m}G2UP@8OK0Q|~n?cYvF2EuUTdYiL zK*9Uw6$NmU@>Q#rD;nVNPbs%>D;qeQHlw3yl zq4^Geq)3RGay%^H`HYiFe0yG`l>g{`P+6{3J;e@{B=(zAzI1cP$a@hMcOQ*znrmf6 z0}4i?85MdbBfZ(_$cgb8?#w+Lr@!9@@*A|xiW0eTuEoag_=l?IJ9U_OXH`KZ$qV%c zDP`p^{Q?&jExn@-W@b#*D8~O9_{S%QBE1oF(PGddQeGm!rKvuML{iW#WWqn+y2f~n z_?C(7(aMWH(sz6wCzS!?E&@#cEf3;%M-n3FW)bm{#R!PDUqJ$mE%<5y>(1^?&Q6Pn zZAO%pTiY<1ZA8)2s3SVYg_^#T@Q}Sp3l%5ypOY$d1(A}g*R)Hxb+JnexMMx9H=^-3 z(e$?uobQD)Z)@r5SdGWo{JE$`V0LH*bO-fhSr62avfwZ2c7H@6TOiu=c_7(su|~$P zss@O!3_Efv~wq%QH|Q z=*OmVMcUA_0Z4Yr3B|O5h129b>~wH?NnDh+hTUhK*a0Aa6oAA>PYHr~%cqQ#mR`-K zOm2q*#%ht&U^7yDCvYHD2{SBfgSuhoAus>WXdd{ck)}Gu<8uc(Gj;+TndoQ|0?ve> zKby$zXVITS+ZO}%Ulntj$w|8?=s`TRur^=Ud&%bBD zKfg15pOP-)SV$^QSZj3Y0(v<;Mc3`G>2&9vC2!8f6tX+yYB2~zk5VatF_DthK+nEx zZt<|7zESVfYz=qk*M}m>VN&+l2jDH~+l%HIjol9v6$T=_A}Ijz4UdsZ9%d}zwAXA? z-09#NQJ)0B$gwY%bb?(@z(5C;UTkES858H?2yEWAJ9juS|4p3!2W3o#`p?D^Zbf53_KWjj%|`_ixyd z@T`6;jL8aUn9si~7Rg0jRz%zim`XaIUV6zU`qHqGUr^`0|e2s-b(>wnIO~XF~l1}gnb-1SyQ5E0JN0Xc$&&n6Z zvfp$cT(k^H2Q_`!8kFq~M4LD6NV7iYpWRDrQo@O@W zIB|{iz0by^u{JX~iza7}J4v2p&*V5u)R~W=&?hygUmT?I$v^TU)gT_>>Ev{DeUC4j z!k^u2E8<&BlkOynuA-wEv$Ce60=$cud+gQK-Vafgp63e*{a}1?W$FF#tV|kz##I}} z_Ve|=?+1fkZ7;)57d^GU*37HzyL8z3785=>>1i@}#@`8Wg1^z*m;{B@v`=*=43)%u z-^{lc7AGX#`DGh$861JMduG5oX;Mi?9u;u*jv6Z?cx?*e8ue#H!aSevE;F> z*9NA!ATGd@Se9k{Mmf^MPp33jp`An)snj=c;?HfeXER~bXYbw|emcKZVyD>TrSOK7 zG4B3zD+@f75G4p!V1?a_DZ!k-avt51)E~MQ-LEy+aUEC|5k;#m1;|E%pm}e1v3LZ)YKV-eQrJ_8#I=$Em!1*DdP0PqH`{eD(Ym0H$xnaDdG4kl zsvC^&pO@>@gQF;bgq*nMpK%^huq&g5meGXbbr5L2b@;D45sK23>7Ls9vW%x}%63dX zXmE@O$w?I;59e=M{XZgh;CqDsbp8ht*um2C!a(x#%458a(R4g0)mQ=kun57>F*yo+ z`HB3HXcPQPC3t5F@^S2Vi-MG}0q?h0wVWH(x*f5zBNx#mIneuIYCOrx2tl95j#&Qo zvL0Ko1D#AAj;GfNyEj&K3Ua)~dWXJ|YM{wfreM>@(B%`#MUlQo+fZ!^hL%&h9aARi zpChM!dwA1>z_i%plPkP?Ukhq}&a+C0Tnx5vKO^=19d9T4MQE%AJHc{luRQ+Aec6(7XT=T1Fn2dv@pYR zmdb{!&U#YG%4J|GN6FqRdh!5CC|5!#n$I(TNDC36+7W zu#53l7zjtFasC?s;iVChJm8J=25QZI?SEjrH_C&m=bvd5sGTLc1p%`l!Np}95rtrG z3PH6rAuO|j;DA2;T;rpvLU!F#dX1vL<@!VzM9j{Nub{z=uYSZOzFG@SS}z|95CQN{UCcEzv_lG&dZ?aG&Fhv?X*p2ogc<70H48MS z+jJTdzs6B9KG*$oCc}{lEqW+6m8usptH(youbjU}>PNy}AC_`utSt^a|at_8E9BG-alPmKBp zee2syFtC*`BpmP@W0p?+8&U{PDqxL88n9j3TwK_dwb%-@@;?e-L-jLvI9fJPv(MMk z>b2VGzID`Ug^W`G9&E76u;ap%826NzV0K`Ux_H#l`rva3?sctdSmOxSRcO6W|xFHKgyi;jPcg=^7_2Z% zXrTm=LNaS_;78|EPxi4XV3>^T2=@Txf8a_CSapDW zR8m-KdM4CHBT8#W4P&U#=N>R-qoVPD-s-9U)vxAjHYW|6-o`@!+Mf_cF|P!XK`^sy z0Qmt_^-2MTY&3X<#CHX%l0}adiXa60AivGPIk6xY3O2;0P|9f#B|Fg{Puq%jNaDcY zhIiJeLbA#N(QZ?S5rB!)4ib-KytHF&>{AB-Xw~f?kr-BNH~?U8&+T3aNzztKpbZ1+ zhso2hfzz}IP62+4kV;N6%4^NKHa~JHdupj4V)v7zO$#WDQ@x*455^_g9)Y_V0S}DC z4d*@;Ovji)D$TT|0cK(nh zfXQ_a$vMJas=ywEJ_*ESS2zz$Hf+o$+F;xVGVCco2nkgAN6Yf_B)aIU=a7`KOSb7m zpg6QxR@G5ehf~F*SjEN>Jjq5KjU@Y3;QfMA4IAJH0F@@I(C8bEoVa{2-Sv(oRAWc|2m7EKt@>1Vm4XrtwcD!5rx- zl0+MWqa0kU(OLZTZ?V2iiLMNI3j#Li1XmvJ(OBeoW*2Bt!;MV}Jw-EZFsyW%5E&rD zj_K6({wzxkiFm$4_x(SO&WhZ>6$LW)vx~}#&dLwVv@GcIM;^1y76W26Ra^&EeVwyX z9@U?Nhb2Ar{DaF9o6Eu&0O8A#C!C+LOM(;Y2-3Zg%8TH-Kf!gW!0|nqdfbqD!mj%J zAOhve=T(o)mf`HL%RhLR3q>u82n$2sELY2V49G!1!Vs|Bza}NwW|fd;jjraWD@~Tm z%>sZX)`Tkau0E@OE%bt|PK?uoovlI%twMq|6&DTC-g)r8yq`fu-%V0SuG>>Xa@;!C z*_YdTO{{m(ET<5H>JHr4e|}w39WKEg1KC}5jApqXYEJ0ciGWOpz|5Js0>;kvuZ&$U z%(}7}y9fTYG0T4Pv@reluXO05C$lTnH~3S`bo|=$UdnG>f4WLZb7B@4(4g*5bN5AQ zS&Nmfw{47{Si3vuUqvzBbRGRO#>(FKF39%7yVL3ZB}vK+Y-^)EGtpn9`Ycz65@ib; zuN09FhTdom&1hkXR{NW}dS9=WXy%mYtPZ~<8Bv)uQd;e~&-#+DehTsJj+5I>urklQ z84By}uj}r*4Y5;2u%GXL>605DdNuyJdwk+%d`50!;nl>q?uoUVi4D2QpRXo&yC)BB zCQqy;xp3Uxh>VKT^q+j_Z;|^F!Zd2G%5E<@L;ZS&zGsH{c7{!Umh1H_U(c-2?X0N$ zoW$!n>7F_H+c_ocncEvvMY+#aHwC)P3%I!hz+nIa0Y0^wXk%Y=lb>|yS@h1Gcp?8a zXl?vu&sUW7c$oas%quV=KN)LL)KODeI{m9tdAv@EJ87SZ;!?{Dyz~ zmii6Eyo_D__Cel1k94Jpc}*i?r6hc9#d)YO; zJBfEYws+g9p}UDTyV-ZUaV$Fpp?fatyLop+cS>lz(BH}6-|*YteG2*#Rg;mM~%C8?v6^}|1*hqre}6$;0=tb2sL$Juws z?`-gDp#f`mC+~DHY~kPe(lK>wr;ozyMZ;FOSWo49+ulW-O8cFa!Ooxdp25GhP(dDa z7qGM!PJ%{T^wC`FLDW(A>lU*kkbnq=JG#NDhk&$084gj5&NC7wy%)BMmoB}R zFIWLSVOJq}kUJ#9J{$92diRpI?wNTP)~uJfuuHe^m-zO7gT7zk!v2S~yMBx6?fXW* zW`+r3U2eQS=EEE&!r&X!J-(z%S}sm3m_x=C&87wf)MBMN11s--45CY3SLgpSn+6)@A6#g*Kyv~;&brP4Lv~$LPH@LpmZ*&p$aShlBuqBUJFqV z+Z~5KfO^{@)hnje^083PQgj%l+V9cuE3Z`&8K{us!w~4L2E499f3I zTp_d>;i(A+01zhuRoEu*S}u2sJI$1S z6ED!{K5eVYL8;ocnCQ-#ITNK8+D_K+RNMJm3bRNZiN6Ll?(%&P6f54;q^O>C<#X1uCM33vlc7!zstQT z{A3ZkmquAOuB)2irn{eax)A%QCpra zB=~4l=%E$9iNY~ygaPV3INHlei1k}|_G8FzF=Xd{ugp_MZ@7E_okO=2VauLe^n;j` z8kI#K*ANNd-w~slKECHYb4q|J`7cMo%Vbs))UV2}r(ZitoC7MV4Q-4ViX}&mu?F?a zxEBk*SD`nR0@i^$08;3l%~*^y=Ln_B-k;^GXZx|gDBBq4yheS!tt1^l({^9?{_KTr zDm`2IlIN*-I`huli2A!!2Wrz{@xt%obTRSy<=GGAJ%6aQ33p#50F0u#)!D_Ul>6 zj#IJ?+4eQ(_q7tlV!Y!VM2eU`bR?*XX;9DlYg3&rH%4k>*vV&9srMN>M5>8xK&3Es zQ%=6W#oqBAK7A~!eR$cc4ysqdDr8F;#lE93AQ@N*gqfqRH&Q248uI|eIBq;(13EH7 z$MKo#T-wk8SyDVaR$jgGmz^ltwsECX9J7CYNg~mr3NoGf9LY)pRL8B0JS4?%<`>aY zE<36M0X=e8R#;9kF#4lnoJ$usTg`9PJZ8SD3ZGQ2>=G*qEAS;TmOR{rtay4SV@f|H zK(kQ_zpBxZ=hss!gWOtG_?#5Oppl|ng6_SymQQIw=Rj#Ws>;-|922^wLT!pyrFUqj zw3Hz5*bi@$pb*qK=X59eq*gBK9L&am{`*3PAs1CU+jtQ=Tl%m0Lx|y|7|u~!cBN+{ z+O8O*2r#CAGNM#N(9Jk*pBiz>coP+gkMTpCyq2AJH4Jt$%1`$x<(K}hUgeX0pA|&0 zy|wZ{fo%MEdb31T+ST~>cf9ZwPPQ^HtQ8!AsU`Yikaa4yeGq~Z-$8T{QbaGs!np_S z#Gf@1)9KU(@~@UyUbm@HwxC7jjkTnF$ijHmmZ~(Gizu}4H*bi%;1~)0D8tR)-;XQzyrw^|qv_L&o z!}Tmzx$3UJ@`B4hIDDfj-pRhEP4YbVl1KDdEmrTunU5~d&&74YkQ z=yMlUL)Pg?24CtKxm%%3A&p}=8lMtjWE(5)caEZ$0J=_mjf{ZDM*bs|kq7kseTGq* z4kt4|h=vmcLUWA{Nr8MB!|C4|!sDFrCPb-_kH-wI zX9PntF;b?78~P8QeaRm7$=*I6VHspcRUBh`vNfm1f(RQqTUAI~3H`|`mC0+Fe!!u#V2?~EuVd=$R z(%LAliXS&}A~8_uJ4UnO*xeI+z#Wzrw) z#JR^~&uqBfv#P`>Qi1*Is~5CF_qN{0BrOU};j8Dz+%5mn<{rbSp<%_xFISFg5bV>o z?2#R`_v_@)ltx%Gf(*%(plpO+TsxvhM)bLZ!IPH*ZC_Vq)cOdV?uW&~!Q1+I+MI3P zR1Y`GI*PK0PXt!zf}UcQ@vHT-K)SE|y&N(0TWY5)@f#V0%?6c;Dx3 z)BKNwU(GwgKZ1TVEfOeyw~>b&gkNi3rb_(XB^+`X_o#W5gX&M8UdU1E+vfFaiGKzk zh8$=AXx>z&Ivb4*IVryOY1=UIY=Wg_@Xe!7JJwWxn-xRvQ+Q*8>=OUZ?S%aD%~JgF zoa%gue327o)OE8|93E*l!rs^y_G-;5J}{`Lhw=|(lHpxW-4`s=Pa=j~g+c~QaIJ*4 zMJm2i#VwaVzu5H);;sh4*v{M8@AnBS$sLBt;nmemr?t3)4hV3cHPn?+(kYvJoGHNs z;JNAn#aKSMxe9bnj11}xUq{1b(eMvbAuN4Zwo*SDF{*qR@CxIavZMv&BxQa_RnhUW7IPzsAlu!*-Sc+6o;n6D%GC)K? zIV0|vp-k(Q%ov?M|AhYl03rh8cMz#C>h6leMVI2nCP1g7kCEb}6K$xZ{7?}_H}7#& ztXJs0-@eNmQ5XcU4k*WJ$GmchIp-$b!RNu{ji8ZUGO`$|>?Meg7$rdr3>ZN#Hz5IN z45clcxMUDoVkg~-PCttBP^F4of@lJW3BQ;TMEqFBHHa5t217-B__<9L=h}k84ya0@ z!7b}?k0;3X52&X7XmUzrnV-Z#ZQ+P9%4RftTs!fnOXBZw#Hv@~-@e2P0nKnP=+Ysj z)mkFd6%YS&EzgMZv>F+&fB2-W(XaU5@ruv6ggysCYb&84o6uoGXjUiG z-5}KRkB*KK&5GgSVWL?vFfj1>^XI<4zV7bs&d$#N$Q3OuEzQl%M7g4_uI@i_MNLf& zp<3a;@QQLdLd6wADcOJIinCJTrpk08TTxY2RZ&s#-{lHIp4YpgqQb&LB3?n%DhR15 zge2wdq}zn&Aq0Pw)j;2zoSf|J?5wP;^z`)9)Knr~k&uuO9Uc82ydpF-^na2o{QUfg zLdBCOPrSXo|1DGyTwMr``~=gx1T!Xrz7#=SB+bdr&CSi(*_mio*xTFN{2$E z6ciNXSq*%woUQX({hXs$ zS2f?{fBb!ZpziHrD+WT&u3vw!c#WM#OJz$Xr>GXst(U9c@NRto;e7tZ4zm%){^m+Qlhikh`p^qY(w3Tf6NL7_EipKKgFn6Ms|?w9OKR(-Zv2dMT+r#$zwUMy|4#O6rSwSDm(dx-2@pE%;q{S~WCnTu$n4dne#;Zq3 zY6~i`L^LZHGoKyYEwKsR6`i)Z`B#)qN7kIlWjTV;snpiDNBs9v)M)@?A&%x|h7oA- z&b#Fpk&jy|7zBMPhU6c!B3@>rbTvWdu?h^X025rp%kmi+g&a-3SPORGjLu6ol=y>> zMnoJYQeAT@TTi!Cqc2i{G^4sQ9MWAkGKppdUzV1ccUP8IkDznbH6LDlisSMOPimm9 zY1hl&U;l-&2`lc|UQF)PYlKJ0+dswg`5*-CRd5>C~sX4tG)6IEc^zCP{19dFei z%v^|Fvz34#K$~H2VT@Q1}H4)Dyn%WA_u50o#Tu~8r_1?Xln-#~ySA#R(^*dcO zOALyqWRwihaeLH^Gt$0U9#YT}{W-z-$MWdjgL6qRFqhkG%rpKkse&|ET;I7h)mQIf z?U2;BM^vfaSfkq>zvlfp96o#&-y;-8t5DXD-u=pk6~!a&b4y)UbL!nQnH5p3N?uEm z-@iWgOg_hUKEQ83U?Om2txh%kiGz%KEXRb*hF&c@?Yclad((Q-eWe@N?B`W~_bnsY zzX-bjERY7mo9$sluEGSwvGBe~r=HqUZCGI>+XuzH*>zi&*A{}8W1E<$rM$|l(UJZW zQhD__S(9T=ZtllGWy28bu_xg|^o$(1?EAfAU1 zp^E%))hr@ZA=4S|P}`yGWQ3n!Dvm_kS+f=utK$xgRFo(R*?(zgCy~bE^oV9f=2lm$ zsxkIhCX?sQzo7~TB2>ZmZ>S=5%})MQ46mP04Uo1$6)bFVbhvo;H%(c)D(^lgzJJI4 zwyTc@A%-`5TmY4-G z5NIt^5Ah~7b6-%_8 z8O#%8h)@NtM8SI+m68j8<&3O!;aux2kACIjQ1*s()4#LkppYXMjnEPd)vF;`Al?@Z zReCZcPrc3e6?xMw^zexQJuOcWhXH=iL6BwY*+P0nQ+$=r{9TKdi1j)<(yG53vK61* z9B4VDF^@kDSdPoxvmec=diHhp{#%}ye(ZhZ#%ojNd|LOTG!Tp+*5qWK1cSuLy-4CpW^%q$(I+kDB1yjoBR52AJ^4h zzPkTRd~oHRn;9SLX-pIYh24|AIxZd=*gd4gZ1luwvk=THHY$7hI~eJhpeP>yRxU;5 zM4gdo=`ddLXtks=qt9$(J=UJaK5I~>OWM;sT#yE1a}q`i->%Vk)7&8J{D&~4GAE&j zpIOfgn(48BeU$pBVG}1c%_yV&B=5_NHF|Y;$jdtp~pB7QEW%46oj3amk)%*YYkZ-!mAugQ`2JuM zImrfEuvo|%T;+WfFcg@pQh4LjccyTf5px9k*U=nj;uLgqS>ro&PhSS? z?L0O_PP2-m!B%3oSHwrLs8lpm6ai4U;lu8-_EBHfK(MO5xxUSzMlvr&R1RbApRX{E$aL!k;q8U+G2jL}dQf%u)evK}EkOz=#mZv8C8#JINSO$eDXDw3y=hUIOiwZ?63({koSG~C*OIrpbO$&MK zPceM8uOa4hlCNZk+%%7~#FwJ3e9TXL2n!mQt_xV}R1B!Ur^HDwpjmlkQ|rH#O}R8Y8Ub`DXbv^XEeXVuLPQ ziws-RM~9ML^t_+%hBO;{zqy@zc7l#XYstx&`}Prii;nny!b3$6Xt;I$w>MSe(O1JW z45=vJLl5DaB95#?EhjYoU2heC75mav)x}9=8hnt zb~o|%z_(9ASR$}WudyUGzS3=&?iX0vbh{|}XDI*B4Nk0}Dpt%EdvF~5iGh|@jKbL$ zKqJCnsXDgy1GMsyZly@n>hB1`ofgTkx& z85ukxvnaB$E7DU2mx7JpD2NbkkFZ&fVqgq~5SATU#exjAG0$b(!u_K^*-Aqt>2ZC; zcF^FsX1ls)L`%bU^SE>QwC;avwLF1WB; z5F9@*uF5R#fvr$!p-}C+IE5pjnvS^9Qtl6rh54?>+}y%x;o|MLJl-JUNH`-_RU>+2 z5)>sR=6Lv?Bqx0L=kqw?+xeaF!;F6t7h9;ENN;O-(FP-Rj-1YjAL@=-W5i$aMoa)y z2TK$NykdpbM2VYB)JSB*Uvx|+>G}${idqt*AZS@4vGKPp+cq`cj3hHX=KOc!Dj!}z zmfBGarnm%2#ZYP4+*}4=rb`rqKoW>>J4%izL|)KZ*cNcwAochaJ7s3Vv*pE?k*r&W z+BHIOVW@omrA(N&-KUntochNvOh<73b~ZkUxbSyH;)3+d(~(JlpBI(Zs3-UkiE>0y zx3Q_J+@vsi;T!P6Kl8=2h8ICIFMQ2GE=Hgb*^F@Wj3CmCP}hu@hK%6ojJQ7;c=Hzt zOqr?X87bzO5&f>YUXYl8%#1&o&$ct;bRb#{kvgvFdYS(a6Z>K?00aM}f*Q3Uh1)8* z8zWrsFB=K8FhNsj5UcS?LNi?i|NVE0>UKIYx%_p)I(V0ZHB9+Ki{K+^I z%)|GQ#LndXWy;6uWEKm?<=u>1GEXPU67Hmcr)!#Qe+pep8b`FRkSYM*B&C9--*-(# zSlE&^=IdsXmmH)TlLE>rX*3q8u^DNW+l5qz&Vd5yw%Y|8P&`jeR$3cW_zvkg3TAqO zw6=i`jZ(-679~F|;_ffj2q<7`cWqT6x!fvT5@27cFRC&lTks;H=;Uf|@VjDEZ&hxI zk`-Medqq<6nm);XlF9Mmna5}C{M$;w%3e7ST=A7_=d*OXN@=D!sxFO++uNB@TL5R~-`<`wg%%Pozw zF^v0Lxy4y|t!{a{Zsp7=_3U+uFx~q+ve9Q_Ii0_AMwu()Hrw(ohUx_i zt^=XMBa7L1@KZvU>Jf0)h~TTqr2EBrTf`g6Fo;5$>f znqi9?enL~K;A{Zg$O8}GUj#d5QF@QqRc{rAy{a`66Ky3`E4878I%^f=}f`_`zjJ3T@A7%^wfg{TALnDo-f{1Vgo)l2|1hz$N z6KRWl%A_TLE}wJ?{|_7yfd{z$1xF0nX!nP=+$wKb>ub46-g-D&xdE@~+N8D@c+YUN zgJ0jGjtEC!iope>*X~jKsUXSK+k_90c04HUf5s%JzP4$C$Dl+DnlMTcoq~)PL)jlt zy_7+DXEJu%*0K*at-HP5XzaF#t7b@w@>p^ecJB}!dHv`W{oO7jOVmd~1HEZb_s+}i2l^lG4s^5J zrzQvnXvCt*RT{uaq!J3$kBMr8*yn%L2pb;OQHuJu8xdZV{HwsR7aR~H9YrhO&1{Dl zE9~fWv+ed(Av!Fg>$&xN7BvS==xtvi?yJl8WCo$k@KgzH5PvZ$e{^LEhmP#^2L z^aKs^MWY;5kf%1tk#g#y9U0!^msMN+mz*$jf61Eh*J(2q+F1+M|ZuwvA%Hjk3Wg4eSjcLsM;`$yLNq z!GG(pdLx2+<#@|}E7tzh!P;N`mX~Cs(tDU&!8L}rCQZn{n6OPzQzuKkm~?2EbZi*M zzpDR1-tZ@mT7~p}zwVd5@*Dzu%jQtSpHgnl2mqdhHVm zul=gPV@lQOTgj)H?4hZQ`LB?Ig6c_7o#Hf!-fTqRv<-67&SNeHNsZal6|o#FuAJ<+ zXzxNcH-4J>Xf?&a`D%`Fw$19>7$Ls9G-n#eHrc1RfLwmJ-+lN-ewpRIw9`*j(lp-}tW1?2biq!pgsg-LQ zy=#BjRwee=#VD!IpOs%{Uy=1+PpMoF?^~a~Sh-8Nj^0O^WGy*fPQJ-nb9)fs&c5a} z{4JP$kUA+q`f}YUVWqWTC4jL1FfgHCWq8YTVV#OPs7G(>`Bi1v2PN{kTd2A%pNlR0 zgYA%c6go!4^)2PjC-x3XanOAzqQLWeI#H$04eGzF_j>RhyuSmZ4r;lz6OphX zm%IM8%4KH1s&e>y?(io0A-VJETE0@rTEg~5$i7$lKESg4)L`#R0!sD;g{Hyos^?Bq z%+BxJA5Htavjzvp!+Y>{QV!@=chxfK;wrh}A<}SrsOpdm3wl3w_h{j8(({nP(C;jv ze5Y!cg=2#(39dg4uoDcA&~AJD99HoF@(}Z13WR(6%?aMcR?1yX~J&IVW~^XT*00m}Mhq7wBYjpBOS!LjF73wG;vo}uso zl_k2DIlFjof8XHRzR3>hMH_kZ{)zh{iznfp&X%raE-GJ!30^K)|6%j8ekpdjm3O(`no;rSX#DN{LNw)y4~qGK ziZ6IW!+HVu$E*m2BH1-EPyj@Vf{tibh;yk&(TG0Co<^-|CXfiK4SxB-7@fci4Ux)} zu`)60| zOe;wn=oJpi7x^o#o7km<$9M;8?>t;^XSuikFSBA^@Us;IL$Dw)eb`5al$`Zd42toy z`PLA(E|)<5r(%`2?@U^--1tyuNYvVM;}1R2tax=RPc!FW(QPUi=$ig8oJ+W_=S9o6 zAQJG{xx2CHtmU%|rX-{d?BF!>@>kD?vb!<9>{e$!-zPU$OmkVU9V`v}c%1l|5n4mU zqXX;6b8VjNFcj29aadmloxy7!X<6S>9J^5e3wPX248hebDeScj7*>va*V|HrafFMh zk*+sVwL`w>Ro75(%vM*v*F`-{nZG*mR=tEi+XxN6?ND=*!P;S;qx7+)ch}e@q*`;0 z#-u3E!M&RLJz?73`zB+ehJ+5ia2H;q(Tjxab6)Xoe+5Msm#{W-P8_a}F8+>$zIbnO zLO)Hz8fvJ|XUt*IKRN_+U`7!JEov8-vDX*Nv({cso#J))qch@3?0@D|hEzGodVS<6(b{=t+} zdFZeWBD3wBK{}=X)X4H)eD$PR;?3(bSgBiIOm93wrYryOL2MCBYPNIOx|;&1oB-n~Xf#e8phNH1L$6)#cUvz0wLdRC&s+-gxQ}e~

7bzwQL}57qUDPE=FW`f`SRUD8>%BF+TyyEB>ulYTr{ro};cM?)^y=ojLtFJ+uE zm&qHxL}|5{uVC|WlE^fj7VTMhLr#NBk!pFv5bo)NGiR)>O)5}Acxh^6Zz`)K_ptJY zp2b9VW>38XHdo-Me!eJ8mTF<0Q`25SBfamsEL&}8ee&@_K48G zMh!(>Pxs&EIH_fXR7eLNzOk|l^cuMK;_eYvy0w0d5+@v4+*h_gzFuzIqwsWcF(>Uu zbvK{Y9G6=7#n1d(L@s91Z}Z|~pgqHjn<3>Y5C`E8^=KHIWd6z^zr@8h z9M#pIOsMdaZzbiSncRvcH*IU*2p)~RNxlp|yrDqW!wYtoiOhc1rw%al(2VCB!XMRl zd9I6LDMaY#0#@4KLZkdQ&e;br! ziqlZjJV;Pud>0u_;`okU_U3hoqXeF8^2S|%UA+zOMD{IvwR~ez!z}UCI-f~_#cAz3 zmx))U(FS66<~py;QCuuGT3l|?dQMz=FT9D=#c~F%tO-FfOVZd;876)!`%djk(TAMC z)iEfu3y5Jmqu?p!jJ|KnR_4^&hJLf)$U`;BTt3iio=vZjjKSM{>K!>Mrm6{narRf_ z1?=UoxRv>Zq~r-5IxFvxjx>?vCtPTEYOsCQ3vas?ooDHy&BXUfYhxss--Dd&-4+l( zeq103a*+w>z&&>X1A-{%_3zY_w{SLSv%U!VZ{D$j6b?XaUyownG7js{$^2_N@*&+j zgCx_ZO30^zTCwIPZ_M61Q%AVy5l9URZ3DRx?ftaDThPRcaEAEp>|9(6YN%ggGk`e!e2`frRzDg~oa*iTyLu;e@S0V`O63Zs;cvO&comULQN^e2Bmk$9$j7yweuh{$WtXXsgrNM;z(10 z()NTbQPRiqG+zqxxo81&r7A@dCDu!YEy)XjO4-IwTm`elY(?JCO#)*@irxe0E_t8X z`=_CC#k?oHy7#8jQhpXO^cr8)IugF}4z^A?fd_m>gz;B`!e}6>9oLEG!b3bYP*fcy z`EhB&62Zd~&)CO!dB_l|v6Oao#v|~iq0G`u9=I-wMTfFzDu+6eEys!?1|LP zHj=|ONjGC^G6l#LvpzN9H-`)+=bdnH4S~3oAGl2Ms2X-TI1I2z(wz?sWK`tXFQEX zuX`x%`kc_y>U63yYC>~|V1N$I+*BHRB^yiLHrz?0BCu=gC+cWj*L1bbVE@Hx@b;TN z`JR)j+Qo^R)Pb=~i)Ku{Nk3rr zU%WrVwZ>%xOi@uE{#_I{K6PGKpNy|#6=3`ItM{q)ZVm!-uiNHDzvHEb(|}Y+vv0s? z8Tg6bkLGyI8~w;Wh-}W6IWI+L_NEA>pG+@gTJGgNnu_28Rw#;8pflHA|Ft?vE>%zx zDS7towwg~(UXZZ;Bl&Upci}RbWV>E(>t;EUw}ChFKa6by7uH+!N=Cu~V|DTcQ5xU& z7oTR_AZLrb94T$r9vlK+o75N|{dq308cZ+Qw;`T))Jw4Zo|5;BJD-}$r_1gmI0+*# z#YuJVJs@uSwNa-ggkV?5s3Ib$j@vSR;E&BvEGX4dQgt7T;?}pNUmV4#Xi`&(;a)P; zJz@)bVyLkP;pOR5d9Wh+BW-|cF?K#S=xDMf^tl%Z;A(@jk$}UWOU?Ps+^E^F%d;y8 zvSGYHkqim9*0HoMk=K7QZY5zw5J3eaNZ4~mEcQ3-rVRD@tm4J$r}G_BRYug9cpI2b zdHlE`QBD!+-T=;s*nt2F_3%&(Ob`A39$Dz~EfB1_ou#Xtb)ubZt)2a(ouvYhD#dW{ zbZ|*^uv2t!Ds=EVsB!3b@P&5>yl>}ERTHEG5A=m`6n6-%sd3G9TqWsbJMZ8t#*TBV z(%xw`K7bKE+Nd&wxAP0vtEq&^7I(_M@09QARG8>gT^wB>QdLx zP)-f|$0^7N(+Kairn?>Y!n=i1yUm;1rHmN(57ao{ci*Y#e&Eny&C?;l+ODtPddvMrkqTKTM)?l} z!%^Bw#?#{XQWH-eL+Zt9n9l$>T&uObdCb1Ah@~GV256o~(4urAe5B%}NM&)*pgtm5{c-4^ zFHye<->gNq^XejnRCx<-Zv+`;Q3wo`%QOSs%#RGpfXZoCHr4B7XUpaAv=tVYCI=x{ z1R{x}Tr_Ci3Lb?QsnHtM@DLTaj@XAroNgI~+?#Ce@;QNO4IJ=0Tr()N$G+c|RxiZ` zd$alc@W2L;WK`bu?cn)QQ14GM^SjmR4aP;*yr%DP$d16??F$o_|e$svL(;ChX4HXeXkYPy16!gcl6$oF>ReF3x zmPs(cR=B257zJ*qxmfet9Pa&Y-@?gID`XgzI<(wu0AL1h2!P+&8$4_tvOu-<|j`9lP!d)5cX(^JP@l$j7BRzgcGrGJ&n(I}46 ze9(u^Bc9PkUiS}U&Zy&blp>QR)yFC66Qg5S?x1dc@#Qi+))={wHmWpla=Rm%Z;Kdw z4!eN^M-Lk2N*U8jkXqqXtbj?Q$q2Geav{Y#gUeAqGzbn%)C)-?x?4sh>&hv=F*Y*S zZ}>yf=DuhmuPfhdMJe7rn~5^_kFZON@En!Ss~?{Ty5q{+yh;KS@DFR+opeGDNbVu1 z@#8PSMEG>lhK)7E40;=V&%}k~?q0NGgrQR9l*CPhr3Q@OA95pO(06h|_9n|<5Y9q{ zBvgjPLhO#$CtmF(twN)Fe;mGA1y4)`WefO2rhV@Cc^DAf*Ac!5a3~P^6k&#i@{(x} zFd2onKE5jxF=?LmFLt zq!j5DHW;lys2JPrK*ce$oNVi#mQscPunU9^_izi9`AOdXiL|){8Iw3NkmXI#bI^_N>| zcj-)V7QC{6&CK7_`^ym%o1YNA=y~ik*cY?R=rnTg!#q{UO0ptu^#n>T1N59q1X)Rl$%dBIdY zBK`7Tbyhk|eOP@Mj{ukIS&IRH4Op-H4sDBV(5Ly9zYb@D5jtpuj#z|-lf&k%_2o3& zD`+x}f0*T`Rnf?qU!M?aX&Y)+)~sIV`7K!zd4->9>$DFX1omyh%w|_oP2C(FAN8!$ z?cXtWbT%2XewfSgq)i6c3VVWb@|s!}nA*g;0M{-^%F3|mcZZ!GIO?`I%tdVeunm7U z8m>4EG0uP!H0zxOFP&lxHbcFvd}V=>h*8d~PKioe8A~AX-{g1YSHpW)_2bVqp9to3q-ntb>A>%rt_ z4p_$JD61vn+68Zl$YQPz&4*eOB?SSDDMt8nmHXx0osU(n9}S!#rFup9)dALgGlYeOn55?f;>qDv`dzsX$bYPj1pB!h1z^W*+`&-&_zrs=fMx&6ILCwJ%= zw~`!Uvr+u%k;AWj#+za{B*h?l8E~>)r$xSvA1z+kYT(*lxF{J&!Ro<}j|ZbIZ2A&7 z0$KHz8qNb3?hcE8rY}?et;hFQl{EFb7+j;7*>XR9DUfiz9VG_`GD&S zbupWet9#O3K(rGgwm(D!WrT?=dUGoK{E}WY1P*dS?xP7l5>bdWy`%6x@GXI;0JDf! zxhI)5;Jf+OcT2&4dv@RYY~Y}P{E#fr2PjP5R=;*ET1Pc#`7_l2Sf({XaT+6#_q4ll z_d$tOb$ho1pa^JN3zRzE894;qb52`|a@Ho9WkE9L`RWC{y0-$rmwY5|_{P#-WigWr z1)hjA_&xh|;%!LEVE7Aa{mWDEJ5=&_@NbyT(n3z@X(*)~Av^PX4dA8rV>p=VSBT-$ zV8s^fVwNH*N@sLU2LV_23is`M61Eg-j*fbc55vktQ0Pu2WO>GZeVkQC4aS&KO}N(G z^nLl_m*d!P$Ccle{ShzN5%Q(giqrXFD2Q$bB;D_i1+Kv3*6H7>fVkG*C7qt9OgP(- zFL_!%6!2$nt0%w{a0cAI=Q&epPI~c-d1Lx^?=9>Mu3n zZ;$3yt#X#Tj3c&`#N9~ru|J|TG0;y1?#>9kqOBd}Y+YkW$MU;1`R|b!$CHZIv!+(s zY}`HrgMUZV70G%cSQTM{hXoSD(lR9aEzHh=J|wi7^$c+Qi*_Ko@eA zu4iTOCa=b&Kn0+9U}97cur>oFqM_?rYAbb@dyKf)y>SwTD2H;$e`G&LQ{El|FkNHRQ z)rdQ-ZYKicF9>Vz_5HLRNT^K0&Uf0Egr+Ji>K^ZX|0z60<|2dER$&l@Rg!ANi>Vyqf$o`So7|i-F zvqJPuRy$DbJTUZ%+x|fESfWRnIp14CrPJoR$87zhsg_SHuk%7K#=|Lqbz~~g3Oac} zS=;dB#b{v1KH~&C6<%@ogTsj-ErzbJdXl_Er%OwuVeUhdG%ru0|GvspgHz%+#!RWA z;~zf=${5h4=6{I>xKZ#I7*RAxego_!8NfFAx<2s8si`s3XV<^Y94*+XgpaH=~q3DjeZN{|s`D!)7owX4A_fYcs+t$*N{yA8bZeJ7fPpeDrsM=I)>7JN2%U@F ztv3LsJs$o(gpN{=T}J}>HXYd{)`^s7Mc=Riymr~A9D3Y~7nRDr-?I{?+W0R>>^pq; zn-6;kq!``ucfBG62UjOQBW_UhtC05{H&TPbyRQG;eKJJBUWTG%01&&>O8!CNeX>S6 z>mYYBWd-TUyZ3|da8EjbM(F+XQ~J8uoLD#No6?5Nft+dHuBa9!bT^CsiQlQaPneUR zwiw~$estHEb5n{6138`pVdTelYN<}b0hI$SxV-4yiB|*4%7hC_ zc`prm7WY%R`mUFI%ANX zL9~CPY4VfEt_8F)HI)L|G{y-ae+^pNQmB-(u ze-ycmE-}-YmMt+7_-;x&h5>0(7d(%wU;&Z>200&$^UsvdX$fJGcau7m6`Ogl*Om>< zuZ=sVo^N>SqbMHUQsMb9mQF`$GiX)yh2LT~nrUA=-Xv9x`IPv@rNojxJav0{dCsqr zIDTseoARQmz*IR%H8e>KP06p0RqZt$)s_CjFI(CrEbx^du#(JYzYx&&kT8P3dy-t6 zsnVx8l}z5o=}8mpsu6HBJoZ$o`1&V7Z7sQG#}HWT%R@mUiu{kZ)s?&&TWtEXnRjvq zQ~3)y<6Vt9$3j-#zcHPBZBU*u*yQn{#EMN9`2ILC_eYAu_58F5AMzF+9;=*qHNx1l*!+`=>C%hDL@ zPb-eHkcr%4RhbZfQc4Rtc&=Ug`&W}Y76U(1?8NEKKc9_Q@(ZJBd^$(~F;#wgq1pMz zE=9WW+mCL13AYzG;za~OC?(1>hwLI7UL3mKeo9j_WvX9wXWauc0gK}UAUCHkJQuoP zmMIAgl4@vJ3}PvnzlD>G(#X>(Tb}6;AG9%gQfKPp)Q7j`4DXiK6G<`4RL@T!j2|zq z`3slpPcWNGUPoyvD~(}ZR0|}ZD1MF*r&#-N=_Lt1t2SO)bCM^yq&^+Bww=D4rh1ZO$(L-Cqm&b8O^(kJZ5I9Ks4!s!n#C zwR_w0yF|6>N1C-A=z#(g-`1VY#3&jkacA?+yQkHY$*hi}K461qTb}$=B94c!7tK#K zV~qZaQ?Rs=K>78|XZhSVRX0h7?%uA=mQRVx87To>}HCSM~ti1_?Yb#uB3|q zo{t|oq{*_n8A~$Oyb)z9)$*m|h6yEy8*X`SfPIyuG0f3}4^%bQbzRi51O8oNckqI{Ay>t(V6N0@O>r z${NN$-<)Mn(DS<(^8qnewdT-NHZEVDb3Mte2e%IxZe9)y}ZBJbQ})x8kbvD&+@ZXCgcc2j0`n)H@dz+&%X*)J|9%& zIQtA&{4UKf-@{EvHft-he)DT>wei~DlW1nxIiu&C_ufsVTR# z=k^t&F1x$d_pE2* z(paa{?innx8|2e=^K#M_+Q1}IXfJ11exm<@4BXYPSQOA$&?CP+NJBFGoDa{ldU?xo ziM+@5;BfhX_rW0%@JR<}SF5mi-X`r~r3kfU{1`4%(09JhSVRZf__Q2q&c!6Oz!^%y zD6q(9H%aBh*#j!LRcbS~OhWhSHt%&V)&yJswB?DMWl#)o7T5VFctw<#Yoca_cVEK_ z1<9KyiLF;9eb2#Xk|_)xhAC0deVzwwAldowt9B_@Ef%<1!rAvZ4SmwBXS&4pra8`* zg^mhiXY%K$EP$*zmP$yc{DP=!d^G$ga zB>&M~Kq8+$xlk`i#V;7F)T0rhVUNU#vxAyC|kyGx4~sNhZu6qh0ein~j330ho>QyQc#QmoM86f0JsxR-36b9UeN z?9S}0+b%|xuKV}(u54UotwqDjh^cgp0&2o-SYSy4mW&`rxVHvIzh$|Kw|ZRFJ4 zDAGpXT>pihthN)YmeeW*vH~UJ7l;Qh^W3|NmfKYBn)OvSH^_q+0TC1 z51UuIuW$CM*f)l#^jL(-6~2IRyrg{BTLj8OhB+SC^+$u)zJh|WP%Q1(w45QlZv9OT zmL{pJrWtv73bX7RDtLRJh`Mc@jh{y>&oKXE6od&^u(^M;9o$EQ^18!teYd}3PAJm* zS$xBxv;CLtDxMnK;dO;y@=EV(&1!oslc^ND4%^+2bzpB*p@~-{z697-`bh|Pj<~S$ z?E51*E58F3uv=`30F~8Xl_y%NPw8=yk)I5~+(qoTMX<;sYgM;J925HyT1%7_>u%9l zM5#`d>65CmPMq?bPu7F1(&VAJ50(KWR-S3t?@2DqqhW*sdOsD6P@u+Yl1HxeV7jVy znY(VYs_x*W(l*GQNJ&*R{u~+u}P6X*r$IhbsN~lNi z%PJuppyp*Y7OJ`@38EYE)OOdxsj8y@r?cGAh;a0<>)?)42$XR-H| zd!fJd;$SY^pl5LKh0`~sO_YXeZz7mKS*haLQWdG`*fZ@g8MScmD9igW8dgQ#3eJgC z2bsPn*jgM}o#8Ftfeh|_{#0kJWflIszUei3rh%al^Zn^){k)0V;G8hbd*?}_b7BUE z)?A{1Zw)KU>bJgHLrVU)%LZ(2AR<;pwnJs=X>@Hb5sDKPBRQMAylMTEwr+is4S@E> zkk`IujN)!}o=9c4UAE-%?UzMj^V`;K7SQ3CV&^IJS4Q$XCAtJCx$s~Gd%dR8k+Bbd z$$OOOaFVfeJGMYw zxy~Jv?t0s3DFBNBTzj$iy;5C$7)?OYm=C#fYtwyCeAlBF^{q50uQjm0x}yEd`*$zj z-F$XN6#NM)Lj~O_r$PnJa1QBxDeO4 zj8c>HBqCOQmuCxSOPt^&R-!IWADzQSNpvvxK+Ka*ZZ|msJE3v(;a@pQ_tmzu{+_!L z@f;lrQ3S%`PL1C}lNaP|!$erzNpBA0z6~N~RRunSK@A5~83HtgZeYw*3&9BGdU|Bv z(Bo)9&M`L{gT|mN;PtOVP2XR~osCRPLU5`i_((QoH+CKhi(>bPv8z@zwMM%l;ePwO z`2s@XBv<-ee*AIwhUue+Pf!qZ&{bIYbMI-RQm*V`szuL_{2Q*f2=furHzPDS2`tSu+21 zjhqWLB)4)PZ6^%*Sszp}%F%6rJ^GtY*IM$W@JW*gzN5QB*fe1HTb?y^i9tlE+2ii~ zp&dgQ5qKCIMWlD`$s#W-cu~T?t*00nQMEIu8 z_!eHNT9=9#JjF7^&TCMf0MOpXny+j=zPIacQa{Q0OkXtUB4(22?eNe=A3MS)ILbFU z$}ha}bwiZDZ#dPUlH}Jg5zf(v(_aF4oiz7E;X9gn$sj@-Z%fBk&7fB=5N_@v-fGYm zMay7=N8+z$UVV1|oCL;*GwLby>bUpS(`3}sf#7>up_F?HEPMUe)-f4wF`0+D4}R*? z48*Wew{75^n|X@aVS2Bu?AHDRdM%2sIjygFE-W8Ed3m8y5kLIt^+09maFt zEot-R@;O*xa3K5J(q|Bu5?fk~)3Jlu^Xj=w(v{YuGt)=sye1a`k1n;i0Iv|4;6)T~ z;SH)y`X>cHN?p!0A8i^`_7(O0n_EZ2y>K_%-S8>DzcSK^(jyKNyz1aPvW4`cW8e(2bA4 zs<39~wO(_;h)rYfg$ic^DOWZrcO@y1*T=cv=kigXcjwFJ@g%HUw!GxfvuK&-Okd&V zYh6Pi9IpxVsn=WpL{8<~YA5+r)9sYeZ>Ka^1{EWXfPPzl()^KQXgz!%z|KqrtH>+r zb>52g2QKyp*iPvaps`uWFJ|q;kS1LASqdzb{Av@f{w?l5+OAjc$(et-tw%}sJAsVu z*>V4oUFJf6ScBZ^sY#O4q1zgo^g0xYvUume%ZUl0E4SX5i_86y z*TNr=%u{=PNFZOqUzdovxeEa-XI@86hi!f-J51PSm zkq1&ZTL>2z$Pw2iBs}Huai9O3$h5me=T~YtBsprnS=qm&>4hf}MJb!(wbPx+RH7{_ zto_kii^w|pn0+`jGF@-|N7p>hpV}TGWBw09CvF*drakX%^ZY!w#+?f?2)nt@QosRc z1YU=|PF!$yi@dsv=UVZ|8e*2evuCav3l=wQ(Q=HlpMW>0Rw)t!_HT_iXR7QB`q zDkK2?P(Zm@sR%(=Ysw}crwx9wS<&sF(&f}$ITUfb{VT3 z?tCn&?5`{`DYI|u#lo1RHPtV>c?C(86dV;2Ebbo>1^3c|4Z21aX&3joFie=K{tKcAwH% z)e^eD&p3DNKNGTiPLwbkQcNB>9TI6s35op7S7}yM{%gm~xB4k`fwAT6+0Vc$HcW}K zeUp!SIXZqn4e9lhImmI153 zipU&I=@IjhI`j=+*$jF1>2$H^cwc#@0u~adkv`)wZYJY8W|ym)akh*e?Rx0vxZx~^ zs4K+XPDsd3W&QH?@5XWSoBhgqAOXLf*y8r6<$^Kbc+w7m;`xbU{<||8WN~-3iY~aj z8A@V8|LvG5M5F7sVdca-Z~qd5e;L`esJXJ28W54yYkyMbs=@ z(sHq5YzB~$f^V0QMD=?rKl>b{9k`wI_ujww?J@V>%sZ{%>@=F&)$eNxbj4%Po?U7| zo$RF)57OqQfBI?l%O{-Wf1@DPm?}{vzXw7o(%Gkhu)+P751#HC^bVJnO+G0Qi`X>^;{4t~L5^fG0&WU| zF_FeSQ|Gd(2Y+H`vV~emCZZvja(~#3Jy~spYOe9lGyRBgOEDLeq8>Jq#b;C0&?&I| z`P1XBu-Rhbhgp5RJw>1!_>YFN78>iRG@YzkZa~~uLl-YKeMU>Hgucw_xil@N+#g0z z@~X-qBv))&U$YT61h_#0jGKZZK@&X+tz+u&gGULwf1b;U^IX{s5@Hi1MzehMK#FS!JA zH7S_Xc*_$I`?jz86*<1nE%?{1q^HZG`+4n)~HA@t)eY#2RYWb9N`Kw(-$;o9> z2ED)kY{k9oXp=qkr(7KVpmX^}yV-4Fw+#F#qpwjkmE2l4W`MGAw^R9pL6Sb*hA78q z_x{UF7#LqOxII`cOPU(1E1;J4erE-dy=R#?WGk~}1a$C$m)&dSDZ8($UqXR#JVD+z zxVOAZw#Tb+ylf|%$XC&LVV4sXEfs=p;B@b*JF6LC*pV&0nmyuYNfDRiXS4W0>w>gh zae7#>amU|cueQG@S-)`Q7b&1een+<>2`gtbM3+cpqz}*iNs6n*5`>ZfJ+z0!0jlt4%Wbw|;OQm`c@U8N3e^5<@BeKz73aR=Hv)xDou} z0=-LSB?KVG`=GWY%l25b@dW<&QS{w7&VC}nYQwAULo8=&umkqh<|7t%0h~E_vEc+n z)(!ZpNw7WvO_>;Z*@ufhz`fSKq{PB0ONL?Yt~rhnLdgJLBW4*C&X&N22p$BNK^ajy zEPdeHO32h9!Hh1Efgn6am&|IC)UJU-Iusa~09o*DQL^B>)?+n}Q3dI3Qs1YHnf(2t zkw~=%9O1+XQc6yOrCGq|gb>=4WkMFNNYI479_hOj z+9?udes_3t3U!+vM05?roe&#q`8Aw~IW&=UW|FpAkaTs2;-?jxJghWtf z?<3S!sIL{FmwFT_DJ(of^I-Q$+$K1I5Ej=OSjUMbOprNJgMrV3WwMb8ua28~l}Q8y z=qr#n6fyQGlBonE8W2>AMGP)h_)sOhj9$h8D-!%-SY0n;g%u(7+KQOaAE{I`c-aCB z3?a2)CAMBm#yNVTPy2|J4Lg;y0ZCWB%9etn7`B9<5Ol^?m@mM8qWph>oq9dKr3{_TcuteDPY((GWcrn-dP3slvAhqMz+eqlp@@|; zC5&f{(-T4p#lmZ~Vme=?&42)IA>`0C=p8c@0GJMg5%5)dcIf1^rz}IgEV_+VsWg?S zf>b_jk0mLM(jZ+`^}b}_8hyGYA}6}<>lMXq4hpkml3dNKqEA>BkOACW9y>82@|#<2mgpDHrlg)p6hL?n8=y$eoq-lv5a#wkSn5+ltSx&BET}n6QRI`tD<`0sYml&^P>lc z1c1j%frn(K=pMn&v!dcgB1ntqm%#wJ0;A9qQRYxmb73*OVw#s}0)I~*1rd>S_c9hR z6Hq$9&hX_DoaLg(fb<01kj7tk6Ie`dIrGRKS6V@q2}OcYjA#{RXd;4QaTNzp0DlEh zB%)xOR`)>)1jmXb!3a`t^CS7`r*xyRgAjOPF!_84j{eXy$tvvGtpx#Mur|OlqOHdu zYH`-0nL@^sH$?y+ebpCCvlznQ5%LUz#kp@qADxQW1?UcnXw&sghbaCOD3aqA1A`$X z^H1&gEj6+gej*d7%)Bf#Gb{qnXn!_XXO4kR6=6^;3fm%^`~9Fb>-2<06xXzzmF`4P8w9=I#!dINF2q6|FG@c*iY zct^QWb^a2Ba3l&1o$m|v7>t}o5@D@7bG3Q!wRxmi!5Mu#CEGk@FFX~+y;L*9yrB<@ z*2M_KyG4E7?JA^c=9<^9hw!M}ggYAV7 zhbowv1i$#?6OjAEfvZ{Qx6eA1Dv$(5(zD9=qUBi-h2gq^q4v4$&J4x4LC~Wl|93xsQ-$RV>9&wR=a2}0>Kl>WD$g@3 z$)6S8s1-)h?@uOd$dnaeLLD*Z9RA#J&)%2Y$yXe^eGOM4>QxrQUox_w%cIb&chS^Q z(pj3sS+QKRQMt351-{Ws&Czs1F&tB|{t_Y065`qt@x8NeK3#@aOC%g!XsH0K4UUOB z?TP!BiANGiXTC{S?MZ(xlR%QmIDW}^9mzyj$t02~6n-gxsgK7D6PBo7viU|W_@=h` z#Qa&mhvl6n*^wrDm8K|}uIiVr-jS|-m98iG_Nm`nqmH*`S8uIoG8pE}6thwv&t|ww zX3ky4j+X+~3SjE1q)#kaF;~e^9a$+x$>=1>?Ck8M%#Q3Lnxw*xls4+vj#YRfnO}XC zQu{u4ayAv47Rh|2x|LlRrCd0rR5TP?L`Pdx-Ivom7o9Yl|I-gSDjv;(AQj?O5$h~b z+$c#(D!$d=03Yqt|TuD@=)~>c7|JMI6w(*A3YI4d~7W zqJ?S_>Bi>QjWi2Y3^$EsQcc;faT^pwPNbSu`-&E@i~T~IrTtCAu-BS?vWv^@&17EFN@=&0SL~(UPvfhq=>-Fl6V_LQbRw|k~i`pw3JPG#%HNiG;HP! zYj$60Hfm|+e%LHJ%$`ys1YxR30iYn4QZ|#lV?oDEu?`5B6%`6OOx8vVwWe?a@ula_ z!LjAR_1QTnWR{_a(&ahb%QuUM(`wUmrv* zrg#n*fa9gbvZb*~OM27b?;r)j^VPt|Ck%#Dq}_oCl-Xh?!_SexpHoY#%;sxEO5`3O zM{!0#>P?FoqY8a5T>t=-uh0uki_|j!1FPhOO4vdnben&n!&bOJMkmOU2AU3E?j3nv zu<6VQxD_D0d$xiKM8EqG*I3aTTk-CBA-c(A{&ep+-fb=fBFcLZ0gT%qOQ~wi8@O4g zW9m2hXqw0R&E^-z-4XLGKSqEXMLU5}!OckxzYL>`@Dt^BGT%&py4xvP-n;1egI?Ys zP@?#8e2AyCVN;Bic|+kJbkT@iA;O92qUhsE*~g1o zrpqt6e`)d%fRbhpX4c-;@d+H26@*786#x}19*805G475QEcu*3Fa7!!DpWd{!iv_+ zk%JTZ1Yrf)t)|JSNoxBHE?|g_S&SSeR z*}6CP-f^KPLAvc=soN-4IsI_5C6eVC;LE;S6z1m(s4cvE^iwV`72uspPoC&n_!vg~ z$AP}XV-tY>jY~PqV+Ja$*=~>TtL`7*M34~|F0LMLMvPH#wl6a5br`?{j?tqK)4-q3 z5lleNAz8j0das!PNL5S2=nYS-7`$;DzL&qI@JjPc#WvUg zeun^AD7{mZqB%SYfA; z(cs?L;3%bzmf&`Kk6e7W_zox@9 zi97Th_iX_IgVL)fGAEfYHhi3=|1`4@7i;7e&dQt|E!-tsrFT$D3>KGY?#FRYqPmCyr0Kak$k=S zK5%>1(V&zJZwyOFtT^FkIAZO~rB46q&IiP`heeV$q1}Y1oil9s>!9tkN6M7r3e7IR zN!*b`;tl#jJOyhjC!?$_9~DL>%^S`QBRxd>IBXvN2VEC;{)c#e zx*F2IyF<+tHF#~tCE_@lZuVM~le!LYjt-;``>^4-!Uqj$nsv)z_vKtha?t^&yFPsU zz*kK0U+oJUxo-D5+ql?`aeSmJNl!xHMs!h&>} znJvK9038(mvugSNFv*Lel%i%<8&1FyVn3^!j5#yqbB!5!^|UXv`xXKx z#R_x&>Lwoj#8#0yrbN%T#9t(~S2A4}u6d5jG^!TOo@aG$V(?eOJFVwRhC9R3i9DSC zU&|!NW5&Fynpt^(Q0bpLV@uDmDbRBX(2sHDloc9 zI~7;_t)30FFO>7_(S*UDM4mK^#lJ**mC)~3C|f2cJcYj(XW~UkJWwkEMTgQacalJ; zBf$2hN^v5_ID`bLF)x2`>Ht|};*C#Xs^kOMa$fd|+{Q#reqNPY&Q*`!Lb07!uyCzC z6&LqIs+mqDV4bnOY0`$u_g>R+IpK6elqlg) zF0PcTxZ3J3E+CoDa~7NG<$$&WpD#YG%nyS2+FEDVxP`@C@3!v!TGt?g#T9&?_5r>+ z_oTSR4Q`)~ug-Ozg#=668a|!q>Dszi^>IskFMYZe_v?H<5-cCa`gCvb)%%UdEuU8T zeAsiY_y0-o^Kv+|vOcdq@K4;&TW)buYK>?DfwG?ffiDVN#}`BpzXIm*?Um(LxMwa( zB*i))cs_x{l&TMxda};A46jnAckE>=deG`^_&^r9ip{H_%-Et^#av^R#XoesD}dN0s~vNqW%NM^5(HO$3nw7g@0>#hdiBWxr>_OTNuydk-uP zAVY#C)+f&;z7$&!{Wf$ICqQpw5xb0HpK5h})9COj7vG0JD#V?J;{Zp%1jGkG;-FF3 zb$%0%j5Ph{r{(w|dyP?11Cq>X$maZ{7`rG5rLlh8V5cp6C&GIsbC}_5$10*fz9Tnn z>ADamZ_5ak30BBuLpbpsA~7f$#jSo0V#?Wr%M6C$^PtGzP6qDTQVqaQ)xwEW6`;i9 z{_FIAd>=xRqa9bU8CoTn0nVB@<=cB+w4aw?`_r-Bx5@(pk?oyqchA=wZKymC+sA`o zUWrml^osX8Cs~phO;s!vA^vVr)5);23eCTj*@!6FrXwg=C-AqaxU~WRFkgWIP5=OS zy#ZC=4Ey$fWdr`A|K9wE9B_@kIY-}|-rnBc+}xnAPp_}9|6cub-CdrdFMeNMUS3>W zpwIug&d$y-I{|m6d+5{E|H20R`ZpVJ_~Y>K5W@zb_xJA(rqElz(7%W7w)@b(+WsX6 zY;SLGZEgLF4fwORwz|5CVFT_~deA@1(R0)2#eDQk^8Y~&_?C;Fc#Zz*x->oYFFD}u zODX!Z8M?b0-5HPmsD@3r|AGgIi;IhiiHV4a2nq_`zki>f zpP!ePmxqVvf9D4v82`B#7#Qg3>FMa`XlQ7tsHi9@DJdu@$jQmc$jC@ZNl8dZ;BYuG zF)<7V`@duZUSU25002b;ASk_B1F|;^O2%zE*ih6T1;3|}r`A~fDUMqB<>Fvt$(JOA zaxA@iQ|V9|=i@5Vp{BBtOaYtWJoV=C(e%~3ooTM!@_(@by*P$11`Pkr2DDUtuQqIc zxis8T{ckp)PPlXES#Y*Ux(Jw#4R_3URg2X{th2dx`!wKJCer^Sd z!h2!3VXPVUYcXPy?M&fR`i4c3Vn$g-aiT+N$)19|tV5EHMceC13b;clv0yHN-V`Xgbwuwo0YTen)rIUL& z0o;dLZRPuJR&EspobPN=yusz(M*8=lvK6hy(kqIe55KP{N%)+;osAc9G)`PZ0}q2T zc<=7KLq>A%R+MJE+^wuAuiCAuY2DqeZupGm{$2C_$7^m)6)fE?d1{%GDUzOQk}`3&2O|)b$e- zDh7onr@-2Luckc>w9mftu#}2=ng*fwFMhH`j*{Nbg`NfzL}3NDK6pvM8afAUNq{e6 z57nmr%ACq4-OP1N{MItpIU~MOnt4#L!b6fcu|^|0mb?Mc)oSiP5B;vs^4V5~|vL2cTQ08Am z&l=L=a8nPz|5a$hw)9s&nM&$XKTAvhsD>=eJ3a&mEzNbQg2B{>!B8zE7L`2;U{wK+ zBR-j=Z$Sb!LJ7!1l zQb6*k)6fa1`+;B*5p;vH1V9l^3n!aC=|hZf$0!tol-rC}nfjQadxXczEW6`LK_b?h zU`e%_>>;0Gn>8}3p}}kw!MNmjR*JT)Wd1kqekaH|)+WK^Cnzl7A57rEe_{fqS|!q# z0&wkV5&(Y?N5<40O3^Ut+-O2O4ZV_7NCd|)f;N?MfR>%-Rqye;TVXOWRHKJrCA@;E zfPNW*0X27|X>6^>UoC5mr=8<0<+gZ#btCa`JHI7TdpSbQDs+5arbHHplTRUg@mH`O zIQPZnHkjZ@Y$L;XB|-_gY92Db5s0B$CIyUq2Pj@xM)^mBfFw8s{%oaCu2m%2H&<6f zW|G)~y19Iikd}qGQ>$S9tPXaxqy7dU!Yudrsg`XkSk45i2V*mB21k&>j-jsxuqiTq z%iu04Fn_0eBv@98{A(msOh3rV?EbQuuG1RdCHz3J>OPRqJN)r&?J={z3GDDtV__bh zp@kW7!24}&{Y?2h&WDvmMLya+_y?^}>u`3hbEdz+hh0h=%m(G2PA*9(WqK!dBflb+ zLi`&-C6@WoI#cC`2Aerl^<#lUE>_=6RuaE{V0KWFPu0Udw7y^w|7D^xK4M{4KEw7q zP~HFg?m}{Qc&$rIy`y5P#oR&LN4WV$kO`?}CSkj(!zVX&Eu^um7Hjtrt7icnZVLt{)8xc zEt2~w1Ja2eJFja}nd(^wrAFN1R9Sx7&IYp}S{u{ea{Us@O&sQGY|?1BUBh}DhaSSc zQZXR_Hd$tjEC#g`Jx0H7l@uAVW|BweJnnlT)H_%1Z7!s))e!&2_j2q@K95e(;+979 z-Z;a~+A68IeLDGd8^4&BTa*dbJr3jEhPUtEa5?Wh3*$2*OFK~Sv`^M4+?Yz15^-2^ zO2K9|`r7$pFySoE#(?hTVb=2CkvG=tFVR1Kley++b(tUbKe!^^CgUpBki^8T%%h5M zMb$Rq;^_hDZyWiijWeU=wvOOXQZJBRrk&zHYycye8BkGEA}dZts9i#c!K8Ew76E8Rp@2wL zN&=R9iDDH9FXRaeE%nuTZVRt%$|92KuY__m6~DPm^?YwlPy4s^uucNt?~ZO#=k&X~ zQv$c69MVzNZn3$cN0F)NWirpXK`5vW44{u4lGnBRk|F~`e$4%=S@;}6f> zwrC{%**_f9rMnyDf-98rFI24L4NbYOw~&HDqyA;U*S^vrVv;q__D z??akPHG2@b1nsFfY3mEpE;~^?LvaMNkA$w-`WC!DGT_s*5KajyDo#=wLsB|lKY06d zI(N{Q31T-)iN-fLmYwmyF7z-nRDqhDhnkd6jr4v+uvB}PU4b_j!^8e_^EP9Vbj;R^%bNZsjx)eBSYeiPiw2+MX%!W8_sfzZ9- zbq`0FyHZ3^ROA~dxzQzw2`8x;b(F{K3;JHXzX0LpgUEgKm#9A%QK?xhqjrMA*k(dS zf~y8^G<>6rKa(&86N+)VOBzQ05{;>#CR1tR-}i`dhLW9x3U6gPx@EzGCWt>Dg1gS6 zDKcYwW=T7mcs^M34j8iaDe->Fiq{O~9rl3dMZavxlBOpCK2ALI@-fq!^{&K?k-Lmr zzSL^?tn*5VbHgw(5Q}p&D{<4Fb4((X=qP?-JBEzeVz>bp+z@x{8}KD1;OA@-I0X6w z0|o#@7NUa1DA@5KJ|7C+QOrMlnXF05_82P#u6}<%D`8_R@lQnx0Z1iwn?N<#o?1QB z#yj@THx*Y8*JcGkcY!wHuourp&aGv>09*_nmenIaQmHdkTKV`4QB#Mg%~8vyWgBL)i+WxB!l z`>7&>asSV308Rd|I`rf_t{37THek{LS}sX@o0ZdZ3CN<|a59iEC3tSLQLZaZrYB9# z0Zn$oRl)HbP$F5FZ&Y~hmwlOCnA}mAIEUx_9DK4G8E@CgM3~|P=QLrbhcZ-euNCYWy zRLV>}JD!#MFGu2hjKoMKP)7B1g3=Rp$gVT7c(gg8KG^4FupJKjLhucN#I) zSZqFp%^|%BzvBJts;HM0>GNr%DQ^NgE5B4F5ya;7$EJRYttmCG{$gB7a^xvSja7VB zjUQ4nDOEclRWX}WBkfcE)0iYX_E`dV%|=zp_o~|M*Ogwe;pB>-90&i765hHM~ zc0#w6+Jmabpy9?!n#P^i_2$s#$V+%14q*;Dr)hjXOrQaOPnUSc4TokDiq@6jhT|{j z60gJYSp?vQNP<5ruyzF;Y-Zd^IPvZwKIuBnv>WmA3WVUOlJ|E4zhixSY(3`31nCh- zbg=%#bvn1}%tyaI|Y#bYKa;u9RTjB0;pBr#Ly={~v!0ef%(KUh= z0o?auaI+RlgB59wLtG6XV%5?t%TT04Az zl>%OFAihBo`GEnmVA%B`@i-v4xB|r%#6?@iV1qJ$tc&8UAgT<;F5oKB8n4$b3-di=bO>oCFABKLE%^I%6GS zm4kpxH=+T@ZoH6gWI&`-cfX;-@VnbaT;>lw6VdWcA8%N#u|B4aUkq?(EQ#kPKF}6P*-lZNlHiUV!uF8_`dn~d1)}3*STh`qUDRUwyX6|4 z`E=itN)Du(saTL z6k7Uwz47-Op1I?Pb2UzL`T0MB65xWH{pJi!NksE0eDfs_=j|7!YCEU&o#7B_O7l-Z(p!s5{WB7AguaURz>cA1oDd6I8=U3=+s{_JM$qGrMmFtbnm--Vw{&#MbVd0+6+S&f<*8WetH*J4yQSK0{ZN7Eh^tlBoR@!1p%7F(v ziLhOL_T9aQ+w+0z`Ockg`5QFmLRzp@9oX+8xpgs@4ac4x0crrXVs>G_*T1~ueYArz zw{9wkDmUMZCJH;P*z~_!{cy1Uk#V10Y=86N?;kGP0@0QdYJ1!Jd#^zIE6WyZiNPD@ zyE8hSvDfyy%X_tVd-Zn*B$R*h4S#jH9F)@8ydK+A9Xs$^J-Bl*2bhvd&F8-#)WIwX zm!JN@`}k*n`47>!1@Zj|5{reCgZegK!W^ALnxFeFcl!)X3W)+l7|*2%4S=zG2?A0c zRI+bCEjFs_w&}C>3IvWw$A7~Xj(uNYMnk|)6bROkpmRD`ejtdcKH;t0Cf1*c;}$|q z#3>6?h^p&p%O@-}3PF<|CUj<3D$PSmkit$6@U7vZn8sI7rGz37c zkzhYvSfMT4u7<3mGQaBMbC~vXyIAQEK_r6Rq9QFiC z<*f~7FCB+;u>gr+G0QmhEd(`^214;L^3&6UhzlIa2Le72<=x?gL6?W#X!E3aN z&y@{?ogR+&KPpyDU{uX{vZG(Fof-Rj=F_KXe85+sQ>i~*+?lVnsH{LpL?+~ zh4vj5>!7{z*c{E5N2_-=9kfo58-J8DZNP{E`ZmNSw-TqZ!$XA+3(aLcb_!YuaQ}$( z++GA}v;Ka!{D>hkv^3G|}Bn}E)>;DgY=EUbz005LsW zkysuqI1o$D>eN%NWs3iaoW_X&%jS9&+)wy?KudXDZckT*!DmBIfz+;hq8C9hg$eEN zA{#%m(&ahHz#?`9HMri{9z47>e6RVb^!*~KW)lpK``~^xop2YMxQM_*?it%=?XH?9 z9%|5EFCc3|(I^KO`;(rn$v37R8 zlrct1VeZ>?fF&_&jrbr-X&Up8{YooU^h9ggJCESFBl z!aRQXT;y%5S3DEAXu-Y+JitFH6?cRuYHWw>q zhF2OdJ?;JV?ek$y*nQ+%Le*c*sE-R^uO<7>9q)6}avXmo!!T8! zs%REJe(6s5E2Jw{>%l*+`0mRZUfSYi+#bv2#e;8ed2|{UMSqFK?bLMs@!RcB*ZIBQ zhXe5cUo?TQhiT<%bV*! zO!JWk!wu06Z%QUpHZBSRq@=@IZ^$EEJY$JtnTUxPb4J?+Zss4m2>rIbbmz~izjRTp zk5Kwp3)@9~0YOYUzv0G^?Xj)nqez^TfA__NRA2oeRlH;>2i{jAT;cA}s^LS=OgCE6 zRLKV@vz#Q_=nlcQ%;#!d!b{Wf;1|sTTmk6$t;@m zwfaVzB59|SRgNp)EaqX&VxJ)Ko?duZ>%-KK*>N4rFs#Qt`VvS!%|}y z7S`7Vk;|~ag+Z?DvN16e^;t;qoovz6&t|?;PRj{CG{%S{27m{5 zd7-#GM#V80s8a<*sA@8eBQi8qj@l4$G?qfoSVbpqSX^Rn)R^A*VkCBIx}0=*=5e#` zO7`6s%ulkiH*8e!G;;gZ4=Gy*wO9d+q>?!WX&nTl?>i^fFbM@Td-4tHy;0oG=|a5LNftid9XazO0(gd8+jOJmW&!ks44csaVy<* zC?inQVxsgMZ|_E(!j+36TLCu3STwPaHvoP8ZO_s-spH#2b+U2Uhv^AIgYa>v{L$uC z5j#$h|5Q2yQR_*SZ?DVQfY)brO}hO!f0<8*J%i=%`%egyn1Q%>(vqiI@2W&qXQ#l3 zo40iN9lG8CdhR0GI~)|+T8zH5q)C%f5`pd(`La28jIqq22E74p5P-zuHTMCG>1r~H z<;3I)feJW~85$@Vmn(u<@X|e~t;{V}u;8V-RENasi?e@=cQ|_>LrQ^|;v*R!R%HnR zc*rC%6-HT|5kc*NqRKbn1?bZfG0cGdi98?^c6)xpQNWfbvWd!WUE|{A_?O?tXpm8B z=xZNiy{^9w*P^Gnwy&G%M~l@m4zxZZkK@tWfWaM34M@s+U#LtH3JzJh+BCJWCbDzM~ErlmDxi z^YY#51vcu}HkuLKfxWqCet8Alm(HmFNdn^Y2I@Evova7Wes6!+lqrTqi zH0g|8fYC)gBK2)MNS&H;?`KEJFAZuwSe~0bIwr_|VVKS^QTKWODal-yc{_hp@-ne_ zph)H*L+1?5eVbasSV3q)W5-kn2A@d3_$bwsPc@r`}wOM3CiNk>46ys-tK!0|JlD7_OCf~a?VKiA(^qu)zXm+JzOViBu+o_naiTg=#dIEzGfl-OTWJqAPCopyZN-Y?c6axDl0!t8qt%A%3 z=y668xXEmQ5P|atfmsRU6;MKET2ah;D8m8a96e#50Z~mo@`JNpsq={rg^#)oGJOTF zOS7sg6vuC%n=CIhsGu~cXgH{3KS)yc8B~cJypS@edS~!|vjIx3I^GzF{@DM^251@> z)ay4DsY>;BlXW8=RL1#Mf6_@mZEr0dwVv3}5Z?m9e02z(KVa!IUsyxqGAy0N8yh{7F$iJQ81qO7aX~ zQ^hBx>5u$;+zom?Oh~3|z)^l>N|)`z`p2X#D;gUfsu7cVDH!0YVg zrbm`SZ6G-{hOfKqUPnI}^Uit2mCvomj(+*(RhW>;a}C3S0Fd!m8o4VhON0agoy|kT zEgk)>K1z>j)gCrxfSvo@F<{kD%_of)A5*_7#z8LQ)5(Q&bO&WTlDg%GSug`N^CFFy*IpNMr!~(fu36pZppv*`a-+uG9v2S9*bhcyc9d`yls+6RZ4~8+1 zwsBj|%^;iO$3AtueLeV=Lcr2~bCfD3(-IF-bx!`3Y`IvW6m6J!OI7UeC&a+y_*!rG zw|KK1sOh4T36nKMbqv&Q_%2>?B8!;5$DP4ek2tWmJY;?|C5b;_R{N()*u5Q*oC)HBdxVev)ce7 zl$ajoY!f;Uccs^xNaYG z*xXQjHxoNC<6~kX2xmfq%7;u(lx)^qtT*Fq3zo6fn#wyGSz;EPr2CPUU!>k=ojgsz z-xbY&&9h@oYca-LhqPGNvLH@tuh~)2*cBX3V4aipHSM^Cdt`2j2|8qO?ehS-Ak~;; zdYqkxa-Zx@hTD3-8*#?+ODdd;T9n3qwc#E1B~i6oo}0Jt!aUr!u(+$>zRC>T6!%U@W( zthaHy&6nVjY6m#khC)Ry&W=Qy8@bJ7jA;bvVUAt#0Y)F93~kF=QVqqBhV?MrHOHVV zXp9e~*W0_|S|6Z1`aeJzZnP0J-^#mgD%LkMiXMwaf=N-6A8!4uquhVZ;hgd^P~E|I z*3rl@-wipqoqnaBmqGY_YVn*(-?Y$|j96)K28($)HPRWHW%6iq3$#*CW!YXRp7#yjqp68<_er2Xqhiso3|U znbug&DzwaeeAxV5CyjhPOQwWJYEUWMZhyFM_|wZB-fPw=>==YJ>S+Y~XB^LbmDUs% z1;n4in7|ljIg6QiS7Qh3bZOoR;W~AE`mK30l1WSIl(MUg(HBGM3>+6WNfkqkcj~PB z!nCGP@&yU2hoCV~b-DI?!(SA_L6R|wz!>=r-N$Y(e7mu@C{(J0LZ-Mu;F!;O7GJu2 zGkNFJVsY@mQpEMpXHVX`6Cm>j5vGSfZLueqk}arIHlPwZ@`&Z@$JDRI^)MHYE|wP9 zWjvV;;J-p<18A=RmQF+Gqh;Ia9wz{n-d4O`>Ko7Ep>Rg!Dza1>De+GZAku(8a5gQ` zSbDOsUZNG2_f=g?8nac!D8asY#NKi*3qZVA&WOri;*jb7>o9#JY5<&>*(Q`M=FkKu^tuUl8>Ue;4^z!^~)VC2O2!4;y`9LwM3+x!3UfSHS? zFO^rHw?bnuaP3?07~I1FH*$G@wV!JeYkg%~$xG&?&*!(ZHX=A%Tne@nYUjM_#OhaF ztWK{ypQK8J?k@BAebdCcXYNl2{GHaHTLWX$$6)}U?yRTL%%}Uy$G4f(b`dCPWZi8n z)1sI0@i#axh1HGkRu(IP+LaL)RbU?yiTvg#^3B+>5Wx8O31={|k4g8fh46kAd}th- z_Q1G4-I@r|My8Tt15)A_{S%r3A~Jok^q5OG7JOd@@I?8QuY=_4DebcTQ}5o_2u+I$ zK=^k-29D-E|E>csOZkCvNfD&~^<-LS{~PeDtcw{eldy#ObRGb(8%rrNzIx>4os_z= zQJ=h_=?M>b_iOuVnTUIocBXw784N&>!GP8}av0#*LlqaeQVznoAMKa{F2+LYuDUe& zS|s>osUoUR1A+M@cHV1kyh`m8-W@VIyd!t9NYDj(uk6YVUwGi{3`Ek{mLzWeE}OPk_Nh6wKGi)J!6S!p4E-ku(DrOQra2Mhl1jEx z5!OhO#zXtznq1@L3tB_FCHRSv8~_eXMfR_7?q}*$w3tHDY1aAV^i?fod2_!X{Gv1YWDa3z5Ae$ zZ)q42y0KbpSM%AY_SAj2DgK*vLNKg^J+vhRyABD(1?Zhg&WPAu%#c&w<4^0k$f%bT!;g@cVVFd9yjbMH2mHGqK70; z)&nZZgQSx-x#@IyNyW^QBvWEq{8%c-hp*zlxPz=Euo&p&n$UAge;I#D%CTTm+IjN0 zQIGGsm*be(n+}Vuj;t|opxlhc=+R&U8ClXOl!b%RNE?cpav-UoLuN^U1F?cZUE0wH!sv_ms8 zj?_kB+Vg<;=#9_S!H%8etlR$U-v=nZpWUXN6k#DCA>{CXsg*I>9{(jQ%KDC656a~m>XYgmxCtt*o<$zch>*{Mfm1Uj3 zb>E$qqmoKaQW?@R292X|A)oShqN`<3>l+Y3$Dn(&pn+m!10T{pAC}v79P{C{whQx< z3XXBl0M?^C(sjDHZ>C)QQ@@nvz>74Shfhf$vhw2q-PC9_`BDNboJZ%3H~!WI3IzU< zT?x|vR>r6ESn5mGECsG|LYu&q0mbcLF-Wmyc1RZyH+ynIP`bB|L;z}-dgi;S;pS) zrjWpp^UC)ivwa6M{LR#iGwgg)B9NRKS|ukm^dB2QI{!{m7!vg*qk92xMyVLMCAT_^ zO(AG~|NpQ7BROm|=h-0QKQ_Q5%~ffykVCQbo3sF#4Hz$#*E%~w{eQ9nwX&qQVGXqJ z(G7&xZ#hbT>M<*0h2C{TFD^HJJt$w(-ERS+%G3lNq;X0 z^ANQ2sWakx$8D}3d_9RCtQp|+%#cOZBFX+&y=vp%8@Z^SeGsgri<99x{|wbNs=xko zB$W}wnB5e;8*0PwQE;&*KdR$nkBXn4#ro;5e{4Wv;*CkWEG-QnA1y6^-P(wSBxO5H z&E-=Fqw%mFybW!61@}Ntg{?0oq5|)xxnYOyK)8bpQC^8s&%3zN`MQz1LA(^HZw2}F z!f8yMG2XYMO?z$ObRMBAuT8jGA}Hz6UEvcUfRdbr^uaAM8<2z4BeMafc%Mr-|HB5H zn$Y+hum=pQ$^XX&RNI1NHi%5L;?hIRpMyLny1qV`gx$2~eDgyP4aoUU!nsw^6y7<> zDx%^cigT*=Jf{m_3Zc$bgHbeBCst?-~!AkUbCylbi=`4nA3dt+E)#=1R= zMX0Wt0;tQ4%uweGYsnR&vu`m~c?rXcw`Af3d;KQ=F)IPvXUc)(rTM;yE#%;}pOP)|{o!YJXT zx7vRK6bDTta|U4mBr(N`7bT3fw6}|;|2#nNa!Yyc65kqHM$n}&L)7i!g=EpZXzw>6Ea)Oi)=OPj z3mAa+dS!AEg728N&K5GQ2z7j_yir%4ppJ%U3ef4C%^1A$<1l&rYw>EQxrU7a^R$&L z^Oz5m+m>7z+bv=Z>D_sDEx_CQ40;|vxoqwQ01;<3bjPIq8Zz7vx^FIXA<+k^J_Fgu zYsLWkw8y905x4jOW@<*#fQ^-r^5*ZY{{BHaWWg|8RZt`Bwq)!nq1-ZZw1;YJ6&gY` zOV9l!1>v>E%C3AK#|$9Ct;vD_Zb+5(02#fS0WnqeB#(8-f&jqT+oFqR4$B3_`+yDu z?$KMHAY+8|$b!JENoDJk5=>^Iv8DiHk#keq+gvQR4RxJ9g9&!L3{eoD2s0Egng}Y$ zw$9;zmm!$l7WjptCx@?g$TP;qqB!S>NmR@8egBL|eO;`?;sLlIz>?~>vmw3Ed*M{^ z*8DV0pE)=ZClj1jP!?8eRv%zghC>@&KJ!|v$mj*jgoypz2St%5c{~}mLWei))?c&2 z{d;S8UXaEH&`JnEBWQ(pzKf2Zq2Z0&VWD}J;pbA6DTim4Vc~^K_BF=(%KJ&QhHnF>MzXzOO(4aeu-o_)fGde$(_f>MQMi z2{S_6#SE{V{&5?8d7b z;vZj4IEt6TF1D&NF21}1PHH(xO++R15yGNf>P~6#e9%;Qz?mYfjVJmoPn!hBsDj(7PrY=GDp4p=SQyoUjGLN4XH#9BH{qM~cpD!nC zoNq{Sey7+KYJGYud{wuILx|f#Db{m`WA_Y__8Kl#M|bVJSAPn$zbpKK9W;PsTVDLh z$Dt|Os&ms{5XMW=W$Y$#?o8i|Yf=A=f0nAZbpH;Xrg|>4=gX}??{tl~uPiV4MFOHU zz(Vs@nqN!m{m`9(BXHmPs9f-5ksRsX{2#}FPQv}bsoOn7eU4F`k#AuwyzwumUv{Bs zLl?cM38KZ@z~GVF2V)ez8_D&2@1UZ>&LfCh>IfdzsC=P z`(7%H%I#t!N*>rNKq%QduJ`1I-1)HZmAW#{N(B(LMe)|%;M;%Iug%E#ljN``pL!_M*aS08w& z7j!RmGosp9dxwt$D{pKJynHma*Z%eF?rl=Rz}DY=LY}GWUl1Lqdq1whDg5ArOrh(q z0gz5Z^tT6JBX61U&R*|K_+{z^QY9$-g`R6y4mKa>SreD=^U9Xon2)pfcGm1coTyzR zx49JeUpAM{=D(iPJeW593Izk8#)_fyln2+#PoI5lDky9}qm+rYilLhS=ML&j4<(MztPH5S z5avmY)8F_9l(p+=_Dn7`Kms`mdGt1$Ht39dyE}(*!!JJia2}scX!Xa1P*!es{409?N3)?I>C(Z#_#wc2KyAiA22+^!Lr6MH_&PJ* z^WK9mNX&CX!e{I6SMLg4QV|}~tZRD@su-t_alg%OkHx4Ao5&4l;0Vm)0~a#ry1KtR zONjbIN9BERUvL?QAMb~}^i4cm+xQKt=t^#95u3a79jJipgD}YXP0>h3X zORw2kPoD{`?ua^4)|#QP%6N#TE(zkGPK~+9DTvQhnH0`?SdZPs>)3w$e}wp?mfnNGw?8mdY?MYdTJHV1TDOW}^`2(O2{T@FImUtAkX*5n4 zlsDiB+SF@F;*ODc{P6MPCW$A{1D}K&+C5L^XWon&_#}YOlT3L-NM6NkQ)8{jX+wP?XAHv$JuXZ>-X={T$|F-cgc=K7!p(RNTsJhu<8jyH|#eKJ?SuEw5&zz4+51>{Mjdmc{MytLbHEwVchjfXGW zPL1hgY}w~uLu=~Nxh4tM8@$kNtdhCRHk6riS!zfMovev`FNf7AO=29=Pl;;Gqm>Go zNtLhn$z4uy!U|76lrnA#3I*%R$nj3hN!;ZDSL{RRPNe2=wiP%qQ1M-D-aux(c8XCd z@Nk4agFn~y4wJ$#dK#(T%o)r!iD7gG>!c*T$gP0IKq_<%evywki%(uFH2KX8%K^C6ffQ}H z6&O=LD^X`v`O&OYUvUYszyQ67o*FUib-ABH*UtJrJe(iPr zlDhANV<~*-Re{9b=FP^0v=KyONv7eR*|ym2%gu{{)rs2FLs@gg0n-aUA}1pcmzRTg zMU32_5J;7*sgwx!$*0rH0Y3wq{tn3oJk?bndvz{TeWK!b{gaWrzQZUKxEf9b?d>gp zdt#g=)>xodp*jFDkUPq4_IJhnzPy0eo#EQ|LpX^cLgZ$W_Ny)MlH>}$haN?_+#g42 z{~yhlL8MT0{T_L140NUWPlL#l20Y7Oh)Sp~-JeiK$uK|75ZDLiZloNDuN9Ff|FUiS z4`Xx17rhGI5oWss>giDOCwenXUpEa3PcMa!hO&QcWmBx9Sz%|Nhg8&pscH{czsYh5 z9&G6^(EoDk!eww(V5qs;wl;SWieY!IW0ZzWQB;Sh_F!He1z+lp3_r2`K_kM z+bE4gLjsLMnUl8z4?<>wuhO5bM?<8_6THg?@&@=$#BNQLBK>gDwGR(h>$O~$a z+T{ErKoI}qsP+$k??~V?wNW%`aeVxv*QHksB@QQK^Av({c*uPPm6~vgXoU-d%@;~$ z04ebbcC6H1JEuvT3L7j_$N(Pb9LYPX`?*zLRLS67yTOMey#u@k{*}u5W22BZ#po)( zczosk<|sYPE82IQE(iM8A`FV;1H>^RL$99n{m^^mSLOCyhR=g^I-vum<1(MI?A+6- z36;(bBWB%YEd8w00-l^YH& z&usGXyFa!p=S8_2LE~4WY~w`O*;L49eE9$-pFXnyS6(QWS)@w=Xo7_UKy+dQ+9yna z$A3-${do8m=HC!-h}@WO+cLG8b6dM-F1qRdO5i8ar<69L`oFZTYb$ETfE zy;Kw9W_>YqFW0I1YZBA2al%FaGG zHs8C;qyNY%e@x!|*uwt!IkRq&q(Zo8bfApc(&RO?80|`Y%8G98sc&T^>I>xOa(OhqUB=f)lSg5CmUkAVnd`%ZK|F+rXF;Wveg2HJu1fB ze9KK+L)qj{omO{IVx@n}e@FoN#Q7rw?*;=Pc2jt$fa=6LhGc`HDQx0nW(j>Z(4%2Z z5!)~M%c{bu;w|w?kyQUz&sXJw_~;SwxbNJ= zTgACbGEl{9SIp?`axJX?IrbQYzW=F@&Kok(A&j*pd^?K$W%h@W?WoBhhhvCB)_&qB zTe}ycSn+j;ety_meJ;TWBt=X56|H#?_vKDDiN6k9u?o=*0R3NVfTuw^9Y2{3DDX1M zW|Q}u>5}&(k0Vvnl;!~oNP#G#P${$3PREjwN;9cl1Y%GuX0y{bP zrjEf5FOY8+g-e}euK-3r1sq;0wb-E!YZDZ$OT)ZJ^Z32bI6v-vc})%Zu_=o7qE!tI zQtdU5iu^G3@Vovom1_7H;i;93s_@STLi3$r-{+p*Xxp55xnpTQy;quQ*PCPqT|Rwse1G|! zY@hs%tu>z4wD>f`s;7k@xVbd}#-$OW{`WMQzIrL^H&D$uk4dHgZ5Fl2o#%t)4e9;} z95ipT+oSQ!6on|BhOsbG(lE!>#`mHKL28-NEHUHIk_d?S9G~vd|qtlS)%T^5cXT7Gcn0Z{X<*a!PA+K3HL(B6jejJ0MeHSY6yXk*Z70Lbgvb63XcC9MU{dBE7QTr5MZv8S%g&3oc-Kc8jJv(^iEv(+@MX;ZTY;j;gm4WO_o)n{qiPf2UJvasK&!!Z#m`EPHNc0l7RNH#&s zeDM#t|Gxxch@Cg%rBr~zkjR1z{cTUC`}5jj#s#NyvYEyvypwuKQ2*;C!^5&L*_B2(Qnm6iS);v!p9?yGfH6$_f<rHZaV!ev41zqEIraf5748SGH(BT ztnIQXkt$(^RrTULK&MM#ta+2L#m!DkTN{CoIVQ;aayFP`F8#r|#uqI01`Zjnh;S+$ zR1#$eeL8%s{lm*(75~Ir9A@eHtSc!fi=g_uwp>qUtt*+@;GP7XuKY{Q;dh@q9Bo^H zJ{FeXJZSPL2`0b0KRr))>ZiYcA0dRx=RFgoXqyeVUiJB73?rvP&7DQnK9~3Vq^t{FhQHIp;!0do zG6cARx3~R1mlJLKeih?{2$R73>A|ZJtwTGqiJgHSKnj*y9iYduaC_;<&p*Zm70c0b z$y4q9sy?_Sa;=*Z14^mp)@G;AFsfLQDu}7}sL`#4x28=uIrkf>gqw|0S=;p1P{l^* z!7843i}PiV{#ktl0PpF%4f$iS_w`tW zqnG2_)BT>vR0<5uO_%4;dZ_ep7rvKe;(ET~izT8Z{g7~F_!DbQLF9Eb z1$W)UErs`=BPb2QGG^v|Wz=H`)z{0UXpKufL16i!ESF z`MDIOwOw$9;iC)HCxo6Zt-?&-SM?O8^Yx)evO2%F5f66Ctp5H|Ym0YLet-hEBz>uo zTTP26UW(^aBQEigc1q&+iJkpE>N;mdIFEzC7En6M%e-_6)Ut;gYhI(J2c17%J{kYB zy9eqMAl1qU>Fy~eyq(|{0Lar1R%;L&%}-l8Xk61@5~>Btr++50>=?Lr9G)jI3FbJ) zL3(z7P+P(UiTF}FU*PhY>r`jtNfpr3p^OzW|cPaB9-lc!WIXM?2N0}%N z%hKx%N{;1qsTQRDh5*u|b_z$ExDWXrLRTY$NZh3+wLoWE445~z zC{4CisvBi63?C-p#d36fVc;jZP)T_j;mJe#Y9Ji7g2N#%415dNr5&|mKCq_0MnBSM z*(WB?vbV=r;(ZB>f;CxF+Tssn2B3F9J)}SewvhJ>(G1j}Es790JIR{e$lJ+dS8+~v z!_v!bjFxjJpZiS#=aaBGp@Yo?2CjZ9t}T55=mQFc9+d<%MB1iwhYYXyQ#P=f9Yg+@k z6eE^G>N1aX8JOzi`#b1FHr|Q10Njn9s3IcEYYYO9;c_KM|1mt4AY?wCWr852N#u3} zQS4)QY5!~fv+E(n$Za_@qbNBccJzl1d{MzYO9j5)B7*_uLlD>xKDgg zA_UIx^)Ah79=3=h&UPvDTBv@=k9>V@>1l3*Fva_mQsqaB`Cz&xPq4nC47vC}RKc5kUCA;(v4s0POSAAq5yFlQ3g%E+n?^W0_<%ePAnfu!3bE-p8g;QBiqX z?Lox++<|}>!1K@pWoUP?mcZ&*4X)*9X+crBg1B%&ns1K!C+)NlSgq*x=$ne#(qSwl zhrQp`dlV0w#e-jiD656jZPZGbbO)_G88ktMhyMEyl|VT<>+va+u#0(%r&B3W?@L z9-Q`7-I@Sr3;|53&oBYf13W;hdRl+Ng(dXlD2h;(Ao*5C?S>z7jQrf&dYo+@l#*E_ z?LiVSDG`k0t7tNF>o6))H2&JmjEEF8oQ6~rIAidyVw8~Eddw*Rh5ZtbJ9(vr$ZZRv z*!AG8WCS`;|11b0f<&FYHKKTGm&i-0heQ*2G#mWDVI~s$(%}GvbbnymamMTlv+*yR z%VAFx%k`D|aN~FZ>WU?vPkL;OH&9|zystrm6a%!+mv~zUg3-^Mk}Wy)JyFy+ZcfkM zToyZZ{PC{cua;%_@h-|al1p;dw&B_3uu$WV@7?TnK|efckpe7!1b0CQ7|DM+a0r%D z@m7xVR(tNPb?hyRqhMTPLpMteN19)1<)eGf_TJp{=ML9# z`X1<%Dn87AY(VDofZN9b+0WU`i7|}<{$KnPDpV5gsRY*e2R5k0B<+0kq2)nt0IFC6(Z{sDQXCTGGsM@PSIm&!~{!&qK~xL)&IQ;j@PEYL)QVQP;~e|HsDvd{DlZvr-a7QuvepjS|wMzRU+#U zk)|av=D#AjP}%fzY*bEPi4N`?4qjBpI#zcTZ!q}I9y0Un-w4~G-L9fbndP~Ri3+)( z>unpo*32x}dc$Qdx=fm3Xo;8J!KR2UTCq4bnoZiGz+9N(X6Mw!pK{VAPQL9Q;+@{b zBBC!6*gkw?@~Be29KjaX%of`nV)voM>GOwM!%lIX7krDOHTI)Z`ZQt7v}_&?N@mF-n1-JLD@yHJ@UTQRmsD>h5xcac$d zra^2@`#?G*D*0L`AyhSE??TFxhgcqiyIje4IR@`SASF}}6W?DbaQm3^=2vpu$5dZ* z$bKHYdC&7hItL4>egzr^LU#`(Qt-0``TJL79>CGy&7qvF0HCF0% zmpE&jUetMhs=D&2s+Gt$(2fgJ7kZA#|BnrLl%!stdb9o?8*o~G)xbXdW`nXm>@SGI zOZ_p&CrvUN!1Rv|c-*S~#QWxx?t688r%&wE8;9@JzPefE4^V9uHhkpNFrJqfQWIbN zBu-ksEU?Kbu*=!}{e}49i>HLnW-c(<3}}WWw@|qxw(7U&OtmEIx3U?6#6aYbG1Z3MJJ>uFV<4`gh?H9^Xp&A_~aVXA1enEvU=_%LFYH}i|`)XV_l@}1S z#7EBt_+ePr`FRvPpMrFsUHbg&8Mr5p3n=V)PBYL$h(pz5SjMV&+X#8KanD>_B)K*C z!LE3Y&!TW{e%b{TqbvFTZc)|>Oan$_-${#j+2@K=`q;DRE!dfwF~>SiQljUKA^6n869u#LxCv zmwHA|1LQI6ayIPk`ijsyazB1NO!GBjd3=itp!8&V;ej~8@G|NRUs@RcsVBMnTb}dF z`y&no-Y@bZ_vIzNObPN#eg7C9Kp_7*vN(c(1Y*OQGEZT=0Etj?Qpko!4TFe`ElDWn zCDyL$X&tQ@6CR3-=QG2~vlNBAEkmf&Ls>}soYpNAN!M-0ln0>3&(L{M#-GbP6_ouI zK98uL?;Myb;Q3I}_pzv#@-+eW*OmIXD&{vMFOq)F_x{{7{m&rO$B0`WD8LKDTD?^I z%#og`nOi7lLi723V_tsl1OTW9cxDu39qw~m6HrRJOfQ#YQ;FPuC>NU^b&6_wqTUFs zl1M|o^Q{uaT)D(k2_%)!wN-InCaB+yMEMk{6vwYn{UzSIh0=eC;{3Z5$E@s7r0m9| za_Ob%l?0;q;)*{n5V#0#1JMA)ccT0e_Gf&J_+lJ6Sh7$X12`Pcd9<`*8SVzDQJNMxxg)KiPWfGge<+?Yf+^?A0tYUf|*AN0Bd zyfa(5^M!YJt#WrK;aYqH!@eFDIrJZ{$Az5KM+|6o4(xy6-RC0itR(DiB^d0v&vs91 z5F$`=e1KB_{`AWuCY>J~q~~UysJ|7=#t*hg{3E1F6!gJ4T zAmXpi>eFVOKb>D?`mXTdubd&UXK(q=K|}^%`3gG#IBzpSP;BB@Amxl{K< zZeHQ|`JenTb)R%@b&>)pxY7I(T`_HVuk=;uns zPMLSoKuK@;(UfckR3!TFh@sH&{&Jn3n=tx2H75B2ruU$@JL142#-jSoSsvuwh##^R9xCQs`A~2)cjYo#jr5oYPE=VX$eC2*{#zbJ6viMK(hrk z6~W9kENo>|OxW&u4u@`4qC9)G1{75+m3HNCgRYj1vfgOEo73GGwRZkUIMRKjDDDDb zu|LU#nHCeX^{V*7!B*qmS8aDd#KF6MJJ(A!g-V6^crOcQ|GF4kL(jYffv4HLmwNL@{#|a3aGmTd*XDxIKr!i<;@Is|9 z+KLsVvK!a(r|XL)m@4#r5ZHx&5+7H>Q z@}-Pd$ueX7$&yai`hV$vIG%qW4FH)U)o71=fcm3Au1olaa4CRFq7`9mFr}A-PkB(P z{)|z41tC9?t2O1bgv*~ED$148RZ_PRBz2gGQ$K03d#CJVO^E^DL2l9rnJJ9Hq`$Qo zO#(#~c2+XlLZzFJtw57N=22JA4Lfkl$;uLp(=B z$K94;-tz6Xx7t*?9n+3+(tzH)U=}^P{xG-s^l(cS551=m`eKXMoZ$(jYcds!SM3oW zu!xnE>4t>o1QWIeq!^x<*4AWEsTXyJcb&3}jfi`0d%)GplwwA;QjvOD8uJP<*?eeg zy=+xZARDGS=dp>ST&gHcrS;qgHU+onT}(8yl*EjMBU>l|!9CnRETAjW<8#PY34NJp zpdeLg8ZbLC0( zOe0&Q&IVJjT*q*EAnEI*mU0F_7}kd#W0H<~;*K;#?p_E6xeelh5u^p2Pe!SkkpuKu zp(#RARTK#OOoH?}=(Nir*bmhBZvfVRF;!$9@;E49fMo-hHp2NcBlHXa>~&52IENqe zoYhcL%X?r|#^~kt2O*-3)hx{!!%~5*Hd>fbI))!uQer?7e`)?mGqr9u6iZ2NU}ZA# z_|V1K4^XDpBWyT*0keHUzBBwqXh>aZ;z<_j>3$L1Z7iR{8iI8Rsukp;c!lD`V=1t#j?T`V~Kl%DApHpEONE>Vq>177vFjc-Tyrr%{(a< z7FvkP5JS|r)bJpL!!j*aKP9QmW1OA6VIz%?wDvOJ#V5ev3m!04o)n$)gJv5D(n!tk zrzCBtIK{LzjD~BNQW>nv)Kq(?oLD>IVnGUJfF1zw*#C#L`+jSx{~tVm5)ueKAiaj( zktS7o2PrDOSLszix(U5EL7E`FgLDuOLr0p3NC#;mO#}o)K(e{-+5OCSc4l_3Yd8PF z$q&hSm)G;L*B@xN<#NSet*MvrNT9!n{w)$UWq}k6IYYS|IV+Z`oTLc$Wb&cSI3gR< zQq|88q)o*X6R_bTVuNA=jEM@R+$ii>jv{_@Cw)Zbm_g+fI(xgQU;A_ROk;w7or6vq zGyk7d<@hb8#DpS_@4xw8i&PQKH>!*GE+D?&my^CJr(risYTb)O}n>FF` z!dO6i>;D@YFcQuB-`Ifcc1(sOsj>yKV((uz;K-@=VD(=%;7bXJfrZ;`7R92~G$MG_ zC=fBrLjN0vr_SMP^xG#+AmLr4=)Q0=vyCm?X(P0qB%L_KSy}FzM`I*2(MHdGR(iVy z6!YOHXx0YX9R;+q)MiL@n8GGrxa1=h-ZXso-9yfszj)EnK(foB9ih?gu+OOtiS#a# z#6G?;^*PZtOxuR(HMakM;}B1N&fQx(3Z-okCOZ}>8;U`|n4DG8)EbBB)hBdSBZ+o| z5~aE{uoc}Ye$vn!VJc$wIND9^WDOw*@#Q6#a@k5|B{vn}=RbJ41fNI%XY86@p+$CD zct?dV_*38HX}^5ebfm`bB60U8cVB&b0GD3QMFd(U7B1o=C&>m$e*y}Gx9NDAzY+OK zo^7?(Kg>uLB1!KwMct!O!snEs&0NSCWy^f!1aQBMFHX4&Xy~N*qM>sWp6x9<=JEb# zDD0rmpt>J2Rr_Y0WcxA}OO->(umv*C6b+{BhtZTp)kA|+=S|v{oWb0icv{?pVXu>a zh91y2FN|_(Fv-o6SWVl0W%${N ztw+OrLqoUO?@GDeK}9njZ!q$Rz8$wFd5R@C87|gw+0oR$ULD*|1cClL1Mn1316Ux} z{|g4->i=Q@t}!?NRRTEwA0&Xw|CI!AzK{9!_3Z5I*RNlvr>B^c?f+Q zZ{L3VhS?jyeDC>xzyMCL6u`e20A{@tvpDmw1d#s!C;^OOW}-14pJB#5R%b{5BLQGW z$}z*%|4IO9|40B`_c854m}ZXuodnR|-;YM4-@kv~+uPgI)ARQ2+m4Qowzjs`*4F0c z=D&?{{}=$()tE{rOg%NGmJCx(jH$xMRN`VPz*q(VQwm&Ga`n``z)Aphb#?!h0Vpjk zEh;K{{rWW~HwTlNg2~dx#00hFW@FR;`T6z6yQ6H5Ol1Mq8q zb-d%}D!(-jA=87-e;5G0xyue{%@(aVWHIni^3-8WPryE)Cg|zsslx0C5)U!=pap6xUhDwl061AxB`6Q$9A?G7P^55Tbuz_%=uC)M9x zT9Bkes5Jd}c5)nsh0sb|d84oMI0CXN^4&bMSOc5>IQ|y~;5Bk>&q|vBEaXT?TX|^e^rhdHH_fsmy(H@B1^h*2?YwkpakaaA&*!hXEiY`lMux zo3>tNm=&HgU1>&^nAJ2AL$F^l*(R}uhY3Zlx6T?Zlef-vl_8+YCg|EX#->6LC;>}I z)?35k{D$VCX16a@YqoAbdd}vS(|eYbc;Fq|zF!XB7@n9nbbk=Z&+59%a+uN2+qcZv zd!fdEGDxU6G1I;kPI#;hCe=QE%lyXexQ``~KWAXV^ufs(|8lMGz!iA9N!#j1SxFJ| zq!s@jxarZjiYW7-khXHILF*?Du2*MT+}L&dxW2mO`e$z2l{Z@NGg;vfp;wyvQ#3#L zr(qIo+oDR?4Rt>)x7V}n%i0}h7aBTz>TR=u-x=3dIZZK>kLCzaVd)D*1!4M2&`HaT zO*Y}Rz!eo`tG1TSlltG^a_F6;G{b8L2~0y5hydoFnN7s9?cR;psDBRYA*3`%R8Pzb z(W)VRQUxaX2+&x?Vx#^8Z;IHgr%i#ESzrq4%4aP=t>wX8;zY`9ID%z`pp z@fdPH@L4;}HXE6^i4qGo7-F(r5(ekiIK@5fN%d=FV}{tCEr|DL7?4V>d@dv~?#!Zy zD0@nPj3jc>7@%7^juA0HDgk)Nyj6ZbS!_KAVT-4l82 z`tU~2Ktw>=18M-s$S7k6a2uhz2Fi>wyNq1jyP8pTGpt|BG$e;yw19OR+EGc+nSv(w z*bf1-=A_E|kCn!g{d76Hg`yQMG%#H@r@Hw7&@bQF2kioG9u41&EfLFlwi!}w>>B){P}03AyTq7{&_f}mB|M83ote5t8W0Yt7q@hQ!} z>=1vaG_|$nn!z@8G@3kGNZ_B~zn{?gcOj`gK=+^Ef6)**$xNL8U?gR6(Kg(#7#sW_ zfP;Pd1UFAow}{zmjQuqnXhlrN@=pIz3GjM?n;VC<%bpO|JJUwYC00@LMQoXi z^6X%FKaaALlB~fnZkc>*&B$})T*FcL+%nR6mIi`6^7hRa**E+Bj%`Sg&z{OK+dG?M zExF$Jg$x;(CbBk_@8@>e^`d*O0*B0%#2n@zpp>JQmBe+D zj;6w>D%|_)AmZ||!+%;v{8nfIu;UvKhxSsJO^t z0-vU^dIlk0KCcnmK|k7oq>R!()M%SI?{8!7yN@0pmT9NO%B>0G0^1u*kaRU}5)l+N z@dmTJH?lz{EsBt4eI8BH-WaQMXh%=K@Y5dENUab7Ww>6PP6=qdn-)c~d$qI>fQC+a zqufKTm$BbQ=g8k59?$Yuc6B?t#wUOHcVDk=i%ayp@z`)&u~|EMDbf4;ohNQ~|Q&36UTu4%49e1^}qyBd03GfskW z&r5~YaZ;t*kmHF4VrGccine;6Fb}J1vn8ACfVq@Occ<9DhqjgNZ3FdQ;oY*U9?!d1 z`WSz|U1nVNx9-UP?ES30qxS?cGnBwW%CbYj_ zxs2t$(R|nZkY_*&<0w~&Vw$VuCTq}I^UFm8GKI4N8d{+bfuu89lZtr>*ah!?(Bd_HY-eFGP zSMBM%DIC6ouONKI5-*x?RS^C0-3`8ho?+A$6Sh!zthbU9G;NnV+Htp#0-(`H;szpN zIYl8*<^xar{04mx#fKdPjpc{Tlp2ge7AHo%ue@-xXhobnT3hgGF7RY5S@^ z#-1sDXnimV0YuTH#*NUc^#_k7g^ajEz8PzwIwgG`gD10a3&i6Vp)u{4-w_Tp@sUqr zzzcUFoyeS=c%mx!pR*Vrj>i~3aj>dB;Ra!;H^JL9GFFp_Q1J+|jo@JfIMF1oaU<@H zaAZbKq9rO3&f>z-^hn@~^Iu59Q^Us+S&wD>;gL2Z2Ss=_lHrer;;4l~*4UHRTgCQA z!r4_4nZHCh;Kp~+q%`y;l5Qj-`iwmNg9e-dQKyWs` z9fMDs5z&-J{3(t1B#nzKeLN$Y51%YyQE%M28da zMq54%>BxDZoBL7_lm+4zy}wA#?LyA0nW?NPa!8S;+DNXb$;7ls=U)91X-f7y7tWbW z?qf>+)Fs>BR0yt!FUbiCUd-ZH%&rs8K?UWK+UB-OIIeBpHQXcL^v&8HNgs`lW)Fnl zrG1gEnb)S0TU(r)Lz|Be%7+#su<%0R-U|UTex!+ggL58{ZRRjCvsUT_lrw+y?MvrH ztOd^9mBF1sUck7?oyJ-)_Xm+_$Fuz{ziuG`5A@QGR;mu;qSsJO*P8q4Lr@{kL+(dP zoJW5OEl)XY!LQFuIjw$auJEL9@hCY*Wv{orrnP;^{2_DKw1}a&Fm&-1xDPSESVZp2 zLc3Ws&%?j`Hm8_9*CbjkB_2PGr*K#*9+$3!4OJ9KBf3`o`p;rUr6!!Ch)C$I5RJ6c z8q6EQTOuw^#%{)4<5WydP_)yL)BhGMv|n0r?}^CqKUw-YBsBc(D~YQzg7i|(u2Md& zY{QxyLNZ_g9S#;MW9EhP!%1q3pfYgWwcmNV1m&(~@JBU8?}JKs2`Y_h;3~)nwIVSU zIty7`0`#%py{-zRE8JtOlvBCN$}F3{%QTkG86T5QT!tXr7b1=nDngl6!-cDi$8ut> zUi0w61+Gd0mrRw9S?}n>FKkF(dqbo2Nz)B-U0kd65~|TWl_t`)1_^LQv#LWys(gKH zzC9Gnk0N$!o)gp}d23s1u&jA$K~4E#wpDSLRp~x!xfXo0hyX_swliHex>nWhv`!tdWj^sJ`VdLg25x)Q8NfOai>vtQ3b(BMVaaJ5u$Ee)rq3pq4SfJ~gk>sK%v+WCT5hj$#=2Uxms{7aTHEN_3<#Ux=1oO;tx0)pW`wmCA#I|G z&5!7t`r~a~^P5EXE1eSC<@1dc3EMqtJM_n$B$hjT$6Nf(t6j9)tq40q2|M?s(=7QK zpVG%Xkm<}Z?Gy{?OqOXwb{Er`zD?ol%;>Jj9B&Vi>55w}unTGO;p6&No%Zbdtpsh? zr{LzM?slwntQJqyY|>TI+(pp@!xY`)xA_+^upww;g_}2s<{R zpRs@e8jtdGR|8*0V{J<-hOjqhxzl_p+`5($oIqv@kbEh+rzJ$_IE`b2CT_;^0BDk0 zI0QScwChbTgRGJDhN6Xt!A&^7gb0*vU{^MFFvXHpKJTyN)%m=AFGJe)#vo-OlzVPu z3}|8-v@!%`V1R;Vwm>lOaQ`&Y_m6OIyy=U*iE%)LUGVaiYc!0uk4d^u%AzmE4PSCD z`g?bGYAsp40s;1w6h|0#fPgbLlH>y*Dt&@Q1xguj(uhWY4NlmNfTO3iOL0hXAG!&W z)2F))=)?~URS&pK42bcyC*<_~?C*x7@a7Z*HHZKK1c^R7Tx*^9x{-9LNEMid?iG<@ zj)@!xh?6ivaQkD@0x39Lg38f-SUi4Mlc#$#zq4&Wcob+DFaaN@T` z^i*)-`ZTB+f^dFaKnP7->f|~AA z_i|7W4z@f|>`um51i7h$%&Ze=c^ge16H+U{W4uYM27uEvJV1z`j0-M|rUBptbMOJt zo~airQxX$XgfBZL+&f2mhD|!7|MCu+l-^?oh`&tZ{J_CsW`$gM6Ig8${KRLxZ`kGWNl)T7qY7tVl*1Q)hy1BE^cox zzSfy}5k^j*RH5pzXdky&{A6NiV)$Uw@#DQEyMTGZ#HAPA^Y0eseqobUlW)lbtftKt zTnrZ53trX~*wzt$%;A^tJGPDzSmvbo60?CGva}ren>t-E>m4Te0vWN7*9yWysd48=i$;>@X~g2$c|;+dclW%OG=4p3ti-zAKPlQ;_5G1v-2N{ zJFcch^;!5wSk~XZia6;&iu99A{-1Ba^I{&NS z2FM%=OY&HF;PI^M3B(yk4@s?+*_Pq{;^D+^3^;YHu-q+l)ZB#NPo{)KN<2q48>v83_u;5p@V^UDq;6WqFJU{@I-SoWLGPK&{ zYM|7cwm=nqgEwV!Xl>N-eYNs*b#??gfH!~w%&rjH>>c0ieq!2M8e|&B5T(dfw=iJw{IxN4f!LcFODGI}Df?^cLqBJ+X z)|M4gHhGIdm~&V_N|v9XV}Bvd;MCEHfnMb?iRJXn+6+z#5-P5by9VsSHnwhb`+mP0 zusp$AV>~WhZ2lT|ylJBMr1+gEKy+wBx(X+dP5JqJa;FVLzsBzc_SzfMiM z9_4e)PO1&nwUvI}pqje==$1@v+CnAmmx0_yDbtyd@I#GbaN`)`&=_FX%CA z-l;Ew<$mKC{g&Uqs4rM$E(T)+kBw5zp{X>!UYARem$W{=^FIE%{6NX{o`@Ux6ZAFx z#e3OKk3W#`Do76Giifj`W%v1f7^B%@DXs zU|ubkU#)p_?KpIu|Ks|N-Y@KJ%@%+BKhD<$*6o&4H+Go!HxI*a_I_MBdr_*Rzs{5X z&3t#Xa@T+A>*B8bt%*E2LD8O6_n!sp{77b+toOG;pKq^6{{SF`bu@}(N)nNyzo8UE z%qYhn2*)x2l(cjz&R7NjP|Z9)D221BXK=7R5zF=6OnNSA&>N+BGVq>M*kf%l_wje# zLfNoe2pz@FM4l35bE|FZwnjO7uK4ODg{x}yV?3&~*`EtI>E!ihbyry|+Szu|$&B(b47po&RetpJ zMu}4OPnuqZ;ii4oGmY=Fx|<)9Xws}XR{JjlAddMsrzIeIadWTZ%c_3Jfx*K%>$1eE zI~b~(;PwZ3;|21uOshd2r5&mCZxSu41BzEXZudrr)O|8Ln>q{y!&v;!f2_WbCCv=e zKUn;D@b2fF%=F*8IyU>U88KJa@#un?M6cdUDu+fzJmyEol~>1Osc#6d!L}A6lt^T5 zcpQ!Qz@*BnS`Iw6P$5-H<0O)yLe9ZAJqHf0slzmr&JmN^Xe=yWH?s>*<42t#uQFxG(ODJP;l+Ab5btj>^zpn|~7-@fU_nkHFxNhsV zF%$tminG(fH%)osp=WIII{HG<=`n%fLu-0QvSop`NljE;lH&S;ZRDc>wkKcm#m)TZ zvjiO;Dtx_c7QZzt z2P7`)+!o(3d%PsP@tTydPIZ?J3Ap|-t&Ycg6uuL_;Avxsr*-OPgM0^_kp12huxvfX zP}0{C{Yq)>gH9;RFpit#<)h?EBligL;)=Zz&se#u3}5T6ZMu->B5p<771t+X&wt04 zv&bQyM?{JLGuvfVZF}*(JXSs&=2H1F_-m8ISxBkp<><-mi7}xz@9$I{b`_$4q6nHo zmK2hSnBdb$L^sny+Ug`>=y{h7Dy@loAnv=@Hj*LYxXuOBD9|zoF zNc`Je`R*XTf$L_=%s_m!kCF315K%fVx6!2>H5FN~kc9?R6j#A*F^$WVN3GK@r!VB( z+f?2FhPUJs$3pihQQe_9$|2`HTsl2T{w*p?Y4a|hV0p5^04t#O2}moT&h~3{Bthz&AP1B@0RmajOG$K0&N@VIxP0c>bXTDQ1DE{tY`h(Ub zy*Qh4uFj@(&0p;3&A0|3yO}KLXLd!&KW&e(S%;xoj!oa(G((Ql7ZIU}YlU~ljj0}M z)Q6HG@|}l8GjzFhkKuP7JnBpo#;D~;vy}+9@hCc+I=pZp| zH>{R5i~u>Dv6V=D*|P=j_vBEW>xmlf^z)kO1e2d~rtYeXJo5gW^)l`W<3Yv4wuCRJ zIa0rKcW1;v9yvwmcBKMit^OP7_6E-{_4nLrY2F9FuaN%IAXKa(pCoKpGv_ZLkUXjV zRobKq;otDgqe7G{pPVb|J1K^(e%}Bfr0*l2YgQDlvmVMbYTv*<#x5S`1Hg2$!m;^H z^`WDoc7EM{R0Vp#McRJ(xNWw!tC6qa^zF0ZyvAg!2Y1)?#DsxX&GrA-iU&wDX7U#udwyFt#!> zQvX?27)~*oXMrWvw5KR|b(KF5o8HJ+M=NKh z9DbfVJ`MdP$O(aA)SSoNtiFktchP?UOV*Ita!iyE$pSbM4lHnzMte#{jR^kfbh5|J zr9?7lB^pR`WKfbFEM_{EhQW80W}cSyvoCgJ4M38umy&?V`sG_~K9!N1qCpjW54^jR zB-u^+V#Pfot@}Zq$PH>T-8jahJ^--k)7HL>B?W|{LRTbMiaUoDY>E@52Ii;U$R*a| zZ$>`n1_3sgc=))iDJt9!V0MOn`S5kXj(T}vL@l5>>z(@(u4}MUr$S4)tcR=K_2Q?7 zfc7?>A8uaD%U|UJI{L!gDefDS>(l&h9xCt*cuK$YBj$Ir2f`(*HG%@@Y*oT-B0>4t zFyfbOu`Zt-eLSEpY0w8o0XUz5b)5TVf9*_+dw8Zq&;m%7wEHWOh#6S45~qZM z;;X)GF7==>!(QK)9V_4N#s*C|%011SU)hlu37Ycn{gvaS^u{L#=VP>-UkUZ8 zX#P$?3y%_#@e>t_pnE$S2QB%O!0)U`HLnrEdkcb~EH;>bb966$3hxDtF&=fyH!RcI zVF-K=Z4jMvZ3=-p&cN3@Gg`8DrF0&lY@;rS=^7nRvzQ;0zli!rgShxdgWv}M#z5S= zSRzKTYybeG{?Q-+-EDgW)n#lRqg-0tbzYRmNZ2jm!9FObpFtiGCwDChz`%-Zy(|ZH zd#tZ~P`nOtk!%Vad*+q1RdOl200&xuBMsNMv5gcNW8Dcv2t_@m0Z=wT5cY2y7Wur2 z9jJ=LJ z1jYvJMl0TlqsfU5RERaSkwj@UQGQmYZB@cSeQ7V+e#m7)d0KdZOl>#c&5v!+ey^-(M5m*nY_2 zhZm1xPO$8NGdP-cDk>D8@oCcJgQ;g`Q%i%|1wE6|h=^1eJ|!~pd&^WU|5SEbtl@$v zd-~+jM8nUUk%Jp<3!-$DKIBem6aYhVBXM9Bdei(5vWguWw(!nrM9-OEdF(W>%-ZMXCJJ1;j9}PUAC0-1|&0NaK-4a;uR? zT-azS${7`w)})(dSZ*-qU8bY*clPG~=b5zhtixDaG=NHbFc$SmUv@fkJ=Sh@Fj!;G z#M0<@$rp3z+zC7T$|GDjS=^q1j$zxETneLT$tdN8Shdl4Wetc~PK>XtvGoIE7oErV z7z?TY6d`FeF|p{$ zVb=LBo%2U57bA=@ZH6P+WWQP6ditIf|s#Z@`4M< z#DB!vq_IA>#F5l6Y*;nNyaJoUHhUJ1gl<_z8`wY=eOA&Lr-GqOqx^;*1ru!( zmW7UqTzBFuxFHb;h=t_x#=Cbz3y>cc!}DRYqn6gau&5b!k_d%KZuocBFWM1p6_spRiUeLC=tNvjuJ>54ep~*?5f@|vjxYfSUs?kV zokI&yB>*7T!1JxbBMZ0Mv(%xy#aD={IiZQms-MEI*jUxUw-$m%NJb~~S(Kfxv$f^= zV;5&MQLaLO%qTA8$;NK7QIXK_J-WD}=w7-hD|+#Gfhs(kg(w{$COB|O;e3O+w``~= z_98wS1I`1H=x%UY*@_>jnN zP1XcMXT-OmUBhE1Vu-v<}dXH|oR{ph1GB!EQFuIWJvAi0w@i%&r~hUku~V%o?W4#c37J zJhyV@^Nhob?21Bw%>SFNP!vs6`n`PZ8)?x_dw`qknzKKNQ$211fkrc43XD|Yi<;5; zC~XaQesk<47FfV}7&2X9yYFI_vs_&w`=h)%y9Xe5~U=+W5%`*9L`2#8#^i= z$2D_!w&)zpRygOQ@D!-xn4K-=b!@)MIS!w~F)T1x;7C-3o73>u6CUPh8|lie`w{S! zQznaYHP0tuOn%&|aoVw+M$T0Yc138^_k^e`$~bytWJb!7C!`A0Ka0viO)TI4+@LwA z`;)pkSG5Z7@idOCP;`(9G6H)@A4=7=Q@g8o!k=!t1i|0!4;)!BRaIrhgv zZ_F`BSfiU<FVKlD5*V8GLYcGkOg+&okZNc zlwKA`eKdmgtPWdQKXo_8KY{`r8nG6gc&4LRMCpl;+7E}+q9tzE1UQafr<^l2%xDzK ze74HI|I{qibx9YWfqPQ>5)qw-oS@Y5RzI_rZ@^4!i>k+A4>2HkssVwiJYx$u|2Pg+ zxUyAoPN^4WIXXVE_%X(Q|`=NeLtW`cN z{p0Uv`mr7g(C?Enr}*u*rS}J~yDPjpK15!5ya?{+15MN6QrNV|ls~Ymy{dlG{su3^ zE##_cUVJ4vJ``nQnMUn1lxE5B0OMGuj*>3tJ zZU)qE2KC-bAHRJ9gJhRRJ`=+ks=OKNxEYs!TlRQQB@GwLBd7p_1L40rvI~bA@di9S zLpno3^Vg7vAnB|Y+%ds8!qqPo*h$o3N;?qFic-ZPQ33uh& zRr%X*#^SB9_=t6g=V+{D&UGSJScF-Un=>TBJBpSlcup_QUtzRhi3`E)KmPvmEx=;`lIkMv<5I6-1j0Rccw0# z>{*AC=p=j%cCj}&Q&`nA&S1^#W0|z_F$S6<3T5FF)86;NPGhJje#=vXw=G=L>GF}} z1tvaf4*@f+f_ywaml;xwoI<_pIq!cM0F!D1GP|IA9!s@+3{oadr+3q{=or*onm|wJ zI`HZEtRM%!%D%oAz`>LrU z{#viYk2_tb6#l3xZ!ZVCA8d}ixa)NrI(E!F*YXpvDE`MzjxFNUcZ3h^g#2eeVAY3`^G~>^=)YZwW zK(Qou(lr(nqlPZOpvV$hi;|`GJK0iYVmk1o3Njz6ac#jj<7ATkoXLVjufDOH=(|GV z?6?CQUQj?gO$snb3tcXbPz>Trsmq;=AkI9Ons~FocPr`BjPHP=SaI!(^WyBmZ!Rl^ z3J-%yG}@+yAUN^qL1 zJTj?F`8h3Gx~6d9wEBl@$AuUgSkGPLd;2Yq&^FL<<#94^jlO-VN>oxrUFbxN^Ut_T zU&s$OHb*pWBAry?7ql_utIQ7GAGXP|7Y3#3-fs(Kgoh|A+t*2orj-b}pFN@EtzOBi zxtql9Gx}ckIgH~?lo)+tN+`VM&UYVaxu@cGiCl29I>4JHg ztL9OOJX3WcXWV;>}0YK*-%+?f8W`c1T;%HzOZ5H8T;MY<@&RCxM~_D9yB z=5{Nv0C>9w7n$WVFIR@zeyWynxpA9FU|GwcQOoOL^L(P7FlQkm zti}Ce%ZhtMs*vY?5;}%zy$>o|H2{~S$odPe&R|w6ab%B2CnO*!ILVXJai6mH4^mKE zw0@T**Z?HZ$B8iBL6YA#3Qg?zNRAseA3XeMzDsX4U~rQPhC$)-u4{~#&WNaQ&?4Ek z`$)rQOYc||zjn*))L?v>lmjRXh!i?$WGpxk;L}tfQn{G80?L$Vn$uz={nCumz(Bs= zC}Pehjik>04!lu;rx~OLAUEil^*NM=QLrfQ5;~GxAcPki(?4x_z12qs$tZ%(++=9Z zoLPuzMm%sVQE}xpDG|2C)y&n&d{T0VpBAOU&c^Z~Ag~b^+Vep(s#SsEwL%^ee#W@LFi2p+l(Vu{v>RTh6pzjXNdwcOuoR})G3$Q_|#B>x8`9u$yyJZUIfw>wkh zdawE-Dv!bE&Z}*e%Gk0<0=z#vr6uW!FHI11^`j9ODhD58LI7!xm(Bw?yFPx!3weF; ziA(=ijqxPx++Ia?UlE6ooQu1ZSxX0hf38tFj?U0?u4!LQs9aJvhyd`rjFl6)CdKxG zLBK9rG>~j262{876!k9?`pm(I`5Ik^01$e?OQLLHt9+hM2{V@?_TQvX^4rKLnG6V0 za(u2`yI?hw_@)+LW7f^BhveY5qdjQR>TDn{+enZI2k72+Dku^8qMjnM5o zKY)>Cd`i{6ufU=w!<_)s|*~EIR zY|-($3nvZmKe@W_8}79f@_t@R#)_~Xq14A`-6$GGT+j2V^)jVD1e=C-vqPYPTHD%ZXdo|S-k1;WhK|&U$AIYUm+Fw{@Fxx00ls@#&&$zi3;1Ck)Uq_nOf0?w7!0si_+ z#vYd+K8A*^iTD0l^hg|@obLN8fxYgK6i$Hyz3)Th5Oa9Q-XPs~jGI98-DAM)d-vww zm1p|B?|P!0pi6=Sb2x&ZQlG3Nx$1&-ky2|KS@Id*(nH&{j&eq1FVZ)u-b*nGlTajY zeO&FiAO~@ON_Bu2bIqRWjfIgM#XjfD?ml!JJW76=l8Ge8RR?is37tRP>#2#1X&vXG z3#fA7+>tWyqjJR3L?w^^OR6W-ydDU57b8o#hxJ#$xfB|PNL*Jrhz%STZ8_} z!t;;OZ{L(P1SL6xTmEui9fk}A$%a_1c;d+@#py5Hp0MM%r9IuC|N68--Sv078cObV zgLLA1q45+K{`#}3;NkY*Ss6h=z1!^a?MSBedX!9;gLPPxLxi~Vv<%1Gd%1Jcwy#kn z@5Ho=e%sgp+{&Sm_(X-L(6y~TtL;x;uUrP?Lva9`g1HaO2a7D-@lxAl|Jr69wQyV2mP}4EjQJur8+Mzg7VX zOhj+j4^R5#2XTU$Y|39@Y}ECOlA_kh_SVxLeprM?6A)GGL zMgxLHox4~?$~Iki;~Wz4i(g%j8=Y{OykNOOp2zZ&cAfNPF4<0>e33F)#70@%M*1T2 zak7m!?CUSMswfZAFmR=9lqLDnhS6hV?vonf<;KlMv2ogluN13ECc4oQe0efR(ch;m zz)E*T$3;iXo`H|(GU2&VUNG4t(<*5=U+X?8a*bl>^FiowD>U~N^UT_Shl1or`vC1Tc;wZVe-He1NI96y(bjpF_9*9yCE8!FK}xiA#K4z^^#d3{%$`=sC`9z zX^}^5S>kF`eluU{W}xY;RKCPsv3g6OdCRp(L72t}P>9#5La_#{D2H1plVmZfm8iL{ z(M;ot+By8vaTtbf&*-o@B9Nn$^nhgitP1V`@%DawnROdG-%?qO(BMWVgi?6){nbsXm43hQ@{y1@=E>&TRILZv|seK5UsNtt1at;&9! z!R;&%h3S`v6WY#|+4dIwS+#aGPC;rx%4F{jb9CEW^eM5U+IeE0kV`nNCb-V&?22pXyXAH|Xd!~Lgzu!8 zWXGdb;T5p$wqPH*`$XO!$HOGUZ+Oj}fX?osLN^#{zccxATkn;?wp9$5g&H`sYhI1g4UtF(JtZEVK1Y`9`tE8@A%`ET0befIR`v?B9J6iC<<=SzLW9bpzyJs zYsMg4N5@djnc?(1sQvq+sR8-X0cpqG1oGVwx+=RX)d0`$5eZQV=srBplGuJH?=-H+ z9L#rqe6UArX3|Baws)U^fx{mnfa{gA?6FdXJ8rBMA|VAr(3)#cm(WbJFt!azW2#C{ zadKaZOP@+758TKQ;Y#F;q6zGG%t~eL8KBii34{(fD>@_xROMPh^?034d?C+)bq3FB zpk|kGhY4>whWQ=OiwlS{!yxcV`6GbFN(HXAd#_zx((IsFh{!mwhI%0SWYUzDm-o*X z`#iPLysk7tF%CWr-dDJ)<^3P!O+ZS(fCfvHWf&TMGe9bdY+~YT=B#ZNnZ8LIf)jhx(0BzEWBIlsCCwy&6$V(ldqp-Fmfe(BCv74^8s~yAF<9X0M z%=b>DmiQ9EVt{iWjUyI^a(69+_6*1$D&sBemz}CKc=pMsEhr8u@o!UP;`h@&;2$!o z8?xdbeo{B=$v+ZMHxkZ28dEo#ayT>xs&)i_a6M#ze_|-B8}H?x7_OU`;-8$Wn_#VG zeA!2H1HePUa_p!)aVJj!B={C*n(i8r z+S|OOhpumK_YI!#P~o~h+OBeYq5_gsr+@)PYgJ+-d-6n}kli5_ehijH82D6S{i;8Q zXL^|Btp00_N`sYaML1A-6urUeTEz(^U|-7S6B|wGjm-cJGUlY*(0(jj2b}I5l>%OVSY)xiKr0g*m4%s}2;589T7Fk%| zlpb^?*!$DKmNzB<94qlc>Q9#DpWZ63?!37rSMyhL2H`*nc4_tm8kMRZSaI&)By!=a zIozFfJuzcoo{r)1_TI}gz339$ynuk>7+kF!l`@?vr7?|vs80U;L2!Gci1|U>$I3J& z-a{-u<+oFaxda?Tg#wR+^bn2UL>r}|n$+gT_q0C3OU1lV1F}^(ckc^RY?-r6tBJEa zQ5p~B+4+RKHfc>b;fI_k!jPBg)dVk2j?|8=H|d>jBP9lR8MwYdzdDe-afQ{Ykp5f{ z0SN>8+VnK(G%v8P)s8G*mw+m;2Qc6vD8lyHnO#}LxJ*kVvj#sANe>}{JUiuQZi3iz z{+*h6emlUQS;`Y>FBr1Lmc4gD1tp-Mq9@-5wGvS9Gm)hVi)Ej1x#bB=AK(3Y%trDn zzT#B-vQacd*vf2tyWu#zYhM84RxzX?K8-tIg?WmH7sE);RXgPfer>CrS*4#MD&XbY z(NpvN$r9x(uHxHYGCz$EYJ7!pRPoc6n7B-Edu+u>Pvw>q5nQPu$5)x7J^&7D6VOnsNbw ztgm0?stQAsZ?t@iBhw;`02= ze&jgJA1%iI)6s305_8W9Ph6`^OSH&bKS|)!U)<)SzkB6{{4zDA%2)ZG2*>y0LQd`G z73c2sPxCoM_4q{@Mp4060e{Hvxzd~mAehn}=;`WkwMu^j)y7f}zR+*Qf zBb-ZumpL#9ZwM!o-Uu%m7f2!#DnVg7F33+UF|&k&V2_;08?{RvdcWu6qEES0Y8VD^ zE>ys+S`-w>*!=y(>yEgOzx8O*EEo)qe9dKe%VkQp(_;Uuc8*Q=1_V znicMkIagA@$1H4YD{O4nF?^7dUY3&_jcc?mtEDJec3Xaam1ruV%OhL>3}(K2QMP(p z_V^=czdiLM0#i!yl^ql32<4ObyS-+I@zqja z%hSztP2Y$zC_am!b!7;2z=KuxPyIXJo_@AZ^v$1iao|dduR2CMCX3uqxlX3n4w6bh zgoXV%R6{q=2GY^4xzkhY+k8GjH#a1N`=;OhQ{r2{sP=*UMR(nTIBMv6xb9u&vxmy$ zcb@be#eN@Uyn08&3n!i(5Bqj#Slk}mE)^skSI_!otbWSe=^q-RV3gi`riOAt9 zWFT+|`Bc=TeU^|t_x%#<-V3vTK1lkPCquFLg=0TPk(6J2Sw-FH3AM2M!bsE!0lh?0 z>qIgTK<-UQ5lILLE3iAs6EO729C%Pw>r;0UW*$y}{jOwj6*l*uO!>ZC;d`mUGQ@vD zpJp$bakceOS$3b6X;_)G7ARnT!OY5@zUwDuw<&a-fGOLt2N3L`HHX;0W@! zzfwtx`O_@@dD7KD=CAWp?r!up|D`YNVI+xI&)Y@ zLHRcn`zcW}9RJ1u=rco%QF3X5J&CsJ$?W>?joOmzG}HO4hjOk#MPHH#UM)54uE#)f zC4Gxx=8g@3RL-wGoJEP~fqnjLnOI6=)Sl)CV`G_|KvICtkp#HoVyzEt)x}QrTK%Z| zI5zU_5i4f|pKhPRF57Ex+e0SPZdpnsq~i7d)BbQmc9V`)uJNuYSHYiN#%?NOG_L&n zs!FApBIu)QE2^djyO~mfCo0d;z(fBpFhR%p@gq) zQmsu(&vl=o-rZe10+9H58?dS%sQL>QfFT1jKBPS%91)74u~QJ;0e7zdE4QN5Pau!0 zuaqhna*&_X_lZD+l+~?>-p)l0g_c;>%@l)2_h#b;$2?Q2h6m1)KR{R`j1;I$Q_xW$ z`+zn%M#YIXd;nv+0uJzP3n&$ty;k3$G~)MrtyHB3Jm>p3q-8iRBF{rOLM(FUT2GIS zc%QFkGy{rzXvCmCF>ntRR;9%ZeW2Fu^td65&dT0Mj`2X;E`r6vn;ip)`ctA$Va8z} z?MFmtL+qE-G@>o~Z0uRBJ)PqGys5SF!CZe&W3ArV>t?LjfFw>vR?=@s#qcDsbd}jN z_s}D=8vGw)qI|zs;Dh`~@3Pz{O&k%a_NW_HM#+}8Us(eDSt2GW=5-h>0VC3jYi~FF zN56KzTzkFT?W5E)p=vOLvceO~;vbu|HT|^67u=?BUGaR2*Zy0WK$3Osld#~W&1iux z?Jp1Yo8~J>u+z%p1F}FMR#*v=ISQ&}V8)gH6yIApv-?jOe+>PESRt7gh%?{G1K)hd z-8~LZCqediMlogtI+U7%^$&g^C5HVozh)@wIo(Im)1T4NLrX}5-+MMYjnmJCoGSKM zg&ll9{w~h9;gTE068owKDy<6iSv@4U35(naTMRRc@W42iJRGE4tU1YFnRwumX*RH) z5pXNVi7B=|!dN<5xR)g`rD*!Kxp&L|&Jt5+8J-HGMl%3MqAEOY7TWP~%5t}q7=g)1 zV-40BOQtTb>0e5yJdlfM=`2cSq=;TN^ve1>w;cRklq$%WsdY47*+!a78Ocu3f{ zPrkO@Wwn2U7O&tQUXAaJ6FP|!&u;(TTvZ12#=mb88$BTWi@*SBF$Hp#$Jq5p(|6Hf z^G6_B$x-x`*-o*p8k#@}$Qp=Qp82tf1HSJWKxq`tVH{c+ zc=ZbXDPN8)S!kv)^XkdTBN8H%Q%n!j76n?36C97Zt@vj?CQ|kW;xXAr;?s^O(Qnjo znMq+2to`UmEL-z6^KVj4M-U0r41^p(XnHl!?GYIzSia`Hr%f3hQhTSdz82qLj4eYa z7CofC6^c|S!pxBvEVpowg$=#H*#O5&Tlc;O9P<3l!AWbu_S z($VPy45H0;go`6X_TG>g$BJP7_O~8Lg+!7#)L2=7$}lrYEuV84Dk7#ZHM2DP@}t6z z3JwFRS;S1Blqa-QA1_oFcj3)@ZI3;yOrIp}Fa0#%y*jd+PA zVlt_Z<*md^p&BWdNo`2AR2Lhx!sLqBK-YfDJ!xf)5Q<4_Dit|&(9brXuSsjJ_BeF3 zre2-aL1%#rf*p6Q!lcLLTRJZfodc;YHt^G12Stut!+mAth+a3Oc^tWmfMl}X^y&WD~s!c1P-16ODlfZmZA7$DZXXoro{pZOwn@Jb?f!L;JxBo;b zq<8<-j(7uS!qc-*D$~a01hzfpVs}Q91d7Y7y;cOhyUu&RMDe&k-hGPaeBJ#=8XKK% z#sa@f@g+?wP@>br{i2`buDQDz!soC_GIkv%{A4NgGTR#eIHP-mMw#5H4)&z#Sp*s9 z3E8W=&5yA$6a*s?yc;edArd4N48{(cu3EAL=NX^L@z{C3xW>En6k*aCZ|a-k08re1 z2VETvVx?q7imlV0F|7t2i(4+>ZRRA?S9g^-sdn*MamG&)7#RFTL88d_fKZoU7JcUU z-OESA{w=~PD5syQtKy8HC2|#mI(v@R*=gekuDQDDKj>cH%v6iARX!uKmywx6DR;K3 z;Y>VyiAB&J_V%cxwi)BVtWqMT&hxT9He;7CKXaBqnxLB}$Z<;eWZ=C_VO{ixT&YhQ z%Ok%%r`jzEA91tw4KU#mJ_!l3&*#HAw*LOU+Uan{i8^QK{�B`Rk~d)tru!f!u{^ z!MELyzilgBzTBx6_1((esGq%3y0+APazzDX?yAOc6oEYna@HN<-t@92pNL3zY_R_N z-S?R2G>-cfM|ycgk$nGYs$$m9@deK`O2$~P@?tW1G4E1sx(mPJ99FLHA}znfKa1^(@E6!5v9VzGzEmhq#633TrV}B)?3L9JIji5#J@d)) zW6sp}XpOC+=-z)r3ktg)2=*%@eyZLka+bg-ybU2Pj{v;}#pIjj{f^%9Rk(YyM>5^3 zqpKMKOgV;dYSQe^vvdYFQt}e$LrFIhe6t@s_1z8M`CZHTiF%6!>q%x61FS$l818d7 z9gWhibdK0(w?QXWd(OP_@BeU8`P)7ZIOQCJ_P~pPiq2m5rEuTBsM^y8CqS#0CSbjE zo8X>=U*ZD+;8r^%16|9IUjyX8OT~CcBL^e3hhUd)4F@FO3gM!qHYk?Kzho!S;SvzN z-b54uTNslx+G-}V$GgA)$|f+J^#JzR$M=B*NBFQn1W5a2Xh#>)rnn2p!S3yFB5*K8 z_%Q$0?&Te)hw)=oPq`AE-vw=FZfV~`kg3Bqa(mL;kIy}%R`!^T(mY$?%DdjfOJ%(XotnR{`e+XX(^DlZ} zw4R9g8Dg?dcmhJaUVwL73+Z=;jE-Lnd5$O|3^6Qh}K`?IvDL1X~v>1rsr(1FY z+YzxihOXqM&q$qJ1#k+8Zb8IF1^9G{QvrlGW{FSS^zl&MrW?Ae7BICHW)3RJut&S|_N)V7IY(1aQYY$OTXobZ7eFlCrISvQwS zZ1^8Rgk&3dVXt_1XINek2)}By_-QbkcFK|9h9juQs3#}He?8R(*!k~lQMmCXR`@Jt@{B#RfH8JUkNKIU#MiKsACgrJT}yDJ!aHB zQ_U4p^B`dZTfx9aI4|{>HT ze?O;%dM*D$xMGP!VeLYDgHLDnf|X?*D`*feMovYjNHIM{*JDzb;F4cDS?|@XUa<}< z{yMifCQd>Vi-jw=*vNnpq5aT9{F2zP(ZDd$nYH~wvww~y<&Cbs$4?+hxp+(7&_(Z2 z^KT1MQ*{Ms$$K3_ELOU8H;h^>l=G$5VWY0`rNKLq2f_1?G@10toAphZbfqUv@-L0L zNiF&lrOHyx{XM?#8JG$cq2H^ga?D1?V1v$7gQv}pszuC4n=Kw+S};C9$0nJL0OryH zU2_{F&N`z*4}&rR(_x|fF~g^zdh^0drifJc1vyNmc-EJs*8Rq`#3t5n=QSLOZ43=; zoouT=V>_72gw-P~+l>9x#x$bvv7M*& zD^Fp{-`e12Q+ksZ)d?>ioiKsZ-2DvMw=eC}TMQ%@o;lYzyo-2R*s@)+;K-@~iMq5A zB4fifk$>^~$;ULu;Z$xiG^jEZ1k*~O(u9xA=Quq_VYqq9{{&i zo(v}lvSdvf#DHxJqV?N^Ol^=R0R%hN3V;>-LY^?JfLM)HD=*DWcgjuv>Iz9F9J0X1 zRnU=!uPW>LvXa>P@u|;35eor$)M@S244i?6BUs<1;)Ty1sSaH=NRxedvFZ^h*(>)^i8t7c#86J zvV6gnpio@)mAj$$>vuM?w~F-l%yJkda`;ey$X1?eTV6?wQR6xUn<=z*NxVrckzE+{ zY@NP^ff1#^NR<(M+3>lGh8wcfPy44ZtNJFZUOcjgJ*%ba|S7MIxBNX zqjRRkYbLyNkKr%$ZPcQ+)sk%0v$oZXN*KyZ9xN?#$}k4}`pD1)^^Uxu?BC5uZevJW zPEdrm(PTAk_u%maW^=X|@vdZLS`*Rv6pOe2!vM%jlqj#XrtI?*!KldW4Cz=6*h&o^ z*g>ZXNt4#`e}cSZS&dX!&kEe#;I}hmZHe^aNsVKfpT=_Gn$VvG5CyA>%=U`h+loSo z52X^&TaDbrvv%!fwHSgu zM1{ANo!3NnQvhhzW6135*tIUbm^5Tn7V{H(>3j|Ebm*ZqK^Q}r>_{#9&C@MWUxOlyTJ{*`?t$_-l?=^4&2#I0+LTfd>g%2Zkc>F{jbA$v+JI%*6B+&uO@g0 zAI5H6H|w_4RTAa-&$TdnHq)Ne{_t$lmTXIXECKQ`4yDF&&Cbku6R7yOeLh90(sxNM z{WjuH+h6YX#@LU_iyv7(H8F}cc2c)TO47c4+|f+lmYLm=xzINI_}$`aE9YtlpKse$ zcDH6y*Z!ZsJ=tSM;veB(+dWpFg^;(hJ>Vb+b3e5TU#+|0ROyrUl_ zeb+B9HK6P_px!Z{eK(*lHE8TN_^4yh@@~*tYRJxS$l>cCeV_BYPt73Tmig4-&yTyj zjb6|NVMcb0#NLf0N{y!ajb?U?=H87KN{yBJja77vRo{)(OMPzk`yB1}sS(`0f7#RT z+t8oWcZ%COKL9+pg1)@#Z!Q|&xEuT~HL)u-_^V^$G-u#gYVw9=;HqO%-4FU4@DyYF zG@SEgW1){bCG``hLR;T7b@3;9%Nh30-pSBTW$J0-wP8!@F4~#T;S)3UdgzSt40GY?l4&7a`h__{X!c7<1K_GrDWmuF{LO;q!!Fr?9`y+O2jw{K;msBA%MGK}G#t zqGns>3tP@!Te>O3Nbtre?_8<=yHYQ`+U&pDCcXMf4&hX=I_Up()ch!u0nz~+g?RU!@z-XaL_q~bmA`F*6w2(n!d#`aocg+3l;!nUC>f0G9 z)1_%Q!v}!uAGl&89bR;FEOVT1x!l~p+~0rG2D#0qUlCEdEz7^5tRY+o#C0mb-;^J~ z0H~0R@E``#)*1$^K)BO7j*~SFl!fsnhgY?zi16x|z;gjylx zf-nfVY~bx_kl(VR?L)gJ!%i(bhqjaW+L9WRb}4*J9bn>Ji6lC zi1RKEqnKfTjvm!!$!_tZbpL6TO;r0F#!zlVPUo{jNu;^JW8U%~3_$(nU<|cn0Iqn$ z_Gk+CzPj6A7Z>IEy<;7%yax#V$ z)uq~e)uSnhVv?RD7Ph>@XG^!YeUpW%=`y)KA^;ESIg7>FWO(0?@q9&kPFld@`(h}h z&Hx`{A;ji)r3QYrg9D6;nvcD{2ie_rVVg_id8nK~dDM@$`J&jC6 zs)1 zSu!KBmlb92+h11J4rNVMHNS7gl377T6vFsc_&;iLF|wXcB1p&__i8^h>~U2!%)E3| z)9`AXlv$Ze&}&)s{KH$Z!K8WAfL%(&kYB;?`%Bj0hRUF>f5EY;bu{fWPdBza)ePB9 zNFt)Q2Z#FQ5S8;6*I~MMxNgt95`u?`eCiri70mR`<7L{{lQh+s?|MRcXZ3&{jyjem z$H8u}l}jjdx}V$FYW;!W7r|L4p^4Z#MFHT!L2_CLw(I_3h+=k3!`H((5G_X@S+4aY?j5sZUWXvG^Hb>2=0LNvn zpE@UkFdUZ<-&aWyo@Emvyjd7$4(&CJzQ#P_XAL&3E2dlM33^X9g$?sT4>|83$X{FI ztKlJuf0bkM1z5>J8X%m274)InS+Kv7HVbh9COt3(VdY39KrQv{Dp<$fo7smmo-!gr z)smR#^o2)20KBd|2UQ5H6HomiASJdLOoXDx_NSQubl8v#j1C*RSW*xx4B_O~hszo< zlUWxivEFYXBmp^poic=%769m_6w!HSs3cYq0!Z9#1~_N&n-Ck8*pP&GZfg0)A%U27 zYQr27Z^C^~7_lo{Fqx!FqK!>Jz)~+)00?&R z@kkv23-zBlNOTNR>9_#fvRtb2X3FPfayBt9c797kG*^T?Ey(GY&p5mK zbqUm?6^x;zT%x^^N#>BGMEHG2PgqNz%AKdk@WC}Ex#-}(roG#@5gf?ViVHnVLqDn> zaUw=h-#5AyS^ILF1NCyc13QTAo^UY=kc2{Oq5>Vdvkdlz{S{bnIV*CP5|%9ic6o3Y2VW8gn%2Xu5$UX z_8kho4#34&WRT&00wlp~VJsxm>nZ3{FB9#JUMjK2&hHPb<8>_p5tsZ_?|VF|v`!t+ zevE^H4Pi8>(rb|Cb$v7+6lZtrnqC1b61Rh}0FTuR4u5^}UXL(t+{Yecw?ILGCx+8c zikam-GA!g*nAjh-kO4OImC@6fA3ToUpDmt5!9#$b{K4Y2U+qJGxBpp72zhJxo&l3h zC{^pel#hvyNHq@I8ee<4HimkWIN(yV;sM-eD&#>^v|SIL+0=4{9t@=;{ywVWpIL3O zuSS^Q3aCSCUq?oeatKH+iuJ|I_{0OfN0V8E%~U?~RcHo4fIay2i2{aFD2OXnIK<=| zreT?vD)~!)ejUbT#YZEm%zg>s-gD%J62`meX=fPs9W$W`GM(wGei-W~Mj;r83Wb#Cpa$3KnG^xGtnb`@!S< z4+DTcTlV`YT-!G89EWBA{C-I}iw*eTUlhRocPhU@?@&bGU}YlzT`lMKS(M{NnWq1q zQSEIAZVwjBq!^!ZI$PSWKHOsg^bY}Ht}1x6L+2_ZdOb{w)F*HN7~wMsst=xsM>s7h zQis;He@Ee8S4g4>h;`6E1cc}2GZJ|;0r5H{)L#sY<;TCN#={@wi109TLSb%%19%SC zHgMA&3@)M~O!ql!OphJ&^```XmR9}1=j*NtM)g8^N&<{|t<&598IDr|%O2xy2Ln-1 z_`5f*gg;Ni_Ep$lE^EHKo#PY#xE<*4y0XQHNj&=kbi zxzGPbK_s9C%u$`4sMhp@9pjVA2bM5ozOoTL}exFeK@Ly7F9)z zs(}BCf`Fh(|D{2c0JmjaJyo%24Whcb`hV9TP^l@X1f%JcBs2?=mzRg8AhNQu&=f>k zS{j;yNJvQdUmOUOpD)T=9re-yWvhrXF+mv#qSVz<%G^;wLCAmc4@K^;|AT+<^78r* z{=wbd-PP6g|DJy^GBPqSFwoc6|KIrs6&02LMSws_a-xJdQCw6g7IG9lIf@$HorORV z;Gp1GC`=d%20=mo5g_i!33a6;(d)lNAb5Fsd3boZxw-!xfna84W@2JuWMpJuVE8{G z5X8j9|D^*#0fFG);9z58V_~6xSeTfY7#J8Z7z_%9LLd+@7z_e|PypbM{vQD7-2ec> zqEV|W=ncjq#>qL=)r<*8Fl*$f)fWv$lR82_1lAW1$J2?pLDd^r)DqbYKjcKXm1?H) zJ{`NGaDP7@ZgxMeH}YR=5PHQLxi9&Lx~Yt^Ma5{ajs4ln-RzAzAjPKTGvvrjI>nt57n4L?3-2+?2o-UvLM%y07~ zla_F@n{sD%{Fer?SZD3t5+mXKYPCf7*TSo;v%}^O&*1br9j&KZsxOF*_zT<4e@zu@ z=IeCcLh)_I%)U?fe+tU)J`O|GO6J`ijsEDwP<=fmhf7Ge`8i*=yX)_t>+}8Zlil4Y z6oA38{vR3y7F+px(5<{DsXU~EVF0Z`*l&bVJV$E~#7wR*BAPIcq6j|RDMKIk!kx4z z?mTwNXoKouI(d`7&;C0NqGCHqOLTWTSr5Fs{uHdu7S@A2+@AvMnd?W@}xt}3^2@=80^1KHNV_o^@ zTb$nA)Dk0o^NOrE>pd$Ace3qXS-Lk|d*vl*5~*&)So(oQF`LGL2;viz?XFRyig9Ii zR@lPo6Ss*Qhw}Fr+y`|7Od(uVRiZwoAL>=IDr-uuJ@*Y~*HUWTGe4%FS@Y^W2Slom7TuzJGN_? zetI^VW886IoO3!Mb%i@W^xESK@hAZQnmmSCAA=Yd>CdT{)m4?Gm>AhTIG;Cr@t1hY zJ~wEK{tkSiDrsjW6wl2EY~o24%5llFZ;folkYlmhOh}eG*$B^g>Y)tdC0gyRu;bnk zmt4qeW!t$&>p{}Q4B{cmm#!v`uWo*rJJZO4bKV}^{3-~a@CL9WdvG})v;rzi@7CR; zNi9l}HM!OP1vjKNd?Ax!u!$$YShLn;kh9&K_y+4vm}C^;kRQRIu2az5BOrOxDxXN7 z>aV}*-hFMpb}roJn)>YZ{SCQu4nTA8@%aAF$?#+V7zZ1#r|WOfc(7c_2*ioE80f*h zux1NfS0Ki)4&%U>!QBS+;GhcR=XX-tIljM zIUmP#N#>SyAmExfTM8ox+mQoKS_=S__n>&XK4$tV07-y?jKoRfZWH4h0S~@TvTPhZrVUmk>rY%m~QgJgUM?(mdZT zWr?J=Av@fz$$X9R}dcE+J}4KLLdNG5q<~ya6Ii$z5Q6pCa8f_fzu!+B8p;q2P-x!IdK|$ zo%2G3N@Gj7<2B4Fwjswjw@LH6M}-mE z7xcJei$0WEO<9&oFHj>^RCHfaHpCSOJqs=DbG27WADf%gA^{|u;nO29t$|AtuCxnv zlV+|)09s5RyR>dxJy<~)^r6CD+p&JFODETXEie)##(sI0)At{rk&6aa1x!oj+k=jR-qS;i8YF!qsr;cYv{Yd08+2+*KjpgW zHAC0Q_?T5RBi}i0e#00nz#`>ys%L#hB}wV7fee>f`A?I<8-pF633P+CK`&#E%n(OH z(I&$ed!5Ft#VVaC}v%r&#&rdMU^GBVY zOH*4+(tZ-kJ@h*Xqt2NOFlj1R*LGFc?bxKyy%-dlIF)nun}!d`4>SKgO? zS9dnE?BE3}oA|7Cb?UD_e|*iQ?NaESwXRBW@+X$hB9QXSb*+x84(V*6jz^U{?SZYT zj8sLi+&y~-ocI!CO?c+zQ4H#bODJf$#02p7Hif^%S$JCPQS-RVu=Hd| zdLj^A{q>gi%qx`sRoCz5uyt^`Zs(rqg?Deg81=w3NTg7yrMwJg#Iw6jWA~p^_WEh z{}Vxddy^^CP#=2%Q!!HVRDG%8P~b$nu7rY7#DLWU!E8lvRtIuGiM=CF36d!dNhwE+ znSwoAZ4ENQeU~EFX2J{SEnP~(;$e?cIf8IpfxfBN9$UL#=0dN$UEh<_$ zsz!~Z)ZREL!gw+WlS$R+v2xxPF>-kmGF2>r;qnKwYO&J2A<6s}nb$U> ztufyyc*Z%%CppNbDTL;igc-dMY)ITUJN$1s9yeUao<-1X?2v8kkp7?$DKqnvBDCn9 zG99{(BP5GIH%sW(k9Ty9f0P&>*BGrZ9o>a4X|9V(vz+fm8a5% z0!N*+794pWlKA^!&}{^wPYri)CoU@@oK8F$^TsGViGv9h8SQ?`!BCzwRg{!mptVAg zAb=e&?443uNCQ~0nh~+-WU``h1YPme2>~`cLDSuc5OsUR!zqFhbcDz#1rnKJ+eW29 z$;h0P_L7o`4$S0ulg7d%XtbT29FpV^$Qf6l4qzvLZH=_MNl!0K0r%1vJ<6C3q+PMj zFvR9GQ%^tGOdzOW!{^7fvP&FiPZLl{K(=LiGiI2N#>Y{n{oz3H-XuX`nT*ir-|sVX zmb2b$WX@1z6-7opR!4L&q{KU<=apvhjAYf^WZQ$Xe{y7(Rb;znqykf^Pama&A0hY) zaQ5^F=3HPwgNZ%fxew2cny|Bq#dGx1(@`Ti87OfC*E-(&1egQ@1F7o05Se>)BeXJ_ zyUK~yAo5A%GGnbW^~CbP_1O2UDu*|D;C7O}wxsi$OsuGaJ~7<);@KSr&I>2l)h_r` z3|Q)<1(2*l75xG{hn#O)h4dOZe&UEuWcDVfz5)Y1(Z5uMEGt-$9)U`V2gQd%Q7YtV zX2G}RT#WWy#r4$qt7M{3<}@^{kl+a>#OYHl?(#0y*?VNAfEg?|~B&2sCBNcp% zPzgn+^+nKAyi$Hd2tWS(a*1x%dzrN2`q5%(^HK~S(7+UdTS5NnNa=?*927Q?k1RQe zeE*WF9M)U-*gW6Gy!>nw^KVaqGioLCG7NT8hb5hWd4>$r;wsO;DP{60Ggv8q#f4y% zz&wYFFMsR*IxFLPt4BpA!4#xDQ-vN*)2sPVSSD9bBK0vFG- z%8L8LDhaakV{QMw5r7k1VUISUF!N;lk_OiVGQKd3a=N4E~ zRakT9lY4KTbL^A3L6tqQ2dA*AJ4vbqK2*a$*No%ToKn@1J z&c%}~0{hm|W!r2;f%!ghj-uKd0#_Q8DC_yDt1{1k?y1+Fx3wctWRWKXbj9F8B;F-} zU&sK41j5>;@DHruM*IkyDcoZuevKUK69Dh30PkH7F-~-2PDNwR%Ld6m_3>?1nmsM# z(bYPEur&rex@2gL9)=Wvu{?zXt_ST|;m9GO)q41rg^&kh5R*Fi6azwnfdEZ~hoZTF zP=uXh3o^3h#Jo|UvgK!QNEiQyg%9Ld+$7Wqcve=jP*{VP-@52|n02sof7A-Z$p?TBk_hztD7Y82YlTgq z2P&|_tFDAxp%7R&4B%=PIJmGKxsH!9ZFg!-N=4mKE#5(XQ+Mv$v7=DcXI1ruTVSG+ z#7hpZUa%9W1AkAzh9p8)>InY0;1RJPEUoZwPYAvs1(yr3AOaXDM3Q?7^D(?To3mSE zsBvPi5qSz6kYWG!t>cI$5wOBHbm?+tLC~$^HX+DJ*Kx~{ut!rk^L1Pg67X^W$xlc) zn?Wx*daARxi*CJ(?yiL4z=~6=N%}K6Bl%!YeV^*TYz2#d*$Ur#L0^#Ybt0^v1v~@{ z1YQ7;ae@o6CZ!AO+RH}ttPTj>3}CBtGj?=)5T+!rD>GS;m;NE9Nq~msKqnJ$)X^sa zbW^yWtUyqGtZfECI6&YH0C@>-jAsx)5B6Nor!LK5F2~`%)p{1(hCI!VWP$J+(vjN8 zK}|;CSSdWI1c?VHwDML2MGR221e`AiaOCSN<`w*>wqF~1|k_&kNbp8%(0LwEsrCocH){}=+zS9N&L_P@~L zj;nHxM?7p_=on6t2S~7sXhX6(SGw^ozx?(aejhVtST)65Mc!wI>kdpMa!z9ljAZH$ zWAesde^n>(R|n(K(XVBsxMn9KW~7(X1v952!`)DO`tn z)RyWZucB6ST7plpvMvB=yeDl`=pyx5Y`oc;gPAfv@?`aJ1ZAXZXO{YSgC_4F-}u~I z44Fe+IU)Z%`=j|z?|Izp`JvT0i?x}z^0oKu3lRM%vRF!rR||Qqv%^=ja-CBig{C7` z5XYry2HquO(C74*i#3spw`Gg-Rg=E;HeqGMd&*Pf=93YfF;TpvF0{)@(&NZL+nVO( zK<$NPpJktNtjQDnU+7>IKjIUT8PxQir*l&8%hIJIMJ&IOvdBt{HmSQmrN^t4F=O~U zB-Drj{=ES7>yPJyo~%si$d}dgxs~LYC&t!;%hUdYDdQjdI>UKTCj=Hif7Z%sbMBhs zXY!}7aM=)x%Cw1h4)bf(;nF7r(L9|y31}h(JAr34H+M3wbKcE0o8!y35Z)OtpT^Ty zNDKzJFBg_g0n~>9U%aUcME;!Zg&XVJ4U+T?DxH@!-!}4pZ!mP(D@}Q61NKZZ=yc#F zSAac7_&W9j|KfE#&W{rNZN05*&JtZ)Qs1^@?ziOVwiRl&_x4X@Uh>fWq+0x8+hxxx*Wj@3`aIxgn&?m4 z`^|ve?dgX=AwRy~Tg2lN0zQjr`@@DN%WqDHWNq3;M%v$!QFvQ#Cftgq@GY%AqZ65_ zE-(>2jMX}L?aObzx5paA6COCpVJ+XLuQXYD=TXU*P z2u>Nrl36<}J3GXtJ|g?>MiCze&tD`wCTWw##Tz*cM$vtY3OLKnIOA+Pi(Wg^ng%^3 z-D8wJU$HzFtqm7@mp(^#p&+~O9=N|>eKB}HM*Q@Q^y$U5=f$gx3l!RmlO{(b9L#rJ z+-Y8zpn}Y5rLSZbXlj?sZ{|l_ASDlef04PYB>ZZpYyIL~j>P0|bG~!8K;Xjsk+tsr ziO%o0^oI>yy8{!u$RjdMt4)jtS9|hj9?oasy3f4ni+l;znDR-$h?K4#V}F9v(!7~; z=ZnbiOEKTCD^Vn3Q^!T!zq!<|vaGMlYArG+qaAeDN0x8334u`(+)uPuA>a3#-c6^y z`*WQ72PA!aJ#l%@OD4)+=EuL(kWbS6in68lt_d}GN9_N17XMzFajvgNy}tW~N9(3J z|L$x2pNe;f`p0u;e59-=r*wyRFW=2RTfTp=^OwHq4*&w>f`#y)bV~oJK}fLJpKPEt z2zHgGjCz~mfc^(&1LgYLYGI7(c_kEEPjORtEt4)zCi^wBME+faSTV4REqI_!#_CP7 zt5&KhBnr#2Hj`D=g-dArknSs{@_dwt6+hoMYp@&7Q_ePdHTF(v@j=L~XpKd+Gx5aX za@o^*0u$C1<%las(;o4DGL;;&Q?v%*if_q7QN2CtL1;J>$w*-woAKF4MPo@|tiM=0 zUnST4a=j&ymmEV|^fzj8neUQHX!=HEeMMHew#JO=+GTSvmR=U?k*jmrm+a$~{T!B% zr+?`pQ=SNan)p6KigQKxyrp&awdC0KXy%+JW0Qw%157up`yM*>$tyu07De zK{Ba;_cTO6WnK(d04+JrVXKBA?D@G#7iaX#Q}5jMRhZ+I+<2+HnWw85TzzKVa}a72 z=RbRWGOfZIeo#BY(hU{TDoCR_9R_E=A<|x+bE-hnHCn`t7ntErY6=_=2u&uBywUwE zHXfrlk^G_Ktb`NgAYsHJ(b;IIt4beA!YC6+LQ<*pw7scR5xe{WQHtQ-CWCyk=52aI zR2xRC3bS3aF+aOB@f3kGiARMZ_TbEvc_O%($)M7eaf#F@b=3G-JSp*loSk%~sb!`% z@k*N5;qa_psU`7hky`9ft8pUi;n%a2+)G{a=F(S-Q6Gfa7GM0;iZ=2d+E7WQj3Cvt z@W1*I|MmGi-q<5COeIqm%#ivC4&*ZT(#LlpCk!^&L`3~@oC8)rsqszzq&$a^| zyiP%re^=fUMC_IkD$RxwxulRCmPAuEwZdr0*7H8O4(IOqRF(bhTRqAdqI>VuXt|(s zBHdZ#`l_glWt3F{3^#bw7lQI=&RlmmTxrAdWLcPAy*KNnc%&ZI<*?|$8r zcw)^*QpJExU!us^i|{oowkG=ZTycp|AVSBFi9qBG6jIIaqW3iyQTVfqY*a7u=@%;E z;fHc{ZFOv1)EJ0jHI+t^smD*C&uC=Xh9C}!ZU!`uv|n4r1Pla*HuY~Ad^MxNADd1{ zDB8NM!y1wEiDd&ND9Hv`htM`m`>6QQ6A`qjyRaI(i+xiT?I_*e|MpNeZq54wd!J6UsO8c7PbfFQ%rA2}wY z9M(jr*(__p_k5qrzX*12W3)yq654ue{$w;{4rb9|tZmc5wG(1*cEXa{QrC&H#Y{@F zRfG;XOq_JWa{Kk!C1D>Zl%=+4e<5KAd_jw%^gtj|9_xq^QW}~^L1RZ_19j5 zl21;3$UC-`oqa|fpIo*qb}rf-`)0dziB*9h$Ck%$Pd`1q97^v-HNVD_@gX+y0|RBo z5e!pko}r|lh@c$csOmLWvf4tdov3gcF(9CDDB@_Rnk`V$W{^UT%m5}wcNCcL!bO3x zH0cq;1phOt#igN#L#}Zi9na{lmWE|9+!8{iY?;WHM^sf%XL0*=nooNIvDL%eQc9)l z&{=f^qz0R=Tp$oq{F{OMT7?Zi3Hs{b8U11b$nbDFhW9|296TDvgfAHO&WM3=JT^l^ zNy|oN)sE!bNmSIMgH1_E^7a{+OHuRwQ{{(Q?J=HB#f-GOO1fDc_EpYMj#rkN&OY6_ zzc0LCJS*7)Jv4^vb?KmW(2FSrCQ=s+uDXO!6Qll#lIvjts7>fQ4&e#+8g~UNzYo$^ z%S$h?mBrq;AhwuH8OExsl)KTlC7u_I57!^FtS1Bu1bA?xl(1><3klp%!SuIi@LsG3 z*TUryLm+=R2zmy1uY-WJkzskR6M`;J3V{B3jXUbn&nc+P4k)AuCqQg2Nnk;-l4Dz% z89844iQERzDP5X5B=U8zNoq+8Hf9q48H*G%>ACt?C28}wxm zfYc2S(9u);*zqdD8ZL8@6;VWMiIoOFz(wl&ZNW{gFofP~xMCRmF(78SJQZtBxTYf*FrYX@w);y$hGaJGV>O@?(hgwq}nyEhE;7%ZK-K71&KNtpU znDupfb|Qau_}%V!GSbH{Gxgk40e=b=9iV2jFV}l%Z9GMhRgm*edoIm z8Q){|!-9G7VKeuDa6o$9x0*5uLJWt|-4L4On^~UI#%?*PY^yrZLu4>^-AnAA4laV^auOm2_;C z844-Kipolqg!6S>*Y`g-Kb+e+ukn06?lo$plmeez;b!W|g4h9}CIv*kASFLPWDCzM zE=%Gzuw6Dt6M|(gCf61QDPR)lbkVf^bx!Y5Ec`<(CwLO*5SylYascpUGYJv_7AljY z$Urkq4)BN%iCeIxOoE(3y$A!I5vqx<8yQ?5vX&l+ z;jMyT>l_0BFcz$UXiR^hRwJU7+Nmx#GNkV|nuHt?SJGm5qv@*-FW?~+9|S4vikg*= zN*HP_+#hv1DKIGSQ{2)r@QQcs(*RI_EI~;rV+4AkHAXw;<%6|y<9AKe^y7_lcuWpV zfE1P#-c&bIq>XypYou6&kuIysaqRBi6EN_k~7>*`Jj->rIhbv)79!w-_M%;cWHIbl0eV%O1|s?`Bp2=Y-2>LnSVy9;yLr2vHEauBX1j_ZA+^|a5Q$E;a z^#D150D7RC-m>s+dDFmrZ!}y~$1V@cLtrmtfHQcG+~U_y@9*!ifQKVV#7(f|O^I(O z-@Qv5oaCsPx=;;%j=8MW1rQjb$<}bg$=h}F$)vuw@#S|`wosq)N7pIU=%euTZ$=#~ z3>NxT7Y(s7*5x;@tI6$#+x$vj`}uZSl;e2@1r@OWF^oobP0tD&B@t5g`CmmHO>aSG za{0B#>-+z-8fnwrPv!mMI=C`JaV+XB zpT&?A<9yfAjK4BgSaXmlA}~XtNoH&&+Ndh>aBpm`4bQY83?I^@s=f_ix6VE`1Pv)W$#%iC*rb`oEpG~P; z%t>DkOUBLVXI5E7B*o;A+>J@H-X+ETdqLi6M60sU8(=2Wl>Ti&$ozB;8A3*jG|S7I zt;bndX0n@0k;Gb){3lCdW|HWN%w7+90#t64XLK9gMZE)u9 zG4=Y^<698(fXllPDioJLV2%NpoSX>|$z2K(!6IuI4+@JkNeQvEGJ1@8QU}r?JTdLC zT-RK1lBJk_OGV7UW7fn>JS`|nHQ|va;6#)7NaRwyN}U}G6kq`b!&9P!KYGP1*^MrC z1el$0V4qmOt;?|bP5H5CHpv79H$`iXbqN#U!4 z#VWib^RY>}>?>M|k6KF7Z%TA%g2k6FSTNddl%z!8Pg=?V<+v}WyH7NRl0_9jsTtw% z5rB%!WLc7RPhG00b&^*EskupCj)a|5DX9h)6h0gOK@`?7dN*lnp$rbBQf1t78j+K_ zQ@;2q-C{vZ;M0&L=k05epwB=HM>3wds`OolO^bqCiL|7`Rw*a`G|_I_-XUq$I?)89 zWSvOVYDx&+lzvjvl83z`<&;rQ9X0jrz{QS5VIr*@gS7%#eB zI8MZaSTN$aWb>SLR%+v4+vDR&t51PD)7IE`RFFBOV`Su zEBdq0a8FVNchd0o(w@xClgzbL+($@*H8C=?C^zuRTuwaeeBx-MpfxIj#r;}R&!=)+dj`9S!myG~Z(u2o{KJn|f_(#5o39(RD*FH;D4E^{ zi^xGS7f1Cn|wP#hu*cO-uUunYX zhDu1Cuo?*qI4oS-`;6535a6Z=?Z4$_l#{YugQbOG%so?r@yVvR59;Z~8WgfxkZ!@l z8<+7xKy(oB&O;Uc6cM4f_xM<3=IO8Fpo{OvQcv56rqN`+?NATWjHKzGx4$K;ps*^t z$!UlnWnqW_4&og_N(kM?Kk5*LoS>Lb&_XBbRUHPqu;2UAN;wJK4G@i#6WyW{y{8>w z^j3gEq6ZNpFl&*K|`S6)Dm&}4ptl>3A*N-CcL7E#bPEThn6H_#aODQ zc+s;Ijiz|kC5+KTJR1PJHLP1pHp)X>v!m|6L|Al`D4bOK9^XN@d zS;82PpRukemnbHYw0iOY^x)!?c4}$WgLI^?$o}_5 zW|z&e%hj3ED3f4rz=qSwZt-bMd+&KrZ*=;Z?}xRkh}DbTqS(qe$#+oLJNV=eY_JWV zi<0c<@sDs-1@6{f?6=9)Utw2YAD$V&-~bp#iSRtS)*#54Z~9e@Ds|RAS5|(waR{c*j=C&_9-~PSbnbB>X!e(gQqBrS{Pa26Cmr16v2?GQ>Lwm@6d+sY3Z&cc!f4q+~u}>Hi1qzsl8_d zJnrL7mvAJ>3_N7<)KVl5>gDl4RWosevRFn_v{~ChFlyGA;t#nV0;%&4I2WspB?>Ie z3{*qK^C#4B08X7KytDu@66R$|)RNq9ccoy2pB@?AhAjtXsw`xz&jv}ZL<&_#n#s)E zxe0F9h($N|@MR4!dNpM+oStoJ8{LL{9o1s9P{%0S6JB{IfUv{$VM*7s zrrsgSG8%?@KO^nwlMm+bOT^7}StPM9^zpi{%#$u-I?@Z_%Yids!2YK(R{z4a3RPZr ztkVXx^QNPxGI;l5$Jri84K<3G-C;WLsUBBMQjWHLu3+i&vyN0Tz_*8807uH9hRc-wo$d`nUg*hV}dV#{-4L z1G76(puG{9LE5PAp%$-o0qcUlzP^6kZ$>$<7a{icJ8S@MSnY&o@ZpgLH#q>nisLBo zWc-M)1a^Q6NuvzlIO!I~Re9mpF@!t!4K=V|t;e4KnQKp$(=@oS9lxz9-6((dV_fR@ zI4wmh2twq;rQ~3lKrUP1EX^r22e)W|U8gh-T`<$5qYMk^JIK^h5(%{#Jct1bP+)Yn z6LUtj`uNC1kC^e$p^P|bH*5KRKCWL&xg1%^sa!udxhYPEkzty;n&ey5k#LDM)>*#g zvr4pF993i{ACK&>4Vef+{2fOr_-{lKA}1#;tRLW6pI29D%NzE03zH=Y3hItM9uTieli^2>?>$9#G_}a5U5(r8a9vK_!E#-+AtN zPRG$PgzUQQD6yLxI;Bm4{wC~b7t(ct1TCu189r+11sO7vb>X-!n+B=L%QN!Q>jW|j zHU3q<&Xxj6r~RE!U%ornE`3vzyTmB8?NP-{2t(bq29d7mHCOUts!pXNt=ocpE)xe( z`!7*x9qL(}u`u$pw_-7HHzc$g-sE^Gnx05r+1w-0K**ycg4!%I>b;;KGfV<4*m^N< z>eS7R@tvgzxYm8DNn2Th#Tp`Jy@M@i=;?9?9xQZZGk~bQFc|y87ccBSFz`Rv_)!Ix zEvcmLc~*I8;G8bH%%4@*1?HLAQ=$WZT9@oJtKaiDR?2mA?y+&W6!!}*E1EUy?ixDT z_XkO_AY&4NZ;?X>j?vawOXNc{*qtW-qYsCY1qCORv1OrIa@=rKDVqLaq1MYe z8EqkT>n*W&f?Ds%tTSI?G!tXquDuZ~)`&%pVbqAcfUxrSqPC<~C1xLSxJLxPAdswf zF_(RBp?8$)v()89w95jeGs|Vp2nbIBlXF7~DSZk2{`RGD8B_YG9Ca$U@DfdrYDu|* zoNtQOuZ`G~4KR;%oq0x!n-{0z<8SUaJId|1vx<>iMC^EmcmLNQM^-)efvT+n8w;`S~DCp%u8ipm#^QeJwiK^kP5nb)Vi z=hh#-{#KtYl8Fe9e*dzt$1WLg(Sh^pApq94;a2Z3 z5(&ujwLza|1_XlfnZEvN$my95T=4yF#Mq04DXHWb`7* z)u*!Ym`}8s5iiBAuNES-kCN_%Os8)$|`&{w-G<* z@#XSa+?{8Ojzqmm@Nv?_U)bSP2|129BRPTmKDP!FMA|ZpN}H5iS&lrfXD?iK@^2*^ zbUO`MLe2wn=z3_VzOpeDjvyE`wiUItN{}f9&g{0x88WB0uLx>6XqJH)mRNgo(xe}k zOSn6l0Z?0pGhD@}lWqWqf6Et5O6P|R>yH+J^Y*u#FO0e9O4*a4)Pid+{Q1h&b`M!= zO8&0-eXFcca7mZN+`brA#%%DnX$u%t2y1JZvLu{Yj`*{@Cv$Wbe@vLpE#(kg<;G=G zU#ABG;>0tC)n?<+lz?E4h6(}vR(eE?mj&TCieS-LyRXZexm4S~zlDD5H zuASC39g7xRK;LA8@^%fg8WPds0T33^5t+2llGB=S{rJ>oXN^QFl^9-<~(}L)-*xD&5UX1+JSm#_AjAWKbT% zgxh@@x3GhQ)oyh*DA9vq^b5BTnL4Hm4G}U;v37O!@@yHBAy#ogSGfjPRY5oH1~(%? z_qz@5j)MRF*YKYo@hj^j2#W@L+-<0BALK}ExL+yg)zIM8Cg|NG=siHN1EW|o;%F{V zf&>U%28ZKx3D^m8zSVH=1>A|e0nPB=*Dgb&1AaS650l3N!KxlM$pRsy^-#Rg4MV(@ zl8136W}ko$`L8h~Rw&r3F``l+ve3i)g}YXZ26Femd!j3V4CLHeFMwRg@Bm}@zK*c8 zsg=bb#+A!6Jtif^`GY6X?ys?4p4)nT5uz&tDxL@?45|PgdM<*N8me_3 z00w5VC4TA=|Fu?ECJwV*B`2u4;-;Hgx*PwsQpQGIT^OXit8p7kPixzh2?C$*?Id4~ zlUkq|FNniD7K4-kz}v3DDhv{z-Nf=bDGcrE*yDeo)z#W|(K3tsPHx(A)rc#NgwDwX z-Vw+Np3xJmWFq{q*v0P@IG6{p$djHpCa(U*>Bi{6VP*ZhmF zC?a*fjAIhvf=cGZN55yM#2If-iu}9y#v@vzL#jp3lEffblLZA<;=bj_e(REbjNTfm zIM|I|vF5>L3tB&B$@9!871ezJNO5Qhht)6&df_C!ipLrR1JG2$ae~(cf6edRRN!-` zsuoAl)`qIq*pcqD_@Z@IlSF(Dw(e=+)wu&m$1wm@hv-8@t(Kd+BxhJD>S5-$*8>_@6H?b-ujH0eY}awUMGlm@wU8U^VO4T8Rp{U z%n+T^mnhiCdEExbUop_MK+gMf=T#+UviSAv4Q}9kfGKpZE@5QMcj2zXWY5IM_yy*= znTLg~_ji4|d|S0Yuy)CWgc|4kWcgzULPtz8xCm*z>LCI*`BVbr`jO2)0zj(PXkc{o&|$ z8U!WjuY_ccRNsti@cMRbRJn@#g{(?c)Xx}2K3#6}=Sds!@!ZgbV`_Cl(7GE<)O8<* zs&9NR0)>Fj6(}yvc#p~JE_p`~b)I_Ga21{nLGpk-(kJLKW{L>NdCmm**3l2@_T!sS z(9uv*f#$vpi8pXWlHi}EcgUM};2^kf9EUy+P={|iLsFg&k&`065p+;Qyqz@K*}7fg z#Sw-1;kQ|-7aJe0=eEu#x2V&lD4#vmHfddRb}>+4nsSh4dM7dI7vT37f4fBtW+6?J z9Y9J9&}#DCOVt!2=c4<^$3n!N=Kb`rL7!{Zu|56CS&P&O5xq$%sp~05!LG>(si70< zp!D}bJL0Hl7-)1gp6MTOKRkp`bZRRARR#XKNPM7H8n66KKDC?tI|nv>H$w0?s8oRQ z8sn<}j_EoBTMMPsC$*&zqPij1o4}i*umGenPJ!zS|2sP7x>+?(h=g~Q#1FrBN{M8c z;p7NqwNz zD+j3?fhwCFq>VDV-5A)6gUV2dgqjTMULx7q64OIXvP3sM;xDr&ovROmsU9u>7V77K zh?$VA<&!TCe|2w+{6r*7()Znx5(~8q4+c4((wCW2Ave{Q669h|Ip3U|6doZW9_t?6 z;5fUX@u!QgOhyJ4%E83oa+M&8kaPUgs{QoWD%bVbgtd;0Xv2OY>XdWx-|ZewVu-P3 zSFqtp2PL3Lgeb!YUFkpH8W&^AW0!_Y>)=q~u|1Zzr95w?(m(T3l*Mz_&3tK*^M2NC zZ3iXU`W_y`YR=N(`?A|@*zfILkB(DnVL)mTCbbw2Eh#1|g(otPfE6b+WD=9m{d(oQ zyXrYTm2PNN91Vo*&v19xvGy!W&qQSOM9$a^8}yP zGD{AKg9SZ7G%Q1^{ZL>}|LKK(`-16j)jK4s>gVNR4`{-z>8oV^S<8Aub#+>dZ~wW> z>U*yHN4xIbi-^;gBk%eb-o4^a6fcfPT^QhJO{4sY3PYGURsH~q#51vPr#6wlovffX z5B+quLgbz*#Pt4j%a*hcPn?8iO%W(b_YG$*3}3R1+zg3Fb>*PMrvl&Rb)q z6wVWhbn8{f&<^+&KSHM4E%m2&|8JxoHcab`im>3e$uPanKdmZmq`o?sXk=7BqU(Ir})pHe4={xi>u}5qE?4m%>b}_RI-f^VHt> zx6cgvL7XxRtnSfFX*8bl^DKD=_?(cy8TO*FF^Wn~vylxF7X{tn)m}OM`_TX7u^nTE zD->FRAhAJ^-bb)RA>gSdT3{42J^{%AErk##Qt?!y;RW|Wptlo3Y}w4%0*|GvR0VZM}d@eC(&np9H8gwO}!5%Q3|*j)w;k} z<9T_FH|IW_-0@CS?r52?`m2{NZP#_KWp8%N?Y-c0lu(SBaHg5aw-(DSE&9o+8dcZi&wUBTQ&ANhfywNd_gY424tALnRd707=_x$~1DSOq?3zYCk4T6Uj_m;TFN%%$ z}GTz1_d+T+10m;>$W{q zp9d^itRyj&q4nefX;zO5>xd@4gxkdd&ci9oj#}mPTN`nH0;dTUW&pi{xB67^ zr&%OnMi($;& zCHJ$UD*QPxyEhtlKVEAPMsq#iwu3%uSFX~+I207ZVjn(62Hl>w`@=i9A7gL+GqCUP>KI`>0*yFCf!2KnY_5ilWtRFvGNZ z;?km^wc4Zh){!5=P&tAVkrxBAJZX_W^b(&`uay!H)S$b6G&sVODo!WJKrxvsRYq+% zTLZ7tB?IBY@*nGq6--LJYl-6jslzu&X+9~P+Y(^V@8cC%+c~YD{`S_77dJ%}t7_;Q zC3P->CRP6K(aRWIo$r(;y|t$`I_meT;fBhK5>nsY6ni_}AXtAg``eF$(wO@6WPaWl z-TF4q%U(E?L|q`h)lBbI+GK7fScW67kfp)#|7fqA@yRo%g6%e9e3L+?kjKJ%0hIX`^zAG|X`_kVMx)Oq-X(4@2R6jDN_)tAU` ztslQc|Lp!4e@lFV_;Kwa=qh|I)`80U3&-TUK|<0tXYqOpPs7J`tVnXiMw&F~*+zz9 za&NL@>Ym(ct{&4}%G(Wygc5%RDflc3qNwq;hF`xURn zGiz68vT%F8{F1qUz;f8H_@(SH?edD9kZtgZt@|mh@x{D{j49lPGklx8R#1%GnX29@ zKFyY`V~S~fT1RYEvyJh_=MX^NdK@us{z~GQOpEQXn$jem7bK4Ucr*NSfr^hEpr__= zw(jxce`i;T*TbvU-rB+D6pEKb?MPcRrU6lhMTb;0kEN zvCaH9b1j{>3U;A=MIvpvnf>wi(k877Xb`pBu@ep;@p;nw9a^ckzSVNSv6cX8ekOSN zZ1NCkmj~s)eowQhgX|u$l&c&|=ajR%a@etGs87%4q@HXE$>$9pI-7}7!?o4Ua%y$I zOB)rea*2rTzP%jG(=pm&VnCM|IB;p^x7KZ&pUu)Z8RE2|?S@_2f7Qjt{By`mM{a!y zq_zf}Zx4RjmZe`d(7fyvf$oxsexuWK6PyoSox~~1W2dS8%#ht@5V|I0y1yst_J@(L zDj%EfNK2AZU9yb9Hh8D?&do|D#XWAZ4#htVsIKfA+0ppaWUT-Amr$-V6j+VN=ybeK ze0Tj2`|t6~xDx`mo~Ne}PpO%lK0`+Oa;CH)#`KS;MP5#Alj#-wQF*6ZLzo$*1Ya39Prsg4$Yfe0E`9@i$ViV?;rS>4hNF75bt6A8Ibg%RFb~P~V zs->t8LX#Ms+k7s)(M7yvC>1TuH&#gqGQ$zP)yVB;X#cZ|(|^ky^wREIWn1r#%p?dC z_qMQ{heRqZzAWd-;+yx2*9~_^kH)eu{+3q3wV!p>lF)I5lW}O{K8K)DJDUq)@{$O-%ia;&m#Np9FOjF5F14vvc`XX+0$R`)Aq{tZUoJY#cCw%3sO> zQ$jk&o`oD`{(b36#GQ>>P9xF-U$~_>PeO6XTRaN9S%GA>- z_O{?=bJ{hs5=8+jvMG#H_aoJh8rt?M;CDl(h`fi*y={z+p{^> zLmnzlt~q?kc~Ws$+k75W#tU%RA5dxIxx)69!(F^@uSKjqpPKs;{^pj@#Hi$3GG5{R z=R;Nlnlvw$mIsW-&12VfGtak7*G67@oC~oQ%diKvI{_@#Kdb$l_bXm}%UM@Geboz} zxmWWF%HZsmG|r7)S)uWW{Cp7JtGo%~-hTD3@;q%sMFTDs@e38#4ISKY@uoT4)u=lC zBpDO(r0S}_P4%l98vV6C2W&}SH|;4E^-DhMVf~GPpD*NBzb)PX%685XybvyTtji6a za}gE}!qwT#_evV@l>a%j9sIoZc;YE95_3ktQ)K}Ci1^>XvjL)(0Z}{PWRm*Wa0YBM z+qh&rqErI}5rXms%@{UFBV31#5F}dJFd_2ltEVJMM=`nxzzn$Bddf2}^OrZ^;`}L@ z^Bs~oe|U2a5_4n9Nd!uL{Uo%V=X*BUEd*(G`z6Zn5717&cu4L+{ph;)&N2c)=kPGK zgMJ-?DonsXO(duNNaosU7EK6~x}^7y$b61?G-pBSvoGj6UK!4k*Gt{rZKV-7q$$bb z1tUp1CCMLT@&+JSLlCs1PcJH^D4TaLkhy>OX-|c7_c+ukrV=RJvv~{KdDHx0<2jTu zQmS0Ew|S)*7yTH2wDGLupjUA4_7px26boH8lUnv)B2zAHRbYkiEVB)QrGz#FfrL3} z-fzm}`zpm!+cBz6%Y5noU^<7*k`|&9h?JD3m+#=C?w}r)e#bWV>-!w*J1O{F2T3a} zB?t$dRF4n908TaZYNlM{rj&ZQbnD#Llm8Y-hW2VMJP(7W6S5u2yb{Oh6Gu+! zLS8t?H3XuC4^g)bay2v(t{;ThjzV0a|EEgC6@;xq)ob8w7r(R|7{4hs<3krNjbjqE~kBhYXu5VxTykNvTL zmZTt>7C_+OJ-K8rehLVqSogCTBlCEOF=nlpSrIuTJKl+zw-dQX;L_Y8M`@E?RsTx|4HGy(wku@e%0tt<*Q@v18|&d-)~@iP1O|{V$qz3_)(gsR!aEc3`YYBxnYh}#|TcmdF~Xbb2D7e|2UO&lEufMfwm2 zrV!oW1ClE=1!+8ec{TFw7-VJJ0V?FG4+uP{=9ZE*mkl*n>^4`CHBTRe3JV4Zo;vGx zTTp$qFqL((2(`Sdw{(zogztzbAjy1W$trmm4c|gaoteckNb)!iQWTO2;3ChLMyu2F z2HzyY;#no<#c$1QspR*Y=;Cdjs_cC#n}G=A)tZDvWe}r}lHQ4vV4J z-D-!=j1JGnG!4M=k)do6_?{IR_#T=e5g;?G=5z!AO&o^_i0lBx^@0xQLUL2{z{TUl zYt3!7+H|umka-KH38H4MvMxp#Y81g0E$5~c=BC%xwgH5J(1u;@?Me7zQEt0QQ4wHtU-%0>9U}WYkCF)Su6* zA4MKPR{pFp+9rpNyAV7hjU&XcfDzt{b3)MSLHGpm;+cp2I_SM zYRLr4_iEDj2GvUjpb!0ctb9NIUPMlMql*qTnYr&+(cWWb)BBU58Xl_C7D`*gL?RzF zo*6FScSGc3*gSPOje59Fc$hy;E2Km!#D@2!#P!8IWWijv zB}Pm7zh;gz=;fH&5x+B>iiV_dYNRzP*fvjJ*DzUwtpagle_r6A zSYY+Hz&)~1QL*s;-$IY&!obKPQ=6j5zeUol*S&g&&fek*7Ya><5@JDQNy+n)ioYe* zilz0DrOkhDwBw6Ao(o$LxO0HwSIdt+X~72~%VibI-~26i#h1_hEnAGNc=f#Eb4k&< zVx?UqX*)`@Q?bfeL-$#H_WhwM;&OI180Qg>yElY8RjmGJgR25p8w^!*msVGRYpOJA z%HnGnm1>1nYBIsK5<|6WrM2ncIWBH)eo;U|4@2N27Y>Ki)?aY9IEDO0hz!)HRYa5@Gr~AvCAlZdM2VM ztNKY=n_XJ}QwtLh=LC*)kHC4?1Bhazz+f1@>LHcoQ#T0c2}k$b zFRQF$?+q>M1rbDQgG8Uu0c|(MdT%;EcX>Yk>G=%%i$yymHKP!FE_vm*2wH`6W{;HN8PhyV*KnyROU?)yoL~?Xr>ZiU_bgkZnnp-sk=@6p@2#Cd$ z@ttrS-R36_#z5l{VIa!*Ys0>pjnswFYhA)fdDNBF*^g4GHhtW!{PA2NO?~-~D_^J~Bwc#SV-(aZfS< zq=TG2p5xIMbG-w-XkGxww!WyH>G{_zc08My~697Ow z8UrCYjH;0`1p2-~>0AuQe<+WXb2-TMAMPM$KKpxtiuV!@Z%EYV6+h4S3j6%QvyD_U z>L(bJfE5dFy|#&YFLwDJrv8DfW}c|_`A!VILee9J%x51j8J74QmhN%RXMP5^tWyGn zDd|D$#DCl^_yrj6;`YW|+FOzNGyTkim*?wcKS#Sgxm%>ZQH4?-Q(Kyh}|TK zXK1*X(u><%zU0pPv<~Cl5USjWyV{V}|0-L#ndyl95`$!tqhz~U2jTAT$LzU7Xof&E z`6!wNXBy}Rc@5}}w=)yb(;2CWhxH+uaO<+l&U3Ka;}u*R0+kYzT>Fca`yl-Oy5qsO zF9$!bWUuX@elEb;i94@sC#F)2RBiv`!2X&e_eSgi$^W7bAf&cOm$rY%4$*v@gyGkW z<1Z@ipDOo$zC*D?T|bG*eS-~wi@AU+)ji0)qkFH96xDw24E*+g_ydF_n{}oo-S{(F zxmV9EGqgTT;zG-N>!f6ywdV!$s0&r=%>6!ud-mkX-Tc+%nsXTVADKF|=k-6bjen*N z-jmg0k(|H-mCIIcV5#b0Z4C)*#Pur!;F4PafI%q(CWHEL!aFragqUqVR=Rd9ZJiu# zAJSR_X99@jsbCRByOU(+*kvsw5D*MH4ft!4q4@0U6#F7=e3S4eE$)9q_W4qW zGys>LE#$m0iC@SIVYRq%F@MW*j!Cbq2Wxwp{m_Z-u`m^8_5~@KEbZv$zrjPZwYd;u zDjeeZ2*8BrYbsX+c4ni$S5CjI@dqSrd#^lnVSw~MT`*$H2#i_o_AkmFunTSI-r;(1 zOavV<2r>OEniVCU@+XTp@0lbkRw#Qea{dA0p(1-rDeIQq7jaO=&Ih$md?%`Ly#bY*XFU?ZW=L7rPclHpH}B z)N0XnS`3%Nw{h_!oX2n%j{;fylI=>z`0MLEx6)KW0KLSQhS05hKYjh2>}^wRj(X%y zU8L8W?RpkYG7NZONj-^W$8$rlJm|fM`;+|dtlm}3bEPAS&3*Wm82>TF#(ZWX&roI; zvm(8|I%&ouY`0p+5e@Sfzb>?#lcB7ncA5AiKjY4PaIV~+Y7KGe zQ6R#E{Py>LI*6vZxNEk;-!O5hLDKC0fMFUPWob=k@%d?`=eUB|N!c~Z`f;W7@_?CV z>V*iZXOjs=LKLVituc0kA2JiSbsUa6EbNYrSMEm-cYox_E_-up|N0_rk!tk#P)p_F zk>(df_3@iKH?F*=gj&lXQ;#EWY)sJrCeB%0vGXs6)htnoZEOEugLp_CwQKU5khSq; z0ASZFR~UW{>TG|a$hDwc^7r-crP@@+_=RUFYotE^Lv9GyD7M;OxO%C#w(~~)npUHU zIeBmVbV<i0^ciw` z{UdHDZXT7H(1G*bn6?HLxvmkY;lnI%1CnK0*0r2+GA%K)_mZ3%Dx*GpTJCZ%%i0o{8|9V)Jn%ETfRD*v6a?x4M{2D$+luDbsw>nHhS-cI7`aH-L zjfhXNC0y&rwG^H$n4J}!8{%88v?|w+BKeEtonJk6U~f`qyb8pMP67bdNryEbpb)w~ zfzNNL6SyH#sOEIYeI+^~e-K!>;e6;@Hq7_xEs84IdN|~Y+-_pGyWvL#7|0VzQ3+UA zF#H}=)W27M<009k6M1m)h?XmH7-Ps6P$vMEpf;L?Sb2HB^nQ$Ak7WvhD) z@~_FJ1JZ)ax5OJ2XHus_9tT(K`83{MBb$kM8(ewP(x`HnI`iOra7Nck<8>Et7BetU zcQX!4al$v7C>l~t`AQJYPCkd#52=xo!SMF*Qr$)o>nK;+QzU=m8xj|)uO)_LCW#uo z?&hz$ve(J`Lep%I3xHw<1Cv1U!@ZX_+1^(-89yXnz`6WK`vEabedUxb37}wSyHLat zGAqZ?nY-X@kh|SHmpr6~ZL*WkfM{yLBeTi+Vkw@nOFAua*O?=97R`Agw9xl9v@L`r zOL?d$$4tSKzDrM6Q2lY5T~iwybEL5502?-u5T`(<2Q}?NBN+5M+VWdl+!@mnAL3n~ z9pPa=oSf4#lNs0wFcYjt9U52`Ii7o?>gxP1+^Cjoz2|IPS;3no*gmYce_ul7*-^IS ziBq2nmeo`1li>SOrfw!131DDFJzZdnW?>&dQC#o!H+~}%2KL*+U$YxgFF|q`mq%of z@nm>%Ii7N4ix$(I)d%&4`Z+2Qps6e;FrTUa;#z}vR+1XB7YDm5ta(`cHkEsohl7X! z0WGLS?mf^G#y1e<$L-)tl+~TzqlYnHow3})AcWB6(^TV(4QFaR;v;@s(ThhC2w131 zI2(TiNSP%`xAM|?lH9)Pc>mWnYnb_$6mXo=5xQ4HE#lYts7icND-rV6qOG%_R}U_} jhoafXzAbo7`Bh5n7yV|tj+|(Rtn`z}sd)-GaQpuO(_5`= literal 0 HcmV?d00001 diff --git a/planning/behavior_velocity_intersection_module/scripts/ttc.py b/planning/behavior_velocity_intersection_module/scripts/ttc.py index e4633981570d1..6d1593d95f055 100755 --- a/planning/behavior_velocity_intersection_module/scripts/ttc.py +++ b/planning/behavior_velocity_intersection_module/scripts/ttc.py @@ -126,8 +126,11 @@ def plot_ttc(self): self.ttc_ax.set_xlabel("ego time") self.ttc_ax.set_ylabel("ego dist") time_dist_plot = self.ttc_ax.plot(ego_ttc_time, ego_ttc_dist, label="time-dist", c="orange") - self.ttc_ax.set_xlim(min(ego_ttc_time) - 2.0, max(ego_ttc_time) + 3.0) - self.ttc_ax.set_ylim(min(ego_ttc_dist) - 2.0, max(ego_ttc_dist) + 3.0) + self.ttc_ax.set_xlim( + min(ego_ttc_time) - 2.0, + min(max(ego_ttc_time) + 3.0, self.args.max_time), + ) + # self.ttc_ax.set_ylim(min(ego_ttc_dist) - 2.0, max(ego_ttc_dist) + 3.0) for npc, color in zip(self.npc_vehicles, cycle(self.color_list)): t0, t1 = npc.collision_start_time, npc.collision_end_time d0, d1 = npc.collision_start_dist, npc.collision_end_dist @@ -137,15 +140,13 @@ def plot_ttc(self): c=color, alpha=0.2, ) - dd = [d1 - d0 for d0, d1 in zip(ego_ttc_dist, ego_ttc_dist[1:])] dt = [t1 - t0 for t0, t1 in zip(ego_ttc_time, ego_ttc_time[1:])] v = [d / t for d, t in zip(dd, dt)] self.ttc_vel_ax.yaxis.set_label_position("right") self.ttc_vel_ax.set_ylabel("ego velocity") - self.ttc_vel_ax.set_ylim(0.0, max(v) + 1.0) + # self.ttc_vel_ax.set_ylim(0.0, max(v) + 1.0) time_velocity_plot = self.ttc_vel_ax.plot(ego_ttc_time[1:], v, label="time-v", c="red") - lines = time_dist_plot + time_velocity_plot labels = [line.get_label() for line in lines] self.ttc_ax.legend(lines, labels, loc="upper left") @@ -218,6 +219,7 @@ def cleanup(self): if self.args.save: kwargs_write = {"fps": self.args.fps, "quantizer": "nq"} imageio.mimsave("./" + self.args.gif + ".gif", self.images, **kwargs_write) + rclpy.shutdown() def on_plot_timer(self): with self.lock: @@ -277,6 +279,7 @@ def on_object_ttc(self, msg): default=60, help="detect range for drawing", ) + parser.add_argument("--max_time", type=float, default=100, help="max plot limit for time") parser.add_argument("-s", "--save", action="store_true", help="flag to save gif") parser.add_argument("--gif", type=str, default="ttc", help="filename of gif file") parser.add_argument("--fps", type=float, default=5, help="fps of gif") diff --git a/planning/behavior_velocity_intersection_module/src/util.cpp b/planning/behavior_velocity_intersection_module/src/util.cpp index a9d0f56266181..e6e6fa0a1da9a 100644 --- a/planning/behavior_velocity_intersection_module/src/util.cpp +++ b/planning/behavior_velocity_intersection_module/src/util.cpp @@ -36,6 +36,7 @@ #include #include +#include #include #include #include @@ -1304,14 +1305,27 @@ TimeDistanceArray calcIntersectionPassingTime( const bool use_upstream_velocity, const double minimum_upstream_velocity, tier4_debug_msgs::msg::Float64MultiArrayStamped * debug_ttc_array) { - double dist_sum = 0.0; + const double current_velocity = planner_data->current_velocity->twist.linear.x; + int assigned_lane_found = false; // crop intersection part of the path, and set the reference velocity to intersection_velocity // for ego's ttc PathWithLaneId reference_path; - for (size_t i = closest_idx; i < path.points.size(); ++i) { + std::optional upstream_stop_line{std::nullopt}; + for (size_t i = 0; i < path.points.size() - 1; ++i) { auto reference_point = path.points.at(i); + // assume backward velocity is current ego velocity + if (i < closest_idx) { + reference_point.point.longitudinal_velocity_mps = current_velocity; + } + if ( + i > last_intersection_stop_line_candidate_idx && + std::fabs(reference_point.point.longitudinal_velocity_mps) < + std::numeric_limits::epsilon() && + !upstream_stop_line) { + upstream_stop_line = i; + } if (!use_upstream_velocity) { reference_point.point.longitudinal_velocity_mps = intersection_velocity; } @@ -1326,28 +1340,46 @@ TimeDistanceArray calcIntersectionPassingTime( return {{0.0, 0.0}}; // has already passed the intersection. } + std::vector> original_path_xy; + for (size_t i = 0; i < reference_path.points.size(); ++i) { + const auto & p = reference_path.points.at(i).point.pose.position; + original_path_xy.emplace_back(p.x, p.y); + } + // apply smoother to reference velocity PathWithLaneId smoothed_reference_path = reference_path; - smoothPath(reference_path, smoothed_reference_path, planner_data); + if (!smoothPath(reference_path, smoothed_reference_path, planner_data)) { + smoothed_reference_path = reference_path; + } // calculate when ego is going to reach each (interpolated) points on the path TimeDistanceArray time_distance_array{}; - dist_sum = 0.0; + double dist_sum = 0.0; double passing_time = time_delay; time_distance_array.emplace_back(passing_time, dist_sum); // NOTE: `reference_path` is resampled in `reference_smoothed_path`, so // `last_intersection_stop_line_candidate_idx` makes no sense - const auto last_intersection_stop_line_candidate_point_orig = - path.points.at(last_intersection_stop_line_candidate_idx).point.pose; - const auto last_intersection_stop_line_candidate_nearest_ind = - motion_utils::findFirstNearestIndexWithSoftConstraints( - smoothed_reference_path.points, last_intersection_stop_line_candidate_point_orig, - planner_data->ego_nearest_dist_threshold, planner_data->ego_nearest_yaw_threshold); + const auto smoothed_path_closest_idx = motion_utils::findFirstNearestIndexWithSoftConstraints( + smoothed_reference_path.points, path.points.at(closest_idx).point.pose, + planner_data->ego_nearest_dist_threshold, planner_data->ego_nearest_yaw_threshold); + + const std::optional upstream_stop_line_idx_opt = [&]() -> std::optional { + if (upstream_stop_line) { + const auto upstream_stop_line_point = path.points.at(upstream_stop_line.value()).point.pose; + return motion_utils::findFirstNearestIndexWithSoftConstraints( + smoothed_reference_path.points, upstream_stop_line_point, + planner_data->ego_nearest_dist_threshold, planner_data->ego_nearest_yaw_threshold); + } else { + return std::nullopt; + } + }(); + const bool has_upstream_stopline = upstream_stop_line_idx_opt.has_value(); + const size_t upstream_stopline_ind = upstream_stop_line_idx_opt.value_or(0); - for (size_t i = 1; i < smoothed_reference_path.points.size(); ++i) { - const auto & p1 = smoothed_reference_path.points.at(i - 1); - const auto & p2 = smoothed_reference_path.points.at(i); + for (size_t i = smoothed_path_closest_idx; i < smoothed_reference_path.points.size() - 1; ++i) { + const auto & p1 = smoothed_reference_path.points.at(i); + const auto & p2 = smoothed_reference_path.points.at(i + 1); const double dist = tier4_autoware_utils::calcDistance2d(p1, p2); dist_sum += dist; @@ -1355,12 +1387,16 @@ TimeDistanceArray calcIntersectionPassingTime( // use average velocity between p1 and p2 const double average_velocity = (p1.point.longitudinal_velocity_mps + p2.point.longitudinal_velocity_mps) / 2.0; - const double minimum_ego_velocity_division = - (use_upstream_velocity && i > last_intersection_stop_line_candidate_nearest_ind) - ? minimum_upstream_velocity /* to avoid null division */ - : minimum_ego_velocity; - const double passing_velocity = - std::max(minimum_ego_velocity_division, average_velocity); + const double passing_velocity = [=]() { + if (use_upstream_velocity) { + if (has_upstream_stopline && i > upstream_stopline_ind) { + return minimum_upstream_velocity; + } + return std::max(average_velocity, minimum_ego_velocity); + } else { + return std::max(average_velocity, minimum_ego_velocity); + } + }(); passing_time += (dist / passing_velocity); time_distance_array.emplace_back(passing_time, dist_sum); @@ -1370,6 +1406,8 @@ TimeDistanceArray calcIntersectionPassingTime( debug_ttc_array->layout.dim.at(0).size = 5; debug_ttc_array->layout.dim.at(1).label = "values"; debug_ttc_array->layout.dim.at(1).size = time_distance_array.size(); + debug_ttc_array->data.reserve( + time_distance_array.size() * debug_ttc_array->layout.dim.at(0).size); for (unsigned i = 0; i < time_distance_array.size(); ++i) { debug_ttc_array->data.push_back(lane_id); } @@ -1379,11 +1417,13 @@ TimeDistanceArray calcIntersectionPassingTime( for (const auto & [t, d] : time_distance_array) { debug_ttc_array->data.push_back(d); } - for (const auto & p : smoothed_reference_path.points) { - debug_ttc_array->data.push_back(p.point.pose.position.x); + for (size_t i = smoothed_path_closest_idx; i < smoothed_reference_path.points.size(); ++i) { + const auto & p = smoothed_reference_path.points.at(i).point.pose.position; + debug_ttc_array->data.push_back(p.x); } - for (const auto & p : smoothed_reference_path.points) { - debug_ttc_array->data.push_back(p.point.pose.position.y); + for (size_t i = smoothed_path_closest_idx; i < smoothed_reference_path.points.size(); ++i) { + const auto & p = smoothed_reference_path.points.at(i).point.pose.position; + debug_ttc_array->data.push_back(p.y); } return time_distance_array; } diff --git a/planning/behavior_velocity_planner_common/src/utilization/trajectory_utils.cpp b/planning/behavior_velocity_planner_common/src/utilization/trajectory_utils.cpp index 71cdd9650a598..7fe8612cc6858 100644 --- a/planning/behavior_velocity_planner_common/src/utilization/trajectory_utils.cpp +++ b/planning/behavior_velocity_planner_common/src/utilization/trajectory_utils.cpp @@ -88,15 +88,14 @@ bool smoothPath( const auto & smoother = planner_data->velocity_smoother_; auto trajectory = convertPathToTrajectoryPoints(in_path); - if (external_v_limit) { - motion_velocity_smoother::trajectory_utils::applyMaximumVelocityLimit( - 0, trajectory.size(), external_v_limit->max_velocity, trajectory); - } const auto traj_lateral_acc_filtered = smoother->applyLateralAccelerationFilter(trajectory); + const auto traj_steering_rate_limited = + smoother->applySteeringRateLimit(traj_lateral_acc_filtered, false); + // Resample trajectory with ego-velocity based interval distances auto traj_resampled = smoother->resampleTrajectory( - traj_lateral_acc_filtered, v0, current_pose, planner_data->ego_nearest_dist_threshold, + traj_steering_rate_limited, v0, current_pose, planner_data->ego_nearest_dist_threshold, planner_data->ego_nearest_yaw_threshold); const size_t traj_resampled_closest = motion_utils::findFirstNearestIndexWithSoftConstraints( traj_resampled, current_pose, planner_data->ego_nearest_dist_threshold, @@ -114,6 +113,10 @@ bool smoothPath( traj_smoothed.insert( traj_smoothed.begin(), traj_resampled.begin(), traj_resampled.begin() + traj_resampled_closest); + if (external_v_limit) { + motion_velocity_smoother::trajectory_utils::applyMaximumVelocityLimit( + traj_resampled_closest, traj_smoothed.size(), external_v_limit->max_velocity, traj_smoothed); + } out_path = convertTrajectoryPointsToPath(traj_smoothed); return true; } From 8d52529d396b0fd9e74810010dcac92520e4bb8e Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Wed, 8 Nov 2023 18:32:41 +0900 Subject: [PATCH 146/202] fix: add_ros_test to add_launch_test (#5486) * fix: add_ros_test to add_launch_test Signed-off-by: kminoda * fix ndt_scan_matcher Signed-off-by: kminoda --------- Signed-off-by: kminoda --- localization/ekf_localizer/CMakeLists.txt | 4 ++-- localization/ndt_scan_matcher/CMakeLists.txt | 2 +- map/map_loader/CMakeLists.txt | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/localization/ekf_localizer/CMakeLists.txt b/localization/ekf_localizer/CMakeLists.txt index 45d420bafff10..9944cbb84d97c 100644 --- a/localization/ekf_localizer/CMakeLists.txt +++ b/localization/ekf_localizer/CMakeLists.txt @@ -43,11 +43,11 @@ function(add_testcase filepath) endfunction() if(BUILD_TESTING) - add_ros_test( + add_launch_test( test/test_ekf_localizer_launch.py TIMEOUT "30" ) - add_ros_test( + add_launch_test( test/test_ekf_localizer_mahalanobis.py TIMEOUT "30" ) diff --git a/localization/ndt_scan_matcher/CMakeLists.txt b/localization/ndt_scan_matcher/CMakeLists.txt index 6fe61cd25bc6e..4beecc2625fe3 100644 --- a/localization/ndt_scan_matcher/CMakeLists.txt +++ b/localization/ndt_scan_matcher/CMakeLists.txt @@ -38,7 +38,7 @@ link_directories(${PCL_LIBRARY_DIRS}) target_link_libraries(ndt_scan_matcher ${PCL_LIBRARIES} glog::glog) if(BUILD_TESTING) - add_ros_test( + add_launch_test( test/test_ndt_scan_matcher_launch.py TIMEOUT "30" ) diff --git a/map/map_loader/CMakeLists.txt b/map/map_loader/CMakeLists.txt index b94eaac7ee34d..115f7e5b17464 100644 --- a/map/map_loader/CMakeLists.txt +++ b/map/map_loader/CMakeLists.txt @@ -46,7 +46,7 @@ rclcpp_components_register_node(lanelet2_map_visualization_node ) if(BUILD_TESTING) - add_ros_test( + add_launch_test( test/lanelet2_map_loader_launch.test.py TIMEOUT "30" ) From 328bfa6a644e2043ced593d304d34df2e7828d52 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Wed, 8 Nov 2023 20:59:48 +0900 Subject: [PATCH 147/202] refactor(behavior_path_planner): remove status_.pull_over_lanes (#5520) * Remove unused variable and update function arguments in start_planner_module.hpp and util.hpp/cpp Signed-off-by: kyoichi-sugahara --------- Signed-off-by: kyoichi-sugahara --- .../start_planner/start_planner_module.hpp | 1 - .../start_planner/start_planner_module.cpp | 43 +++++++++++-------- .../src/utils/start_planner/util.cpp | 7 ++- 3 files changed, 28 insertions(+), 23 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp index 8ea963fec0b8d..91121598cb3ae 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp @@ -59,7 +59,6 @@ struct PullOutStatus size_t current_path_idx{0}; PlannerType planner_type{PlannerType::NONE}; PathWithLaneId backward_path{}; - lanelet::ConstLanelets pull_out_lanes{}; bool found_pull_out_path{false}; // current path is safe against static objects bool is_safe_dynamic_objects{false}; // current path is safe against dynamic objects bool driving_forward{false}; // if ego is driving on backward path, this is set to false diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp index e3670710b64f0..bd042f8ecef4d 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp @@ -619,8 +619,11 @@ PathWithLaneId StartPlannerModule::generateStopPath() const PathPointWithLaneId p{}; p.point.pose = pose; p.point.longitudinal_velocity_mps = 0.0; + const auto pull_out_lanes = start_planner_utils::getPullOutLanes( + planner_data_, + planner_data_->parameters.backward_path_length + parameters_->max_back_distance); lanelet::Lanelet closest_lanelet; - lanelet::utils::query::getClosestLanelet(status_.pull_out_lanes, pose, &closest_lanelet); + lanelet::utils::query::getClosestLanelet(pull_out_lanes, pose, &closest_lanelet); p.lane_ids.push_back(closest_lanelet.id()); return p; }; @@ -664,13 +667,15 @@ lanelet::ConstLanelets StartPlannerModule::getPathRoadLanes(const PathWithLaneId std::vector StartPlannerModule::generateDrivableLanes( const PathWithLaneId & path) const { + const auto pull_out_lanes = start_planner_utils::getPullOutLanes( + planner_data_, planner_data_->parameters.backward_path_length + parameters_->max_back_distance); + const auto path_road_lanes = getPathRoadLanes(path); if (!path_road_lanes.empty()) { lanelet::ConstLanelets shoulder_lanes; const auto & rh = planner_data_->route_handler; std::copy_if( - status_.pull_out_lanes.begin(), status_.pull_out_lanes.end(), - std::back_inserter(shoulder_lanes), + pull_out_lanes.begin(), pull_out_lanes.end(), std::back_inserter(shoulder_lanes), [&rh](const auto & pull_out_lane) { return rh->isShoulderLanelet(pull_out_lane); }); return utils::generateDrivableLanesWithShoulderLanes(path_road_lanes, shoulder_lanes); @@ -678,7 +683,7 @@ std::vector StartPlannerModule::generateDrivableLanes( // if path_road_lanes is empty, use only pull_out_lanes as drivable lanes std::vector drivable_lanes; - for (const auto & lane : status_.pull_out_lanes) { + for (const auto & lane : pull_out_lanes) { DrivableLanes drivable_lane; drivable_lane.right_lane = lane; drivable_lane.left_lane = lane; @@ -693,11 +698,6 @@ void StartPlannerModule::updatePullOutStatus() !planner_data_->prev_route_id || *planner_data_->prev_route_id != planner_data_->route_handler->getRouteUuid(); - // save pull out lanes which is generated using current pose before starting pull out - // (before approval) - status_.pull_out_lanes = start_planner_utils::getPullOutLanes( - planner_data_, planner_data_->parameters.backward_path_length + parameters_->max_back_distance); - // skip updating if enough time has not passed for preventing chattering between back and // start_planner if (!has_received_new_route) { @@ -734,12 +734,15 @@ void StartPlannerModule::updatePullOutStatus() planWithPriority( start_pose_candidates, *refined_start_pose, goal_pose, parameters_->search_priority); + const auto pull_out_lanes = start_planner_utils::getPullOutLanes( + planner_data_, planner_data_->parameters.backward_path_length + parameters_->max_back_distance); + if (isBackwardDrivingComplete()) { updateStatusAfterBackwardDriving(); current_state_ = ModuleStatus::SUCCESS; // for breaking loop } else { status_.backward_path = start_planner_utils::getBackwardPath( - *route_handler, status_.pull_out_lanes, current_pose, status_.pull_out_start_pose, + *route_handler, pull_out_lanes, current_pose, status_.pull_out_start_pose, parameters_->backward_velocity); } } @@ -761,12 +764,14 @@ PathWithLaneId StartPlannerModule::calcStartPoseCandidatesBackwardPath() const { const Pose & current_pose = planner_data_->self_odometry->pose.pose; + const auto pull_out_lanes = start_planner_utils::getPullOutLanes( + planner_data_, planner_data_->parameters.backward_path_length + parameters_->max_back_distance); + // get backward shoulder path - const auto arc_position_pose = - lanelet::utils::getArcCoordinates(status_.pull_out_lanes, current_pose); + const auto arc_position_pose = lanelet::utils::getArcCoordinates(pull_out_lanes, current_pose); const double check_distance = parameters_->max_back_distance + 30.0; // buffer auto path = planner_data_->route_handler->getCenterLinePath( - status_.pull_out_lanes, arc_position_pose.length - check_distance, + pull_out_lanes, arc_position_pose.length - check_distance, arc_position_pose.length + check_distance); // lateral shift to current_pose @@ -785,18 +790,20 @@ std::vector StartPlannerModule::searchPullOutStartPoses( std::vector pull_out_start_pose{}; + const auto pull_out_lanes = start_planner_utils::getPullOutLanes( + planner_data_, planner_data_->parameters.backward_path_length + parameters_->max_back_distance); + // filter pull out lanes stop objects const auto [pull_out_lane_objects, others] = utils::path_safety_checker::separateObjectsByLanelets( - *planner_data_->dynamic_object, status_.pull_out_lanes, + *planner_data_->dynamic_object, pull_out_lanes, utils::path_safety_checker::isPolygonOverlapLanelet); const auto pull_out_lane_stop_objects = utils::path_safety_checker::filterObjectsByVelocity( pull_out_lane_objects, parameters_->th_moving_object_velocity); // Set the maximum backward distance less than the distance from the vehicle's base_link to the // lane's rearmost point to prevent lane departure. - const double s_current = - lanelet::utils::getArcCoordinates(status_.pull_out_lanes, current_pose).length; + const double s_current = lanelet::utils::getArcCoordinates(pull_out_lanes, current_pose).length; const double max_back_distance = std::clamp( s_current - planner_data_->parameters.base_link2rear, 0.0, parameters_->max_back_distance); @@ -812,10 +819,10 @@ std::vector StartPlannerModule::searchPullOutStartPoses( // check the back pose is near the lane end const double length_to_backed_pose = - lanelet::utils::getArcCoordinates(status_.pull_out_lanes, *backed_pose).length; + lanelet::utils::getArcCoordinates(pull_out_lanes, *backed_pose).length; const double length_to_lane_end = std::accumulate( - std::begin(status_.pull_out_lanes), std::end(status_.pull_out_lanes), 0.0, + std::begin(pull_out_lanes), std::end(pull_out_lanes), 0.0, [](double acc, const auto & lane) { return acc + lanelet::utils::getLaneletLength2d(lane); }); const double distance_from_lane_end = length_to_lane_end - length_to_backed_pose; if (distance_from_lane_end < parameters_->ignore_distance_from_lane_end) { diff --git a/planning/behavior_path_planner/src/utils/start_planner/util.cpp b/planning/behavior_path_planner/src/utils/start_planner/util.cpp index 40b100a1bc070..7b4d4566bba27 100644 --- a/planning/behavior_path_planner/src/utils/start_planner/util.cpp +++ b/planning/behavior_path_planner/src/utils/start_planner/util.cpp @@ -89,15 +89,14 @@ lanelet::ConstLanelets getPullOutLanes( { const double & vehicle_width = planner_data->parameters.vehicle_width; const auto & route_handler = planner_data->route_handler; - const auto & current_pose = planner_data->self_odometry->pose.pose; + const auto & start_pose = planner_data->route_handler->getOriginalStartPose(); lanelet::ConstLanelet current_shoulder_lane; lanelet::ConstLanelets shoulder_lanes; if (route_handler->getPullOutStartLane( - route_handler->getShoulderLanelets(), current_pose, vehicle_width, - ¤t_shoulder_lane)) { + route_handler->getShoulderLanelets(), start_pose, vehicle_width, ¤t_shoulder_lane)) { // pull out from shoulder lane - return route_handler->getShoulderLaneletSequence(current_shoulder_lane, current_pose); + return route_handler->getShoulderLaneletSequence(current_shoulder_lane, start_pose); } // pull out from road lane From 934db6cea18115face4585bbf8711b11005c0f0a Mon Sep 17 00:00:00 2001 From: Alexey Panferov <37497658+lexavtanke@users.noreply.github.com> Date: Wed, 8 Nov 2023 17:31:40 +0300 Subject: [PATCH 148/202] build(lidar_apollo_segmentation_tvm and lidar_apollo_segmentation_tvm_nodes): remove download from cmake (#5431) * add include tier4_autoware_utils and dependency Signed-off-by: Alexey Panferov * remove downloading logic from Cmake, update documentation Signed-off-by: Alexey Panferov * build(tvm_utility): remove downloading logic from Cmake, update documentation Signed-off-by: Alexey Panferov * style(pre-commit): autofix * build(tvm_utility): fix lint_cmake error Signed-off-by: Alexey Panferov * build(tvm_utility): format warning message Signed-off-by: Alexey Panferov * build(tvm_utility): add logic to work with autoware_data folder, add nn config header and test image Signed-off-by: Alexey Panferov * style(pre-commit): autofix * style(pre-commit): autofix * build(tvm_utility): refactor, update InferenceEngineTVM constructor Signed-off-by: Alexey Panferov * style(pre-commit): autofix * build(tvm_utility): add lightweight model and test with it Signed-off-by: Alexey Panferov * build(tvm_utility): make building yolo_v2_tiny disable by default Signed-off-by: Alexey Panferov * build(tvm_utility): remove test artifact for yolo_v2_tiny Signed-off-by: Alexey Panferov * build(tvm_utility): update docs Signed-off-by: Alexey Panferov * build(tvm_utility): update docs Signed-off-by: Alexey Panferov * style(pre-commit): autofix * build(tvm_utility): update namespace in abs_model test Signed-off-by: Alexey Panferov * build(tvm_utility): rewrite yolo_v2_tiny as example Signed-off-by: Alexey Panferov * build(tvm_utility): clean comments in yolo_v2_tiny example main.cpp Signed-off-by: Alexey Panferov * build(tvm_utility): add launch file for yolo_v2_tiny example Signed-off-by: Alexey Panferov * build(tvm_utility): update yolo_v2_tiny example readme Signed-off-by: Alexey Panferov * style(pre-commit): autofix * build(tvm_utility): add model for arm based systems, need to be tested on device Signed-off-by: Alexey Panferov * style(pre-commit): autofix * style(pre-commit): autofix * build(tvm_utility): update config header for arm Signed-off-by: Alexey Panferov * style(pre-commit): autofix * build(tvm_utility): remove debug output Signed-off-by: Alexey Panferov * build(tvm_utility): add find_package conditional section Signed-off-by: Alexey Panferov * build(tvm_utility): fix lint_cmake errors Signed-off-by: Alexey Panferov * build(tvm_utility): remove coping model files during build Signed-off-by: Alexey Panferov * build(tvm_utility): update readme with new data folder structure Signed-off-by: Alexey Panferov * build(tvm_utility): fix spell check warnings Signed-off-by: Alexey Panferov * style(pre-commit): autofix * build(tvm_utility): add no model files guard to get_neural_network Signed-off-by: Alexey Panferov * style(pre-commit): autofix * build(tvm_utility): set back default paths in config headers Signed-off-by: Alexey Panferov * build(lidar_apollo_segmentation): wip update launch files Signed-off-by: Alexey Panferov * build(tvm_utility): add param file, update launch file Signed-off-by: Alexey Panferov * build(tvm_utility): add schema file, update node name Signed-off-by: Alexey Panferov * style(pre-commit): autofix * build(tvm_utility): fix json-schema-check Signed-off-by: Alexey Panferov * build(tvm_utility): fix json-schema-check Signed-off-by: Alexey Panferov * style(pre-commit): autofix * build(tvm_utility): add parameter table to example readme Signed-off-by: Alexey Panferov * build(tvm_utility): fix typo-error in description of schema.json Signed-off-by: Alexey Panferov * style(pre-commit): autofix * buiild(tvm_utility): fix spell-check warning and typo Signed-off-by: Alexey Panferov * feat(spell-check): add dltype and tvmgen to local dict Signed-off-by: Alexey Panferov * style(pre-commit): autofix * build(lidar_apollo_segmentation_tvm): remove test Signed-off-by: Alexey Panferov * build(lidar_apollo_segmentation_tvm): add data_path to constructor Signed-off-by: Alexey Panferov * build(lidar_apollo_segmentation_tvm_nodes): add data_path to param file Signed-off-by: Alexey Panferov * build(lidar_apollo_segmentation_tvm_nodes): add allow_substs to launches Signed-off-by: Alexey Panferov * style(pre-commit): autofix * build(lidar_apollo_segmentation_tvm_nodes): update README Signed-off-by: Alexey Panferov * build(lidar_apollo_segmentation_tvm): update README Signed-off-by: Alexey Panferov * build(lidar_apollo_segmentation_tvm_nodes): fix schema typo Signed-off-by: Alexey Panferov * build(lidar_apollo_segmentation_tvm): remove unused import Signed-off-by: Alexey Panferov * build(lidar_apollo_segmentation_tvm): suppress cpplint Signed-off-by: Alexey Panferov * build(lidar_apollo_segmentation_tvm): suppress cpplint Signed-off-by: Alexey Panferov * build(lidar_apollo_segmentation_tvm): return test back and update it Signed-off-by: Alexey Panferov * style(pre-commit): autofix * build(lidar_apollo_segmentation_tvm): fix cpplilnt errors Signed-off-by: Alexey Panferov * build(lidar_apollo_segmenntation_tvm): update checking for models files Signed-off-by: Alexey Panferov * style(pre-commit): autofix --------- Signed-off-by: Alexey Panferov Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../lidar_apollo_segmentation_tvm/.gitignore | 1 - .../lidar_apollo_segmentation_tvm/README.md | 7 ++- .../baidu_cnn/inference_engine_tvm_config.hpp | 55 +++++++++++++++++++ .../lidar_apollo_segmentation_tvm.hpp | 3 +- .../src/lidar_apollo_segmentation_tvm.cpp | 4 +- .../test/main.cpp | 40 ++++++++++++-- .../README.md | 2 +- ...r_apollo_segmentation_tvm_nodes.param.yaml | 1 + ...ar_apollo_segmentation_tvm_nodes.launch.py | 11 +++- ...r_apollo_segmentation_tvm_nodes.launch.xml | 3 +- ..._apollo_segmentation_tvm_nodes.schema.json | 8 ++- .../lidar_apollo_segmentation_tvm_node.cpp | 2 +- 12 files changed, 117 insertions(+), 20 deletions(-) delete mode 100644 perception/lidar_apollo_segmentation_tvm/.gitignore create mode 100644 perception/lidar_apollo_segmentation_tvm/data/models/baidu_cnn/inference_engine_tvm_config.hpp diff --git a/perception/lidar_apollo_segmentation_tvm/.gitignore b/perception/lidar_apollo_segmentation_tvm/.gitignore deleted file mode 100644 index 8fce603003c1e..0000000000000 --- a/perception/lidar_apollo_segmentation_tvm/.gitignore +++ /dev/null @@ -1 +0,0 @@ -data/ diff --git a/perception/lidar_apollo_segmentation_tvm/README.md b/perception/lidar_apollo_segmentation_tvm/README.md index d1337304fbf06..72fb26105e63e 100644 --- a/perception/lidar_apollo_segmentation_tvm/README.md +++ b/perception/lidar_apollo_segmentation_tvm/README.md @@ -6,9 +6,10 @@ #### Neural network -This package will not build without a neural network for its inference. -The network is provided by the cmake function exported by the tvm_utility package. -See its design page for more information on how to enable downloading pre-compiled networks (by setting the `DOWNLOAD_ARTIFACTS` cmake variable), or how to handle user-compiled networks. +This package will not run without a neural network for its inference. +The network is provided by ansible script during the installation of Autoware or can be downloaded manually according to [Manual Downloading](https://github.com/autowarefoundation/autoware/tree/main/ansible/roles/artifacts). +This package uses 'get_neural_network' function from tvm_utility package to create and provide proper dependency. +See its design page for more information on how to handle user-compiled networks. #### Backend diff --git a/perception/lidar_apollo_segmentation_tvm/data/models/baidu_cnn/inference_engine_tvm_config.hpp b/perception/lidar_apollo_segmentation_tvm/data/models/baidu_cnn/inference_engine_tvm_config.hpp new file mode 100644 index 0000000000000..d7541df046532 --- /dev/null +++ b/perception/lidar_apollo_segmentation_tvm/data/models/baidu_cnn/inference_engine_tvm_config.hpp @@ -0,0 +1,55 @@ +// Copyright 2021 Arm Limited and Contributors. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "tvm_utility/pipeline.hpp" + +#ifndef PERCEPTION__LIDAR_APOLLO_SEGMENTATION_TVM__DATA__MODELS__BAIDU_CNN__INFERENCE_ENGINE_TVM_CONFIG_HPP_ // NOLINT +#define PERCEPTION__LIDAR_APOLLO_SEGMENTATION_TVM__DATA__MODELS__BAIDU_CNN__INFERENCE_ENGINE_TVM_CONFIG_HPP_ // NOLINT + +namespace model_zoo +{ +namespace perception +{ +namespace lidar_obstacle_detection +{ +namespace baidu_cnn +{ +namespace onnx_bcnn +{ + +static const tvm_utility::pipeline::InferenceEngineTVMConfig config{ + {3, 0, 0}, // modelzoo_version + + "baidu_cnn", // network_name + "llvm", // network_backend + + "./deploy_lib.so", // network_module_path + "./deploy_graph.json", // network_graph_path + "./deploy_param.params", // network_params_path + + kDLCPU, // tvm_device_type + 0, // tvm_device_id + + {{"data", kDLFloat, 32, 1, {1, 4, 864, 864}}}, // network_inputs + + {{"deconv0", kDLFloat, 32, 1, {1, 12, 864, 864}}} // network_outputs +}; + +} // namespace onnx_bcnn +} // namespace baidu_cnn +} // namespace lidar_obstacle_detection +} // namespace perception +} // namespace model_zoo +// NOLINTNEXTLINE +#endif // PERCEPTION__LIDAR_APOLLO_SEGMENTATION_TVM__DATA__MODELS__BAIDU_CNN__INFERENCE_ENGINE_TVM_CONFIG_HPP_ diff --git a/perception/lidar_apollo_segmentation_tvm/include/lidar_apollo_segmentation_tvm/lidar_apollo_segmentation_tvm.hpp b/perception/lidar_apollo_segmentation_tvm/include/lidar_apollo_segmentation_tvm/lidar_apollo_segmentation_tvm.hpp index b9734a41d28ae..7f8c5f51f73a6 100644 --- a/perception/lidar_apollo_segmentation_tvm/include/lidar_apollo_segmentation_tvm/lidar_apollo_segmentation_tvm.hpp +++ b/perception/lidar_apollo_segmentation_tvm/include/lidar_apollo_segmentation_tvm/lidar_apollo_segmentation_tvm.hpp @@ -141,10 +141,11 @@ class LIDAR_APOLLO_SEGMENTATION_TVM_PUBLIC ApolloLidarSegmentation /// \param[in] height_thresh If it is non-negative, the points that are higher than the predicted /// object height by height_thresh are filtered out in the /// post-processing step. + /// \param[in] data_path The path to autoware data and artifacts folder explicit ApolloLidarSegmentation( int32_t range, float score_threshold, bool use_intensity_feature, bool use_constant_feature, float z_offset, float min_height, float max_height, float objectness_thresh, - int32_t min_pts_num, float height_thresh); + int32_t min_pts_num, float height_thresh, const std::string & data_path); /// \brief Detect obstacles. /// \param[in] input Input pointcloud. diff --git a/perception/lidar_apollo_segmentation_tvm/src/lidar_apollo_segmentation_tvm.cpp b/perception/lidar_apollo_segmentation_tvm/src/lidar_apollo_segmentation_tvm.cpp index e6c95f202106d..85f0a69356d55 100644 --- a/perception/lidar_apollo_segmentation_tvm/src/lidar_apollo_segmentation_tvm.cpp +++ b/perception/lidar_apollo_segmentation_tvm/src/lidar_apollo_segmentation_tvm.cpp @@ -108,7 +108,7 @@ std::shared_ptr ApolloLidarSegmentationPostProcessor ApolloLidarSegmentation::ApolloLidarSegmentation( int32_t range, float score_threshold, bool use_intensity_feature, bool use_constant_feature, float z_offset, float min_height, float max_height, float objectness_thresh, int32_t min_pts_num, - float height_thresh) + float height_thresh, const std::string & data_path) : range_(range), score_threshold_(score_threshold), z_offset_(z_offset), @@ -118,7 +118,7 @@ ApolloLidarSegmentation::ApolloLidarSegmentation( pcl_pointcloud_ptr_(new pcl::PointCloud), PreP(std::make_shared( config, range, use_intensity_feature, use_constant_feature, min_height, max_height)), - IE(std::make_shared(config, "lidar_apollo_segmentation_tvm")), + IE(std::make_shared(config, "lidar_apollo_segmentation_tvm", data_path)), PostP(std::make_shared( config, pcl_pointcloud_ptr_, range, objectness_thresh, score_threshold, height_thresh, min_pts_num)), diff --git a/perception/lidar_apollo_segmentation_tvm/test/main.cpp b/perception/lidar_apollo_segmentation_tvm/test/main.cpp index 9fd644afff1f2..06cff2a67e908 100644 --- a/perception/lidar_apollo_segmentation_tvm/test/main.cpp +++ b/perception/lidar_apollo_segmentation_tvm/test/main.cpp @@ -17,14 +17,18 @@ #include +#include #include #include #include #include using autoware::perception::lidar_apollo_segmentation_tvm::ApolloLidarSegmentation; +namespace fs = std::filesystem; -void test_segmentation(bool use_intensity_feature, bool use_constant_feature, bool expect_throw) +void test_segmentation( + const std::string & data_path, bool use_intensity_feature, bool use_constant_feature, + bool expect_throw) { // Instantiate the pipeline const int width = 1; @@ -37,9 +41,10 @@ void test_segmentation(bool use_intensity_feature, bool use_constant_feature, bo const float objectness_thresh = 0.5f; const int32_t min_pts_num = 3; const float height_thresh = 0.5f; + ApolloLidarSegmentation segmentation( range, score_threshold, use_intensity_feature, use_constant_feature, z_offset, min_height, - max_height, objectness_thresh, min_pts_num, height_thresh); + max_height, objectness_thresh, min_pts_num, height_thresh, data_path); auto version_status = segmentation.version_check(); EXPECT_NE(version_status, tvm_utility::Version::Unsupported); @@ -85,8 +90,31 @@ void test_segmentation(bool use_intensity_feature, bool use_constant_feature, bo // Other test configurations to increase code coverage. TEST(lidar_apollo_segmentation_tvm, others) { - test_segmentation(false, true, false); - test_segmentation(true, true, false); - test_segmentation(false, false, false); - test_segmentation(true, false, false); + std::string home = std::getenv("HOME"); + fs::path data_path(home); + data_path /= "autoware_data"; + fs::path apollo_data_path(data_path); + apollo_data_path /= "lidar_apollo_segmentation_tvm"; + fs::path deploy_path(apollo_data_path); + deploy_path /= "models/baidu_cnn"; + + fs::path deploy_graph("deploy_graph.json"); + fs::path deploy_lib("deploy_lib.so"); + fs::path deploy_param("deploy_param.params"); + + fs::path deploy_graph_path = deploy_path / deploy_graph; + fs::path deploy_lib_path = deploy_path / deploy_lib; + fs::path deploy_param_path = deploy_path / deploy_param; + + if ( + !fs::exists(deploy_graph_path) || !fs::exists(deploy_lib_path) || + !fs::exists(deploy_param_path)) { + printf("Model deploy files not found. Skip test.\n"); + GTEST_SKIP(); + return; + } + test_segmentation(data_path, false, true, false); + test_segmentation(data_path, true, true, false); + test_segmentation(data_path, false, false, false); + test_segmentation(data_path, true, false, false); } diff --git a/perception/lidar_apollo_segmentation_tvm_nodes/README.md b/perception/lidar_apollo_segmentation_tvm_nodes/README.md index 488eea4f92168..a9ffd59f228ec 100644 --- a/perception/lidar_apollo_segmentation_tvm_nodes/README.md +++ b/perception/lidar_apollo_segmentation_tvm_nodes/README.md @@ -28,7 +28,7 @@ See the design of the algorithm in the core (lidar_apollo_segmentation_tvm) pack ### Usage -`lidar_apollo_segmentation_tvm` and `lidar_apollo_segmentation_tvm_nodes` will not build without a neural network. +`lidar_apollo_segmentation_tvm` and `lidar_apollo_segmentation_tvm_nodes` will not work without a neural network. See the lidar_apollo_segmentation_tvm usage for more information. ### Assumptions / Known limits diff --git a/perception/lidar_apollo_segmentation_tvm_nodes/config/lidar_apollo_segmentation_tvm_nodes.param.yaml b/perception/lidar_apollo_segmentation_tvm_nodes/config/lidar_apollo_segmentation_tvm_nodes.param.yaml index 97f733f01c794..30bf0ba68d28c 100644 --- a/perception/lidar_apollo_segmentation_tvm_nodes/config/lidar_apollo_segmentation_tvm_nodes.param.yaml +++ b/perception/lidar_apollo_segmentation_tvm_nodes/config/lidar_apollo_segmentation_tvm_nodes.param.yaml @@ -24,3 +24,4 @@ objectness_thresh: 0.5 min_pts_num: 3 height_thresh: 0.5 + data_path: $(env HOME)/autoware_data diff --git a/perception/lidar_apollo_segmentation_tvm_nodes/launch/lidar_apollo_segmentation_tvm_nodes.launch.py b/perception/lidar_apollo_segmentation_tvm_nodes/launch/lidar_apollo_segmentation_tvm_nodes.launch.py index f4c81d6b154d7..2d070f2611ac5 100644 --- a/perception/lidar_apollo_segmentation_tvm_nodes/launch/lidar_apollo_segmentation_tvm_nodes.launch.py +++ b/perception/lidar_apollo_segmentation_tvm_nodes/launch/lidar_apollo_segmentation_tvm_nodes.launch.py @@ -21,7 +21,7 @@ from launch.actions import DeclareLaunchArgument from launch.substitutions import LaunchConfiguration from launch_ros.actions import Node -import yaml +import launch_ros.parameter_descriptions def generate_launch_description(): @@ -29,12 +29,17 @@ def generate_launch_description(): get_package_share_directory("lidar_apollo_segmentation_tvm_nodes"), "config/lidar_apollo_segmentation_tvm_nodes.param.yaml", ) - with open(param_file, "r") as f: - lidar_apollo_segmentation_tvm_node_params = yaml.safe_load(f)["/**"]["ros__parameters"] + + lidar_apollo_segmentation_tvm_node_params = launch_ros.parameter_descriptions.ParameterFile( + param_file=param_file, allow_substs=True + ) arguments = [ DeclareLaunchArgument("input/pointcloud", default_value="/sensing/lidar/pointcloud"), DeclareLaunchArgument("output/objects", default_value="labeled_clusters"), + DeclareLaunchArgument( + "data_path", default_value=os.path.join(os.environ["HOME"], "autoware_data") + ), ] # lidar segmentation node execution definition. diff --git a/perception/lidar_apollo_segmentation_tvm_nodes/launch/lidar_apollo_segmentation_tvm_nodes.launch.xml b/perception/lidar_apollo_segmentation_tvm_nodes/launch/lidar_apollo_segmentation_tvm_nodes.launch.xml index 0d7bebe986df4..c97d7356f5616 100644 --- a/perception/lidar_apollo_segmentation_tvm_nodes/launch/lidar_apollo_segmentation_tvm_nodes.launch.xml +++ b/perception/lidar_apollo_segmentation_tvm_nodes/launch/lidar_apollo_segmentation_tvm_nodes.launch.xml @@ -23,6 +23,7 @@ - + + diff --git a/perception/lidar_apollo_segmentation_tvm_nodes/schema/lidar_apollo_segmentation_tvm_nodes.schema.json b/perception/lidar_apollo_segmentation_tvm_nodes/schema/lidar_apollo_segmentation_tvm_nodes.schema.json index 8e56cfb820766..aaabbf2b65879 100644 --- a/perception/lidar_apollo_segmentation_tvm_nodes/schema/lidar_apollo_segmentation_tvm_nodes.schema.json +++ b/perception/lidar_apollo_segmentation_tvm_nodes/schema/lidar_apollo_segmentation_tvm_nodes.schema.json @@ -61,6 +61,11 @@ "type": "number", "default": 0.5, "description": "If it is non-negative, the points that are higher than the predicted object height by height_thresh are filtered out in the post-processing step." + }, + "data_path": { + "type": "string", + "default": "$(env HOME)/autoware_data", + "description": "Packages data and artifacts directory path." } }, "required": [ @@ -73,7 +78,8 @@ "max_height", "objectness_thresh", "min_pts_num", - "height_thresh" + "height_thresh", + "data_path" ] } }, diff --git a/perception/lidar_apollo_segmentation_tvm_nodes/src/lidar_apollo_segmentation_tvm_node.cpp b/perception/lidar_apollo_segmentation_tvm_nodes/src/lidar_apollo_segmentation_tvm_node.cpp index 8f1d3301cf3a2..618d2e258c99b 100644 --- a/perception/lidar_apollo_segmentation_tvm_nodes/src/lidar_apollo_segmentation_tvm_node.cpp +++ b/perception/lidar_apollo_segmentation_tvm_nodes/src/lidar_apollo_segmentation_tvm_node.cpp @@ -41,7 +41,7 @@ ApolloLidarSegmentationNode::ApolloLidarSegmentationNode(const rclcpp::NodeOptio declare_parameter("use_constant_feature"), declare_parameter("z_offset"), declare_parameter("min_height"), declare_parameter("max_height"), declare_parameter("objectness_thresh"), declare_parameter("min_pts_num"), - declare_parameter("height_thresh"))} + declare_parameter("height_thresh"), declare_parameter("data_path"))} { // Log unexpected versions of the neural network. auto version_status = m_detector_ptr->version_check(); From 5797ee516587d9e881f62123b0a25194bf294bd5 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 9 Nov 2023 08:09:21 +0900 Subject: [PATCH 149/202] refactor(tier4_planning_launch): align argument name (#5505) * chore(tier4_planning_launch): align arument name Signed-off-by: satoshi-ota * refactor(tier4_planning_launch): pass params directly Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../behavior_planning.launch.xml | 117 +++++++++++++++++ .../motion_planning.launch.xml | 2 +- .../config/scene_module_manager.param.yaml | 10 -- .../launch/behavior_path_planner.launch.xml | 77 +++++++++-- ...t_behavior_path_planner_node_interface.cpp | 13 ++ .../behavior_velocity_planner.param.yaml | 17 --- .../behavior_velocity_planner.launch.xml | 121 ++++++++---------- .../test/src/test_node_interface.cpp | 21 +++ 8 files changed, 275 insertions(+), 103 deletions(-) diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml index 085dc92982663..ba2318c438674 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml @@ -5,6 +5,112 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + @@ -23,6 +129,16 @@ + + + + + + + + + + @@ -66,6 +182,7 @@ + diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml index 577b0e00d133c..a8dbcfd372226 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml @@ -180,7 +180,7 @@ - + diff --git a/planning/behavior_path_planner/config/scene_module_manager.param.yaml b/planning/behavior_path_planner/config/scene_module_manager.param.yaml index 5797704e8a0ca..91e34c0e91931 100644 --- a/planning/behavior_path_planner/config/scene_module_manager.param.yaml +++ b/planning/behavior_path_planner/config/scene_module_manager.param.yaml @@ -4,7 +4,6 @@ /**: ros__parameters: external_request_lane_change_left: - enable_module: false enable_rtc: false enable_simultaneous_execution_as_approved_module: false enable_simultaneous_execution_as_candidate_module: true @@ -13,7 +12,6 @@ max_module_size: 1 external_request_lane_change_right: - enable_module: false enable_rtc: false enable_simultaneous_execution_as_approved_module: false enable_simultaneous_execution_as_candidate_module: true @@ -22,7 +20,6 @@ max_module_size: 1 lane_change_left: - enable_module: true enable_rtc: false enable_simultaneous_execution_as_approved_module: true enable_simultaneous_execution_as_candidate_module: true @@ -31,7 +28,6 @@ max_module_size: 1 lane_change_right: - enable_module: true enable_rtc: false enable_simultaneous_execution_as_approved_module: true enable_simultaneous_execution_as_candidate_module: true @@ -40,7 +36,6 @@ max_module_size: 1 start_planner: - enable_module: true enable_rtc: false enable_simultaneous_execution_as_approved_module: false enable_simultaneous_execution_as_candidate_module: false @@ -49,7 +44,6 @@ max_module_size: 1 side_shift: - enable_module: true enable_rtc: false enable_simultaneous_execution_as_approved_module: false enable_simultaneous_execution_as_candidate_module: false @@ -58,7 +52,6 @@ max_module_size: 1 goal_planner: - enable_module: true enable_rtc: false enable_simultaneous_execution_as_approved_module: false enable_simultaneous_execution_as_candidate_module: false @@ -67,7 +60,6 @@ max_module_size: 1 avoidance: - enable_module: true enable_rtc: false enable_simultaneous_execution_as_approved_module: true enable_simultaneous_execution_as_candidate_module: false @@ -76,7 +68,6 @@ max_module_size: 1 avoidance_by_lc: - enable_module: false enable_rtc: false enable_simultaneous_execution_as_approved_module: false enable_simultaneous_execution_as_candidate_module: false @@ -85,7 +76,6 @@ max_module_size: 1 dynamic_avoidance: - enable_module: false enable_rtc: false enable_simultaneous_execution_as_approved_module: true enable_simultaneous_execution_as_candidate_module: true diff --git a/planning/behavior_path_planner/launch/behavior_path_planner.launch.xml b/planning/behavior_path_planner/launch/behavior_path_planner.launch.xml index a4d3cab3c1bf0..d1dac8ad8d93e 100644 --- a/planning/behavior_path_planner/launch/behavior_path_planner.launch.xml +++ b/planning/behavior_path_planner/launch/behavior_path_planner.launch.xml @@ -1,20 +1,77 @@ + - - + + + + - - + + + + + + + + + + + + + + + + + + + + + + + + + - - + + + + + + - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp index ec2d01e44940a..423fcd2b05048 100644 --- a/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp @@ -48,6 +48,19 @@ std::shared_ptr generateNode() const auto behavior_path_planner_dir = ament_index_cpp::get_package_share_directory("behavior_path_planner"); + std::vector params; + params.emplace_back("avoidance.enable_module", true); + params.emplace_back("avoidance_by_lc.enable_module", true); + params.emplace_back("dynamic_avoidance.enable_module", true); + params.emplace_back("lane_change_right.enable_module", true); + params.emplace_back("lane_change_left.enable_module", true); + params.emplace_back("external_request_lane_change_right.enable_module", true); + params.emplace_back("external_request_lane_change_left.enable_module", true); + params.emplace_back("goal_planner.enable_module", true); + params.emplace_back("start_planner.enable_module", true); + params.emplace_back("side_shift.enable_module", true); + node_options.parameter_overrides(params); + test_utils::updateNodeOptions( node_options, {planning_test_utils_dir + "/config/test_common.param.yaml", diff --git a/planning/behavior_velocity_planner/config/behavior_velocity_planner.param.yaml b/planning/behavior_velocity_planner/config/behavior_velocity_planner.param.yaml index 276e8f8e3145a..aa51c38b55742 100644 --- a/planning/behavior_velocity_planner/config/behavior_velocity_planner.param.yaml +++ b/planning/behavior_velocity_planner/config/behavior_velocity_planner.param.yaml @@ -8,20 +8,3 @@ system_delay: 0.5 delay_response_time: 0.5 is_publish_debug_path: false # publish all debug path with lane id in each module - launch_modules: - - behavior_velocity_planner::CrosswalkModulePlugin - - behavior_velocity_planner::WalkwayModulePlugin - - behavior_velocity_planner::TrafficLightModulePlugin - - behavior_velocity_planner::IntersectionModulePlugin # Intersection module should be before merge from private to declare intersection parameters. - - behavior_velocity_planner::MergeFromPrivateModulePlugin - - behavior_velocity_planner::BlindSpotModulePlugin - - behavior_velocity_planner::DetectionAreaModulePlugin - # behavior_velocity_planner::VirtualTrafficLightModulePlugin - - behavior_velocity_planner::NoStoppingAreaModulePlugin # No stopping area module requires all the stop line. Therefore this modules should be placed at the bottom. - - behavior_velocity_planner::StopLineModulePlugin # Permanent stop line module should be after no stopping area - # behavior_velocity_planner::OcclusionSpotModulePlugin - # behavior_velocity_planner::RunOutModulePlugin - # behavior_velocity_planner::SpeedBumpModulePlugin - # behavior_velocity_planner::TemplateModulePlugin - - behavior_velocity_planner::OutOfLaneModulePlugin - - behavior_velocity_planner::NoDrivableLaneModulePlugin diff --git a/planning/behavior_velocity_planner/launch/behavior_velocity_planner.launch.xml b/planning/behavior_velocity_planner/launch/behavior_velocity_planner.launch.xml index 69d9c27331e52..46472619d5fb0 100644 --- a/planning/behavior_velocity_planner/launch/behavior_velocity_planner.launch.xml +++ b/planning/behavior_velocity_planner/launch/behavior_velocity_planner.launch.xml @@ -1,82 +1,73 @@ - - + + + + - - - - + + - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - + - + - - - + + + + + + - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + diff --git a/planning/behavior_velocity_planner/test/src/test_node_interface.cpp b/planning/behavior_velocity_planner/test/src/test_node_interface.cpp index 6756a82ca20d4..491df4c7a8766 100644 --- a/planning/behavior_velocity_planner/test/src/test_node_interface.cpp +++ b/planning/behavior_velocity_planner/test/src/test_node_interface.cpp @@ -59,6 +59,27 @@ std::shared_ptr generateNode() return package_path + "/config/" + module + ".param.yaml"; }; + std::vector module_names; + module_names.emplace_back("behavior_velocity_planner::CrosswalkModulePlugin"); + module_names.emplace_back("behavior_velocity_planner::WalkwayModulePlugin"); + module_names.emplace_back("behavior_velocity_planner::TrafficLightModulePlugin"); + module_names.emplace_back("behavior_velocity_planner::IntersectionModulePlugin"); + module_names.emplace_back("behavior_velocity_planner::MergeFromPrivateModulePlugin"); + module_names.emplace_back("behavior_velocity_planner::BlindSpotModulePlugin"); + module_names.emplace_back("behavior_velocity_planner::DetectionAreaModulePlugin"); + module_names.emplace_back("behavior_velocity_planner::VirtualTrafficLightModulePlugin"); + module_names.emplace_back("behavior_velocity_planner::NoStoppingAreaModulePlugin"); + module_names.emplace_back("behavior_velocity_planner::StopLineModulePlugin"); + module_names.emplace_back("behavior_velocity_planner::OcclusionSpotModulePlugin"); + module_names.emplace_back("behavior_velocity_planner::RunOutModulePlugin"); + module_names.emplace_back("behavior_velocity_planner::SpeedBumpModulePlugin"); + module_names.emplace_back("behavior_velocity_planner::OutOfLaneModulePlugin"); + module_names.emplace_back("behavior_velocity_planner::NoDrivableLaneModulePlugin"); + + std::vector params; + params.emplace_back("launch_modules", module_names); + node_options.parameter_overrides(params); + test_utils::updateNodeOptions( node_options, {planning_test_utils_dir + "/config/test_common.param.yaml", From 63c1dd642150dcc425b3b35b354d2660a720c80e Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Thu, 9 Nov 2023 11:55:54 +0900 Subject: [PATCH 150/202] refactor(system_error_monitor): hide error log in no-fault condition (#5522) Signed-off-by: Takamasa Horibe --- .../system_error_monitor_core.hpp | 2 ++ .../src/system_error_monitor_core.cpp | 31 ++++++++++++++----- 2 files changed, 25 insertions(+), 8 deletions(-) diff --git a/system/system_error_monitor/include/system_error_monitor/system_error_monitor_core.hpp b/system/system_error_monitor/include/system_error_monitor/system_error_monitor_core.hpp index 0bb95882700a5..4dbf8813805e3 100644 --- a/system/system_error_monitor/include/system_error_monitor/system_error_monitor_core.hpp +++ b/system/system_error_monitor/include/system_error_monitor/system_error_monitor_core.hpp @@ -148,6 +148,8 @@ class AutowareErrorMonitor : public rclcpp::Node bool canAutoRecovery() const; bool isEmergencyHoldingRequired() const; + void loggingErrors(const autoware_auto_system_msgs::msg::HazardStatus & diag_array); + std::unique_ptr logger_configure_; }; diff --git a/system/system_error_monitor/src/system_error_monitor_core.cpp b/system/system_error_monitor/src/system_error_monitor_core.cpp index e74ac9c360164..c7fdfa61f1d2c 100644 --- a/system/system_error_monitor/src/system_error_monitor_core.cpp +++ b/system/system_error_monitor/src/system_error_monitor_core.cpp @@ -140,17 +140,9 @@ diagnostic_msgs::msg::DiagnosticArray convertHazardStatusToDiagnosticArray( diag_array.status.push_back(decorateDiag(hazard_diag, "[Safe Fault]")); } for (const auto & hazard_diag : hazard_status.diag_latent_fault) { - const std::string logger_name = "system_error_monitor " + hazard_diag.name; - logThrottledNamed( - logger_name, clock, 5000, "[Latent Fault]: " + hazard_diag.message); - diag_array.status.push_back(decorateDiag(hazard_diag, "[Latent Fault]")); } for (const auto & hazard_diag : hazard_status.diag_single_point_fault) { - const std::string logger_name = "system_error_monitor " + hazard_diag.name; - logThrottledNamed( - logger_name, clock, 5000, "[Single Point Fault]: " + hazard_diag.message); - diag_array.status.push_back(decorateDiag(hazard_diag, "[Single Point Fault]")); } @@ -688,6 +680,9 @@ void AutowareErrorMonitor::publishHazardStatus( hazard_status_stamped.stamp = this->now(); hazard_status_stamped.status = hazard_status; pub_hazard_status_->publish(hazard_status_stamped); + + loggingErrors(hazard_status_stamped.status); + pub_diagnostics_err_->publish( convertHazardStatusToDiagnosticArray(this->get_clock(), hazard_status_stamped.status)); } @@ -703,3 +698,23 @@ bool AutowareErrorMonitor::onClearEmergencyService( return true; } + +void AutowareErrorMonitor::loggingErrors( + const autoware_auto_system_msgs::msg::HazardStatus & hazard_status) +{ + if (isInNoFaultCondition(*autoware_state_, *current_gate_mode_)) { + RCLCPP_DEBUG(get_logger(), "Autoware is in no-fault condition."); + return; + } + + for (const auto & hazard_diag : hazard_status.diag_latent_fault) { + const std::string logger_name = "system_error_monitor " + hazard_diag.name; + logThrottledNamed( + logger_name, get_clock(), 5000, "[Latent Fault]: " + hazard_diag.message); + } + for (const auto & hazard_diag : hazard_status.diag_single_point_fault) { + const std::string logger_name = "system_error_monitor " + hazard_diag.name; + logThrottledNamed( + logger_name, get_clock(), 5000, "[Single Point Fault]: " + hazard_diag.message); + } +} From 27f61b0ed668ded54f5f896218e45703aa9fb16a Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Thu, 9 Nov 2023 12:40:49 +0900 Subject: [PATCH 151/202] feat(behavior_path_planner): add option to insert zero velocity to the center line path (#5517) feat(behavior_path_planner): Add option to insert zero velocity to the center line path This commit adds a new boolean parameter, `insert_zero_velocity`, to the `getCenterLinePath` function in the `utils.hpp` file. When set to `true`, this parameter will insert a zero velocity to each point in the path. In the `utils.cpp` file, this option is used to insert zero velocities to the reference path generated in the `createGoalAroundPath` function. Signed-off-by: kyoichi-sugahara --- planning/behavior_path_planner/src/utils/utils.cpp | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/planning/behavior_path_planner/src/utils/utils.cpp b/planning/behavior_path_planner/src/utils/utils.cpp index 62a48da85ba2c..19c408359e5f2 100644 --- a/planning/behavior_path_planner/src/utils/utils.cpp +++ b/planning/behavior_path_planner/src/utils/utils.cpp @@ -974,9 +974,11 @@ BehaviorModuleOutput createGoalAroundPath(const std::shared_ptr(reference_path); output.reference_path = std::make_shared(reference_path); output.drivable_area_info.drivable_lanes = drivable_lanes; From 589e0a98e991d3ce78d0ab50c99862e5fd6e63a6 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Thu, 9 Nov 2023 13:56:20 +0900 Subject: [PATCH 152/202] refactor(start_planner): support new interface (#5526) Update getCurrentStatus() function in StartPlannerModule.cpp Signed-off-by: kyoichi-sugahara --- .../src/scene_module/start_planner/start_planner_module.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp index bd042f8ecef4d..77a290835fb31 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp @@ -172,7 +172,7 @@ bool StartPlannerModule::isExecutionRequested() const bool StartPlannerModule::isModuleRunning() const { - return current_state_ == ModuleStatus::RUNNING; + return getCurrentStatus() == ModuleStatus::RUNNING; } bool StartPlannerModule::isCurrentPoseOnMiddleOfTheRoad() const From a3e87cc537554e18732c0ebd86ae39d7b9d14a85 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 9 Nov 2023 14:20:23 +0900 Subject: [PATCH 153/202] refactor(goal_planner): support new interface (#5525) Signed-off-by: satoshi-ota --- .../src/scene_module/goal_planner/goal_planner_module.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index 6d34ce4ecde38..69c1fb911c4f9 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -296,7 +296,7 @@ void GoalPlannerModule::processOnExit() bool GoalPlannerModule::isExecutionRequested() const { - if (current_state_ == ModuleStatus::RUNNING) { + if (getCurrentStatus() == ModuleStatus::RUNNING) { return true; } From 0e471b3ba67c02fe3c399fe0e9c23b411fb00271 Mon Sep 17 00:00:00 2001 From: Yuqi Huai <34195403+YuqiHuai@users.noreply.github.com> Date: Wed, 8 Nov 2023 22:08:13 -0800 Subject: [PATCH 154/202] refactor(gyro_odometer): rework parameters (#5243) * refactor(gyro_odometer): rework parameters Signed-off-by: Yuqi Huai * style(pre-commit): autofix * doc(gyro_odometer): remove copyright --------- Signed-off-by: Yuqi Huai Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- localization/gyro_odometer/CMakeLists.txt | 1 + localization/gyro_odometer/README.md | 5 +-- .../config/gyro_odometer.param.yaml | 4 ++ .../launch/gyro_odometer.launch.xml | 6 +-- .../schema/gyro_odometer.schema.json | 38 +++++++++++++++++++ .../gyro_odometer/src/gyro_odometer_core.cpp | 4 +- 6 files changed, 48 insertions(+), 10 deletions(-) create mode 100644 localization/gyro_odometer/config/gyro_odometer.param.yaml create mode 100644 localization/gyro_odometer/schema/gyro_odometer.schema.json diff --git a/localization/gyro_odometer/CMakeLists.txt b/localization/gyro_odometer/CMakeLists.txt index 59a5e1121b22f..57589837dd529 100644 --- a/localization/gyro_odometer/CMakeLists.txt +++ b/localization/gyro_odometer/CMakeLists.txt @@ -32,4 +32,5 @@ endif() ament_auto_package(INSTALL_TO_SHARE launch + config ) diff --git a/localization/gyro_odometer/README.md b/localization/gyro_odometer/README.md index ec50a113af4d9..e9e390010f084 100644 --- a/localization/gyro_odometer/README.md +++ b/localization/gyro_odometer/README.md @@ -21,10 +21,7 @@ ## Parameters -| Parameter | Type | Description | -| --------------------- | ------ | -------------------------------- | -| `output_frame` | String | output's frame id | -| `message_timeout_sec` | Double | delay tolerance time for message | +{{ json_to_markdown("localization/gyro_odometer/schema/gyro_odometer.schema.json") }} ## Assumptions / Known limits diff --git a/localization/gyro_odometer/config/gyro_odometer.param.yaml b/localization/gyro_odometer/config/gyro_odometer.param.yaml new file mode 100644 index 0000000000000..420a9b0d80582 --- /dev/null +++ b/localization/gyro_odometer/config/gyro_odometer.param.yaml @@ -0,0 +1,4 @@ +/**: + ros__parameters: + output_frame: "base_link" + message_timeout_sec: 0.2 diff --git a/localization/gyro_odometer/launch/gyro_odometer.launch.xml b/localization/gyro_odometer/launch/gyro_odometer.launch.xml index aeb505270b2cc..21aff3e10d26c 100644 --- a/localization/gyro_odometer/launch/gyro_odometer.launch.xml +++ b/localization/gyro_odometer/launch/gyro_odometer.launch.xml @@ -9,8 +9,7 @@ - - + @@ -23,7 +22,6 @@ - - + diff --git a/localization/gyro_odometer/schema/gyro_odometer.schema.json b/localization/gyro_odometer/schema/gyro_odometer.schema.json new file mode 100644 index 0000000000000..189df2a2f63f3 --- /dev/null +++ b/localization/gyro_odometer/schema/gyro_odometer.schema.json @@ -0,0 +1,38 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for gyro odometer", + "type": "object", + "definitions": { + "gyro_odometer": { + "type": "object", + "properties": { + "output_frame": { + "type": "string", + "description": "output's frame id", + "default": "base_link" + }, + "message_timeout_sec": { + "type": "number", + "description": "delay tolerance time for message", + "default": 0.2 + } + }, + "required": ["output_frame", "message_timeout_sec"], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/gyro_odometer" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} diff --git a/localization/gyro_odometer/src/gyro_odometer_core.cpp b/localization/gyro_odometer/src/gyro_odometer_core.cpp index c14c48ffb2046..5de0ecd7cdc0a 100644 --- a/localization/gyro_odometer/src/gyro_odometer_core.cpp +++ b/localization/gyro_odometer/src/gyro_odometer_core.cpp @@ -102,8 +102,8 @@ geometry_msgs::msg::TwistWithCovarianceStamped concatGyroAndOdometer( GyroOdometer::GyroOdometer(const rclcpp::NodeOptions & options) : Node("gyro_odometer", options), - output_frame_(declare_parameter("output_frame", "base_link")), - message_timeout_sec_(declare_parameter("message_timeout_sec", 0.2)), + output_frame_(declare_parameter("output_frame")), + message_timeout_sec_(declare_parameter("message_timeout_sec")), vehicle_twist_arrived_(false), imu_arrived_(false) { From 8cf879aa2ef6d8e6fd019db413588cd69b3948b1 Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Thu, 9 Nov 2023 15:29:56 +0900 Subject: [PATCH 155/202] refactor(ar_tag_based_localizer): refactor `ar_tag_based_localizer` (#5521) * Refactored ar_tag_based_localizer Signed-off-by: Shintaro Sakoda * Refactor ArTagBasedLocalizer class to use shorter type names Signed-off-by: Shintaro Sakoda * Fix const correctness in ar_tag_based_localizer.cpp Signed-off-by: Shintaro Sakoda * Fix position difference calculation in ArTagBasedLocalizer Signed-off-by: Shintaro Sakoda * Renamed arg name Signed-off-by: Shintaro Sakoda --------- Signed-off-by: Shintaro Sakoda --- .../ar_tag_based_localizer/package.xml | 1 + .../src/ar_tag_based_localizer.cpp | 156 ++++++++---------- .../src/ar_tag_based_localizer.hpp | 39 +++-- 3 files changed, 92 insertions(+), 104 deletions(-) diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml b/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml index c0d1b00e35d3b..a22e7b1acf6dc 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml @@ -19,6 +19,7 @@ image_transport landmark_parser lanelet2_extension + localization_util rclcpp tf2_eigen tf2_geometry_msgs diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp b/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp index 73e7b8b7e3587..bc40fb1532297 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp @@ -44,6 +44,8 @@ #include "ar_tag_based_localizer.hpp" +#include "localization_util/util_func.hpp" + #include #include #include @@ -111,18 +113,19 @@ bool ArTagBasedLocalizer::setup() /* Subscribers */ - map_bin_sub_ = this->create_subscription( + map_bin_sub_ = this->create_subscription( "~/input/lanelet2_map", rclcpp::QoS(10).durability(rclcpp::DurabilityPolicy::TransientLocal), std::bind(&ArTagBasedLocalizer::map_bin_callback, this, std::placeholders::_1)); + rclcpp::QoS qos_sub(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default)); qos_sub.best_effort(); - image_sub_ = this->create_subscription( + image_sub_ = this->create_subscription( "~/input/image", qos_sub, std::bind(&ArTagBasedLocalizer::image_callback, this, std::placeholders::_1)); - cam_info_sub_ = this->create_subscription( + cam_info_sub_ = this->create_subscription( "~/input/camera_info", qos_sub, std::bind(&ArTagBasedLocalizer::cam_info_callback, this, std::placeholders::_1)); - ekf_pose_sub_ = this->create_subscription( + ekf_pose_sub_ = this->create_subscription( "~/input/ekf_pose", qos_sub, std::bind(&ArTagBasedLocalizer::ekf_pose_callback, this, std::placeholders::_1)); @@ -132,29 +135,25 @@ bool ArTagBasedLocalizer::setup() rclcpp::QoS qos_marker = rclcpp::QoS(rclcpp::KeepLast(10)); qos_marker.transient_local(); qos_marker.reliable(); - marker_pub_ = - this->create_publisher("~/debug/marker", qos_marker); + marker_pub_ = this->create_publisher("~/debug/marker", qos_marker); rclcpp::QoS qos_pub(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default)); image_pub_ = it_->advertise("~/debug/result", 1); - pose_pub_ = this->create_publisher( - "~/output/pose_with_covariance", qos_pub); - diag_pub_ = - this->create_publisher("/diagnostics", qos_pub); + pose_pub_ = + this->create_publisher("~/output/pose_with_covariance", qos_pub); + diag_pub_ = this->create_publisher("/diagnostics", qos_pub); RCLCPP_INFO(this->get_logger(), "Setup of ar_tag_based_localizer node is successful!"); return true; } -void ArTagBasedLocalizer::map_bin_callback( - const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr & msg) +void ArTagBasedLocalizer::map_bin_callback(const HADMapBin::ConstSharedPtr & msg) { landmark_map_ = parse_landmark(msg, "apriltag_16h5", this->get_logger()); - const visualization_msgs::msg::MarkerArray marker_msg = - convert_to_marker_array_msg(landmark_map_); + const MarkerArray marker_msg = convert_to_marker_array_msg(landmark_map_); marker_pub_->publish(marker_msg); } -void ArTagBasedLocalizer::image_callback(const sensor_msgs::msg::Image::ConstSharedPtr & msg) +void ArTagBasedLocalizer::image_callback(const Image::ConstSharedPtr & msg) { if ((image_pub_.getNumSubscribers() == 0) && (pose_pub_->get_subscription_count() == 0)) { RCLCPP_DEBUG(this->get_logger(), "No subscribers, not looking for ArUco markers"); @@ -166,7 +165,7 @@ void ArTagBasedLocalizer::image_callback(const sensor_msgs::msg::Image::ConstSha return; } - builtin_interfaces::msg::Time curr_stamp = msg->header.stamp; + const builtin_interfaces::msg::Time curr_stamp = msg->header.stamp; cv_bridge::CvImagePtr cv_ptr; try { cv_ptr = cv_bridge::toCvCopy(*msg, sensor_msgs::image_encodings::RGB8); @@ -185,20 +184,20 @@ void ArTagBasedLocalizer::image_callback(const sensor_msgs::msg::Image::ConstSha // for each marker, draw info and its boundaries in the image for (const aruco::Marker & marker : markers) { - tf2::Transform tf_cam_to_marker = aruco_marker_to_tf2(marker); + const tf2::Transform tf_cam_to_marker = aruco_marker_to_tf2(marker); - geometry_msgs::msg::TransformStamped tf_cam_to_marker_stamped; + TransformStamped tf_cam_to_marker_stamped; tf2::toMsg(tf_cam_to_marker, tf_cam_to_marker_stamped.transform); tf_cam_to_marker_stamped.header.stamp = curr_stamp; tf_cam_to_marker_stamped.header.frame_id = msg->header.frame_id; tf_cam_to_marker_stamped.child_frame_id = "detected_marker_" + std::to_string(marker.id); tf_broadcaster_->sendTransform(tf_cam_to_marker_stamped); - geometry_msgs::msg::PoseStamped pose_cam_to_marker; + PoseStamped pose_cam_to_marker; tf2::toMsg(tf_cam_to_marker, pose_cam_to_marker.pose); pose_cam_to_marker.header.stamp = curr_stamp; - pose_cam_to_marker.header.frame_id = std::to_string(marker.id); - publish_pose_as_base_link(pose_cam_to_marker, msg->header.frame_id); + pose_cam_to_marker.header.frame_id = msg->header.frame_id; + publish_pose_as_base_link(pose_cam_to_marker, std::to_string(marker.id)); // drawing the detected markers marker.draw(in_image, cv::Scalar(0, 0, 255), 2); @@ -240,7 +239,7 @@ void ArTagBasedLocalizer::image_callback(const sensor_msgs::msg::Image::ConstSha key_value.value = std::to_string(detected_tags); diag_status.values.push_back(key_value); - diagnostic_msgs::msg::DiagnosticArray diag_msg; + DiagnosticArray diag_msg; diag_msg.header.stamp = this->now(); diag_msg.status.push_back(diag_status); @@ -248,17 +247,13 @@ void ArTagBasedLocalizer::image_callback(const sensor_msgs::msg::Image::ConstSha } // wait for one camera info, then shut down that subscriber -void ArTagBasedLocalizer::cam_info_callback(const sensor_msgs::msg::CameraInfo & msg) +void ArTagBasedLocalizer::cam_info_callback(const CameraInfo & msg) { if (cam_info_received_) { return; } cv::Mat camera_matrix(3, 4, CV_64FC1, 0.0); - cv::Mat distortion_coeff(4, 1, CV_64FC1); - cv::Size size(static_cast(msg.width), static_cast(msg.height)); - - camera_matrix.setTo(0); camera_matrix.at(0, 0) = msg.p[0]; camera_matrix.at(0, 1) = msg.p[1]; camera_matrix.at(0, 2) = msg.p[2]; @@ -272,111 +267,88 @@ void ArTagBasedLocalizer::cam_info_callback(const sensor_msgs::msg::CameraInfo & camera_matrix.at(2, 2) = msg.p[10]; camera_matrix.at(2, 3) = msg.p[11]; + cv::Mat distortion_coeff(4, 1, CV_64FC1); for (int i = 0; i < 4; ++i) { distortion_coeff.at(i, 0) = 0; } + const cv::Size size(static_cast(msg.width), static_cast(msg.height)); + cam_param_ = aruco::CameraParameters(camera_matrix, distortion_coeff, size); cam_info_received_ = true; } -void ArTagBasedLocalizer::ekf_pose_callback( - const geometry_msgs::msg::PoseWithCovarianceStamped & msg) +void ArTagBasedLocalizer::ekf_pose_callback(const PoseWithCovarianceStamped & msg) { latest_ekf_pose_ = msg; } void ArTagBasedLocalizer::publish_pose_as_base_link( - const geometry_msgs::msg::PoseStamped & msg, const std::string & camera_frame_id) + const PoseStamped & sensor_to_tag, const std::string & tag_id) { - // Check if frame_id is in target_tag_ids - if ( - std::find(target_tag_ids_.begin(), target_tag_ids_.end(), msg.header.frame_id) == - target_tag_ids_.end()) { - RCLCPP_INFO_STREAM( - this->get_logger(), "frame_id(" << msg.header.frame_id << ") is not in target_tag_ids"); + // Check tag_id + if (std::find(target_tag_ids_.begin(), target_tag_ids_.end(), tag_id) == target_tag_ids_.end()) { + RCLCPP_INFO_STREAM(this->get_logger(), "tag_id(" << tag_id << ") is not in target_tag_ids"); + return; + } + if (landmark_map_.count(tag_id) == 0) { + RCLCPP_INFO_STREAM(this->get_logger(), "tag_id(" << tag_id << ") is not in landmark_map_"); return; } // Range filter - const double distance_squared = msg.pose.position.x * msg.pose.position.x + - msg.pose.position.y * msg.pose.position.y + - msg.pose.position.z * msg.pose.position.z; + const double distance_squared = sensor_to_tag.pose.position.x * sensor_to_tag.pose.position.x + + sensor_to_tag.pose.position.y * sensor_to_tag.pose.position.y + + sensor_to_tag.pose.position.z * sensor_to_tag.pose.position.z; if (distance_threshold_squared_ < distance_squared) { return; } - // Transform map to tag - if (landmark_map_.count(msg.header.frame_id) == 0) { - RCLCPP_INFO_STREAM( - this->get_logger(), "frame_id(" << msg.header.frame_id << ") is not in landmark_map_"); - return; - } - const geometry_msgs::msg::Pose & tag_pose = landmark_map_.at(msg.header.frame_id); - geometry_msgs::msg::TransformStamped map_to_tag_tf; - map_to_tag_tf.header.stamp = msg.header.stamp; - map_to_tag_tf.header.frame_id = "map"; - map_to_tag_tf.child_frame_id = msg.header.frame_id; - map_to_tag_tf.transform.translation.x = tag_pose.position.x; - map_to_tag_tf.transform.translation.y = tag_pose.position.y; - map_to_tag_tf.transform.translation.z = tag_pose.position.z; - map_to_tag_tf.transform.rotation = tag_pose.orientation; - - // Transform camera to base_link - geometry_msgs::msg::TransformStamped camera_to_base_link_tf; + // Transform to base_link + PoseStamped base_link_to_tag; try { - camera_to_base_link_tf = - tf_buffer_->lookupTransform(camera_frame_id, "base_link", tf2::TimePointZero); + const TransformStamped transform = + tf_buffer_->lookupTransform("base_link", sensor_to_tag.header.frame_id, tf2::TimePointZero); + tf2::doTransform(sensor_to_tag, base_link_to_tag, transform); + base_link_to_tag.header.frame_id = "base_link"; } catch (tf2::TransformException & ex) { RCLCPP_INFO(this->get_logger(), "Could not transform base_link to camera: %s", ex.what()); return; } - // Convert ROS Transforms to Eigen matrices for easy matrix multiplication and inversion - Eigen::Affine3d map_to_tag = tf2::transformToEigen(map_to_tag_tf.transform); - Eigen::Affine3d camera_to_base_link = tf2::transformToEigen(camera_to_base_link_tf.transform); - Eigen::Affine3d camera_to_tag = Eigen::Affine3d( - Eigen::Translation3d(msg.pose.position.x, msg.pose.position.y, msg.pose.position.z) * - Eigen::Quaterniond( - msg.pose.orientation.w, msg.pose.orientation.x, msg.pose.orientation.y, - msg.pose.orientation.z)); - Eigen::Affine3d tag_to_camera = camera_to_tag.inverse(); + // (1) map_to_tag + const Pose & map_to_tag = landmark_map_.at(tag_id); + const Eigen::Affine3d map_to_tag_affine = pose_to_affine3d(map_to_tag); - // Final pose calculation - Eigen::Affine3d map_to_base_link = map_to_tag * tag_to_camera * camera_to_base_link; + // (2) tag_to_base_link + const Eigen::Affine3d base_link_to_tag_affine = pose_to_affine3d(base_link_to_tag.pose); + const Eigen::Affine3d tag_to_base_link_affine = base_link_to_tag_affine.inverse(); - // Construct output message - geometry_msgs::msg::PoseWithCovarianceStamped pose_with_covariance_stamped; - pose_with_covariance_stamped.header.stamp = msg.header.stamp; - pose_with_covariance_stamped.header.frame_id = "map"; - pose_with_covariance_stamped.pose.pose = tf2::toMsg(map_to_base_link); + // calculate map_to_base_link + const Eigen::Affine3d map_to_base_link_affine = map_to_tag_affine * tag_to_base_link_affine; + const Pose map_to_base_link = tf2::toMsg(map_to_base_link_affine); // If latest_ekf_pose_ is older than seconds compared to current frame, it // will not be published. - const rclcpp::Duration tolerance{ - static_cast(ekf_time_tolerance_), - static_cast((ekf_time_tolerance_ - std::floor(ekf_time_tolerance_)) * 1e9)}; - if (rclcpp::Time(latest_ekf_pose_.header.stamp) + tolerance < rclcpp::Time(msg.header.stamp)) { + const rclcpp::Duration diff_time = + rclcpp::Time(sensor_to_tag.header.stamp) - rclcpp::Time(latest_ekf_pose_.header.stamp); + if (diff_time.seconds() > ekf_time_tolerance_) { RCLCPP_INFO( this->get_logger(), "latest_ekf_pose_ is older than %f seconds compared to current frame. " - "latest_ekf_pose_.header.stamp: %d.%d, msg.header.stamp: %d.%d", + "latest_ekf_pose_.header.stamp: %d.%d, sensor_to_tag.header.stamp: %d.%d", ekf_time_tolerance_, latest_ekf_pose_.header.stamp.sec, latest_ekf_pose_.header.stamp.nanosec, - msg.header.stamp.sec, msg.header.stamp.nanosec); + sensor_to_tag.header.stamp.sec, sensor_to_tag.header.stamp.nanosec); return; } // If curr_pose differs from latest_ekf_pose_ by more than , it will not // be published. - const geometry_msgs::msg::Pose curr_pose = pose_with_covariance_stamped.pose.pose; - const geometry_msgs::msg::Pose latest_ekf_pose = latest_ekf_pose_.pose.pose; - const double diff_x = curr_pose.position.x - latest_ekf_pose.position.x; - const double diff_y = curr_pose.position.y - latest_ekf_pose.position.y; - const double diff_z = curr_pose.position.z - latest_ekf_pose.position.z; - const double diff_distance_squared = diff_x * diff_x + diff_y * diff_y + diff_z * diff_z; - const double threshold = ekf_position_tolerance_ * ekf_position_tolerance_; - if (threshold < diff_distance_squared) { + const Pose curr_pose = map_to_base_link; + const Pose latest_ekf_pose = latest_ekf_pose_.pose.pose; + const double diff_position = norm(curr_pose.position, latest_ekf_pose.position); + if (diff_position > ekf_position_tolerance_) { RCLCPP_INFO( this->get_logger(), "curr_pose differs from latest_ekf_pose_ by more than %f m. " @@ -386,6 +358,12 @@ void ArTagBasedLocalizer::publish_pose_as_base_link( return; } + // Construct output message + PoseWithCovarianceStamped pose_with_covariance_stamped; + pose_with_covariance_stamped.header.stamp = sensor_to_tag.header.stamp; + pose_with_covariance_stamped.header.frame_id = "map"; + pose_with_covariance_stamped.pose.pose = curr_pose; + // ~5[m]: base_covariance // 5~[m]: scaling base_covariance by std::pow(distance/5, 3) const double distance = std::sqrt(distance_squared); diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.hpp b/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.hpp index 6bd66eead653f..fe33a64b995a3 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.hpp +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.hpp @@ -66,17 +66,26 @@ class ArTagBasedLocalizer : public rclcpp::Node { + using HADMapBin = autoware_auto_mapping_msgs::msg::HADMapBin; + using Image = sensor_msgs::msg::Image; + using CameraInfo = sensor_msgs::msg::CameraInfo; + using Pose = geometry_msgs::msg::Pose; + using PoseStamped = geometry_msgs::msg::PoseStamped; + using PoseWithCovarianceStamped = geometry_msgs::msg::PoseWithCovarianceStamped; + using TransformStamped = geometry_msgs::msg::TransformStamped; + using MarkerArray = visualization_msgs::msg::MarkerArray; + using DiagnosticArray = diagnostic_msgs::msg::DiagnosticArray; + public: explicit ArTagBasedLocalizer(const rclcpp::NodeOptions & options = rclcpp::NodeOptions()); bool setup(); private: - void map_bin_callback(const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr & msg); - void image_callback(const sensor_msgs::msg::Image::ConstSharedPtr & msg); - void cam_info_callback(const sensor_msgs::msg::CameraInfo & msg); - void ekf_pose_callback(const geometry_msgs::msg::PoseWithCovarianceStamped & msg); - void publish_pose_as_base_link( - const geometry_msgs::msg::PoseStamped & msg, const std::string & camera_frame_id); + void map_bin_callback(const HADMapBin::ConstSharedPtr & msg); + void image_callback(const Image::ConstSharedPtr & msg); + void cam_info_callback(const CameraInfo & msg); + void ekf_pose_callback(const PoseWithCovarianceStamped & msg); + void publish_pose_as_base_link(const PoseStamped & sensor_to_tag, const std::string & tag_id); static tf2::Transform aruco_marker_to_tf2(const aruco::Marker & marker); // Parameters @@ -96,23 +105,23 @@ class ArTagBasedLocalizer : public rclcpp::Node std::unique_ptr it_; // Subscribers - rclcpp::Subscription::SharedPtr map_bin_sub_; - rclcpp::Subscription::SharedPtr image_sub_; - rclcpp::Subscription::SharedPtr cam_info_sub_; - rclcpp::Subscription::SharedPtr ekf_pose_sub_; + rclcpp::Subscription::SharedPtr map_bin_sub_; + rclcpp::Subscription::SharedPtr image_sub_; + rclcpp::Subscription::SharedPtr cam_info_sub_; + rclcpp::Subscription::SharedPtr ekf_pose_sub_; // Publishers - rclcpp::Publisher::SharedPtr marker_pub_; + rclcpp::Publisher::SharedPtr marker_pub_; image_transport::Publisher image_pub_; - rclcpp::Publisher::SharedPtr pose_pub_; - rclcpp::Publisher::SharedPtr diag_pub_; + rclcpp::Publisher::SharedPtr pose_pub_; + rclcpp::Publisher::SharedPtr diag_pub_; // Others aruco::MarkerDetector detector_; aruco::CameraParameters cam_param_; bool cam_info_received_; - geometry_msgs::msg::PoseWithCovarianceStamped latest_ekf_pose_{}; - std::map landmark_map_; + PoseWithCovarianceStamped latest_ekf_pose_{}; + std::map landmark_map_; }; #endif // AR_TAG_BASED_LOCALIZER_HPP_ From 26fdcf59b80654334653924c8d3943e096b0fd0c Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Thu, 9 Nov 2023 16:43:11 +0900 Subject: [PATCH 156/202] refactor(motion_utils): fix typo in calcLongitudinalOffsetPose return (#5528) Fix typo in calcLongitudinalOffsetPose return statement Signed-off-by: kyoichi-sugahara --- .../motion_utils/include/motion_utils/trajectory/trajectory.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/common/motion_utils/include/motion_utils/trajectory/trajectory.hpp b/common/motion_utils/include/motion_utils/trajectory/trajectory.hpp index 5d773c5be32d9..61dc65c5ea3f2 100644 --- a/common/motion_utils/include/motion_utils/trajectory/trajectory.hpp +++ b/common/motion_utils/include/motion_utils/trajectory/trajectory.hpp @@ -1251,7 +1251,7 @@ calcLongitudinalOffsetPose boost::optional calcLongitudinalOffsetPose( From 20ad7c2e092773b039006fd615f361e749c2c64b Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Thu, 9 Nov 2023 17:29:28 +0900 Subject: [PATCH 157/202] fix(simple_planning_simulator): set ego pitch to 0 if road slope is not simulated (#5501) set ego pitch to 0 if road slope is not simulated Signed-off-by: Daniel Sanchez --- .../simple_planning_simulator_core.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp index d7e25860c8abf..f2629a0586045 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp @@ -326,9 +326,9 @@ void SimplePlanningSimulator::on_timer() } // calculate longitudinal acceleration by slope - const double ego_pitch_angle = calculate_ego_pitch(); - const double acc_by_slope = - enable_road_slope_simulation_ ? -9.81 * std::sin(ego_pitch_angle) : 0.0; + constexpr double gravity_acceleration = -9.81; + const double ego_pitch_angle = enable_road_slope_simulation_ ? calculate_ego_pitch() : 0.0; + const double acc_by_slope = gravity_acceleration * std::sin(ego_pitch_angle); // update vehicle dynamics { From 4f2d5132a85ba366d53eb87f8d482f5ed47f0286 Mon Sep 17 00:00:00 2001 From: Yamato Ando Date: Thu, 9 Nov 2023 18:23:52 +0900 Subject: [PATCH 158/202] fix(ndt_scan_matcher): delete diagnostics thread (#5532) Signed-off-by: yamato-ando Co-authored-by: yamato-ando --- .../ndt_scan_matcher/map_update_module.hpp | 4 +- .../ndt_scan_matcher_core.hpp | 4 +- .../src/map_update_module.cpp | 4 +- .../src/ndt_scan_matcher_core.cpp | 142 ++++++++---------- 4 files changed, 68 insertions(+), 86 deletions(-) diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp index 13721c03ca22e..78052cb8198a3 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp @@ -51,8 +51,7 @@ class MapUpdateModule rclcpp::Node * node, std::mutex * ndt_ptr_mutex, std::shared_ptr ndt_ptr, std::shared_ptr tf2_listener_module, std::string map_frame, - rclcpp::CallbackGroup::SharedPtr main_callback_group, - std::shared_ptr> state_ptr); + rclcpp::CallbackGroup::SharedPtr main_callback_group); private: friend class NDTScanMatcher; @@ -82,7 +81,6 @@ class MapUpdateModule rclcpp::Logger logger_; rclcpp::Clock::SharedPtr clock_; std::shared_ptr tf2_listener_module_; - std::shared_ptr> state_ptr_; std::optional last_update_position_ = std::nullopt; std::optional current_position_ = std::nullopt; diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp index 9eb62230dad9e..f0d90fdfa0e08 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp @@ -132,7 +132,7 @@ class NDTScanMatcher : public rclcpp::Node const rclcpp::Time & sensor_ros_time); void add_regularization_pose(const rclcpp::Time & sensor_ros_time); - void timer_diagnostic(); + void publish_diagnostic(); rclcpp::Subscription::SharedPtr initial_pose_sub_; rclcpp::Subscription::SharedPtr sensor_points_sub_; @@ -203,8 +203,6 @@ class NDTScanMatcher : public rclcpp::Node std::mutex ndt_ptr_mtx_; std::mutex initial_pose_array_mtx_; - std::thread diagnostic_thread_; - // variables for regularization const bool regularization_enabled_; std::deque diff --git a/localization/ndt_scan_matcher/src/map_update_module.cpp b/localization/ndt_scan_matcher/src/map_update_module.cpp index 7512ae2e77a21..f0a583417fb76 100644 --- a/localization/ndt_scan_matcher/src/map_update_module.cpp +++ b/localization/ndt_scan_matcher/src/map_update_module.cpp @@ -26,15 +26,13 @@ MapUpdateModule::MapUpdateModule( rclcpp::Node * node, std::mutex * ndt_ptr_mutex, std::shared_ptr ndt_ptr, std::shared_ptr tf2_listener_module, std::string map_frame, - rclcpp::CallbackGroup::SharedPtr main_callback_group, - std::shared_ptr> state_ptr) + rclcpp::CallbackGroup::SharedPtr main_callback_group) : ndt_ptr_(std::move(ndt_ptr)), ndt_ptr_mutex_(ndt_ptr_mutex), map_frame_(std::move(map_frame)), logger_(node->get_logger()), clock_(node->get_clock()), tf2_listener_module_(std::move(tf2_listener_module)), - state_ptr_(std::move(state_ptr)), dynamic_map_loading_update_distance_( node->declare_parameter("dynamic_map_loading_update_distance")), dynamic_map_loading_map_radius_( diff --git a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp index cb66998147220..a2e89540a172f 100644 --- a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp +++ b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp @@ -280,16 +280,12 @@ NDTScanMatcher::NDTScanMatcher() &NDTScanMatcher::service_trigger_node, this, std::placeholders::_1, std::placeholders::_2), rclcpp::ServicesQoS().get_rmw_qos_profile(), main_callback_group); - diagnostic_thread_ = std::thread(&NDTScanMatcher::timer_diagnostic, this); - diagnostic_thread_.detach(); - tf2_listener_module_ = std::make_shared(this); use_dynamic_map_loading_ = this->declare_parameter("use_dynamic_map_loading"); if (use_dynamic_map_loading_) { map_update_module_ = std::make_unique( - this, &ndt_ptr_mtx_, ndt_ptr_, tf2_listener_module_, map_frame_, main_callback_group, - state_ptr_); + this, &ndt_ptr_mtx_, ndt_ptr_, tf2_listener_module_, map_frame_, main_callback_group); } else { map_module_ = std::make_unique(this, &ndt_ptr_mtx_, ndt_ptr_, main_callback_group); } @@ -297,76 +293,71 @@ NDTScanMatcher::NDTScanMatcher() logger_configure_ = std::make_unique(this); } -void NDTScanMatcher::timer_diagnostic() +void NDTScanMatcher::publish_diagnostic() { - rclcpp::Rate rate(100); - while (rclcpp::ok()) { - diagnostic_msgs::msg::DiagnosticStatus diag_status_msg; - diag_status_msg.name = "ndt_scan_matcher"; - diag_status_msg.hardware_id = ""; - - for (const auto & key_value : (*state_ptr_)) { - diagnostic_msgs::msg::KeyValue key_value_msg; - key_value_msg.key = key_value.first; - key_value_msg.value = key_value.second; - diag_status_msg.values.push_back(key_value_msg); - } - + diagnostic_msgs::msg::DiagnosticStatus diag_status_msg; + diag_status_msg.name = "ndt_scan_matcher"; + diag_status_msg.hardware_id = ""; + + for (const auto & key_value : (*state_ptr_)) { + diagnostic_msgs::msg::KeyValue key_value_msg; + key_value_msg.key = key_value.first; + key_value_msg.value = key_value.second; + diag_status_msg.values.push_back(key_value_msg); + } + + diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::OK; + diag_status_msg.message = ""; + if (state_ptr_->count("state") && (*state_ptr_)["state"] == "Initializing") { + diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; + diag_status_msg.message += "Initializing State. "; + } + if ( + state_ptr_->count("lidar_topic_delay_time_sec") && + std::stod((*state_ptr_)["lidar_topic_delay_time_sec"]) > lidar_topic_timeout_sec_) { + diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; + diag_status_msg.message += "lidar_topic_delay_time_sec exceed limit. "; + } + if ( + state_ptr_->count("skipping_publish_num") && + std::stoi((*state_ptr_)["skipping_publish_num"]) > 1 && + std::stoi((*state_ptr_)["skipping_publish_num"]) < 5) { + diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; + diag_status_msg.message += "skipping_publish_num > 1. "; + } + if ( + state_ptr_->count("skipping_publish_num") && + std::stoi((*state_ptr_)["skipping_publish_num"]) >= 5) { + diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; + diag_status_msg.message += "skipping_publish_num exceed limit. "; + } + if ( + state_ptr_->count("nearest_voxel_transformation_likelihood") && + std::stod((*state_ptr_)["nearest_voxel_transformation_likelihood"]) < + converged_param_nearest_voxel_transformation_likelihood_) { + diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; + diag_status_msg.message += "NDT score is unreliably low. "; + } + if ( + state_ptr_->count("execution_time") && + std::stod((*state_ptr_)["execution_time"]) >= critical_upper_bound_exe_time_ms_) { + diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; + diag_status_msg.message += + "NDT exe time is too long. (took " + (*state_ptr_)["execution_time"] + " [ms])"; + } + // Ignore local optimal solution + if ( + state_ptr_->count("is_local_optimal_solution_oscillation") && + std::stoi((*state_ptr_)["is_local_optimal_solution_oscillation"])) { diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::OK; - diag_status_msg.message = ""; - if (state_ptr_->count("state") && (*state_ptr_)["state"] == "Initializing") { - diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; - diag_status_msg.message += "Initializing State. "; - } - if ( - state_ptr_->count("lidar_topic_delay_time_sec") && - std::stod((*state_ptr_)["lidar_topic_delay_time_sec"]) > lidar_topic_timeout_sec_) { - diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; - diag_status_msg.message += "lidar_topic_delay_time_sec exceed limit. "; - } - if ( - state_ptr_->count("skipping_publish_num") && - std::stoi((*state_ptr_)["skipping_publish_num"]) > 1 && - std::stoi((*state_ptr_)["skipping_publish_num"]) < 5) { - diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; - diag_status_msg.message += "skipping_publish_num > 1. "; - } - if ( - state_ptr_->count("skipping_publish_num") && - std::stoi((*state_ptr_)["skipping_publish_num"]) >= 5) { - diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; - diag_status_msg.message += "skipping_publish_num exceed limit. "; - } - if ( - state_ptr_->count("nearest_voxel_transformation_likelihood") && - std::stod((*state_ptr_)["nearest_voxel_transformation_likelihood"]) < - converged_param_nearest_voxel_transformation_likelihood_) { - diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; - diag_status_msg.message += "NDT score is unreliably low. "; - } - if ( - state_ptr_->count("execution_time") && - std::stod((*state_ptr_)["execution_time"]) >= critical_upper_bound_exe_time_ms_) { - diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; - diag_status_msg.message += - "NDT exe time is too long. (took " + (*state_ptr_)["execution_time"] + " [ms])"; - } - // Ignore local optimal solution - if ( - state_ptr_->count("is_local_optimal_solution_oscillation") && - std::stoi((*state_ptr_)["is_local_optimal_solution_oscillation"])) { - diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::OK; - diag_status_msg.message = "local optimal solution oscillation occurred"; - } - - diagnostic_msgs::msg::DiagnosticArray diag_msg; - diag_msg.header.stamp = this->now(); - diag_msg.status.push_back(diag_status_msg); + diag_status_msg.message = "local optimal solution oscillation occurred"; + } - diagnostics_pub_->publish(diag_msg); + diagnostic_msgs::msg::DiagnosticArray diag_msg; + diag_msg.header.stamp = this->now(); + diag_msg.status.push_back(diag_status_msg); - rate.sleep(); - } + diagnostics_pub_->publish(diag_msg); } void NDTScanMatcher::callback_initial_pose( @@ -476,13 +467,11 @@ void NDTScanMatcher::callback_sensor_points( } // perform ndt scan matching - (*state_ptr_)["state"] = "Aligning"; const Eigen::Matrix4f initial_pose_matrix = pose_to_matrix4f(interpolator.get_current_pose().pose.pose); auto output_cloud = std::make_shared>(); ndt_ptr_->align(*output_cloud, initial_pose_matrix); const pclomp::NdtResult ndt_result = ndt_ptr_->getResult(); - (*state_ptr_)["state"] = "Sleeping"; const geometry_msgs::msg::Pose result_pose_msg = matrix4f_to_pose(ndt_result.pose); std::vector transformation_msg_array; @@ -573,6 +562,7 @@ void NDTScanMatcher::callback_sensor_points( make_float32_stamped(sensor_ros_time, no_ground_nearest_voxel_transformation_likelihood)); } + (*state_ptr_)["state"] = "Aligned"; (*state_ptr_)["transform_probability"] = std::to_string(ndt_result.transform_probability); (*state_ptr_)["nearest_voxel_transformation_likelihood"] = std::to_string(ndt_result.nearest_voxel_transformation_likelihood); @@ -584,6 +574,8 @@ void NDTScanMatcher::callback_sensor_points( (*state_ptr_)["is_local_optimal_solution_oscillation"] = "0"; } (*state_ptr_)["execution_time"] = std::to_string(exe_time); + + publish_diagnostic(); } void NDTScanMatcher::transform_sensor_measurement( @@ -859,8 +851,6 @@ void NDTScanMatcher::service_trigger_node( if (is_activated_) { std::lock_guard initial_pose_array_lock(initial_pose_array_mtx_); initial_pose_msg_ptr_array_.clear(); - } else { - (*state_ptr_)["state"] = "Initializing"; } res->success = true; } @@ -897,9 +887,7 @@ void NDTScanMatcher::service_ndt_align( return; } - (*state_ptr_)["state"] = "Aligning"; res->pose_with_covariance = align_pose(initial_pose_msg_in_map_frame); - (*state_ptr_)["state"] = "Sleeping"; res->success = true; res->pose_with_covariance.pose.covariance = req->pose_with_covariance.pose.covariance; } From 2cbd0c33fab33779dcee41eae17feb383f12b7b3 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 9 Nov 2023 19:12:48 +0900 Subject: [PATCH 159/202] refactor(dynamic_avoidance): support new interface (#5527) Signed-off-by: satoshi-ota --- .../dynamic_avoidance_module.hpp | 22 +------------------ .../dynamic_avoidance_module.cpp | 12 +++------- 2 files changed, 4 insertions(+), 30 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp index 6c522c79a8774..077e0ecec0f29 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp @@ -273,29 +273,9 @@ class DynamicAvoidanceModule : public SceneModuleInterface parameters_ = std::any_cast>(parameters); } - // TODO(someone): remove this, and use base class function - [[deprecated]] BehaviorModuleOutput run() override - { - updateData(); - - if (!isWaitingApproval()) { - return plan(); - } - - // module is waiting approval. Check it. - if (isActivated()) { - RCLCPP_DEBUG(getLogger(), "Was waiting approval, and now approved. Do plan()."); - return plan(); - } else { - RCLCPP_DEBUG(getLogger(), "keep waiting approval... Do planCandidate()."); - return planWaitingApproval(); - } - } - bool isExecutionRequested() const override; bool isExecutionReady() const override; // TODO(someone): remove this, and use base class function - [[deprecated]] ModuleStatus updateState() override; BehaviorModuleOutput plan() override; BehaviorModuleOutput planWaitingApproval() override; CandidateOutput planCandidate() const override; @@ -315,7 +295,7 @@ class DynamicAvoidanceModule : public SceneModuleInterface const double min_lon_offset; }; - bool canTransitSuccessState() override { return false; } + bool canTransitSuccessState() override; bool canTransitFailureState() override { return false; } diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp index 2c5e78a267d5a..7aba1d1b2d97f 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp @@ -251,7 +251,7 @@ bool DynamicAvoidanceModule::isExecutionRequested() const } // check if the planner is already running - if (current_state_ == ModuleStatus::RUNNING) { + if (getCurrentStatus() == ModuleStatus::RUNNING) { return true; } @@ -279,15 +279,9 @@ void DynamicAvoidanceModule::updateData() } } -ModuleStatus DynamicAvoidanceModule::updateState() +bool DynamicAvoidanceModule::canTransitSuccessState() { - const bool has_avoidance_target = !target_objects_.empty(); - - if (!has_avoidance_target) { - return ModuleStatus::SUCCESS; - } - - return ModuleStatus::RUNNING; + return target_objects_.empty(); } BehaviorModuleOutput DynamicAvoidanceModule::plan() From c4ca645cbbd0a7b919ba1c2cdf78742bb81b87b5 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 9 Nov 2023 20:52:26 +0900 Subject: [PATCH 160/202] refactor(mission_planner): use combineLaneletsShape in lanelet2_extension (#5535) Signed-off-by: kosuke55 --- .../src/lanelet2_plugins/default_planner.cpp | 4 +-- .../lanelet2_plugins/utility_functions.cpp | 33 ------------------- .../lanelet2_plugins/utility_functions.hpp | 1 - 3 files changed, 2 insertions(+), 36 deletions(-) diff --git a/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp b/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp index 673519b6f7a0e..0fce63827b5e7 100644 --- a/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp +++ b/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp @@ -288,7 +288,7 @@ bool DefaultPlanner::check_goal_footprint( lanelet::ConstLanelets lanelets; lanelets.push_back(combined_prev_lanelet); lanelets.push_back(next_lane); - lanelet::ConstLanelet combined_lanelets = combine_lanelets(lanelets); + lanelet::ConstLanelet combined_lanelets = lanelet::utils::combineLaneletsShape(lanelets); // if next lanelet length longer than vehicle longitudinal offset if (vehicle_info_.max_longitudinal_offset_m + search_margin < next_lane_length) { @@ -347,7 +347,7 @@ bool DefaultPlanner::is_goal_valid( double next_lane_length = 0.0; // combine calculated route lanelets - lanelet::ConstLanelet combined_prev_lanelet = combine_lanelets(path_lanelets); + lanelet::ConstLanelet combined_prev_lanelet = lanelet::utils::combineLaneletsShape(path_lanelets); // check if goal footprint exceeds lane when the goal isn't in parking_lot if ( diff --git a/planning/mission_planner/src/lanelet2_plugins/utility_functions.cpp b/planning/mission_planner/src/lanelet2_plugins/utility_functions.cpp index 690a864fcdacd..126c673108b3c 100644 --- a/planning/mission_planner/src/lanelet2_plugins/utility_functions.cpp +++ b/planning/mission_planner/src/lanelet2_plugins/utility_functions.cpp @@ -54,39 +54,6 @@ void insert_marker_array( a1->markers.insert(a1->markers.end(), a2.markers.begin(), a2.markers.end()); } -lanelet::ConstLanelet combine_lanelets(const lanelet::ConstLanelets & lanelets) -{ - lanelet::Points3d lefts; - lanelet::Points3d rights; - lanelet::Points3d centers; - std::vector left_bound_ids; - std::vector right_bound_ids; - - for (const auto & llt : lanelets) { - if (llt.id() != 0) { - left_bound_ids.push_back(llt.leftBound().id()); - right_bound_ids.push_back(llt.rightBound().id()); - } - } - - for (const auto & llt : lanelets) { - if (std::count(right_bound_ids.begin(), right_bound_ids.end(), llt.leftBound().id()) < 1) { - for (const auto & pt : llt.leftBound()) { - lefts.push_back(lanelet::Point3d(pt)); - } - } - if (std::count(left_bound_ids.begin(), left_bound_ids.end(), llt.rightBound().id()) < 1) { - for (const auto & pt : llt.rightBound()) { - rights.push_back(lanelet::Point3d(pt)); - } - } - } - const auto left_bound = lanelet::LineString3d(lanelet::InvalId, lefts); - const auto right_bound = lanelet::LineString3d(lanelet::InvalId, rights); - auto combined_lanelet = lanelet::Lanelet(lanelet::InvalId, left_bound, right_bound); - return std::move(combined_lanelet); -} - std::vector convertCenterlineToPoints(const lanelet::Lanelet & lanelet) { std::vector centerline_points; diff --git a/planning/mission_planner/src/lanelet2_plugins/utility_functions.hpp b/planning/mission_planner/src/lanelet2_plugins/utility_functions.hpp index 3ea6237f38501..df9d42bab9444 100644 --- a/planning/mission_planner/src/lanelet2_plugins/utility_functions.hpp +++ b/planning/mission_planner/src/lanelet2_plugins/utility_functions.hpp @@ -49,7 +49,6 @@ void set_color(std_msgs::msg::ColorRGBA * cl, double r, double g, double b, doub void insert_marker_array( visualization_msgs::msg::MarkerArray * a1, const visualization_msgs::msg::MarkerArray & a2); -lanelet::ConstLanelet combine_lanelets(const lanelet::ConstLanelets & lanelets); std::vector convertCenterlineToPoints(const lanelet::Lanelet & lanelet); geometry_msgs::msg::Pose convertBasicPoint3dToPose( const lanelet::BasicPoint3d & point, const double lane_yaw); From bff877c695f91aa12a3bfe1ea9465b946d887bbb Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Thu, 9 Nov 2023 21:03:50 +0900 Subject: [PATCH 161/202] feat(controller): publish processing time (#5537) Signed-off-by: Takamasa Horibe --- .../controller_node.hpp | 10 ++++++++++ .../src/controller_node.cpp | 18 ++++++++++++++++++ 2 files changed, 28 insertions(+) diff --git a/control/trajectory_follower_node/include/trajectory_follower_node/controller_node.hpp b/control/trajectory_follower_node/include/trajectory_follower_node/controller_node.hpp index c108bec2671b3..cc43da7114630 100644 --- a/control/trajectory_follower_node/include/trajectory_follower_node/controller_node.hpp +++ b/control/trajectory_follower_node/include/trajectory_follower_node/controller_node.hpp @@ -20,6 +20,7 @@ #include "tf2_ros/buffer.h" #include "tf2_ros/transform_listener.h" #include "tier4_autoware_utils/ros/logger_level_configure.hpp" +#include "tier4_autoware_utils/system/stop_watch.hpp" #include "trajectory_follower_base/lateral_controller_base.hpp" #include "trajectory_follower_base/longitudinal_controller_base.hpp" #include "trajectory_follower_node/visibility_control.hpp" @@ -38,6 +39,7 @@ #include "nav_msgs/msg/odometry.hpp" #include "tf2_msgs/msg/tf_message.hpp" #include "visualization_msgs/msg/marker_array.hpp" +#include #include #include @@ -52,6 +54,8 @@ namespace trajectory_follower_node { using autoware_adapi_v1_msgs::msg::OperationModeState; +using tier4_autoware_utils::StopWatch; +using tier4_debug_msgs::msg::Float64Stamped; namespace trajectory_follower = ::autoware::motion::control::trajectory_follower; @@ -78,6 +82,8 @@ class TRAJECTORY_FOLLOWER_PUBLIC Controller : public rclcpp::Node rclcpp::Subscription::SharedPtr sub_operation_mode_; rclcpp::Publisher::SharedPtr control_cmd_pub_; + rclcpp::Publisher::SharedPtr pub_processing_time_lat_ms_; + rclcpp::Publisher::SharedPtr pub_processing_time_lon_ms_; rclcpp::Publisher::SharedPtr debug_marker_pub_; autoware_auto_planning_msgs::msg::Trajectory::SharedPtr current_trajectory_ptr_; @@ -114,6 +120,10 @@ class TRAJECTORY_FOLLOWER_PUBLIC Controller : public rclcpp::Node const trajectory_follower::LateralOutput & lat_out) const; std::unique_ptr logger_configure_; + + void publishProcessingTime( + const double t_ms, const rclcpp::Publisher::SharedPtr pub); + StopWatch stop_watch_; }; } // namespace trajectory_follower_node } // namespace autoware::motion::control diff --git a/control/trajectory_follower_node/src/controller_node.cpp b/control/trajectory_follower_node/src/controller_node.cpp index e35848e9495af..322aa9eef5a79 100644 --- a/control/trajectory_follower_node/src/controller_node.cpp +++ b/control/trajectory_follower_node/src/controller_node.cpp @@ -75,6 +75,10 @@ Controller::Controller(const rclcpp::NodeOptions & node_options) : Node("control [this](const OperationModeState::SharedPtr msg) { current_operation_mode_ptr_ = msg; }); control_cmd_pub_ = create_publisher( "~/output/control_cmd", rclcpp::QoS{1}.transient_local()); + pub_processing_time_lat_ms_ = + create_publisher("~/lateral/debug/processing_time_ms", 1); + pub_processing_time_lon_ms_ = + create_publisher("~/longitudinal/debug/processing_time_ms", 1); debug_marker_pub_ = create_publisher("~/output/debug_marker", rclcpp::QoS{1}); @@ -205,8 +209,13 @@ void Controller::callbackTimerControl() } // 3. run controllers + stop_watch_.tic("lateral"); const auto lat_out = lateral_controller_->run(*input_data); + publishProcessingTime(stop_watch_.toc("lateral"), pub_processing_time_lat_ms_); + + stop_watch_.tic("longitudinal"); const auto lon_out = longitudinal_controller_->run(*input_data); + publishProcessingTime(stop_watch_.toc("longitudinal"), pub_processing_time_lon_ms_); // 4. sync with each other controllers longitudinal_controller_->sync(lat_out.sync_data); @@ -254,6 +263,15 @@ void Controller::publishDebugMarker( debug_marker_pub_->publish(debug_marker_array); } +void Controller::publishProcessingTime( + const double t_ms, const rclcpp::Publisher::SharedPtr pub) +{ + Float64Stamped msg{}; + msg.stamp = this->now(); + msg.data = t_ms; + pub->publish(msg); +} + } // namespace autoware::motion::control::trajectory_follower_node #include "rclcpp_components/register_node_macro.hpp" From 4db9fc5231c530d8ad15ea46050f3adc7fdfaade Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Fri, 10 Nov 2023 03:31:22 +0900 Subject: [PATCH 162/202] fix(mission_planner): revert "refactor(mission_planner): use combineLaneletsShape in lanele2_extension (#5535)" (#5543) Revert "refactor(mission_planner): use combineLaneletsShape in lanelet2_extension (#5535)" This reverts commit c4ca645cbbd0a7b919ba1c2cdf78742bb81b87b5. --- .../src/lanelet2_plugins/default_planner.cpp | 4 +-- .../lanelet2_plugins/utility_functions.cpp | 33 +++++++++++++++++++ .../lanelet2_plugins/utility_functions.hpp | 1 + 3 files changed, 36 insertions(+), 2 deletions(-) diff --git a/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp b/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp index 0fce63827b5e7..673519b6f7a0e 100644 --- a/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp +++ b/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp @@ -288,7 +288,7 @@ bool DefaultPlanner::check_goal_footprint( lanelet::ConstLanelets lanelets; lanelets.push_back(combined_prev_lanelet); lanelets.push_back(next_lane); - lanelet::ConstLanelet combined_lanelets = lanelet::utils::combineLaneletsShape(lanelets); + lanelet::ConstLanelet combined_lanelets = combine_lanelets(lanelets); // if next lanelet length longer than vehicle longitudinal offset if (vehicle_info_.max_longitudinal_offset_m + search_margin < next_lane_length) { @@ -347,7 +347,7 @@ bool DefaultPlanner::is_goal_valid( double next_lane_length = 0.0; // combine calculated route lanelets - lanelet::ConstLanelet combined_prev_lanelet = lanelet::utils::combineLaneletsShape(path_lanelets); + lanelet::ConstLanelet combined_prev_lanelet = combine_lanelets(path_lanelets); // check if goal footprint exceeds lane when the goal isn't in parking_lot if ( diff --git a/planning/mission_planner/src/lanelet2_plugins/utility_functions.cpp b/planning/mission_planner/src/lanelet2_plugins/utility_functions.cpp index 126c673108b3c..690a864fcdacd 100644 --- a/planning/mission_planner/src/lanelet2_plugins/utility_functions.cpp +++ b/planning/mission_planner/src/lanelet2_plugins/utility_functions.cpp @@ -54,6 +54,39 @@ void insert_marker_array( a1->markers.insert(a1->markers.end(), a2.markers.begin(), a2.markers.end()); } +lanelet::ConstLanelet combine_lanelets(const lanelet::ConstLanelets & lanelets) +{ + lanelet::Points3d lefts; + lanelet::Points3d rights; + lanelet::Points3d centers; + std::vector left_bound_ids; + std::vector right_bound_ids; + + for (const auto & llt : lanelets) { + if (llt.id() != 0) { + left_bound_ids.push_back(llt.leftBound().id()); + right_bound_ids.push_back(llt.rightBound().id()); + } + } + + for (const auto & llt : lanelets) { + if (std::count(right_bound_ids.begin(), right_bound_ids.end(), llt.leftBound().id()) < 1) { + for (const auto & pt : llt.leftBound()) { + lefts.push_back(lanelet::Point3d(pt)); + } + } + if (std::count(left_bound_ids.begin(), left_bound_ids.end(), llt.rightBound().id()) < 1) { + for (const auto & pt : llt.rightBound()) { + rights.push_back(lanelet::Point3d(pt)); + } + } + } + const auto left_bound = lanelet::LineString3d(lanelet::InvalId, lefts); + const auto right_bound = lanelet::LineString3d(lanelet::InvalId, rights); + auto combined_lanelet = lanelet::Lanelet(lanelet::InvalId, left_bound, right_bound); + return std::move(combined_lanelet); +} + std::vector convertCenterlineToPoints(const lanelet::Lanelet & lanelet) { std::vector centerline_points; diff --git a/planning/mission_planner/src/lanelet2_plugins/utility_functions.hpp b/planning/mission_planner/src/lanelet2_plugins/utility_functions.hpp index df9d42bab9444..3ea6237f38501 100644 --- a/planning/mission_planner/src/lanelet2_plugins/utility_functions.hpp +++ b/planning/mission_planner/src/lanelet2_plugins/utility_functions.hpp @@ -49,6 +49,7 @@ void set_color(std_msgs::msg::ColorRGBA * cl, double r, double g, double b, doub void insert_marker_array( visualization_msgs::msg::MarkerArray * a1, const visualization_msgs::msg::MarkerArray & a2); +lanelet::ConstLanelet combine_lanelets(const lanelet::ConstLanelets & lanelets); std::vector convertCenterlineToPoints(const lanelet::Lanelet & lanelet); geometry_msgs::msg::Pose convertBasicPoint3dToPose( const lanelet::BasicPoint3d & point, const double lane_yaw); From 32c897d54dc4fd84e4d5e401334d587b19c1318c Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 10 Nov 2023 13:50:16 +0900 Subject: [PATCH 163/202] fix(tier4_planning_launch): obstacle_cruise_planner pipeline is not connected (#5542) Signed-off-by: Takayuki Murooka --- .../lane_driving/motion_planning/motion_planning.launch.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml index a8dbcfd372226..18de04fd9e317 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml @@ -127,8 +127,8 @@ - - + + From ce0f11ab2f688f69a89c178b64c34f68de44f985 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Fri, 10 Nov 2023 15:19:46 +0900 Subject: [PATCH 164/202] fix(image_projection_based_fusion): add missing install (#5548) --- perception/image_projection_based_fusion/CMakeLists.txt | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/perception/image_projection_based_fusion/CMakeLists.txt b/perception/image_projection_based_fusion/CMakeLists.txt index 53aafa44b75d6..c021dd92dae64 100644 --- a/perception/image_projection_based_fusion/CMakeLists.txt +++ b/perception/image_projection_based_fusion/CMakeLists.txt @@ -146,6 +146,10 @@ if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL) EXECUTABLE pointpainting_fusion_node ) + install( + TARGETS pointpainting_cuda_lib + DESTINATION lib + ) else() message("Skipping build of some nodes due to missing dependencies") endif() From 9000f430c937764c14e43109539302f1f878ed70 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Fri, 10 Nov 2023 17:36:41 +0900 Subject: [PATCH 165/202] perf(motion_utils): faster removeOverlapPoints and calcLateralOffset functions (#5385) Signed-off-by: Maxime CLEMENT --- .../motion_utils/trajectory/trajectory.hpp | 1 + .../benchmark_calcLateralOffset.cpp | 77 +++++++++++++++++++ 2 files changed, 78 insertions(+) create mode 100644 common/motion_utils/test/src/trajectory/benchmark_calcLateralOffset.cpp diff --git a/common/motion_utils/include/motion_utils/trajectory/trajectory.hpp b/common/motion_utils/include/motion_utils/trajectory/trajectory.hpp index 61dc65c5ea3f2..f4f9f45935347 100644 --- a/common/motion_utils/include/motion_utils/trajectory/trajectory.hpp +++ b/common/motion_utils/include/motion_utils/trajectory/trajectory.hpp @@ -168,6 +168,7 @@ T removeOverlapPoints(const T & points, const size_t start_idx = 0) } T dst; + dst.reserve(points.size()); for (size_t i = 0; i <= start_idx; ++i) { dst.push_back(points.at(i)); diff --git a/common/motion_utils/test/src/trajectory/benchmark_calcLateralOffset.cpp b/common/motion_utils/test/src/trajectory/benchmark_calcLateralOffset.cpp new file mode 100644 index 0000000000000..549ca4c0ae5bb --- /dev/null +++ b/common/motion_utils/test/src/trajectory/benchmark_calcLateralOffset.cpp @@ -0,0 +1,77 @@ +// 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. + +#include "motion_utils/trajectory/trajectory.hpp" + +#include +#include +#include + +#include + +namespace +{ +using autoware_auto_planning_msgs::msg::Trajectory; +using tier4_autoware_utils::createPoint; +using tier4_autoware_utils::createQuaternionFromRPY; + +constexpr double epsilon = 1e-6; + +geometry_msgs::msg::Pose createPose( + double x, double y, double z, double roll, double pitch, double yaw) +{ + geometry_msgs::msg::Pose p; + p.position = createPoint(x, y, z); + p.orientation = createQuaternionFromRPY(roll, pitch, yaw); + return p; +} + +template +T generateTestTrajectory( + const size_t num_points, const double point_interval, const double vel = 0.0, + const double init_theta = 0.0, const double delta_theta = 0.0) +{ + using Point = typename T::_points_type::value_type; + + T traj; + for (size_t i = 0; i < num_points; ++i) { + const double theta = init_theta + i * delta_theta; + const double x = i * point_interval * std::cos(theta); + const double y = i * point_interval * std::sin(theta); + + Point p; + p.pose = createPose(x, y, 0.0, 0.0, 0.0, theta); + p.longitudinal_velocity_mps = vel; + traj.points.push_back(p); + } + + return traj; +} +} // namespace + +TEST(trajectory_benchmark, DISABLED_calcLateralOffset) +{ + std::random_device r; + std::default_random_engine e1(r()); + std::uniform_real_distribution uniform_dist(0.0, 1000.0); + + using motion_utils::calcLateralOffset; + + const auto traj = generateTestTrajectory(1000, 1.0, 0.0, 0.0, 0.1); + constexpr auto nb_iteration = 10000; + for (auto i = 0; i < nb_iteration; ++i) { + const auto point = createPoint(uniform_dist(e1), uniform_dist(e1), 0.0); + calcLateralOffset(traj.points, point); + } +} From ff255eb62ff8780db527cd2d3f2355997c7ad770 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Fri, 10 Nov 2023 19:20:43 +0900 Subject: [PATCH 166/202] refactor(goal_planner): separate thread safe data (#5493) * refactor(goal_planner): separate thread safe data Signed-off-by: kosuke55 * fix style(pre-commit): autofix fix fix --------- Signed-off-by: kosuke55 --- .../goal_planner/goal_planner_module.hpp | 190 ++++++--- .../goal_planner/pull_over_planner_base.hpp | 22 ++ .../goal_planner/goal_planner_module.cpp | 360 +++++++++--------- 3 files changed, 344 insertions(+), 228 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp index df21bad862cc9..e4044d7191805 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp @@ -68,38 +68,30 @@ using behavior_path_planner::utils::path_safety_checker::SafetyCheckParams; using behavior_path_planner::utils::path_safety_checker::TargetObjectsOnLane; using tier4_autoware_utils::Polygon2d; -enum class PathType { - NONE = 0, - SHIFT, - ARC_FORWARD, - ARC_BACKWARD, - FREESPACE, -}; +#define DEFINE_SETTER(TYPE, NAME) \ +public: \ + void set_##NAME(const TYPE & value) \ + { \ + NAME##_ = value; \ + } -#define DEFINE_SETTER_GETTER(TYPE, NAME) \ -public: \ - void set_##NAME(const TYPE & value) \ - { \ - const std::lock_guard lock(mutex_); \ - NAME##_ = value; \ - } \ - \ - TYPE get_##NAME() const \ - { \ - const std::lock_guard lock(mutex_); \ - return NAME##_; \ +#define DEFINE_GETTER(TYPE, NAME) \ +public: \ + TYPE get_##NAME() const \ + { \ + return NAME##_; \ } +#define DEFINE_SETTER_GETTER(TYPE, NAME) \ + DEFINE_SETTER(TYPE, NAME) \ + DEFINE_GETTER(TYPE, NAME) + class PullOverStatus { public: - explicit PullOverStatus(std::recursive_mutex & mutex) : mutex_(mutex) {} - // Reset all data members to their initial states void reset() { - std::lock_guard lock(mutex_); - pull_over_path_ = nullptr; lane_parking_pull_over_path_ = nullptr; current_path_idx_ = 0; require_increment_ = true; @@ -109,16 +101,12 @@ class PullOverStatus pull_over_lanes_.clear(); lanes_.clear(); has_decided_path_ = false; - is_safe_static_objects_ = false; is_safe_dynamic_objects_ = false; - prev_is_safe_ = false; + prev_found_path_ = false; prev_is_safe_dynamic_objects_ = false; has_decided_velocity_ = false; - has_requested_approval_ = false; - is_ready_ = false; } - DEFINE_SETTER_GETTER(std::shared_ptr, pull_over_path) DEFINE_SETTER_GETTER(std::shared_ptr, lane_parking_pull_over_path) DEFINE_SETTER_GETTER(size_t, current_path_idx) DEFINE_SETTER_GETTER(bool, require_increment) @@ -128,24 +116,14 @@ class PullOverStatus DEFINE_SETTER_GETTER(lanelet::ConstLanelets, pull_over_lanes) DEFINE_SETTER_GETTER(std::vector, lanes) DEFINE_SETTER_GETTER(bool, has_decided_path) - DEFINE_SETTER_GETTER(bool, is_safe_static_objects) DEFINE_SETTER_GETTER(bool, is_safe_dynamic_objects) - DEFINE_SETTER_GETTER(bool, prev_is_safe) + DEFINE_SETTER_GETTER(bool, prev_found_path) DEFINE_SETTER_GETTER(bool, prev_is_safe_dynamic_objects) DEFINE_SETTER_GETTER(bool, has_decided_velocity) - DEFINE_SETTER_GETTER(bool, has_requested_approval) - DEFINE_SETTER_GETTER(bool, is_ready) - DEFINE_SETTER_GETTER(std::shared_ptr, last_increment_time) - DEFINE_SETTER_GETTER(std::shared_ptr, last_path_update_time) - DEFINE_SETTER_GETTER(std::optional, modified_goal_pose) DEFINE_SETTER_GETTER(Pose, refined_goal_pose) - DEFINE_SETTER_GETTER(GoalCandidates, goal_candidates) DEFINE_SETTER_GETTER(Pose, closest_goal_candidate_pose) - DEFINE_SETTER_GETTER(std::vector, pull_over_path_candidates) - DEFINE_SETTER_GETTER(std::optional, closest_start_pose) private: - std::shared_ptr pull_over_path_{nullptr}; std::shared_ptr lane_parking_pull_over_path_{nullptr}; size_t current_path_idx_{0}; bool require_increment_{true}; @@ -155,32 +133,134 @@ class PullOverStatus lanelet::ConstLanelets pull_over_lanes_{}; std::vector lanes_{}; bool has_decided_path_{false}; - bool is_safe_static_objects_{false}; bool is_safe_dynamic_objects_{false}; - bool prev_is_safe_{false}; + bool prev_found_path_{false}; bool prev_is_safe_dynamic_objects_{false}; bool has_decided_velocity_{false}; - bool has_requested_approval_{false}; - bool is_ready_{false}; - // save last time and pose - std::shared_ptr last_increment_time_; - std::shared_ptr last_path_update_time_; - - // goal modification - std::optional modified_goal_pose_; Pose refined_goal_pose_{}; - GoalCandidates goal_candidates_{}; Pose closest_goal_candidate_pose_{}; +}; + +#undef DEFINE_SETTER +#undef DEFINE_GETTER +#undef DEFINE_SETTER_GETTER + +#define DEFINE_SETTER_WITH_MUTEX(TYPE, NAME) \ +public: \ + void set_##NAME(const TYPE & value) \ + { \ + const std::lock_guard lock(mutex_); \ + NAME##_ = value; \ + } + +#define DEFINE_GETTER_WITH_MUTEX(TYPE, NAME) \ +public: \ + TYPE get_##NAME() const \ + { \ + const std::lock_guard lock(mutex_); \ + return NAME##_; \ + } + +#define DEFINE_SETTER_GETTER_WITH_MUTEX(TYPE, NAME) \ + DEFINE_SETTER_WITH_MUTEX(TYPE, NAME) \ + DEFINE_GETTER_WITH_MUTEX(TYPE, NAME) + +class ThreadSafeData +{ +public: + ThreadSafeData(std::recursive_mutex & mutex, rclcpp::Clock::SharedPtr clock) + : mutex_(mutex), clock_(clock) + { + } + + bool incrementPathIndex() + { + const std::lock_guard lock(mutex_); + if (pull_over_path_->incrementPathIndex()) { + last_path_idx_increment_time_ = clock_->now(); + return true; + } + return false; + } + + void set_pull_over_path(const PullOverPath & value) + { + const std::lock_guard lock(mutex_); + pull_over_path_ = std::make_shared(value); + last_path_update_time_ = clock_->now(); + } + + void set_pull_over_path(const std::shared_ptr & value) + { + const std::lock_guard lock(mutex_); + pull_over_path_ = value; + last_path_update_time_ = clock_->now(); + } + + void clearPullOverPath() + { + const std::lock_guard lock(mutex_); + pull_over_path_ = nullptr; + } + + bool foundPullOverPath() const + { + const std::lock_guard lock(mutex_); + if (!pull_over_path_) { + return false; + } + + return pull_over_path_->isValidPath(); + } + + PullOverPlannerType getPullOverPlannerType() const + { + const std::lock_guard lock(mutex_); + if (!pull_over_path_) { + return PullOverPlannerType::NONE; + } + + return pull_over_path_->type; + }; - // pull over path + void reset() + { + const std::lock_guard lock(mutex_); + pull_over_path_ = nullptr; + pull_over_path_candidates_.clear(); + goal_candidates_.clear(); + modified_goal_pose_ = std::nullopt; + last_path_update_time_ = std::nullopt; + last_path_idx_increment_time_ = std::nullopt; + closest_start_pose_ = std::nullopt; + } + + DEFINE_GETTER_WITH_MUTEX(std::shared_ptr, pull_over_path) + DEFINE_GETTER_WITH_MUTEX(std::optional, last_path_update_time) + DEFINE_GETTER_WITH_MUTEX(std::optional, last_path_idx_increment_time) + + DEFINE_SETTER_GETTER_WITH_MUTEX(std::vector, pull_over_path_candidates) + DEFINE_SETTER_GETTER_WITH_MUTEX(GoalCandidates, goal_candidates) + DEFINE_SETTER_GETTER_WITH_MUTEX(std::optional, modified_goal_pose) + DEFINE_SETTER_GETTER_WITH_MUTEX(std::optional, closest_start_pose) + +private: + std::shared_ptr pull_over_path_{nullptr}; std::vector pull_over_path_candidates_; - std::optional closest_start_pose_; + GoalCandidates goal_candidates_{}; + std::optional modified_goal_pose_; + std::optional last_path_update_time_; + std::optional last_path_idx_increment_time_; + std::optional closest_start_pose_{}; std::recursive_mutex & mutex_; + rclcpp::Clock::SharedPtr clock_; }; -#undef DEFINE_SETTER_GETTER +#undef DEFINE_SETTER_WITH_MUTEX +#undef DEFINE_GETTER_WITH_MUTEX +#undef DEFINE_SETTER_GETTER_WITH_MUTEX struct FreespacePlannerDebugData { @@ -276,6 +356,7 @@ class GoalPlannerModule : public SceneModuleInterface std::recursive_mutex mutex_; PullOverStatus status_; + ThreadSafeData thread_safe_data_; std::unique_ptr last_approval_data_{nullptr}; @@ -329,6 +410,7 @@ class GoalPlannerModule : public SceneModuleInterface bool isStuck(); bool hasDecidedPath() const; void decideVelocity(); + bool foundPullOverPath() const; // validation bool hasEnoughDistance(const PullOverPath & pull_over_path) const; @@ -352,8 +434,6 @@ class GoalPlannerModule : public SceneModuleInterface const GoalCandidates & goal_candidates) const; // deal with pull over partial paths - PathWithLaneId getCurrentPath() const; - bool incrementPathIndex(); void transitionToNextPathIfFinishingCurrentPath(); // lanes and drivable area diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp index 54bba6aee2fc2..4267261fdfe84 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp @@ -46,6 +46,7 @@ struct PullOverPath { PullOverPlannerType type{PullOverPlannerType::NONE}; std::vector partial_paths{}; + size_t path_idx{0}; // accelerate with constant acceleration to the target velocity std::vector> pairs_terminal_velocity_and_accel{}; Pose start_pose{}; @@ -84,6 +85,27 @@ struct PullOverPath return parking_path; } + + PathWithLaneId getCurrentPath() const + { + if (partial_paths.empty()) { + return PathWithLaneId{}; + } else if (partial_paths.size() <= path_idx) { + return partial_paths.back(); + } + return partial_paths.at(path_idx); + } + + bool incrementPathIndex() + { + if (partial_paths.size() - 1 <= path_idx) { + return false; + } + path_idx += 1; + return true; + } + + bool isValidPath() const { return type != PullOverPlannerType::NONE; } }; class PullOverPlannerBase diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index 69c1fb911c4f9..0475cd92f1bec 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -58,7 +58,7 @@ GoalPlannerModule::GoalPlannerModule( : SceneModuleInterface{name, node, rtc_interface_ptr_map}, parameters_{parameters}, vehicle_info_{vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo()}, - status_{mutex_} + thread_safe_data_{mutex_, clock_} { LaneDepartureChecker lane_departure_checker{}; lane_departure_checker.setVehicleInfo(vehicle_info_); @@ -138,16 +138,12 @@ void GoalPlannerModule::updateOccupancyGrid() void GoalPlannerModule::onTimer() { // already generated pull over candidate paths - if (!status_.get_pull_over_path_candidates().empty()) { + if (!thread_safe_data_.get_pull_over_path_candidates().empty()) { return; } // goals are not yet available. - if (status_.get_goal_candidates().empty()) { - return; - } - - if (!isExecutionRequested()) { + if (thread_safe_data_.get_goal_candidates().empty()) { return; } @@ -157,7 +153,11 @@ void GoalPlannerModule::onTimer() return; } - const auto goal_candidates = status_.get_goal_candidates(); + if (getCurrentStatus() == ModuleStatus::IDLE) { + return; + } + + const auto goal_candidates = thread_safe_data_.get_goal_candidates(); // generate valid pull over path candidates and calculate closest start pose const auto current_lanes = utils::getExtendedCurrentLanes( @@ -208,8 +208,8 @@ void GoalPlannerModule::onTimer() // set member variables { const std::lock_guard lock(mutex_); - status_.set_pull_over_path_candidates(path_candidates); - status_.set_closest_start_pose(closest_start_pose); + thread_safe_data_.set_pull_over_path_candidates(path_candidates); + thread_safe_data_.set_closest_start_pose(closest_start_pose); } } @@ -457,13 +457,13 @@ Pose GoalPlannerModule::calcRefinedGoal(const Pose & goal_pose) const bool GoalPlannerModule::planFreespacePath() { - goal_searcher_->setPlannerData(planner_data_); - auto goal_candidates = status_.get_goal_candidates(); - goal_searcher_->update(goal_candidates); - status_.set_goal_candidates(goal_candidates); - + GoalCandidates goal_candidates{}; { const std::lock_guard lock(mutex_); + goal_searcher_->setPlannerData(planner_data_); + goal_candidates = thread_safe_data_.get_goal_candidates(); + goal_searcher_->update(goal_candidates); + thread_safe_data_.set_goal_candidates(goal_candidates); debug_data_.freespace_planner.num_goal_candidates = goal_candidates.size(); debug_data_.freespace_planner.is_planning = true; } @@ -487,11 +487,8 @@ bool GoalPlannerModule::planFreespacePath() { const std::lock_guard lock(mutex_); - status_.set_pull_over_path(std::make_shared(*freespace_path)); - status_.set_current_path_idx(0); - status_.set_is_safe_static_objects(true); - status_.set_modified_goal_pose(goal_candidate); - status_.set_last_path_update_time(std::make_shared(clock_->now())); + thread_safe_data_.set_pull_over_path(*freespace_path); + thread_safe_data_.set_modified_goal_pose(goal_candidate); debug_data_.freespace_planner.is_planning = false; } @@ -527,14 +524,8 @@ void GoalPlannerModule::returnToLaneParking() return; } - { - const std::lock_guard lock(mutex_); - status_.set_is_safe_static_objects(true); - status_.set_has_decided_path(false); - status_.set_pull_over_path(status_.get_lane_parking_pull_over_path()); - status_.set_current_path_idx(0); - status_.set_last_path_update_time(std::make_shared(clock_->now())); - } + status_.set_has_decided_path(false); + thread_safe_data_.set_pull_over_path(status_.get_lane_parking_pull_over_path()); RCLCPP_INFO(getLogger(), "return to lane parking"); } @@ -546,7 +537,7 @@ void GoalPlannerModule::generateGoalCandidates() // with old architecture, module instance is not cleared when new route is received // so need to reset status here. // todo: move this check out of this function after old architecture is removed - if (!status_.get_goal_candidates().empty()) { + if (!thread_safe_data_.get_goal_candidates().empty()) { return; } @@ -554,21 +545,23 @@ void GoalPlannerModule::generateGoalCandidates() const Pose goal_pose = route_handler->getOriginalGoalPose(); status_.set_refined_goal_pose(calcRefinedGoal(goal_pose)); if (goal_planner_utils::isAllowedGoalModification(route_handler)) { + const std::lock_guard lock(mutex_); goal_searcher_->setPlannerData(planner_data_); goal_searcher_->setReferenceGoal(status_.get_refined_goal_pose()); - status_.set_goal_candidates(goal_searcher_->search()); + thread_safe_data_.set_goal_candidates(goal_searcher_->search()); const auto current_lanes = utils::getExtendedCurrentLanes( planner_data_, parameters_->backward_goal_search_length, parameters_->forward_goal_search_length, false); status_.set_closest_goal_candidate_pose( - goal_searcher_->getClosetGoalCandidateAlongLanes(status_.get_goal_candidates()).goal_pose); + goal_searcher_->getClosetGoalCandidateAlongLanes(thread_safe_data_.get_goal_candidates()) + .goal_pose); } else { GoalCandidate goal_candidate{}; goal_candidate.goal_pose = goal_pose; goal_candidate.distance_from_original_goal = 0.0; GoalCandidates goal_candidates{}; goal_candidates.push_back(goal_candidate); - status_.set_goal_candidates(goal_candidates); + thread_safe_data_.set_goal_candidates(goal_candidates); status_.set_closest_goal_candidate_pose(goal_pose); } } @@ -630,13 +623,13 @@ void GoalPlannerModule::selectSafePullOverPath() { const std::lock_guard lock(mutex_); goal_searcher_->setPlannerData(planner_data_); - goal_candidates = status_.get_goal_candidates(); + goal_candidates = thread_safe_data_.get_goal_candidates(); goal_searcher_->update(goal_candidates); - status_.set_goal_candidates(goal_candidates); - status_.set_pull_over_path_candidates(sortPullOverPathCandidatesByGoalPriority( - status_.get_pull_over_path_candidates(), status_.get_goal_candidates())); - pull_over_path_candidates = status_.get_pull_over_path_candidates(); - status_.set_is_safe_static_objects(false); + thread_safe_data_.set_goal_candidates(goal_candidates); + thread_safe_data_.set_pull_over_path_candidates(sortPullOverPathCandidatesByGoalPriority( + thread_safe_data_.get_pull_over_path_candidates(), thread_safe_data_.get_goal_candidates())); + pull_over_path_candidates = thread_safe_data_.get_pull_over_path_candidates(); + thread_safe_data_.clearPullOverPath(); } for (const auto & pull_over_path : pull_over_path_candidates) { @@ -660,26 +653,24 @@ void GoalPlannerModule::selectSafePullOverPath() // found safe pull over path { const std::lock_guard lock(mutex_); - status_.set_is_safe_static_objects(true); - status_.set_pull_over_path(std::make_shared(pull_over_path)); - status_.set_current_path_idx(0); - status_.set_lane_parking_pull_over_path(status_.get_pull_over_path()); - status_.set_modified_goal_pose(*goal_candidate_it); - status_.set_last_path_update_time(std::make_shared(clock_->now())); + thread_safe_data_.set_pull_over_path(pull_over_path); + thread_safe_data_.set_modified_goal_pose(*goal_candidate_it); + status_.set_lane_parking_pull_over_path(thread_safe_data_.get_pull_over_path()); } break; } - if (!status_.get_is_safe_static_objects()) { + if (!thread_safe_data_.foundPullOverPath()) { return; } // decelerate before the search area start const auto search_start_offset_pose = calcLongitudinalOffsetPose( - status_.get_pull_over_path()->getFullPath().points, status_.get_refined_goal_pose().position, + thread_safe_data_.get_pull_over_path()->getFullPath().points, + status_.get_refined_goal_pose().position, -parameters_->backward_goal_search_length - planner_data_->parameters.base_link2front - approximate_pull_over_distance_); - auto & first_path = status_.get_pull_over_path()->partial_paths.front(); + auto & first_path = thread_safe_data_.get_pull_over_path()->partial_paths.front(); if (search_start_offset_pose) { decelerateBeforeSearchStart(*search_start_offset_pose, first_path); } else { @@ -714,7 +705,7 @@ void GoalPlannerModule::setLanes() void GoalPlannerModule::setOutput(BehaviorModuleOutput & output) { - if (!status_.get_is_safe_static_objects()) { + if (!thread_safe_data_.foundPullOverPath()) { // situation : not safe against static objects use stop_path setStopPath(output); } else if ( @@ -732,7 +723,7 @@ void GoalPlannerModule::setOutput(BehaviorModuleOutput & output) } // keep stop if not enough time passed, // because it takes time for the trajectory to be reflected - auto current_path = getCurrentPath(); + auto current_path = thread_safe_data_.get_pull_over_path()->getCurrentPath(); keepStoppedWithCurrentPath(current_path); output.path = std::make_shared(current_path); @@ -751,14 +742,14 @@ void GoalPlannerModule::setOutput(BehaviorModuleOutput & output) // for the next loop setOutput(). // this is used to determine whether to generate a new stop path or keep the current stop path. const std::lock_guard lock(mutex_); - status_.set_prev_is_safe(status_.get_is_safe_static_objects()); + status_.set_prev_found_path(thread_safe_data_.foundPullOverPath()); status_.set_prev_is_safe_dynamic_objects( parameters_->safety_check_params.enable_safety_check ? isSafePath() : true); } void GoalPlannerModule::setStopPath(BehaviorModuleOutput & output) { - if (status_.get_prev_is_safe() || !status_.get_prev_stop_path()) { + if (status_.get_prev_found_path() || !status_.get_prev_stop_path()) { // safe -> not_safe or no prev_stop_path: generate new stop_path output.path = std::make_shared(generateStopPath()); const std::lock_guard lock(mutex_); @@ -766,10 +757,7 @@ void GoalPlannerModule::setStopPath(BehaviorModuleOutput & output) // set stop path as pull over path auto stop_pull_over_path = std::make_shared(); stop_pull_over_path->partial_paths.push_back(*output.path); - status_.set_pull_over_path(stop_pull_over_path); - status_.set_current_path_idx(0); - status_.set_last_path_update_time(std::make_shared(clock_->now())); - + thread_safe_data_.set_pull_over_path(stop_pull_over_path); RCLCPP_WARN_THROTTLE( getLogger(), *clock_, 5000, "Not found safe pull_over path, generate stop path"); } else { @@ -786,7 +774,7 @@ void GoalPlannerModule::setStopPathFromCurrentPath(BehaviorModuleOutput & output { // safe or not safe(no feasible stop_path found) -> not_safe: try to find new feasible stop_path if (status_.get_prev_is_safe_dynamic_objects() || !status_.get_prev_stop_path_after_approval()) { - auto current_path = getCurrentPath(); + auto current_path = thread_safe_data_.get_pull_over_path()->getCurrentPath(); const auto stop_path = behavior_path_planner::utils::start_goal_planner_common::generateFeasibleStopPath( current_path, planner_data_, *stop_pose_, parameters_->maximum_deceleration_for_stop, @@ -796,12 +784,13 @@ void GoalPlannerModule::setStopPathFromCurrentPath(BehaviorModuleOutput & output status_.set_prev_stop_path_after_approval(output.path); RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 5000, "Collision detected, generate stop path"); } else { - output.path = std::make_shared(getCurrentPath()); + output.path = + std::make_shared(thread_safe_data_.get_pull_over_path()->getCurrentPath()); RCLCPP_WARN_THROTTLE( getLogger(), *clock_, 5000, "Collision detected, no feasible stop path found, cannot stop."); } - status_.set_last_path_update_time(std::make_shared(clock_->now())); + // status_.set_last_path_update_time(std::make_shared(clock_->now())); } else { // not_safe safe(no feasible stop path found) -> not_safe: use previous stop path output.path = status_.get_prev_stop_path_after_approval(); @@ -813,7 +802,7 @@ void GoalPlannerModule::setStopPathFromCurrentPath(BehaviorModuleOutput & output void GoalPlannerModule::setDrivableAreaInfo(BehaviorModuleOutput & output) const { - if (status_.get_pull_over_path()->type == PullOverPlannerType::FREESPACE) { + if (thread_safe_data_.getPullOverPlannerType() == PullOverPlannerType::FREESPACE) { const double drivable_area_margin = planner_data_->parameters.vehicle_width; output.drivable_area_info.drivable_margin = planner_data_->parameters.vehicle_width / 2.0 + drivable_area_margin; @@ -831,10 +820,10 @@ void GoalPlannerModule::setDrivableAreaInfo(BehaviorModuleOutput & output) const void GoalPlannerModule::setModifiedGoal(BehaviorModuleOutput & output) const { const auto & route_handler = planner_data_->route_handler; - if (status_.get_is_safe_static_objects()) { + if (thread_safe_data_.foundPullOverPath()) { PoseWithUuidStamped modified_goal{}; modified_goal.uuid = route_handler->getRouteUuid(); - modified_goal.pose = status_.get_modified_goal_pose()->goal_pose; + modified_goal.pose = thread_safe_data_.get_modified_goal_pose()->goal_pose; modified_goal.header = route_handler->getRouteHeader(); output.modified_goal = modified_goal; } else { @@ -879,22 +868,25 @@ bool GoalPlannerModule::hasDecidedPath() const } // if path is not safe, not decided - if (!status_.get_is_safe_static_objects()) { + if (!thread_safe_data_.foundPullOverPath()) { return false; } // if ego is sufficiently close to the start of the nearest candidate path, the path is decided const auto & current_pose = planner_data_->self_odometry->pose.pose; const auto ego_segment_idx = motion_utils::findNearestSegmentIndex( - getCurrentPath().points, current_pose, std::numeric_limits::max(), M_PI_2); + thread_safe_data_.get_pull_over_path()->getCurrentPath().points, current_pose, + std::numeric_limits::max(), M_PI_2); if (!ego_segment_idx) { return false; } const size_t start_pose_segment_idx = motion_utils::findNearestSegmentIndex( - getCurrentPath().points, status_.get_pull_over_path()->start_pose.position); + thread_safe_data_.get_pull_over_path()->getCurrentPath().points, + thread_safe_data_.get_pull_over_path()->start_pose.position); const double dist_to_parking_start_pose = calcSignedArcLength( - getCurrentPath().points, current_pose.position, *ego_segment_idx, - status_.get_pull_over_path()->start_pose.position, start_pose_segment_idx); + thread_safe_data_.get_pull_over_path()->getCurrentPath().points, current_pose.position, + *ego_segment_idx, thread_safe_data_.get_pull_over_path()->start_pose.position, + start_pose_segment_idx); return dist_to_parking_start_pose < parameters_->decide_path_distance; } @@ -904,7 +896,7 @@ void GoalPlannerModule::decideVelocity() // decide velocity to guarantee turn signal lighting time if (!status_.get_has_decided_velocity()) { - auto & first_path = status_.get_pull_over_path()->partial_paths.front(); + auto & first_path = thread_safe_data_.get_pull_over_path()->partial_paths.front(); const auto vel = static_cast(std::max(current_vel, parameters_->pull_over_minimum_velocity)); for (auto & p : first_path.points) { @@ -917,13 +909,14 @@ void GoalPlannerModule::decideVelocity() CandidateOutput GoalPlannerModule::planCandidate() const { return CandidateOutput( - status_.get_pull_over_path() ? status_.get_pull_over_path()->getFullPath() : PathWithLaneId()); + thread_safe_data_.get_pull_over_path() ? thread_safe_data_.get_pull_over_path()->getFullPath() + : PathWithLaneId()); } BehaviorModuleOutput GoalPlannerModule::planWithGoalModification() { // if pull over path candidates generation is not finished, use previous module output - if (status_.get_pull_over_path_candidates().empty()) { + if (thread_safe_data_.get_pull_over_path_candidates().empty()) { return getPreviousModuleOutput(); } @@ -944,10 +937,11 @@ BehaviorModuleOutput GoalPlannerModule::planWithGoalModification() } transitionToNextPathIfFinishingCurrentPath(); } else if ( - !status_.get_pull_over_path_candidates().empty() && needPathUpdate(path_update_duration)) { + !thread_safe_data_.get_pull_over_path_candidates().empty() && + needPathUpdate(path_update_duration)) { // if the final path is not decided and enough time has passed since last path update, // select safe path from lane parking pull over path candidates - // and set it to status_.get_pull_over_path() + // and set it to thread_safe_data_.get_pull_over_path() selectSafePullOverPath(); } // else: stop path is generated and set by setOutput() @@ -959,27 +953,32 @@ BehaviorModuleOutput GoalPlannerModule::planWithGoalModification() path_reference_ = getPreviousModuleOutput().reference_path; // return to lane parking if it is possible - if (status_.get_pull_over_path()->type == PullOverPlannerType::FREESPACE) { + if (thread_safe_data_.getPullOverPlannerType() == PullOverPlannerType::FREESPACE) { returnToLaneParking(); } + // For debug + setDebugData(); + if (parameters_->print_debug_info) { + // For evaluations + printParkingPositionError(); + } + + if (!thread_safe_data_.foundPullOverPath()) { + return output; + } + const auto distance_to_path_change = calcDistanceToPathChange(); if (status_.get_has_decided_path()) { updateRTCStatus(distance_to_path_change.first, distance_to_path_change.second); } // TODO(tkhmy) add handle status TRYING updateSteeringFactor( - {status_.get_pull_over_path()->start_pose, status_.get_modified_goal_pose()->goal_pose}, + {thread_safe_data_.get_pull_over_path()->start_pose, + thread_safe_data_.get_modified_goal_pose()->goal_pose}, {distance_to_path_change.first, distance_to_path_change.second}, SteeringFactor::TURNING); - // For debug - setDebugData(); - if (parameters_->print_debug_info) { - // For evaluations - printParkingPositionError(); - } - - setStopReason(StopReason::GOAL_PLANNER, status_.get_pull_over_path()->getFullPath()); + setStopReason(StopReason::GOAL_PLANNER, thread_safe_data_.get_pull_over_path()->getFullPath()); return output; } @@ -1002,7 +1001,7 @@ BehaviorModuleOutput GoalPlannerModule::planWaitingApproval() BehaviorModuleOutput GoalPlannerModule::planWaitingApprovalWithGoalModification() { // if pull over path candidates generation is not finished, use previous module output - if (status_.get_pull_over_path_candidates().empty()) { + if (thread_safe_data_.get_pull_over_path_candidates().empty()) { return getPreviousModuleOutput(); } @@ -1012,10 +1011,9 @@ BehaviorModuleOutput GoalPlannerModule::planWaitingApprovalWithGoalModification( out.reference_path = getPreviousModuleOutput().reference_path; path_candidate_ = std::make_shared(planCandidate().path_candidate); path_reference_ = getPreviousModuleOutput().reference_path; - const auto distance_to_path_change = calcDistanceToPathChange(); // generate drivable area info for new architecture - if (status_.get_pull_over_path()->type == PullOverPlannerType::FREESPACE) { + if (thread_safe_data_.getPullOverPlannerType() == PullOverPlannerType::FREESPACE) { const double drivable_area_margin = planner_data_->parameters.vehicle_width; out.drivable_area_info.drivable_margin = planner_data_->parameters.vehicle_width / 2.0 + drivable_area_margin; @@ -1029,21 +1027,31 @@ BehaviorModuleOutput GoalPlannerModule::planWaitingApprovalWithGoalModification( current_drivable_area_info, getPreviousModuleOutput().drivable_area_info); } + if (!thread_safe_data_.foundPullOverPath()) { + return out; + } + + const auto distance_to_path_change = calcDistanceToPathChange(); if (status_.get_has_decided_path()) { updateRTCStatus(distance_to_path_change.first, distance_to_path_change.second); } updateSteeringFactor( - {status_.get_pull_over_path()->start_pose, status_.get_modified_goal_pose()->goal_pose}, + {thread_safe_data_.get_pull_over_path()->start_pose, + thread_safe_data_.get_modified_goal_pose()->goal_pose}, {distance_to_path_change.first, distance_to_path_change.second}, SteeringFactor::APPROACHING); - setStopReason(StopReason::GOAL_PLANNER, status_.get_pull_over_path()->getFullPath()); + setStopReason(StopReason::GOAL_PLANNER, thread_safe_data_.get_pull_over_path()->getFullPath()); return out; } std::pair GoalPlannerModule::calcDistanceToPathChange() const { - const auto full_path = status_.get_pull_over_path()->getFullPath(); + if (!thread_safe_data_.foundPullOverPath()) { + return {std::numeric_limits::max(), std::numeric_limits::max()}; + } + + const auto full_path = thread_safe_data_.get_pull_over_path()->getFullPath(); const auto ego_segment_idx = motion_utils::findNearestSegmentIndex( full_path.points, planner_data_->self_odometry->pose.pose, std::numeric_limits::max(), @@ -1053,15 +1061,15 @@ std::pair GoalPlannerModule::calcDistanceToPathChange() const } const size_t start_pose_segment_idx = motion_utils::findNearestSegmentIndex( - full_path.points, status_.get_pull_over_path()->start_pose.position); + full_path.points, thread_safe_data_.get_pull_over_path()->start_pose.position); const double dist_to_parking_start_pose = calcSignedArcLength( full_path.points, planner_data_->self_odometry->pose.pose.position, *ego_segment_idx, - status_.get_pull_over_path()->start_pose.position, start_pose_segment_idx); + thread_safe_data_.get_pull_over_path()->start_pose.position, start_pose_segment_idx); const size_t goal_pose_segment_idx = motion_utils::findNearestSegmentIndex( - full_path.points, status_.get_modified_goal_pose()->goal_pose.position); + full_path.points, thread_safe_data_.get_modified_goal_pose()->goal_pose.position); const double dist_to_parking_finish_pose = calcSignedArcLength( full_path.points, planner_data_->self_odometry->pose.pose.position, *ego_segment_idx, - status_.get_modified_goal_pose()->goal_pose.position, goal_pose_segment_idx); + thread_safe_data_.get_modified_goal_pose()->goal_pose.position, goal_pose_segment_idx); return {dist_to_parking_start_pose, dist_to_parking_finish_pose}; } @@ -1103,17 +1111,17 @@ PathWithLaneId GoalPlannerModule::generateStopPath() reference_path.points, status_.get_closest_goal_candidate_pose().position, -approximate_pull_over_distance_); if ( - !status_.get_is_safe_static_objects() && !status_.get_closest_start_pose() && + !thread_safe_data_.foundPullOverPath() && !thread_safe_data_.get_closest_start_pose() && !search_start_offset_pose) { return generateFeasibleStopPath(); } const Pose stop_pose = [&]() -> Pose { - if (status_.get_is_safe_static_objects()) { - return status_.get_pull_over_path()->start_pose; + if (thread_safe_data_.foundPullOverPath()) { + return thread_safe_data_.get_pull_over_path()->start_pose; } - if (status_.get_closest_start_pose()) { - return status_.get_closest_start_pose().value(); + if (thread_safe_data_.get_closest_start_pose()) { + return thread_safe_data_.get_closest_start_pose().value(); } return *search_start_offset_pose; }(); @@ -1187,44 +1195,42 @@ PathWithLaneId GoalPlannerModule::generateFeasibleStopPath() void GoalPlannerModule::transitionToNextPathIfFinishingCurrentPath() { - if (isActivated() && last_approval_data_) { - // if using arc_path and finishing current_path, get next path - // enough time for turn signal - const bool has_passed_enough_time = (clock_->now() - last_approval_data_->time).seconds() > - planner_data_->parameters.turn_signal_search_time; - - if (hasFinishedCurrentPath() && has_passed_enough_time && status_.get_require_increment()) { - if (incrementPathIndex()) { - status_.set_last_increment_time(std::make_shared(clock_->now())); - } - } + if (!isActivated() || !last_approval_data_) { + return; } -} -bool GoalPlannerModule::incrementPathIndex() -{ - if (status_.get_current_path_idx() == status_.get_pull_over_path()->partial_paths.size() - 1) { - return false; + // if using arc_path and finishing current_path, get next path + // enough time for turn signal + const bool has_passed_enough_time_from_approval = + (clock_->now() - last_approval_data_->time).seconds() > + planner_data_->parameters.turn_signal_search_time; + if (!has_passed_enough_time_from_approval) { + return; } - status_.set_current_path_idx(status_.get_current_path_idx() + 1); - return true; -} -PathWithLaneId GoalPlannerModule::getCurrentPath() const -{ - if (status_.get_pull_over_path() == nullptr) { - return PathWithLaneId{}; + // require increment only when the time passed is enough + // to prevent increment before driving + // when the end of the current path is close to the current pose + // this value should be `keep_stop_time` in keepStoppedWithCurrentPath + constexpr double keep_current_idx_time = 4.0; + const bool has_passed_enough_time_from_increment = + (clock_->now() - *thread_safe_data_.get_last_path_update_time()).seconds() > + keep_current_idx_time; + if (!has_passed_enough_time_from_increment) { + return; } - if (status_.get_pull_over_path()->partial_paths.size() <= status_.get_current_path_idx()) { - return PathWithLaneId{}; + if (!hasFinishedCurrentPath()) { + return; } - return status_.get_pull_over_path()->partial_paths.at(status_.get_current_path_idx()); + + thread_safe_data_.incrementPathIndex(); } bool GoalPlannerModule::isStopped( std::deque & odometry_buffer, const double time) { + const std::lock_guard lock(mutex_); odometry_buffer.push_back(planner_data_->self_odometry); // Delete old data in buffer while (rclcpp::ok()) { @@ -1254,6 +1260,7 @@ bool GoalPlannerModule::isStopped() bool GoalPlannerModule::isStuck() { + const std::lock_guard lock(mutex_); if (isOnModifiedGoal()) { return false; } @@ -1264,21 +1271,22 @@ bool GoalPlannerModule::isStuck() } // not found safe path - if (!status_.get_is_safe_static_objects()) { + if (!thread_safe_data_.foundPullOverPath()) { return true; } // any path has never been found - if (!status_.get_pull_over_path()) { + if (!thread_safe_data_.get_pull_over_path()) { return false; } - return checkCollision(getCurrentPath()); + return checkCollision(thread_safe_data_.get_pull_over_path()->getCurrentPath()); } bool GoalPlannerModule::hasFinishedCurrentPath() { - const auto current_path_end = getCurrentPath().points.back(); + const auto current_path_end = + thread_safe_data_.get_pull_over_path()->getCurrentPath().points.back(); const auto & self_pose = planner_data_->self_odometry->pose.pose; const bool is_near_target = tier4_autoware_utils::calcDistance2d(current_path_end, self_pose) < parameters_->th_arrived_distance; @@ -1288,12 +1296,12 @@ bool GoalPlannerModule::hasFinishedCurrentPath() bool GoalPlannerModule::isOnModifiedGoal() const { - if (!status_.get_modified_goal_pose()) { + if (!thread_safe_data_.get_modified_goal_pose()) { return false; } const Pose current_pose = planner_data_->self_odometry->pose.pose; - return calcDistance2d(current_pose, status_.get_modified_goal_pose()->goal_pose) < + return calcDistance2d(current_pose, thread_safe_data_.get_modified_goal_pose()->goal_pose) < parameters_->th_arrived_distance; } @@ -1302,9 +1310,9 @@ TurnSignalInfo GoalPlannerModule::calcTurnSignalInfo() const TurnSignalInfo turn_signal{}; // output const auto & current_pose = planner_data_->self_odometry->pose.pose; - const auto & start_pose = status_.get_pull_over_path()->start_pose; - const auto & end_pose = status_.get_pull_over_path()->end_pose; - const auto full_path = status_.get_pull_over_path()->getFullPath(); + const auto & start_pose = thread_safe_data_.get_pull_over_path()->start_pose; + const auto & end_pose = thread_safe_data_.get_pull_over_path()->end_pose; + const auto full_path = thread_safe_data_.get_pull_over_path()->getFullPath(); // calc TurnIndicatorsCommand { @@ -1435,20 +1443,18 @@ bool GoalPlannerModule::hasEnoughDistance(const PullOverPath & pull_over_path) c void GoalPlannerModule::keepStoppedWithCurrentPath(PathWithLaneId & path) { constexpr double keep_stop_time = 2.0; - constexpr double keep_current_idx_buffer_time = 2.0; - if (status_.get_last_increment_time()) { - const auto time_diff = (clock_->now() - *status_.get_last_increment_time()).seconds(); - if (time_diff < keep_stop_time) { - status_.set_require_increment(false); - for (auto & p : path.points) { - p.point.longitudinal_velocity_mps = 0.0; - } - } else if (time_diff > keep_stop_time + keep_current_idx_buffer_time) { - // require increment only when the time passed is enough - // to prevent increment before driving - // when the end of the current path is close to the current pose - status_.set_require_increment(true); - } + if (!thread_safe_data_.get_last_path_idx_increment_time()) { + return; + } + + const auto time_diff = + (clock_->now() - *thread_safe_data_.get_last_path_idx_increment_time()).seconds(); + if (time_diff > keep_stop_time) { + return; + } + + for (auto & p : path.points) { + p.point.longitudinal_velocity_mps = 0.0; } } @@ -1499,7 +1505,7 @@ void GoalPlannerModule::decelerateForTurnSignal(const Pose & stop_pose, PathWith planner_data_, parameters_->maximum_deceleration, parameters_->maximum_jerk, 0.0); if (min_stop_distance && *min_stop_distance < stop_point_length) { - const auto stop_point = utils::insertStopPoint(stop_point_length, path); + utils::insertStopPoint(stop_point_length, path); } } @@ -1631,7 +1637,7 @@ void GoalPlannerModule::updateSafetyCheckTargetObjectsData( bool GoalPlannerModule::isSafePath() const { - const auto pull_over_path = getCurrentPath(); + const auto pull_over_path = thread_safe_data_.get_pull_over_path()->getCurrentPath(); const auto & current_pose = planner_data_->self_odometry->pose.pose; const double current_velocity = std::hypot( planner_data_->self_odometry->twist.twist.linear.x, @@ -1648,7 +1654,7 @@ bool GoalPlannerModule::isSafePath() const const size_t ego_seg_idx = planner_data_->findEgoSegmentIndex(pull_over_path.points); const std::pair terminal_velocity_and_accel = utils::start_goal_planner_common::getPairsTerminalVelocityAndAccel( - status_.get_pull_over_path()->pairs_terminal_velocity_and_accel, + thread_safe_data_.get_pull_over_path()->pairs_terminal_velocity_and_accel, status_.get_current_path_idx()); RCLCPP_DEBUG( getLogger(), "pairs_terminal_velocity_and_accel for goal_planner: %f, %f", @@ -1744,23 +1750,25 @@ void GoalPlannerModule::setDebugData() goal_searcher_->getAreaPolygons(), header, color, z)); // Visualize goal candidates - const auto goal_candidates = status_.get_goal_candidates(); + const auto goal_candidates = thread_safe_data_.get_goal_candidates(); add(goal_planner_utils::createGoalCandidatesMarkerArray(goal_candidates, color)); } // Visualize path and related pose - if (status_.get_is_safe_static_objects()) { + if (thread_safe_data_.foundPullOverPath()) { add(createPoseMarkerArray( - status_.get_pull_over_path()->start_pose, "pull_over_start_pose", 0, 0.3, 0.3, 0.9)); + thread_safe_data_.get_pull_over_path()->start_pose, "pull_over_start_pose", 0, 0.3, 0.3, + 0.9)); add(createPoseMarkerArray( - status_.get_pull_over_path()->end_pose, "pull_over_end_pose", 0, 0.3, 0.3, 0.9)); + thread_safe_data_.get_pull_over_path()->end_pose, "pull_over_end_pose", 0, 0.3, 0.3, 0.9)); + add(createPathMarkerArray( + thread_safe_data_.get_pull_over_path()->getFullPath(), "full_path", 0, 0.0, 0.5, 0.9)); add(createPathMarkerArray( - status_.get_pull_over_path()->getFullPath(), "full_path", 0, 0.0, 0.5, 0.9)); - add(createPathMarkerArray(getCurrentPath(), "current_path", 0, 0.9, 0.5, 0.0)); + thread_safe_data_.get_pull_over_path()->getCurrentPath(), "current_path", 0, 0.9, 0.5, 0.0)); // visualize each partial path - for (size_t i = 0; i < status_.get_pull_over_path()->partial_paths.size(); ++i) { - const auto & partial_path = status_.get_pull_over_path()->partial_paths.at(i); + for (size_t i = 0; i < thread_safe_data_.get_pull_over_path()->partial_paths.size(); ++i) { + const auto & partial_path = thread_safe_data_.get_pull_over_path()->partial_paths.at(i); add( createPathMarkerArray(partial_path, "partial_path_" + std::to_string(i), 0, 0.9, 0.5, 0.9)); } @@ -1782,7 +1790,15 @@ void GoalPlannerModule::setDebugData() } } debug_marker_.markers.push_back(marker); + + // Visualize debug poses + const auto & debug_poses = thread_safe_data_.get_pull_over_path()->debug_poses; + for (size_t i = 0; i < debug_poses.size(); ++i) { + add(createPoseMarkerArray( + debug_poses.at(i), "debug_pose_" + std::to_string(i), 0, 0.3, 0.3, 0.3)); + } } + // safety check if (parameters_->safety_check_params.enable_safety_check) { if (goal_planner_data_.ego_predicted_path.size() > 0) { @@ -1806,17 +1822,22 @@ void GoalPlannerModule::setDebugData() // Visualize planner type text { visualization_msgs::msg::MarkerArray planner_type_marker_array{}; - const auto color = status_.get_is_safe_static_objects() + const auto color = thread_safe_data_.foundPullOverPath() ? createMarkerColor(1.0, 1.0, 1.0, 0.99) : createMarkerColor(1.0, 0.0, 0.0, 0.99); auto marker = createDefaultMarker( header.frame_id, header.stamp, "planner_type", 0, visualization_msgs::msg::Marker::TEXT_VIEW_FACING, createMarkerScale(0.0, 0.0, 1.0), color); - marker.pose = status_.get_modified_goal_pose() ? status_.get_modified_goal_pose()->goal_pose - : planner_data_->self_odometry->pose.pose; - marker.text = magic_enum::enum_name(status_.get_pull_over_path()->type); - marker.text += " " + std::to_string(status_.get_current_path_idx()) + "/" + - std::to_string(status_.get_pull_over_path()->partial_paths.size() - 1); + marker.pose = thread_safe_data_.get_modified_goal_pose() + ? thread_safe_data_.get_modified_goal_pose()->goal_pose + : planner_data_->self_odometry->pose.pose; + marker.text = magic_enum::enum_name(thread_safe_data_.getPullOverPlannerType()); + if (thread_safe_data_.foundPullOverPath()) { + marker.text += + " " + std::to_string(status_.get_current_path_idx()) + "/" + + std::to_string(thread_safe_data_.get_pull_over_path()->partial_paths.size() - 1); + } + if (isStuck()) { marker.text += " stuck"; } else if (isStopped()) { @@ -1832,13 +1853,6 @@ void GoalPlannerModule::setDebugData() planner_type_marker_array.markers.push_back(marker); add(planner_type_marker_array); } - - // Visualize debug poses - const auto & debug_poses = status_.get_pull_over_path()->debug_poses; - for (size_t i = 0; i < debug_poses.size(); ++i) { - add(createPoseMarkerArray( - debug_poses.at(i), "debug_pose_" + std::to_string(i), 0, 0.3, 0.3, 0.3)); - } } void GoalPlannerModule::printParkingPositionError() const @@ -1847,7 +1861,7 @@ void GoalPlannerModule::printParkingPositionError() const const double real_shoulder_to_map_shoulder = 0.0; const Pose goal_to_ego = - inverseTransformPose(current_pose, status_.get_modified_goal_pose()->goal_pose); + inverseTransformPose(current_pose, thread_safe_data_.get_modified_goal_pose()->goal_pose); const double dx = goal_to_ego.position.x; const double dy = goal_to_ego.position.y; const double distance_from_real_shoulder = @@ -1856,7 +1870,7 @@ void GoalPlannerModule::printParkingPositionError() const getLogger(), "current pose to goal, dx:%f dy:%f dyaw:%f from_real_shoulder:%f", dx, dy, tier4_autoware_utils::rad2deg( tf2::getYaw(current_pose.orientation) - - tf2::getYaw(status_.get_modified_goal_pose()->goal_pose.orientation)), + tf2::getYaw(thread_safe_data_.get_modified_goal_pose()->goal_pose.orientation)), distance_from_real_shoulder); } @@ -1882,10 +1896,10 @@ bool GoalPlannerModule::needPathUpdate(const double path_update_duration) const bool GoalPlannerModule::hasEnoughTimePassedSincePathUpdate(const double duration) const { - if (!status_.get_last_path_update_time()) { + if (!thread_safe_data_.get_last_path_update_time()) { return true; } - return (clock_->now() - *status_.get_last_path_update_time()).seconds() > duration; + return (clock_->now() - *thread_safe_data_.get_last_path_update_time()).seconds() > duration; } } // namespace behavior_path_planner From 08b905aedd4def7dd04c9d3ae486f361179c87c2 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Fri, 10 Nov 2023 19:21:20 +0900 Subject: [PATCH 167/202] refactor(start_planner): refactor backward path calculation in StartPlannerModule (#5529) * refactor(start_planner): refactor backward path calculation in StartPlannerModule The method "calcStartPoseCandidatesBackwardPath" has been renamed to "calcBackwardPathFromStartPose" to better reflect its purpose. The method now calculates the backward path by shifting the original start pose coordinates to align with the pull out lanes. The stop objects in the pull out lanes are filtered by velocity, using the new "filterStopObjectsInPullOutLanes" method. Additionally, the redundant "isOverlappedWithLane" method has been removed. Signed-off-by: kyoichi-sugahara --------- Signed-off-by: kyoichi-sugahara Co-authored-by: Kosuke Takeuchi --- ...avior_path_planner_start_planner_design.md | 2 +- .../start_planner/start_planner_module.hpp | 10 +- .../start_planner/start_planner_module.cpp | 101 +++++++++--------- 3 files changed, 55 insertions(+), 58 deletions(-) diff --git a/planning/behavior_path_planner/docs/behavior_path_planner_start_planner_design.md b/planning/behavior_path_planner/docs/behavior_path_planner_start_planner_design.md index 131202038c270..28a1db649cf04 100644 --- a/planning/behavior_path_planner/docs/behavior_path_planner_start_planner_design.md +++ b/planning/behavior_path_planner/docs/behavior_path_planner_start_planner_design.md @@ -252,7 +252,7 @@ If a safe path cannot be generated from the current position, search backwards f | max_back_distance | [m] | double | maximum back distance | 30.0 | | backward_search_resolution | [m] | double | distance interval for searching backward pull out start point | 2.0 | | backward_path_update_duration | [s] | double | time interval for searching backward pull out start point. this prevents chattering between back driving and pull_out | 3.0 | -| ignore_distance_from_lane_end | [m] | double | distance from end of pull out lanes for ignoring start candidates | 15.0 | +| ignore_distance_from_lane_end | [m] | double | If distance from shift start pose to end of shoulder lane is less than this value, this start pose candidate is ignored | 15.0 | ### **freespace pull out** diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp index 91121598cb3ae..8d2532504926e 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp @@ -176,8 +176,9 @@ class StartPlannerModule : public SceneModuleInterface std::mutex mutex_; PathWithLaneId getFullPath() const; - PathWithLaneId calcStartPoseCandidatesBackwardPath() const; - std::vector searchPullOutStartPoses(const PathWithLaneId & start_pose_candidates) const; + PathWithLaneId calcBackwardPathFromStartPose() const; + std::vector searchPullOutStartPoseCandidates( + const PathWithLaneId & back_path_from_start_pose) const; std::shared_ptr lane_departure_checker_; @@ -194,9 +195,8 @@ class StartPlannerModule : public SceneModuleInterface std::vector generateDrivableLanes(const PathWithLaneId & path) const; void updatePullOutStatus(); void updateStatusAfterBackwardDriving(); - static bool isOverlappedWithLane( - const lanelet::ConstLanelet & candidate_lanelet, - const tier4_autoware_utils::LinearRing2d & vehicle_footprint); + PredictedObjects filterStopObjectsInPullOutLanes( + const lanelet::ConstLanelets & pull_out_lanes, const double velocity_threshold) const; bool hasFinishedPullOut() const; bool isBackwardDrivingComplete() const; bool isStopped(); diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp index 77a290835fb31..75562f59a402f 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp @@ -718,7 +718,7 @@ void StartPlannerModule::updatePullOutStatus() // refine start pose with pull out lanes. // 1) backward driving is not allowed: use refined pose just as start pose. // 2) backward driving is allowed: use refined pose to check if backward driving is needed. - const PathWithLaneId start_pose_candidates_path = calcStartPoseCandidatesBackwardPath(); + const PathWithLaneId start_pose_candidates_path = calcBackwardPathFromStartPose(); const auto refined_start_pose = calcLongitudinalOffsetPose( start_pose_candidates_path.points, planner_data_->self_odometry->pose.pose.position, 0.0); if (!refined_start_pose) return; @@ -726,7 +726,7 @@ void StartPlannerModule::updatePullOutStatus() // search pull out start candidates backward const std::vector start_pose_candidates = std::invoke([&]() -> std::vector { if (parameters_->enable_back) { - return searchPullOutStartPoses(start_pose_candidates_path); + return searchPullOutStartPoseCandidates(start_pose_candidates_path); } return {*refined_start_pose}; }); @@ -739,6 +739,7 @@ void StartPlannerModule::updatePullOutStatus() if (isBackwardDrivingComplete()) { updateStatusAfterBackwardDriving(); + // should be moved to transition state current_state_ = ModuleStatus::SUCCESS; // for breaking loop } else { status_.backward_path = start_planner_utils::getBackwardPath( @@ -760,71 +761,66 @@ void StartPlannerModule::updateStatusAfterBackwardDriving() } } -PathWithLaneId StartPlannerModule::calcStartPoseCandidatesBackwardPath() const +PathWithLaneId StartPlannerModule::calcBackwardPathFromStartPose() const { - const Pose & current_pose = planner_data_->self_odometry->pose.pose; - + const Pose & start_pose = planner_data_->route_handler->getOriginalStartPose(); const auto pull_out_lanes = start_planner_utils::getPullOutLanes( planner_data_, planner_data_->parameters.backward_path_length + parameters_->max_back_distance); - // get backward shoulder path - const auto arc_position_pose = lanelet::utils::getArcCoordinates(pull_out_lanes, current_pose); - const double check_distance = parameters_->max_back_distance + 30.0; // buffer - auto path = planner_data_->route_handler->getCenterLinePath( - pull_out_lanes, arc_position_pose.length - check_distance, - arc_position_pose.length + check_distance); - - // lateral shift to current_pose - const double distance_from_center_line = arc_position_pose.distance; - for (auto & p : path.points) { - p.point.pose = calcOffsetPose(p.point.pose, 0, distance_from_center_line, 0); + const auto arc_position_pose = lanelet::utils::getArcCoordinates(pull_out_lanes, start_pose); + + // common buffer distance for both front and back + static constexpr double buffer = 30.0; + const double check_distance = parameters_->max_back_distance + buffer; + + const double start_distance = arc_position_pose.length - check_distance; + const double end_distance = arc_position_pose.length + buffer; + + auto path = + planner_data_->route_handler->getCenterLinePath(pull_out_lanes, start_distance, end_distance); + + // shift all path points laterally to align with the start pose + for (auto & path_point : path.points) { + path_point.point.pose = calcOffsetPose(path_point.point.pose, 0, arc_position_pose.distance, 0); } return path; } -std::vector StartPlannerModule::searchPullOutStartPoses( - const PathWithLaneId & start_pose_candidates) const +std::vector StartPlannerModule::searchPullOutStartPoseCandidates( + const PathWithLaneId & back_path_from_start_pose) const { - const Pose & current_pose = planner_data_->self_odometry->pose.pose; - - std::vector pull_out_start_pose{}; - + std::vector pull_out_start_pose_candidates{}; + const auto & start_pose = planner_data_->route_handler->getOriginalStartPose(); + const auto local_vehicle_footprint = createVehicleFootprint(vehicle_info_); const auto pull_out_lanes = start_planner_utils::getPullOutLanes( planner_data_, planner_data_->parameters.backward_path_length + parameters_->max_back_distance); - // filter pull out lanes stop objects - const auto [pull_out_lane_objects, others] = - utils::path_safety_checker::separateObjectsByLanelets( - *planner_data_->dynamic_object, pull_out_lanes, - utils::path_safety_checker::isPolygonOverlapLanelet); - const auto pull_out_lane_stop_objects = utils::path_safety_checker::filterObjectsByVelocity( - pull_out_lane_objects, parameters_->th_moving_object_velocity); + const auto stop_objects_in_pull_out_lanes = + filterStopObjectsInPullOutLanes(pull_out_lanes, parameters_->th_moving_object_velocity); // Set the maximum backward distance less than the distance from the vehicle's base_link to the // lane's rearmost point to prevent lane departure. - const double s_current = lanelet::utils::getArcCoordinates(pull_out_lanes, current_pose).length; - const double max_back_distance = std::clamp( - s_current - planner_data_->parameters.base_link2rear, 0.0, parameters_->max_back_distance); + const double current_arc_length = + lanelet::utils::getArcCoordinates(pull_out_lanes, start_pose).length; + const double allowed_backward_distance = std::clamp( + current_arc_length - planner_data_->parameters.base_link2rear, 0.0, + parameters_->max_back_distance); - // check collision between footprint and object at the backed pose - const auto local_vehicle_footprint = createVehicleFootprint(vehicle_info_); - for (double back_distance = 0.0; back_distance <= max_back_distance; + for (double back_distance = 0.0; back_distance <= allowed_backward_distance; back_distance += parameters_->backward_search_resolution) { const auto backed_pose = calcLongitudinalOffsetPose( - start_pose_candidates.points, current_pose.position, -back_distance); + back_path_from_start_pose.points, start_pose.position, -back_distance); if (!backed_pose) { continue; } - // check the back pose is near the lane end - const double length_to_backed_pose = + const double backed_pose_arc_length = lanelet::utils::getArcCoordinates(pull_out_lanes, *backed_pose).length; - const double length_to_lane_end = std::accumulate( std::begin(pull_out_lanes), std::end(pull_out_lanes), 0.0, [](double acc, const auto & lane) { return acc + lanelet::utils::getLaneletLength2d(lane); }); - const double distance_from_lane_end = length_to_lane_end - length_to_backed_pose; + const double distance_from_lane_end = length_to_lane_end - backed_pose_arc_length; if (distance_from_lane_end < parameters_->ignore_distance_from_lane_end) { RCLCPP_WARN_THROTTLE( getLogger(), *clock_, 5000, @@ -833,27 +829,28 @@ std::vector StartPlannerModule::searchPullOutStartPoses( } if (utils::checkCollisionBetweenFootprintAndObjects( - local_vehicle_footprint, *backed_pose, pull_out_lane_stop_objects, + local_vehicle_footprint, *backed_pose, stop_objects_in_pull_out_lanes, parameters_->collision_check_margin)) { break; // poses behind this has a collision, so break. } - pull_out_start_pose.push_back(*backed_pose); + pull_out_start_pose_candidates.push_back(*backed_pose); } - return pull_out_start_pose; + return pull_out_start_pose_candidates; } -bool StartPlannerModule::isOverlappedWithLane( - const lanelet::ConstLanelet & candidate_lanelet, - const tier4_autoware_utils::LinearRing2d & vehicle_footprint) +PredictedObjects StartPlannerModule::filterStopObjectsInPullOutLanes( + const lanelet::ConstLanelets & pull_out_lanes, const double velocity_threshold) const { - for (const auto & point : vehicle_footprint) { - if (boost::geometry::within(point, candidate_lanelet.polygon2d().basicPolygon())) { - return true; - } - } + const auto stop_objects = utils::path_safety_checker::filterObjectsByVelocity( + *planner_data_->dynamic_object, velocity_threshold); - return false; + // filter for objects located in pull_out_lanes and moving at a speed below the threshold + const auto [stop_objects_in_pull_out_lanes, others] = + utils::path_safety_checker::separateObjectsByLanelets( + stop_objects, pull_out_lanes, utils::path_safety_checker::isPolygonOverlapLanelet); + + return stop_objects_in_pull_out_lanes; } bool StartPlannerModule::hasFinishedPullOut() const From 208ecf21240ebca1802903e079855f7b6ab6bb11 Mon Sep 17 00:00:00 2001 From: Alexey Panferov <37497658+lexavtanke@users.noreply.github.com> Date: Fri, 10 Nov 2023 13:25:24 +0300 Subject: [PATCH 168/202] build(lidar_centerpoint_tvm): remove artifacts download (#5367) Signed-off-by: Alexey Panferov --- perception/lidar_centerpoint_tvm/.gitignore | 1 - .../inference_engine_tvm_config.hpp | 60 +++++++++++++++++++ ...processing_inference_engine_tvm_config.hpp | 59 ++++++++++++++++++ .../inference_engine_tvm_config.hpp | 55 +++++++++++++++++ .../lidar_centerpoint_tvm/centerpoint_tvm.hpp | 5 +- .../launch/lidar_centerpoint_tvm.launch.xml | 2 + ...inference_lidar_centerpoint_tvm.launch.xml | 2 + .../lib/centerpoint_tvm.cpp | 14 ++--- perception/lidar_centerpoint_tvm/src/node.cpp | 3 +- .../src/single_inference_node.cpp | 4 +- 10 files changed, 192 insertions(+), 13 deletions(-) create mode 100644 perception/lidar_centerpoint_tvm/data/models/centerpoint_backbone/inference_engine_tvm_config.hpp create mode 100644 perception/lidar_centerpoint_tvm/data/models/centerpoint_backbone/preprocessing_inference_engine_tvm_config.hpp create mode 100644 perception/lidar_centerpoint_tvm/data/models/centerpoint_encoder/inference_engine_tvm_config.hpp diff --git a/perception/lidar_centerpoint_tvm/.gitignore b/perception/lidar_centerpoint_tvm/.gitignore index 8fce603003c1e..e69de29bb2d1d 100644 --- a/perception/lidar_centerpoint_tvm/.gitignore +++ b/perception/lidar_centerpoint_tvm/.gitignore @@ -1 +0,0 @@ -data/ diff --git a/perception/lidar_centerpoint_tvm/data/models/centerpoint_backbone/inference_engine_tvm_config.hpp b/perception/lidar_centerpoint_tvm/data/models/centerpoint_backbone/inference_engine_tvm_config.hpp new file mode 100644 index 0000000000000..8201dd25c1039 --- /dev/null +++ b/perception/lidar_centerpoint_tvm/data/models/centerpoint_backbone/inference_engine_tvm_config.hpp @@ -0,0 +1,60 @@ +// Copyright 2021 Arm Limited and Contributors. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "tvm_utility/pipeline.hpp" + +#ifndef PERCEPTION__LIDAR_CENTERPOINT_TVM__DATA__MODELS__CENTERPOINT_BACKBONE__INFERENCE_ENGINE_TVM_CONFIG_HPP_ // NOLINT +#define PERCEPTION__LIDAR_CENTERPOINT_TVM__DATA__MODELS__CENTERPOINT_BACKBONE__INFERENCE_ENGINE_TVM_CONFIG_HPP_ // NOLINT + +namespace model_zoo +{ +namespace perception +{ +namespace lidar_obstacle_detection +{ +namespace centerpoint_backbone +{ +namespace onnx_centerpoint_backbone +{ + +static const tvm_utility::pipeline::InferenceEngineTVMConfig config{ + {3, 0, 0}, // modelzoo_version + + "centerpoint_backbone", // network_name + "llvm", // network_backend + + "./deploy_lib.so", // network_module_path + "./deploy_graph.json", // network_graph_path + "./deploy_param.params", // network_params_path + + kDLCPU, // tvm_device_type + 0, // tvm_device_id + + {{"spatial_features", kDLFloat, 32, 1, {1, 32, 560, 560}}}, // network_inputs + + {{"heatmap", kDLFloat, 32, 1, {1, 3, 560, 560}}, + {"reg", kDLFloat, 32, 1, {1, 2, 560, 560}}, + {"height", kDLFloat, 32, 1, {1, 1, 560, 560}}, + {"dim", kDLFloat, 32, 1, {1, 3, 560, 560}}, + {"rot", kDLFloat, 32, 1, {1, 2, 560, 560}}, + {"vel", kDLFloat, 32, 1, {1, 2, 560, 560}}} // network_outputs +}; + +} // namespace onnx_centerpoint_backbone +} // namespace centerpoint_backbone +} // namespace lidar_obstacle_detection +} // namespace perception +} // namespace model_zoo +// NOLINTNEXTLINE +#endif // PERCEPTION__LIDAR_CENTERPOINT_TVM__DATA__MODELS__CENTERPOINT_BACKBONE__INFERENCE_ENGINE_TVM_CONFIG_HPP_ diff --git a/perception/lidar_centerpoint_tvm/data/models/centerpoint_backbone/preprocessing_inference_engine_tvm_config.hpp b/perception/lidar_centerpoint_tvm/data/models/centerpoint_backbone/preprocessing_inference_engine_tvm_config.hpp new file mode 100644 index 0000000000000..2f6943e90bc83 --- /dev/null +++ b/perception/lidar_centerpoint_tvm/data/models/centerpoint_backbone/preprocessing_inference_engine_tvm_config.hpp @@ -0,0 +1,59 @@ +// Copyright 2021 Arm Limited and Contributors. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "tvm_utility/pipeline.hpp" + +#ifndef PERCEPTION__LIDAR_CENTERPOINT_TVM__DATA__MODELS__CENTERPOINT_BACKBONE__PREPROCESSING_INFERENCE_ENGINE_TVM_CONFIG_HPP_ // NOLINT +#define PERCEPTION__LIDAR_CENTERPOINT_TVM__DATA__MODELS__CENTERPOINT_BACKBONE__PREPROCESSING_INFERENCE_ENGINE_TVM_CONFIG_HPP_ // NOLINT + +namespace model_zoo +{ +namespace perception +{ +namespace lidar_obstacle_detection +{ +namespace centerpoint_backbone +{ +namespace onnx_centerpoint_backbone +{ +namespace preprocessing +{ + +static const tvm_utility::pipeline::InferenceEngineTVMConfig config{ + {3, 0, 0}, // modelzoo_version + + "centerpoint_backbone", // network_name + "llvm", // network_backend + + "./preprocess.so", // network_module_path + "./", // network_graph_path + "./", // network_params_path + + kDLCPU, // tvm_device_type + 0, // tvm_device_id + + {{"pillar_features", kDLFloat, 32, 1, {40000, 1, 32}}, + {"coords", kDLInt, 32, 1, {40000, 3}}}, // network_inputs + + {{"spatial_features", kDLFloat, 32, 1, {1, 32, 560, 560}}} // network_outputs +}; + +} // namespace preprocessing +} // namespace onnx_centerpoint_backbone +} // namespace centerpoint_backbone +} // namespace lidar_obstacle_detection +} // namespace perception +} // namespace model_zoo +// NOLINTNEXTLINE +#endif // PERCEPTION__LIDAR_CENTERPOINT_TVM__DATA__MODELS__CENTERPOINT_BACKBONE__PREPROCESSING_INFERENCE_ENGINE_TVM_CONFIG_HPP_ diff --git a/perception/lidar_centerpoint_tvm/data/models/centerpoint_encoder/inference_engine_tvm_config.hpp b/perception/lidar_centerpoint_tvm/data/models/centerpoint_encoder/inference_engine_tvm_config.hpp new file mode 100644 index 0000000000000..521036b49a533 --- /dev/null +++ b/perception/lidar_centerpoint_tvm/data/models/centerpoint_encoder/inference_engine_tvm_config.hpp @@ -0,0 +1,55 @@ +// Copyright 2021 Arm Limited and Contributors. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "tvm_utility/pipeline.hpp" + +#ifndef PERCEPTION__LIDAR_CENTERPOINT_TVM__DATA__MODELS__CENTERPOINT_ENCODER__INFERENCE_ENGINE_TVM_CONFIG_HPP_ // NOLINT +#define PERCEPTION__LIDAR_CENTERPOINT_TVM__DATA__MODELS__CENTERPOINT_ENCODER__INFERENCE_ENGINE_TVM_CONFIG_HPP_ // NOLINT + +namespace model_zoo +{ +namespace perception +{ +namespace lidar_obstacle_detection +{ +namespace centerpoint_encoder +{ +namespace onnx_centerpoint_encoder +{ + +static const tvm_utility::pipeline::InferenceEngineTVMConfig config{ + {3, 0, 0}, // modelzoo_version + + "centerpoint_encoder", // network_name + "llvm", // network_backend + + "./deploy_lib.so", // network_module_path + "./deploy_graph.json", // network_graph_path + "./deploy_param.params", // network_params_path + + kDLCPU, // tvm_device_type + 0, // tvm_device_id + + {{"input_features", kDLFloat, 32, 1, {40000, 32, 9}}}, // network_inputs + + {{"pillar_features", kDLFloat, 32, 1, {40000, 1, 32}}} // network_outputs +}; + +} // namespace onnx_centerpoint_encoder +} // namespace centerpoint_encoder +} // namespace lidar_obstacle_detection +} // namespace perception +} // namespace model_zoo +// NOLINTNEXTLINE +#endif // PERCEPTION__LIDAR_CENTERPOINT_TVM__DATA__MODELS__CENTERPOINT_ENCODER__INFERENCE_ENGINE_TVM_CONFIG_HPP_ diff --git a/perception/lidar_centerpoint_tvm/include/lidar_centerpoint_tvm/centerpoint_tvm.hpp b/perception/lidar_centerpoint_tvm/include/lidar_centerpoint_tvm/centerpoint_tvm.hpp index 168a249714bb4..865ca7d4253bf 100644 --- a/perception/lidar_centerpoint_tvm/include/lidar_centerpoint_tvm/centerpoint_tvm.hpp +++ b/perception/lidar_centerpoint_tvm/include/lidar_centerpoint_tvm/centerpoint_tvm.hpp @@ -60,7 +60,7 @@ class LIDAR_CENTERPOINT_TVM_LOCAL TVMScatterIE : public tvm_utility::pipeline::I public: explicit TVMScatterIE( tvm_utility::pipeline::InferenceEngineTVMConfig config, const std::string & pkg_name, - const std::string & function_name); + const std::string & data_path, const std::string & function_name); TVMArrayContainerVector schedule(const TVMArrayContainerVector & input); void set_coords(TVMArrayContainer coords) { coords_ = coords; } @@ -132,7 +132,8 @@ class LIDAR_CENTERPOINT_TVM_PUBLIC CenterPointTVM /// \param[in] dense_param The densification parameter used to constructing vg_ptr. /// \param[in] config The CenterPoint model configuration. explicit CenterPointTVM( - const DensificationParam & densification_param, const CenterPointConfig & config); + const DensificationParam & densification_param, const CenterPointConfig & config, + const std::string & data_path); ~CenterPointTVM(); diff --git a/perception/lidar_centerpoint_tvm/launch/lidar_centerpoint_tvm.launch.xml b/perception/lidar_centerpoint_tvm/launch/lidar_centerpoint_tvm.launch.xml index e838f01e347ce..2bd6e3aa15c21 100644 --- a/perception/lidar_centerpoint_tvm/launch/lidar_centerpoint_tvm.launch.xml +++ b/perception/lidar_centerpoint_tvm/launch/lidar_centerpoint_tvm.launch.xml @@ -10,6 +10,7 @@ + @@ -20,5 +21,6 @@ + diff --git a/perception/lidar_centerpoint_tvm/launch/single_inference_lidar_centerpoint_tvm.launch.xml b/perception/lidar_centerpoint_tvm/launch/single_inference_lidar_centerpoint_tvm.launch.xml index e62808804ca07..c2e0801fbd11c 100644 --- a/perception/lidar_centerpoint_tvm/launch/single_inference_lidar_centerpoint_tvm.launch.xml +++ b/perception/lidar_centerpoint_tvm/launch/single_inference_lidar_centerpoint_tvm.launch.xml @@ -12,6 +12,7 @@ + @@ -22,6 +23,7 @@ + diff --git a/perception/lidar_centerpoint_tvm/lib/centerpoint_tvm.cpp b/perception/lidar_centerpoint_tvm/lib/centerpoint_tvm.cpp index 7b31bdf3c8fd3..2e0f9ad28bfb6 100644 --- a/perception/lidar_centerpoint_tvm/lib/centerpoint_tvm.cpp +++ b/perception/lidar_centerpoint_tvm/lib/centerpoint_tvm.cpp @@ -43,11 +43,10 @@ namespace lidar_centerpoint_tvm TVMScatterIE::TVMScatterIE( tvm_utility::pipeline::InferenceEngineTVMConfig config, const std::string & pkg_name, - const std::string & function_name) + const std::string & data_path, const std::string & function_name) : config_(config) { - std::string network_prefix = - ament_index_cpp::get_package_share_directory(pkg_name) + "/models/" + config.network_name + "/"; + std::string network_prefix = data_path + "/" + pkg_name + "/models/" + config.network_name + "/"; std::string network_module_path = network_prefix + config.network_module_path; std::ifstream module(network_module_path); @@ -159,14 +158,15 @@ std::vector BackboneNeckHeadPostProcessor::schedule(const TVMArrayContain } CenterPointTVM::CenterPointTVM( - const DensificationParam & densification_param, const CenterPointConfig & config) + const DensificationParam & densification_param, const CenterPointConfig & config, + const std::string & data_path) : config_ve(config_en), config_bnh(config_bk), VE_PreP(std::make_shared(config_en, config)), - VE_IE(std::make_shared(config_en, "lidar_centerpoint_tvm")), - BNH_IE(std::make_shared(config_bk, "lidar_centerpoint_tvm")), + VE_IE(std::make_shared(config_en, "lidar_centerpoint_tvm", data_path)), + BNH_IE(std::make_shared(config_bk, "lidar_centerpoint_tvm", data_path)), BNH_PostP(std::make_shared(config_bk, config)), - scatter_ie(std::make_shared(config_scatter, "lidar_centerpoint_tvm", "scatter")), + scatter_ie(std::make_shared(config_scatter, "lidar_centerpoint_tvm", data_path, "scatter")), TSP_pipeline(std::make_shared(VE_PreP, VE_IE, scatter_ie, BNH_IE, BNH_PostP)), config_(config) { diff --git a/perception/lidar_centerpoint_tvm/src/node.cpp b/perception/lidar_centerpoint_tvm/src/node.cpp index e63cb7e19ba8e..0054211a15f9f 100644 --- a/perception/lidar_centerpoint_tvm/src/node.cpp +++ b/perception/lidar_centerpoint_tvm/src/node.cpp @@ -65,6 +65,7 @@ LidarCenterPointTVMNode::LidarCenterPointTVMNode(const rclcpp::NodeOptions & nod static_cast(this->declare_parameter("downsample_factor")); const std::size_t encoder_in_feature_size = static_cast(this->declare_parameter("encoder_in_feature_size")); + const auto data_path = this->declare_parameter("data_path"); DensificationParam densification_param( densification_world_frame_id, densification_num_past_frames); @@ -83,7 +84,7 @@ LidarCenterPointTVMNode::LidarCenterPointTVMNode(const rclcpp::NodeOptions & nod class_names_.size(), point_feature_size, max_voxel_size, point_cloud_range, voxel_size, downsample_factor, encoder_in_feature_size, score_threshold, circle_nms_dist_threshold, yaw_norm_threshold); - detector_ptr_ = std::make_unique(densification_param, config); + detector_ptr_ = std::make_unique(densification_param, config, data_path); pointcloud_sub_ = this->create_subscription( "~/input/pointcloud", rclcpp::SensorDataQoS{}.keep_last(1), diff --git a/perception/lidar_centerpoint_tvm/src/single_inference_node.cpp b/perception/lidar_centerpoint_tvm/src/single_inference_node.cpp index 8b810c5a7d759..a08850a7572f2 100644 --- a/perception/lidar_centerpoint_tvm/src/single_inference_node.cpp +++ b/perception/lidar_centerpoint_tvm/src/single_inference_node.cpp @@ -70,7 +70,7 @@ SingleInferenceLidarCenterPointNode::SingleInferenceLidarCenterPointNode( static_cast(this->declare_parameter("encoder_in_feature_size")); const auto pcd_path = this->declare_parameter("pcd_path"); const auto detections_path = this->declare_parameter("detections_path"); - + const auto data_path = this->declare_parameter("data_path"); DensificationParam densification_param( densification_world_frame_id, densification_num_past_frames); @@ -88,7 +88,7 @@ SingleInferenceLidarCenterPointNode::SingleInferenceLidarCenterPointNode( class_names_.size(), point_feature_size, max_voxel_size, point_cloud_range, voxel_size, downsample_factor, encoder_in_feature_size, score_threshold, circle_nms_dist_threshold, yaw_norm_threshold); - detector_ptr_ = std::make_unique(densification_param, config); + detector_ptr_ = std::make_unique(densification_param, config, data_path); detect(pcd_path, detections_path); exit(0); From 042c7a0c51ba72b8fb7b0199e292c15512b6da4b Mon Sep 17 00:00:00 2001 From: Yuxuan Liu <619684051@qq.com> Date: Sat, 11 Nov 2023 14:44:04 +0800 Subject: [PATCH 169/202] refactor(perception_rviz_plugin): apply thread pool to manage detached thread (#5418) * apply thread pool to manage detached thread Signed-off-by: Owen-Liuyuxuan * style(pre-commit): autofix * clean up the destructor Signed-off-by: Owen-Liuyuxuan * style(pre-commit): autofix * use function object in the queue instead Signed-off-by: Owen-Liuyuxuan * style(pre-commit): autofix * fix condition variable naming problem Signed-off-by: Owen-Liuyuxuan * add utility include for CI Signed-off-by: Owen-Liuyuxuan --------- Signed-off-by: Owen-Liuyuxuan Co-authored-by: Owen-Liuyuxuan Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../predicted_objects_display.hpp | 33 ++++++++++++++ .../predicted_objects_display.cpp | 45 +++++++++++++------ 2 files changed, 64 insertions(+), 14 deletions(-) diff --git a/common/autoware_auto_perception_rviz_plugin/include/object_detection/predicted_objects_display.hpp b/common/autoware_auto_perception_rviz_plugin/include/object_detection/predicted_objects_display.hpp index 5493f1dd594ce..2896286970217 100644 --- a/common/autoware_auto_perception_rviz_plugin/include/object_detection/predicted_objects_display.hpp +++ b/common/autoware_auto_perception_rviz_plugin/include/object_detection/predicted_objects_display.hpp @@ -24,9 +24,11 @@ #include #include +#include #include #include #include +#include #include namespace autoware @@ -45,10 +47,31 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC PredictedObjectsDisplay using PredictedObjects = autoware_auto_perception_msgs::msg::PredictedObjects; PredictedObjectsDisplay(); + ~PredictedObjectsDisplay() + { + { + std::unique_lock lock(queue_mutex); + should_terminate = true; + } + condition.notify_all(); + for (std::thread & active_thread : threads) { + active_thread.join(); + } + threads.clear(); + } private: void processMessage(PredictedObjects::ConstSharedPtr msg) override; + void queueJob(std::function job) + { + { + std::unique_lock lock(queue_mutex); + jobs.push(std::move(job)); + } + condition.notify_one(); + } + boost::uuids::uuid to_boost_uuid(const unique_identifier_msgs::msg::UUID & uuid_msg) { const std::string uuid_str = uuid_to_string(uuid_msg); @@ -100,6 +123,8 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC PredictedObjectsDisplay PredictedObjects::ConstSharedPtr msg); void workerThread(); + void messageProcessorThreadJob(); + void update(float wall_dt, float ros_dt) override; std::unordered_map> id_map; @@ -108,6 +133,14 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC PredictedObjectsDisplay int32_t marker_id = 0; const int32_t PATH_ID_CONSTANT = 1e3; + // max_num_threads: number of threads created in the thread pool, hard-coded to be 1; + int max_num_threads; + + bool should_terminate{false}; + std::mutex queue_mutex; + std::vector threads; + std::queue> jobs; + PredictedObjects::ConstSharedPtr msg; bool consumed{false}; std::mutex mutex; diff --git a/common/autoware_auto_perception_rviz_plugin/src/object_detection/predicted_objects_display.cpp b/common/autoware_auto_perception_rviz_plugin/src/object_detection/predicted_objects_display.cpp index 24e67a6f44e95..2cc5397d18721 100644 --- a/common/autoware_auto_perception_rviz_plugin/src/object_detection/predicted_objects_display.cpp +++ b/common/autoware_auto_perception_rviz_plugin/src/object_detection/predicted_objects_display.cpp @@ -25,27 +25,44 @@ namespace object_detection { PredictedObjectsDisplay::PredictedObjectsDisplay() : ObjectPolygonDisplayBase("tracks") { - std::thread worker(&PredictedObjectsDisplay::workerThread, this); - worker.detach(); + max_num_threads = 1; // hard code the number of threads to be created + + for (int ii = 0; ii < max_num_threads; ++ii) { + threads.emplace_back(std::thread(&PredictedObjectsDisplay::workerThread, this)); + } } void PredictedObjectsDisplay::workerThread() -{ +{ // A standard working thread that waiting for jobs while (true) { - std::unique_lock lock(mutex); - condition.wait(lock, [this] { return this->msg; }); + std::function job; + { + std::unique_lock lock(queue_mutex); + condition.wait(lock, [this] { return !jobs.empty() || should_terminate; }); + if (should_terminate) { + return; + } + job = jobs.front(); + jobs.pop(); + } + job(); + } +} - auto tmp_msg = this->msg; - this->msg.reset(); +void PredictedObjectsDisplay::messageProcessorThreadJob() +{ + // Receiving + std::unique_lock lock(mutex); + auto tmp_msg = this->msg; + this->msg.reset(); + lock.unlock(); - lock.unlock(); + auto tmp_markers = createMarkers(tmp_msg); - auto tmp_markers = createMarkers(tmp_msg); - lock.lock(); - markers = tmp_markers; + lock.lock(); + markers = tmp_markers; - consumed = true; - } + consumed = true; } std::vector PredictedObjectsDisplay::createMarkers( @@ -188,7 +205,7 @@ void PredictedObjectsDisplay::processMessage(PredictedObjects::ConstSharedPtr ms std::unique_lock lock(mutex); this->msg = msg; - condition.notify_one(); + queueJob(std::bind(&PredictedObjectsDisplay::messageProcessorThreadJob, this)); } void PredictedObjectsDisplay::update(float wall_dt, float ros_dt) From a84c43b2cb6c0a3dd00df19f66866d28dd15c752 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Mon, 13 Nov 2023 09:52:56 +0900 Subject: [PATCH 170/202] feat(intersection): use the centerline position of first attention area if there is no traffic light (#5547) Signed-off-by: Mamoru Sobue --- .../README.md | 15 +- .../docs/data-structure.drawio.svg | 745 ++++++++++++------ .../src/manager.cpp | 1 + .../src/scene_intersection.cpp | 173 ++-- .../src/scene_merge_from_private_road.cpp | 4 +- .../src/util.cpp | 86 +- .../src/util.hpp | 3 +- .../src/util_type.hpp | 3 +- 8 files changed, 690 insertions(+), 340 deletions(-) diff --git a/planning/behavior_velocity_intersection_module/README.md b/planning/behavior_velocity_intersection_module/README.md index cb65e2a3cc23c..3ed4ee8fd334a 100644 --- a/planning/behavior_velocity_intersection_module/README.md +++ b/planning/behavior_velocity_intersection_module/README.md @@ -100,7 +100,18 @@ If a stopline is associated with the intersection lane on the map, that line is #### Pass Judge Line -To avoid sudden braking, if deceleration and jerk more than a threshold (`behavior_velocity_planner.max_accel` and `behavior_velocity_planner.max_jerk`) is required to stop just in front of the attention area, this module does not insert stopline after passing the default stopline position. +To avoid sudden braking, if deceleration and jerk more than a threshold (`behavior_velocity_planner.max_accel` and `behavior_velocity_planner.max_jerk`) is required to stop just in front of the attention area, namely the `first_attention_stop_line`, this module does not insert stopline after it passed the `default stop_line` position. + +The position of the pass judge line depends on the occlusion detection configuration and the existence of the associated traffic light of the intersection lane. + +- If `occlusion.enable` is false, the pass judge line before the `first_attention_stop_line` by the braking distance $v_{ego}^{2} / 2a_{max}$. +- If `occlusion.enable` is true and: + - if there are associated traffic lights, the pass judge line is at the `occlusion_peeking_stop_line` in order to continue peeking/collision detection while occlusion is detected. + - if there are no associated traffic lights and: + - if occlusion is detected, pass judge line is at the `occlusion_wo_tl_pass_judge_line` to continue peeking. + - if occlusion is not detected, pass judge line is at the same place at the case where `occlusion.enable` is false. + +![data structure](./docs/data-structure.drawio.svg) ### Occlusion detection @@ -170,8 +181,6 @@ entity IntersectionStopLines { @enduml ``` -![data structure](./docs/data-structure.drawio.svg) - ### Module Parameters | Parameter | Type | Description | diff --git a/planning/behavior_velocity_intersection_module/docs/data-structure.drawio.svg b/planning/behavior_velocity_intersection_module/docs/data-structure.drawio.svg index fb512902ef856..ec5878a0d828e 100644 --- a/planning/behavior_velocity_intersection_module/docs/data-structure.drawio.svg +++ b/planning/behavior_velocity_intersection_module/docs/data-structure.drawio.svg @@ -5,31 +5,31 @@ xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" version="1.1" - width="2159px" - height="1028px" - viewBox="-0.5 -0.5 2159 1028" - content="<mxfile host="Electron" modified="2023-10-03T07:12:57.327Z" agent="5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) draw.io/20.3.0 Chrome/104.0.5112.114 Electron/20.1.3 Safari/537.36" etag="t-GOTeomSwFlDSuYHtEs" version="20.3.0" type="device"><diagram name="intersection" id="0L5whF3ImEvTl2DSWTjR">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</diagram></mxfile>" + width="2382px" + height="2070px" + viewBox="-0.5 -0.5 2382 2070" + content="<mxfile host="Electron" modified="2023-11-12T05:07:41.048Z" agent="5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) draw.io/20.3.0 Chrome/104.0.5112.114 Electron/20.1.3 Safari/537.36" etag="NhhSyCkZKf7kn4cJ36_Z" version="20.3.0" type="device"><diagram name="intersection" id="0L5whF3ImEvTl2DSWTjR">7V1Zd+O2kv41fjQP9uUxdreTzknuZKazzouPLNG2bqtFjyT3cn/9gBJBkQBEgQsoyLaTnFg0BUqoD18tKFRd4OvP335cTZ4ef81m6eICgdm3C/zuAiEEMcIJUr/lF7/vLkIgCEvE7uLDaj4rLu8vfJz/J9X3Flef57N0Xbtxk2WLzfypfnGaLZfpdFO7Nlmtsq/12+6zRf2pT5OH1LrwcTpZ6Kv6S+TX/5rPNo+76wLx/fWf0vnDo342ZHL3l88TfXPxXdaPk1n2tXIJv7/A16ss2+x++/ztOl3ks6hn5s/rH8n3//tj9vsPs6ebm+t3//zvTzeXu8Fu2ryl/GqrdLnpPPQd+s91xi9//R1++BHKyfcvHy7TS4Z3Y3+ZLJ6LKSu+7Oa7nsNV9rycpfko4AJffX2cb9KPT5Np/tevCjzq2uPm80K9gurX+/licZ0tstX2vfhq+4+6vso2k808W6rLl1DkA603q+xT6ro3U6PPNznqaH6j57cvZulLutqk3yqYKGbjxzT7nG5W39UtxV8vIWNEaIAUIL+kFBTQ+LqHC8HFXY8VqDCZSA3VAqYP5UP2glC/FLJwy+Xqp38vyd0tufrKr/6S6Z+X6F83lx5ieVByeeo5N+XCm9zpYcHROcMsQRgjyjCmXNRnjwMuEyIZhVgtJASJNZVY1t4OMbZnFgvFM7QcBAPcf5r/9SGbfSNfHufk6o/Vh0/8lt/9dAk95jmftLlilF8md+nit2w9L2B8l2022WeFT33DD4v5Q/6HTWasCUUcT/lgn7895GSb3E3W82mihLa5zpbT94uFYsN0uyLUpR+WD9sng0QwlM8PJwBiqf5Td6TL2f7vEALMuIKr5JxRItXfJ6upJjmQMG6vx3dcXgFgrkfsXI8zLu+29x5dj40Q9l6P2AQGqWELcpBQC05QQBs/kMtQgCFh+dIpHxmFeJTux7QmEQRkwpBNlijh3EGXIJRM6AlkckCHjS0UiPJFU5eKkK51UrlxHKmw41LJ6Sw38tSrZbZM61Koi8ya6VIqu79o2iP23Kff5pu/i0Hz3//ZsiMtXr37Vjxh++J78aKdvNbZ82qaetBGOquZq7ZYKxKjwJaWvrZKFwqJX+qmr0uExRN+y+bqe5So4W4VXBKtxo8ecff9ikGqJqYxLmscF1FrYKXwHtKNNfAWcOWs9MAgP47B6fPqyxZlsNCvIwByObuZ59+kA9QiQVBrSftCaMdTB0fGNjgPYEjJcfK9cttTfsO66zfaP3cP0d0ThgWsaEWa08VkrUzJYDBVX+ZvzY75iwpz5i/31Ll91Y07d+LzUO+RIL89QH2hr4ZsXFQ4IH1Ofnt39fc/4OmXxeXjH/+zWV3ffZY+Tmgfu0oyjn9gfnZVfu+EjRobkATW5v+Sccksu4ogl6k7TGTgD/TlmvFZBh8I/UT/fvyVzv8KLRSDHlymbUVc0svUHUwknKHEkgqTIgHCEgwWark4fEMOk6ZF7yubO/a0+PDz37/MSHY5f/fXzz//F393qaNEr1I4Ais5EIdwOHQIR11mwYTj/E4eXmKj+VfXl7j1ZEaiv3Jmo9IQkzAjbL4663IboDNHE8anGshE2z4MHPjoQ9llThH29WVfEHaYKQBiSrsVdszRIBsRO/qjB8WOhw/6SrADobFboBZvR1tZjUaRNZowglnDYYdqM6/y0Ul47LRzB32wM5usH8twh70Fd5P/c8YQYwKZhKK8Kt4ZZPZ4DAVzwtxT7GHwvxb+cBB4d7uFIjae7rEfpnRPQkegECxb4ccZUqqRRo6Hj8V7s9XmMXvIlpPF+/3Vq3Rxtx1Lb4xaTFOAtO4KvRxUMmzoIX9U0lKHVQgnmFazPzpmoP0nNN7UG8fOYJQHjIdOVNk60PfZclO5b/cTR/oKR4gaoqDE3vrjACTUsfXHUcLIYcD3ilIFDoScpbQgoYktL+LYrGVSji6x4d2Ul25qUoupSXdPGOr5rmgRI4kl9GZpfzvhyNZTueaCbNkPt13VhL/qVn+TnqpuazXdFw+ehbDsYY4641lgczSEjNEC49lDBb3huYbnJk1exXPTffHgmUuSSGkqXEh5QjiR+qczwJ3DcwX8BJhBrcBAbxcgCJwzUAAddAE6HAvojZt3VaQ33hgR1BExcQi7B0Y4NFENTIc2MKI9kmzfEH2cuh0ZNk33RYRnABNlX5uYpiLhGJQ/3bcOnOMr1YASwEYFers96S5AL5NsXoiN0pSodNTmjg3oOZoNEHLcmbi5Fc7jCIxL3O32ycfB8xkSt85bPsrc+sZoEM0Qr2ctXjIiuxM1QuZoZYBzLON6+LShFx4X49T0/DntHkewRxN8XE7Dwyf/vHAE2PlljHTeEVPyNlMvxo6MYo/Y+ItOhDZJmEPHEWmdjhMgEdotlcA7gtFLxUx/otR1cN2RZRtSKnqhv5mA3iZgI7qPHo/B0W0kOExAnfg3iAlImDFa6GgUihDScXvpjWr0OKRj82o41iLf2yAC7MP/nfZ7LavGNWLoPTKPSOup6owIBhMACMASYKpzzPdegBRqtqT+K3KkvRBafT905VMQmAhBzEEGr+bisbV+YJabpdZ7mmECsZpogTlHCpMM4LRMOG2YSjTKVLojHh72RR+rj12L91vny8wssji7vLNbqYfWNh8EIMF1mw8znOjvXxGXUGJ1nEo0/ebhZOKB79NV0eE7NVctnIPyS7VaOcp58YLCJaFxYIEmBFRWWz1IAgFJKKiQo308kqoRhMNjo4DnhYMCAcXDkhp68R5y2cYWGabClpF9MrJkzqFXrluTeKzcwQpklDPu77clUGrT9p/iNWo2ddWL39LVXE1PujLN35YeXacyHd4hfl0N8WiIv5BIJMawWk01U0DXfypQjah0mWWtSyHg5qeA+lOIQVgDZchD2vgpoHR+iqAFQvT6DOiLtl+mY/ii+8UIAyxGdJ6LUSGvDtA6PlnzKvFdjIQ0PgV2WouDZS23O940gtLqthq0ptuvCCjh0TWhXpnabuilAXyXRlzbUBDJGmiNmCRHYAg9BY2lYTwFN2vD4ZZGY3LAq90gsYqR6IqiI1X2/axm9O/sz7v1fEa+/P7HbP4nmvvEgoY+GWVLpKBBQxjKr57N0/0BquKu2XyVTouh0sl6E1ZsVOvYitjsiBSWTrEFkln4fNSXdpSgCfpVVdJ0XySaRGGS6E22/V5rnx0tZob+qZmtPZxmcE6wR0bLGwfVJeTYWx+Xg9qdz3zjoGboH+UgFj8HEb0xPQgHERzMcXNOMAq8kROYhJZ56YuwLGSnPhJdfKu6N+eocYgBOoywXizkEzAenYbiTu9pRP9RHtI3xkNEbF+HtgQmQqhr1dt8px9Ix4gBq926ZxqdNSGp+Q5NSIxbKojZO4sjE1L406+vg5CQLyGh2AiJMmDTBwY9CIlj5BiRjk1IHmGHV05IwJRSBIQU/kzn6yAk4ktIJDZCIoINTEiMihgI6bzjRl/T0HEjbLbDy6uEWHxUpmONEjdCb4GjYfjIN3KEogsdYUtNMrNBXpvMdWweyGDcKEoXmoc8yiK/ah6iZgUX54k9LJ1nw0Lx0AB1aN94aA/+4zwkYuOhMmC9Zw7TDG8TwtZZsftNGhkshO1snuwRwTaT1tfzh+U62awmy/VTttqxSzKdrG5xHenb1MR09f5LmmcoOllqVwTnEC11zLefFK+m6XKbUmT3Ib1fzJ9+ujiUhhcw+I33bn7VuSuN4CpmiTBN4049flxCbxcAb51vdnNTk+pLKNvOqbXX1GPnilllKq3RAi97dBIEtF9vESHArjMuSWcE2KONjQCPmLMm/q+T71suz+X5Kd1MHwux52Suq+ivs0X+uKv1/D/5S3aA/4t0dTU8vbqg7wyNoGvqp2qU4vgf0Pxdef1USRfdkXwlgfRqvZw8/Z7t5u1Q8ZLDgA2pDoglc8c5ReJAsVl5ZDBF0Lcw0BEaAEDKl6YIrJrADPeIiVlngqlZzjUwDQTucH0AAeetCCyZMdYZARxYeILBIhFOBHjE1l6RIigBG1QRWAgStlcwqiLo26TrCA1wpV5v7BMoZ60I7IUruxcIY9RK9Cfj0kDgM0gHEHDWisAOSetJG8QUYKZaCYwAn7IUr0gTlIgNqQms5keMnNgl8CmE8YpQMI5jaC59rIvVnwwFrgARW+SSzttTXeRVevQcsf97znabQfj+fjtblUugkPv+Gqz/uUTV/mLlt4fi/9sn3znvzz/P5e4pP6gbEHr65hxlusjW6XpzO5990wOqqbkzH6Ku7b6hvmxgf6/ncgQd2ZQLFxptt5dmaSqso03Vsh3cEYU2y94Oh7DwSY8NUchcxB93yES6GkfbJKN2Aqv17mhacvEYOJSZu+QYdjdxuXUgCYNxYx3asX5BpLbePE8/3a432dPtYq505KsntvIs9OmILXzy5JkRW3TJjTaxEbPJRD9iGzmICwNHcV/ihq7tebEe4Rsrj4OhccM3PoUy3nZ0L5r3YKnsfiKeSSseOPKOLvQI4r557gN77ta6d7UVGNVzdwVyjxu5xb5HlEbuLL2fPC82MZi5g+1ot4KZ3YhW6jp+1Zx84DJzcSCc+Zx972nmNmweHzRzk2qtTZ0aO46ZG10TA0rMs64SGOO0MXNtrgvXx8oNOVdo+rz99/v5ar25nWw2CoPzbBkDxZ3Gky+zqJspTnfzHsWT14wWmSd/OopD0dnw2Dol0ovioEVxzBgtNMW5ouLHKY4riru/j5Pisul08bzOye0pTT/Nlw/lsCt9Swy0N1iKSivaQ5bXKLm99Ye465RTKA/C58x+T9pryAaJkfZi67nLABjSsmNaq1ZOQwYr5udORj9BRdFDZV7Le8cr86oM6cQQAWX6FGOtP6GjJcpAhV7dcvGwgAaRy2EpmD1sxpMKJciSCnVIBQtedsGodbyASdPi7icYj93zFysYwoQtGDXbukhKTTYicSnPoLJppz99mu22m8x49BTLmzuZxMa7Z8szZBMlp347LW07Z2wfRw5+/KFaZLghNHzH7vOFkC0DbIq8FYTs8QAeFUL644eF0PAtv88UQlQgW5Ez3qP4NbbH42agfTgIIQwdH3/YRj1uCPXdU351XeOxYDa5IJl07FpzYERiblOH9s76ng56SVTiovPuBk1eUm1EbeR6nNJGySgKyeOE0dA+/q7aR7YvZaTu2/1E4vlLRQ7W8oaO+o8AJNTV/RclzEDLYH4M8djhfXUCE6Rk84rAuKOqC5NyfJH1rezy+jQ2tQmdmiew/QldKQhbX5etOEbS1zrv7K1MWb+4v9ZY1TJljTfGA2sqHXaFma7Rwk6hxDGeHDf9g8RYJv0MYa31+lFY6xvjgTVROhVKagJRWbWEq78VP51R7hyeAQITAEbGevg92JdWgbtxn+Q4hUe3x5tbJkaf2ksqRXdfExPqGBCMu9NL3krLDwNs5AtsFBuwCaCJYBbLYpjwoiBo/tPdVnGOTwGiCRi3oAZpF4J/M1iOZIccx3ps7iUHwLGDaMKwTZspO/7IwMjJOiTGavxnSOHM1zZhsdkmVHJux5FZ5x01KpE9HjHb04aG9fC7HC88dkaYHRRgXdvQHxiPk5HJrW8dtFeHAleOj9UMuk2oSdjb3WNHUOkJtj6iyke16Zjq6oa1fFRnF6Bw+ag6zfK1yoXaiSfEVSoMO7uiBJQLasWabybhEXwfNQlpbGrAaRIiE3A9TUJMjPFCqwGPHYfp8+pLqd37VNjoAPAkP/JdBTkUshnm6kWlsEIv6KvvejPP57PDQogGtowgkDDBCaIMQmAeQqVM4IRiDhCQgGHUfWuBYZlwIQBX/0Kz/BAlHCak/CvyC1N1yP8hxLE7zUgC+bHPr9w7W/Vw851hMod0tm9U2uUM42jUd+OPxrbxpxagA7gUJ9Lcg26TquHIq3WOGVrLeGyJPCj8PvW0LPOzw8tlOtV1d9Q14BZrtVIaVUqGACwBVo6ZOV0CUjVdsvyzo7cVoQnYDwBdCVEEJkIQc5DhjVSPcPyBeW6WW++JhgnETChdwzmCDDKA9/VRi7nWG8INU4tOOLUeIeE+fllZCcZMFbSInF2L99twylGvrBkj3m6ZMhoSXG+Zi/OICLLkJaDWlnUZBWvu4xHQ7NhirxrvMroD3k2U7k3URG+us+X0/WIxf1qnW0mpSz8sH3YlvxLBaWEvl5dyeOKryWqqta+yb4WNhZsbxiwfndBIwEATUqFLowEgBCShoEKXdqIvzTcvHVEVCnjCeCikBE7NLuXgEVYZXWaYCltI9knSkjxHWbvMIwA5mOdZrqgWnmeeJlXzPKUu1nB6z7MRGMetZEdz2sZVE4mVrNZTzRzQ5ZMKWCMqXaZaW7s5P0HS9BRQfwrx62bb1pWFtPFTQOn8FEGdVOYRmu7ppJbUGJWTul+N7mKwPVejbw52ZKtRQa+O0DpAWfMy8V2NhDQ+BXZajIOtCNRqRQzVW3Dw5aB13X5JQAmPLgr1ytR3g68N7rs24mqjDpGsoZbXXV2OwBCaChprw3gKbtaHodeGR0hz6I1MexEVS85YLcqPm83T/RG84q7ZfJVOi6HSyXrjBPRwhdGgI+CnE+eqBV6kI+zB5GFI9jPLY8xePsNItIb/8dQ3EhVzKWBCYqe74D77nNyOQmMzyz80G3lERt/YyBCSK/FiZDaKMRH3HNmI+bIROws2gt33xJxsZDb9Cs1GHnHrPmx0c3NFOQjGRstslcs+bAE8RxkPfYKtukPkqEqIdY7D8HTULnW2W7nsQnQvOQmM+QYgWVxu3faIIbSqYwBJkx4HzyG2Rsy33MZ117hHOD5iA0nNd2hKwsKhiIi9jTIuJfHwQdlXkZfKfTOHeGyZQwwx4iAQ3IOSCGaOEcXYlITeKOkIJQG7tlYElBRjFZNzpCTkS0koNkqCEgxMSZihGCgpcFDblUYyICV9TUOHkYBwFKJldsPAMjFolDASDx/UjnPnemhG8g1q8+iC2sChKqnZV6tVarXjAOHI28/8vIPa4dkIQYfQHac8sXSeJgzFRm9B7WHYyDeozSMMarvOGvUJattFWIiZuhmajVo0Z9ap1Ov5w3KdbFaT5fopW+1IJplOVre4DvdttpzRldlKoK/1GTR4p2MW+KR4tWvYXGfCy10l38X86aeLLm3CW8bD7V0Lwmwm42UkstaK2bKTByMzCDy8vRPm4AssKGeEEgQwJBdWQj5HHBPBscSUS6/sfOcJeoTs9Hy3YgwIEiFF01EmSWA1H8g+bnOSzHwIXD7Vrh/i+mmyrCGpbWfG5v6Oh+9v6kTJpiK9u7ffu0y/bQ42cmzs+bj7mkF6Ph5wS9o3KGjnBTpq83LHURCoywrXyCpUP28ITuYGRtr2sVx70VhGVDqgw2TnauUMYEd5OmKY9oEtIwhcjlrEFHd/f5dvQlvvfVqlX6KjuAM75oEpDgFHMRBHP++xKS68b3lgvhsproVzOTjFxef8OU7lo+4ZTYxAm+KgHDe/EgKX9xc1xTF2h+33pg/Zbba63QYuUA7MCPnOeZYxMN9hR2Gu0sWoBvaxo/4BDhVKg2CMjCznfEdr0kWXMoUc0OGkR3NC6egWOHIpVQhd+VIR811xlMzmux3RPWTR8dyBw28nsOswPrnrCsOneR2Y71jtOhhdHpbTrut+boZhabeCxiMH9cuaOw6es/igmX+24fnKpeMESegBgvyQR+PXu43Ej5vs6Zf5Ml23IjBj6Wzy2F1tsViRfzNE/Xk+m+Vvv1ql6hMXdZByoBcn+9W49OqCvsvHet5ku2/lYLoiSlwNMutLxqozmgaW6zUcG3KgeUcDkAPhqujiWFfBCoeUFbaiguRvk83jL5Nlukg3b0gMoJcpt+OC0rEBhkNhcZ19nV5/ef8XWmbpf199/vAe//z9sp1W9m8bbCg13zk9YdxWgHqNoUsmzL5L/qqPMIKs0YwY8GAlQyllzHoYMqDRr5yKEzsuxfqGnZ0AGDFWbItcCCzN0TD0i/d3wI79MFY4BkGx0y7D+gVjhzB8SABdsIM07irYCVPfyfkwhvnQjcqd8GlXbXjwDiBnhzKKocUpqAdDWaNZmB3OrXMCoF09Xu/yr90luZ8cgvL6xPmpyLx3vJnEwgTieRILZ5ICIvXGcBUIECaY7t/vyGchSDnqqBwDD5Hb4pxmj/zc06VGMcQFxJwAiKX678JMjYJATQwFXHLOKJEXRmqUmjS/1CjimzJ8EGxVUB2G80FQYVYDBOf1xol5IjfGiDKMKVdGqw0pKBznpyAfYFPD+W0CVxruk9UdSkQQmTKyRFRZr/ZxEiwcWY8slNcXuHqDcxU5akG3SrwPJblLoaiCYJLX9gZccFSvQYYITnij6JAcU3R9e59FknevVCC/qOfek/KCV03ZhvJ9jeZZkzlRTcQ/vHBOZcZtC1LuKaZuWBwzCXytu8aHQCxcPDaSzefcsTSwf4pWP72Lsg6A3Op2UxPlH0U4jxbhysqrGc5d+xfuSq4eeopgjQ8ZyHlu/KLc+T2D+tMj7M7GfOI93LJzlH+Nb9kRtbKUA0UEBQBKDLVTqk0goExbRAnmQnJJpeiY+ULroNcxTb28hXrKXrUIMLJyQcdXwKkiCgLUHb5LxrXNWXXyyp5lAVpKuufMI4obqNWnsYG3+2mkncEcwR1SGtfqCUQRqP9alaa957bf8dr2ZKzX7lGW3QH2ZNZNQgiRAEGGOBSCGFGcvFNU5aej/S4JTRBFGHIoBWekzTNCU2zEQVuOTIoV2y4aGCCGsSDILmtN84IMZdyNS10yooYc6Bpk+NX/FqctqCdsDBA2h5LyvF5Z+SFGOXvuDuOeLlALTxCp9Y4DhhMTBU1iQiKX037NQkdFe+FS78FydE4RrnW1/hpLTtX1UsqBlsrsdIIIf1Yj5ronHQwzXzcZ+oan4EkjsFgg5Sgzqcw3rGw4Wd/kyR1Y5asBhjBSKs9kbV8Lrs5GLMFsvwaYDHZKxJ3i1SPkGnGQ6Hzhf9I4EaZ1IxmyunXbNV+SGPENCJvHHSgISwzFz51PDZtCGWXcNeGotqoQJs3rytE4MvyaYadcCgQbkJUDLQUjKtDsQIZm/3bduMd12I0g9SXjhFfjy3arBQpINVEGug76EuXUi72Thk05DmZLIg/X681l7+9joAM0oX1BYSXqYIf4T+eioxM4fyO46MfEIusnGpTlfUwuaFRXEHm4gpFVLh1eWN5rBnNXseRQssEeTss55Ei1c1KGSSdBjsamjbx01GVBJ/XYieFOE2UDuMDa2k6zWpU2jxvYUsNx+hF5PamaIyF4GOwP6ID4rwDf3I6drjjVCkAGUuUwCwCbC+u0+EfH8X+K1MBOQaoT8PjJ6Nk4JptXoGB4DyOzhLk3Onn9gFI93w5jPz+6fUDJ+DbA+W0O6hRcf7to927o85XDnsrzMIp38QJnSk/dAn7H5ZWjHHaXlJ6AZ72g0dKFcWjv6nKOXEWtQ+YD0XY28MvKByInVbjW8ayuBXTyoycEUMqAEAhwIOv0gEkiKdlvY4+rcWnfE9xHlOw1x/RA8SyDKO4nTABPuMR4NpcxXhesIhHUUe/lo2n3d382V48/FjT6ns7uBg1HFGUCKEKzc4aGMNPSGOteZ5VRExrc7KEXGhoeKYA6Zv118n1rcOWC/pRupo8FHnIZfyxuX2eL/HlXRUkgduHutGHXEXLUCDKLD20tlGoxooqDuStlVHE5r9bLydPv2W7iDtUYOIzkg6ZLbxNFidgsDsOEHaEjDhibJUyGM0489pV6RiuaOGKwmqcd+cTDK6Mn3efPq9hbqJHdqyExRiwzeWzicW23Ha+wNt3BqFZhbQed/TV4pABb2/KovkVWs+l08bxWLtTt1+x2sygHXekbbp/Uurn997NC6e1irjjOuuNIbdR67Tdjgfarjdpg3oXjQiqFqQCljjBUd5K4q5laMDJ89V2n8t//vKh2oAoifCyxIXyqjz2O1H/KLX+PoMkrMolubgo8BkWCSQNE2EgY1SRirniNTxMAuwJoLPppusjW6XpzO599O52eKeE0qp6B2gXeA0w6Mkm4g2nMjq7DISz8FuGByR62AHc4o3u3Bk9odNvFwgjrGjxULKffWxktWO1t94SiVpBrHQg6urjPLuBDsRXwoaJzwIdiZPpd1mihIRA4TNxAOWcLAWpBwCy00wYC9mhjQ8AjHPxm4A5r4HJL6NQ+xTiugeuK/J63gbvePE8/3a6Vy1sLr7waIxdb/rTrRPO4Rm74yPK5G7kHztyOpt6gNM1SanYd6mnh+NXZH0y9He4b2K6dVTzENkvvJ8+LTQzUdrSHViBqM/13hh0nDoCL2kIdGGIeccJzaKAVkNpOmsqYw8ZK5JDmNlcbarMSOagc13/nLy8oeT9frTe3k81GQS7fOouA4k5jvZUbsBXrza6vgTSiR7HeeJQhyvrhHXRajuMnjlESabUr6cVx3EpOGbmRhAZ4S47jiuPu7+PkuH1iwFOafpovHxypARHwHldL8eZmZN4j0ig7eplXc3Hw3pgpALxdkLQL7x2Y7HPJh9qt0hPSHjPOZvSkPSsRk/Fx07e5R1D2dafg8RMHSghFFlOZLQRb7QZamnZsb6JbBPgtBe9FpeCV7U0r+hedWv96pOC97VNfNO9TM9KDnKworjVaaHIK3FfndexTS9YdAtZoY0NAuKJdBgTe9qmHVQbWPjVzHJ8ddZ9atItBtSaCo17vGRKBtExL2iNtTS/7ypG3cUNCwhUSCg+B89YFlgI3W1a38lWs9rJ0ZAh4RGRekS4oERtUF1gQ0qHgk+mC0xxkfoFn3GnZSK2ypHvEz5iFFTmysehxkDnQGfdzhQCmZjyL9Un8ERYE+Lh5rcIj1+wV6YgRzrIrHWFBSJ8xGF5HqJerLA/37UGTH778NZul+R3/Dw==</diagram></mxfile>" > - + - - - - - + + + + + - - - - - - - - - - - - + + + + + + + + + + + + - + - + - + - + - + - - - - - + + + + + + - - - - + - - - + + + - - - - + + + + - - + + - - + + - - + + - - + + - - + + - - + + - - - - - - - - - - - + transform="translate(292.95,0)scale(-1,1)translate(-292.95,0)rotate(90,292.95,751.55)" + pointer-events="none" + /> + + + + + + + + + + +
@@ -294,18 +285,18 @@
- closest_idx + closest_idx - - - + + +
@@ -316,21 +307,21 @@
- stuck_stop_line + stuck_stop_line - - - - - - + + + + + +
@@ -341,18 +332,18 @@
- default_stop_line + default_stop_line - - - + + +
@@ -363,18 +354,18 @@
- first_attention_stop_line + first_attention_stop_line - - - + + +
@@ -389,25 +380,25 @@
- occlusion_peeking... + occlusion_peeking... - - - - - - - - - - - - - - - + + + + + + + + + + + + + + - + - + - + - + - + - - - - - + + + + + + + - - - + - - - + + + - - - + + + - - + + - - + + - - + + - - + + - - + + - - + + - +
@@ -649,18 +632,18 @@
- next + next - - - + + +
@@ -673,18 +656,18 @@
- prev + prev - - - + + +
@@ -697,18 +680,18 @@
- ego_or_entry2exit + ego_or_entry2exit - - - + + +
@@ -721,15 +704,15 @@
- entry2ego + entry2ego - - + + -
+
@@ -739,7 +722,7 @@
- IntersectionStopLines + IntersectionStopLines @@ -747,7 +730,7 @@
@@ -758,9 +741,325 @@
- PathLanelets + PathLanelets + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ + + occlusion_wo_tl +
+ _pass_judge_line +
+
+
+
+
+
+
+ occlusion_wo_tl... +
+
+ + + + + + +
+
+
+ + closest_idx + +
+
+
+
+ closest_idx +
+
+ + + + + + + + + +
+
+
+ + stuck_stop_line + +
+
+
+
+ stuck_stop_line +
+
+ + + + + + +
+
+
+ + default_stop_line + +
+
+
+
+ default_stop_line +
+
+ + + + + + +
+
+
+ + first_attention_stop_line + +
+
+
+
+ first_attention_stop_line +
+
+ + + + + + +
+
+
+ + + occlusion_peeking +
+ _stop_line +
+
+
+
+
+
+ occlusion_peeking... +
+
+ + + + + + + + +
+
+
+ + + occlusion_wo_tl +
+ _pass_judge_line +
+
+
+
+
+
+
+ occlusion_wo_tl...
+ + + + + + + + + diff --git a/planning/behavior_velocity_intersection_module/src/manager.cpp b/planning/behavior_velocity_intersection_module/src/manager.cpp index 5c5f5eac16b81..5de74aeb82d86 100644 --- a/planning/behavior_velocity_intersection_module/src/manager.cpp +++ b/planning/behavior_velocity_intersection_module/src/manager.cpp @@ -193,6 +193,7 @@ void IntersectionModuleManager::launchNewModules( const auto lanelets = planning_utils::getLaneletsOnPath(path, lanelet_map, planner_data_->current_odometry->pose); // run occlusion detection only in the first intersection + // TODO(Mamoru Sobue): remove `enable_occlusion_detection` variable const bool enable_occlusion_detection = intersection_param_.occlusion.enable; for (size_t i = 0; i < lanelets.size(); i++) { const auto ll = lanelets.at(i); diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp index c3b429680ab91..476238f6b1e9e 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -936,6 +936,7 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( const auto routing_graph_ptr = planner_data_->route_handler_->getRoutingGraphPtr(); const auto & assigned_lanelet = lanelet_map_ptr->laneletLayer.get(lane_id_); const std::string turn_direction = assigned_lanelet.attributeOr("turn_direction", "else"); + const double baselink2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; // spline interpolation const auto interpolated_path_info_opt = util::generateInterpolatedPath( @@ -969,15 +970,17 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( const bool is_prioritized = traffic_prioritized_level == util::TrafficPrioritizedLevel::FULLY_PRIORITIZED; const auto footprint = planner_data_->vehicle_info_.createFootprint(0.0, 0.0); - intersection_lanelets.update(is_prioritized, interpolated_path_info, footprint); + intersection_lanelets.update(is_prioritized, interpolated_path_info, footprint, baselink2front); // this is abnormal const auto & conflicting_lanelets = intersection_lanelets.conflicting(); const auto & first_conflicting_area_opt = intersection_lanelets.first_conflicting_area(); - if (conflicting_lanelets.empty() || !first_conflicting_area_opt) { + const auto & first_conflicting_lane_opt = intersection_lanelets.first_conflicting_lane(); + if (conflicting_lanelets.empty() || !first_conflicting_area_opt || !first_conflicting_lane_opt) { return IntersectionModule::Indecisive{"conflicting area is empty"}; } - const auto first_conflicting_area = first_conflicting_area_opt.value(); + const auto & first_conflicting_lane = first_conflicting_lane_opt.value(); + const auto & first_conflicting_area = first_conflicting_area_opt.value(); // generate all stop line candidates // see the doc for struct IntersectionStopLines @@ -986,22 +989,24 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( /// conflicting lanes const auto & dummy_first_attention_area = first_attention_area_opt ? first_attention_area_opt.value() : first_conflicting_area; - const double peeking_offset = - has_traffic_light_ ? planner_param_.occlusion.peeking_offset - : planner_param_.occlusion.absence_traffic_light.maximum_peeking_distance; + const auto & dummy_first_attention_lane_centerline = + intersection_lanelets.first_attention_lane() + ? intersection_lanelets.first_attention_lane().value().centerline2d() + : first_conflicting_lane.centerline2d(); const auto intersection_stop_lines_opt = util::generateIntersectionStopLines( - first_conflicting_area, dummy_first_attention_area, planner_data_, interpolated_path_info, - planner_param_.stuck_vehicle.use_stuck_stopline, planner_param_.common.stop_line_margin, - planner_param_.common.max_accel, planner_param_.common.max_jerk, - planner_param_.common.delay_response_time, peeking_offset, path); + first_conflicting_area, dummy_first_attention_area, dummy_first_attention_lane_centerline, + planner_data_, interpolated_path_info, planner_param_.stuck_vehicle.use_stuck_stopline, + planner_param_.common.stop_line_margin, planner_param_.common.max_accel, + planner_param_.common.max_jerk, planner_param_.common.delay_response_time, + planner_param_.occlusion.peeking_offset, path); if (!intersection_stop_lines_opt) { return IntersectionModule::Indecisive{"failed to generate intersection_stop_lines"}; } const auto & intersection_stop_lines = intersection_stop_lines_opt.value(); const auto [closest_idx, stuck_stop_line_idx_opt, default_stop_line_idx_opt, - first_attention_stop_line_idx_opt, occlusion_peeking_stop_line_idx_opt, pass_judge_line_idx] = - intersection_stop_lines; + first_attention_stop_line_idx_opt, occlusion_peeking_stop_line_idx_opt, + default_pass_judge_line_idx, occlusion_wo_tl_pass_judge_line_idx] = intersection_stop_lines; // see the doc for struct PathLanelets const auto & conflicting_area = intersection_lanelets.conflicting_area(); @@ -1083,16 +1088,91 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( if (!default_stop_line_idx_opt) { return IntersectionModule::Indecisive{"default stop line is null"}; } + // occlusion stop line is generated from the intersection of ego footprint along the path with the + // attention area, so if this is null, eog has already passed the intersection + if (!first_attention_stop_line_idx_opt || !occlusion_peeking_stop_line_idx_opt) { + return IntersectionModule::Indecisive{"occlusion stop line is null"}; + } const auto default_stop_line_idx = default_stop_line_idx_opt.value(); + const bool is_over_default_stop_line = + util::isOverTargetIndex(*path, closest_idx, current_pose, default_stop_line_idx); + const auto collision_stop_line_idx = + is_over_default_stop_line ? closest_idx : default_stop_line_idx; + const auto first_attention_stop_line_idx = first_attention_stop_line_idx_opt.value(); + const auto occlusion_stop_line_idx = occlusion_peeking_stop_line_idx_opt.value(); + + const auto & adjacent_lanelets = intersection_lanelets.adjacent(); + const auto & occlusion_attention_lanelets = intersection_lanelets.occlusion_attention(); + const auto & occlusion_attention_area = intersection_lanelets.occlusion_attention_area(); + debug_data_.attention_area = intersection_lanelets.attention_area(); + debug_data_.occlusion_attention_area = occlusion_attention_area; + debug_data_.adjacent_area = intersection_lanelets.adjacent_area(); + + // check occlusion on detection lane + if (!occlusion_attention_divisions_) { + occlusion_attention_divisions_ = util::generateDetectionLaneDivisions( + occlusion_attention_lanelets, routing_graph_ptr, + planner_data_->occupancy_grid->info.resolution, + planner_param_.occlusion.attention_lane_crop_curvature_threshold, + planner_param_.occlusion.attention_lane_curvature_calculation_ds); + } + const auto & occlusion_attention_divisions = occlusion_attention_divisions_.value(); + + // get intersection area + const auto intersection_area = util::getIntersectionArea(assigned_lanelet, lanelet_map_ptr); + // filter objects + auto target_objects = generateTargetObjects(intersection_lanelets, intersection_area); + + const double occlusion_dist_thr = std::fabs( + std::pow(planner_param_.occlusion.max_vehicle_velocity_for_rss, 2) / + (2 * planner_param_.occlusion.min_vehicle_brake_for_rss)); + auto occlusion_status = + (enable_occlusion_detection_ && !occlusion_attention_lanelets.empty() && !is_prioritized) + ? getOcclusionStatus( + *planner_data_->occupancy_grid, occlusion_attention_area, adjacent_lanelets, + first_attention_area, interpolated_path_info, occlusion_attention_divisions, + target_objects, current_pose, occlusion_dist_thr) + : OcclusionType::NOT_OCCLUDED; + occlusion_stop_state_machine_.setStateWithMarginTime( + occlusion_status == OcclusionType::NOT_OCCLUDED ? StateMachine::State::GO : StateMachine::STOP, + logger_.get_child("occlusion_stop"), *clock_); + const bool is_occlusion_cleared_with_margin = + (occlusion_stop_state_machine_.getState() == StateMachine::State::GO); + // distinguish if ego detected occlusion or RTC detects occlusion + const bool ext_occlusion_requested = (is_occlusion_cleared_with_margin && !occlusion_activated_); + if (ext_occlusion_requested) { + occlusion_status = OcclusionType::RTC_OCCLUDED; + } + const bool is_occlusion_state = (!is_occlusion_cleared_with_margin || ext_occlusion_requested); + if (is_occlusion_state && occlusion_status == OcclusionType::NOT_OCCLUDED) { + occlusion_status = prev_occlusion_status_; + } else { + prev_occlusion_status_ = occlusion_status; + } // TODO(Mamoru Sobue): this part needs more formal handling - const double baselink2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; + const size_t pass_judge_line_idx = [=]() { + if (enable_occlusion_detection_) { + // if occlusion detection is enabled, pass_judge position is beyond the boundary of first + // attention area + if (has_traffic_light_) { + return occlusion_stop_line_idx; + } else if (is_occlusion_state) { + // if there is no traffic light and occlusion is detected, pass_judge position is beyond + // the boundary of first attention area + return occlusion_wo_tl_pass_judge_line_idx; + } else { + // if there is no traffic light and occlusion is not detected, pass_judge position is + // default + return default_pass_judge_line_idx; + } + } + return default_pass_judge_line_idx; + }(); debug_data_.pass_judge_wall_pose = planning_utils::getAheadPose(pass_judge_line_idx, baselink2front, *path); const bool is_over_pass_judge_line = util::isOverTargetIndex(*path, closest_idx, current_pose, pass_judge_line_idx); - const bool is_over_default_stop_line = - util::isOverTargetIndex(*path, closest_idx, current_pose, default_stop_line_idx); const double vel_norm = std::hypot( planner_data_->current_velocity->twist.linear.x, planner_data_->current_velocity->twist.linear.y); @@ -1113,28 +1193,6 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( return IntersectionModule::Indecisive{"over the pass judge line. no plan needed"}; } - // occlusion stop line is generated from the intersection of ego footprint along the path with the - // attention area, so if this is null, eog has already passed the intersection - if (!first_attention_stop_line_idx_opt || !occlusion_peeking_stop_line_idx_opt) { - return IntersectionModule::Indecisive{"occlusion stop line is null"}; - } - const auto collision_stop_line_idx = - is_over_default_stop_line ? closest_idx : default_stop_line_idx; - const auto first_attention_stop_line_idx = first_attention_stop_line_idx_opt.value(); - const auto occlusion_stop_line_idx = occlusion_peeking_stop_line_idx_opt.value(); - - const auto & adjacent_lanelets = intersection_lanelets.adjacent(); - const auto & occlusion_attention_lanelets = intersection_lanelets.occlusion_attention(); - const auto & occlusion_attention_area = intersection_lanelets.occlusion_attention_area(); - debug_data_.attention_area = intersection_lanelets.attention_area(); - debug_data_.occlusion_attention_area = occlusion_attention_area; - debug_data_.adjacent_area = intersection_lanelets.adjacent_area(); - - // get intersection area - const auto intersection_area = util::getIntersectionArea(assigned_lanelet, lanelet_map_ptr); - - auto target_objects = generateTargetObjects(intersection_lanelets, intersection_area); - // If there are any vehicles on the attention area when ego entered the intersection on green // light, do pseudo collision detection because the vehicles are very slow and no collisions may // be detected. check if ego vehicle entered assigned lanelet @@ -1196,43 +1254,6 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( has_collision_with_margin, closest_idx, collision_stop_line_idx, occlusion_stop_line_idx}; } - // check occlusion on detection lane - if (!occlusion_attention_divisions_) { - occlusion_attention_divisions_ = util::generateDetectionLaneDivisions( - occlusion_attention_lanelets, routing_graph_ptr, - planner_data_->occupancy_grid->info.resolution, - planner_param_.occlusion.attention_lane_crop_curvature_threshold, - planner_param_.occlusion.attention_lane_curvature_calculation_ds); - } - const auto & occlusion_attention_divisions = occlusion_attention_divisions_.value(); - - const double occlusion_dist_thr = std::fabs( - std::pow(planner_param_.occlusion.max_vehicle_velocity_for_rss, 2) / - (2 * planner_param_.occlusion.min_vehicle_brake_for_rss)); - auto occlusion_status = - (enable_occlusion_detection_ && !occlusion_attention_lanelets.empty() && !is_prioritized) - ? getOcclusionStatus( - *planner_data_->occupancy_grid, occlusion_attention_area, adjacent_lanelets, - first_attention_area, interpolated_path_info, occlusion_attention_divisions, - target_objects, current_pose, occlusion_dist_thr) - : OcclusionType::NOT_OCCLUDED; - occlusion_stop_state_machine_.setStateWithMarginTime( - occlusion_status == OcclusionType::NOT_OCCLUDED ? StateMachine::State::GO : StateMachine::STOP, - logger_.get_child("occlusion_stop"), *clock_); - const bool is_occlusion_cleared_with_margin = - (occlusion_stop_state_machine_.getState() == StateMachine::State::GO); - // distinguish if ego detected occlusion or RTC detects occlusion - const bool ext_occlusion_requested = (is_occlusion_cleared_with_margin && !occlusion_activated_); - if (ext_occlusion_requested) { - occlusion_status = OcclusionType::RTC_OCCLUDED; - } - const bool is_occlusion_state = (!is_occlusion_cleared_with_margin || ext_occlusion_requested); - if (is_occlusion_state && occlusion_status == OcclusionType::NOT_OCCLUDED) { - occlusion_status = prev_occlusion_status_; - } else { - prev_occlusion_status_ = occlusion_status; - } - // Safe if (!is_occlusion_state && !has_collision_with_margin) { return IntersectionModule::Safe{closest_idx, collision_stop_line_idx, occlusion_stop_line_idx}; @@ -1257,14 +1278,14 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( temporal_stop_before_attention_state_machine_) : false; if (!has_traffic_light_) { - if (fromEgoDist(first_attention_stop_line_idx) <= -peeking_offset) { + if (fromEgoDist(occlusion_wo_tl_pass_judge_line_idx) < 0) { return IntersectionModule::Indecisive{ "already passed maximum peeking line in the absence of traffic light"}; } return IntersectionModule::OccludedAbsenceTrafficLight{ is_occlusion_cleared_with_margin, has_collision_with_margin, temporal_stop_before_attention_required, closest_idx, - first_attention_stop_line_idx, occlusion_stop_line_idx}; + first_attention_stop_line_idx, occlusion_wo_tl_pass_judge_line_idx}; } // following remaining block is "has_traffic_light_" // if ego is stuck by static occlusion in the presence of traffic light, start timeout count diff --git a/planning/behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp b/planning/behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp index 698242da67528..f1b516d72726f 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp @@ -96,7 +96,9 @@ bool MergeFromPrivateRoadModule::modifyPathVelocity(PathWithLaneId * path, StopR } auto & intersection_lanelets = intersection_lanelets_.value(); const auto local_footprint = planner_data_->vehicle_info_.createFootprint(0.0, 0.0); - intersection_lanelets.update(false, interpolated_path_info, local_footprint); + intersection_lanelets.update( + false, interpolated_path_info, local_footprint, + planner_data_->vehicle_info_.max_longitudinal_offset_m); const auto & first_conflicting_area = intersection_lanelets.first_conflicting_area(); if (!first_conflicting_area) { return false; diff --git a/planning/behavior_velocity_intersection_module/src/util.cpp b/planning/behavior_velocity_intersection_module/src/util.cpp index e6e6fa0a1da9a..093f90e4b3df7 100644 --- a/planning/behavior_velocity_intersection_module/src/util.cpp +++ b/planning/behavior_velocity_intersection_module/src/util.cpp @@ -215,13 +215,15 @@ static std::optional getStopLineIndexFromMap( static std::optional getFirstPointInsidePolygonByFootprint( const lanelet::CompoundPolygon3d & polygon, const InterpolatedPathInfo & interpolated_path_info, - const tier4_autoware_utils::LinearRing2d & footprint) + const tier4_autoware_utils::LinearRing2d & footprint, const double vehicle_length) { const auto & path_ip = interpolated_path_info.path; const auto [lane_start, lane_end] = interpolated_path_info.lane_id_interval.value(); - + const size_t vehicle_length_idx = static_cast(vehicle_length / interpolated_path_info.ds); + const size_t start = + static_cast(std::max(0, static_cast(lane_start) - vehicle_length_idx)); const auto area_2d = lanelet::utils::to2D(polygon).basicPolygon(); - for (auto i = lane_start; i <= lane_end; ++i) { + for (auto i = start; i <= lane_end; ++i) { const auto & base_pose = path_ip.points.at(i).point.pose; const auto path_footprint = tier4_autoware_utils::transformVector( footprint, tier4_autoware_utils::pose2transform(base_pose)); @@ -237,12 +239,15 @@ static std::optional & polygons, const InterpolatedPathInfo & interpolated_path_info, - const tier4_autoware_utils::LinearRing2d & footprint) + const tier4_autoware_utils::LinearRing2d & footprint, const double vehicle_length) { const auto & path_ip = interpolated_path_info.path; const auto [lane_start, lane_end] = interpolated_path_info.lane_id_interval.value(); + const size_t vehicle_length_idx = static_cast(vehicle_length / interpolated_path_info.ds); + const size_t start = + static_cast(std::max(0, static_cast(lane_start) - vehicle_length_idx)); - for (size_t i = lane_start; i <= lane_end; ++i) { + for (size_t i = start; i <= lane_end; ++i) { const auto & pose = path_ip.points.at(i).point.pose; const auto path_footprint = tier4_autoware_utils::transformVector(footprint, tier4_autoware_utils::pose2transform(pose)); @@ -259,7 +264,8 @@ getFirstPointInsidePolygonsByFootprint( std::optional generateIntersectionStopLines( const lanelet::CompoundPolygon3d & first_conflicting_area, - const lanelet::CompoundPolygon3d & first_detection_area, + const lanelet::CompoundPolygon3d & first_attention_area, + const lanelet::ConstLineString2d & first_attention_lane_centerline, const std::shared_ptr & planner_data, const InterpolatedPathInfo & interpolated_path_info, const bool use_stuck_stopline, const double stop_line_margin, const double max_accel, const double max_jerk, @@ -269,31 +275,39 @@ std::optional generateIntersectionStopLines( const auto & path_ip = interpolated_path_info.path; const double ds = interpolated_path_info.ds; const auto & lane_interval_ip = interpolated_path_info.lane_id_interval.value(); + const double baselink2front = planner_data->vehicle_info_.max_longitudinal_offset_m; const int stop_line_margin_idx_dist = std::ceil(stop_line_margin / ds); const int base2front_idx_dist = std::ceil(planner_data->vehicle_info_.max_longitudinal_offset_m / ds); - /* - // find the index of the first point that intersects with detection_areas - const auto first_inside_detection_idx_ip_opt = - getFirstPointInsidePolygon(path_ip, lane_interval_ip, first_detection_area); - // if path is not intersecting with detection_area, error - if (!first_inside_detection_idx_ip_opt) { - return std::nullopt; - } - const auto first_inside_detection_ip = first_inside_detection_idx_ip_opt.value(); - */ // find the index of the first point whose vehicle footprint on it intersects with detection_area const auto local_footprint = planner_data->vehicle_info_.createFootprint(0.0, 0.0); std::optional first_footprint_inside_detection_ip_opt = getFirstPointInsidePolygonByFootprint( - first_detection_area, interpolated_path_info, local_footprint); + first_attention_area, interpolated_path_info, local_footprint, baselink2front); if (!first_footprint_inside_detection_ip_opt) { return std::nullopt; } const auto first_footprint_inside_detection_ip = first_footprint_inside_detection_ip_opt.value(); + std::optional first_footprint_attention_centerline_ip_opt = std::nullopt; + for (auto i = std::get<0>(lane_interval_ip); i < std::get<1>(lane_interval_ip); ++i) { + const auto & base_pose = path_ip.points.at(i).point.pose; + const auto path_footprint = tier4_autoware_utils::transformVector( + local_footprint, tier4_autoware_utils::pose2transform(base_pose)); + if (bg::intersects(path_footprint, first_attention_lane_centerline.basicLineString())) { + // TODO(Mamoru Sobue): maybe consideration of braking dist is necessary + first_footprint_attention_centerline_ip_opt = i; + break; + } + } + if (!first_footprint_attention_centerline_ip_opt) { + return std::nullopt; + } + const size_t first_footprint_attention_centerline_ip = + first_footprint_attention_centerline_ip_opt.value(); + // (1) default stop line position on interpolated path bool default_stop_line_valid = true; int stop_idx_ip_int = -1; @@ -318,24 +332,25 @@ std::optional generateIntersectionStopLines( // (3) occlusion peeking stop line position on interpolated path int occlusion_peeking_line_ip_int = static_cast(default_stop_line_ip); bool occlusion_peeking_line_valid = true; + // NOTE: if footprints[0] is already inside the detection area, invalid { - // NOTE: if footprints[0] is already inside the detection area, invalid const auto & base_pose0 = path_ip.points.at(default_stop_line_ip).point.pose; const auto path_footprint0 = tier4_autoware_utils::transformVector( local_footprint, tier4_autoware_utils::pose2transform(base_pose0)); if (bg::intersects( - path_footprint0, lanelet::utils::to2D(first_detection_area).basicPolygon())) { + path_footprint0, lanelet::utils::to2D(first_attention_area).basicPolygon())) { occlusion_peeking_line_valid = false; } } if (occlusion_peeking_line_valid) { - occlusion_peeking_line_ip_int = first_footprint_inside_detection_ip; + occlusion_peeking_line_ip_int = + first_footprint_inside_detection_ip + std::ceil(peeking_offset / ds); } - const auto first_attention_stop_line_ip = static_cast(occlusion_peeking_line_ip_int); - const bool first_attention_stop_line_valid = occlusion_peeking_line_valid; - occlusion_peeking_line_ip_int += std::ceil(peeking_offset / ds); + const auto occlusion_peeking_line_ip = static_cast( std::clamp(occlusion_peeking_line_ip_int, 0, static_cast(path_ip.points.size()) - 1)); + const auto first_attention_stop_line_ip = first_footprint_inside_detection_ip; + const bool first_attention_stop_line_valid = true; // (4) pass judge line position on interpolated path const double velocity = planner_data->current_velocity->twist.linear.x; @@ -346,6 +361,9 @@ std::optional generateIntersectionStopLines( static_cast(first_footprint_inside_detection_ip) - std::ceil(braking_dist / ds); const auto pass_judge_line_ip = static_cast( std::clamp(pass_judge_ip_int, 0, static_cast(path_ip.points.size()) - 1)); + // TODO(Mamoru Sobue): maybe braking dist should be considered + const auto occlusion_wo_tl_pass_judge_line_ip = + static_cast(first_footprint_attention_centerline_ip); // (5) stuck vehicle stop line int stuck_stop_line_ip_int = 0; @@ -354,7 +372,7 @@ std::optional generateIntersectionStopLines( // NOTE: when ego vehicle is approaching detection area and already passed // first_conflicting_area, this could be null. const auto stuck_stop_line_idx_ip_opt = getFirstPointInsidePolygonByFootprint( - first_conflicting_area, interpolated_path_info, local_footprint); + first_conflicting_area, interpolated_path_info, local_footprint, baselink2front); if (!stuck_stop_line_idx_ip_opt) { stuck_stop_line_valid = false; stuck_stop_line_ip_int = 0; @@ -378,6 +396,7 @@ std::optional generateIntersectionStopLines( size_t first_attention_stop_line{0}; size_t occlusion_peeking_stop_line{0}; size_t pass_judge_line{0}; + size_t occlusion_wo_tl_pass_judge_line{0}; }; IntersectionStopLinesTemp intersection_stop_lines_temp; @@ -388,7 +407,8 @@ std::optional generateIntersectionStopLines( {&first_attention_stop_line_ip, &intersection_stop_lines_temp.first_attention_stop_line}, {&occlusion_peeking_line_ip, &intersection_stop_lines_temp.occlusion_peeking_stop_line}, {&pass_judge_line_ip, &intersection_stop_lines_temp.pass_judge_line}, - }; + {&occlusion_wo_tl_pass_judge_line_ip, + &intersection_stop_lines_temp.occlusion_wo_tl_pass_judge_line}}; stop_lines.sort( [](const auto & it1, const auto & it2) { return *(std::get<0>(it1)) < *(std::get<0>(it2)); }); for (const auto & [stop_idx_ip, stop_idx] : stop_lines) { @@ -407,12 +427,6 @@ std::optional generateIntersectionStopLines( intersection_stop_lines_temp.occlusion_peeking_stop_line = intersection_stop_lines_temp.default_stop_line; } - if ( - intersection_stop_lines_temp.occlusion_peeking_stop_line > - intersection_stop_lines_temp.pass_judge_line) { - intersection_stop_lines_temp.pass_judge_line = - intersection_stop_lines_temp.occlusion_peeking_stop_line; - } IntersectionStopLines intersection_stop_lines; intersection_stop_lines.closest_idx = intersection_stop_lines_temp.closest_idx; @@ -431,6 +445,8 @@ std::optional generateIntersectionStopLines( intersection_stop_lines_temp.occlusion_peeking_stop_line; } intersection_stop_lines.pass_judge_line = intersection_stop_lines_temp.pass_judge_line; + intersection_stop_lines.occlusion_wo_tl_pass_judge_line = + intersection_stop_lines_temp.occlusion_wo_tl_pass_judge_line; return intersection_stop_lines; } @@ -1457,13 +1473,13 @@ double calcDistanceUntilIntersectionLanelet( void IntersectionLanelets::update( const bool is_prioritized, const InterpolatedPathInfo & interpolated_path_info, - const tier4_autoware_utils::LinearRing2d & footprint) + const tier4_autoware_utils::LinearRing2d & footprint, const double vehicle_length) { is_prioritized_ = is_prioritized; // find the first conflicting/detection area polygon intersecting the path if (!first_conflicting_area_) { - auto first = - getFirstPointInsidePolygonsByFootprint(conflicting_area_, interpolated_path_info, footprint); + auto first = getFirstPointInsidePolygonsByFootprint( + conflicting_area_, interpolated_path_info, footprint, vehicle_length); if (first) { first_conflicting_lane_ = conflicting_.at(first.value().second); first_conflicting_area_ = conflicting_area_.at(first.value().second); @@ -1471,7 +1487,7 @@ void IntersectionLanelets::update( } if (!first_attention_area_) { auto first = getFirstPointInsidePolygonsByFootprint( - attention_non_preceding_area_, interpolated_path_info, footprint); + attention_non_preceding_area_, interpolated_path_info, footprint, vehicle_length); if (first) { first_attention_lane_ = attention_non_preceding_.at(first.value().second); first_attention_area_ = attention_non_preceding_area_.at(first.value().second); diff --git a/planning/behavior_velocity_intersection_module/src/util.hpp b/planning/behavior_velocity_intersection_module/src/util.hpp index 2f204f06aac7c..0ff35ab5c0c23 100644 --- a/planning/behavior_velocity_intersection_module/src/util.hpp +++ b/planning/behavior_velocity_intersection_module/src/util.hpp @@ -69,7 +69,8 @@ std::optional generateStuckStopLine( std::optional generateIntersectionStopLines( const lanelet::CompoundPolygon3d & first_conflicting_area, - const lanelet::CompoundPolygon3d & first_detection_area, + const lanelet::CompoundPolygon3d & first_attention_area, + const lanelet::ConstLineString2d & first_attention_lane_centerline, const std::shared_ptr & planner_data, const InterpolatedPathInfo & interpolated_path_info, const bool use_stuck_stopline, const double stop_line_margin, const double max_accel, const double max_jerk, diff --git a/planning/behavior_velocity_intersection_module/src/util_type.hpp b/planning/behavior_velocity_intersection_module/src/util_type.hpp index 73e60aea6471a..d1ee4c2f79410 100644 --- a/planning/behavior_velocity_intersection_module/src/util_type.hpp +++ b/planning/behavior_velocity_intersection_module/src/util_type.hpp @@ -74,7 +74,7 @@ struct IntersectionLanelets public: void update( const bool is_prioritized, const InterpolatedPathInfo & interpolated_path_info, - const tier4_autoware_utils::LinearRing2d & footprint); + const tier4_autoware_utils::LinearRing2d & footprint, const double vehicle_length); const lanelet::ConstLanelets & attention() const { return is_prioritized_ ? attention_non_preceding_ : attention_; @@ -160,6 +160,7 @@ struct IntersectionStopLines std::optional occlusion_peeking_stop_line{std::nullopt}; // if the value is calculated negative, its value is 0 size_t pass_judge_line{0}; + size_t occlusion_wo_tl_pass_judge_line{0}; }; struct PathLanelets From d749a7d9d5d3269ee8b5978cc74cb94de1fb8503 Mon Sep 17 00:00:00 2001 From: Shunsuke Miura <37187849+miursh@users.noreply.github.com> Date: Mon, 13 Nov 2023 12:48:27 +0900 Subject: [PATCH 171/202] fix: scan ground filter document (#5552) Signed-off-by: Shunsuke Miura --- .../docs/scan-ground-filter.md | 39 ++++++++++--------- 1 file changed, 20 insertions(+), 19 deletions(-) diff --git a/perception/ground_segmentation/docs/scan-ground-filter.md b/perception/ground_segmentation/docs/scan-ground-filter.md index bc44544fa298c..21df6fa6ea1b9 100644 --- a/perception/ground_segmentation/docs/scan-ground-filter.md +++ b/perception/ground_segmentation/docs/scan-ground-filter.md @@ -30,25 +30,26 @@ This implementation inherits `pointcloud_preprocessor::Filter` class, please ref #### Core Parameters ![scan_ground_parameter](./image/scan_ground_filter_parameters.drawio.svg) -| Name | Type | Default Value | Description | -| --------------------------------- | ------ | ------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| `input_frame` | string | "base_link" | frame id of input pointcloud | -| `output_frame` | string | "base_link" | frame id of output pointcloud | -| `global_slope_max_angle_deg` | double | 8.0 | The global angle to classify as the ground or object [deg].
A large threshold may reduce false positive of high slope road classification but it may lead to increase false negative of non-ground classification, particularly for small objects. | -| `local_slope_max_angle_deg` | double | 10.0 | The local angle to classify as the ground or object [deg] when comparing with adjacent point.
A small value enhance accuracy classification of object with inclined surface. This should be considered together with `split_points_distance_tolerance` value. | -| `radial_divider_angle_deg` | double | 1.0 | The angle which divide the whole pointcloud to sliced group [deg] | -| `split_points_distance_tolerance` | double | 0.2 | The xy-distance threshold to distinguish far and near [m] | -| `split_height_distance` | double | 0.2 | The height threshold to distinguish ground and non-ground pointcloud when comparing with adjacent points [m].
A small threshold improves classification of non-ground point, especially for high elevation resolution pointcloud lidar. However, it might cause false positive for small step-like road surface or misaligned multiple lidar configuration. | -| `use_virtual_ground_point` | bool | true | whether to use the ground center of front wheels as the virtual ground point. | -| `detection_range_z_max` | float | 2.5 | Maximum height of detection range [m], applied only for elevation_grid_mode | -| `center_pcl_shift` | float | 0.0 | The x-axis offset of addition LiDARs from vehicle center of mass [m],
recommended to use only for additional LiDARs in elevation_grid_mode | -| `non_ground_height_threshold` | float | 0.2 | Height threshold of non ground objects [m] as `split_height_distance` and applied only for elevation_grid_mode | -| `grid_mode_switch_radius` | float | 20.0 | The distance where grid division mode change from by distance to by vertical angle [m],
applied only for elevation_grid_mode | -| `grid_size_m` | float | 0.5 | The first grid size [m], applied only for elevation_grid_mode.
A large value enhances the prediction stability for ground surface. suitable for rough surface or multiple lidar configuration. | -| `gnd_grid_buffer_size` | uint16 | 4 | Number of grids using to estimate local ground slope,
applied only for elevation_grid_mode | -| `low_priority_region_x` | float | -20.0 | The non-zero x threshold in back side from which small objects detection is low priority [m] | -| `elevation_grid_mode` | bool | true | Elevation grid scan mode option | -| `use_recheck_ground_cluster` | bool | true | Enable recheck ground cluster | + +| Name | Type | Default Value | Description | +| --------------------------------- | ------ | ------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| `input_frame` | string | "base_link" | frame id of input pointcloud | +| `output_frame` | string | "base_link" | frame id of output pointcloud | +| `global_slope_max_angle_deg` | double | 8.0 | The global angle to classify as the ground or object [deg].
A large threshold may reduce false positive of high slope road classification but it may lead to increase false negative of non-ground classification, particularly for small objects. | +| `local_slope_max_angle_deg` | double | 10.0 | The local angle to classify as the ground or object [deg] when comparing with adjacent point.
A small value enhance accuracy classification of object with inclined surface. This should be considered together with `split_points_distance_tolerance` value. | +| `radial_divider_angle_deg` | double | 1.0 | The angle which divide the whole pointcloud to sliced group [deg] | +| `split_points_distance_tolerance` | double | 0.2 | The xy-distance threshold to distinguish far and near [m] | +| `split_height_distance` | double | 0.2 | The height threshold to distinguish ground and non-ground pointcloud when comparing with adjacent points [m].
A small threshold improves classification of non-ground point, especially for high elevation resolution pointcloud lidar. However, it might cause false positive for small step-like road surface or misaligned multiple lidar configuration. | +| `use_virtual_ground_point` | bool | true | whether to use the ground center of front wheels as the virtual ground point. | +| `detection_range_z_max` | float | 2.5 | Maximum height of detection range [m], applied only for elevation_grid_mode | +| `center_pcl_shift` | float | 0.0 | The x-axis offset of addition LiDARs from vehicle center of mass [m],
recommended to use only for additional LiDARs in elevation_grid_mode | +| `non_ground_height_threshold` | float | 0.2 | Height threshold of non ground objects [m] as `split_height_distance` and applied only for elevation_grid_mode | +| `grid_mode_switch_radius` | float | 20.0 | The distance where grid division mode change from by distance to by vertical angle [m],
applied only for elevation_grid_mode | +| `grid_size_m` | float | 0.5 | The first grid size [m], applied only for elevation_grid_mode.
A large value enhances the prediction stability for ground surface. suitable for rough surface or multiple lidar configuration. | +| `gnd_grid_buffer_size` | uint16 | 4 | Number of grids using to estimate local ground slope,
applied only for elevation_grid_mode | +| `low_priority_region_x` | float | -20.0 | The non-zero x threshold in back side from which small objects detection is low priority [m] | +| `elevation_grid_mode` | bool | true | Elevation grid scan mode option | +| `use_recheck_ground_cluster` | bool | true | Enable recheck ground cluster | ## Assumptions / Known limits From 2a697c2aadc40bd5d9d6d4f45c1b087bc529639a Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Mon, 13 Nov 2023 13:14:55 +0900 Subject: [PATCH 172/202] feat(geo_pose_projector): use geo_pose_projector in eagleye (#5513) * feat(tier4_geo_pose_projector): use tier4_geo_pose_projector in eagleye Signed-off-by: kminoda * style(pre-commit): autofix * fix(eagleye): split fix2pose Signed-off-by: kminoda * style(pre-commit): autofix * fix name: fuser -> fusion Signed-off-by: kminoda * style(pre-commit): autofix * update Signed-off-by: kminoda * style(pre-commit): autofix * update readme Signed-off-by: kminoda * style(pre-commit): autofix * add #include Signed-off-by: kminoda * add rclcpp in dependency Signed-off-by: kminoda * style(pre-commit): autofix * add limitation in readme Signed-off-by: kminoda * style(pre-commit): autofix * update tier4_localization_launch Signed-off-by: kminoda * update tier4_localization_launch Signed-off-by: kminoda * rename package Signed-off-by: kminoda * style(pre-commit): autofix --------- Signed-off-by: kminoda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../eagleye/eagleye_rt.launch.xml | 10 +- .../eagleye/geo_pose_converter.launch.xml | 23 ---- launch/tier4_localization_launch/package.xml | 2 +- .../geo_pose_projector/CMakeLists.txt | 17 +++ localization/geo_pose_projector/README.md | 28 +++++ .../config/geo_pose_projector.param.yaml | 5 + .../launch/geo_pose_projector.launch.xml | 13 +++ localization/geo_pose_projector/package.xml | 30 +++++ .../schema/geo_pose_projector.schema.json | 43 ++++++++ .../src/geo_pose_projector.cpp | 103 ++++++++++++++++++ .../src/geo_pose_projector.hpp | 58 ++++++++++ .../src/geo_pose_projector_node.cpp | 29 +++++ 12 files changed, 334 insertions(+), 27 deletions(-) delete mode 100644 launch/tier4_localization_launch/launch/pose_twist_estimator/eagleye/geo_pose_converter.launch.xml create mode 100644 localization/geo_pose_projector/CMakeLists.txt create mode 100644 localization/geo_pose_projector/README.md create mode 100644 localization/geo_pose_projector/config/geo_pose_projector.param.yaml create mode 100644 localization/geo_pose_projector/launch/geo_pose_projector.launch.xml create mode 100644 localization/geo_pose_projector/package.xml create mode 100644 localization/geo_pose_projector/schema/geo_pose_projector.schema.json create mode 100644 localization/geo_pose_projector/src/geo_pose_projector.cpp create mode 100644 localization/geo_pose_projector/src/geo_pose_projector.hpp create mode 100644 localization/geo_pose_projector/src/geo_pose_projector_node.cpp diff --git a/launch/tier4_localization_launch/launch/pose_twist_estimator/eagleye/eagleye_rt.launch.xml b/launch/tier4_localization_launch/launch/pose_twist_estimator/eagleye/eagleye_rt.launch.xml index 12d84f374f7c7..6cf8d390f919b 100644 --- a/launch/tier4_localization_launch/launch/pose_twist_estimator/eagleye/eagleye_rt.launch.xml +++ b/launch/tier4_localization_launch/launch/pose_twist_estimator/eagleye/eagleye_rt.launch.xml @@ -145,9 +145,13 @@ - - - + + + + + + + diff --git a/launch/tier4_localization_launch/launch/pose_twist_estimator/eagleye/geo_pose_converter.launch.xml b/launch/tier4_localization_launch/launch/pose_twist_estimator/eagleye/geo_pose_converter.launch.xml deleted file mode 100644 index d4f82e72a297b..0000000000000 --- a/launch/tier4_localization_launch/launch/pose_twist_estimator/eagleye/geo_pose_converter.launch.xml +++ /dev/null @@ -1,23 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - diff --git a/launch/tier4_localization_launch/package.xml b/launch/tier4_localization_launch/package.xml index 9a137032e1277..1126914d58c5a 100644 --- a/launch/tier4_localization_launch/package.xml +++ b/launch/tier4_localization_launch/package.xml @@ -16,11 +16,11 @@ ar_tag_based_localizer automatic_pose_initializer - eagleye_geo_pose_converter eagleye_geo_pose_fusion eagleye_gnss_converter eagleye_rt ekf_localizer + geo_pose_projector gyro_odometer ndt_scan_matcher pointcloud_preprocessor diff --git a/localization/geo_pose_projector/CMakeLists.txt b/localization/geo_pose_projector/CMakeLists.txt new file mode 100644 index 0000000000000..6e2cdf32fb6c5 --- /dev/null +++ b/localization/geo_pose_projector/CMakeLists.txt @@ -0,0 +1,17 @@ +cmake_minimum_required(VERSION 3.14) +project(geo_pose_projector) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +ament_auto_add_executable(geo_pose_projector + src/geo_pose_projector_node.cpp + src/geo_pose_projector.cpp +) +ament_target_dependencies(geo_pose_projector) + +ament_auto_package( + INSTALL_TO_SHARE + launch + config +) diff --git a/localization/geo_pose_projector/README.md b/localization/geo_pose_projector/README.md new file mode 100644 index 0000000000000..a3363336da1a7 --- /dev/null +++ b/localization/geo_pose_projector/README.md @@ -0,0 +1,28 @@ +# geo_pose_projector + +## Overview + +This node is a simple node that subscribes to the geo-referenced pose topic and publishes the pose in the map frame. + +## Subscribed Topics + +| Name | Type | Description | +| ------------------------- | ---------------------------------------------------- | ------------------- | +| `input_geo_pose` | `geographic_msgs::msg::GeoPoseWithCovarianceStamped` | geo-referenced pose | +| `/map/map_projector_info` | `tier4_map_msgs::msg::MapProjectedObjectInfo` | map projector info | + +## Published Topics + +| Name | Type | Description | +| ------------- | ----------------------------------------------- | ------------------------------------- | +| `output_pose` | `geometry_msgs::msg::PoseWithCovarianceStamped` | pose in map frame | +| `/tf` | `tf2_msgs::msg::TFMessage` | tf from parent link to the child link | + +## Parameters + +{{ json_to_markdown("localization/geo_pose_projector/schema/geo_pose_projector.schema.json") }} + +## Limitations + +The covariance conversion may be incorrect depending on the projection type you are using. The covariance of input topic is expressed in (Latitude, Longitude, Altitude) as a diagonal matrix. +Currently, we assume that the x axis is the east direction and the y axis is the north direction. Thus, the conversion may be incorrect when this assumption breaks, especially when the covariance of latitude and longitude is different. diff --git a/localization/geo_pose_projector/config/geo_pose_projector.param.yaml b/localization/geo_pose_projector/config/geo_pose_projector.param.yaml new file mode 100644 index 0000000000000..704d9dce8a4ee --- /dev/null +++ b/localization/geo_pose_projector/config/geo_pose_projector.param.yaml @@ -0,0 +1,5 @@ +/**: + ros__parameters: + publish_tf: true + parent_frame: "map" + child_frame: "pose_estimator_base_link" diff --git a/localization/geo_pose_projector/launch/geo_pose_projector.launch.xml b/localization/geo_pose_projector/launch/geo_pose_projector.launch.xml new file mode 100644 index 0000000000000..d840add1ed1c7 --- /dev/null +++ b/localization/geo_pose_projector/launch/geo_pose_projector.launch.xml @@ -0,0 +1,13 @@ + + + + + + + + + + + + + diff --git a/localization/geo_pose_projector/package.xml b/localization/geo_pose_projector/package.xml new file mode 100644 index 0000000000000..d424ff14b9c99 --- /dev/null +++ b/localization/geo_pose_projector/package.xml @@ -0,0 +1,30 @@ + + + + geo_pose_projector + 0.1.0 + The geo_pose_projector package + Yamato Ando + Koji Minoda + Apache License 2.0 + Koji Minoda + + ament_cmake_auto + autoware_cmake + + component_interface_specs + component_interface_utils + geographic_msgs + geography_utils + geometry_msgs + rclcpp + tf2_geometry_msgs + tf2_ros + + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/localization/geo_pose_projector/schema/geo_pose_projector.schema.json b/localization/geo_pose_projector/schema/geo_pose_projector.schema.json new file mode 100644 index 0000000000000..9daafb27f4320 --- /dev/null +++ b/localization/geo_pose_projector/schema/geo_pose_projector.schema.json @@ -0,0 +1,43 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for geo_pose_projector", + "type": "object", + "definitions": { + "geo_pose_projector": { + "type": "object", + "properties": { + "publish_tf": { + "type": "boolean", + "description": "whether to publish tf", + "default": true + }, + "parent_frame": { + "type": "string", + "description": "parent frame for published tf", + "default": "map" + }, + "child_frame": { + "type": "string", + "description": "child frame for published tf", + "default": "pose_estimator_base_link" + } + }, + "required": ["publish_tf", "parent_frame", "child_frame"], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/geo_pose_projector" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} diff --git a/localization/geo_pose_projector/src/geo_pose_projector.cpp b/localization/geo_pose_projector/src/geo_pose_projector.cpp new file mode 100644 index 0000000000000..6d5308b929b25 --- /dev/null +++ b/localization/geo_pose_projector/src/geo_pose_projector.cpp @@ -0,0 +1,103 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "geo_pose_projector.hpp" + +#include +#include + +#ifdef ROS_DISTRO_GALACTIC +#include +#else +#include +#endif + +#include + +GeoPoseProjector::GeoPoseProjector() +: Node("geo_pose_projector"), publish_tf_(declare_parameter("publish_tf")) +{ + // Subscribe to map_projector_info topic + const auto adaptor = component_interface_utils::NodeAdaptor(this); + adaptor.init_sub( + sub_map_projector_info_, + [this](const MapProjectorInfo::Message::ConstSharedPtr msg) { projector_info_ = *msg; }); + + // Subscribe to geo_pose topic + geo_pose_sub_ = create_subscription( + "input_geo_pose", 10, [this](const GeoPoseWithCovariance::SharedPtr msg) { on_geo_pose(msg); }); + + // Publish pose topic + pose_pub_ = create_publisher("output_pose", 10); + + // Publish tf + if (publish_tf_) { + tf_broadcaster_ = std::make_unique(this); + parent_frame_ = declare_parameter("parent_frame"); + child_frame_ = declare_parameter("child_frame"); + } +} + +void GeoPoseProjector::on_geo_pose(const GeoPoseWithCovariance::SharedPtr msg) +{ + if (!projector_info_) { + RCLCPP_WARN_THROTTLE( + get_logger(), *get_clock(), 1000 /* ms */, "map_projector_info is not received yet."); + return; + } + + // get position + geographic_msgs::msg::GeoPoint gps_point; + gps_point.latitude = msg->pose.pose.position.latitude; + gps_point.longitude = msg->pose.pose.position.longitude; + gps_point.altitude = msg->pose.pose.position.altitude; + geometry_msgs::msg::Point position = + geography_utils::project_forward(gps_point, projector_info_.value()); + position.z = geography_utils::convert_height( + position.z, gps_point.latitude, gps_point.longitude, MapProjectorInfo::Message::WGS84, + projector_info_.value().vertical_datum); + + // Convert geo_pose to pose + PoseWithCovariance projected_pose; + projected_pose.header = msg->header; + projected_pose.pose.pose.position = position; + projected_pose.pose.pose.orientation = msg->pose.pose.orientation; + projected_pose.pose.covariance = msg->pose.covariance; + + // Covariance in GeoPoseWithCovariance is in Lat/Lon/Alt coordinate. + // TODO(TIER IV): This swap may be invalid when using other projector type. + projected_pose.pose.covariance[0] = msg->pose.covariance[7]; + projected_pose.pose.covariance[7] = msg->pose.covariance[0]; + + pose_pub_->publish(projected_pose); + + // Publish tf + if (publish_tf_) { + tf2::Transform transform; + transform.setOrigin(tf2::Vector3( + projected_pose.pose.pose.position.x, projected_pose.pose.pose.position.y, + projected_pose.pose.pose.position.z)); + const auto localization_quat = tf2::Quaternion( + projected_pose.pose.pose.orientation.x, projected_pose.pose.pose.orientation.y, + projected_pose.pose.pose.orientation.z, projected_pose.pose.pose.orientation.w); + transform.setRotation(localization_quat); + + geometry_msgs::msg::TransformStamped transform_stamped; + transform_stamped.header = msg->header; + transform_stamped.header.frame_id = parent_frame_; + transform_stamped.child_frame_id = child_frame_; + transform_stamped.transform = tf2::toMsg(transform); + tf_broadcaster_->sendTransform(transform_stamped); + } +} diff --git a/localization/geo_pose_projector/src/geo_pose_projector.hpp b/localization/geo_pose_projector/src/geo_pose_projector.hpp new file mode 100644 index 0000000000000..b24b976b1eb61 --- /dev/null +++ b/localization/geo_pose_projector/src/geo_pose_projector.hpp @@ -0,0 +1,58 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef GEO_POSE_PROJECTOR_HPP_ +#define GEO_POSE_PROJECTOR_HPP_ + +#include +#include +#include + +#include +#include + +#include + +#include +#include +#include + +class GeoPoseProjector : public rclcpp::Node +{ +private: + using GeoPoseWithCovariance = geographic_msgs::msg::GeoPoseWithCovarianceStamped; + using PoseWithCovariance = geometry_msgs::msg::PoseWithCovarianceStamped; + using MapProjectorInfo = map_interface::MapProjectorInfo; + +public: + GeoPoseProjector(); + +private: + void on_geo_pose(const GeoPoseWithCovariance::SharedPtr msg); + + component_interface_utils::Subscription::SharedPtr sub_map_projector_info_; + rclcpp::Subscription::SharedPtr geo_pose_sub_; + rclcpp::Publisher::SharedPtr pose_pub_; + + std::unique_ptr tf_broadcaster_; + + std::optional projector_info_ = std::nullopt; + + const bool publish_tf_; + + std::string parent_frame_; + std::string child_frame_; +}; + +#endif // GEO_POSE_PROJECTOR_HPP_ diff --git a/localization/geo_pose_projector/src/geo_pose_projector_node.cpp b/localization/geo_pose_projector/src/geo_pose_projector_node.cpp new file mode 100644 index 0000000000000..97367d6b9f774 --- /dev/null +++ b/localization/geo_pose_projector/src/geo_pose_projector_node.cpp @@ -0,0 +1,29 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "geo_pose_projector.hpp" + +#include + +#include + +int main(int argc, char ** argv) +{ + rclcpp::init(argc, argv); + + rclcpp::spin(std::make_shared()); + rclcpp::shutdown(); + + return 0; +} From a37b4f36b9ecc4f59ac4b9d298f4ffaf263107b1 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Mon, 13 Nov 2023 13:23:03 +0900 Subject: [PATCH 173/202] feat(simple_planning_simulator): add acceleration and steer command scaling factor for debug (#5534) * feat(simple_planning_simulator): add acceleration and steer command scaling factor Signed-off-by: kosuke55 * update params as debug Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 --- simulator/simple_planning_simulator/README.md | 28 ++++++++++--------- .../sim_model_delay_steer_acc.hpp | 21 ++++++++------ .../sim_model_delay_steer_acc_geared.hpp | 21 ++++++++------ .../simple_planning_simulator_core.cpp | 8 ++++-- .../sim_model_delay_steer_acc.cpp | 13 ++++++--- .../sim_model_delay_steer_acc_geared.cpp | 14 ++++++---- 6 files changed, 65 insertions(+), 40 deletions(-) diff --git a/simulator/simple_planning_simulator/README.md b/simulator/simple_planning_simulator/README.md index 75f77489daada..0c5441c1ad9c8 100644 --- a/simulator/simple_planning_simulator/README.md +++ b/simulator/simple_planning_simulator/README.md @@ -67,19 +67,21 @@ The `IDEAL` model moves ideally as commanded, while the `DELAY` model moves base The table below shows which models correspond to what parameters. The model names are written in abbreviated form (e.g. IDEAL_STEER_VEL = I_ST_V). -| Name | Type | Description | I_ST_V | I_ST_A | I_ST_A_G | D_ST_V | D_ST_A | D_ST_A_G | Default value | unit | -| :------------------ | :----- | :--------------------------------------------------- | :----- | :----- | :------- | :----- | :----- | :------- | :------------ | :------ | -| acc_time_delay | double | dead time for the acceleration input | x | x | x | x | o | o | 0.1 | [s] | -| steer_time_delay | double | dead time for the steering input | x | x | x | o | o | o | 0.24 | [s] | -| vel_time_delay | double | dead time for the velocity input | x | x | x | o | x | x | 0.25 | [s] | -| acc_time_constant | double | time constant of the 1st-order acceleration dynamics | x | x | x | x | o | o | 0.1 | [s] | -| steer_time_constant | double | time constant of the 1st-order steering dynamics | x | x | x | o | o | o | 0.27 | [s] | -| steer_dead_band | double | dead band for steering angle | x | x | x | o | o | o | 0.0 | [rad] | -| vel_time_constant | double | time constant of the 1st-order velocity dynamics | x | x | x | o | x | x | 0.5 | [s] | -| vel_lim | double | limit of velocity | x | x | x | o | o | o | 50.0 | [m/s] | -| vel_rate_lim | double | limit of acceleration | x | x | x | o | o | o | 7.0 | [m/ss] | -| steer_lim | double | limit of steering angle | x | x | x | o | o | o | 1.0 | [rad] | -| steer_rate_lim | double | limit of steering angle change rate | x | x | x | o | o | o | 5.0 | [rad/s] | +| Name | Type | Description | I_ST_V | I_ST_A | I_ST_A_G | D_ST_V | D_ST_A | D_ST_A_G | Default value | unit | +| :------------------------- | :----- | :--------------------------------------------------- | :----- | :----- | :------- | :----- | :----- | :------- | :------------ | :------ | +| acc_time_delay | double | dead time for the acceleration input | x | x | x | x | o | o | 0.1 | [s] | +| steer_time_delay | double | dead time for the steering input | x | x | x | o | o | o | 0.24 | [s] | +| vel_time_delay | double | dead time for the velocity input | x | x | x | o | x | x | 0.25 | [s] | +| acc_time_constant | double | time constant of the 1st-order acceleration dynamics | x | x | x | x | o | o | 0.1 | [s] | +| steer_time_constant | double | time constant of the 1st-order steering dynamics | x | x | x | o | o | o | 0.27 | [s] | +| steer_dead_band | double | dead band for steering angle | x | x | x | o | o | o | 0.0 | [rad] | +| vel_time_constant | double | time constant of the 1st-order velocity dynamics | x | x | x | o | x | x | 0.5 | [s] | +| vel_lim | double | limit of velocity | x | x | x | o | o | o | 50.0 | [m/s] | +| vel_rate_lim | double | limit of acceleration | x | x | x | o | o | o | 7.0 | [m/ss] | +| steer_lim | double | limit of steering angle | x | x | x | o | o | o | 1.0 | [rad] | +| steer_rate_lim | double | limit of steering angle change rate | x | x | x | o | o | o | 5.0 | [rad/s] | +| debug_acc_scaling_factor | double | scaling factor for accel command | x | x | x | x | o | o | 1.0 | [-] | +| debug_steer_scaling_factor | double | scaling factor for steer command | x | x | x | x | o | o | 1.0 | [-] | diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.hpp b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.hpp index 289c607a18d90..92129541ff891 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.hpp +++ b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.hpp @@ -40,11 +40,14 @@ class SimModelDelaySteerAcc : public SimModelInterface * @param [in] steer_delay time delay for steering command [s] * @param [in] steer_time_constant time constant for 1D model of steering dynamics * @param [in] steer_dead_band dead band for steering angle [rad] + * @param [in] debug_acc_scaling_factor scaling factor for accel command + * @param [in] debug_steer_scaling_factor scaling factor for steering command */ SimModelDelaySteerAcc( double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, double dt, double acc_delay, double acc_time_constant, double steer_delay, - double steer_time_constant, double steer_dead_band); + double steer_time_constant, double steer_dead_band, double debug_acc_scaling_factor, + double debug_steer_scaling_factor); /** * @brief default destructor @@ -74,13 +77,15 @@ class SimModelDelaySteerAcc : public SimModelInterface const double steer_rate_lim_; //!< @brief steering angular velocity limit [rad/s] const double wheelbase_; //!< @brief vehicle wheelbase length [m] - std::deque acc_input_queue_; //!< @brief buffer for accel command - std::deque steer_input_queue_; //!< @brief buffer for steering command - const double acc_delay_; //!< @brief time delay for accel command [s] - const double acc_time_constant_; //!< @brief time constant for accel dynamics - const double steer_delay_; //!< @brief time delay for steering command [s] - const double steer_time_constant_; //!< @brief time constant for steering dynamics - const double steer_dead_band_; //!< @brief dead band for steering angle [rad] + std::deque acc_input_queue_; //!< @brief buffer for accel command + std::deque steer_input_queue_; //!< @brief buffer for steering command + const double acc_delay_; //!< @brief time delay for accel command [s] + const double acc_time_constant_; //!< @brief time constant for accel dynamics + const double steer_delay_; //!< @brief time delay for steering command [s] + const double steer_time_constant_; //!< @brief time constant for steering dynamics + const double steer_dead_band_; //!< @brief dead band for steering angle [rad] + const double debug_acc_scaling_factor_; //!< @brief scaling factor for accel command + const double debug_steer_scaling_factor_; //!< @brief scaling factor for steering command /** * @brief set queue buffer for input command diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.hpp b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.hpp index 3bda878f8cd76..376ee55f1aa5e 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.hpp +++ b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.hpp @@ -40,11 +40,14 @@ class SimModelDelaySteerAccGeared : public SimModelInterface * @param [in] steer_delay time delay for steering command [s] * @param [in] steer_time_constant time constant for 1D model of steering dynamics * @param [in] steer_dead_band dead band for steering angle [rad] + * @param [in] debug_acc_scaling_factor scaling factor for accel command + * @param [in] debug_steer_scaling_factor scaling factor for steering command */ SimModelDelaySteerAccGeared( double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, double dt, double acc_delay, double acc_time_constant, double steer_delay, - double steer_time_constant, double steer_dead_band); + double steer_time_constant, double steer_dead_band, double debug_acc_scaling_factor, + double debug_steer_scaling_factor); /** * @brief default destructor @@ -74,13 +77,15 @@ class SimModelDelaySteerAccGeared : public SimModelInterface const double steer_rate_lim_; //!< @brief steering angular velocity limit [rad/s] const double wheelbase_; //!< @brief vehicle wheelbase length [m] - std::deque acc_input_queue_; //!< @brief buffer for accel command - std::deque steer_input_queue_; //!< @brief buffer for steering command - const double acc_delay_; //!< @brief time delay for accel command [s] - const double acc_time_constant_; //!< @brief time constant for accel dynamics - const double steer_delay_; //!< @brief time delay for steering command [s] - const double steer_time_constant_; //!< @brief time constant for steering dynamics - const double steer_dead_band_; //!< @brief dead band for steering angle [rad] + std::deque acc_input_queue_; //!< @brief buffer for accel command + std::deque steer_input_queue_; //!< @brief buffer for steering command + const double acc_delay_; //!< @brief time delay for accel command [s] + const double acc_time_constant_; //!< @brief time constant for accel dynamics + const double steer_delay_; //!< @brief time delay for steering command [s] + const double steer_time_constant_; //!< @brief time constant for steering dynamics + const double steer_dead_band_; //!< @brief dead band for steering angle [rad] + const double debug_acc_scaling_factor_; //!< @brief scaling factor for accel command + const double debug_steer_scaling_factor_; //!< @brief scaling factor for steering command /** * @brief set queue buffer for input command diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp index f2629a0586045..07a5d34f63c39 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp @@ -230,6 +230,8 @@ void SimplePlanningSimulator::initialize_vehicle_model() const double steer_time_delay = declare_parameter("steer_time_delay", 0.24); const double steer_time_constant = declare_parameter("steer_time_constant", 0.27); const double steer_dead_band = declare_parameter("steer_dead_band", 0.0); + const double debug_acc_scaling_factor = declare_parameter("debug_acc_scaling_factor", 1.0); + const double debug_steer_scaling_factor = declare_parameter("debug_steer_scaling_factor", 1.0); const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo(); const double wheelbase = vehicle_info.wheel_base_m; @@ -251,12 +253,14 @@ void SimplePlanningSimulator::initialize_vehicle_model() vehicle_model_type_ = VehicleModelType::DELAY_STEER_ACC; vehicle_model_ptr_ = std::make_shared( vel_lim, steer_lim, vel_rate_lim, steer_rate_lim, wheelbase, timer_sampling_time_ms_ / 1000.0, - acc_time_delay, acc_time_constant, steer_time_delay, steer_time_constant, steer_dead_band); + acc_time_delay, acc_time_constant, steer_time_delay, steer_time_constant, steer_dead_band, + debug_acc_scaling_factor, debug_steer_scaling_factor); } else if (vehicle_model_type_str == "DELAY_STEER_ACC_GEARED") { vehicle_model_type_ = VehicleModelType::DELAY_STEER_ACC_GEARED; vehicle_model_ptr_ = std::make_shared( vel_lim, steer_lim, vel_rate_lim, steer_rate_lim, wheelbase, timer_sampling_time_ms_ / 1000.0, - acc_time_delay, acc_time_constant, steer_time_delay, steer_time_constant, steer_dead_band); + acc_time_delay, acc_time_constant, steer_time_delay, steer_time_constant, steer_dead_band, + debug_acc_scaling_factor, debug_steer_scaling_factor); } else { throw std::invalid_argument("Invalid vehicle_model_type: " + vehicle_model_type_str); } diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.cpp index 964157cdeb64c..670671165de60 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.cpp @@ -19,7 +19,8 @@ SimModelDelaySteerAcc::SimModelDelaySteerAcc( double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, double dt, double acc_delay, double acc_time_constant, double steer_delay, - double steer_time_constant, double steer_dead_band) + double steer_time_constant, double steer_dead_band, double debug_acc_scaling_factor, + double debug_steer_scaling_factor) : SimModelInterface(6 /* dim x */, 2 /* dim u */), MIN_TIME_CONSTANT(0.03), vx_lim_(vx_lim), @@ -31,7 +32,9 @@ SimModelDelaySteerAcc::SimModelDelaySteerAcc( acc_time_constant_(std::max(acc_time_constant, MIN_TIME_CONSTANT)), steer_delay_(steer_delay), steer_time_constant_(std::max(steer_time_constant, MIN_TIME_CONSTANT)), - steer_dead_band_(steer_dead_band) + steer_dead_band_(steer_dead_band), + debug_acc_scaling_factor_(std::max(debug_acc_scaling_factor, 0.0)), + debug_steer_scaling_factor_(std::max(debug_steer_scaling_factor, 0.0)) { initializeInputQueue(dt); } @@ -104,8 +107,10 @@ Eigen::VectorXd SimModelDelaySteerAcc::calcModel( const double acc = sat(state(IDX::ACCX), vx_rate_lim_, -vx_rate_lim_); const double yaw = state(IDX::YAW); const double steer = state(IDX::STEER); - const double acc_des = sat(input(IDX_U::ACCX_DES), vx_rate_lim_, -vx_rate_lim_); - const double steer_des = sat(input(IDX_U::STEER_DES), steer_lim_, -steer_lim_); + const double acc_des = + sat(input(IDX_U::ACCX_DES), vx_rate_lim_, -vx_rate_lim_) * debug_acc_scaling_factor_; + const double steer_des = + sat(input(IDX_U::STEER_DES), steer_lim_, -steer_lim_) * debug_steer_scaling_factor_; const double steer_diff = steer - steer_des; const double steer_diff_with_dead_band = std::invoke([&]() { if (steer_diff > steer_dead_band_) { diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.cpp index 76669c9490fc6..d72b8bf116d77 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.cpp @@ -21,7 +21,8 @@ SimModelDelaySteerAccGeared::SimModelDelaySteerAccGeared( double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, double dt, double acc_delay, double acc_time_constant, double steer_delay, - double steer_time_constant, double steer_dead_band) + double steer_time_constant, double steer_dead_band, double debug_acc_scaling_factor, + double debug_steer_scaling_factor) : SimModelInterface(6 /* dim x */, 2 /* dim u */), MIN_TIME_CONSTANT(0.03), vx_lim_(vx_lim), @@ -33,8 +34,9 @@ SimModelDelaySteerAccGeared::SimModelDelaySteerAccGeared( acc_time_constant_(std::max(acc_time_constant, MIN_TIME_CONSTANT)), steer_delay_(steer_delay), steer_time_constant_(std::max(steer_time_constant, MIN_TIME_CONSTANT)), - steer_dead_band_(steer_dead_band) - + steer_dead_band_(steer_dead_band), + debug_acc_scaling_factor_(std::max(debug_acc_scaling_factor, 0.0)), + debug_steer_scaling_factor_(std::max(debug_steer_scaling_factor, 0.0)) { initializeInputQueue(dt); } @@ -113,8 +115,10 @@ Eigen::VectorXd SimModelDelaySteerAccGeared::calcModel( const double acc = sat(state(IDX::ACCX), vx_rate_lim_, -vx_rate_lim_); const double yaw = state(IDX::YAW); const double steer = state(IDX::STEER); - const double acc_des = sat(input(IDX_U::ACCX_DES), vx_rate_lim_, -vx_rate_lim_); - const double steer_des = sat(input(IDX_U::STEER_DES), steer_lim_, -steer_lim_); + const double acc_des = + sat(input(IDX_U::ACCX_DES), vx_rate_lim_, -vx_rate_lim_) * debug_acc_scaling_factor_; + const double steer_des = + sat(input(IDX_U::STEER_DES), steer_lim_, -steer_lim_) * debug_steer_scaling_factor_; const double steer_diff = steer - steer_des; const double steer_diff_with_dead_band = std::invoke([&]() { if (steer_diff > steer_dead_band_) { From a0cd7ad4bdf6449776898a8ef221921a942ca2c3 Mon Sep 17 00:00:00 2001 From: Kento Yabuuchi Date: Mon, 13 Nov 2023 17:44:07 +0900 Subject: [PATCH 174/202] fix(ndt_scan_matcher): make regularization process thread safe (#5550) * use mutex rather than main_callback_group Signed-off-by: Kento Yabuuchi * subscribe reg_pose only when regularization is enabled Signed-off-by: Kento Yabuuchi * add some comments to describe Signed-off-by: Kento Yabuuchi * use initial_pose_callback_group Signed-off-by: Kento Yabuuchi * fix typo (pauses->poses) Signed-off-by: Kento Yabuuchi Co-authored-by: Yamato Ando --------- Signed-off-by: Kento Yabuuchi Co-authored-by: Yamato Ando --- .../ndt_scan_matcher_core.hpp | 5 +- .../src/ndt_scan_matcher_core.cpp | 51 ++++++++++++++----- 2 files changed, 40 insertions(+), 16 deletions(-) diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp index f0d90fdfa0e08..6f9420f5bc71a 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp @@ -204,9 +204,10 @@ class NDTScanMatcher : public rclcpp::Node std::mutex initial_pose_array_mtx_; // variables for regularization - const bool regularization_enabled_; + const bool regularization_enabled_; // whether to use longitudinal regularization std::deque - regularization_pose_msg_ptr_array_; + regularization_pose_msg_ptr_array_; // queue for storing regularization base poses + std::mutex regularization_mutex_; // mutex for regularization_pose_msg_ptr_array_ bool is_activated_; std::shared_ptr tf2_listener_module_; diff --git a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp index a2e89540a172f..1317b8bacf47f 100644 --- a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp +++ b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp @@ -219,10 +219,20 @@ NDTScanMatcher::NDTScanMatcher() sensor_points_sub_ = this->create_subscription( "points_raw", rclcpp::SensorDataQoS().keep_last(points_queue_size), std::bind(&NDTScanMatcher::callback_sensor_points, this, std::placeholders::_1), main_sub_opt); - regularization_pose_sub_ = - this->create_subscription( - "regularization_pose_with_covariance", 100, - std::bind(&NDTScanMatcher::callback_regularization_pose, this, std::placeholders::_1)); + + // Only if regularization is enabled, subscribe to the regularization base pose + if (regularization_enabled_) { + // NOTE: The reason that the regularization subscriber does not belong to the + // main_callback_group is to ensure that the regularization callback is called even if + // sensor_callback takes long time to process. + // Both callback_initial_pose and callback_regularization_pose must not miss receiving data for + // proper interpolation. + regularization_pose_sub_ = + this->create_subscription( + "regularization_pose_with_covariance", 10, + std::bind(&NDTScanMatcher::callback_regularization_pose, this, std::placeholders::_1), + initial_pose_sub_opt); + } sensor_aligned_pose_pub_ = this->create_publisher("points_aligned", 10); @@ -397,7 +407,10 @@ void NDTScanMatcher::callback_initial_pose( void NDTScanMatcher::callback_regularization_pose( geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr pose_conv_msg_ptr) { + // Get lock for regularization_pose_msg_ptr_array_ + std::lock_guard lock(regularization_mutex_); regularization_pose_msg_ptr_array_.push_back(pose_conv_msg_ptr); + // Release lock for regularization_pose_msg_ptr_array_ } void NDTScanMatcher::callback_sensor_points( @@ -459,7 +472,9 @@ void NDTScanMatcher::callback_sensor_points( initial_pose_array_lock.unlock(); // if regularization is enabled and available, set pose to NDT for regularization - if (regularization_enabled_) add_regularization_pose(sensor_ros_time); + if (regularization_enabled_) { + add_regularization_pose(sensor_ros_time); + } if (ndt_ptr_->getInputTarget() == nullptr) { RCLCPP_WARN_STREAM_THROTTLE(this->get_logger(), *this->get_clock(), 1, "No MAP!"); @@ -816,21 +831,29 @@ std::array NDTScanMatcher::estimate_covariance( std::optional NDTScanMatcher::interpolate_regularization_pose( const rclcpp::Time & sensor_ros_time) { - if (regularization_pose_msg_ptr_array_.empty()) { - return std::nullopt; - } + std::shared_ptr interpolator = nullptr; + { + // Get lock for regularization_pose_msg_ptr_array_ + std::lock_guard lock(regularization_mutex_); - // synchronization - PoseArrayInterpolator interpolator(this, sensor_ros_time, regularization_pose_msg_ptr_array_); + if (regularization_pose_msg_ptr_array_.empty()) { + return std::nullopt; + } + + interpolator = std::make_shared( + this, sensor_ros_time, regularization_pose_msg_ptr_array_); - pop_old_pose(regularization_pose_msg_ptr_array_, sensor_ros_time); + // Remove old poses to make next interpolation more efficient + pop_old_pose(regularization_pose_msg_ptr_array_, sensor_ros_time); + + // Release lock for regularization_pose_msg_ptr_array_ + } - // if the interpolate_pose fails, 0.0 is stored in the stamp - if (rclcpp::Time(interpolator.get_current_pose().header.stamp).seconds() == 0.0) { + if (!interpolator || !interpolator->is_success()) { return std::nullopt; } - return pose_to_matrix4f(interpolator.get_current_pose().pose.pose); + return pose_to_matrix4f(interpolator->get_current_pose().pose.pose); } void NDTScanMatcher::add_regularization_pose(const rclcpp::Time & sensor_ros_time) From 8f0767875f4428b92c890c23cce6770f00c7f838 Mon Sep 17 00:00:00 2001 From: Bupesh Rethinam Veeraiah <93628947+bupeshr@users.noreply.github.com> Date: Mon, 13 Nov 2023 17:53:46 +0900 Subject: [PATCH 175/202] test(obstacle_velocity_limiter): added test cases for particle model and approximation method (#5342) Co-authored-by: Maxime CLEMENT --- .../test/test_collision_distance.cpp | 215 +++++++++++++++++- 1 file changed, 212 insertions(+), 3 deletions(-) diff --git a/planning/obstacle_velocity_limiter/test/test_collision_distance.cpp b/planning/obstacle_velocity_limiter/test/test_collision_distance.cpp index e9cf8d9ad4dd6..c5e69e5fd8fb9 100644 --- a/planning/obstacle_velocity_limiter/test/test_collision_distance.cpp +++ b/planning/obstacle_velocity_limiter/test/test_collision_distance.cpp @@ -34,7 +34,7 @@ const auto point_in_polygon = [](const auto x, const auto y, const auto & polygo }) != polygon.outer().end(); }; -TEST(TestCollisionDistance, distanceToClosestCollision) +TEST(TestCollisionDistance, distanceToClosestCollisionParticleModel) { using obstacle_velocity_limiter::CollisionChecker; using obstacle_velocity_limiter::distanceToClosestCollision; @@ -76,11 +76,11 @@ TEST(TestCollisionDistance, distanceToClosestCollision) ASSERT_TRUE(result.has_value()); EXPECT_DOUBLE_EQ(*result, 3.0); - obstacles.points.emplace_back(2.5, -0.75); + obstacles.points.emplace_back(2.75, -0.75); result = distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); ASSERT_TRUE(result.has_value()); - EXPECT_DOUBLE_EQ(*result, 2.5); + EXPECT_DOUBLE_EQ(*result, 2.75); // Change vector and footprint vector = linestring_t{{0.0, 0.0}, {5.0, 5.0}}; @@ -95,6 +95,7 @@ TEST(TestCollisionDistance, distanceToClosestCollision) ASSERT_FALSE(result.has_value()); obstacles.points.emplace_back(4.0, 4.0); + result = distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); ASSERT_TRUE(result.has_value()); @@ -151,6 +152,214 @@ TEST(TestCollisionDistance, distanceToClosestCollision) EXPECT_NEAR(*result, 2.121, 1e-3); } +TEST(TestCollisionDistance, distanceToClosestCollisionApproximation) +{ + using obstacle_velocity_limiter::CollisionChecker; + using obstacle_velocity_limiter::distanceToClosestCollision; + using obstacle_velocity_limiter::linestring_t; + using obstacle_velocity_limiter::polygon_t; + + obstacle_velocity_limiter::ProjectionParameters params; + params.distance_method = obstacle_velocity_limiter::ProjectionParameters::APPROXIMATION; + params.heading = 0.0; + linestring_t vector = {{0.0, 0.0}, {5.0, 0.0}}; + polygon_t footprint; + footprint.outer() = {{0.0, 1.0}, {5.0, 1.0}, {5.0, -1.0}, {0.0, -1.0}}; + boost::geometry::correct(footprint); // avoid bugs with malformed polygon + obstacle_velocity_limiter::Obstacles obstacles; + + auto EPS = 1e-2; + + std::optional result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_FALSE(result.has_value()); + // Non Value obstacles + obstacles.points.emplace_back(-1.0, 0.0); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_FALSE(result.has_value()); + + obstacles.points.emplace_back(1.0, 2.0); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_FALSE(result.has_value()); + + // inside the polygon + obstacles.points.emplace_back(4.0, 0.0); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_TRUE(result.has_value()); + EXPECT_DOUBLE_EQ(*result, 4.0); + + obstacles.points.emplace_back(3.0, 0.5); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(*result, 3.04, EPS); + + obstacles.points.emplace_back(2.5, -0.75); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(*result, 2.61, EPS); + + obstacles.points.emplace_back(2.0, -1.0); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(*result, 2.23, EPS); + + // Change vector and footprint + vector = linestring_t{{0.0, 0.0}, {5.0, 5.0}}; + params.heading = M_PI_4; + footprint.outer() = {{-1.0, 1.0}, {4.0, 6.0}, {6.0, 4.0}, {1.0, -1.0}}; + boost::geometry::correct(footprint); // avoid bugs with malformed polygon + obstacles.points.clear(); + obstacles.lines.clear(); + + // auto EPS = 1e-3; + obstacles.points.emplace_back(5.0, 1.0); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_FALSE(result.has_value()); + + obstacles.points.emplace_back(4.0, 4.0); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(*result, 5.65, EPS); + + obstacles.points.emplace_back(1.0, 2.0); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(*result, 2.23, EPS); + + // Change vector (opposite direction) + params.heading = -3 * M_PI_4; + vector = linestring_t{{5.0, 5.0}, {0.0, 0.0}}; + obstacles.points.clear(); + obstacles.lines.clear(); + + obstacles.points.emplace_back(1.0, 1.0); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(*result, 5.65, EPS); + + obstacles.points.emplace_back(4.0, 3.0); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(*result, 2.23, EPS); +} + +TEST(TestCollisionDistance, distanceToClosestCollisionBicycleModel) +{ + using obstacle_velocity_limiter::CollisionChecker; + using obstacle_velocity_limiter::distanceToClosestCollision; + using obstacle_velocity_limiter::linestring_t; + using obstacle_velocity_limiter::polygon_t; + + obstacle_velocity_limiter::ProjectionParameters params; + params.model = obstacle_velocity_limiter::ProjectionParameters::BICYCLE; + params.heading = 0.0; + linestring_t vector = {{0.0, 0.0}, {5.0, 0.0}}; + polygon_t footprint; + footprint.outer() = {{0.0, 1.0}, {5.0, 1.0}, {5.0, -1.0}, {0.0, -1.0}}; + boost::geometry::correct(footprint); // avoid bugs with malformed polygon + obstacle_velocity_limiter::Obstacles obstacles; + + auto EPS = 1e-2; + + std::optional result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_FALSE(result.has_value()); + + obstacles.points.emplace_back(-1.0, 0.0); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_FALSE(result.has_value()); + + obstacles.points.emplace_back(1.0, 2.0); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_FALSE(result.has_value()); + + obstacles.points.emplace_back(4.0, 0.0); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_FALSE(result.has_value()); + + obstacles.points.emplace_back(3.0, 0.5); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(*result, 3.05, EPS); + + obstacles.points.emplace_back(2.5, -0.75); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(*result, 2.64, EPS); + + // Change vector and footprint + vector = linestring_t{{0.0, 0.0}, {5.0, 5.0}}; + params.heading = M_PI_2; + footprint.outer() = {{-1.0, 1.0}, {4.0, 6.0}, {6.0, 4.0}, {1.0, -1.0}}; + boost::geometry::correct(footprint); // avoid bugs with malformed polygon + obstacles.points.clear(); + obstacles.lines.clear(); + + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_FALSE(result.has_value()); + + obstacles.points.emplace_back(4.0, 4.0); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(*result, 6.28, EPS); + + obstacles.points.emplace_back(1.0, 2.0); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(*result, 2.31, EPS); + + // Change vector (opposite direction) + params.heading = -M_PI; + vector = linestring_t{{5.0, 5.0}, {0.0, 0.0}}; + obstacles.points.clear(); + obstacles.lines.clear(); + + obstacles.points.emplace_back(1.0, 1.0); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(*result, 6.28, EPS); + + obstacles.points.emplace_back(4.0, 3.0); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(*result, 2.76, EPS); + + // change vector and footprint + params.heading = M_PI_2; + vector = linestring_t{{3.0, 3.0}, {0.0, 3.0}}; + footprint.outer() = {{1.0, -1.0}, {-4.0, 6.0}, {-5.0, -4.0}, {1.0, -4.0}}; + boost::geometry::correct(footprint); + obstacles.points.clear(); + obstacles.lines.clear(); + + obstacles.points.emplace_back(-2.0, -1.0); + result = + distanceToClosestCollision(vector, footprint, CollisionChecker(obstacles, 0lu, 0lu), params); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(*result, 7.34, EPS); +} + TEST(TestCollisionDistance, arcDistance) { using obstacle_velocity_limiter::arcDistance; From 88b06e0c1d70bfdd2904edfb923944422e3583b7 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 13 Nov 2023 17:58:19 +0900 Subject: [PATCH 176/202] fix(sampling_based_planner): fix runtime error (#5490) Signed-off-by: satoshi-ota --- .../include/bezier_sampler/bezier_sampling.hpp | 1 + planning/sampling_based_planner/path_sampler/src/node.cpp | 5 +++-- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/planning/sampling_based_planner/bezier_sampler/include/bezier_sampler/bezier_sampling.hpp b/planning/sampling_based_planner/bezier_sampler/include/bezier_sampler/bezier_sampling.hpp index 624cd585b0a72..18df9dcb796d8 100644 --- a/planning/sampling_based_planner/bezier_sampler/include/bezier_sampler/bezier_sampling.hpp +++ b/planning/sampling_based_planner/bezier_sampler/include/bezier_sampler/bezier_sampling.hpp @@ -17,6 +17,7 @@ #include #include +#include #include #include diff --git a/planning/sampling_based_planner/path_sampler/src/node.cpp b/planning/sampling_based_planner/path_sampler/src/node.cpp index aa037755bbedd..e61f635de67c4 100644 --- a/planning/sampling_based_planner/path_sampler/src/node.cpp +++ b/planning/sampling_based_planner/path_sampler/src/node.cpp @@ -298,7 +298,8 @@ PlannerData PathSampler::createPlannerData(const Path & path) const return planner_data; } -void copyZ(const std::vector & from_traj, std::vector & to_traj) +void PathSampler::copyZ( + const std::vector & from_traj, std::vector & to_traj) { if (from_traj.empty() || to_traj.empty()) return; to_traj.front().pose.position.z = from_traj.front().pose.position.z; @@ -320,7 +321,7 @@ void copyZ(const std::vector & from_traj, std::vectorpose.position.z; } -void copyVelocity( +void PathSampler::copyVelocity( const std::vector & from_traj, std::vector & to_traj, const geometry_msgs::msg::Pose & ego_pose) { From 63220dfcb099ed7619d10f08982d5992ccc12b0a Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Mon, 13 Nov 2023 19:23:36 +0900 Subject: [PATCH 177/202] docs(lane_change): stopping position when an object exists ahead (#5523) * docs(lane_change): Stopping position when an object exists ahead Signed-off-by: kosuke55 * add stuck params Signed-off-by: kosuke55 * add backward_length_buffer_for_blocking_object Signed-off-by: kosuke55 * add stop for lane change Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 --- ...ehavior_path_planner_lane_change_design.md | 159 +++++++++++++----- .../lane_change-stop_at_terminal.drawio.svg | 94 +++++++++++ ...hange-stop_at_terminal_no_block.drawio.svg | 76 +++++++++ ...hange-stop_far_from_target_lane.drawio.svg | 85 ++++++++++ ...ane_change-stop_not_at_terminal.drawio.svg | 70 ++++++++ ..._at_terminal_no_blocking_object.drawio.svg | 76 +++++++++ 6 files changed, 518 insertions(+), 42 deletions(-) create mode 100644 planning/behavior_path_planner/image/lane_change/lane_change-stop_at_terminal.drawio.svg create mode 100644 planning/behavior_path_planner/image/lane_change/lane_change-stop_at_terminal_no_block.drawio.svg create mode 100644 planning/behavior_path_planner/image/lane_change/lane_change-stop_far_from_target_lane.drawio.svg create mode 100644 planning/behavior_path_planner/image/lane_change/lane_change-stop_not_at_terminal.drawio.svg create mode 100644 planning/behavior_path_planner/image/lane_change/lane_change-stop_not_at_terminal_no_blocking_object.drawio.svg diff --git a/planning/behavior_path_planner/docs/behavior_path_planner_lane_change_design.md b/planning/behavior_path_planner/docs/behavior_path_planner_lane_change_design.md index 2e5e486afc7c3..ee74f700c4d42 100644 --- a/planning/behavior_path_planner/docs/behavior_path_planner_lane_change_design.md +++ b/planning/behavior_path_planner/docs/behavior_path_planner_lane_change_design.md @@ -186,6 +186,46 @@ The following figure illustrates when the lane is blocked in multiple lane chang ![multiple-lane-changes](../image/lane_change/lane_change-when_cannot_change_lanes.png) +#### Stopping position when an object exists ahead + +When an obstacle is in front of the ego vehicle, stop with keeping a distance for lane change. +The position to be stopped depends on the situation, such as when the lane change is blocked by the target lane obstacle, or when the lane change is not needed immediately.The following shows the division in that case. + +##### When the ego vehicle is near the end of the lane change + +Regardless of the presence or absence of objects in the lane change target lane, stop by keeping the distance necessary for lane change to the object ahead. + +![stop_at_terminal_no_block](../image/lane_change/lane_change-stop_at_terminal_no_block.drawio.svg) + +![stop_at_terminal](../image/lane_change/lane_change-stop_at_terminal.drawio.svg) + +##### When the ego vehicle is not near the end of the lane change + +If there are NO objects in the lane change section of the target lane, stop by keeping the distance necessary for lane change to the object ahead. + +![stop_not_at_terminal_no_blocking_object](../image/lane_change/lane_change-stop_not_at_terminal_no_blocking_object.drawio.svg) + +If there are objects in the lane change section of the target lane, stop WITHOUT keeping the distance necessary for lane change to the object ahead. + +![stop_not_at_terminal](../image/lane_change/lane_change-stop_not_at_terminal.drawio.svg) + +##### When the target lane is far away + +When the target lane for lane change is far away and not next to the current lane, do not keep the distance necessary for lane change to the object ahead. + +![stop_far_from_target_lane](../image/lane_change/lane_change-stop_far_from_target_lane.drawio.svg) + +### Lane Change When Stuck + +The ego vehicle is considered stuck if it is stopped and meets any of the following conditions: + +- There is an obstacle in front of the current lane +- The ego vehicle is at the end of the current lane + +In this case, the safety check for lane change is relaxed compared to normal times. +Please refer to the 'stuck' section under the 'Collision checks during lane change' for more details. +The function to stop by keeping a margin against forward obstacle in the previous section is being performed to achieve this feature. + ### Lane change regulations If you want to regulate lane change on crosswalks or intersections, the lane change module finds a lane change path excluding it includes crosswalks or intersections. @@ -272,35 +312,36 @@ The last behavior will also occur if the ego vehicle has departed from the curre The following parameters are configurable in `lane_change.param.yaml`. -| Name | Unit | Type | Description | Default value | -| :------------------------------------------ | ------ | ------- | --------------------------------------------------------------------------------------------------------------- | ------------------ | -| `backward_lane_length` | [m] | double | The backward length to check incoming objects in lane change target lane. | 200.0 | -| `prepare_duration` | [m] | double | The preparation time for the ego vehicle to be ready to perform lane change. | 4.0 | -| `backward_length_buffer_for_end_of_lane` | [m] | double | The end of lane buffer to ensure ego vehicle has enough distance to start lane change | 2.0 | -| `lane_change_finish_judge_buffer` | [m] | double | The additional buffer used to confirm lane change process completion | 3.0 | -| `finish_judge_lateral_threshold` | [m] | double | Lateral distance threshold to confirm lane change process completion | 0.2 | -| `lane_changing_lateral_jerk` | [m/s3] | double | Lateral jerk value for lane change path generation | 0.5 | -| `minimum_lane_changing_velocity` | [m/s] | double | Minimum speed during lane changing process. | 2.78 | -| `prediction_time_resolution` | [s] | double | Time resolution for object's path interpolation and collision check. | 0.5 | -| `longitudinal_acceleration_sampling_num` | [-] | int | Number of possible lane-changing trajectories that are being influenced by longitudinal acceleration | 5 | -| `lateral_acceleration_sampling_num` | [-] | int | Number of possible lane-changing trajectories that are being influenced by lateral acceleration | 3 | -| `object_check_min_road_shoulder_width` | [m] | double | Width considered as a road shoulder if the lane does not have a road shoulder | 0.5 | -| `object_shiftable_ratio_threshold` | [-] | double | Vehicles around the center line within this distance ratio will be excluded from parking objects | 0.6 | -| `min_length_for_turn_signal_activation` | [m] | double | Turn signal will be activated if the ego vehicle approaches to this length from minimum lane change length | 10.0 | -| `length_ratio_for_turn_signal_deactivation` | [-] | double | Turn signal will be deactivated if the ego vehicle approaches to this length ratio for lane change finish point | 0.8 | -| `max_longitudinal_acc` | [-] | double | maximum longitudinal acceleration for lane change | 1.0 | -| `min_longitudinal_acc` | [-] | double | maximum longitudinal deceleration for lane change | -1.0 | -| `lateral_acceleration.velocity` | [m/s] | double | Reference velocity for lateral acceleration calculation (look up table) | [0.0, 4.0, 10.0] | -| `lateral_acceleration.min_values` | [m/ss] | double | Min lateral acceleration values corresponding to velocity (look up table) | [0.15, 0.15, 0.15] | -| `lateral_acceleration.max_values` | [m/ss] | double | Max lateral acceleration values corresponding to velocity (look up table) | [0.5, 0.5, 0.5] | -| `target_object.car` | [-] | boolean | Include car objects for safety check | true | -| `target_object.truck` | [-] | boolean | Include truck objects for safety check | true | -| `target_object.bus` | [-] | boolean | Include bus objects for safety check | true | -| `target_object.trailer` | [-] | boolean | Include trailer objects for safety check | true | -| `target_object.unknown` | [-] | boolean | Include unknown objects for safety check | true | -| `target_object.bicycle` | [-] | boolean | Include bicycle objects for safety check | true | -| `target_object.motorcycle` | [-] | boolean | Include motorcycle objects for safety check | true | -| `target_object.pedestrian` | [-] | boolean | Include pedestrian objects for safety check | true | +| Name | Unit | Type | Description | Default value | +| :------------------------------------------- | ------ | ------- | ---------------------------------------------------------------------------------------------------------------------- | ------------------ | +| `backward_lane_length` | [m] | double | The backward length to check incoming objects in lane change target lane. | 200.0 | +| `prepare_duration` | [m] | double | The preparation time for the ego vehicle to be ready to perform lane change. | 4.0 | +| `backward_length_buffer_for_end_of_lane` | [m] | double | The end of lane buffer to ensure ego vehicle has enough distance to start lane change | 3.0 | +| `backward_length_buffer_for_blocking_object` | [m] | double | The end of lane buffer to ensure ego vehicle has enough distance to start lane change when there is an object in front | 3.0 | +| `lane_change_finish_judge_buffer` | [m] | double | The additional buffer used to confirm lane change process completion | 3.0 | +| `finish_judge_lateral_threshold` | [m] | double | Lateral distance threshold to confirm lane change process completion | 0.2 | +| `lane_changing_lateral_jerk` | [m/s3] | double | Lateral jerk value for lane change path generation | 0.5 | +| `minimum_lane_changing_velocity` | [m/s] | double | Minimum speed during lane changing process. | 2.78 | +| `prediction_time_resolution` | [s] | double | Time resolution for object's path interpolation and collision check. | 0.5 | +| `longitudinal_acceleration_sampling_num` | [-] | int | Number of possible lane-changing trajectories that are being influenced by longitudinal acceleration | 5 | +| `lateral_acceleration_sampling_num` | [-] | int | Number of possible lane-changing trajectories that are being influenced by lateral acceleration | 3 | +| `object_check_min_road_shoulder_width` | [m] | double | Width considered as a road shoulder if the lane does not have a road shoulder | 0.5 | +| `object_shiftable_ratio_threshold` | [-] | double | Vehicles around the center line within this distance ratio will be excluded from parking objects | 0.6 | +| `min_length_for_turn_signal_activation` | [m] | double | Turn signal will be activated if the ego vehicle approaches to this length from minimum lane change length | 10.0 | +| `length_ratio_for_turn_signal_deactivation` | [-] | double | Turn signal will be deactivated if the ego vehicle approaches to this length ratio for lane change finish point | 0.8 | +| `max_longitudinal_acc` | [-] | double | maximum longitudinal acceleration for lane change | 1.0 | +| `min_longitudinal_acc` | [-] | double | maximum longitudinal deceleration for lane change | -1.0 | +| `lateral_acceleration.velocity` | [m/s] | double | Reference velocity for lateral acceleration calculation (look up table) | [0.0, 4.0, 10.0] | +| `lateral_acceleration.min_values` | [m/ss] | double | Min lateral acceleration values corresponding to velocity (look up table) | [0.15, 0.15, 0.15] | +| `lateral_acceleration.max_values` | [m/ss] | double | Max lateral acceleration values corresponding to velocity (look up table) | [0.5, 0.5, 0.5] | +| `target_object.car` | [-] | boolean | Include car objects for safety check | true | +| `target_object.truck` | [-] | boolean | Include truck objects for safety check | true | +| `target_object.bus` | [-] | boolean | Include bus objects for safety check | true | +| `target_object.trailer` | [-] | boolean | Include trailer objects for safety check | true | +| `target_object.unknown` | [-] | boolean | Include unknown objects for safety check | true | +| `target_object.bicycle` | [-] | boolean | Include bicycle objects for safety check | true | +| `target_object.motorcycle` | [-] | boolean | Include motorcycle objects for safety check | true | +| `target_object.pedestrian` | [-] | boolean | Include pedestrian objects for safety check | true | ### Lane change regulations @@ -320,19 +361,53 @@ The following parameters are configurable in `lane_change.param.yaml`. The following parameters are configurable in `behavior_path_planner.param.yaml` and `lane_change.param.yaml`. -| Name | Unit | Type | Description | Default value | -| :----------------------------------------- | ------- | ------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------- | -| `lateral_distance_max_threshold` | [m] | double | The lateral distance threshold that is used to determine whether lateral distance between two object is enough and whether lane change is safe. | 2.0 | -| `longitudinal_distance_min_threshold` | [m] | double | The longitudinal distance threshold that is used to determine whether longitudinal distance between two object is enough and whether lane change is safe. | 3.0 | -| `expected_front_deceleration` | [m/s^2] | double | The front object's maximum deceleration when the front vehicle perform sudden braking. (\*1) | -1.0 | -| `expected_rear_deceleration` | [m/s^2] | double | The rear object's maximum deceleration when the rear vehicle perform sudden braking. (\*1) | -1.0 | -| `rear_vehicle_reaction_time` | [s] | double | The reaction time of the rear vehicle driver which starts from the driver noticing the sudden braking of the front vehicle until the driver step on the brake. | 2.0 | -| `rear_vehicle_safety_time_margin` | [s] | double | The time buffer for the rear vehicle to come into complete stop when its driver perform sudden braking. | 2.0 | -| `enable_collision_check_at_prepare_phase` | [-] | boolean | Perform collision check starting from prepare phase. If `false`, collision check only evaluated for lane changing phase. | true | -| `prepare_phase_ignore_target_speed_thresh` | [m/s] | double | Ignore collision check in prepare phase of object speed that is lesser that the configured value. `enable_collision_check_at_prepare_phase` must be `true` | 0.1 | -| `check_objects_on_current_lanes` | [-] | boolean | If true, the lane change module include objects on current lanes. | true | -| `check_objects_on_other_lanes` | [-] | boolean | If true, the lane change module include objects on other lanes. | true | -| `use_all_predicted_path` | [-] | boolean | If false, use only the predicted path that has the maximum confidence. | true | +#### execution + +| Name | Unit | Type | Description | Default value | +| :---------------------------------------------------------------- | ------- | ------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------- | +| `safety_check.execution.lateral_distance_max_threshold` | [m] | double | The lateral distance threshold that is used to determine whether lateral distance between two object is enough and whether lane change is safe. | 2.0 | +| `safety_check.execution.longitudinal_distance_min_threshold` | [m] | double | The longitudinal distance threshold that is used to determine whether longitudinal distance between two object is enough and whether lane change is safe. | 3.0 | +| `safety_check.execution.expected_front_deceleration` | [m/s^2] | double | The front object's maximum deceleration when the front vehicle perform sudden braking. (\*1) | -1.0 | +| `safety_check.execution.expected_rear_deceleration` | [m/s^2] | double | The rear object's maximum deceleration when the rear vehicle perform sudden braking. (\*1) | -1.0 | +| `safety_check.execution.rear_vehicle_reaction_time` | [s] | double | The reaction time of the rear vehicle driver which starts from the driver noticing the sudden braking of the front vehicle until the driver step on the brake. | 2.0 | +| `safety_check.execution.rear_vehicle_safety_time_margin` | [s] | double | The time buffer for the rear vehicle to come into complete stop when its driver perform sudden braking. | 2.0 | +| `safety_check.execution.enable_collision_check_at_prepare_phase` | [-] | boolean | Perform collision check starting from prepare phase. If `false`, collision check only evaluated for lane changing phase. | true | +| `safety_check.execution.prepare_phase_ignore_target_speed_thresh` | [m/s] | double | Ignore collision check in prepare phase of object speed that is lesser that the configured value. `enable_collision_check_at_prepare_phase` must be `true` | 0.1 | +| `safety_check.execution.check_objects_on_current_lanes` | [-] | boolean | If true, the lane change module include objects on current lanes. | true | +| `safety_check.execution.check_objects_on_other_lanes` | [-] | boolean | If true, the lane change module include objects on other lanes. | true | +| `safety_check.execution.use_all_predicted_path` | [-] | boolean | If false, use only the predicted path that has the maximum confidence. | true | + +##### cancel + +| Name | Unit | Type | Description | Default value | +| :------------------------------------------------------------- | ------- | ------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------- | +| `safety_check.cancel.lateral_distance_max_threshold` | [m] | double | The lateral distance threshold that is used to determine whether lateral distance between two object is enough and whether lane change is safe. | 1.5 | +| `safety_check.cancel.longitudinal_distance_min_threshold` | [m] | double | The longitudinal distance threshold that is used to determine whether longitudinal distance between two object is enough and whether lane change is safe. | 3.0 | +| `safety_check.cancel.expected_front_deceleration` | [m/s^2] | double | The front object's maximum deceleration when the front vehicle perform sudden braking. (\*1) | -1.5 | +| `safety_check.cancel.expected_rear_deceleration` | [m/s^2] | double | The rear object's maximum deceleration when the rear vehicle perform sudden braking. (\*1) | -2.5 | +| `safety_check.cancel.rear_vehicle_reaction_time` | [s] | double | The reaction time of the rear vehicle driver which starts from the driver noticing the sudden braking of the front vehicle until the driver step on the brake. | 2.0 | +| `safety_check.cancel.rear_vehicle_safety_time_margin` | [s] | double | The time buffer for the rear vehicle to come into complete stop when its driver perform sudden braking. | 2.5 | +| `safety_check.cancel.enable_collision_check_at_prepare_phase` | [-] | boolean | Perform collision check starting from prepare phase. If `false`, collision check only evaluated for lane changing phase. | false | +| `safety_check.cancel.prepare_phase_ignore_target_speed_thresh` | [m/s] | double | Ignore collision check in prepare phase of object speed that is lesser that the configured value. `enable_collision_check_at_prepare_phase` must be `true` | 0.2 | +| `safety_check.cancel.check_objects_on_current_lanes` | [-] | boolean | If true, the lane change module include objects on current lanes. | false | +| `safety_check.cancel.check_objects_on_other_lanes` | [-] | boolean | If true, the lane change module include objects on other lanes. | false | +| `safety_check.cancel.use_all_predicted_path` | [-] | boolean | If false, use only the predicted path that has the maximum confidence. | false | + +##### stuck + +| Name | Unit | Type | Description | Default value | +| :------------------------------------------------------------ | ------- | ------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------- | +| `safety_check.stuck.lateral_distance_max_threshold` | [m] | double | The lateral distance threshold that is used to determine whether lateral distance between two object is enough and whether lane change is safe. | 2.0 | +| `safety_check.stuck.longitudinal_distance_min_threshold` | [m] | double | The longitudinal distance threshold that is used to determine whether longitudinal distance between two object is enough and whether lane change is safe. | 3.0 | +| `safety_check.stuck.expected_front_deceleration` | [m/s^2] | double | The front object's maximum deceleration when the front vehicle perform sudden braking. (\*1) | -1.0 | +| `safety_check.stuck.expected_rear_deceleration` | [m/s^2] | double | The rear object's maximum deceleration when the rear vehicle perform sudden braking. (\*1) | -1.0 | +| `safety_check.stuck.rear_vehicle_reaction_time` | [s] | double | The reaction time of the rear vehicle driver which starts from the driver noticing the sudden braking of the front vehicle until the driver step on the brake. | 2.0 | +| `safety_check.stuck.rear_vehicle_safety_time_margin` | [s] | double | The time buffer for the rear vehicle to come into complete stop when its driver perform sudden braking. | 2.0 | +| `safety_check.stuck.enable_collision_check_at_prepare_phase` | [-] | boolean | Perform collision check starting from prepare phase. If `false`, collision check only evaluated for lane changing phase. | true | +| `safety_check.stuck.prepare_phase_ignore_target_speed_thresh` | [m/s] | double | Ignore collision check in prepare phase of object speed that is lesser that the configured value. `enable_collision_check_at_prepare_phase` must be `true` | 0.1 | +| `safety_check.stuck.check_objects_on_current_lanes` | [-] | boolean | If true, the lane change module include objects on current lanes. | true | +| `safety_check.stuck.check_objects_on_other_lanes` | [-] | boolean | If true, the lane change module include objects on other lanes. | true | +| `safety_check.stuck.use_all_predicted_path` | [-] | boolean | If false, use only the predicted path that has the maximum confidence. | true | (\*1) the value must be negative. diff --git a/planning/behavior_path_planner/image/lane_change/lane_change-stop_at_terminal.drawio.svg b/planning/behavior_path_planner/image/lane_change/lane_change-stop_at_terminal.drawio.svg new file mode 100644 index 0000000000000..f8aab60d0991d --- /dev/null +++ b/planning/behavior_path_planner/image/lane_change/lane_change-stop_at_terminal.drawio.svg @@ -0,0 +1,94 @@ + + + + + + + + + + + + + + + + + + + + +
+
+
+ lane change margin +
+
+
+
+ lane change m... +
+
+
+ + + + Text is not SVG - cannot display + + +
diff --git a/planning/behavior_path_planner/image/lane_change/lane_change-stop_at_terminal_no_block.drawio.svg b/planning/behavior_path_planner/image/lane_change/lane_change-stop_at_terminal_no_block.drawio.svg new file mode 100644 index 0000000000000..0de2c5fa0a550 --- /dev/null +++ b/planning/behavior_path_planner/image/lane_change/lane_change-stop_at_terminal_no_block.drawio.svg @@ -0,0 +1,76 @@ + + + + + + + + + + + + + + + + + + +
+
+
+ lane change margin +
+
+
+
+ lane change m... +
+
+
+ + + + Text is not SVG - cannot display + + +
diff --git a/planning/behavior_path_planner/image/lane_change/lane_change-stop_far_from_target_lane.drawio.svg b/planning/behavior_path_planner/image/lane_change/lane_change-stop_far_from_target_lane.drawio.svg new file mode 100644 index 0000000000000..dedcc13b6ef6a --- /dev/null +++ b/planning/behavior_path_planner/image/lane_change/lane_change-stop_far_from_target_lane.drawio.svg @@ -0,0 +1,85 @@ + + + + + + + + + + + + + + + + + + diff --git a/planning/behavior_path_planner/image/lane_change/lane_change-stop_not_at_terminal.drawio.svg b/planning/behavior_path_planner/image/lane_change/lane_change-stop_not_at_terminal.drawio.svg new file mode 100644 index 0000000000000..938b7b7d4b371 --- /dev/null +++ b/planning/behavior_path_planner/image/lane_change/lane_change-stop_not_at_terminal.drawio.svg @@ -0,0 +1,70 @@ + + + + + + + + + + + + + + + diff --git a/planning/behavior_path_planner/image/lane_change/lane_change-stop_not_at_terminal_no_blocking_object.drawio.svg b/planning/behavior_path_planner/image/lane_change/lane_change-stop_not_at_terminal_no_blocking_object.drawio.svg new file mode 100644 index 0000000000000..e07a8dcbe0354 --- /dev/null +++ b/planning/behavior_path_planner/image/lane_change/lane_change-stop_not_at_terminal_no_blocking_object.drawio.svg @@ -0,0 +1,76 @@ + + + + + + + + + + + + + + + + + + +
+
+
+ lane change margin +
+
+
+
+ lane change m... +
+
+
+ + + + Text is not SVG - cannot display + + +
From b97ff3c595acf33169208fb185ff12e833d27cea Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Mon, 13 Nov 2023 20:17:03 +0900 Subject: [PATCH 178/202] fix(detection_by_tracker): add ignore option for each label (#5473) * fix(detection_by_tracker): add ignore for each class Signed-off-by: badai-nguyen * fix: launch Signed-off-by: badai-nguyen --------- Signed-off-by: badai-nguyen --- ...ra_lidar_fusion_based_detection.launch.xml | 1 + ...ar_radar_fusion_based_detection.launch.xml | 1 + .../detection/detection.launch.xml | 3 ++ .../lidar_based_detection.launch.xml | 1 + .../launch/perception.launch.xml | 2 ++ .../detection_by_tracker/CMakeLists.txt | 2 ++ .../config/detection_by_tracker.param.yaml | 11 ++++++ .../detection_by_tracker_core.hpp | 5 +-- .../include/utils/utils.hpp | 36 +++++++++++++++++++ .../launch/detection_by_tracker.launch.xml | 3 +- .../src/detection_by_tracker_core.cpp | 14 ++++++-- perception/detection_by_tracker/src/utils.cpp | 30 ++++++++++++++++ 12 files changed, 103 insertions(+), 6 deletions(-) create mode 100644 perception/detection_by_tracker/config/detection_by_tracker.param.yaml create mode 100644 perception/detection_by_tracker/include/utils/utils.hpp create mode 100644 perception/detection_by_tracker/src/utils.cpp diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml index 59fe3f13f1231..b3e9e9148ee60 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml @@ -195,6 +195,7 @@ + diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml index 11deaad5d06cc..20b1b5a4d0b27 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml @@ -220,6 +220,7 @@ + diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml index 1fcf29606891b..33994934949ac 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml @@ -73,6 +73,7 @@ + @@ -104,6 +105,7 @@ + @@ -133,6 +135,7 @@ + diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml index 822c251ddad33..ac521934265d7 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml @@ -61,6 +61,7 @@ + diff --git a/launch/tier4_perception_launch/launch/perception.launch.xml b/launch/tier4_perception_launch/launch/perception.launch.xml index 347606d91759f..8b241db9774b3 100644 --- a/launch/tier4_perception_launch/launch/perception.launch.xml +++ b/launch/tier4_perception_launch/launch/perception.launch.xml @@ -18,6 +18,7 @@ + @@ -174,6 +175,7 @@ + diff --git a/perception/detection_by_tracker/CMakeLists.txt b/perception/detection_by_tracker/CMakeLists.txt index 236268438f852..51839027e0e41 100644 --- a/perception/detection_by_tracker/CMakeLists.txt +++ b/perception/detection_by_tracker/CMakeLists.txt @@ -27,6 +27,7 @@ include_directories( # Generate exe file set(DETECTION_BY_TRACKER_SRC src/detection_by_tracker_core.cpp + src/utils.cpp ) ament_auto_add_library(detection_by_tracker_node SHARED @@ -45,4 +46,5 @@ rclcpp_components_register_node(detection_by_tracker_node ament_auto_package(INSTALL_TO_SHARE launch + config ) diff --git a/perception/detection_by_tracker/config/detection_by_tracker.param.yaml b/perception/detection_by_tracker/config/detection_by_tracker.param.yaml new file mode 100644 index 0000000000000..695704050697d --- /dev/null +++ b/perception/detection_by_tracker/config/detection_by_tracker.param.yaml @@ -0,0 +1,11 @@ +/**: + ros__parameters: + tracker_ignore_label: + UNKNOWN : true + CAR : false + TRUCK : false + BUS : false + TRAILER : false + MOTORCYCLE : false + BICYCLE : false + PEDESTRIAN : false diff --git a/perception/detection_by_tracker/include/detection_by_tracker/detection_by_tracker_core.hpp b/perception/detection_by_tracker/include/detection_by_tracker/detection_by_tracker_core.hpp index 0eacfa527750b..10affd0b94ffd 100644 --- a/perception/detection_by_tracker/include/detection_by_tracker/detection_by_tracker_core.hpp +++ b/perception/detection_by_tracker/include/detection_by_tracker/detection_by_tracker_core.hpp @@ -39,6 +39,8 @@ #include #endif +#include "utils/utils.hpp" + #include #include @@ -46,7 +48,6 @@ #include #include #include - class TrackerHandler { private: @@ -81,7 +82,7 @@ class DetectionByTracker : public rclcpp::Node std::map max_search_distance_for_merger_; std::map max_search_distance_for_divider_; - bool ignore_unknown_tracker_; + utils::TrackerIgnoreLabel tracker_ignore_; void setMaxSearchRange(); diff --git a/perception/detection_by_tracker/include/utils/utils.hpp b/perception/detection_by_tracker/include/utils/utils.hpp new file mode 100644 index 0000000000000..3f39125b95e03 --- /dev/null +++ b/perception/detection_by_tracker/include/utils/utils.hpp @@ -0,0 +1,36 @@ +// 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. + +#ifndef UTILS__UTILS_HPP_ +#define UTILS__UTILS_HPP_ + +#include + +namespace utils +{ +struct TrackerIgnoreLabel +{ + bool UNKNOWN; + bool CAR; + bool TRUCK; + bool BUS; + bool TRAILER; + bool MOTORCYCLE; + bool BICYCLE; + bool PEDESTRIAN; + bool isIgnore(const uint8_t label) const; +}; // struct TrackerIgnoreLabel +} // namespace utils + +#endif // UTILS__UTILS_HPP_ diff --git a/perception/detection_by_tracker/launch/detection_by_tracker.launch.xml b/perception/detection_by_tracker/launch/detection_by_tracker.launch.xml index 79e1b642cc53c..95e7cbf16b388 100644 --- a/perception/detection_by_tracker/launch/detection_by_tracker.launch.xml +++ b/perception/detection_by_tracker/launch/detection_by_tracker.launch.xml @@ -3,10 +3,11 @@ - + + diff --git a/perception/detection_by_tracker/src/detection_by_tracker_core.cpp b/perception/detection_by_tracker/src/detection_by_tracker_core.cpp index 7b436e1edd64c..2595315e1f9b2 100644 --- a/perception/detection_by_tracker/src/detection_by_tracker_core.cpp +++ b/perception/detection_by_tracker/src/detection_by_tracker_core.cpp @@ -160,7 +160,15 @@ DetectionByTracker::DetectionByTracker(const rclcpp::NodeOptions & node_options) objects_pub_ = create_publisher( "~/output", rclcpp::QoS{1}); - ignore_unknown_tracker_ = declare_parameter("ignore_unknown_tracker", true); + // Set parameters + tracker_ignore_.UNKNOWN = declare_parameter("tracker_ignore_label.UNKNOWN"); + tracker_ignore_.CAR = declare_parameter("tracker_ignore_label.CAR"); + tracker_ignore_.TRUCK = declare_parameter("tracker_ignore_label.TRUCK"); + tracker_ignore_.BUS = declare_parameter("tracker_ignore_label.BUS"); + tracker_ignore_.TRAILER = declare_parameter("tracker_ignore_label.TRAILER"); + tracker_ignore_.MOTORCYCLE = declare_parameter("tracker_ignore_label.MOTORCYCLE"); + tracker_ignore_.BICYCLE = declare_parameter("tracker_ignore_label.BICYCLE"); + tracker_ignore_.PEDESTRIAN = declare_parameter("tracker_ignore_label.PEDESTRIAN"); // set maximum search setting for merger/divider setMaxSearchRange(); @@ -259,7 +267,7 @@ void DetectionByTracker::divideUnderSegmentedObjects( for (const auto & tracked_object : tracked_objects.objects) { const auto & label = tracked_object.classification.front().label; - if (ignore_unknown_tracker_ && (label == Label::UNKNOWN)) continue; + if (tracker_ignore_.isIgnore(label)) continue; // change search range according to label type const float max_search_range = max_search_distance_for_divider_[label]; @@ -395,7 +403,7 @@ void DetectionByTracker::mergeOverSegmentedObjects( for (const auto & tracked_object : tracked_objects.objects) { const auto & label = tracked_object.classification.front().label; - if (ignore_unknown_tracker_ && (label == Label::UNKNOWN)) continue; + if (tracker_ignore_.isIgnore(label)) continue; // change search range according to label type const float max_search_range = max_search_distance_for_merger_[label]; diff --git a/perception/detection_by_tracker/src/utils.cpp b/perception/detection_by_tracker/src/utils.cpp new file mode 100644 index 0000000000000..29a500a24cf32 --- /dev/null +++ b/perception/detection_by_tracker/src/utils.cpp @@ -0,0 +1,30 @@ +// 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. + +#include "utils/utils.hpp" + +#include + +namespace utils +{ +using Label = autoware_auto_perception_msgs::msg::ObjectClassification; + +bool TrackerIgnoreLabel::isIgnore(const uint8_t label) const +{ + return (label == Label::UNKNOWN && UNKNOWN) || (label == Label::CAR && CAR) || + (label == Label::TRUCK && TRUCK) || (label == Label::BUS && BUS) || + (label == Label::TRAILER && TRAILER) || (label == Label::MOTORCYCLE && MOTORCYCLE) || + (label == Label::BICYCLE && BICYCLE) || (label == Label::PEDESTRIAN && PEDESTRIAN); +} +} // namespace utils From 6e60821fbe8a7ca5e6bd789c9e7401ba98a66fe9 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Mon, 13 Nov 2023 20:32:22 +0900 Subject: [PATCH 179/202] feat(image_projection_based_fusion): enable to show iou value in roi_cluster_fusion debug image (#5541) * enable to show debug iou value in roi_cluster_fusion Signed-off-by: yoshiri * refactor iou draw settings Signed-off-by: yoshiri * add backgroud color to iou Signed-off-by: yoshiri * prevent object copying when debugger is not enabled Signed-off-by: yoshiri --------- Signed-off-by: yoshiri --- .../debugger.hpp | 1 + .../src/debugger.cpp | 56 ++++++++++++++++--- .../src/fusion_node.cpp | 1 + .../src/roi_cluster_fusion/node.cpp | 18 +++--- 4 files changed, 58 insertions(+), 18 deletions(-) diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/debugger.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/debugger.hpp index 8a6ac7672b3a8..e4b1913effed5 100644 --- a/perception/image_projection_based_fusion/include/image_projection_based_fusion/debugger.hpp +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/debugger.hpp @@ -50,6 +50,7 @@ class Debugger std::vector image_rois_; std::vector obstacle_rois_; std::vector obstacle_points_; + std::vector max_iou_for_image_rois_; private: void imageCallback( diff --git a/perception/image_projection_based_fusion/src/debugger.cpp b/perception/image_projection_based_fusion/src/debugger.cpp index 3f52a0de1f09d..a51c23a77aac6 100644 --- a/perception/image_projection_based_fusion/src/debugger.cpp +++ b/perception/image_projection_based_fusion/src/debugger.cpp @@ -77,6 +77,7 @@ void Debugger::clear() image_rois_.clear(); obstacle_rois_.clear(); obstacle_points_.clear(); + max_iou_for_image_rois_.clear(); } void Debugger::publishImage(const std::size_t image_id, const rclcpp::Time & stamp) @@ -84,6 +85,8 @@ void Debugger::publishImage(const std::size_t image_id, const rclcpp::Time & sta const boost::circular_buffer & image_buffer = image_buffers_.at(image_id); const image_transport::Publisher & image_pub = image_pubs_.at(image_id); + const bool draw_iou_score = + max_iou_for_image_rois_.size() > 0 && max_iou_for_image_rois_.size() == image_rois_.size(); for (std::size_t i = 0; i < image_buffer.size(); ++i) { if (image_buffer.at(i)->header.stamp != stamp) { @@ -91,22 +94,59 @@ void Debugger::publishImage(const std::size_t image_id, const rclcpp::Time & sta } auto cv_ptr = cv_bridge::toCvCopy(image_buffer.at(i), image_buffer.at(i)->encoding); - + // draw obstacle points for (const auto & point : obstacle_points_) { cv::circle( cv_ptr->image, cv::Point(static_cast(point.x()), static_cast(point.y())), 2, cv::Scalar(255, 255, 255), 3, 4); } + + // draw rois + const int img_height = static_cast(image_buffer.at(i)->height); + const int img_width = static_cast(image_buffer.at(i)->width); for (const auto & roi : obstacle_rois_) { - drawRoiOnImage( - cv_ptr->image, roi, image_buffer.at(i)->width, image_buffer.at(i)->height, - cv::Scalar(255, 0, 0)); + drawRoiOnImage(cv_ptr->image, roi, img_width, img_height, cv::Scalar(255, 0, 0)); // blue } - // TODO(yukke42): show iou_score on image for (const auto & roi : image_rois_) { - drawRoiOnImage( - cv_ptr->image, roi, image_buffer.at(i)->width, image_buffer.at(i)->height, - cv::Scalar(0, 0, 255)); + drawRoiOnImage(cv_ptr->image, roi, img_width, img_height, cv::Scalar(0, 0, 255)); // red + } + + // show iou_score on image + if (draw_iou_score) { + for (auto roi_index = 0; roi_index < static_cast(image_rois_.size()); ++roi_index) { + std::stringstream stream; + stream << std::fixed << std::setprecision(2) << max_iou_for_image_rois_.at(roi_index); + std::string iou_score = stream.str(); + + // set text position + int baseline = 3; + cv::Size textSize = cv::getTextSize(iou_score, cv::FONT_HERSHEY_SIMPLEX, 0.5, 1, &baseline); + const int text_height = static_cast(textSize.height); + const int text_width = static_cast(textSize.width); + int x = image_rois_.at(roi_index).x_offset; + int y = image_rois_.at(roi_index).y_offset; // offset for text + if (y < 0 + text_height) + y = text_height; // if roi is on the top of image, put text on lower left of roi + if (y > img_height - text_height) + y = img_height - + text_height; // if roi is on the bottom of image, put text on upper left of roi + if (x > img_width - text_width) + x = img_width - text_width; // if roi is on the right of image, put text on left of roi + if (x < 0) x = 0; // if roi is on the left of image, put text on right of roi + + // choice color by iou score + // cv::Scalar color = max_iou_for_image_rois_.at(i) > 0.5 ? cv::Scalar(0, 255, 0) : + // cv::Scalar(0, 0, 255); + cv::Scalar color = cv::Scalar(0, 0, 255); // red + + cv::rectangle( + cv_ptr->image, cv::Point(x, y - textSize.height - baseline), + cv::Point(x + textSize.width, y), cv::Scalar(255, 255, 255), + cv::FILLED); // white background + cv::putText( + cv_ptr->image, iou_score, cv::Point(x, y), cv::FONT_HERSHEY_SIMPLEX, 0.5, color, 1, + cv::LINE_AA); // text + } } image_pub.publish(cv_ptr->toImageMsg()); diff --git a/perception/image_projection_based_fusion/src/fusion_node.cpp b/perception/image_projection_based_fusion/src/fusion_node.cpp index a540688f7e751..df797369208fe 100644 --- a/perception/image_projection_based_fusion/src/fusion_node.cpp +++ b/perception/image_projection_based_fusion/src/fusion_node.cpp @@ -203,6 +203,7 @@ void FusionNode::subCallback(const typename Msg::ConstSharedPtr input_ (*output_msg).header.stamp.sec * (int64_t)1e9 + (*output_msg).header.stamp.nanosec; // if matching rois exist, fuseOnSingle + // please ask maintainers before parallelize this loop because debugger is not thread safe for (std::size_t roi_i = 0; roi_i < rois_number_; ++roi_i) { if (camera_info_map_.find(roi_i) == camera_info_map_.end()) { RCLCPP_WARN_THROTTLE( diff --git a/perception/image_projection_based_fusion/src/roi_cluster_fusion/node.cpp b/perception/image_projection_based_fusion/src/roi_cluster_fusion/node.cpp index 4a46c8aace696..9da9df7eff6ca 100644 --- a/perception/image_projection_based_fusion/src/roi_cluster_fusion/node.cpp +++ b/perception/image_projection_based_fusion/src/roi_cluster_fusion/node.cpp @@ -84,10 +84,6 @@ void RoiClusterFusionNode::fuseOnSingleImage( const DetectedObjectsWithFeature & input_roi_msg, const sensor_msgs::msg::CameraInfo & camera_info, DetectedObjectsWithFeature & output_cluster_msg) { - std::vector debug_image_rois; - std::vector debug_pointcloud_rois; - std::vector debug_image_points; - Eigen::Matrix4d projection; projection << camera_info.p.at(0), camera_info.p.at(1), camera_info.p.at(2), camera_info.p.at(3), camera_info.p.at(4), camera_info.p.at(5), camera_info.p.at(6), camera_info.p.at(7), @@ -100,6 +96,9 @@ void RoiClusterFusionNode::fuseOnSingleImage( tf_buffer_, /*target*/ camera_info.header.frame_id, /*source*/ input_cluster_msg.header.frame_id, camera_info.header.stamp); if (!transform_stamped_optional) { + RCLCPP_WARN_STREAM( + get_logger(), "Failed to get transform from " << input_cluster_msg.header.frame_id << " to " + << camera_info.header.frame_id); return; } transform_stamped = transform_stamped_optional.value(); @@ -151,7 +150,7 @@ void RoiClusterFusionNode::fuseOnSingleImage( max_x = std::max(static_cast(normalized_projected_point.x()), max_x); max_y = std::max(static_cast(normalized_projected_point.y()), max_y); projected_points.push_back(normalized_projected_point); - debug_image_points.push_back(normalized_projected_point); + if (debugger_) debugger_->obstacle_points_.push_back(normalized_projected_point); } } if (projected_points.empty()) { @@ -165,7 +164,7 @@ void RoiClusterFusionNode::fuseOnSingleImage( roi.width = max_x - min_x; roi.height = max_y - min_y; m_cluster_roi.insert(std::make_pair(i, roi)); - debug_pointcloud_rois.push_back(roi); + if (debugger_) debugger_->obstacle_rois_.push_back(roi); } for (const auto & feature_obj : input_roi_msg.feature_objects) { @@ -231,13 +230,12 @@ void RoiClusterFusionNode::fuseOnSingleImage( } } } - debug_image_rois.push_back(feature_obj.feature.roi); + if (debugger_) debugger_->image_rois_.push_back(feature_obj.feature.roi); + if (debugger_) debugger_->max_iou_for_image_rois_.push_back(max_iou); } + // note: debug objects are safely cleared in fusion_node.cpp if (debugger_) { - debugger_->image_rois_ = debug_image_rois; - debugger_->obstacle_rois_ = debug_pointcloud_rois; - debugger_->obstacle_points_ = debug_image_points; debugger_->publishImage(image_id, input_roi_msg.header.stamp); } } From ea12d77d1e762703201eb85cfea280223b7ab5c9 Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Tue, 14 Nov 2023 08:49:29 +0900 Subject: [PATCH 180/202] refactor(landmark_parser): refactored landmark manager (#5511) * Refactored landmark_parser Signed-off-by: Shintaro Sakoda * Renamed landmark_parser to landmark_manager Signed-off-by: Shintaro Sakoda * Fixed tag_id Signed-off-by: Shintaro Sakoda * Refactored ar_tag_based_localizer Signed-off-by: Shintaro Sakoda * style(pre-commit): autofix * Added [[nodiscard]] Signed-off-by: Shintaro Sakoda * Refactored landmark parsing and conversion Signed-off-by: Shintaro SAKODA * style(pre-commit): autofix * Added namespace Signed-off-by: Shintaro Sakoda * Fixed include Signed-off-by: Shintaro Sakoda --------- Signed-off-by: Shintaro Sakoda Signed-off-by: Shintaro SAKODA Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../landmark_based_localizer/README.md | 6 ++--- .../ar_tag_based_localizer/package.xml | 2 +- .../src/ar_tag_based_localizer.cpp | 9 +++++-- .../src/ar_tag_based_localizer.hpp | 2 +- .../CMakeLists.txt | 6 ++--- .../landmark_manager/landmark_manager.hpp} | 26 ++++++++++++++----- .../package.xml | 5 ++-- .../src/landmark_manager.cpp} | 22 ++++++++++------ 8 files changed, 51 insertions(+), 27 deletions(-) rename localization/landmark_based_localizer/{landmark_parser => landmark_manager}/CMakeLists.txt (79%) rename localization/landmark_based_localizer/{landmark_parser/include/landmark_parser/landmark_parser_core.hpp => landmark_manager/include/landmark_manager/landmark_manager.hpp} (64%) rename localization/landmark_based_localizer/{landmark_parser => landmark_manager}/package.xml (88%) rename localization/landmark_based_localizer/{landmark_parser/src/landmark_parser_core.cpp => landmark_manager/src/landmark_manager.cpp} (92%) diff --git a/localization/landmark_based_localizer/README.md b/localization/landmark_based_localizer/README.md index 35d8d78e7015c..e4c79b7941b12 100644 --- a/localization/landmark_based_localizer/README.md +++ b/localization/landmark_based_localizer/README.md @@ -23,11 +23,11 @@ This calculated ego pose is passed to the EKF, where it is fused with the twist ![node diagram](./doc_image/node_diagram.drawio.svg) -### `landmark_parser` +### `landmark_manager` The definitions of the landmarks written to the map are introduced in the next section. See `Map Specifications`. -The `landmark_parser` is a utility package to load landmarks from the map. +The `landmark_manager` is a utility package to load landmarks from the map. - Translation : The center of the four vertices of the landmark - Rotation : Let the vertex numbers be 1, 2, 3, 4 counterclockwise as shown in the next section. Direction is defined as the cross product of the vector from 1 to 2 and the vector from 2 to 3. @@ -43,7 +43,7 @@ So, if the 4 vertices are considered as forming a tetrahedron and its volume exc ## Map specifications -For this package to work correctly, the poses of the landmarks must be specified in the Lanelet2 map format that `map_loader` and `landmark_parser` can interpret. +For this package to work correctly, the poses of the landmarks must be specified in the Lanelet2 map format that `map_loader` and `landmark_manager` can interpret. The four vertices of a landmark are defined counterclockwise. diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml b/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml index a22e7b1acf6dc..24b737c309016 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml @@ -17,7 +17,7 @@ cv_bridge diagnostic_msgs image_transport - landmark_parser + landmark_manager lanelet2_extension localization_util rclcpp diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp b/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp index bc40fb1532297..a66277c699a00 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp @@ -148,8 +148,13 @@ bool ArTagBasedLocalizer::setup() void ArTagBasedLocalizer::map_bin_callback(const HADMapBin::ConstSharedPtr & msg) { - landmark_map_ = parse_landmark(msg, "apriltag_16h5", this->get_logger()); - const MarkerArray marker_msg = convert_to_marker_array_msg(landmark_map_); + const std::vector landmarks = + landmark_manager::parse_landmarks(msg, "apriltag_16h5", this->get_logger()); + for (const landmark_manager::Landmark & landmark : landmarks) { + landmark_map_[landmark.id] = landmark.pose; + } + + const MarkerArray marker_msg = landmark_manager::convert_landmarks_to_marker_array_msg(landmarks); marker_pub_->publish(marker_msg); } diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.hpp b/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.hpp index fe33a64b995a3..889e76eb78ad2 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.hpp +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.hpp @@ -45,7 +45,7 @@ #ifndef AR_TAG_BASED_LOCALIZER_HPP_ #define AR_TAG_BASED_LOCALIZER_HPP_ -#include "landmark_parser/landmark_parser_core.hpp" +#include "landmark_manager/landmark_manager.hpp" #include #include diff --git a/localization/landmark_based_localizer/landmark_parser/CMakeLists.txt b/localization/landmark_based_localizer/landmark_manager/CMakeLists.txt similarity index 79% rename from localization/landmark_based_localizer/landmark_parser/CMakeLists.txt rename to localization/landmark_based_localizer/landmark_manager/CMakeLists.txt index 41f7c00d61383..1b6126c892d2e 100644 --- a/localization/landmark_based_localizer/landmark_parser/CMakeLists.txt +++ b/localization/landmark_based_localizer/landmark_manager/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(landmark_parser) +project(landmark_manager) find_package(autoware_cmake REQUIRED) autoware_package() @@ -12,8 +12,8 @@ endif() find_package(ament_cmake_auto REQUIRED) ament_auto_find_build_dependencies() -ament_auto_add_library(landmark_parser - src/landmark_parser_core.cpp +ament_auto_add_library(landmark_manager + src/landmark_manager.cpp ) ament_auto_package( diff --git a/localization/landmark_based_localizer/landmark_parser/include/landmark_parser/landmark_parser_core.hpp b/localization/landmark_based_localizer/landmark_manager/include/landmark_manager/landmark_manager.hpp similarity index 64% rename from localization/landmark_based_localizer/landmark_parser/include/landmark_parser/landmark_parser_core.hpp rename to localization/landmark_based_localizer/landmark_manager/include/landmark_manager/landmark_manager.hpp index edf45c2a2997a..9a22ee13f60ae 100644 --- a/localization/landmark_based_localizer/landmark_parser/include/landmark_parser/landmark_parser_core.hpp +++ b/localization/landmark_based_localizer/landmark_manager/include/landmark_manager/landmark_manager.hpp @@ -12,23 +12,35 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef LANDMARK_PARSER__LANDMARK_PARSER_CORE_HPP_ -#define LANDMARK_PARSER__LANDMARK_PARSER_CORE_HPP_ +#ifndef LANDMARK_MANAGER__LANDMARK_MANAGER_HPP_ +#define LANDMARK_MANAGER__LANDMARK_MANAGER_HPP_ #include #include "autoware_auto_mapping_msgs/msg/had_map_bin.hpp" #include +#include #include -#include #include +#include -std::map parse_landmark( +namespace landmark_manager +{ + +struct Landmark +{ + std::string id; + geometry_msgs::msg::Pose pose; +}; + +std::vector parse_landmarks( const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr & msg, const std::string & target_subtype, const rclcpp::Logger & logger); -visualization_msgs::msg::MarkerArray convert_to_marker_array_msg( - const std::map & landmarks); +visualization_msgs::msg::MarkerArray convert_landmarks_to_marker_array_msg( + const std::vector & landmarks); + +} // namespace landmark_manager -#endif // LANDMARK_PARSER__LANDMARK_PARSER_CORE_HPP_ +#endif // LANDMARK_MANAGER__LANDMARK_MANAGER_HPP_ diff --git a/localization/landmark_based_localizer/landmark_parser/package.xml b/localization/landmark_based_localizer/landmark_manager/package.xml similarity index 88% rename from localization/landmark_based_localizer/landmark_parser/package.xml rename to localization/landmark_based_localizer/landmark_manager/package.xml index e3daa93f81220..1a35ae6a338d1 100644 --- a/localization/landmark_based_localizer/landmark_parser/package.xml +++ b/localization/landmark_based_localizer/landmark_manager/package.xml @@ -1,9 +1,9 @@ - landmark_parser + landmark_manager 0.0.0 - The landmark_parser package + The landmark_manager package Shintaro Sakoda Masahiro Sakamoto Yamato Ando @@ -19,6 +19,7 @@ geometry_msgs lanelet2_extension rclcpp + tf2_eigen ament_cmake diff --git a/localization/landmark_based_localizer/landmark_parser/src/landmark_parser_core.cpp b/localization/landmark_based_localizer/landmark_manager/src/landmark_manager.cpp similarity index 92% rename from localization/landmark_based_localizer/landmark_parser/src/landmark_parser_core.cpp rename to localization/landmark_based_localizer/landmark_manager/src/landmark_manager.cpp index c86b35b6115b4..6d1698daf5eae 100644 --- a/localization/landmark_based_localizer/landmark_parser/src/landmark_parser_core.cpp +++ b/localization/landmark_based_localizer/landmark_manager/src/landmark_manager.cpp @@ -12,16 +12,20 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "landmark_parser/landmark_parser_core.hpp" +#include "landmark_manager/landmark_manager.hpp" #include "lanelet2_extension/utility/message_conversion.hpp" #include +#include #include #include -std::map parse_landmark( +namespace landmark_manager +{ + +std::vector parse_landmarks( const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr & msg, const std::string & target_subtype, const rclcpp::Logger & logger) { @@ -32,7 +36,7 @@ std::map parse_landmark( lanelet::LaneletMapPtr lanelet_map_ptr{std::make_shared()}; lanelet::utils::conversion::fromBinMsg(*msg, lanelet_map_ptr); - std::map landmark_map; + std::vector landmarks; for (const auto & poly : lanelet_map_ptr->polygonLayer) { const std::string type{poly.attributeOr(lanelet::AttributeName::Type, "none")}; @@ -93,8 +97,8 @@ std::map parse_landmark( pose.orientation.z = q.z(); pose.orientation.w = q.w(); - // Add to map - landmark_map[marker_id] = pose; + // Add + landmarks.push_back(Landmark{marker_id, pose}); RCLCPP_INFO_STREAM(logger, "id: " << marker_id); RCLCPP_INFO_STREAM( logger, @@ -104,11 +108,11 @@ std::map parse_landmark( << pose.orientation.z << ", " << pose.orientation.w); } - return landmark_map; + return landmarks; } -visualization_msgs::msg::MarkerArray convert_to_marker_array_msg( - const std::map & landmarks) +visualization_msgs::msg::MarkerArray convert_landmarks_to_marker_array_msg( + const std::vector & landmarks) { int32_t id = 0; visualization_msgs::msg::MarkerArray marker_array; @@ -152,3 +156,5 @@ visualization_msgs::msg::MarkerArray convert_to_marker_array_msg( } return marker_array; } + +} // namespace landmark_manager From 60a51e005d99422f726e2388989dac46335e3ce0 Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Tue, 14 Nov 2023 11:03:49 +0900 Subject: [PATCH 181/202] feat(obstacle_cruise_planner): use obstacle velocity based obstacle parameters (#5510) * Add extra tag for moving obstacle type Signed-off-by: Daniel Sanchez * add static and moving as parameter postfixes Signed-off-by: Daniel Sanchez * set hysteresis-based obstacle moving classification Signed-off-by: Daniel Sanchez * update config params Signed-off-by: Daniel Sanchez * Use speed norm for object classification Signed-off-by: Daniel Sanchez * changed '_' for '.' to make the code more consistent Signed-off-by: Daniel Sanchez * update documentation Signed-off-by: Daniel Sanchez * move the obstacle moving check to generateSlowDownTrajectory Signed-off-by: Daniel Sanchez * remove unnecessary reference Signed-off-by: Daniel Sanchez * add const to certain variables Signed-off-by: Daniel Sanchez --------- Signed-off-by: Daniel Sanchez Signed-off-by: Daniel Sanchez --- planning/obstacle_cruise_planner/README.md | 32 +++--- .../config/obstacle_cruise_planner.param.yaml | 31 ++++-- .../planner_interface.hpp | 104 +++++++++++------- .../src/planner_interface.cpp | 24 ++-- 4 files changed, 120 insertions(+), 71 deletions(-) diff --git a/planning/obstacle_cruise_planner/README.md b/planning/obstacle_cruise_planner/README.md index 260f302791079..532761b1f0cb7 100644 --- a/planning/obstacle_cruise_planner/README.md +++ b/planning/obstacle_cruise_planner/README.md @@ -230,19 +230,25 @@ $$ ### Slow down planning -| Parameter | Type | Description | -| ----------------------------------------------- | -------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | -| `slow_down.labels` | vector(string) | A vector of labels for customizing obstacle-label-based slow down behavior. Each label represents an obstacle type that will be treated differently when applying slow down. The possible labels are ("default" (Mandatory), "unknown","car","truck","bus","trailer","motorcycle","bicycle" or "pedestrian") | -| `slow_down.default.min_lat_velocity` | double | minimum velocity to linearly calculate slow down velocity [m]. Note: This default value will be used when the detected obstacle label does not match any of the slow_down.labels | -| `slow_down.default.max_lat_velocity` | double | maximum velocity to linearly calculate slow down velocity [m]. Note: This default value will be used when the detected obstacle label does not match any of the slow_down.labels | -| `slow_down.default.min_lat_margin` | double | minimum lateral margin to linearly calculate slow down velocity [m]. Note: This default value will be used when the detected obstacle label does not match any of the slow_down.labels | -| `slow_down.default.max_lat_margin` | double | maximum lateral margin to linearly calculate slow down velocity [m]. Note: This default value will be used when the detected obstacle label does not match any of the slow_down.labels | -| `(optional) slow_down."label".min_lat_velocity` | double | minimum velocity to linearly calculate slow down velocity [m]. Note: only for obstacles specified in `slow_down.labels` | -| `(optional) slow_down."label".max_lat_velocity` | double | maximum velocity to linearly calculate slow down velocity [m]. Note: only for obstacles specified in `slow_down.labels` | -| `(optional) slow_down."label".min_lat_margin` | double | minimum lateral margin to linearly calculate slow down velocity [m]. Note: only for obstacles specified in `slow_down.labels` | -| `(optional) slow_down."label".max_lat_margin` | double | maximum lateral margin to linearly calculate slow down velocity [m]. Note: only for obstacles specified in `slow_down.labels` | - -The role of the slow down planning is inserting slow down velocity in the trajectory where the trajectory points are close to the obstacles. The parameters can be customized depending on the obstacle type (see `slow_down.labels`), making it possible to adjust the slow down behavior depending if the obstacle is a pedestrian, bicycle, car, etc. +| Parameter | Type | Description | +| ----------------------------------------------------------------- | -------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | +| `slow_down.labels` | vector(string) | A vector of labels for customizing obstacle-label-based slow down behavior. Each label represents an obstacle type that will be treated differently when applying slow down. The possible labels are ("default" (Mandatory), "unknown","car","truck","bus","trailer","motorcycle","bicycle" or "pedestrian") | +| `slow_down.default.static.min_lat_velocity` | double | minimum velocity to linearly calculate slow down velocity [m]. Note: This default value will be used when the detected obstacle label does not match any of the slow_down.labels and the obstacle is considered to be static, or not moving | +| `slow_down.default.static.max_lat_velocity` | double | maximum velocity to linearly calculate slow down velocity [m]. Note: This default value will be used when the detected obstacle label does not match any of the slow_down.labels and the obstacle is considered to be static, or not moving | +| `slow_down.default.static.min_lat_margin` | double | minimum lateral margin to linearly calculate slow down velocity [m]. Note: This default value will be used when the detected obstacle label does not match any of the slow_down.labels and the obstacle is considered to be static, or not moving | +| `slow_down.default.static.max_lat_margin` | double | maximum lateral margin to linearly calculate slow down velocity [m]. Note: This default value will be used when the detected obstacle label does not match any of the slow_down.labels and the obstacle is considered to be static, or not moving | +| `slow_down.default.moving.min_lat_velocity` | double | minimum velocity to linearly calculate slow down velocity [m]. Note: This default value will be used when the detected obstacle label does not match any of the slow_down.labels and the obstacle is considered to be moving | +| `slow_down.default.moving.max_lat_velocity` | double | maximum velocity to linearly calculate slow down velocity [m]. Note: This default value will be used when the detected obstacle label does not match any of the slow_down.labels and the obstacle is considered to be moving | +| `slow_down.default.moving.min_lat_margin` | double | minimum lateral margin to linearly calculate slow down velocity [m]. Note: This default value will be used when the detected obstacle label does not match any of the slow_down.labels and the obstacle is considered to be moving | +| `slow_down.default.moving.max_lat_margin` | double | maximum lateral margin to linearly calculate slow down velocity [m]. Note: This default value will be used when the detected obstacle label does not match any of the slow_down.labels and the obstacle is considered to be moving | +| `(optional) slow_down."label".(static & moving).min_lat_velocity` | double | minimum velocity to linearly calculate slow down velocity [m]. Note: only for obstacles specified in `slow_down.labels`. Requires a `static` and a `moving` value | +| `(optional) slow_down."label".(static & moving).max_lat_velocity` | double | maximum velocity to linearly calculate slow down velocity [m]. Note: only for obstacles specified in `slow_down.labels`. Requires a `static` and a `moving` value | +| `(optional) slow_down."label".(static & moving).min_lat_margin` | double | minimum lateral margin to linearly calculate slow down velocity [m]. Note: only for obstacles specified in `slow_down.labels`. Requires a `static` and a `moving` value | +| `(optional) slow_down."label".(static & moving).max_lat_margin` | double | maximum lateral margin to linearly calculate slow down velocity [m]. Note: only for obstacles specified in `slow_down.labels`. Requires a `static` and a `moving` value | + +The role of the slow down planning is inserting slow down velocity in the trajectory where the trajectory points are close to the obstacles. The parameters can be customized depending on the obstacle type (see `slow_down.labels`), making it possible to adjust the slow down behavior depending if the obstacle is a pedestrian, bicycle, car, etc. Each obstacle type has a `static` and a `moving` parameter set, so it is possible to customize the slow down response of the ego vehicle according to the obstacle type and if it is moving or not. If an obstacle is determined to be moving, the corresponding `moving` set of parameters will be used to compute the vehicle slow down, otherwise, the `static` parameters will be used. The `static` and `moving` separation is useful for customizing the ego vehicle slow down behavior to, for example, slow down more significantly when passing stopped vehicles that might cause occlusion or that might suddenly open its doors. + +An obstacle is classified as `static` if its total speed is less than the `moving_object_speed_threshold` parameter. Furthermore, a hysteresis based approach is used to avoid chattering, it uses the `moving_object_hysteresis_range` parameter range and the obstacle's previous state (`moving` or `static`) to determine if the obstacle is moving or not. In other words, if an obstacle was previously classified as `static`, it will not change its classification to `moving` unless its total speed is greater than `moving_object_speed_threshold` + `moving_object_hysteresis_range`. Likewise, an obstacle previously classified as `moving`, will only change to `static` if its speed is lower than `moving_object_speed_threshold` - `moving_object_hysteresis_range`. The closest point on the obstacle to the ego's trajectory is calculated. Then, the slow down velocity is calculated by linear interpolation with the distance between the point and trajectory as follows. 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 123d0dda93b7a..def2a2af78b37 100644 --- a/planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml +++ b/planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml @@ -183,15 +183,30 @@ - "default" - "pedestrian" default: - min_lat_margin: 0.2 - max_lat_margin: 1.0 - min_ego_velocity: 2.0 - max_ego_velocity: 8.0 + moving: + min_lat_margin: 0.8 + max_lat_margin: 1.3 + min_ego_velocity: 0.5 + max_ego_velocity: 1.5 + static: + min_lat_margin: 0.2 + max_lat_margin: 1.0 + min_ego_velocity: 2.0 + max_ego_velocity: 8.0 pedestrian: - min_lat_margin: 0.5 - max_lat_margin: 1.5 - min_ego_velocity: 1.0 - max_ego_velocity: 2.0 + moving: + min_lat_margin: 0.8 + max_lat_margin: 1.3 + min_ego_velocity: 0.5 + max_ego_velocity: 0.8 + static: + min_lat_margin: 0.8 + max_lat_margin: 1.3 + min_ego_velocity: 1.0 + max_ego_velocity: 2.0 + + moving_object_speed_threshold: 0.5 # [m/s] how fast the object needs to move to be considered as "moving" + moving_object_hysteresis_range: 0.1 # [m/s] hysteresis range used to prevent chattering when obstacle moves close to moving_object_speed_threshold time_margin_on_target_velocity: 1.5 # [s] 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 d8c31fb35df9b..2e1e165a78952 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 @@ -49,6 +49,11 @@ class PlannerInterface node.create_publisher("/planning/velocity_factors/obstacle_cruise", 1); stop_speed_exceeded_pub_ = node.create_publisher("~/output/stop_speed_exceeded", 1); + + moving_object_speed_threshold = + node.declare_parameter("slow_down.moving_object_speed_threshold"); + moving_object_hysteresis_range = + node.declare_parameter("slow_down.moving_object_hysteresis_range"); } PlannerInterface() = default; @@ -183,11 +188,12 @@ class PlannerInterface const std::string & arg_uuid, const std::vector & traj_points, const std::optional & start_idx, const std::optional & end_idx, const double arg_target_vel, const double arg_feasible_target_vel, - const double arg_precise_lat_dist) + const double arg_precise_lat_dist, const bool is_moving) : uuid(arg_uuid), target_vel(arg_target_vel), feasible_target_vel(arg_feasible_target_vel), - precise_lat_dist(arg_precise_lat_dist) + precise_lat_dist(arg_precise_lat_dist), + is_moving(is_moving) { if (start_idx) { start_point = traj_points.at(*start_idx).pose; @@ -203,15 +209,17 @@ class PlannerInterface double precise_lat_dist; std::optional start_point{std::nullopt}; std::optional end_point{std::nullopt}; + bool is_moving; }; double calculateMarginFromObstacleOnCurve( const PlannerData & planner_data, const StopObstacle & stop_obstacle) const; double calculateSlowDownVelocity( - const SlowDownObstacle & obstacle, const std::optional & prev_output) const; + const SlowDownObstacle & obstacle, const std::optional & prev_output, + const bool is_obstacle_moving) const; std::optional> calculateDistanceToSlowDownWithConstraints( const PlannerData & planner_data, const std::vector & traj_points, const SlowDownObstacle & obstacle, const std::optional & prev_output, - const double dist_to_ego) const; + const double dist_to_ego, const bool is_obstacle_moving) const; struct SlowDownInfo { @@ -223,6 +231,7 @@ class PlannerInterface struct SlowDownParam { std::vector obstacle_labels{"default"}; + std::vector obstacle_moving_classification{"static", "moving"}; std::unordered_map types_map; struct ObstacleSpecificParams { @@ -233,28 +242,23 @@ class PlannerInterface }; explicit SlowDownParam(rclcpp::Node & node) { - types_map = {{ObjectClassification::UNKNOWN, "unknown"}, - {ObjectClassification::CAR, "car"}, - {ObjectClassification::TRUCK, "truck"}, - {ObjectClassification::BUS, "bus"}, - {ObjectClassification::TRAILER, "trailer"}, - {ObjectClassification::MOTORCYCLE, "motorcycle"}, - {ObjectClassification::BICYCLE, "bicycle"}, - {ObjectClassification::PEDESTRIAN, "pedestrian"}}; obstacle_labels = node.declare_parameter>("slow_down.labels", obstacle_labels); // obstacle label dependant parameters for (const auto & label : obstacle_labels) { - ObstacleSpecificParams params; - params.max_lat_margin = - node.declare_parameter("slow_down." + label + ".max_lat_margin"); - params.min_lat_margin = - node.declare_parameter("slow_down." + label + ".min_lat_margin"); - params.max_ego_velocity = - node.declare_parameter("slow_down." + label + ".max_ego_velocity"); - params.min_ego_velocity = - node.declare_parameter("slow_down." + label + ".min_ego_velocity"); - obstacle_to_param_struct_map.emplace(std::make_pair(label, params)); + for (const auto & movement_postfix : obstacle_moving_classification) { + ObstacleSpecificParams params; + params.max_lat_margin = node.declare_parameter( + "slow_down." + label + "." + movement_postfix + ".max_lat_margin"); + params.min_lat_margin = node.declare_parameter( + "slow_down." + label + "." + movement_postfix + ".min_lat_margin"); + params.max_ego_velocity = node.declare_parameter( + "slow_down." + label + "." + movement_postfix + ".max_ego_velocity"); + params.min_ego_velocity = node.declare_parameter( + "slow_down." + label + "." + movement_postfix + ".min_ego_velocity"); + obstacle_to_param_struct_map.emplace( + std::make_pair(label + "." + movement_postfix, params)); + } } // common parameters @@ -264,34 +268,49 @@ class PlannerInterface lpf_gain_lat_dist = node.declare_parameter("slow_down.lpf_gain_lat_dist"); lpf_gain_dist_to_slow_down = node.declare_parameter("slow_down.lpf_gain_dist_to_slow_down"); + + types_map = {{ObjectClassification::UNKNOWN, "unknown"}, + {ObjectClassification::CAR, "car"}, + {ObjectClassification::TRUCK, "truck"}, + {ObjectClassification::BUS, "bus"}, + {ObjectClassification::TRAILER, "trailer"}, + {ObjectClassification::MOTORCYCLE, "motorcycle"}, + {ObjectClassification::BICYCLE, "bicycle"}, + {ObjectClassification::PEDESTRIAN, "pedestrian"}}; } - ObstacleSpecificParams getObstacleParamByLabel(const ObjectClassification & label_id) const + ObstacleSpecificParams getObstacleParamByLabel( + const ObjectClassification & label_id, const bool is_obstacle_moving) const { - const std::string label = types_map.at(label_id.label); - if (obstacle_to_param_struct_map.count(label) > 0) { - return obstacle_to_param_struct_map.at(label); - } - return obstacle_to_param_struct_map.at("default"); + const std::string label = + (types_map.count(label_id.label) > 0) ? types_map.at(label_id.label) : "default"; + const std::string movement_postfix = (is_obstacle_moving) ? "moving" : "static"; + return (obstacle_to_param_struct_map.count(label + "." + movement_postfix) > 0) + ? obstacle_to_param_struct_map.at(label + "." + movement_postfix) + : obstacle_to_param_struct_map.at("default." + movement_postfix); } void onParam(const std::vector & parameters) { // obstacle type dependant parameters for (const auto & label : obstacle_labels) { - auto & param_by_obstacle_label = obstacle_to_param_struct_map[label]; - tier4_autoware_utils::updateParam( - parameters, "slow_down." + label + ".max_lat_margin", - param_by_obstacle_label.max_lat_margin); - tier4_autoware_utils::updateParam( - parameters, "slow_down." + label + ".min_lat_margin", - param_by_obstacle_label.min_lat_margin); - tier4_autoware_utils::updateParam( - parameters, "slow_down." + label + ".max_ego_velocity", - param_by_obstacle_label.max_ego_velocity); - tier4_autoware_utils::updateParam( - parameters, "slow_down." + label + ".min_ego_velocity", - param_by_obstacle_label.min_ego_velocity); + for (const auto & movement_postfix : obstacle_moving_classification) { + if (obstacle_to_param_struct_map.count(label + "." + movement_postfix) < 1) continue; + auto & param_by_obstacle_label = + obstacle_to_param_struct_map.at(label + "." + movement_postfix); + tier4_autoware_utils::updateParam( + parameters, "slow_down." + label + "." + movement_postfix + ".max_lat_margin", + param_by_obstacle_label.max_lat_margin); + tier4_autoware_utils::updateParam( + parameters, "slow_down." + label + "." + movement_postfix + ".min_lat_margin", + param_by_obstacle_label.min_lat_margin); + tier4_autoware_utils::updateParam( + parameters, "slow_down." + label + "." + movement_postfix + ".max_ego_velocity", + param_by_obstacle_label.max_ego_velocity); + tier4_autoware_utils::updateParam( + parameters, "slow_down." + label + "." + movement_postfix + ".min_ego_velocity", + param_by_obstacle_label.min_ego_velocity); + } } // common parameters @@ -313,7 +332,8 @@ class PlannerInterface double lpf_gain_dist_to_slow_down; }; SlowDownParam slow_down_param_; - + double moving_object_speed_threshold; + double moving_object_hysteresis_range; std::vector prev_slow_down_output_; // previous trajectory and distance to stop // NOTE: Previous trajectory is memorized to deal with nearest index search for overlapping or diff --git a/planning/obstacle_cruise_planner/src/planner_interface.cpp b/planning/obstacle_cruise_planner/src/planner_interface.cpp index 76469364cfb39..47f62016df53b 100644 --- a/planning/obstacle_cruise_planner/src/planner_interface.cpp +++ b/planning/obstacle_cruise_planner/src/planner_interface.cpp @@ -561,9 +561,17 @@ std::vector PlannerInterface::generateSlowDownTrajectory( const auto & obstacle = obstacles.at(i); const auto prev_output = getObjectFromUuid(prev_slow_down_output_, obstacle.uuid); + const bool is_obstacle_moving = [&]() -> bool { + const auto object_vel_norm = std::hypot(obstacle.velocity, obstacle.lat_velocity); + if (!prev_output) return object_vel_norm > moving_object_speed_threshold; + if (prev_output->is_moving) + return object_vel_norm > moving_object_speed_threshold - moving_object_hysteresis_range; + return object_vel_norm > moving_object_speed_threshold + moving_object_hysteresis_range; + }(); + // calculate slow down start distance, and insert slow down velocity const auto dist_vec_to_slow_down = calculateDistanceToSlowDownWithConstraints( - planner_data, slow_down_traj_points, obstacle, prev_output, dist_to_ego); + planner_data, slow_down_traj_points, obstacle, prev_output, dist_to_ego, is_obstacle_moving); if (!dist_vec_to_slow_down) { RCLCPP_INFO_EXPRESSION( rclcpp::get_logger("ObstacleCruisePlanner::PlannerInterface"), enable_debug_info_, @@ -648,7 +656,7 @@ std::vector PlannerInterface::generateSlowDownTrajectory( // update prev_slow_down_output_ new_prev_slow_down_output.push_back(SlowDownOutput{ obstacle.uuid, slow_down_traj_points, slow_down_start_idx, slow_down_end_idx, - stable_slow_down_vel, feasible_slow_down_vel, obstacle.precise_lat_dist}); + stable_slow_down_vel, feasible_slow_down_vel, obstacle.precise_lat_dist, is_obstacle_moving}); } // update prev_slow_down_output_ @@ -663,10 +671,11 @@ std::vector PlannerInterface::generateSlowDownTrajectory( } double PlannerInterface::calculateSlowDownVelocity( - const SlowDownObstacle & obstacle, const std::optional & prev_output) const + const SlowDownObstacle & obstacle, const std::optional & prev_output, + const bool is_obstacle_moving) const { - const auto & p = slow_down_param_.getObstacleParamByLabel(obstacle.classification); - + const auto & p = + slow_down_param_.getObstacleParamByLabel(obstacle.classification, is_obstacle_moving); const double stable_precise_lat_dist = [&]() { if (prev_output) { return signal_processing::lowpassFilter( @@ -689,15 +698,14 @@ std::optional> PlannerInterface::calculateDistanceToSlowDownWithConstraints( const PlannerData & planner_data, const std::vector & traj_points, const SlowDownObstacle & obstacle, const std::optional & prev_output, - const double dist_to_ego) const + const double dist_to_ego, const bool is_obstacle_moving) const { const double abs_ego_offset = planner_data.is_driving_forward ? std::abs(vehicle_info_.max_longitudinal_offset_m) : std::abs(vehicle_info_.min_longitudinal_offset_m); const double obstacle_vel = obstacle.velocity; - // calculate slow down velocity - const double slow_down_vel = calculateSlowDownVelocity(obstacle, prev_output); + const double slow_down_vel = calculateSlowDownVelocity(obstacle, prev_output, is_obstacle_moving); // calculate distance to collision points const double dist_to_front_collision = From ef0569f5d0e94282454951f94a5abe2963b7b79c Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 14 Nov 2023 11:31:36 +0900 Subject: [PATCH 182/202] refactor(side_shift): support new interface (#5556) Signed-off-by: satoshi-ota --- .../side_shift/side_shift_module.hpp | 26 ++----------------- .../side_shift/side_shift_module.cpp | 14 ++++------ 2 files changed, 7 insertions(+), 33 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/side_shift_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/side_shift_module.hpp index 7c04cab5c081f..fce31b6db7369 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/side_shift_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/side_shift_module.hpp @@ -49,8 +49,6 @@ class SideShiftModule : public SceneModuleInterface bool isExecutionReady() const override; bool isReadyForNextRequest( const double & min_request_time_sec, bool override_requests = false) const noexcept; - // TODO(someone): remove this, and use base class function - [[deprecated]] ModuleStatus updateState() override; void updateData() override; BehaviorModuleOutput plan() override; BehaviorModuleOutput planWaitingApproval() override; @@ -70,32 +68,12 @@ class SideShiftModule : public SceneModuleInterface { } - // TODO(someone): remove this, and use base class function - [[deprecated]] BehaviorModuleOutput run() override - { - updateData(); - - if (!isWaitingApproval()) { - return plan(); - } - - // module is waiting approval. Check it. - if (isActivated()) { - RCLCPP_DEBUG(getLogger(), "Was waiting approval, and now approved. Do plan()."); - return plan(); - } else { - RCLCPP_DEBUG(getLogger(), "keep waiting approval... Do planCandidate()."); - return planWaitingApproval(); - } - } - private: - bool canTransitSuccessState() override { return false; } + bool canTransitSuccessState() override; bool canTransitFailureState() override { return false; } - bool canTransitIdleToRunningState() override { return false; } - rclcpp::Subscription::SharedPtr lateral_offset_subscriber_; + bool canTransitIdleToRunningState() override { return true; } void initVariables(); diff --git a/planning/behavior_path_planner/src/scene_module/side_shift/side_shift_module.cpp b/planning/behavior_path_planner/src/scene_module/side_shift/side_shift_module.cpp index 2232c6d750d55..46332e738f82f 100644 --- a/planning/behavior_path_planner/src/scene_module/side_shift/side_shift_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/side_shift/side_shift_module.cpp @@ -40,8 +40,6 @@ SideShiftModule::SideShiftModule( const std::unordered_map > & rtc_interface_ptr_map) : SceneModuleInterface{name, node, rtc_interface_ptr_map}, parameters_{parameters} { - // If lateral offset is subscribed, it approves side shift module automatically - clearWaitingApproval(); } void SideShiftModule::initVariables() @@ -80,7 +78,7 @@ void SideShiftModule::setParameters(const std::shared_ptr & bool SideShiftModule::isExecutionRequested() const { - if (current_state_ == ModuleStatus::RUNNING) { + if (getCurrentStatus() == ModuleStatus::RUNNING) { return true; } @@ -112,7 +110,7 @@ bool SideShiftModule::isReadyForNextRequest( return false; } -ModuleStatus SideShiftModule::updateState() +bool SideShiftModule::canTransitSuccessState() { // Never return the FAILURE. When the desired offset is zero and the vehicle is in the original // drivable area,this module can stop the computation and return SUCCESS. @@ -150,7 +148,7 @@ ModuleStatus SideShiftModule::updateState() no_shifted_plan); if (no_request && no_shifted_plan && no_offset_diff) { - return ModuleStatus::SUCCESS; + return true; } const auto & current_lanes = utils::getCurrentLanes(planner_data_); @@ -169,7 +167,7 @@ ModuleStatus SideShiftModule::updateState() } else { shift_status_ = SideShiftStatus::AFTER_SHIFT; } - return ModuleStatus::RUNNING; + return false; } void SideShiftModule::updateData() @@ -184,7 +182,7 @@ void SideShiftModule::updateData() } } - if (current_state_ != ModuleStatus::RUNNING && current_state_ != ModuleStatus::IDLE) { + if (getCurrentStatus() != ModuleStatus::RUNNING && getCurrentStatus() != ModuleStatus::IDLE) { return; } @@ -331,8 +329,6 @@ BehaviorModuleOutput SideShiftModule::planWaitingApproval() prev_output_ = shifted_path; - waitApproval(); - return output; } From 6e6cb40e5f91715266d9d4d15f8a0cc89a586709 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 14 Nov 2023 12:46:44 +0900 Subject: [PATCH 183/202] refactor(goal_planner): add updateStatus and reduce variables (#5546) * refactor(goal_planner): add updateStatus and reduce variables Signed-off-by: kosuke55 refactor Signed-off-by: kosuke55 refactor Signed-off-by: kosuke55 * move to updatedata Signed-off-by: kosuke55 * Update planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp Co-authored-by: Kyoichi Sugahara * style(pre-commit): autofix --------- Signed-off-by: kosuke55 Co-authored-by: Kyoichi Sugahara Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../goal_planner/goal_planner_module.hpp | 56 ++-- .../goal_planner/pull_over_planner_base.hpp | 1 + .../goal_planner/goal_planner_module.cpp | 272 +++++++++--------- 3 files changed, 152 insertions(+), 177 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp index e4044d7191805..5149979ef082d 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp @@ -93,50 +93,30 @@ class PullOverStatus void reset() { lane_parking_pull_over_path_ = nullptr; - current_path_idx_ = 0; - require_increment_ = true; prev_stop_path_ = nullptr; prev_stop_path_after_approval_ = nullptr; - current_lanes_.clear(); - pull_over_lanes_.clear(); - lanes_.clear(); - has_decided_path_ = false; - is_safe_dynamic_objects_ = false; + + is_safe_ = false; prev_found_path_ = false; - prev_is_safe_dynamic_objects_ = false; - has_decided_velocity_ = false; + prev_is_safe_ = false; } DEFINE_SETTER_GETTER(std::shared_ptr, lane_parking_pull_over_path) - DEFINE_SETTER_GETTER(size_t, current_path_idx) - DEFINE_SETTER_GETTER(bool, require_increment) DEFINE_SETTER_GETTER(std::shared_ptr, prev_stop_path) DEFINE_SETTER_GETTER(std::shared_ptr, prev_stop_path_after_approval) - DEFINE_SETTER_GETTER(lanelet::ConstLanelets, current_lanes) - DEFINE_SETTER_GETTER(lanelet::ConstLanelets, pull_over_lanes) - DEFINE_SETTER_GETTER(std::vector, lanes) - DEFINE_SETTER_GETTER(bool, has_decided_path) - DEFINE_SETTER_GETTER(bool, is_safe_dynamic_objects) + DEFINE_SETTER_GETTER(bool, is_safe) DEFINE_SETTER_GETTER(bool, prev_found_path) - DEFINE_SETTER_GETTER(bool, prev_is_safe_dynamic_objects) - DEFINE_SETTER_GETTER(bool, has_decided_velocity) + DEFINE_SETTER_GETTER(bool, prev_is_safe) DEFINE_SETTER_GETTER(Pose, refined_goal_pose) DEFINE_SETTER_GETTER(Pose, closest_goal_candidate_pose) private: std::shared_ptr lane_parking_pull_over_path_{nullptr}; - size_t current_path_idx_{0}; - bool require_increment_{true}; std::shared_ptr prev_stop_path_{nullptr}; std::shared_ptr prev_stop_path_after_approval_{nullptr}; - lanelet::ConstLanelets current_lanes_{}; - lanelet::ConstLanelets pull_over_lanes_{}; - std::vector lanes_{}; - bool has_decided_path_{false}; - bool is_safe_dynamic_objects_{false}; + bool is_safe_{false}; bool prev_found_path_{false}; - bool prev_is_safe_dynamic_objects_{false}; - bool has_decided_velocity_{false}; + bool prev_is_safe_{false}; Pose refined_goal_pose_{}; Pose closest_goal_candidate_pose_{}; @@ -177,6 +157,10 @@ class ThreadSafeData bool incrementPathIndex() { const std::lock_guard lock(mutex_); + if (!pull_over_path_) { + return false; + } + if (pull_over_path_->incrementPathIndex()) { last_path_idx_increment_time_ = clock_->now(); return true; @@ -393,10 +377,10 @@ class GoalPlannerModule : public SceneModuleInterface void decelerateForTurnSignal(const Pose & stop_pose, PathWithLaneId & path) const; void decelerateBeforeSearchStart( const Pose & search_start_offset_pose, PathWithLaneId & path) const; - PathWithLaneId generateStopPath(); - PathWithLaneId generateFeasibleStopPath(); + PathWithLaneId generateStopPath() const; + PathWithLaneId generateFeasibleStopPath() const; - void keepStoppedWithCurrentPath(PathWithLaneId & path); + void keepStoppedWithCurrentPath(PathWithLaneId & path) const; double calcSignedArcLengthFromEgo(const PathWithLaneId & path, const Pose & pose) const; // status @@ -411,6 +395,7 @@ class GoalPlannerModule : public SceneModuleInterface bool hasDecidedPath() const; void decideVelocity(); bool foundPullOverPath() const; + void updateStatus(const BehaviorModuleOutput & output); // validation bool hasEnoughDistance(const PullOverPath & pull_over_path) const; @@ -433,16 +418,13 @@ class GoalPlannerModule : public SceneModuleInterface const std::vector & pull_over_path_candidates, const GoalCandidates & goal_candidates) const; - // deal with pull over partial paths - void transitionToNextPathIfFinishingCurrentPath(); - // lanes and drivable area - void setLanes(); + std::vector generateDrivableLanes() const; void setDrivableAreaInfo(BehaviorModuleOutput & output) const; // output setter - void setOutput(BehaviorModuleOutput & output); - void setStopPath(BehaviorModuleOutput & output); + void setOutput(BehaviorModuleOutput & output) const; + void setStopPath(BehaviorModuleOutput & output) const; /** * @brief Sets a stop path in the current path based on safety conditions and previous paths. @@ -453,7 +435,7 @@ class GoalPlannerModule : public SceneModuleInterface * * @param output BehaviorModuleOutput */ - void setStopPathFromCurrentPath(BehaviorModuleOutput & output); + void setStopPathFromCurrentPath(BehaviorModuleOutput & output) const; void setModifiedGoal(BehaviorModuleOutput & output) const; void setTurnSignalInfo(BehaviorModuleOutput & output) const; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp index 4267261fdfe84..acb034a29d9e5 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp @@ -53,6 +53,7 @@ struct PullOverPath Pose end_pose{}; std::vector debug_poses{}; size_t goal_id{}; + bool decided_velocity{false}; PathWithLaneId getFullPath() const { diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index 0475cd92f1bec..202c19f1bf1db 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -255,10 +255,21 @@ void GoalPlannerModule::updateData() updateOccupancyGrid(); - // set current road lanes, pull over lanes, and drivable lane - setLanes(); - generateGoalCandidates(); + + if (!isActivated()) { + return; + } + + if (hasFinishedCurrentPath()) { + thread_safe_data_.incrementPathIndex(); + } + + if (!last_approval_data_) { + last_approval_data_ = + std::make_unique(clock_->now(), planner_data_->self_odometry->pose.pose); + decideVelocity(); + } } void GoalPlannerModule::initializeOccupancyGridMap() @@ -524,9 +535,7 @@ void GoalPlannerModule::returnToLaneParking() return; } - status_.set_has_decided_path(false); thread_safe_data_.set_pull_over_path(status_.get_lane_parking_pull_over_path()); - RCLCPP_INFO(getLogger(), "return to lane parking"); } @@ -549,9 +558,6 @@ void GoalPlannerModule::generateGoalCandidates() goal_searcher_->setPlannerData(planner_data_); goal_searcher_->setReferenceGoal(status_.get_refined_goal_pose()); thread_safe_data_.set_goal_candidates(goal_searcher_->search()); - const auto current_lanes = utils::getExtendedCurrentLanes( - planner_data_, parameters_->backward_goal_search_length, - parameters_->forward_goal_search_length, false); status_.set_closest_goal_candidate_pose( goal_searcher_->getClosetGoalCandidateAlongLanes(thread_safe_data_.get_goal_candidates()) .goal_pose); @@ -689,28 +695,25 @@ void GoalPlannerModule::selectSafePullOverPath() } } -void GoalPlannerModule::setLanes() +std::vector GoalPlannerModule::generateDrivableLanes() const { - const std::lock_guard lock(mutex_); - status_.set_current_lanes(utils::getExtendedCurrentLanes( + const lanelet::ConstLanelets current_lanes = utils::getExtendedCurrentLanes( planner_data_, parameters_->backward_goal_search_length, parameters_->forward_goal_search_length, - /*forward_only_in_route*/ false)); - status_.set_pull_over_lanes(goal_planner_utils::getPullOverLanes( + /*forward_only_in_route*/ false); + const lanelet::ConstLanelets pull_over_lanes = goal_planner_utils::getPullOverLanes( *(planner_data_->route_handler), left_side_parking_, parameters_->backward_goal_search_length, - parameters_->forward_goal_search_length)); - status_.set_lanes(utils::generateDrivableLanesWithShoulderLanes( - status_.get_current_lanes(), status_.get_pull_over_lanes())); + parameters_->forward_goal_search_length); + return utils::generateDrivableLanesWithShoulderLanes(current_lanes, pull_over_lanes); } -void GoalPlannerModule::setOutput(BehaviorModuleOutput & output) +void GoalPlannerModule::setOutput(BehaviorModuleOutput & output) const { if (!thread_safe_data_.foundPullOverPath()) { // situation : not safe against static objects use stop_path setStopPath(output); } else if ( - parameters_->safety_check_params.enable_safety_check && !isSafePath() && - status_.get_has_decided_path() && isActivated()) { + parameters_->safety_check_params.enable_safety_check && !isSafePath() && isActivated()) { // situation : not safe against dynamic objects after approval // insert stop point in current path if ego is able to stop with acceleration and jerk // constraints @@ -735,34 +738,22 @@ void GoalPlannerModule::setOutput(BehaviorModuleOutput & output) setModifiedGoal(output); // set hazard and turn signal - if (status_.get_has_decided_path()) { + if (hasDecidedPath()) { setTurnSignalInfo(output); } - - // for the next loop setOutput(). - // this is used to determine whether to generate a new stop path or keep the current stop path. - const std::lock_guard lock(mutex_); - status_.set_prev_found_path(thread_safe_data_.foundPullOverPath()); - status_.set_prev_is_safe_dynamic_objects( - parameters_->safety_check_params.enable_safety_check ? isSafePath() : true); } -void GoalPlannerModule::setStopPath(BehaviorModuleOutput & output) +void GoalPlannerModule::setStopPath(BehaviorModuleOutput & output) const { if (status_.get_prev_found_path() || !status_.get_prev_stop_path()) { // safe -> not_safe or no prev_stop_path: generate new stop_path output.path = std::make_shared(generateStopPath()); - const std::lock_guard lock(mutex_); - status_.set_prev_stop_path(output.path); - // set stop path as pull over path - auto stop_pull_over_path = std::make_shared(); - stop_pull_over_path->partial_paths.push_back(*output.path); - thread_safe_data_.set_pull_over_path(stop_pull_over_path); RCLCPP_WARN_THROTTLE( getLogger(), *clock_, 5000, "Not found safe pull_over path, generate stop path"); } else { // not_safe -> not_safe: use previous stop path output.path = status_.get_prev_stop_path(); + // stop_pose_ is removed in manager every loop, so need to set every loop. stop_pose_ = utils::getFirstStopPoseFromPath(*output.path); RCLCPP_WARN_THROTTLE( getLogger(), *clock_, 5000, "Not found safe pull_over path, use previous stop path"); @@ -770,10 +761,10 @@ void GoalPlannerModule::setStopPath(BehaviorModuleOutput & output) output.reference_path = getPreviousModuleOutput().reference_path; } -void GoalPlannerModule::setStopPathFromCurrentPath(BehaviorModuleOutput & output) +void GoalPlannerModule::setStopPathFromCurrentPath(BehaviorModuleOutput & output) const { // safe or not safe(no feasible stop_path found) -> not_safe: try to find new feasible stop_path - if (status_.get_prev_is_safe_dynamic_objects() || !status_.get_prev_stop_path_after_approval()) { + if (status_.get_prev_is_safe() || !status_.get_prev_stop_path_after_approval()) { auto current_path = thread_safe_data_.get_pull_over_path()->getCurrentPath(); const auto stop_path = behavior_path_planner::utils::start_goal_planner_common::generateFeasibleStopPath( @@ -781,7 +772,7 @@ void GoalPlannerModule::setStopPathFromCurrentPath(BehaviorModuleOutput & output parameters_->maximum_jerk_for_stop); if (stop_path) { output.path = std::make_shared(*stop_path); - status_.set_prev_stop_path_after_approval(output.path); + // status_.set_prev_stop_path_after_approval(output.path); RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 5000, "Collision detected, generate stop path"); } else { output.path = @@ -794,6 +785,7 @@ void GoalPlannerModule::setStopPathFromCurrentPath(BehaviorModuleOutput & output } else { // not_safe safe(no feasible stop path found) -> not_safe: use previous stop path output.path = status_.get_prev_stop_path_after_approval(); + // stop_pose_ is removed in manager every loop, so need to set every loop. stop_pose_ = utils::getFirstStopPoseFromPath(*output.path); RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 5000, "Collision detected, use previous stop path"); } @@ -808,7 +800,7 @@ void GoalPlannerModule::setDrivableAreaInfo(BehaviorModuleOutput & output) const planner_data_->parameters.vehicle_width / 2.0 + drivable_area_margin; } else { const auto target_drivable_lanes = utils::getNonOverlappingExpandedLanes( - *output.path, status_.get_lanes(), planner_data_->drivable_area_expansion_parameters); + *output.path, generateDrivableLanes(), planner_data_->drivable_area_expansion_parameters); DrivableAreaInfo current_drivable_area_info; current_drivable_area_info.drivable_lanes = target_drivable_lanes; @@ -860,13 +852,10 @@ void GoalPlannerModule::updateSteeringFactor( pose, distance, SteeringFactor::GOAL_PLANNER, steering_factor_direction, type, ""); } +// NOTE: Once this function returns true, it will continue to return true thereafter. Because +// selectSafePullOverPath() will not select new path. bool GoalPlannerModule::hasDecidedPath() const { - // once decided, keep the decision - if (status_.get_has_decided_path()) { - return true; - } - // if path is not safe, not decided if (!thread_safe_data_.foundPullOverPath()) { return false; @@ -874,18 +863,15 @@ bool GoalPlannerModule::hasDecidedPath() const // if ego is sufficiently close to the start of the nearest candidate path, the path is decided const auto & current_pose = planner_data_->self_odometry->pose.pose; - const auto ego_segment_idx = motion_utils::findNearestSegmentIndex( - thread_safe_data_.get_pull_over_path()->getCurrentPath().points, current_pose, - std::numeric_limits::max(), M_PI_2); - if (!ego_segment_idx) { - return false; - } + const size_t ego_segment_idx = motion_utils::findNearestSegmentIndex( + thread_safe_data_.get_pull_over_path()->getCurrentPath().points, current_pose.position); + const size_t start_pose_segment_idx = motion_utils::findNearestSegmentIndex( thread_safe_data_.get_pull_over_path()->getCurrentPath().points, thread_safe_data_.get_pull_over_path()->start_pose.position); const double dist_to_parking_start_pose = calcSignedArcLength( thread_safe_data_.get_pull_over_path()->getCurrentPath().points, current_pose.position, - *ego_segment_idx, thread_safe_data_.get_pull_over_path()->start_pose.position, + ego_segment_idx, thread_safe_data_.get_pull_over_path()->start_pose.position, start_pose_segment_idx); return dist_to_parking_start_pose < parameters_->decide_path_distance; } @@ -894,16 +880,12 @@ void GoalPlannerModule::decideVelocity() { const double current_vel = planner_data_->self_odometry->twist.twist.linear.x; - // decide velocity to guarantee turn signal lighting time - if (!status_.get_has_decided_velocity()) { - auto & first_path = thread_safe_data_.get_pull_over_path()->partial_paths.front(); - const auto vel = - static_cast(std::max(current_vel, parameters_->pull_over_minimum_velocity)); - for (auto & p : first_path.points) { - p.point.longitudinal_velocity_mps = std::min(p.point.longitudinal_velocity_mps, vel); - } + auto & first_path = thread_safe_data_.get_pull_over_path()->partial_paths.front(); + const auto vel = + static_cast(std::max(current_vel, parameters_->pull_over_minimum_velocity)); + for (auto & p : first_path.points) { + p.point.longitudinal_velocity_mps = std::min(p.point.longitudinal_velocity_mps, vel); } - status_.set_has_decided_velocity(true); } CandidateOutput GoalPlannerModule::planCandidate() const @@ -920,31 +902,15 @@ BehaviorModuleOutput GoalPlannerModule::planWithGoalModification() return getPreviousModuleOutput(); } - constexpr double path_update_duration = 1.0; - resetPathCandidate(); resetPathReference(); - // Check if it needs to decide path - status_.set_has_decided_path(hasDecidedPath()); - - // Use decided path - if (status_.get_has_decided_path()) { - if (isActivated() && !last_approval_data_) { - last_approval_data_ = - std::make_unique(clock_->now(), planner_data_->self_odometry->pose.pose); - decideVelocity(); - } - transitionToNextPathIfFinishingCurrentPath(); - } else if ( - !thread_safe_data_.get_pull_over_path_candidates().empty() && - needPathUpdate(path_update_duration)) { + if (!hasDecidedPath() && needPathUpdate(1.0 /*path_update_duration*/)) { // if the final path is not decided and enough time has passed since last path update, // select safe path from lane parking pull over path candidates // and set it to thread_safe_data_.get_pull_over_path() selectSafePullOverPath(); } - // else: stop path is generated and set by setOutput() // set output and status BehaviorModuleOutput output{}; @@ -969,7 +935,7 @@ BehaviorModuleOutput GoalPlannerModule::planWithGoalModification() } const auto distance_to_path_change = calcDistanceToPathChange(); - if (status_.get_has_decided_path()) { + if (hasDecidedPath()) { updateRTCStatus(distance_to_path_change.first, distance_to_path_change.second); } // TODO(tkhmy) add handle status TRYING @@ -980,9 +946,41 @@ BehaviorModuleOutput GoalPlannerModule::planWithGoalModification() setStopReason(StopReason::GOAL_PLANNER, thread_safe_data_.get_pull_over_path()->getFullPath()); + updateStatus(output); + return output; } +void GoalPlannerModule::updateStatus(const BehaviorModuleOutput & output) +{ + if (status_.get_prev_found_path() || !status_.get_prev_stop_path()) { + status_.set_prev_stop_path(output.path); + } + + // for the next loop setOutput(). + // this is used to determine whether to generate a new stop path or keep the current stop path. + status_.set_prev_found_path(thread_safe_data_.foundPullOverPath()); + status_.set_prev_is_safe( + parameters_->safety_check_params.enable_safety_check ? isSafePath() : true); + + if (!isActivated()) { + return; + } + + if ( + !parameters_->safety_check_params.enable_safety_check || isSafePath() || + (!status_.get_prev_is_safe() && status_.get_prev_stop_path_after_approval())) { + return; + } + status_.set_prev_is_safe(false); + const bool is_stop_path = std::any_of( + output.path->points.begin(), output.path->points.end(), + [](const auto & point) { return point.point.longitudinal_velocity_mps == 0.0; }); + if (is_stop_path) { + status_.set_prev_stop_path_after_approval(output.path); + } +} + BehaviorModuleOutput GoalPlannerModule::planWaitingApproval() { resetPathCandidate(); @@ -1019,7 +1017,7 @@ BehaviorModuleOutput GoalPlannerModule::planWaitingApprovalWithGoalModification( planner_data_->parameters.vehicle_width / 2.0 + drivable_area_margin; } else { const auto target_drivable_lanes = utils::getNonOverlappingExpandedLanes( - *out.path, status_.get_lanes(), planner_data_->drivable_area_expansion_parameters); + *out.path, generateDrivableLanes(), planner_data_->drivable_area_expansion_parameters); DrivableAreaInfo current_drivable_area_info; current_drivable_area_info.drivable_lanes = target_drivable_lanes; @@ -1032,7 +1030,7 @@ BehaviorModuleOutput GoalPlannerModule::planWaitingApprovalWithGoalModification( } const auto distance_to_path_change = calcDistanceToPathChange(); - if (status_.get_has_decided_path()) { + if (hasDecidedPath()) { updateRTCStatus(distance_to_path_change.first, distance_to_path_change.second); } updateSteeringFactor( @@ -1079,7 +1077,7 @@ void GoalPlannerModule::setParameters(const std::shared_ptrroute_handler; const auto & current_pose = planner_data_->self_odometry->pose.pose; @@ -1087,17 +1085,19 @@ PathWithLaneId GoalPlannerModule::generateStopPath() const double current_vel = planner_data_->self_odometry->twist.twist.linear.x; const double pull_over_velocity = parameters_->pull_over_velocity; - if (status_.get_current_lanes().empty()) { + const auto current_lanes = utils::getExtendedCurrentLanes( + planner_data_, common_parameters.backward_path_length, std::numeric_limits::max(), + /*forward_only_in_route*/ true); + + if (current_lanes.empty()) { return PathWithLaneId{}; } // generate reference path - const auto s_current = - lanelet::utils::getArcCoordinates(status_.get_current_lanes(), current_pose).length; + const auto s_current = lanelet::utils::getArcCoordinates(current_lanes, current_pose).length; const double s_start = std::max(0.0, s_current - common_parameters.backward_path_length); const double s_end = s_current + common_parameters.forward_path_length; - auto reference_path = - route_handler->getCenterLinePath(status_.get_current_lanes(), s_start, s_end, true); + auto reference_path = route_handler->getCenterLinePath(current_lanes, s_start, s_end, true); // if not approved stop road lane. // stop point priority is @@ -1162,19 +1162,20 @@ PathWithLaneId GoalPlannerModule::generateStopPath() return reference_path; } -PathWithLaneId GoalPlannerModule::generateFeasibleStopPath() +PathWithLaneId GoalPlannerModule::generateFeasibleStopPath() const { const auto & route_handler = planner_data_->route_handler; const auto & current_pose = planner_data_->self_odometry->pose.pose; const auto & common_parameters = planner_data_->parameters; // generate stop reference path - const auto s_current = - lanelet::utils::getArcCoordinates(status_.get_current_lanes(), current_pose).length; + const auto current_lanes = utils::getExtendedCurrentLanes( + planner_data_, common_parameters.backward_path_length, std::numeric_limits::max(), + /*forward_only_in_route*/ true); + const auto s_current = lanelet::utils::getArcCoordinates(current_lanes, current_pose).length; const double s_start = std::max(0.0, s_current - common_parameters.backward_path_length); const double s_end = s_current + common_parameters.forward_path_length; - auto stop_path = - route_handler->getCenterLinePath(status_.get_current_lanes(), s_start, s_end, true); + auto stop_path = route_handler->getCenterLinePath(current_lanes, s_start, s_end, true); // calc minimum stop distance under maximum deceleration const auto min_stop_distance = calcFeasibleDecelDistance( @@ -1193,40 +1194,6 @@ PathWithLaneId GoalPlannerModule::generateFeasibleStopPath() return stop_path; } -void GoalPlannerModule::transitionToNextPathIfFinishingCurrentPath() -{ - if (!isActivated() || !last_approval_data_) { - return; - } - - // if using arc_path and finishing current_path, get next path - // enough time for turn signal - const bool has_passed_enough_time_from_approval = - (clock_->now() - last_approval_data_->time).seconds() > - planner_data_->parameters.turn_signal_search_time; - if (!has_passed_enough_time_from_approval) { - return; - } - - // require increment only when the time passed is enough - // to prevent increment before driving - // when the end of the current path is close to the current pose - // this value should be `keep_stop_time` in keepStoppedWithCurrentPath - constexpr double keep_current_idx_time = 4.0; - const bool has_passed_enough_time_from_increment = - (clock_->now() - *thread_safe_data_.get_last_path_update_time()).seconds() > - keep_current_idx_time; - if (!has_passed_enough_time_from_increment) { - return; - } - - if (!hasFinishedCurrentPath()) { - return; - } - - thread_safe_data_.incrementPathIndex(); -} - bool GoalPlannerModule::isStopped( std::deque & odometry_buffer, const double time) { @@ -1285,13 +1252,41 @@ bool GoalPlannerModule::isStuck() bool GoalPlannerModule::hasFinishedCurrentPath() { + if (!last_approval_data_) { + return false; + } + + if (!isStopped()) { + return false; + } + + // check if enough time has passed since last approval + // this is necessary to give turn signal for enough time + const bool has_passed_enough_time_from_approval = + (clock_->now() - last_approval_data_->time).seconds() > + planner_data_->parameters.turn_signal_search_time; + if (!has_passed_enough_time_from_approval) { + return false; + } + + // require increment only when the time passed is enough + // to prevent increment before driving + // when the end of the current path is close to the current pose + // this value should be `keep_stop_time` in keepStoppedWithCurrentPath + constexpr double keep_current_idx_time = 4.0; + const bool has_passed_enough_time_from_increment = + (clock_->now() - *thread_safe_data_.get_last_path_update_time()).seconds() > + keep_current_idx_time; + if (!has_passed_enough_time_from_increment) { + return false; + } + + // check if self pose is near the end of current path const auto current_path_end = thread_safe_data_.get_pull_over_path()->getCurrentPath().points.back(); const auto & self_pose = planner_data_->self_odometry->pose.pose; - const bool is_near_target = tier4_autoware_utils::calcDistance2d(current_path_end, self_pose) < - parameters_->th_arrived_distance; - - return is_near_target && isStopped(); + return tier4_autoware_utils::calcDistance2d(current_path_end, self_pose) < + parameters_->th_arrived_distance; } bool GoalPlannerModule::isOnModifiedGoal() const @@ -1334,9 +1329,8 @@ TurnSignalInfo GoalPlannerModule::calcTurnSignalInfo() const { // ego decelerates so that current pose is the point `turn_light_on_threshold_time` seconds // before starting pull_over - turn_signal.desired_start_point = last_approval_data_ && status_.get_has_decided_path() - ? last_approval_data_->pose - : current_pose; + turn_signal.desired_start_point = + last_approval_data_ && hasDecidedPath() ? last_approval_data_->pose : current_pose; turn_signal.desired_end_point = end_pose; turn_signal.required_start_point = start_pose; turn_signal.required_end_point = end_pose; @@ -1440,7 +1434,7 @@ bool GoalPlannerModule::hasEnoughDistance(const PullOverPath & pull_over_path) c return true; } -void GoalPlannerModule::keepStoppedWithCurrentPath(PathWithLaneId & path) +void GoalPlannerModule::keepStoppedWithCurrentPath(PathWithLaneId & path) const { constexpr double keep_stop_time = 2.0; if (!thread_safe_data_.get_last_path_idx_increment_time()) { @@ -1619,7 +1613,7 @@ bool GoalPlannerModule::isCrossingPossible( bool GoalPlannerModule::isCrossingPossible(const PullOverPath & pull_over_path) const { - const lanelet::ConstLanelets lanes = utils::transformToLanelets(status_.get_lanes()); + const lanelet::ConstLanelets lanes = utils::transformToLanelets(generateDrivableLanes()); const Pose & start_pose = pull_over_path.start_pose; const Pose & end_pose = pull_over_path.end_pose; @@ -1655,11 +1649,10 @@ bool GoalPlannerModule::isSafePath() const const std::pair terminal_velocity_and_accel = utils::start_goal_planner_common::getPairsTerminalVelocityAndAccel( thread_safe_data_.get_pull_over_path()->pairs_terminal_velocity_and_accel, - status_.get_current_path_idx()); + thread_safe_data_.get_pull_over_path()->path_idx); RCLCPP_DEBUG( getLogger(), "pairs_terminal_velocity_and_accel for goal_planner: %f, %f", terminal_velocity_and_accel.first, terminal_velocity_and_accel.second); - RCLCPP_DEBUG(getLogger(), "current_path_idx %ld", status_.get_current_path_idx()); utils::start_goal_planner_common::updatePathProperty( ego_predicted_path_params_, terminal_velocity_and_accel); // TODO(Sugahara): shoule judge is_object_front properly @@ -1680,7 +1673,7 @@ bool GoalPlannerModule::isSafePath() const pull_over_lanes, route_handler, filtered_objects, objects_filtering_params_); const double hysteresis_factor = - status_.get_prev_is_safe_dynamic_objects() ? 1.0 : parameters_->hysteresis_factor_expand_rate; + status_.get_prev_is_safe() ? 1.0 : parameters_->hysteresis_factor_expand_rate; utils::start_goal_planner_common::updateSafetyCheckTargetObjectsData( goal_planner_data_, filtered_objects, target_objects_on_lane, ego_predicted_path); @@ -1742,9 +1735,8 @@ void GoalPlannerModule::setDebugData() }; if (goal_planner_utils::isAllowedGoalModification(planner_data_->route_handler)) { // Visualize pull over areas - const auto color = status_.get_has_decided_path() - ? createMarkerColor(1.0, 1.0, 0.0, 0.999) // yellow - : createMarkerColor(0.0, 1.0, 0.0, 0.999); // green + const auto color = hasDecidedPath() ? createMarkerColor(1.0, 1.0, 0.0, 0.999) // yellow + : createMarkerColor(0.0, 1.0, 0.0, 0.999); // green const double z = status_.get_refined_goal_pose().position.z; add(goal_planner_utils::createPullOverAreaMarkerArray( goal_searcher_->getAreaPolygons(), header, color, z)); @@ -1834,7 +1826,7 @@ void GoalPlannerModule::setDebugData() marker.text = magic_enum::enum_name(thread_safe_data_.getPullOverPlannerType()); if (thread_safe_data_.foundPullOverPath()) { marker.text += - " " + std::to_string(status_.get_current_path_idx()) + "/" + + " " + std::to_string(thread_safe_data_.get_pull_over_path()->path_idx) + "/" + std::to_string(thread_safe_data_.get_pull_over_path()->partial_paths.size() - 1); } From b902450f8ded636fb0621e5fee5db426940180bf Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Tue, 14 Nov 2023 15:47:59 +0900 Subject: [PATCH 184/202] fix(simple_planning_simulator): change default value of manual gear, DRIVE -> PARK (#5563) --- .../simple_planning_simulator_core.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp index 07a5d34f63c39..a3715a1efe8ab 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp @@ -210,7 +210,7 @@ SimplePlanningSimulator::SimplePlanningSimulator(const rclcpp::NodeOptions & opt // control mode current_control_mode_.mode = ControlModeReport::AUTONOMOUS; - current_manual_gear_cmd_.command = GearCommand::DRIVE; + current_manual_gear_cmd_.command = GearCommand::PARK; } void SimplePlanningSimulator::initialize_vehicle_model() From dc5d76afeaf4c513458877af46ef7673034ddbd4 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Tue, 14 Nov 2023 16:33:19 +0900 Subject: [PATCH 185/202] fix(lane_change): fix object debug marker not having point (#5577) Signed-off-by: Zulfaqar Azmi --- planning/behavior_path_planner/src/marker_utils/utils.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/planning/behavior_path_planner/src/marker_utils/utils.cpp b/planning/behavior_path_planner/src/marker_utils/utils.cpp index 031926f2d9d1d..f1f681fed06a0 100644 --- a/planning/behavior_path_planner/src/marker_utils/utils.cpp +++ b/planning/behavior_path_planner/src/marker_utils/utils.cpp @@ -18,6 +18,7 @@ #include "behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include "behavior_path_planner/utils/path_utils.hpp" +#include #include #include @@ -45,6 +46,7 @@ CollisionCheckDebugPair createObjectDebug(const ExtendedPredictedObject & obj) { CollisionCheckDebug debug; debug.current_obj_pose = obj.initial_pose.pose; + debug.extended_obj_polygon = tier4_autoware_utils::toPolygon2d(obj.initial_pose.pose, obj.shape); debug.current_twist = obj.initial_twist.twist; return {tier4_autoware_utils::toHexString(obj.uuid), debug}; } From d4d08045e438f09d4f2fe3e2ac789417cb39ebe3 Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Tue, 14 Nov 2023 16:35:04 +0900 Subject: [PATCH 186/202] fix(avoidance): fix a bug regarding the nearest search (#5575) * fix a bug regarding nearest search --------- Signed-off-by: Yuki Takagi --- .../src/scene_module/avoidance/avoidance_module.cpp | 9 ++++++--- 1 file changed, 6 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 2ad0928696a5c..2d85f8cbe3224 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 @@ -2025,13 +2025,16 @@ PathWithLaneId AvoidanceModule::extendBackwardLength(const PathWithLaneId & orig planner_data_->parameters.backward_path_length, longest_dist_to_shift_point + extra_margin); const size_t orig_ego_idx = planner_data_->findEgoIndex(original_path.points); - const size_t prev_ego_idx = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + const auto prev_ego_idx = motion_utils::findNearestSegmentIndex( previous_path.points, getPose(original_path.points.at(orig_ego_idx)), std::numeric_limits::max(), planner_data_->parameters.ego_nearest_yaw_threshold); + if (!prev_ego_idx) { + return original_path; + } size_t clip_idx = 0; for (size_t i = 0; i < prev_ego_idx; ++i) { - if (backward_length > calcSignedArcLength(previous_path.points, clip_idx, prev_ego_idx)) { + if (backward_length > calcSignedArcLength(previous_path.points, clip_idx, *prev_ego_idx)) { break; } clip_idx = i; @@ -2041,7 +2044,7 @@ PathWithLaneId AvoidanceModule::extendBackwardLength(const PathWithLaneId & orig { extended_path.points.insert( extended_path.points.end(), previous_path.points.begin() + clip_idx, - previous_path.points.begin() + prev_ego_idx); + previous_path.points.begin() + *prev_ego_idx); } // overwrite backward path velocity by latest one. From b52d323cb7c71b479403117c8d20d44863770508 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 14 Nov 2023 18:48:25 +0900 Subject: [PATCH 187/202] refactor(goal_planner): refactoring plan flow and add post process (#5554) * refactor(goal_planner): refactoring plan flow and add post process Signed-off-by: kosuke55 do not decel when searching Signed-off-by: kosuke55 rename planPullOver Signed-off-by: kosuke55 * add plan flow Signed-off-by: kosuke55 * add reason of early return Signed-off-by: kosuke55 * typo Signed-off-by: kosuke55 * fix path_candidate_ Signed-off-by: kosuke55 * pub path candidate after approval Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 --- .../goal_planner/goal_planner_module.hpp | 31 +- .../goal_planner/goal_planner_module.cpp | 273 ++++++++---------- 2 files changed, 154 insertions(+), 150 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp index 5149979ef082d..2e95ca82735fb 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp @@ -287,27 +287,47 @@ class GoalPlannerModule : public SceneModuleInterface } } - CandidateOutput planCandidate() const override; BehaviorModuleOutput plan() override; BehaviorModuleOutput planWaitingApproval() override; bool isExecutionRequested() const override; bool isExecutionReady() const override; void processOnExit() override; void updateData() override; + void postProcess() override; void setParameters(const std::shared_ptr & parameters); void acceptVisitor( [[maybe_unused]] const std::shared_ptr & visitor) const override { } + CandidateOutput planCandidate() const override { return CandidateOutput{}; } private: + /*  + * state transitions and plan function used in each state + * + * +--------------------------+ + * | RUNNING | + * | planPullOverAsCandidate()| + * +------------+-------------+ + * | hasDecidedPath() + * 2 v + * +--------------------------+ + * | WAITING_APPROVAL | + * | planPullOverAsCandidate()| + * +------------+-------------+ + * | isActivated() + * 3 v + * +--------------------------+ + * | RUNNING | + * | planPullOverAsOutput() | + * +--------------------------+ + */ + // The start_planner activates when it receives a new route, // so there is no need to terminate the goal planner. // If terminating it, it may switch to lane following and could generate an inappropriate path. bool canTransitSuccessState() override { return false; } - bool canTransitFailureState() override { return false; } - bool canTransitIdleToRunningState() override { return true; } mutable StartGoalPlannerData goal_planner_data_; @@ -411,8 +431,9 @@ class GoalPlannerModule : public SceneModuleInterface void returnToLaneParking(); // plan pull over path - BehaviorModuleOutput planWithGoalModification(); - BehaviorModuleOutput planWaitingApprovalWithGoalModification(); + BehaviorModuleOutput planPullOver(); + BehaviorModuleOutput planPullOverAsOutput(); + BehaviorModuleOutput planPullOverAsCandidate(); void selectSafePullOverPath(); std::vector sortPullOverPathCandidatesByGoalPriority( const std::vector & pull_over_path_candidates, diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index 202c19f1bf1db..84b4032cde4ad 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -253,10 +253,17 @@ void GoalPlannerModule::updateData() initializeOccupancyGridMap(); } + resetPathCandidate(); + resetPathReference(); + path_reference_ = getPreviousModuleOutput().reference_path; + updateOccupancyGrid(); generateGoalCandidates(); + // Only after the path is decided, approval is allowed and the module is Activated. + // The path index is not incremented until after deciding the path. + // So return here, if (!isActivated()) { return; } @@ -541,16 +548,12 @@ void GoalPlannerModule::returnToLaneParking() void GoalPlannerModule::generateGoalCandidates() { - const auto & route_handler = planner_data_->route_handler; - - // with old architecture, module instance is not cleared when new route is received - // so need to reset status here. - // todo: move this check out of this function after old architecture is removed if (!thread_safe_data_.get_goal_candidates().empty()) { return; } // calculate goal candidates + const auto & route_handler = planner_data_->route_handler; const Pose goal_pose = route_handler->getOriginalGoalPose(); status_.set_refined_goal_pose(calcRefinedGoal(goal_pose)); if (goal_planner_utils::isAllowedGoalModification(route_handler)) { @@ -574,17 +577,12 @@ void GoalPlannerModule::generateGoalCandidates() BehaviorModuleOutput GoalPlannerModule::plan() { - resetPathCandidate(); - resetPathReference(); - - path_reference_ = getPreviousModuleOutput().reference_path; - if (goal_planner_utils::isAllowedGoalModification(planner_data_->route_handler)) { - return planWithGoalModification(); - } else { - fixed_goal_planner_->setPreviousModuleOutput(getPreviousModuleOutput()); - return fixed_goal_planner_->plan(planner_data_); + return planPullOver(); } + + fixed_goal_planner_->setPreviousModuleOutput(getPreviousModuleOutput()); + return fixed_goal_planner_->plan(planner_data_); } std::vector GoalPlannerModule::sortPullOverPathCandidatesByGoalPriority( @@ -671,27 +669,26 @@ void GoalPlannerModule::selectSafePullOverPath() } // decelerate before the search area start - const auto search_start_offset_pose = calcLongitudinalOffsetPose( + const auto decel_pose = calcLongitudinalOffsetPose( thread_safe_data_.get_pull_over_path()->getFullPath().points, - status_.get_refined_goal_pose().position, - -parameters_->backward_goal_search_length - planner_data_->parameters.base_link2front - - approximate_pull_over_distance_); + status_.get_closest_goal_candidate_pose().position, -approximate_pull_over_distance_); auto & first_path = thread_safe_data_.get_pull_over_path()->partial_paths.front(); - if (search_start_offset_pose) { - decelerateBeforeSearchStart(*search_start_offset_pose, first_path); - } else { - // if already passed the search start offset pose, set pull_over_velocity to first_path. - const auto min_decel_distance = calcFeasibleDecelDistance( - planner_data_, parameters_->maximum_deceleration, parameters_->maximum_jerk, - parameters_->pull_over_velocity); - for (auto & p : first_path.points) { - const double distance_from_ego = calcSignedArcLengthFromEgo(first_path, p.point.pose); - if (min_decel_distance && distance_from_ego < *min_decel_distance) { - continue; - } - p.point.longitudinal_velocity_mps = std::min( - p.point.longitudinal_velocity_mps, static_cast(parameters_->pull_over_velocity)); + if (decel_pose) { + decelerateBeforeSearchStart(*decel_pose, first_path); + return; + } + + // if already passed the search start offset pose, set pull_over_velocity to first_path. + const auto min_decel_distance = calcFeasibleDecelDistance( + planner_data_, parameters_->maximum_deceleration, parameters_->maximum_jerk, + parameters_->pull_over_velocity); + for (auto & p : first_path.points) { + const double distance_from_ego = calcSignedArcLengthFromEgo(first_path, p.point.pose); + if (min_decel_distance && distance_from_ego < *min_decel_distance) { + continue; } + p.point.longitudinal_velocity_mps = std::min( + p.point.longitudinal_velocity_mps, static_cast(parameters_->pull_over_velocity)); } } @@ -709,11 +706,16 @@ std::vector GoalPlannerModule::generateDrivableLanes() const void GoalPlannerModule::setOutput(BehaviorModuleOutput & output) const { + output.reference_path = getPreviousModuleOutput().reference_path; + if (!thread_safe_data_.foundPullOverPath()) { // situation : not safe against static objects use stop_path setStopPath(output); - } else if ( - parameters_->safety_check_params.enable_safety_check && !isSafePath() && isActivated()) { + setDrivableAreaInfo(output); + return; + } + + if (parameters_->safety_check_params.enable_safety_check && !isSafePath() && isActivated()) { // situation : not safe against dynamic objects after approval // insert stop point in current path if ego is able to stop with acceleration and jerk // constraints @@ -721,24 +723,18 @@ void GoalPlannerModule::setOutput(BehaviorModuleOutput & output) const } else { // situation : (safe against static and dynamic objects) or (safe against static objects and // before approval) don't stop - if (isActivated()) { - resetWallPoses(); - } // keep stop if not enough time passed, // because it takes time for the trajectory to be reflected auto current_path = thread_safe_data_.get_pull_over_path()->getCurrentPath(); keepStoppedWithCurrentPath(current_path); - output.path = std::make_shared(current_path); - output.reference_path = getPreviousModuleOutput().reference_path; } - setDrivableAreaInfo(output); - setModifiedGoal(output); + setDrivableAreaInfo(output); // set hazard and turn signal - if (hasDecidedPath()) { + if (hasDecidedPath() && isActivated()) { setTurnSignalInfo(output); } } @@ -758,7 +754,6 @@ void GoalPlannerModule::setStopPath(BehaviorModuleOutput & output) const RCLCPP_WARN_THROTTLE( getLogger(), *clock_, 5000, "Not found safe pull_over path, use previous stop path"); } - output.reference_path = getPreviousModuleOutput().reference_path; } void GoalPlannerModule::setStopPathFromCurrentPath(BehaviorModuleOutput & output) const @@ -789,7 +784,6 @@ void GoalPlannerModule::setStopPathFromCurrentPath(BehaviorModuleOutput & output stop_pose_ = utils::getFirstStopPoseFromPath(*output.path); RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 5000, "Collision detected, use previous stop path"); } - output.reference_path = getPreviousModuleOutput().reference_path; } void GoalPlannerModule::setDrivableAreaInfo(BehaviorModuleOutput & output) const @@ -888,22 +882,48 @@ void GoalPlannerModule::decideVelocity() } } -CandidateOutput GoalPlannerModule::planCandidate() const +BehaviorModuleOutput GoalPlannerModule::planPullOver() { - return CandidateOutput( - thread_safe_data_.get_pull_over_path() ? thread_safe_data_.get_pull_over_path()->getFullPath() - : PathWithLaneId()); + if (!hasDecidedPath()) { + return planPullOverAsCandidate(); + } + + return planPullOverAsOutput(); } -BehaviorModuleOutput GoalPlannerModule::planWithGoalModification() +BehaviorModuleOutput GoalPlannerModule::planPullOverAsCandidate() { // if pull over path candidates generation is not finished, use previous module output if (thread_safe_data_.get_pull_over_path_candidates().empty()) { return getPreviousModuleOutput(); } - resetPathCandidate(); - resetPathReference(); + BehaviorModuleOutput output{}; + const BehaviorModuleOutput pull_over_output = planPullOverAsOutput(); + output.modified_goal = pull_over_output.modified_goal; + output.path = std::make_shared(generateStopPath()); + + const auto target_drivable_lanes = utils::getNonOverlappingExpandedLanes( + *output.path, generateDrivableLanes(), planner_data_->drivable_area_expansion_parameters); + + DrivableAreaInfo current_drivable_area_info{}; + current_drivable_area_info.drivable_lanes = target_drivable_lanes; + output.drivable_area_info = utils::combineDrivableAreaInfo( + current_drivable_area_info, getPreviousModuleOutput().drivable_area_info); + + if (!thread_safe_data_.foundPullOverPath()) { + return output; + } + + return output; +} + +BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput() +{ + // if pull over path candidates generation is not finished, use previous module output + if (thread_safe_data_.get_pull_over_path_candidates().empty()) { + return getPreviousModuleOutput(); + } if (!hasDecidedPath() && needPathUpdate(1.0 /*path_update_duration*/)) { // if the final path is not decided and enough time has passed since last path update, @@ -915,8 +935,6 @@ BehaviorModuleOutput GoalPlannerModule::planWithGoalModification() // set output and status BehaviorModuleOutput output{}; setOutput(output); - path_candidate_ = std::make_shared(planCandidate().path_candidate); - path_reference_ = getPreviousModuleOutput().reference_path; // return to lane parking if it is possible if (thread_safe_data_.getPullOverPlannerType() == PullOverPlannerType::FREESPACE) { @@ -934,21 +952,34 @@ BehaviorModuleOutput GoalPlannerModule::planWithGoalModification() return output; } + path_candidate_ = + std::make_shared(thread_safe_data_.get_pull_over_path()->getFullPath()); + + updateStatus(output); + + return output; +} + +void GoalPlannerModule::postProcess() +{ + if (!thread_safe_data_.foundPullOverPath()) { + return; + } + + const bool has_decided_path = hasDecidedPath(); const auto distance_to_path_change = calcDistanceToPathChange(); - if (hasDecidedPath()) { + + if (has_decided_path) { updateRTCStatus(distance_to_path_change.first, distance_to_path_change.second); } - // TODO(tkhmy) add handle status TRYING + updateSteeringFactor( {thread_safe_data_.get_pull_over_path()->start_pose, thread_safe_data_.get_modified_goal_pose()->goal_pose}, - {distance_to_path_change.first, distance_to_path_change.second}, SteeringFactor::TURNING); + {distance_to_path_change.first, distance_to_path_change.second}, + has_decided_path ? SteeringFactor::TURNING : SteeringFactor::APPROACHING); setStopReason(StopReason::GOAL_PLANNER, thread_safe_data_.get_pull_over_path()->getFullPath()); - - updateStatus(output); - - return output; } void GoalPlannerModule::updateStatus(const BehaviorModuleOutput & output) @@ -983,64 +1014,12 @@ void GoalPlannerModule::updateStatus(const BehaviorModuleOutput & output) BehaviorModuleOutput GoalPlannerModule::planWaitingApproval() { - resetPathCandidate(); - resetPathReference(); - - path_reference_ = getPreviousModuleOutput().reference_path; - if (goal_planner_utils::isAllowedGoalModification(planner_data_->route_handler)) { - return planWaitingApprovalWithGoalModification(); - } else { - fixed_goal_planner_->setPreviousModuleOutput(getPreviousModuleOutput()); - return fixed_goal_planner_->plan(planner_data_); - } -} - -BehaviorModuleOutput GoalPlannerModule::planWaitingApprovalWithGoalModification() -{ - // if pull over path candidates generation is not finished, use previous module output - if (thread_safe_data_.get_pull_over_path_candidates().empty()) { - return getPreviousModuleOutput(); - } - - BehaviorModuleOutput out; - out.modified_goal = planWithGoalModification().modified_goal; // update status_ - out.path = std::make_shared(generateStopPath()); - out.reference_path = getPreviousModuleOutput().reference_path; - path_candidate_ = std::make_shared(planCandidate().path_candidate); - path_reference_ = getPreviousModuleOutput().reference_path; - - // generate drivable area info for new architecture - if (thread_safe_data_.getPullOverPlannerType() == PullOverPlannerType::FREESPACE) { - const double drivable_area_margin = planner_data_->parameters.vehicle_width; - out.drivable_area_info.drivable_margin = - planner_data_->parameters.vehicle_width / 2.0 + drivable_area_margin; - } else { - const auto target_drivable_lanes = utils::getNonOverlappingExpandedLanes( - *out.path, generateDrivableLanes(), planner_data_->drivable_area_expansion_parameters); - - DrivableAreaInfo current_drivable_area_info; - current_drivable_area_info.drivable_lanes = target_drivable_lanes; - out.drivable_area_info = utils::combineDrivableAreaInfo( - current_drivable_area_info, getPreviousModuleOutput().drivable_area_info); - } - - if (!thread_safe_data_.foundPullOverPath()) { - return out; + return planPullOverAsCandidate(); } - const auto distance_to_path_change = calcDistanceToPathChange(); - if (hasDecidedPath()) { - updateRTCStatus(distance_to_path_change.first, distance_to_path_change.second); - } - updateSteeringFactor( - {thread_safe_data_.get_pull_over_path()->start_pose, - thread_safe_data_.get_modified_goal_pose()->goal_pose}, - {distance_to_path_change.first, distance_to_path_change.second}, SteeringFactor::APPROACHING); - - setStopReason(StopReason::GOAL_PLANNER, thread_safe_data_.get_pull_over_path()->getFullPath()); - - return out; + fixed_goal_planner_->setPreviousModuleOutput(getPreviousModuleOutput()); + return fixed_goal_planner_->plan(planner_data_); } std::pair GoalPlannerModule::calcDistanceToPathChange() const @@ -1099,6 +1078,13 @@ PathWithLaneId GoalPlannerModule::generateStopPath() const const double s_end = s_current + common_parameters.forward_path_length; auto reference_path = route_handler->getCenterLinePath(current_lanes, s_start, s_end, true); + // calculate search start offset pose from the closest goal candidate pose with + // approximate_pull_over_distance_ ego vehicle decelerates to this position. or if no feasible + // stop point is found, stop at this position. + const auto decel_pose = calcLongitudinalOffsetPose( + reference_path.points, status_.get_closest_goal_candidate_pose().position, + -approximate_pull_over_distance_); + // if not approved stop road lane. // stop point priority is // 1. actual start pose @@ -1107,27 +1093,24 @@ PathWithLaneId GoalPlannerModule::generateStopPath() const // (In the case of the curve lane, the position is not aligned due to the // difference between the outer and inner sides) // 4. feasible stop - const auto search_start_offset_pose = calcLongitudinalOffsetPose( - reference_path.points, status_.get_closest_goal_candidate_pose().position, - -approximate_pull_over_distance_); - if ( - !thread_safe_data_.foundPullOverPath() && !thread_safe_data_.get_closest_start_pose() && - !search_start_offset_pose) { - return generateFeasibleStopPath(); - } - - const Pose stop_pose = [&]() -> Pose { + const auto stop_pose = std::invoke([&]() -> boost::optional { if (thread_safe_data_.foundPullOverPath()) { return thread_safe_data_.get_pull_over_path()->start_pose; } if (thread_safe_data_.get_closest_start_pose()) { return thread_safe_data_.get_closest_start_pose().value(); } - return *search_start_offset_pose; - }(); + if (!decel_pose) { + return boost::optional{}; + } + return decel_pose.value(); + }); + if (!stop_pose) { + return generateFeasibleStopPath(); + } // if stop pose is closer than min_stop_distance, stop as soon as possible - const double ego_to_stop_distance = calcSignedArcLengthFromEgo(reference_path, stop_pose); + const double ego_to_stop_distance = calcSignedArcLengthFromEgo(reference_path, *stop_pose); const auto min_stop_distance = calcFeasibleDecelDistance( planner_data_, parameters_->maximum_deceleration, parameters_->maximum_jerk, 0.0); const double eps_vel = 0.01; @@ -1138,27 +1121,27 @@ PathWithLaneId GoalPlannerModule::generateStopPath() const } // slow down for turn signal, insert stop point to stop_pose - decelerateForTurnSignal(stop_pose, reference_path); - stop_pose_ = stop_pose; + decelerateForTurnSignal(*stop_pose, reference_path); + stop_pose_ = *stop_pose; // for debug wall marker // slow down before the search area. - if (search_start_offset_pose) { - decelerateBeforeSearchStart(*search_start_offset_pose, reference_path); - } else { - // if already passed the search start offset pose, set pull_over_velocity to reference_path. - const auto min_decel_distance = calcFeasibleDecelDistance( - planner_data_, parameters_->maximum_deceleration, parameters_->maximum_jerk, - pull_over_velocity); - for (auto & p : reference_path.points) { - const double distance_from_ego = calcSignedArcLengthFromEgo(reference_path, p.point.pose); - if (min_decel_distance && distance_from_ego < *min_decel_distance) { - continue; - } - p.point.longitudinal_velocity_mps = - std::min(p.point.longitudinal_velocity_mps, static_cast(pull_over_velocity)); - } + if (decel_pose) { + decelerateBeforeSearchStart(*decel_pose, reference_path); + return reference_path; } + // if already passed the decel pose, set pull_over_velocity to reference_path. + const auto min_decel_distance = calcFeasibleDecelDistance( + planner_data_, parameters_->maximum_deceleration, parameters_->maximum_jerk, + pull_over_velocity); + for (auto & p : reference_path.points) { + const double distance_from_ego = calcSignedArcLengthFromEgo(reference_path, p.point.pose); + if (min_decel_distance && distance_from_ego < *min_decel_distance) { + continue; + } + p.point.longitudinal_velocity_mps = + std::min(p.point.longitudinal_velocity_mps, static_cast(pull_over_velocity)); + } return reference_path; } From e943c22329a9ec78272a7b3fd5fd4da6c793d013 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Tue, 14 Nov 2023 14:36:47 +0300 Subject: [PATCH 188/202] ci(labeler): rename simulator to simulation (#5580) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .github/labeler.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/labeler.yaml b/.github/labeler.yaml index c3efa2a1a2b15..47f8737ebbf39 100644 --- a/.github/labeler.yaml +++ b/.github/labeler.yaml @@ -31,7 +31,7 @@ - planning/**/* "component:sensing": - sensing/**/* -"component:simulator": +"component:simulation": - simulator/**/* "component:system": - system/**/* From 846a1cd0bf26b4a4ca6f5b33f739e8d958b1161c Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 14 Nov 2023 21:37:23 +0900 Subject: [PATCH 189/202] feat(motion_velocity_smoother): add motion_velocity_smoother's virtual wall such as MRM (#5555) * feat: add motion_velocity_smoother's virtual wall Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../src/external_velocity_limit_selector_node.cpp | 1 + .../motion_velocity_smoother_node.hpp | 5 +++++ .../src/motion_velocity_smoother_node.cpp | 14 ++++++++++++++ 3 files changed, 20 insertions(+) diff --git a/planning/external_velocity_limit_selector/src/external_velocity_limit_selector_node.cpp b/planning/external_velocity_limit_selector/src/external_velocity_limit_selector_node.cpp index 2ba0a4c1d46f3..ccca5e97d2b38 100644 --- a/planning/external_velocity_limit_selector/src/external_velocity_limit_selector_node.cpp +++ b/planning/external_velocity_limit_selector/src/external_velocity_limit_selector_node.cpp @@ -46,6 +46,7 @@ VelocityLimit getHardestLimit( // find hardest max velocity if (max_velocity < hardest_max_velocity) { hardest_limit.stamp = limit.second.stamp; + hardest_limit.sender = limit.first; hardest_limit.max_velocity = max_velocity; hardest_max_velocity = max_velocity; } diff --git a/planning/motion_velocity_smoother/include/motion_velocity_smoother/motion_velocity_smoother_node.hpp b/planning/motion_velocity_smoother/include/motion_velocity_smoother/motion_velocity_smoother_node.hpp index 347d19f631588..7be91d67cb945 100644 --- a/planning/motion_velocity_smoother/include/motion_velocity_smoother/motion_velocity_smoother_node.hpp +++ b/planning/motion_velocity_smoother/include/motion_velocity_smoother/motion_velocity_smoother_node.hpp @@ -42,6 +42,7 @@ #include "tier4_debug_msgs/msg/float32_stamped.hpp" // temporary #include "tier4_planning_msgs/msg/stop_speed_exceeded.hpp" // temporary #include "tier4_planning_msgs/msg/velocity_limit.hpp" // temporary +#include "visualization_msgs/msg/marker_array.hpp" #include #include @@ -63,6 +64,7 @@ using nav_msgs::msg::Odometry; using tier4_debug_msgs::msg::Float32Stamped; // temporary using tier4_planning_msgs::msg::StopSpeedExceeded; // temporary using tier4_planning_msgs::msg::VelocityLimit; // temporary +using visualization_msgs::msg::MarkerArray; struct Motion { @@ -80,6 +82,7 @@ class MotionVelocitySmootherNode : public rclcpp::Node private: rclcpp::Publisher::SharedPtr pub_trajectory_; + rclcpp::Publisher::SharedPtr pub_virtual_wall_; rclcpp::Publisher::SharedPtr pub_over_stop_velocity_; rclcpp::Subscription::SharedPtr sub_current_odometry_; rclcpp::Subscription::SharedPtr sub_current_acceleration_; @@ -95,6 +98,7 @@ class MotionVelocitySmootherNode : public rclcpp::Node double max_velocity_with_deceleration_; // maximum velocity with deceleration // for external velocity limit double wheelbase_; // wheelbase + double base_link2front_; // base_link to front TrajectoryPoints prev_output_; // previously published trajectory @@ -153,6 +157,7 @@ class MotionVelocitySmootherNode : public rclcpp::Node { double velocity{0.0}; // current external_velocity_limit double dist{0.0}; // distance to set external velocity limit + std::string sender{""}; }; ExternalVelocityLimit external_velocity_limit_; // velocity and distance constraint of external velocity limit diff --git a/planning/motion_velocity_smoother/src/motion_velocity_smoother_node.cpp b/planning/motion_velocity_smoother/src/motion_velocity_smoother_node.cpp index 6b5da01b9cb09..a27e02c15710f 100644 --- a/planning/motion_velocity_smoother/src/motion_velocity_smoother_node.cpp +++ b/planning/motion_velocity_smoother/src/motion_velocity_smoother_node.cpp @@ -14,6 +14,7 @@ #include "motion_velocity_smoother/motion_velocity_smoother_node.hpp" +#include "motion_utils/marker/marker_helper.hpp" #include "motion_velocity_smoother/smoother/jerk_filtered_smoother.hpp" #include "motion_velocity_smoother/smoother/l2_pseudo_jerk_smoother.hpp" #include "motion_velocity_smoother/smoother/linf_pseudo_jerk_smoother.hpp" @@ -41,6 +42,7 @@ MotionVelocitySmootherNode::MotionVelocitySmootherNode(const rclcpp::NodeOptions // set common params const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo(); wheelbase_ = vehicle_info.wheel_base_m; + base_link2front_ = vehicle_info.max_longitudinal_offset_m; initCommonParam(); over_stop_velocity_warn_thr_ = declare_parameter("over_stop_velocity_warn_thr"); @@ -49,6 +51,7 @@ MotionVelocitySmootherNode::MotionVelocitySmootherNode(const rclcpp::NodeOptions // publishers, subscribers pub_trajectory_ = create_publisher("~/output/trajectory", 1); + pub_virtual_wall_ = create_publisher("~/virtual_wall", 1); pub_velocity_limit_ = create_publisher( "~/output/current_velocity_limit_mps", rclcpp::QoS{1}.transient_local()); pub_dist_to_stopline_ = create_publisher("~/distance_to_stopline", 1); @@ -329,6 +332,9 @@ void MotionVelocitySmootherNode::calcExternalVelocityLimit() return; } + // sender + external_velocity_limit_.sender = external_velocity_limit_ptr_->sender; + // on the first time, apply directly if (prev_output_.empty() || !current_closest_point_from_prev_output_) { external_velocity_limit_.velocity = external_velocity_limit_ptr_->max_velocity; @@ -890,6 +896,14 @@ void MotionVelocitySmootherNode::applyExternalVelocityLimit(TrajectoryPoints & t trajectory_utils::applyMaximumVelocityLimit( *inserted_index, traj.size(), external_velocity_limit_.velocity, traj); + // create virtual wall + if (std::abs(external_velocity_limit_.velocity) < 1e-3) { + const auto virtual_wall_marker = motion_utils::createStopVirtualWallMarker( + traj.at(*inserted_index).pose, external_velocity_limit_.sender, this->now(), 0, + base_link2front_); + pub_virtual_wall_->publish(virtual_wall_marker); + } + RCLCPP_DEBUG( get_logger(), "externalVelocityLimit : limit_vel = %.3f", external_velocity_limit_.velocity); } From 765a596743a5e2c5015636a627112d95480f1012 Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Wed, 15 Nov 2023 09:08:47 +0900 Subject: [PATCH 190/202] feat(localization): add `pose_instability_detector` (#5439) * Added pose_instability_detector Signed-off-by: Shintaro Sakoda * Renamed files Signed-off-by: Shintaro Sakoda * Fixed parameter name Signed-off-by: Shintaro Sakoda * Fixed to launch Signed-off-by: Shintaro Sakoda * Fixed to run normally Signed-off-by: Shintaro Sakoda * Fixed to publish diagnostics Signed-off-by: Shintaro Sakoda * Fixed a variable name Signed-off-by: Shintaro Sakoda * Fixed Copyright Signed-off-by: Shintaro Sakoda * Added test Signed-off-by: Shintaro Sakoda * Added maintainer Signed-off-by: Shintaro Sakoda * Added maintainer Signed-off-by: Shintaro Sakoda * Removed log output Signed-off-by: Shintaro Sakoda * Modified test Signed-off-by: Shintaro Sakoda * Fixed comment Signed-off-by: Shintaro Sakoda * Added a test case Signed-off-by: Shintaro Sakoda * Added set_first_odometry_ Signed-off-by: Shintaro Sakoda * Refactored test Signed-off-by: Shintaro Sakoda * Fixed test Signed-off-by: Shintaro Sakoda * Fixed topic name Signed-off-by: Shintaro Sakoda * Fixed position Signed-off-by: Shintaro Sakoda * Added twist message2 Signed-off-by: Shintaro Sakoda * Fixed launch Signed-off-by: Shintaro Sakoda * Updated README.md Signed-off-by: Shintaro Sakoda * style(pre-commit): autofix * Fixed as pointed out by clang-tidy Signed-off-by: Shintaro Sakoda * Renamed parameters Signed-off-by: Shintaro Sakoda * Fixed timer Signed-off-by: Shintaro Sakoda * Fixed README.md Signed-off-by: Shintaro Sakoda * Added debug publishers Signed-off-by: Shintaro Sakoda * Fixed parameters Signed-off-by: Shintaro Sakoda * style(pre-commit): autofix * Fixed tests Signed-off-by: Shintaro Sakoda * Changed the type of ekf_to_odom and add const Signed-off-by: Shintaro Sakoda * Fixed DiagnosticStatus Signed-off-by: Shintaro Sakoda * Changed odometry_data to std::optional Signed-off-by: Shintaro Sakoda * Refactored debug output in pose instability detector Signed-off-by: Shintaro Sakoda * style(pre-commit): autofix * Remove warning message for negative time difference in PoseInstabilityDetector Signed-off-by: Shintaro Sakoda * Updated rqt_runtime_monitor.png Signed-off-by: Shintaro SAKODA --------- Signed-off-by: Shintaro Sakoda Signed-off-by: Shintaro SAKODA Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../pose_twist_fusion_filter.launch.xml | 8 + launch/tier4_localization_launch/package.xml | 1 + .../pose_instability_detector/CMakeLists.txt | 24 +++ .../pose_instability_detector/README.md | 37 ++++ .../pose_instability_detector.param.yaml | 9 + .../pose_instability_detector.launch.xml | 14 ++ .../media/rqt_runtime_monitor.png | Bin 0 -> 438840 bytes .../media/timeline.drawio.svg | 157 ++++++++++++++++ .../pose_instability_detector/package.xml | 34 ++++ .../pose_instability_detector.schema.json | 75 ++++++++ .../pose_instability_detector/src/main.cpp | 26 +++ .../src/pose_instability_detector.cpp | 176 ++++++++++++++++++ .../src/pose_instability_detector.hpp | 70 +++++++ .../pose_instability_detector/test/test.cpp | 168 +++++++++++++++++ .../test/test_message_helper_node.hpp | 80 ++++++++ 15 files changed, 879 insertions(+) create mode 100644 localization/pose_instability_detector/CMakeLists.txt create mode 100644 localization/pose_instability_detector/README.md create mode 100644 localization/pose_instability_detector/config/pose_instability_detector.param.yaml create mode 100644 localization/pose_instability_detector/launch/pose_instability_detector.launch.xml create mode 100644 localization/pose_instability_detector/media/rqt_runtime_monitor.png create mode 100644 localization/pose_instability_detector/media/timeline.drawio.svg create mode 100644 localization/pose_instability_detector/package.xml create mode 100644 localization/pose_instability_detector/schema/pose_instability_detector.schema.json create mode 100644 localization/pose_instability_detector/src/main.cpp create mode 100644 localization/pose_instability_detector/src/pose_instability_detector.cpp create mode 100644 localization/pose_instability_detector/src/pose_instability_detector.hpp create mode 100644 localization/pose_instability_detector/test/test.cpp create mode 100644 localization/pose_instability_detector/test/test_message_helper_node.hpp diff --git a/launch/tier4_localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml b/launch/tier4_localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml index 59fd5174fa38c..23a1201a84958 100644 --- a/launch/tier4_localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml +++ b/launch/tier4_localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml @@ -33,4 +33,12 @@ + + + + + + + + diff --git a/launch/tier4_localization_launch/package.xml b/launch/tier4_localization_launch/package.xml index 1126914d58c5a..c4de9c04dcaf2 100644 --- a/launch/tier4_localization_launch/package.xml +++ b/launch/tier4_localization_launch/package.xml @@ -25,6 +25,7 @@ ndt_scan_matcher pointcloud_preprocessor pose_initializer + pose_instability_detector topic_tools yabloc_common yabloc_image_processing diff --git a/localization/pose_instability_detector/CMakeLists.txt b/localization/pose_instability_detector/CMakeLists.txt new file mode 100644 index 0000000000000..5270df636d791 --- /dev/null +++ b/localization/pose_instability_detector/CMakeLists.txt @@ -0,0 +1,24 @@ +cmake_minimum_required(VERSION 3.14) +project(pose_instability_detector) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +ament_auto_add_executable(pose_instability_detector + src/main.cpp + src/pose_instability_detector.cpp +) + +if(BUILD_TESTING) + find_package(ament_cmake_gtest REQUIRED) + ament_auto_add_gtest(test_pose_instability_detector + test/test.cpp + src/pose_instability_detector.cpp + ) +endif() + +ament_auto_package( + INSTALL_TO_SHARE + launch + config +) diff --git a/localization/pose_instability_detector/README.md b/localization/pose_instability_detector/README.md new file mode 100644 index 0000000000000..89cf6ca3be684 --- /dev/null +++ b/localization/pose_instability_detector/README.md @@ -0,0 +1,37 @@ +# pose_instability_detector + +The `pose_instability_detector` package includes a node designed to monitor the stability of `/localization/kinematic_state`, which is an output topic of the Extended Kalman Filter (EKF). + +This node triggers periodic timer callbacks to compare two poses: + +- The pose obtained by integrating the twist values from the last received message on `/localization/kinematic_state` over a duration specified by `interval_sec`. +- The latest pose from `/localization/kinematic_state`. + +The results of this comparison are then output to the `/diagnostics` topic. + +If this node outputs WARN messages to `/diagnostics`, it means that the EKF output is significantly different from the integrated twist values. +This discrepancy suggests that there may be an issue with either the estimated pose or the input twist. + +The following diagram provides an overview of what the timeline of this process looks like: + +![timeline](./media/timeline.drawio.svg) + +## Parameters + +{{ json_to_markdown("localization/pose_instability_detector/schema/pose_instability_detector.schema.json") }} + +## Input + +| Name | Type | Description | +| ------------------ | ---------------------------------------------- | --------------------- | +| `~/input/odometry` | nav_msgs::msg::Odometry | Pose estimated by EKF | +| `~/input/twist` | geometry_msgs::msg::TwistWithCovarianceStamped | Twist | + +## Output + +| Name | Type | Description | +| ------------------- | ------------------------------------- | ----------- | +| `~/debug/diff_pose` | geometry_msgs::msg::PoseStamped | diff_pose | +| `/diagnostics` | diagnostic_msgs::msg::DiagnosticArray | Diagnostics | + +![rqt_runtime_monitor](./media/rqt_runtime_monitor.png) diff --git a/localization/pose_instability_detector/config/pose_instability_detector.param.yaml b/localization/pose_instability_detector/config/pose_instability_detector.param.yaml new file mode 100644 index 0000000000000..29a25849d6b1c --- /dev/null +++ b/localization/pose_instability_detector/config/pose_instability_detector.param.yaml @@ -0,0 +1,9 @@ +/**: + ros__parameters: + interval_sec: 1.0 # [sec] + threshold_diff_position_x: 1.0 # [m] + threshold_diff_position_y: 1.0 # [m] + threshold_diff_position_z: 1.0 # [m] + threshold_diff_angle_x: 1.0 # [rad] + threshold_diff_angle_y: 1.0 # [rad] + threshold_diff_angle_z: 1.0 # [rad] diff --git a/localization/pose_instability_detector/launch/pose_instability_detector.launch.xml b/localization/pose_instability_detector/launch/pose_instability_detector.launch.xml new file mode 100644 index 0000000000000..4a390ee2854d7 --- /dev/null +++ b/localization/pose_instability_detector/launch/pose_instability_detector.launch.xml @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + diff --git a/localization/pose_instability_detector/media/rqt_runtime_monitor.png b/localization/pose_instability_detector/media/rqt_runtime_monitor.png new file mode 100644 index 0000000000000000000000000000000000000000..b3ad402e48ba7a154489ba02935817e050a39f62 GIT binary patch literal 438840 zcmX_n1yCG8w>9nrCmY<|o#5{75^Ry+?(Qra+}+)MaSJ54J6VDg-1X`oYtDUZW1mQrf$}b z4rH3v_7)$FP*5Cf9GrWdE$r<3IZ}>m)A)K6hQ4w4m2jxlsfI5p%P-IYY zl46=(Ij6baIfh!9_kGj+_ghtUXC=*vxm4yD!I*6g^%Dfh)u{0lQ5}d1P{mT_$@Ejv9jTI{1cITDgCSQ*Lx!8LDm6$J$V2*ox!v$QmNJuNalQz((hY|vKW zN%A+)yY#_cK6*cVkSN%xYn)nRb{<-jUcqW<*oS; zRDL-G-?RGm^2D>3^*UgY%VEc|1AxcpwLQvOprWY7YMuGn*v7sRk{UAf?Lhcg+_1}PQL~biF-KGkwh8Htz45{Ukx=JzB zm2~KE8K3wYnW8D= zOR+CdAT_~RGuT*P1qA5Rf4SQNDJeqk^XQ_#+t?JT(t+*HHjRx5`x3v|cSj|ACD>Nz z!4I*Obar;G11Q9CrHADdTlFWUOqBl@Q`z}ca^D>t&-e3ck=vy`=~WYQ8B^u!<=~16 z=yG#&H7D?JYZDA&ma8Y1>7G7%A2Dlu+aQT_&@~_$YiV!yB&@gGv?bcsH&8*MPn8D% zjcB-PTfu@T?6kDygdt=$vi4W2h=^q0UlH9B#tWuG*B zO_w=M7JyD(jTL~f8^>Z2Ol)K)Gf^~?89Ub!Vex;?lNWD8e`&ClgvA%XrdV@`ad`O9!2EW z-A_1NBZsIZ6jUro*Ain$Av<9gni1S>Y_(OJddzO#r6OW!+O??&QLyBuLp5|0e}kWW zYCP{{hA9G=p|LB&h&H)0RMfjWK5H+yeWRUwb)Wm!zS*wfv2L^Zul1-4on_MqE!tjJ zMR}@vx2L?hxtV3c2px#FXp=fMHMPtWTmn;T$Wr{hT{6z5bxkRVnA?>6bpF8FX0o^Hh5K|@)X zjcK|#lH>clUU;!OH76!-uFaXvUd+$vM6%=;-#4Z(`riE=-p2Kd zh_FX8pxE(8tRQM?aEV;9`jTpK*0=^{a{@}YdHn>#x@P(I*(ghZ92zfN_Gr8jFEO?# zEbwK;y>4R^AV-BQ7+&x@At%Wjj!xiFH5xH@(p4P?rysiLeZWpaK}rIr;jfIQf_zM5jb=Q;wNJe4Hb2&H248&{hx13F@qrN8Jg8! zLUmzDYV`X}LT)+;lLKZ^qAhtTN51%m&q9sALOKg|G{qpBq}I{l zp~-5K#m&hwhONC&Km-1+ZadNw7Ykco>cqG=y6mR%pGFAgIrPYSkS>hbIeS)g!mu|O z&I^rro!9x7l8EKw#3I!wBvwp3CYl1Gipv_}%)UfR7ESrehBUlu2hAv-JUNO>{UhuL z0Gvd}hdkH#EmOd;JGJ|)H?plMDFfR^Vl?*47L>O#GS;0)%iho$iD2VB*TqLrg)e^Q?MB2EB9c1FLG0SjV(o!HShOL4vY!rYo zbgfw^k_xmHg`K9k$-5Yl`(L$|JL|nhnR3@_6-TqNDV{18QEG92yhVlrJ~&$ZVUq<7 zq&cX=h8eg~h?Lr{+U`oS4IAIr_Syr)<@e9Vop%C;o|}PAo6Ehw+v{JyqUwM%qH)~$ z#NiScsM<23=`W*VK!Z@JKdMv`>gyd2(g*{8&Z|rpb0Ro0i2+<5$RpW2ZjfNIOT~v(7Q+_A?_A6FzN+%XpKQM?13G-I(`QR+xx+Y<;i3jHiQWxFHqYr zXMtDi&!h!4pP~kIpk*6|)kTL3oZ)9P=orXosMKOKkV1cec4;}B2ZK{!rfWssNH|Hn z*#xF3hV^Ht7LT{EeFq3f6yQ&QvS$6*wow`}(=`LV9@jw>Mi&fGD>r^OT3{b+CS(&k z@f{CSumtiY?!~a6fE9k9xsA|}GW3qPbdt7z8o%MrtiFze? z4UO+0YPaL8%zcX8^UN@bs!%3@Zz#l`IwoV(s;X-uY`IjR?3Yn$uqSi4mhA=?$Z~prc zC6WK%Kf2>gL@>eVKdyM{`u@l$<_qOFwHrF!$^Fh0O3p14S@wGa3SLESyDS$^Uw6Jg zv-|M!J9M1&>4J}`Cu}lZ78(tGM(}R12fhzh;W2hXU`Z`r4#^E&7t1sIOt7W}+rxIJ zzJ?+Oz9Q!3T+(HGw6WX0lcNy`hFRr#$G<+I@ARYx{s^T}qKaMjx=8%8;qiQKy{`2q zWxm|ykJN!06QCwTQvw9Rp^g%GoK1L-IZ|OQ>gfqBlt7#h6b;;;_Kq-ujl4R;c%_Vt zC5@o6An`lI3h*B5adXq=e?G0u30PV`#2Gbw&wn4tp{`zOtd09qjPaM0XIdV|^MdyRa=*u4I&&N9ip&j}n@;x$1_MBPjmk9slN{8JmrV`tox1hT#{*9e zt1YvLdv?E<{P)D&=>XdE?j6m#w^7d({Lc?h>2Kk*Wg>%)0gr@6D@}1`m9z(n0{QdG zBB@CUYC3y&>w&+{&$^P^jW6(7a(oC9gm^+>Kdp|WB$t0Irtz;0@9RUwof)~v`Pr?} zXf4Js{5FE5@27n;<$84O_J5|jN&eP}yd)Ns(jI`Xg}}EZKx9MlgZO`#I$jqlfsjLB zf{AQL%$Go)peoOrP4Jgy++Uaae3~P4?Fg~Y0EzY*{PoIOy_{6Oj zGT+(5Zs+0V=lQ;w;hfd!hO)V2*LdQXOLi5(H#(KyS-&o2hzG}nAB@iW-pSvbrb#PD zb2S@OZ`2mQI(63YAh+NQ9uL+>C_K$iR1IlUVnkD=PrY`kJzK| zCN?UlF#AVsXK=Yv_UI(<_V4q+_vfdtQ(sSNo_Llyf<0AKE0MnsdtA)?=C?bMUFid0N5F5nTp4^3 zu!N(;03>z+3F~B(uuIlPH~3XJ-ToF5c|4fYp#2*d z`5rEC4rjYRC%heroe>HpqHb|~8J;UwAypQ!C3wa-4sQJ9jyyspDyz#8C~PEDt|Ame zOX3$qEbx`z{@D9>UI44-#-s13a?bCj&V{-y0-mCMt@_2G6suNtmpDWTCH z0IaeGkDRdNXj0l_brioW@>^s`={1MFBncWUj4 z_VtNDz+ezoF`u0mbYq&tr_A9*86`_d2RYnQkXMd2DEU(wv)*rLN*PYGQ(cm-10w`< z!jUiKxuZ9T=ldTo8*^{u#&iFAr?c_a&za-A^u=zoDcJb+>eD9xPna`ow3~+}pVJ0( z%}Q750X~z(pM7f0uh>5AJoB?^(!cCqUdFZ$61@re_Lvx>j>b-?VTio*K&oN`=4mZQIz5cK< z=}dbUz^#dl#LzD*oRFt;|MW$JR8*F%(U-?xdN(f|Ra3iK>`NT~LaqUPH&7^QL707m ziIb1Mh=b18{knftuRhenW++aay(xI2pHLDcSl*{74RkJE4+%R#uKd-nuTDeIdS9QRjI;iuREuT z&?OwS1%q=x#DbB3C|@z9(*QnU7EpZ@seckwnB%{14Q_BF$v*n!Jzv&ndi`m?#z;jC zh|lDgr#%0gI{n*dKsbj&zHib&IumeNE;7jrz~zQ}pePiY&I2B?0LFQwBfRm2P?1y*k`$4Vp+vMj(V~+5x zp*E9Wj>WI^`BkiDr#G0k_V&xM$T!JDLE_xOG-lgMG{DqUJcCRQA84=(UC?bi*KWNf zj*^yidddDo7i>?v-sS*V4Zr^K^$Cup>w&n#p7nBd+HmB0niV+spawwZyZH(H!VSh? z{46+nt$?q=zvq<0&gUowS3Xnzt~&Mg+D(6hCg9=1v9VN}rRy)Y&$!3_WKVQzOuDMD z0|y+ubgWQR^Hfie*@kkIL=s0#o`3ZD`>D>UEJZ{dVC=K-^E6!6*TA@tcKA;scW}yr zZcN$fQ|99#)HzOn5c%(OcGUtge(?xK()I(L%`#jzK(QqJA#`;!LZ-bq-%Islu0CjMu@14u8Z`C3LhVTPfGOY>? z63kimx$xF~@BJdYmC}yB?R^Gja!h|tj*f&nZ4n({lEWD*r=8D{t|GD|X;hqAIIdlt zya8IR1VA~w$RMsiA_S@qqp3J3Ec=pINhjM-A&Lnonko24tXbupC6`rdTXA0ijf~$Y z&VE6)$3QY(!;CD4z03U@8yS~UkE8;+o_vZh+Vsch!s-t*a}D<6d9!jc6TYJqoYlaY zfMHWopWAhe>gY-<7Ze&-YXL0m@P3rS*5O8IcU%cE#jIHaI~xiv@zxD7Caol!R9W%{ zp14&?GBh-$aHy8F(?rWAA80~4X#wX&idcrTbEWG#f-V ziBCz|D;)FtIAk6Sm-E=h$?pJx>V3`UZTvn9GsXAMD<`rasctUQvdoe+H%Skm#e|I; zg#taL6Q$K?nn8m`t%ZgFgfUY}_D91nj`)d>1^Usij)upMiAxcyrHHuze`a=7 zPAk}_zauCPX%Oj>#g-dy0mseWWWG&%ORY|uo*)5m(Hp%SCf^!+Z+=h~qy&_*H$lc8 z>CTwZM=7;L_(US>YFO|d@Y(xc!usc4;hU-*u6j|$Zj2i&V&WCH;)NQNrE8YW; zZ39xqVfWbhjuQAlDe`jWe#4~K)}qDd1L4ccMp^Z;ZVLZlSqo~n-giyoYc_t@zOa9} zvJ$cQIa8=8@M<1$$Lw;V;%M>|Wy+M<9yXqwQ2HLwGZ54meXWK4xdhbWmfE}84Ad2c z6(rZjM)1(&>>*2rkCNDS)E_4f#f9 z++3!C$m zDO1NYc^Z>$|9-%0qB=%AzY9z+P$0D`vH_G>Jm&Pw&y~yF24})Xg*jGQ49qf^MP0Nc{o{}yA8f_q?E1Rna+L53 zPr=U&5Kia)QK{kkKU-^_hRrWDidl*p-<|cvxP$qazX9zT%w!Y=bEcI9DU$t?(%vgm zE0FBcT&cWnPkFuQBqGswK}Q$^cd5UP!Po~VUgA$T|C9zsU-r`szPR>G?b+cNAj8xy~O7b=0&NkNoaXr3-pxq3)WSU0P zAq0=J4ZZ0zVjepHEaInAOZb}3Y(fPvS5r4?`yG~Ltm$b-V~*g1xxT)>)0Feu<3aOB z!rj3g#&+rFn(z^g=sV)QxAIhWS{Cn$cOem@SfMB#a&SUpxc1iT8zbN8PYJ!I3;s6y z)sSd%a3D!jc&rhq+wSy{ihM!v(^F=vO?aALak!9v z&`}Ml(&5tMiVu%un4yZ{s$s~{;xCE5Dj$g=8 zf=9BW#2aZ7)xeEmrPxY^J5+Eu>ivI&h};g%x88&A)wbH=v>17=?qce9ims;zBM{h+ z2y&3g?TR|-Wm8j-kx;P0$#%kaRd#MTm8}-%MwoOv!YZtcx84&m=9@Lmw>H9wJQnEv z?&e7gHKC}AOy;pU@}R72LfWsc_Zd- zKnm%CvMaIFvpt<_S{T&3zD`O=W8xs8qA1Bj%C(@}Nyj<{03EeQL>5-u)A zaSmrY48ib9FxZ5DYQsB1sFgVtN16^Z#~#{k>knS@dm?aX6UroMA>@gcW__U_ZXxw7<%XyWf_eIzowAI*lPXm z@M4lD8yJzZW<>4K0AWn)J`b17*FqlA&E%2mBl117EFX3=EPw|J7o6j<>vAkhLm z3c)QxY+E@nr78x^uzU!4p^d(1_{zU+uJvkHc_L6r)B8R~t8vR1REN)@V_gixWmVUUbD!)z~UUV^~xI zyBD|~TbKOGe&eb7xpP+qwd1UNc}71P+3!n!SQM@tEUwvIE1%a#?P>Jyr{v9-5xL)W z-@1<>)ifnZRF$YhqwyrIB!j+;EIqz3a<$6FwIa@OPhXq<{uqUsHU%sR_?%918W>n9 z@hwG*@LIl~RgRked*9!;ETTJZOIvgGRy6sjz|78+3@C`6&cn2S525Sg;LAyPI2{DmyL)i#y;?& z-=rfoX5j;AL>05>U?Tt+!J-i7ObgY;lJHP+Jen=j5i3_D`4oLje>|1UDS1NP*FztV zHmx8ewNMS2QvJGi8yH!t9f|x`im_Y5=mbyl(OpG20NT;FcG{nJ`9smaus!Cc7^{%A z#i$iGck9rQw$?S-K(zKVxR558T8fZ)O{6dNeA%PJg(1A~XmV*`loiOAHc%=BM^)gm zGq0fjl0PW&K88eO!nMl>i$P(T%JN83Yz#+oRN`cH!jU7TMM{G=&Uj!9RXhC+13!Jq z4TD&QC7t;dRd%mIMIsvATRIk;z|H4iw?vPx&e%JPz}76Gnke*nRgp%3T8%b4RVF4g znY6lTP2L7(Ml&rzGA;P2OV`H6rfT`Ot=qxZgRV}CA-0-y?~iJ7kOQ@DR(7_vqhtLt zlwIuDx=?4aF4NM%iiZE-=7CKtagBCW{hBLZG(}D8t@xa;yy!Ud|8Vu-mM9m3j?^;c z2cP9;#Wko_A6IKNqt;43&MLsI*Jm8Kq}#tpn5{?mP4Kk%?(EQ?Sgj3em|m%T1GQ^s zGJZda39+!%@*d8meX~)M6Ywoz2BUSi^HUmBTHb**G4;7@d1-osq7mi#%zJdivuS*( zGTdq@eo$qQ4f;}3{6i~3P@FtXb}z(S)LbF6PPChpG+ZJtRglV+-7 zbNIf(wm7tMZI;PKsOqlwOTBhBz;oqg?s>fLJI%kHLTyCJ*pJbX;dA8Jq}d_!9ct)v zD{69gP5}omJ+6L&-ef9QFB!S90tv0RlL}TvkD;+FA z#cxn&4ssiW$MZYUSz2@aGD%do+FsmZ->Lrn#El^Ts6`uWLmYN3R%bhrevhxxHZ5rv z>E)RGLv3#K(5S`kSvr|VmaiQ#R2p9Ftx9F`jakbru+E^x%RbVnn1(YWP|*Dx+{#z& zv%PdGQTtYEWN>gMJG8s{ne7KY`k@O16m)N`AUH`?A8l^Nf~Q&3`oK!i#*A*lgYwNH zE46L`tvOQ5y;jC{y=>0npIYU4>!yeJ6HBUF&u!`{4U6rZrwa8KO|0?ZWH(UJXwO1x z{oJe~PuUV_y2En;KJ4;$ta+xkt3ASPe;O$Q>9D#+!uv#zZF_WW-toJ^U(31CHEU_s z?f#1&wD8>)qIZWVrtDu@}~n@(COF2-(Ryn zX!)i!t`m1*yKh|2=C>+QUemjS-^;qbGrq>G2%9Sd#f=Vs&Q8{F;?hQ?f0-ArchWf6 zrj6-)a5TtZ>1Ol(PfqK9;mBYE^AjM^s$Wa%ydYUvg&kq~dMlT7s`mZgiQf!09N}g= zw==%Z?u}887~I+0n^4^5;gmg5x3-VvJqKId*`5$h*aAnS>wiTe*Oumb3~qxa-r(vCCd?pEL77{_aVD(CH*oX7aVAsqs0*wJim0d5jK& zT{rF3$-#O0vP<5n933|bT`i&!SQu-CoBS3kaa6Ui2f3|lL>+DFyz}bu?0hph+%ZAB zFQWByQXcS9%32^Y_B$*2x_!9UNaK+^F?oKZ+CuJ3IpFo>wW z?5@_?&h2h%n*Mrr>B}s2t>3G0w-Blu3$E%%=doLPxEh(OFgK=e@Z0vL^mxk-2mAiY z4)qs`f4u#XJTDdS`WI~E;pu&b6X%#H^8T_`-f5xI)EKiVwbN_K+-JwUnmB#HPa3n-o$k z!|^;xE}0h|N-5ML+&T6j*&w0VVsd27-hVoL5z?r>ZEu&1*Khm|uZX#mLwOf{4UI=y z1QQHhO^gc*U$09D>9M6lcuyzy+6P&!v{+LLc=SZMA}?{N*`1C5m3ZcS2|{Z5QvE9C zgY)kAbK$?E>VsLTH5iL07BE`+RL6eZp-Q)tvm2xaq=O^xu1ce|5*a&o&!(fzt(ZJ(ry z0fnU!!=@!MJp-m~B|@9_95b=5Cbg!m3T2pBA2fD4K6=Y@S2tVORvoRHZ@2y}vs$@R z)DLd8X3cN8)`rCcf2jIF<4?Y4g^fu(EsjZ92V3T~NkkxBO~oau9^2eFVlhG;xutyt z8;OJeo2ki0?|GUCG~yf|naW$MbfzI*dsl$2gs%)DA&;ZwPJ?!U)9&;a{x>p&*o=O# zw@L%>fG6V9m+`2^NT=>3}1tb#9c=nHztTen{ZoS2_3?tjPyip8x3&kzr=<*;Qrfq{;g&_ac60D4E_=15 z7#%(PI|DwlDwBATNodP*v5r)%33aW;E_MQSe}#IAvZc^H6RShQ(Rz8R<@{7lX2M0G ziqQ}RKvRipsh%zQ{Zkt+3voW}^$|6=*5+2yJSsWsEw9yIrywnqBeI}tn zE(sp`F7AEevt+*|x8R9cr4@@6tE(xbj0a>6ZtUP2h&F*$sQCmGhuP^i?u&k8t+7}b zmizs%`+7sj7gSLRMF%PmFo{K1J)gHDr38e{M07lDhKQADa~uTj|NXCYDpXbXdeG+S z_DHO=D`t<;*yJ^0(r$fA+KRhS*Jc1I>N<+uZdLEkz!#PIVoz2cyXuQWVDsY`MsIF= zo*U8L9moB^=E7DPMt|Si{ssenz@$%#Lb{g*dr42L26RHR-}H+EJv_*9}~qOV6Lv28fqcmUyjr_qFsd>Req+iExyCII5-E)`iKjC8mt zPOLT=R4QhvCwEf|9NV4f~pmjt#(T@0ey0#@3Gn@Uk1R;>DdFEOv{ zwtZ*0-*%;)X3-yi043Ami`TF-89!n(8m$cOz>d0}u%27?7tEg8tPfP}G4cf-BiHyl z;{86%BN3ib_6n| z93kap=i*hh!+W3N1@{ztFC5<|+Iz3y5$=OXx7=`4Sak=xw_i!x{%t^Cvh==$t6V!8 zKM}CVJ^b;k+nX7RHyi#5%Xc1ftp_&a9>%NixOz+oOu`C9ye_S-GaWhRei`GfFI{T` z$(;2hE3NwC#v_Rad3!I> zzZym*({VccEcJDymADG@y*<{tX$ndct4#Z4_@4O(<>JxNnj~?2XhJe}l?8(-KZ)d! zz8=zgVVN246D|j&4wVy)9?lkbJp4O1nN2FygdHM1>r2n%B!yL4X>rCGBXMO){*?Dy zf|Eo7!XffBaL;#90Ly>f($02WSw4X4ZF(vA_DAU4^x*-N8(uiMG@{fdixZ1P9Ns8_ zFY`=hpD$mUS~s3|{FWS7!r8@L6>vZpD|7hG4)aSraDB*`<8-x0~B0@AtzuTjtZ50M$lK=LqU#b8)R@qJdk zpXX5jLIjbR<}jAn`SU3AYr+6rYwIDNwam5gkPnN}b{Xm#q;dLA5v{G`IJ``gI*sq8WApG9f|{K6-FhEdPabv-`i4Dw z-MRZZZ!H5{h7yi6y&$UxofpLCyJrFpRueykHy(EL8-%Q-lf#CQ@vMtH-=R0Wm(M%S zdjrM|1fb4eBj@$NcFd@0_9Y9|7>hQ9sZ+$hnd+hvlH{r~1Kv?M!;)0kvvRT_ zQe5unG2wJU)YFrt@6fv$S84Nf(o%yJ!x?H4{I3t7jfdv5P3d&eUj^P0zsL zAhBoHQ+7u&oP+`Of4K6K%#tHW=L|1z2O|3r)TzDPbpI6Ma53%87eb9@H`IuA*Oe=69sgK$Na){Z6tRU~Wc>qqm|q)R3INb*6*O#aWU zP43Suenq+mNNa6pWx5X!|v$Qf`k(|7!}jb#R^#D*!B%FNOi zmWhkqe53~HlvvbC>Dh3p3kf{c<;*^PJv8Zcn$%G{N3shRKQSp{B9y+g+uWL(xh&?l zTI1^V+-3HA73m!*7rsRHX~jkM$J22i1{JH)B~tAO;l_NB)=}E{pVHPGF`^o?m{0_a zWqC7y*r}|o@TlS#YesR4?IsZhMWYxk%s%7zQp-UR1+(*|TZ-A{;U)cVNPo>MzNCjf zX?Cj~Y`JiK^OAaVI3H;=iG^UXGV`j(=ZHm1>`T}8Iuwcw2$@_4r;%^1N+${C&=4)X#Q2`?|CD7?+#eWe~UMjntnDE-~ei%r1gO z8zuX;dUQE_X-BjU5iW^th#B0XFg80A+nDFO7qP#E)9E_adwZ&hVLXN@& zQl~48aq8rgDQZB_w{Uv{4|TfR;+eIC>AJhXkfY zauLtonWvfcf5whkHknNl&=5P*(Zn_&posa1YC!+r-i7OSapp%JXQ(ur*0@&II`hXl zsSW3K*2i&HlARn>)>4&ba!~-k9bal2^NpQ$d=6JI_C#zAsm}(qu zmk%$$y`l=f-q@wF=>1gUeb16&^t>8RFj6jIM@AmlO_(&7zokQ|1Bt?Xoe=PLTPpr2 z8iqOV$`lV*aEYaq3TMOYj>heQE6XneMee-=-m}*qF2>$LtVY-Fy>0%eN|Vfnca1SW z$V}4pW9xT5`~W|$%xa6vv4QeI?{q+7rPbyH^?7GhvNAu`E>JM7Dk7{`oDPAVT+VQm zps+|>3T_uY`IA7-yXRu6;p3uXQ^3%th%=F_le%}|(!x;k>h)&e*ry^h94%6(iOkO~ z!{Z0Db93Tg{{E=BURTCQ5`T{L9$QqM*I$v=j`eK+{+<5`)$v2BW)D`X^)`zcR)@i= zp_?iL(F;XGYi#qRvKqVMf&Pu?)IBkrKkh`XxP1t4A1%&{OH0EO{GYCg__|1Amf!(8 zblQw<$PFz3~n$Z=iT)CTr5r6|9}ki_8VoIus7g)uaz;a07Ety5YodFC$nX_mB*$uG?nh}$YI7AW@ zbtxCZdMEwLA`ZJHRe(&+E-eINE;xoRw8@HkVWA-USB97PDb^FP9fE~e2MZKjtoY)N zTv%;34DpAyLgB*!g2&{=Aro+OsOMseIoenFNVR53pBQjKN+1|53i@KB$}CH4m{?8B zWjVUZVTKASF6+!_uH+SLslMbY=mQ}o{Si6Y5t%6aBD&m;5;UHIV^~e%LT$PvRdjvl zHsoZtQ#B;{GyJJ>@1dFHnQQf?r1Sdp7yST#a2jy&XYc8G-(sWM-O&c_Uv%5E+X#mP zW1$JuYHih856m!fvurHNVGt~iN$t+JRMoJyTmb-w7n_j&b8{)v%W>QGeBXP(N1PaB zMql8sGnn*v&1do;tIYrAB>t7Ho>NE^`rKY0sK)@;D{q2k!Ab|ug;deSpai3h0|U$9 zyJT0Z$)H)yzUUIp#$+-C6JEB!Y%9f%^26g%R=}9fsELKhYk_tr1!}F zp)8j_mVl{Xw0z5+TESj>0S+Ko^rHeEr+nZCf%hwpFfTQ%H0c zygY>9BQ%m!v)z=^Y#NL`>M$y)tCM0Dj(O+I+MymcZ8+w*w$tC8wrcf-s^P8R1DEU> zt5)7)&e}}_+*$j0N|!9Z($XHp_1o%?_c`|U-W)I5Ce-V-*?rl1ZXxS=$;=;pY<=lk z)gkX?eKyeGzFiyJ`i%7;ozRm2Ry+7Z*qIynN++joad1bhxl2`R#q`O^y4DzdZXZ+o zI}84Yf2OHD{EVqX%v!VF|CF1XvYWBROdWA&UmBR7rZ+mC?VdA ztz4$`a27WST~IBnLXj^*ra(wg`TP&wR9l&)A_lS5@+^BL*Y|K#NJhLU9;UU6j8k@W9GpLuM-F@MK73MI+nEn217 z19O{NzdO+reSF-TQcWv~%5=6!3XN3QFQGnDz>|eG-_PasHtyWN7Tno;@#eX*?B7wJ zR@tYuC0lJiWh-@I)L2$6A#-PN2kbi9U7IYwgh9yp;er1PMHtbD{aBqd{X^B+vfLM6bkD>HY;7EQce9o9A_f45K9_*?_&{yrL-TebfsGHMh|^F0&k=lp7p zUSDl{c6K3N ztk#RC1HerVDzUArw4OaHlIMKR17PNtoh_k9W!MQPJW$!|S#b|SvF{hv?caN`0y8}IFn>9`Zp-RKh|+RwZ<*IuRcfZ75RkSG|6Z(W+!g$Uw4E}h+*ncJk@zMjZpQkTyfeUD(H;O?Hy%vJhn!D~%bb%+as zEZGbQQ|vV(*p=^FWG8gVKyd4c?&I)07h2}UuC-7di~m%Uu-!o=YmM1qomgn0vxLS3z6 zw|1@N!oO(2k-|j-oF=cJ+(ge_Cz>D|&&cWK#%u4g=>5$6lUqYmTKhuc(B2fKTOG`AC@Z0-Y$h-dWzj3r6J<{Cl9Rq2)_bfk=_f_ zAyO2iZdkLb$Kt5Q@0^I$SA>TzR;^{421SlIkOcQsC^n^qSr~0${=}znDO|_Rh@ayF zzkdaT1vNcb;MYCWZ!gsFRrx%4JqBGl~<=zE2QA?tl3>Z$5#)dD4EEyBD&0NT9~9084wlTB?-uhGickPkTg0A z2-pH=-DU^Ul+(dwng1Dt2S2~*ERjXdzmUjC8jw5Ji^9L*VXD~xu-sQ#)w%gWYXe`Q zBUWvSA#f@?*Zerb6$yod}yeU0sYWxx7! zo^at2F@Lvh2Ctc6fO+@5fPThYS7N_`QpYM9deTV-VPJ8hU$poPlVn9I|h+z3AiYP~!#*72SEWdz>*G4-uGQ&Ixbn6_n0{}OOH>MwU)C)hZJBjYwX zzbc2EO|)2Rqap(i4}*R!VLB5<5^3!#tl<9=K2+E=b7~2k$&jtIyQUknRA|S>P(3@t zwg}um9ZkcXZggxXVn#ln#!9OXd-ZMR&$5~;l6rLlCB7;SLEYKEhv#;C%yvF|dnv+} zA}g9UW+$TEPne3RV4}=(Jsg$aayf3LJUr-5;4MqZ#SQH~+ZGw`fn#p3u*+2#y#|a! zfe1*mA~1Tta51P~e14HJ z=qQ&hTH8OKMV8VDAy6|z_F(Af_ixjU%dDFEDL9En{4p2?PArCAJx#(uRWEy21P5CTNy|`lG(Pt)JX*}rVh$g2;&aK( z^%){*)AvgoTh_Nws_CK!8itgiW#iwLTaeb2FnNIcIo;O#Lv_^PzGu`W%Jr3A(;*@n z{gCID$NZ$<^JY5$t8-BVW{_t}hF;rWBt08(Tb2!zsU4AM+~_Yaju^6l$3IIQ={908 z-|_y16+E0?ixWAi@_UsgMrN7$zvI@NwJR=`gQ)t+#dEmD5fXkZZ1ks1W+>w$fMPp4>@YUZq^Jer#pEx?WLX+uz# z!i7uFm?gc`i>9ECXlka>6Cm_5vI>6QvRkrWi>0R)pT`{hyT5*Je%ZAsc(v2xWo8Bl zSeE@@!2KEIIv2+&2mC*Df))g2=`Ueit$L@IQSq;zp3ga->aqcBhthXM4B`ycy^!L^ z)0N&x9(!eppV$G0Yzb>|*~vdr!ab>`RfgZ_scFvdRt@N^#<{dCHi$g^W5Q)NAxxlP-Z{ zm~8(K$v`&0Y-UM7_wL=PQ>U&SbG9^9F5Ql@*RB3J_Ls=`mH$5SIM<`cJo;LBZv)Cy zwqvBEMy=ZP=+Ogoy_7OHx;zn8FGzx+qdfn@3(TLt!tPgv9TNm6;-#g&4G}8wV+2dL zLkNxZ^mMMd`WoVsk}SqrS+;6*>(!@6uU@!)J|;c$4Bve_4?~&9zK4pm_1OI|`l>az zic3P)6jJ6feWrlr%a-uq*fA6Z{88gl-a3mK3jrvD+`~H=H}*mH98u-2212?X$lOqLJ59qI8{{c7r%QsGes-jG2c7$h;h zO4w%4nt(dV^;ku=WabC&@!8ykC)>$242&TWOpI6r%&h0`Aa!;G?&yGjTka~1gABxftNyd zZQQ_fliz07fy12B`yvJmxQYaIly_dA%J<7QkXKMd-R5l>b?@C&i<3Z*Lx*;A^T6w< zT)zn~JvENEo_~yn?Rs(1h28KWK}k%*L=zes5>=AT8?U~>oQ12XQM)0-N8CZ}TIuL! z5gXTU;Dwjo;>giFF6!5xE3UYZ$q$cV+42>n)~?TO!|&#_MlOV=P|`$~#T?kX7k8zG z9NxQwaSx1P@4+kt3U}o?y#B^3tY18f*Is)YlXxz<{3K7xwN$dc6j` z^70h+?%PMrW{uH-JzLf=Y4TJu4rOtEpFUhQ=o-8#z=AJk@XpNnWFI|B)hg-Sa@W0_ z-n=TaKmM4lnL5L7>Q9VI2VoG(*~deVO=R_!10*K+xVYZ{&hOiU1QEoalgYEsOk~ZL zT{LOcfuTchBR$zm#+Hpd`P3x#9?9q2o)>f5O;_U)1-$;oyUhD$9@XkJX7HVN)1+29 z9%oO{?ciiOnEotw?%6{?Db{{BhgaTwkAvAoG^ksP;iK-SLG4ru5AWjfr(a{k*1a@o zQlE#%U585rm^|@uX3lt#%dhFrm6u<_bC2E6s-M=A-k>?R+%b}t^<(kqCL32SV9-^| zQ7$*v-*g)tI-h|I2HCo9EdgoAyj51JEG<~VFWY`0Bo%}TnKEe-(?9u$^SX8A;E^DM z2j5PMhN%RO>}S-NhZu7IcpBEOfy;h3i9*N#7y+id@)qBI{~gI`)i{__1iB6~#EM1V z^U7QA;5TErZtxJgc5RJNe)jCx&c%KEQlnl|UU~5aj_g{`%dfw~rX2_9*0VPQukTNs zE-A_0&vTQfv2^Wb>eNc-{-Kv6OA5I4>dUDVukr9B_i<{oMtu1GyL|T9m(;A+f?I|T zr)m8(c5Gh7YcIdb#vS`PwM|#XKR6nfvdt1u$2Cj%H{!T9f#t!vBjPP|X3w4+_<9cU z3iKaWfVAS^NvWYwgrtGb>)~K1M2jw+QCOb9mKB7KrpMB>c}to#Z%p2Rz6`j2951~5 zKDC4kDJ_c!sU+Wh@-eTxG?g*WOeVf0lSf{fZneSou2Fz#1{pY@Kiw|7npgoP_^44W z700aErR!)y5by^znMK&SLH+z5;kgIJ%}W&%a|9A5=0P=S98 ze#?AAAkf0W-3>ziJU)2qeR7Kxk3RMk7x(T$912trL@`sRyv&GEkCU2Sg(Ck?%=q|I zX3hDAN`+f^@!6?RqdG2K@#W{Al2|#7S}7^aoxhm4)EW%$-C1w3@e1+ol+KtSa`IME% z9f<)1LYBJZ@WDf*=Zh~GGGrJpPkWt&;6X;* zbq8H~U&-bD&mtwg8aj$z=XRmnxgGf6%f(E5?hRg@cr!{$G$m2W&-QKG@T9k;XPa7# zA9D{ye#N9IuaZqN?pQ&i2DKP{&s}WYafC-FOrT|_b{ImVcFih0^}-}XLJFFuvwibs znzuQX{Jb1S-ZPqJEzjh-UOjp8sR`^WFc>}LKYahqZ1PKD7(QYIpUwQ3(PJLv!`B}n zH!p|GEDh=Gf6647yN{L2mT>*3XDG?t$D@xvj>{9v1zj3)=UpSn$|>Q-TW;pnH{Rl| zyN2+>ixati&~;FY858dK$td=-s_5mt5GJ$!~wnb1%Nb>(2~D=sJZ(`P_8rH5@v$mus)Q zl(#F1w`OH2%}B(S8L!YpF)GZT34%jJw3eGi$LhgrF1J3<-k*t~(qADzJ9 z+lP^r8)DSR(R?OlihR!!jPXP+WAIStGb#*Z6Ei`MNK(xWerJTigGbsBPh$L2gR zY$zEyiW`TI1fvkQ&xgySbKjWpG)PaRPW2c*{9r0?zCVjGqwizE_e&Ud>#cnJ*;}kx zzn-dr4(Mbo5P0>lUop^WxF;k_+bf0vyLD`enN$ZiSr7C zu-X-$;G=4lM7D0-j>1ikzJ1ueVFf=eTf~ANmT;g*(6UKG^iYtD-5IoN*VZ<^)x-Hp zDo}w6{5zpgVb4cRnS=s)WMvm1JaN>lQ^%4Jng+@=QAREwfASS|T6Jg1+I4(5^+{4x z9v^%#lM+KGsOwxi>;b-;ql^`da!&urPg zlaHp)VEzpC?c1Nli@)N6Ztd8zdL@|!#RQdyl&Up( z`K>pY{r>aRN>AbWH{RvuftTS`*rxvysZ2Bi96q>{S@TzO@3ZgHt9N&vdwL{pS-`q& zJ6ZbuQtC8p&W*Rg$K{^tj=~ zdR+FNuK^|rm8)`k`#5+an%5A(j^NGOh#Yqzj_%UViu_ONvMYJwsbcU(FR8#Se2 z^;q`rUd@UP863(gVAYTFNf3TM|NJYq?abhp-A8$8+B@{>aW;K=b^(vX)I8K|+?+;@ zsuAld;M4ctVc_le(DB^!xa+q5#0GY=aQP~V^h#7pZ$y_aT{)|DQ``z$g?>EM_P-aU zWS$Nq=%`J~mk!!a=$b&QQ;U{EZ)S%F;%e0(;L<5piXaN<@se1(4o8xcIcMBB^y<~n zL`1=?kYs1==ds7earSxVapi#9Y0$U{H{N_XXLj#}@aJ%G_w$(W++=$9yOgxbv0U1_ z2j^dMHNx$}=hjJY)Qn)j&&&^J()Y6doY(PmhFo_gJ$qfi%dfwSRJNBJ5?8Fwx#xA{ zn>q6cnz1x*-I41r?ZzFqT+itHA7aprx00S(nWIMw*|IB#3;UiEopa=W4XNDCIvZ#RIOeQZ)_a3YE&i8?IJ5H2NQvTz|>r% zr&S}?qY(%x+&(vzlVU0M7h2jT1j;Z`O3}1YJv61r%P%4`^Dvs%N7ZUo(R?ndS4|@~ zI~UUkA(aa$eBkkro|=G11qlX&9LPKZnog0alU-24MHgR4@AJ+AE72u}=ECjONKW)1 z1AdBvU??jxtU@?uWENB;%BfOTb_7i*{6#sK%0-nL^{p_8Zj+>VAB81BGBY!Yi%S5P z%Muc(0v3Jo5#yhFh4ec0X;8l=I#z&wsbTA%tU$T~D-Gu_n|5&PEq8ItkejJnBb9=j z13Ylwc#h;0(el*hRF2m%O*_1dDbY2TC99E^ow_vqwL#%uc=OeL-KIc;W$)665XKv`D8b zi~TUAWs9f@HxkR!H7?GJX-GmMj(&sg;Q1#WWcIXIxbmV4IFwgRiOYvn2D&oQLfOoj zHJvA4`jDCpn^Uh|4RoW#wo%nEO>hYXnxcBuD&*%Cp_ITxq6>jr6G$US$PA%$Wm`*H z6GG{h2eA-v{yD7)J-jv*9xDMgbV{A41_Q#%FidMQf)eRI*$&W&t>G8N4R^) zU}Rx28jASD1PrijDU}3e$2b-e6)2=IFQ0^@N+2LM)=OfXheKIe1ce(zi$N+&9;;#6 zO6;mG@QiNal}0bhRh zDM6{>6()DwGm1Ozz6Ytr+7Yh6R0@{>;g031fj2VqhOw+)|1)h*Ys9rT-^{f)4?zkK zCg7roxyyc}O5-*(tyjm|5|k+AnqPqmRN&tSYg@MSVhDlTmqO28z4&<6cRY6AXmT*P74f z&u7QxEoe2X!NgJ;#Nf*+`XB+Kn%?q)x%}wE=2`G zgo+C|av+n0P%I0VucTF{E>vsK1g}}Z^0^D}ozavH%hys&EOpbX;x8(oSKmG~XmSew zx#dxEZ@r3UEt_$8|5i@9^jzE?56bPq?Y6gEp@Wk#!ZA5gDx8VJF<%f-f%yVOB{Xf+ zfF~b)nEnHI5gpMWy$dW9w zb8{#ESjROZ{)5+JY4%K|aA^j`{sM|a%5n*^r))yJ#=iZ#ID9k*kIO}sDpk4p zhJj3-^gKeVM$0y*q3Mn-oipnNv6WJ3dHSi${p=&!G^~am2vDM8ka`@g+n&zSX`fTK zPE`_f2#Jm|s)UB}#M1D>%c$MvOb+hYNq%M~LTDsbNux%y zrf4ZuY(r2HakUNW+kGfypbKe*WY9GGXEy-Slz26P5Z*}L0)$eyg$BZlK*J>z3Jvht zso^9ZEs~?y%JmmVa*Za8xMcvD`*&luZV_&ak_wlQAPdRKJHn*{uEYzGj3LpX^vm=J zPQM&;tpXLOz&{684o`~>5C~lKy0jn92SdE@`umK!^L7lp)NkB^wq4KT_Tj_GKXQQE z1`WiWP@RE8?q$$5mvC_HH)u-Xl7>Zl1nANPyqH2ms2~LWXv!q}@BwbVZZO3GxN`6a zF7A0Ql|6n&-@Ap0FTKmVQ(vKV#~$1__HNL5RAVRcXM)7hj=w+Z3cwXav!ej+6hvhmT>m4`IjVEsPyGg7_MzG56!wcyio5wCXvC zp|@R!2Mt}1;hc_bdF+Xo=-8t>4?i%1XC^$tw{vC?RBo;rd>btr)FD9v^j^cdni0x2}B@9fb<7zmlq?2o_Tr@bB~KY2g#9!F3i zIFPZMF{8(!g^rS5yCLHq9!-_1af}^t3zJ`XgsIQ#XfdhWG3sGzrN%SouiAyDl_HP2=9XhI8%O6`X%TFZx`54P)*d%b=_KQ!L%otkVK; zk(Qds`c?1J|LSE(<>kDK2JxSZx>K}k6Cr5@0`J(N9q+#T4&VQ#@uk-4ODN?iYb#Oa?1@DGv$S+ zCLMcTk6k_Yvt<e2-zL1>bwfH6oX^^$!S)sz9!0L>GYCKMRz2opd~9YY>kN? zkzhG$W-X##(=lv`iwlH-L`S0GQb7JYBtt3)dJ*}${rY#iFmA&`a z`UB}VPBWOyaakJ4zk0MjP58X**3LQ=CC0h=N!M?&Q)RbTk1DLmo&En4LX zmu)dsQF-5;=Y%IJE37L_o~(^BlHc4N-hw@jRisVp+~F>XWFHkop2jAFu1N1GOTwi9 zB^()xV`=5kd5aMYr=Sxa+w{y5D_9JuC|z#&X$>^1FI?gJqgrM6OEhJ+7$+TfxaCeq zM3oa}jWiH3DBTlQdPRCxBRX`5=G2c~N^_`}xmVZ*PYS{2jcZu+!%~c>e)9QZx$??> z#Kr1p(gaj4mx{s-+bZS-(AjqT6n)MwNpne*fKLUdgMzzbu0(*?`8hVgUhi&_$^qhAAqpDhmckPWy4_e z>{%?I@*+(W5=ay-l+-vZ6^n}U=rm#&je7P(cs${BE@efJ8ct|S5taAHA{^?ECoB9- z2&E9h3WzFIH1QQ-?XyCmNvD$pC>R3<$8H2Fb=TLY9rN{O!PWuN@>FBN9MqNE$5 z^jn3Gyb6@CoFyzV*Po|g{}`Eyis-a_RqFA?lTT75DUshCk>7kV75-B|jK`!(N(=!J zi>|v+5bG?&eaYk#F6Au4;YBWw}QEQywlQR=-S>%t^4A%Syy^yZu%UaHrsO{~|0 zFiJ>E^iYtJNJw}vgoY_};wz;ggQ{&gHcG$55y1dEjZ)? zQ78%IvuDo%7B1V%WtVj$)*Uw3uutldc7zNQmuA0%QNnj$&L*MmX`IrkDLy69|Azuh zR-gj^B>a{-SOFV0Y@|!)PPRH2z(h(*y{HL`E=VcSG@I2EV1!I`mliqvDbR#NzeKoj zB^>J`=SETP=6LcqOp6ILrGf4+7|M-lN`!75zojxPPhES%RyI59WQo$sWd=*XUzm$5 zqg<2Hs^6;Gp{)@;P^m{9n(rLAf8(u0sSke^(MnR=o}82A8epqa(QGeNqDoeT9Yn-` z!x5pZ2qyY^*?x~^7NawmMDEeT;}*h_nQFH1Br+SczxSwt3)hX1)-B z8N&Q!JL_J5l}5oJS)2Cb4F++UmVJb26q3DhGu5kBX31kuQnOA&v<7wUv^anW5egh) z%9LsB%*Y1KKq((ho3-S&TL&KROnp+Jl!AbtXC8foy6rBs5~xc*nFsdq!dtT$IA8#c zYga^0G6^Z29UUHTfmU;*|M?YK-#U<97V2UT5rFyw3*41`YwMJB6ej^MjiR5 z5v71u1D)6_2Cc?Rae=Rm( z8OEK?oD~a358m0u}g& zAhJnWQagh!8&{B=luEy=ZzQXr7*k1*MT{SDJ2h)HWd4#3NDWJ7qzubeP}qUxZA}7Y z@}*m!LWIN53;UWfBK3#wSAdC=i`a2hvC1*An7T3wUu6&#;mw95R8qtT)2DOl>1R;2 zS~V`Y_&@yo^LER`M})Zl-g|g+`Yc=siVAY*f6dhl8F4TEph@`IN*Gu>A-Kkr*E>KE%54c!9|2ujn zR$`x_==H-Qgx6)C94w<}nU~GHvpSOMN@BzErJR9dOJge?OoiK*!08>@)3!kk5DE=R zLC$V&yL~hn`wK`-NZ{EgM)JWYv-#}Xb;QIbbL-$sXy2+X4?Xrg8GH9)C>Oo{Gmx7G zoKN*04r9keaOG-=ipk1+7(9cA6>_3Y2eMtI_=T(u@0+O@S^3?U z+Nl7}CYc66xVG zqS4Zy$}>j$)$uyHIHpA>RXP_{Ryj=W|2KeZqiYu<5X3d)6n@e%@QsK|e!<&$dW(1+cj}mSWmV-Q) zUDycMQIfcn@eXu{`(8qg0J6Vf(I39(e3U+MiN`{*Ar%7$-@xIlgZOmaHi^(NLOQ15=b^E; z^JcX)1`fHCbI@4yC?CB)1EK4HhwPj@2;?$(;xkN~G7Vjm7-j-jTzM@IKXwP>?;XpGPiCQ~ zRVScgSu*DX=FEAYyT`wb%aeen!=zVUBc)wK?!5Iz4i`xL1;x~A+L9OEoJPk}s_^WD zhj{s|Pf3h{tOA{s+Ra$HXgUkO_?-JjkL74lG0IT1>ClylFTcdvAC@wG=1g9Es|^Xs zZji;~WbWgwnLjXL;?s2K&=wyC9nPqaD=v&au~XDFZ`1z;$PX;zh^%jzg6OQ-Su~4Y%B2l5jnIeMOs=Kx7>0I4H`7y zqKht~YuBz}kF{uVzW|gbs8+ikMIi&PG?{tMxxC-03-5L6!h4-NF|B6g1&&q*G8jTiE1zg=LN#7|?KPGz`htF!b?5dw?_$%Q zTrff;#CXx9NiY}!yN^n%Vk%I93jFOMu(cQpEAE{^R#pxkkB6Q;&gRECpEGmjJU*Mh zmRoMUp5%BBS(yjOJ-m~5-kQoe=U>S83l`Ah+|Io7_M5Ezc`Iwzt|zT>6{dgqA#2wD zNX;5)Y+SvJl9C{ko_~%tYk%V0Zk>sZi{a^y(5b?b(vX~#H;gslM-bne%WJ^m8B9xv&|CDhL^ra_*cy1B*FFDM~B zVB+@r*k2T&;{_L?Y^F*HJ6yEeg>=PHtzkV*Ii(4$o7E@QCBUWI4s^C%4FF_ugkyy;@aPtzL)ea*>r^jK>>8tk3(` zk5&aLP=UV$(bl|H;N>8Bd4)(_=lqK=qfWIr9(mva@{I&;y?GERaf;ldSri@3;>h76 zEc@{X2H!N4JqPx2diz$yB~)g_h+(89#nP|OrQ9*>5q9p+=IR@6rbpM-+%aS@{jR*8 zAD69S(cC$l->DmeZ@it)zWNraDGaIDy>~bHC0^QfI2+;C&}0Y^3{jGo%aJ38Ig*>r zu%UM{W9ApMX?GU!aq&oH(QG$nI38e9rDUYxr`TU;+W-oL<|03@5Rcbm8T<(sgQBG!HT4IDUt$}hkzCA#gr z5dsWNhxmA6o3)_EMSbn~dQq+u(nJP|*s^8|X4WAzCGcnlb{FqO)S)JF#rs ziHTfw-2k3?dOWGVAUk*LWJ6{lqgu8lFFzNTZpUX=2K#qzV%_E)R8Ox)d`cSo4(+oo z8{FVZ;LKB-v3~Vpip_y|bqx*6uv!TjHq6e>+|HsOR+3($9!r)jCgb2y+O}qNjqFKYLG*9nI=gw#I*4ytgV%${Pwrs#1 z{mY&;58OUCA*FL_n~q#L>Q=_xdk^;v9mb1qO(oW4<$I_=1uF3G#Bno* zluj8}&hG-W}&kkHF5@_1=RBEPFvKUd#$JI9ug}CZWfA2jK zQ>yUH#HXlTyE=P*`GwP3)I+ypbrlo`c>n#6$;m6AVdEy;cJ~NdC88mOj|+RB&5RG< zWBc9%G^tY)mvEuG6Y0{aEh$M>hy+6kR;*mbhG`#>UcEX~UwM({wc;qw-OUHHzu~rF zBk;N$w$Dir6zwwq2cew4j*h(b$4ZTs;QsMum2St$wtXyZGy3PEbp5;RGE4V+1^ya{ zaKuy%sdRGu28Qm#CdgIQmr>EQPIXnk5snx=XAbovZ#8hisu zG2rpU6RW$aTKg1kxc(a6p79>dKX{G&fE!=ch9sob<@y`0!Dc^tg1U;I|X_K>eL;?g= ztn~`~ckrvZgMS+e41?@#+sOF%V={hRLSDvROkI##w-$9ecBEFnepISeA2gR0S<(rT zsuWIgNrlaH;y4#8+igBN<&X&H5_F`A_7i9dE7Cm*h~%0qZN(V55^>cJq5_#bGX4ny zRapqN@^SPk)^^zg)*luf0OGIJdo+O{x8ox7lvfl>ihE?+~&zAQR*??#nM@fJl=pv(g1&0m6wO{Qn(GbqYG z!kRU!Ie0i9bRTu=*5%a3HCeOzCk|xhAaxH_YuBe;%VzBOc^TVx>?5GuR7y*y-5F;R zrw3WRd=dLH^H9P?Y+^E}p4OULX>lCgzl)t28Dt+h#F$53CC^u#yU%T9_4gCr(b=8QAikdhRS zCi7UkW)pFh>(Ho94ZzR7jD4)xl0oNA9jFu+^WPk*tf=I0;Ub+q!Py8kWv@5K z$xqp_740;55pL1R$!mMf{sF>#(&%0VDsTdb4i^0ImWT z5LP5>CgIG5rPj1UDH%D5Yw%mAt4Q*0=QhVHSvW;fPDN2rc5JQydHF@mU$~YF&OZ;2 z+jX2;Rn&h1X#`j>|7+@NjrY2Lw9s^s*})%|7eu$-;*N|EVVTLL~$y*jA;A~hwS$-fg3h#q;uy^ zC}nNNLbwTU&k{6epI0VI=tzZ~YuB(sVxggg+m4#zP$)~q>>PKav!+X|n58aZnVq0? zq|Ffs!vuMl%X;);#g=`P1Qq$ASjIf{BBO7)2zQybN9du66gnmr)z$3klnR1SC@Ii{ z$2N2Um#|_KN}(gsaYfCEQVi376=f&p$&t84m!w5~R%IMugmc1msw=yfl+w_sNG|3- zaypMxN(J4kz<&#+Glu+G2o2%(05Tjo9;}6hvQJ6EnbN;TPQ(dqaUzP(QueZrtWhVJ z&2KCwp`(Z)DJhOi`}RPpV=^d4!8sjTsgE?>%{e_Tz!VxzmZ;xV=ZV5@j#Y(2x=!%< zsE#%5fZ)1zViHBAq;(1w!VV}demk?w2{qDcpv6Bso92m^U)GF4Nr^ate4M{!2Ju%v zUw)bLq?ReL+NltKDjb?nR^WCa{w;~2qA8FIDXp}T0?lIVl%081SveDQN0KBpl%`v$ z*Rc9lN@ddph0rxLB~Zc&R<9=hoTDXza27Mf|Cj8!>}(Rp zx&G@YZ!Jc%mDUF{oEA?+)9&y-;t*d|x)23YsqnMmbN`98FkIm8p?kkOqgOf437c-8 zY}!f zOw><|U|I~r$tJYUhGbX=6y?R{!~YzlLP&*a+p%hYL?UQEBklI+5H0-r2SO1&7lqIf z!p_kl6%lO)go&DSudYX}dTabOJ>o_uu+|?+;t~R-Or+F7vlDPBK-26z<<9u(pe1v~ zz#&{NL@C3TaG4HcB1D8fI9WQ5Im~L7v!9ACM}a1y zMimTT1&)V5f6%je9VsHV4Z51M8qmlf;e8CCjt{?=JMDh_px^CE^B|anYR;y08|L2vU%sNsjS($4^7i;$C(p> zLaBVd`TTvxJpLm2Au!}IiK6}hghh4HK$#Tf?%~DBlgTSCIyMc}ufVzY%_*<&!{Q$Z zDn-Vg-4qoR+R~ff*Ks9&KYoA733FPXefAlzz4rRa%{FB<9Hsn(%zP$Je3|U5+&^9H z(IZ(*eClbkit`EmiE^gB_%ff)nnef|dG9~<{?QxbNht1w;iSY8Q56f6a1^b_#w>&i<}vHNX}mXmHaQ`q%p8wO$)$)8RlssMGwpf+rDL7p zT@cl}@Uzhf^S8G0Q#ftcu!3MoTRE*PMu_U=7!LQPRpQe0F> zNgz<_v1m;%QX+#vX1?wexr(CQM40aQVXa*wj@mtP3@^Y~`wJ4|}@eS)Us(EdFf z$~*$n#P9bLkS68{F@R8-?iu7B`GprIPo~%i9Ea{HLcsvV{*n_O5g`OpN(u@JPw>eK z{4e0-Nc%-Z?j^$Cqg)tDN!cB>YGkcT8RGlz7m}HkjS^8Dr9%i5C}~Z769ZF)A}3)P z;Fpc7`6Xi?QYhY<_6DDQIUmE$9qgQPEoF&)vR6(^1W?TOZR?r*>U)#~Lspxk@+n)D zo1mnXv)E~t46oP3_qn{ap^k#=rRg_8L!T=X3Wj^-k5Rfcq`b&Qkjvh7ci-<^#?gxI%x zE4%jXM*_M~AVaol(W=(K3~wFL*DW2BS!yKgx4}@R&8!;u3y<>M{O`#N1dmJXlscAO zaOm%b4XZhP^e~2L^4!Fy*|c>Nrm`|ot5W@K{aJk>t^SrF7JW5~&*ywciQWFv{TWrK zG6`pRRgx7e*RX2MM$2%l%s5(eKp|y_=3CKSpD@y)zN6ql3$ zW_VsX%x&5Ji0u23eBjo2NDA_ES-4<6hH1}D#{ntoUNf4(S74fvIVY6~nC#lQm7_-w z6H?ZCMgvor;fGYX;7B=2n$|j^42z*ml##>KDbFzUj=LE;{0@fRekV^(d^voNRqtN~ zfo0$?5W)lkES&QRBkvf&l69L2X;74($xF{X%DBg$rNDIfGi6EQq{W6wp)l>illHhP zVT(wGfieqteB5|G|Lkl0h8a1a2vAD1^PAiKY12s|ZBq=3SX#&1aK}lTpr|mZD)-fd zBKzPrMh(B6sqfAt5GZ2dS2GxS*B#tB{7(Llz4wl@s@V2@zg2UE&JEp7lY^k5 z=z0aWZ{A#Y^}33gYwCBi7*?%X%O|798$&C0y+pKBbS4?mYgAc2<3AY5>djjS0ou`? zC}OrFf#WFFEnmXHqesk|2T;b$-?MWok3RM^Ik{)qz2g_Q?b(k~iiux*#`Kx9a7s?_ z-diuT{orA=jBT~+4)E5@@6I-+&9;i_y`tPREMByPeB0HZ?mASS60nPzGkpSMznV^w zHn4&VvNd0@)QnurdN!Z$-?yLFN4!R1H!OeDfgu8BZOHoeryCjYzlHtuyyNhv@#3C62kSmDG&lJEZ4|W;FN+4 z021YZw)~On8s`5-fd~OOWe6*Xc5IM7a{?8nULgfaIS8$Bu&^wNR?5ZY$Y}m~Vc`gg zZHK@Lp)sLhPa(%%?}+RjXjHfuVfjs4l>#S(&>^JJ?l|s~KH+}R#5qt>;+TC6pAMsJ zjr0Xv@25mdW1|NICR`@`2pvK>+JNGvVOsPd5QG7r3z(NkT?zth;$jrB!Y9I@Z8xqM zhtfVX4$6$FqXiZrY~ja3Ae0T34+o9Z2G=G$0T2caL7$J2Z@-DOg4hBAI*h=F#&W#? z4p>&iaJRKYD4S!uf8}_fI$^*s1U_wpFqveOcFZ^m@CgSH=6oPDAxGlK;P2F<5o-vP zjj)1%HnJD);uE&(h4DvV5DpRx7pvsTJyfc3tRS{B<78%l&ovl~_xz81=t5w|UrX0W zF*my{LioHfu-v(%9e3Utd>igckwRff_i!Wxjus}ADHJ|!W1(G7h{h)@v<`z%D3@U_ z0z0tF5PqLAkkAn_B{PQ==pvT=G@Hy;*U+Ow3mgZM%Vi*x#}gXm3h?^s8TS95gO}Qq zpcmIGX4}T4d_MYf>U8K$<0kbfDLBoXucxr3tO9pG@-RtO7$E}YFrh$6%VgQm#UO)7 ze38}}=2Qoy#MS~w*=RIj8?=QPZ!NJAW?ktpj__llKsZRGxr_qFBk0Zxgjui3QTU|| zKA*d7y9hT|j|izK$vw;$pL{~cn-jSH>W(a%^9}EhnMHE>bV`Z~35COCTvDH@Uw=i1 zCiSo|Yfnq?Y2`v-!XScRS!ktkq;P$aCaPjP1{Pt-K!no)?Vxbk6WnmPkTy61Ap>Sk zxl%WH#~2m^6(TFE7hSsd!x9Qq7~x_VBRWinKnt|?8K0&l5aCjGZdyt5mF_ z2xD#)TL_d8SSo~+U@Hshs@KS&0T9^uqWXqm?AdA_(djoy19>%G& z`GkvedHSAVd^2|;`;Hu7$iVJ&>)w^_Sy^0v(=Dvuz6T|xA(lpfDrV&KPx0=U$!J~7 zvV}9bc0e}0d-vq=XNGe=uZS5_zGU!#o^IC{_^`vkA!My*;=ahv1$a!yozFRh~p+m#k z^vLQ#moDA7{f-AXcq$i73Exflgh5viBCBr}f4lQu*6-Sn6q>!iZsc$Mdz00@J40^1 zjbphbC@t~Xg?#e%%Upf!AhNT1@!%8BaX7Cqau$q0AB9HiB33V%$>3`T(k1&^?t0`| zutAj;G2*!w=$qA#tn48yUcVEx&CXv|Gwg-|^zWZd_pE_ToiP_jY4Xk-;pvC(rdM`< z`d)V%D_5;YBhgxO?(8uhy5m+}dh>U*-KZrw-+@Mn>}0BaMQH|>5>`O&9@%JTW}^_S@1zaPDN^x)&qCK0v*ARVSo7|k^UZ{vee zUt*V?=gZM=a^2wT7}%!|ci#6XhtB3xoPU}(UwMIUJ$ll2z(8isnUB&Izdt1lv@T%b z4^wE-qCMSu_M%g#&b;v2XbOr;35N=p{MpC!>z76MUcI>W?{~1{;4zf4S-<#u2K4Jo zpPv1==q-X*Lxg=bE4$E`P$m6gSStFL4G{u5{&V#A_Y+;rp34D6RppX@;_-nb2=ZMOZq zhJW0AGyQt?;qP}o#DSA%(14{woH%}vTZi7pjF~gZIe&&{pL&dIugRuIpT4~M!34_C zY*@8`K3&?8)vG&?KK3x1fBu=Px(#N}{-f>$#&`p*IO;a4Plpa|>E5|Dt(!OP*=PU& zAOJ~3K~z*HRCb7$hd)loZhh&UJ(xN37g6TT`wRWM|4GF&qr7d;4YaygIVmL;VSb!C zmYS8zla`)NohzF#dg5$Cb^)W`eU{p_tC5^ij;1ZzvS!0Zp1A)Zs%O-sa`lGnIdK}{ zFJblaWj(jJ9>onO&XJZ<1H*&xso>ZYmkPd|K}KK=TT-KRf8uD_XIb{|IBxr}~iIK8v3X5iIB z89in^jvZp#rsdpy+YJopKY)P)Z)D!mHI#r^!?6a2EM@MTSv>vtaFl(P58ix<4xPKv zqeoY|bkF9S?-vsem+-}ykLca48-uPM%!v2KQf39P5xhNO1cL?)vj6{%cfWFEIu0l1EsdZt}PpA-+2(H&le*+{H7}8omZac z?GL}e2|>>3Q#|+2=NLTTCO#cCnhwnxvg^coLKHD`!ut%l?P2ml4qAFflxx=MFgrG{ zV8}K7>5^BBd2rmAt*d`kQbkRf`J1D(>tp-FTFdK!mz}Wnnkm}WypYGy!-wb zLS;Ej82b^|Uwt(LdUxZtJ09g^P7$TWIea$eBl>3bBzr(M&yD;9EflAZ9^(3e{ki=g z_i-|(h{f}N;JU#B>DDWY>#w_+W$QNMVDsbm<7wWi6`lHC&y%mbOPL0QLSiHTAhPvW z`JY|>^Dc(`2Z|1t@af0zqY^7H`mJ}d>@x1S;~^|3jI@kr%+UfI8*PUP3yZ?CF!@Dc z#(X-7#2`%l;xnFo_7$dm_6m-cI6|X!7@@-E)LfF!dvAZhHFrEl_m1tcq@QxhiS)|O zrgP686qW_J{r;ypa&RB`gS5V?C-1)X9EpjLd-f;~JpL?izVj~4nl<2y@n0}w);H9u z{WxR3n#Y5WJVlFUb@}G2PxxxZiQo6n_3h;67E>C6313XWDl1^v(7RZ?Y8`zVRcF-b zPkHF|_i0h@3dW3`z^CthNYi&7XVk=r)M(a~H}1HOP|g9e2mK8T!HUJpSh#R0BR~F< zlz72?Prk{S$&~lUQ54dQ8T|?I@kyiv^Vz#; zDW&I5^4v>rQoU*e?z`*n{Jd;7i{~xm%`p=xmu&ISlW(%&m)*3vL{Vl7-W&5FRnyCp zB+3{!VH%e-XlVQ`DufftrCXWsmnN)=Lg{H1qT zx_kpIDi^V8!>_zM?laPo;&|zWkywPWA{=9$uTz5vbN0kx(rVRZ%qQ<+=bz@@`<~{+ zHEpqcFzx%*3?Dv{Dpish^U(+V^O;xp^sVQ4;kg&dy7eIj59~_rnUmb};JZktfY~#q zQ0T<-{>S4va`ZS)KKlwc49OxhsT>Jr0=gx{&R^CrZqj!Qf9pN!)~JZGe3YC!O=5B? z!$-bNYLdmXk37P}$=~wmZGCw7?t6Ib?Qyhg(~{{k=Q4TP_q4A!j4>a7Ox?CUc;)(R zgtRD^nvBHe;K5^j`uBSna>Gqz_v*;k6TTp?#NwlmCvf!0DIR-f1h?GQpTjvt#Fwke znDOKA`2^DP^X?nZQLS=@*%VzIi7qSR-4|bE$_H;E0&zU>$bIx^Rgr^7PI1SB&(ga? z1CkQs@kh4Q{|cW()U4Fu5FZbJj_G6Hg_1(H?K+IFc2$&?wCr#d6TbYE+?*nw8~zTT zkDEyU9u3*L`8UG8Og{R2IG0r^&yIBqd4KE_{&CM8^y$`=yNBM5(2^FdT5?GRAN#g! zU|+qO95{M}Wh<7^sBsgHoGfA3OV@El{VRC?lhK?ydxo)}&EcI9uXF9St=Ya~H%E`2 z=H(AQzmi*A%=N?WL`ok)jHgx;=6rqu^;&o5rDyKv-0_1v{@4S| zZG1W9gFe0(KZ}n(A4{bQiH!Sb3?F77{-p91RaV`ZT@!btgqi;zSY8zVIS45YM!)zT~@^^Jvwg0gjXm zy74CZ_U*&rtv_@9ZO_xTQ5BL=XlcBL$_|@LP}235S$+@}<)? zJFaSwz^Jcg^8P1dxvWYiO8PjqcPEu9SLXAH6G%u1Anan^{^(0?yZuf&wQs`gucz_S z@Yncm`b3T$IZQ^idW`-2BT{@8J`YDJAc|4_tNgo^{}v-KR93{kU3Ft~j*IgUK7`WlRw_{ENh$kVwh^_m6VcV`l487w) z;zTY2hrZYJ=g^V;6p=#xM$Jf1lT=Di!N;*b?4!hlC$uk-)btF>`2#e%yb5P?a`}1V zIRbIXG-}?83Q2Kv?a+qjpL~kqa|hXd_!y7B{4$lQB%%|GN%9#ghh@vwuzb~4I`!yA zA`Z%zMxU#PMS@oX?XuT|C@d}_r_iEZ`wnELl|$$d+CGOCaipeake-oF!z*gBe9kxI zoIJp`od=k=@&jHT{t`h|Oyx^zQjnL+^w~>z^w9^YR;`K&!`h`-D$L3yb7|PFKd-(u zlGMZ?t5>XH#oBFj$?8MUE+Z`B>C^XW(5c8kA}ML9R7g$2B8he#x<|cLQgJ@#BpbIM z<%tpf$*7QyEKVgc4iFkkLRmO$6sQL_)vnh!kVs@Bgn~%;pK}q?#l-Pz3&Yze(G##d5S~9uk3tU23VqLSCpqPNT6q3_3 zNXv+)O1S{V1;;slzJ!!YS5UWJ0}_KdWcO;z2gBZB*WP2CIh{k#f!B~;(IPDY;-p46 zMXXq{l&@EwWZL&X5~o7=d=@$9&QdX{oDr;N9cjh!LwiWCaVd41*CP$EwC2#+Q{YP= zy;4;&5=&{(pe9T99pd1@BOE+*p1U4=1iubpVbQ+Z0Gy(8?Ap7RKKDLLxe6HsHK4-S zWu=TB_Zc0p9>R4u4Z&ySvTD(fOkIAMA7;%b5H3UeEKZ*~fh~iGxN?+F%fON*P}sJ4 z{TK|B2HPR%3o!JyTj+9C8?-+_)oPg_4xtE=RK6-{X{q>P{D0zt4*%yDsWoTLoT9Ms zJR)35VVO-id^k>s1#^Go!KX(MP=1Pv3aQ$p8b!q=Na6@2SEWU}cGRn2v0(CtgmoMP z|2B+{^%BTP2%;Q|#JG5Rc5cF!wJQh&g5V3VdF@J8G-{1Vu1?R6t=Y6@1&`eGASJ~` zloTsU>>&B2WjF*t2C3hoH62>kVEf8B?Av#MjfaZ)Y5rmaB_wBF!P#?Xp>hJ=wY9Jf z4j~f?v<h^6c5U zizb()5(UE<2!ocMGz=s{TYmiUaik;!2?XQG>eqvBXZ^@^otv|M({^5eq74Y|;=DE& z@>H1fIcHe6^(ZgA)sKwKbV9kQ#05-$w{F?ar(gfT7vKFvz%C>#(l~SK1P%fbmrPuO zpLkWu$-TQ-uxKqmZN7=1I*+3hsaLx)`(%jP4O>ySaXm6Hq35H!ZIp~7rCfR9d_^4E zxtE+GNs|`ss8GRA=Z=jT{?Rl}oh<+*u@cfLmzF}g$V%|w2Y=xK|J}-eixFr^NQ?_| z^uTVkZVOTp(i$Z!QsNUKRE!-8Lt+r66+XwouL0Y}1z~aWY!2Wf;P-(JA(ahM;z)^* zkerf=W0z4n z_b{L=1j5`>*A}U%sTAd%Gw;WTMzDRwBDQYd$+*eiB2I1RiMJ+W`2@j09AzbC2HB|v znVHpS-n=m*KA%SAv;?#kB*zEYxZo?!o!x8Tb^jzfa>bK+zU2?@!hCZ`Yx#&P`k5o%Ygg%p;#G-dfHU%4VT-PMmL z@4lUQVQ^+CphJB!OUng8af5yVk;z0dBtG8aD0U%SWGl%HwwqBBM%Gh79e_vya|GJYlqe zl(Ynn@7{-y%4KA7-|Tr95C|N!CD4H&m1|yG%LpL zcFczD&h-cl$baazxAX=T0zrm-23o@ zqy)nhl=-QDNfi@-)EcCA@7y_PE$~S{LMbeuupp1`Cw;}{eaFcfl1;h91OnRN)ok26 zOiJNX%3#jW*kM6lZW$FX%Ooi=jx%RZ5V9RCpT*(hC-BF`WBJm!^TB87l(mCN<0o>@ zJrD81Yj2R4T8TH_c$IG5S|Xe-hYeC-{2$9FnSDNz?k5 zxtK{amkn-P5*HUFH8seYGpEqH4v2tpdH_kONeuhPT?~8VF;a9Xw)9gjsM)t}7UA4t zS2Pw0$;q^8*N#_4e??}{to_6Q%=>N>xu8KL3= z&}ro472pdd5Fd=gLuk5)Ll?8_8iD_X2d=-$e^2>u;R5v~CeiEKfsA?US-$;pJWE%s z;&fgZhw`LlR3Y9z!sH2KS-XALrs)^RumIUGB%movF}lo2E(lBt-H z!O5*FSTcVuKP}lzdX1KJXj+>w?>x`u-?p=Q!%j||Dy4GeYFt(|z^fykVePujY}<91 zvQVk%ln~zaDYH=tP{P4hVMC~^B{%{pBu!g2BQ;6##fR^+a?t|b{pd5g4H`;PdTsi3 zZp|zA4QATZDJ)yHk@KY{JTmy|-kdygkZE5|WB1NoY}m4m{BX!SAe$zjKv|?Dr&70O zD$hLePZq6M$4^Vvg0=`L<1Lh0qn!|?3X&>bLbuM%dFO?@S-D~*Yku9&`mKiv1QL1v z;hXqo{D;h#K8K~tx3h2OVL}9`SnYD&d-Hit?AgG$&!*6?Umwn#IKY(gpR;549@hW5 zje;`J+9K@UkQ3S_=kRvAw`<12H5*-Ok~or6EAzxZ1~K-HXPEWHVYd8E%iGbRTn{wvBHa;2t8mrc3 zq|ewE%Do^Evg2uRMLk6R9zJ>JHRjG)!5i;RW!UYvQonvxI(Kf(^AFw6!XFnif9VDa z6euf=YX{%LhB=d2GH)io?%d1foks{t3rj?ovjz~7E1I^V?A$(Hed3=iU$KgrKdq)% z3v6vJvc%)xEz zxn{^P_8mTf_UNSi8b_6|f7f0%uKSfWD>t)Y?awINM@UFyz%oX3Ne=f8y@3xWOedrS zySH!Uwi||#UsQ&63V8dKNBR3hk5lj;x=bu0P7dt>9vVx5Ki0R4kvw;T^y5+VHnnv1ThJw!~2)dUITYO@OMk>e0SU zGd3=p%X1Ij&V6^?!^~Op3C72x@PY7|SSA2|Py$PYDLB2C?j74wuU-r8esm;(inY1t z?qOuc`5E)ZbG-B3`vw!Jg~7$yMf|e*C+5%liH|@3n&sQhGi30M^lDv?a|br@#w)Kf zclJu|d-P>Gb#6&&yv>i_O(tBbseNffj-4$fkd(&FgF7%`%t%(R*~FTS``CBk-XOA7@{OLS$@*Ql)BLP?J+^~VQ%h&VJW5Y?UP?5In+9S2cb1O+ruf&1hwv%)0 zl(~@T6X1_0BQ=>tv*)s4lG2lW@!?2zZ{N91I+wPSamWrOQ069^3=cl5`J8`h`IBZP`O$y`V8nt z9Azy0;X9l_0!x>#p;O21JpR;UB*j@=R_AiIZrxAa+SMs>H0hP9)3|PJTD57--krPo zdfIf(CB$@Bh_kLLa$yusad58Nq!$+O`F1roI={Py^33|>(9P@ zd--<89QN-&LW>s7sZyyjZCW>H&)$Pfn)(ezB_a9@7(|Q44NbPk2uR65%5!sbIDYyh zeX_F&NQ)x}k5jQm9U9iVl(uc!uwunpe)wSy+1FgpEw@}poIgmTM)j#tDU<25=CE?j zdfImAN>=Ya)T~j7HmzE-VDUW;t?mb2*=vPq(ZrI<{?zUnpkIn#aaXzi>(I+FW^g9WJ@N zI+^9unEdrD)~(%0{kpXY#3w+Y96dU=qd%U3+w*Tj$O!Ubc!K=glQ#Yg)Bz zLC_K$JaU@$S6xL?AV67R9ve3POsmd4s8TT#DJ+DrXw|j_LFr@aH#6C|`B&Or)rqbh z+f$`dCKWR>nKWrCn>YVVla{UM*Yhe0P95O8`5W*By2IH3M)IO#Espn}6O+qh>AW(X}Jh zs#N6knRCpVISaqvPy6<*XxIKK*00;h%$eU&P*O(g_HC(JDU(*MTC#k}BIeAQOI%_q zgZgLFu3eGKcBke9MN-Tj<_1i}r0>QL|<(E~!$HnKNgyc*zRNr&pk5(}u>A z9l_U``Iwwqo{sIWV#AuX%$vV}g5omTw{69VV@K%Fr7Lk#a^mPooVXM^b!^Yo*?l;2 z>=fV4_?BIJ_RyqhQ)*PHO#S)|2o)DIdGZu?@7+)9)@{kp$)QTE+B9m?m>QX>EL*dQ z>uxRM$bQW2_*&6_q+`O*e7xS}@2xw-7# zwV#gNIuW!KyS8t|j!&n3yEb_DwS^Ekj>FlrXGu*>{X?a6`qXJ^)T)8&YvS0E6XX^daz=R)(GM2!aTnIZZ_Mt?xbO(22`tFnLteX zC65N|-1!2+wxm_FMjSeNn(CL-;nM0E6c-k-cmFh0`=82bIB|Xt^Vh=(@k|mhL27Zf*hd=FY{k1igB7rB$motXs8)IdkT4=6pU~ zx^<;;g><@h?8J&?%b34#5v2+S^yx*_ishL;a}K-qAE85sj&$qLlpWi*Gws_SXx_FH z5C8LC5&{ksVO$;0>F%b0Jclb%{0pVA;)Di#D<3*!kBhW^CD<6V=8m~?g?WtWH3 zFw8PK26AQ`_d+`;EzmB@z7(L9gOn0SIY?=_!6tu_2_()B`G+VtI9v)WBa6bq&o zfTPN=q{LAgDg34`Z!EN-DnMFpDk*LHuQk$bZ)A*I%#0-kN^3(2gEIV%F1R{E>*1y> z(=PbO(r)%njZ2;5X8dr|rD@koqX6mTv+}3!`P-A9vwGbUD#aO@Z~EB)03ZNKL_t)K ztJb&yIF~fnJ>f@HmXW+yG5{3<^l6N*QgYD*=1@W|P)?ZVUHTnI;b?{QGHGZB zOIne(YIpu<7sBA(@s-{j71HqGNg0)i5I87&?%G5e+UAHX9gXnPHi#$%l8i~U6$*ve zxpOBqYSiG5%5Ph?(xKy3-XujkrVWm8iJ!Hb7hTH;6a)oY3OuzUaZ|Bb!pK=`q_ofo zlyW_H;jp=!A>3>&4hWxR#!h?KJ7Gxn5m7L{Ys@J?I3O)U*lxyIBZV^hz#UJsCcG1Y z83&2EcqcJyTWLd26A&o z4(C}s^6V3olM)k9cUPD2m~!3uuHDBskerf2N=gcs)NRVzjav{%H;aHY zJYsI{VO;(#EzSF-D+gn+y4W2JLdwYEbJ~ z?~OI-;oNp>?U7t4mzE`3q?CXUO9tH2DiH$@AraCS86WA&(u&YHm{1ME7;h#VDct_J z#od@S4OU(C=gfzmybGK6Hhn%}95;hpQn0^|O8#xOhqeiN0p%G}y7!$%>FG6^^h9k#QGhMYwg=rC?^~4vMFBT4d93fFcy7Si^ zuZY|&wD2K?IjkbV=Na%siQRp|+x(@$**+TB=`h=S5Dp-B85AT-MJym0a&|w zSa`;a6o!XSSf*3T?TjwumcdyhBqWlUltf};3JHm+bjrGpkPv8W5XQKa!quJL0Y|!X zOG_+mMOg22^mrdxrwC&(SwfpRFD)DoEA1YXq^mC+H==XFdJqz0S}VXt3hnAtht;c= z(yo0+7H&Go?RVWpIm=@2uFW)S)QIGSWRemRNQh4&CA9*hCQe6Vx$E4>&u3Y#?)7M7 zw7WjMIcy;;Uv!ON5wJW|xG=g^n>Kpn1X{YRevwQt3Ms&nM!#qwBP8EGcW;oc&Xs=| zfd5w%p_KZaR{XEcF{mR-(JK;+GBAl6UGTE<%nZPgDx)Nh<(^P5grZt_p#$N1bUd%1 zd4v3uzG%2mN9QHCDhnelRY5;sPW_Q*orlRR2S zb2oe5$Y?7gipd*EFt{@BS@V!fg6a~)Y8=-nw4!6 zWjnGyz#Jsd#z-+&L@%azk9q}SKZ!~)GC|xAG#5>TnBsX)V&;n1ZBH)08^?&>E2eHM z@=k?e6Y%8k;9v>Mo!1wPHUObeh#fn2P_t&ui(iCB^V`;6>3CJA$d`4bg4j&Do_EO< z?}|p0*5o3QxZjW(v@n@#P%7fdH4jG(`p8_>o+k~2(nilko)O;Z&OOU`b;Z6l#(=*_ zqPQ4LGupn$Z*=7Me?+~l5R@34uZY9v9u}kX!4CL^;@6V`G7ca~ooS0=6=_5+rVdD}fs-wqm8=>RS_9H( z7iqkuVT!j-qLPlpEVV;S;yCx&n51CtcOpaUhQPEY<~xGeElbBPcz3O7*DGY+tRs!P zxaD5||Mx{l#OeLz9Xn!wZRUoj6I}9@$o##~t9F4g=$HVuPa4L6Xs=XcR>h{(jBSs= z+p?pL^XN*vdSq;FVJ_&(MN`IvZN)_!yhpJWJMz&!NHlRMEG)NEQPU)PEXG|U(SyD> zCegJQ(XpP=MSzGSIlU^?s@0%sm8w*&T8(N|s!}Z@1;6&JHu1ZDC|3*V$aVKvW7Z?a z@w8PGGwZb)Tm#T+qIBmXDxyEV|005ne9IT9M@KH-2z*-MQ%0X^8Ba!~8dR-Tiz?M? zQmslAYE;P}HR!vrI#22m=!l38UW~Q{Z_A3^8w3dN=C@a=JCZS>b#K@5b~H!&?*F?fZT#(d^3GMr6pl3>Bn=6D{UNwNE6`| z!YoXsquvWc3nHU=FVUbvoY=aaTW-9C!{>6%_HEl}+d*i9!%z`L6_fN`2tz=P0HR7; zyZ;8))L za6IP=!){p0#ELzIsZ}1Umo8-cp2K)9f`}_$nsBBMy?AHs?8`f9s?Z@>PUO}h^pWRJiNImICfARWcg zgWH(<(-KMmTS#>AX>J@mkR`wThL#d7%;xL`k8MYxwVOW6Yn^L&c^<}CgEeBiYw#cs zI`*@RwnZZ^3k#p|P)SKx+i2mB2{BqA!>n7oh81gn#V5gX_eiBZZYq6;GmGqBuMb)k>u4?JlC zEGrr^cR?@)ydvB`G2f3q0}(8+xY%fm{o{@);)2iru%8hF@M3e(!UM!e_+32$i4?v_ zv?8{p7dPmFcEx@k85?=g?@S05VW0p)`jFCuM=c>Dbs5qvuYKMpkr9gNzd&NS&&JBy zG~#zMx}e>z6x=q+2*l|3()8pdVrr8fO_Knhv|`#QkXAHQf8iK;;~Ry)TsSr!V90Ch z#e*PX|LGQ2rWei5SUH)7`oJR_^Tr~&L;qF&&C9>u*DEwq+Mr4i+6DoRi4S_BOG)kD9kj4!kLJB)#D?~heb}2YT2%+3Ft>JA;uUU;d@421w$%zOYET2O7 zP1sop3tPLm3>^Y(5>naPEIb#6&jpK2IcV+RSUwC^MY))iFz66kYS$No8~$|LCndf6 zWix0%Z&R1sA0aFp8N}8;cQXiso9EI2^KV_mr17KpZO1OkEU>kQxUrFFY)sx!V^V~$ zl;cJYHI~rW+HH?J45j&J8S&iX965ZDGQg1*QW$2a$Qe+UB2+PGlN(k@fw17_TW_X$ zv!<>m&YU7mwBABlzQ`tQynh<4{p9E8FnZJ&3JM%-Bw;L*r=1eO*tNF6V8L`4beYMe z?7{;~+l^P&M+jR8!mh348Sft6MQhMf<9Qzq_Q(d|U`t7h+nZsrhMiDo9m0hE%RreEf0^r15h4T_nj$3yVI-E2h9F$q zW{%@}7*!b(g`>e%5(uMonCRAEgEl!&y;`*p;1q)@L2FG|f|APo>_WPP^ifuNj?cz? z%(m^jPzY@8qe0VV488SwW9wT0rDz<&8bZ=N1n4k0B?fnfz>xxJ38V)0~{WmGmX z8}>!YCN*!}OmdvQDdsAbX5 zFK+vVhQlBA_y0+5;)2JbZ~3#H{JuxxPoB6Kz;JO-Vr%;2k@~ZCU;LIo{?ecK{^I)n ztd0LCHT}87{_H)`Z^Yn@fA>DGTzq7@@OyuifA8`yHv*+4L6{_IJv&F)2o%oMt1^<~S>LxgoPb7oDaP16>XPf4X|vo@?=zXPRV zgq*utKS@SmhFlYV+A!GowV%z!^v~Jpf{l`wCRWU!!o6Vi~Jx;i&fSaxz zNQKOFI(F>LFI%>vEq}y_)LQf7yt&Muw}d$0_~C=}?wd`uYL{^DgOB2bLs)1I@7_+E zrVYtVPv*v(Z{*nd0uW%A7INFo!^kXuDeu1j2_js|$M3#RojP@B+N>pumaRim#@SQ* zxjK6w6)IGsNB8bbo%|IwFKx(*3Fygo7I~d)i2@27hj{)y(OG? z_Bgi=9ZKaIb?Dx+58>QAN=rhttlyYQnYCH9b`?bhc|7~n(^RThiLTwV`EC0_Y@yh+ zW)0ojwj;B0CfDA0E#J(T!R>cGNnvprp`s$5dFTN~ef|YyM1vXtLWj8Lwi}uH-E>NU z)2H^)u2Xl`{k)5>KKqQ?m(-+M&04(o@i=2TyBI?$Bxg^Y=FtcL$(eI!kvM$$`KMf7 z_i|d-YsB(ZYmq)dxU7Ju9=V^4v^1JFZoz`3t5H?}A#CP;H=QcwYSF*%wUmTyMtwSt zqlb>**NUZ!7Sp168|u`)lu=_R;s`-O?g{>R|NUHA=W;4mtjMiH@8Eo1ab&KAp^`j?zwkUYt5v2)uRi>;W1rcZr5Dgrgo+D!`PpZvQ>zx8I(B2n&Vwi+*tBvn z-P*Mvy+S70*A8Rrjy?42)s2h_<;WT^h$AOX0wKaqm>aLVk<@Y(m^A$xe%-m3FTa`r z3X1Y`c>d{Us9dEoJ+gYU@8C(afU}48F|bz`Dp#vX<;v9={>oeAmfD;LbR3j0 z*r()_3|@WXZ8oo;PurFa7(Zb$nlg6mJw)T?Jz2eCC3oF;4MPX_deamXD`}=)d zGweYYE?z>N8nxKHXE%;VUW(_S(OgzLlO(^xFWdKkRBT+ohFT3C{=+%8wOHVZfnsZC-gcc?>-Wc+ znZ1wkDS4jvHNW?H&g}=`>@$1KnpI|9>t6SLU5i#MVch5g*s^*FgGP*D_NQO)v!7o~ zesKj4KKeADem0MT`j+v+i_g=nA?Z4#oL1_Z_Hge#4>9fB3wd|OYphu|m%mN_n7W2~ zetz)<6jTl1_37_%&t11-=jB2)%G;lP!m{OGFlIz=p84}bY_3(znmvazPnp1tS6xPJ zYct<&-i00Q!rwof$K7||$q|PhMBR=W>gyY5ji=dGQ_ImujSmj!P3sEKE=P|X!k0^y zlR~m-?OLqd0(uS^%=i;dX4ae!dFiP?^X^|CWyPkgBxJ|{L9MV|hje=@NXg7M-{px% zp5k|p{E5e&ew2!`0#a$P!v$P=`E@M*Y7y68ekzYW@i2#ygm3YMRvsC|>cRaF{)x{%`-uMidUMCGevOO9wexu3 z(WhCpW(8-QJPy)Lq*8HEE&S#2C)uzw$?I>u%h{8TW!ecxvZiJqO)br=UA2)XUU-Ff zUVWS|KYo`v^A};~6f%1B;S?3*{(vv1PV2Nz>$Lw}_JhmDX)o5vQZAL1JsCE97-NPF zV)OEqe6wOPmHkgc3567CQt<>Iyg!%u3+J-CNmEwU-()(<94fjGV8GD*sV)ff$o=~bH8?R4iZ(RdJx?_&j1W4sjR@s&Q`}b%69ufZh?BCh6Y7Gq= z=d<6?gE;5Hb14-rT`NnF+6f%v*;!Sgq7o*abTZ2puVBi^UVOc52^Zad7U&rB=gwi? zqUE&h-9RkbgShr{7(E}4HgR9O_tvp@Z!1qdbt7f@E~TLa55BSxL7aG7JukibD%;k7 z!;Za86xX()909_jv@A-Wo@I!}9eniu2b}xUyE$yk7z*?uteC%$Z&rTI@G;}aDXe7h z;6ap>qs>=P}F}oDOVw|ks`^Cog4Z5%cbmXZX;|vY}&XU^}+iL>Rv=`Q;Y|0xsi&ZJi}iv;WQocRb92BZkwjXBji!dX_I1EhQ~-D6Qm~mq$2)nG_yq0HP zd7b**`>5Mp%eI}h6m$qwH(o)P6mQO&%dr!uancDVVu_s$9@q!V*636VOBa2{^w}Q~ zZ`i_))NrFrk*tJ2jnD~*wKC(q_gL}uXEd}WDeGH`(^ki#1&g@y zo~IZ#;y^5sB9)9Y`=do%ebY^h9C09Ftq}2Tyz$assSWkzx*KkywWXcCO>M-Tw2@gv z(cZe7MGHP*YlG(YJMSdj+Q!Zud)c#d7fK1rx>PY>$UsU$VH#`q@cyjXELyRQZM)k% z2yUZXNw?~5bnjY$q!vr0O>TdxnI+4Xan7~B;m|{eaM+M4-g@rOeDe7Mjvv;WoZKk= z1`lL#mEy?5N3m^NBl#05xcS!G$P!3{EU#~;by}x&TBrT@?T6P6_7^s#(XJnYugH&v zaMDR^%f=QiLdSXeug@{}^KZH3j^DC)`5NZV{}SyQK}1a$VL>zuVVxwIPJ6_nUh;rW zk&_!D?V98f%eFi)=HhCPI@y*)LN+>;B9%^)Us#MK4N!Bv?BEP}Cc)pr&ST1HQ@Qn? zCz=0Q7ZNhe{sa2*-pkK0WBLrP`Srad_H5*_H|BadR}!Ip!fG!#-eZoH7=Aq=zz&BY z*~+=+ol52Y6S(E}U-R1Q@6h0au)~DIVGpVR$|dP2qIm_LD7nCrhHp#>3vGo>%%O4- zmJC9CMG$=jmUfZKWX1{+M%odQ2|pCy<@OtIqGoRcH{9|YR(<&y^H$b)LHve}rn$L^ zK?4SG&jSxoSQG`J36+$ybNwoWEeU%WaJUZAwh+oiYS+{kiQ{UdW#I_JR~E7a$wbmb zH98K;1M8=j)_uhR7OU2^Pma}BVR?fNn zGU|72=QnrU&e=b`iXr{_bL%gENivzDC?XAYM-Ve(;tCT^3OgrkIJ}g?LSkuH_0 z&&xrlxQqgXLyKcIcZ)zpC+;B5XSFC2@ay@f$O+Pt#I8Wu5!5P=Gz!Hq_0tLmN|6kR?X_U zb4aH(wvedwUY>pGPb^-(iJNb~laJ;t?F77v`*`^ zPWw;Tza%ll=ku?r+05!yYx!*cCw#Pc6$1y3AkR^xo9k%Wx08KMO;q$7Oi@`8r3GQa z!dE8%TX{gra!Cotkj0WV)FEERorCtWW<#V?9!-ZFTY^^ zyiZxXZap>I>ku+00B&Yk^HP&#F4etyQ4((F=HETe*vZrAQV^!8u9m89)l_$_rnD%J zh%jt%kx+;oJ9ZOyGzy87A*#BRQBjt|AOG|?Yu9aIN6lWGxPwZ$v^2KUd%puHDX*le zq8L;Pl%}|-n3c;`vUT%znp)c#GkzQ|J^xo$u2{*ZpDkeV+T9EqFodX^Kx)ThhEK75 z+gcuY=u!66H3vLdp`0kiMTLB|XaQ^2Ze?F>6OQAvUV(5O_B5pE(rXB%6EEM*sGZ=6C!S=@hRv*AzX5?wVQvodXT8h1 z^_yr13&0o01*mGdUMi*Be?(0D`*uZ4C*%skxUTEDP+Ka!4#Jk63#K|3QCD(?KunC9qu#iZpXljqsWAGtVlyspqCrU&s!Z~@AmgKVV(+^m` zb_2Wiw1UV*NDC{J&(Og`ng0BnY+Ap8>C@-2twC|v=!3B(9)UP`tk7tg#!a^J{7cWV ztG>|-!;qjg>%aMm*WY@ZB${+8&hyW|%z}kW(aI%OznvGJ|10~NnzKlqI<3<>tS~_gsx{4p4a{-rJegh}|=yZ-4Gl7bdZVc^T$xClcXW9jqvwPz=j6Y&5 z*WdUn3QEgB=b~H}OC~``k}^Wd3SlV+p#{>i4c&yyM-#@@8g1twfRNUt?E=sc#egB# zX~hb|p+}y;t-rX4dwzK}Q>UKEhAo?ov`!{hHlQm-*yQHraro#F)YUg~>W`)(MTk?+ zJ)cCZjpN6T+08b&IW&r9y6~F6N9)9pK>S~)a{g79}9lyPwSD$%| zGftnzyw4Y*WC&X)49&3>;?BEnVfD(d7&g%uI8n` zKFP7;j^$@p-bhnxjEd@BJn;L6S@z*frc5}2i!QsCR;PeVEfl4ES^G7Iju?m)Af&7_ zU1cFegej9wVDHX#j5us4#l;15>t4;I6UK4DkEe3f_~Tf!y`C;5r3@WBfCCRcfImL? zC@F0bH+u?BIb|}JUHlVnx$@^6KIUYWuirwK@&bk*HI8morTplG@tk??<)pPFYzc;q z9L@gwRWWVyNnC%+?WEEcX$)xTF=RLwUhrdnd;OK1dB%AR9X^7eUVaf;SlB8-4sp<$ zxC=_zSV|K@deVXb0ujpR*1PUy)AG+b`tYN;_J%tsDJ#LsDd*aoZYI8GEys>OnsYC? zl1;l>`Nc1PiHV#uC=bQ^zzqOvruDYI{#gb{KOl0!pQS%zcNGCY{Ec@69D8LMRKQRmf#Oy_j&KhAAgb=J!v$%!7Y@h2aDDLutck z7!m*>l$1n>qaD-9du-zm= zh7JE3AW2~9FnAC_YIFRQmeIhArBFx}M`@e16(OSHC@i!LW9bBr2&0kMx*a8Q&`LnM ziTZ{XBB30bVrkC3_!=&`@NCXG^F$C~lt&li>rn#Ww&Tb=v=D@J8c6~~4$8F=mIxFh zZJj`gFpet-lf<p1Vy3pxI{u?QW*tD>N2{RwyO%O}n{q zAZ7Yd=6F;rU@HfSOG-qrw8D~*LJ}g0z_hC?EF5fvg0N7a6CgvlgbcqT5Y`DV>eI#% z7Pf8!ZIhNcUjHW%Lg1<}+NTh6o6$1gknakko}h4XgiDw(K2;sUa9N@qEEGb7aFj(_ zLP(zLb6@yLQ8);2N}4_(mz4B1logg1XjhZACAQN7 z(k3l)iI75Jk@mRWER;u;(;_x<)xzFA%433i*i9(Lq-e)iLguthFmgbBJrf`|eZ($i-3pFxWV0zt?EO^&D2 z>eW3I2|^B~_kWGK-tfs`1j{@EU?hYvu}{j=TJ;&BGJIHp7@JpWB(os;Ynv6uu;SZT z!Ur4?kNnn;eatuI*`^(rE%=Q4?!FIMIf%gr9Dv3}i?Byys!SZ268NO2e*JBsy?9Im zWu@@?TMLj8kE+Fh1#N{*9}0nTHBu*-{_=CYH1i|6^c~J^x7o@qZ%P)pbz05nP|66q0)=YZ6P8di`IcnKNpV5Ef(=i|%q zSs2X^!%Hg&ArR76Ixv!7R!|RtmJve^jyBq|c=r&1FyeIxZQ97|3$VbJ2DI5xFV+u? zKU5IT&IJ(?L@1zc*Mzb}Cj?k|0hw?ogzL0U>$Fb$kL`!|1Ol2A0zp!T3;^*KlZ_6TyH`2s|skTy+;vV;(=L%0W4fo2Q&!R(~*#w3}j!oRAd%1?KO${hj({j zbZ31jDf29TB$N*cRR%m}>1t-$Re;Xuc}fqoWY%3@Q&O8Ul#6y0Ius$Tl~I`hI`~|I z%9@APLZgJ^m0*!AmxWK{EHbG#u6JjN;S#pB3)1y^*2V|9xJi&k0mD0_C#@Z%N0y9N z4HZ0__PnGL?SnuaG(o2GkVa)mfD*nwr~vGYycD2?3dT=Rd4UeH^`G32 zFqIjQ%D}BGPn3(Fq3)A#XEnFSshROmTS4pkN-0u%{hwXcpr2G`+zFo?Ju~-2 zke{0ktE>P7nmYK8pCu#bt6XS-D?C}gpzr-2^V`<%L;q(HJZB(Bi}Gsb5w{0fGg&Uv zpnbm|1a^7?JFU|?t!t8M7b%kQ7M6Uynpn!oa#d)2?JQrU zM+dOXi&gUeA3(JLL21w_6q*!v;L*z{rTR!fBBeAALoXIk0*>-QroXWJN1oaMO9D9K z-8Z8J>MLDt-?*Nw+jo%m7G+0}iLpW>h?9!fv-F$Q#L}*LTLu52f z%!=vD1bHz41y@T*FMC-B)i<^DYnUa=1T;4{ zv1q{p(n_Im5txJ_<$XbFh1BiTY~943rk2cz5k7<#MpY!(4B*u!fkxp7JAf|PJFUz( z)mZ>oppYmL_HN<>dPD4;0YP-=OR`$dw`@!rG=li<=XeO&lZX<+tB&?I19+PZa~RuE zNG#L8835>;cb%`HEBx82zf*B@C!wW(=|A+3UvB2pEENO48d(y9nMTgcn`{%%3GOkrwvh0UX49R|pd&gP^vS_q!Bi>reJ@-FGeRI26lFgetcUqnEJ#taWeYp&n{b6sj_gCa z?BzYPC>oID0VSbvv%!dyV9kmp>}ziEJWbz~jMp9z^}wF+q}I^fch_&2H}_-ThZG!} z8i?on@`TrvCdomk+gQGGHLYnfAWdiJo_#PWz39u}X@ut??a;&mA!VRLni*LVDXpxn zfDW>uO_N&qe1Hg8w`wK7zTyBHp73HfzcViYo=QT2*2JLu&IK^ z$R2zmm?Pk~o5=J<_T_lvUHi~Gqg1lDW*d9=?IZ1d?*BnsLFGipk}~CG%|V5W@ictdJHXih^@BeP{B{X$)v*%6l^x+*lC^CX`Pm_9~=bgz_XQkO$&UF zpo^9%5{aY-6dZ5y%sytyc-nMOnqP_!MErXJNbKBP%B#DgY#ZM@=ZmEWi;KUs3V+Eq zAS)YuWEN`|9i)9||7%&EJI||w0^yKK#Bd#j5Q5UOa;mDTgQzGUNVsl_eGP3M`LJI{ zZxPlCt!laV?wj~v@iJ1u(`D3vgVqcdS>IczJP?#w&IM`O>uNaX)RXvn)kZJDApo{rR?X74a9EsAiXD@PcA{hrX0E*`3 zCfXBDFk7TH{!ugb(tJMWb?*JcA87|1ZGjb`Yqwq$M5A77_;fE>b?Xp?k%8y7cLZyW z{j+qjv+84#hZI7ab`Lz1J{M)so<5{D-ci3z0;xTTcbsglH^55q)FTfw|BKH^(ot_Z z)BZYm27mT+@Vto*qZhI^BN}01K!pK`uFyv3+0${xo7LJwd5)U_i~hZoHh;c@{Iby_ z{)vHUm&|qlg6Nk{>$FbmwEy4Q51tqzwFcs>{CWv*&iaI=hGr_tDwuHkSsXa17#Bra z8CVi;YvpgxJ;(Zu+vwVRFlYYw9J-e0vU2%SX1(_z`|9f{s_f3RpPWy>9u;g~|1Iyl z^(Ncv+lk~9FzMtUama`RDaf@bDlP(P(YR{^FaGT{Ht%kxFq+4NDQ9x%A%h8vG&{C! z=G8aeX2+g-@`|fDZORme4;_H?&oTjoV%O$xdH%&$x%jHvs3^8sy?PysS8U|mGf(7& zXP)Mpb=#<{>dw@&rqQQIl_Aa58Z9)%1rqE6G%n3`+j#l4ne5!QmXOpaCDF>IvA%}K z|NIp7jjaqAb}&CW;|$6p3YBQ(<)@$Js}DbB%A~OzKXxRae7t~<=YK{hn$M|I&td3* zDq>B0dHKb6*sysk-MUpXX3P=1GHX6pU3ob@EAkO&Ea6~lhsXc;Ff-on$>kTHLnPh6 zn=?OVXG4t9V~*tPNk{X@Ll3fTXFYuf9LSGOpF-ElVu}h2u|g(8d3VhkUVnQg+xIjv zX3Wu?c+v#IB1yWfo|j*n$*MIq^ypU3nNvofQf=IO>upq(*!=Wo=hC}-H6PCTfKNYP zK$jl-aoQPY(Wh$>+c&Lc`dc&Dx@#|kh7MxHA&0SIs3-Su}*Ty+~m`gh|O=buDraXvb1BXxp}YuE6`J9B7jZ|CRdj2W}}`rFkc zlkN1~e-u;Cm`Z7W$eeI`v4sZMx(MO2X8BUyoIaD5lxE`ODRj#V@yVivoN>X$6o^Lt z_Uar)966C*g${4MGo2-?YpAU3#-t;MGv|XjTyV`zR25mQS-qMi%eQg%=@WSI`Da+Z zdJ{dm^2(5(yeKcCN8mt06xH1ql!b2xDH@$6S= zGkewte6eIL;c%2oFPuhomr|y`Gn-{!FQ(^!!Tf0IG`i#`dHT8688z-y4(QhvTWb&w zI@Q43d0+C;ysya1%i)Skr?GU!T2xL~ju|t8hF!b(+lw!7-c^@VyQ79#Z@tCNx)%Bk z8_798Ig>mvKv-lQ6Proe;hhtB|8yq^?6gknv`)*me*vk!M!PXSn)x^WKJQZwA3L61 zyLRxCv(IP!h8ohI=RyFskPPb6gDDe_Vd3JXJofC{Xi|JSZyw)%y^iC@9z)HBjhr%h zG7Yg5%NH-^?N?sn(8EU&u{Bp+bsZaPc9Lps-hG|Ruegq`-Fng5+R8;2 z|D2lbTd8l@%^R=3#i&C@bI|YuX=tqFFVDV0ePesz9Tn0X08cn+5@%g}IbFL}^Z5tw z@bx#}aKwaD=+(C$!b&r2NM9zNcsw7>{yTqp?r$U&Ecj$T+qP{Ym5g)e%{S9j-^?Kg zkK&$t?q&X0D{vAqZn^qWUVi0eMjUoH)m?iSH5B18W$LM%^WzKX)vbc}X1>Ai9)6UO zqYq>K`t|(c7gv%%v2ej6X1wthZXp(L<-Ipw!-^J=CfgUJ zLAo^U+`x=E9}ojJZ(Po6(`R58mQqrb!%4@Fqer*yTz&N~S+`@Cp&e2hr4+IHT3&kg zDO%gxS^m``F8s;a6qgj!xA%VR+EZ&(Hw5(R+JzHOIF?krjXQpQ4+$)Ul=Sb@i?h%B zDaV{J8B53c`|S7FRo6gU<329``DLVqP2WC!x#rp%`Eu!MT3dGW&_fSXTG^e0MvUMO zzk8UcpLvm_@{f;&=TkPaac%o*xafjQuKkdU*?dp6FF$)7}{sCaTm`&`wYDX9L$m9 zCX$~Q;!l6Lo44P2o8yl?hW9_1$K%hviAu$JZ`KU9?)5qU1h{GD&3uQOZ@iHq!wzEb zkfDS`3tul=$d{|Oqb0QLt7q1muhW`r=abJr#@ge40X)QH-AiF^>BXs@Dr5SiaFC~V!N^6uvH81 zNK}JeTE>{8j$-jw-!Oi77nUtu!bunW60Ib;#pP_T*~^GQU75LT8|_Nr;1K`=Xp@b+ zbJsprt=Y?qufIdDsyq%H(v$a>{tkqNvZB~IxwJIZGJ53xY}v9Mg^P@Y>9t=^#tiR; zY~9KAe|eeS)!5lQGD}`svok-Yx~hsC6{BwV3b6C(KYSzycF|brUA*%A z3!H!b?VK{{7{-nq&N*kC#{5OgXtfF{?=ysnQ%**ZBHq?QWvGFz+tyLpr5nw( z%|Ro& zldn_A_-3>ho4D|kFRAJ^lnbu9f~p*whWch6yyF(0eEc?2kzx)z?sN_t(go3!5Gu}V%*t^p@t>A_%ogn+QU!&;pW)B(}6EtEe!ZPwkjU zrgV(^Zo7rYo_U+5+9uL14G3j2IJFYsdGOMSIIRt>RQKwQD*#(jRbD_tV;yM>8=hJJ zER%tWN4|`gFrYP-M+;)=r9oOKk9SY#G%q~;BESFr6YQz2Bi^zXoP-y3DG)d`G&Ycw z`J~bz;)ygTOq#^mKblCgrJcNJ5oP6--V*G^PrA0}j&ab5CK{XSDJUsI1I2kcl;(xl zwQnEBA8LDW)g~H^aK!MQeE!M%tgor1sM|1dqmc~Pp!Sn=Bs~TU#7Q)>as76_TDFzR z6OJWTSI3>V+{J<~zoxCZfr!(Bt2D00(_PNQwrQcMZ)~A^_dZD50ykl_tbwhoS8&VC zx3g-~Zqlvw=u`~lg3^MdE4*k_FIQQcSi7CucT-eSiWLqcg`j)aD)#K!iY8@}gQQWo z>Djf6bTWpc%w|JiWl}-3!`Ag{DX*%)3R?)Ny?8tY3Z%9{NJB3pyhIXdnEJE;5zgi0 zv(9GqiluB=xrv6BIKu|_WzmNpbI-5tX3LJUB`>L(>NXl4mgBtjiVe7blE7^ zF)@b99L1)zxlb(CPD^VFCsaanOw(__KK$&Gvrq`6whZT=*Jnz(G&Z(VURgyN543r} z&2{~I3zXxa(g{O`qzwnBPnV>%A6Y9ALUj0}I{{#)by}x&+J9(2CYBV@^N{Ln}pN2|BwMeOB<62X)${2 zk$m$0EIyb$hoJ`_h?LS}m&;1s(Kh8>`Z9Xh0G|BaZ`j)4aKMlQiP!BS*3`(A*IvV! zKmG|_yZ1y$3#lE_$u^RX#?gQfSkh+rkbZo*;3Mkm>Pe*qv6M!+nvH9gQ&rWK^Dn-D z2~(z0QdEi*5Dw?i-c&~{mLQRIyc{M||NRdf!p?2$X{p^uthI$DE52p_kt30o$sjlJ z1{#Dy3k^be6hzrGC&b}L9LbJ#t7)#QC!S1`Oe-q7mebx^PyL=+k|`TUcN7J*ioUi83VgDh6Iq$+t8Gqu5gu`JZkdrT|uiZ&3ktFVD z%Da@2h&8cq*Dg{iiA%V{yz+aXu(X11J-XAcTRGFFp2q2?pU&~)MibVp)Ya~!EtU2X zLd^Gib}wVi@};C=F=BBCmwZYpy0CZ4N|Nz7v4o3be!1B&Gz)tJ5PV2Pqw;w(+1ha#;l*_jZKjDTeucfVS zJ9*s)Gv?@tlt&c>;S}$G^eJN}v7iV~001BWNkl80LU|>J~ z_~I;%IesFp2qA$kT`IZ!ic5L$-n;l)WhIGtf~u-Y@=HoM_reQ!@u|mHFsG7jyY?~U z$Wswkl(FN-@$l16vtaJ0Og#Q@F2C_se)F3LxcZWdiKjK)_CJDyh95y=!(K8p8A+Bc zp3B5@ZsYGC{hfmcb^|RDx%r%V?pZwX$3O7i`*XSQ%#(nS;l?u!%!L=6&EtQ4iEr0$ zBGJ@HNw5Bdga8N9DxdPwZk#c36t~`TH3bzt$c+~9t9$OGd!HU$`qQ8A>sxQ4qPjnM zIXT>U=QSL2lrlPvxqse#t|Bc!*zoKAXmvV!}CBFt|@|Rxe(P@Tg{d z8tj3?M$xsbD<98zhsR%=MkruS&hq$JQG^mqJ9#3?LhhJYk1*Jh~#jryUV%Xrm+(E1!Gry$i{1EG3Xy884nN)HPPH-7tM1&|v2=dD{7WvFui^zv8Eai>f&0xDz@1 zgkkJIq%XHzeKl2OIc(hCOm5Uu(9ve57=mj_QGNlVhV$@bH1$e%;knmlm>qTQj*iVeljh zEe%>}WPTC9y7LYmd+HSy%>4ir$>W@#oXgn#i@5aS%Q^qLKQQ^|1Msje=brZ??tb7g z7Jm5+d4(nX{1@kQ*pcIz^Zsr8?BYvEr$ab7rC8xYEEz&;2O(Spt$Z-^ZJwL8f+rup zmq@yvt1dgABc}d>i_ScemCNSyG$*lH#HQ zaN_LQvzz?N?ue8_yseG0E@eoaq`sk*aDFj)mP=hzD@A1$h-4cru@psR<=84sZCw-j z`32-gAs%ySY;Hj76qj9lFUK5r3_ri5v9T3Ui7 z6{%#Ly>+d0sjMVod)i|&iwlbLwZ@mQ%Cb&bs=QkrlmLV0B+VWH4Yocg9V;t3bqwkfZyK&8_()Yqec z(vlLQIU$;x8)$7y5DG^rE-fVzlC-tQh{cnXmzN-P3Mm|L9iDvZHRgZ$4S#;}5egy} zmUq~Wwu}c@n&cbh#M!&AmT++e#d*0{$|2U;Mq^tmt^#S<6qc8hYeP#z9Vro^BtMt> zeS0Xa?m@&(lWcFJu{lZFNn?d`C@w7{*HSb!wb0g{G#S>>T*@lS2)QYmnp$a&#R*3u zRF&sZ*U(IEVLAC>K_VWbv8ffMT%v^~6ciL-xiR+EwNhMKPL6Gnj5pKP-cE6OHQ-_k z%don89!gw?csx#1OB-pW$SW$Mv>-%07N@ZxhSmxhiBM8jMo6{N*qo%OqKlDZ(*P;j z+v{m)h03aGql4@wX>4qvEuKOMO(?g3;?ffAR0|D_EyPohS6E0{L4-ssMnh8!rCekr zhmz7VA|gS3V;lLUmE=f}I*nE?P0j7J#N%jTQC?a~UN}u%Lo3n33i87Sq#9bB1TD=e zT3X|1DJd;4B`0jr*4#pCYa0TKNKOs~<)tLr+HsOe%F4?SxWro8X-T`3loVr;q^W){ zp}Y$6a>J-(E42-2%FD}$gsgxazf&=!(>m?@?Yl5Q2!T=xDgOnzqn-AD-Le%!esB=z zIw>sC&hPKOgGIY?c;?C9QGgrx+l)UXlNl*dCP3a-81rhYGrCcDQEukHfb`6JiHi(n zZpN~H4?vo_y}Nko*}sur5M|Gv?R@yf8lHaq5uEmYG&Z&qR89*jx^`#q&_RSSf^z0u zIlCGCvR%(nWqCjQ^vW{$*;CBLm%q|{C-^?NuW_IFac2?{NX%v5Haik3BaP>gL2I8l z*e8Wk9v_`iip6g`)4-Y5@<8zR&1;$d_Up`=yMo_6ct86O>T6=P0*<&$EL(<;uH!S| zlR^7L(ZcJUtYiF4x`#rj7|RxY!NMiqGIQ=%+;iXk95|>Kt&O!TUAhd{BeO;bq-8U7 z#KDvm6$CDB@tx6~QQGjS<+8?+_F_H*Zb8dy2A}xb>R4F7u_uDI&x}R?m^3p+{gV7o zvpY=-g&@VIjq6yyX$O`S3dTt^TEJnW55*3sinJ$NXL<3PnLd&pDAxFO@@ZxuV37`L zV|7sM3H*=RECQL-imXOMcT@@SL26K_xloA=6?!0F=qHx=8NEUV<4lQ6Uu61B1&JRS zB^mE}1zKu+(L_VOEinJMDjgb&mP}U6u_3fAHgAVTC|PIO#{z zI4qq<1e39AUgf@snbBztUi`iSTGrxV7A%WQ%7>M;Q28J+i$m4}H~}Ec28vn`jplIZ z$YInswbHB4ew=mD74+*-#iGwvQCHhyg6%O2eyE^0z)L>yt+|J%-zt1GCe6a@ahYj+ z5?eoJ%)~YdzoNc0n)h>nExmg%)j71c$omVW56FUB zXV9eggVHXcP?(;*2XNQDr!%nsepntd7hc==$uqu=ia-Q3$o}1fKJ`Ft(4Qg$BZINx z)guzgqqov!M|E9ET1vcv;CX+0aY+fJJ2Kkq94# z$e;rLCmPuS>-cIa*{Wrk=Fjd#|1Uq`!@tT2%0(E;ZK)xdXrrm286`~nDFo4cmy|bp zEHB>AJ1EAhhNt@CKXag%jqoJkgs=D!^n=Q(oBx?WYk?MS(1ZT-X4)d7LSjD8>UDo0 zYmW~!7)aTz6Et2&nd@u-7<}$OQAXD}C_>`ZF+*maIYj^OTU%QjH8nLzOL_??86ccp z{y*-ZeUP86T9Sd&|7iaw_TYZ`9q;d#pBdlZcf0TX@c)wiTP-KP=d=G>*%`v|tcm&G zDEFUfoy@iW_I*44=HI&R-@5B}`}yCiS;h(S?~U8w4eZAd3qjYeT`4Xu{&&jmwEs!= z!+Qep6e2t)n8%5Wt2LJ8pi~ma2@?w02w|2sltqU*o%OoUS_;i|_;@Gtxxnzj2`M{# zv*S$2tVsShO)-9kMaCoHLzxVtVfK3GJ&=|dFPnp#N|C}Q6ps3EB6tevNv&xeB9&Bx zLN-!n0T>@Mp%6l%wTlq`-DL&@3hxPY*2K7-f zTh~<04LmMh=~=DeKV#avUnq0Trn8<8KzqtC!gz3W2F@USZC;t>h0_`z_8>AU(0)BK zfHMQaR95{0Anv+2ZWfXl?od?TuYYhvP$q>-De9`uzI< zfa{GjNe1{TG!BZ8w=Ggec}7d5$UK`!r*RdyAseJ18^EAYt7 z4n`P{VlbWkJ7*Q=*TL6v7JeTq836SEiYKt4p@BEvc!QSKW|B?bEN_!$Xs4vk+8F%@CbH&?)*00$DZET_p-|pS)#y!o z8*8aigv?7->r7(7I=<&x;m=pPjWi7K9 z`=9E}QLB*n2djZXvCdL*^%kUnwv6oKEW=;-=3k#dRQKk@Nt0Q>Yys^QFzS%ug#1O1 z7<+eY*-f;pD|wNyS&XvXj#keX_YxQQ3qZ&_>Nn3W09z}=@#wXYlTPu%6OYpCh+`Rb z=)r`v#`2EQgJWPH0J{Edv*tz?C=^1W-847d{2QiDJ)Kd99fH8}pD<`Ub9qNn=4?-w zX?BIyiiXAp3QG#GYzwV4Uw^q6N5jE~jlv4LC)+Ffo$d;}i)QpFL@+jk?Emldynp=e zA7W>(hndCkp8zfzlu}%O{qEP#(*yWt)jEqUu0(H|FMXx4zEbB zbnhs^f4_mB&7Hk5$u!hI1ML3UBSWSA@BqJnf2cGa`{$o4zhfExcHLhC{1XapAqgvftHOfcVZB@6arsvqJgn zq7MSa_x6duRWr8`-|6G` z@1o7|neyhD&YCD4)*gX(9Gm?M?@}Sm_r2G^?wT#sH#VcRV#VT5S+sN|akA#2O3~W5 zhcA|_BJP48L*>6NK%w0>9=`u>KK^2f;g|EjtkXfA@vhB|{qhe6eRW?y&a%C3Hy58X zm1V2flM2AJLioE&Z&CL>h^`R0o=fJ7kLR*s^Jb$joTYB-?{LYki`OrWjXSvZ#$U3d zK4#(?gNJv#e;W^=L2Jg_qH#^^TLb#)S-qA$&22$ncyDxbA1B7bd9(P#gO8B%>*&Uq z^ZsnM)i#n*0CqYKBX7_0-Tuk+nc1!j?-<`~k{nPPl}@p4)pB;%Hjjp2-mGlJR$OQ1Xd@0r3E zr0!754(}Kty)j|#=elNg2W=uuh>jHgZ1A>HuK!Aw!P=mO+hI=@xD|vM^Bvm3f58PO zKq80%HoyM9hs%^IzB?KG{`cG4=hp0`Qu<$MKe#8*;D!`U4ZGR3r;em6v2*h1+N~SK z`3|n@;HVHDfRAU`5#ZraQ4-HpUk8X1nzqjxV#a&m~bHnXE< zGci}-+F`nN?Mg*SAw|9WaK*L1ptK+lH_^(bZR?38B$gGSs#|x;N{WzZVr>m<-?58C zQlld|R9APQyr>XMc*z?8Xkx96Y}-~tw*mW85Khz5)J{`#lAb*(*}8QDjcsYHNR*yE zx>FoAeiflyY|CQOsizYYCFB5ZqKz#(cF^9kn>~AKNxK4}AeCrg)28jDT}8N{h(0~K z5!NpCJGZfB^=hihi|F39lI|5n)a~2NzI{!&Ru0|&Kla`{I*MxR`~RG(>h8=5At5A? z5avN<5m6LHK}8e>Q3;v@A|FxuKV2Qx1Q@+D=SlV)u}V?z0Y@lzqz@jB?Z6xB(;PZoVti(qjivj`wvkXbcm0OBPFqd!o&O6 zuyGxw$CGK?q!B4`K8_deqo}A1E2$Rs^72Ry_^2!|q44m2DnenBQj(~ZR)qLtz*S(VFbMe5U^G6>@UwVB&D<_#q099mk}EljRY#VW70bp#!@(SrWqX#Zfmm zkMzUo=2@lt7ETRPGyhKdIUEF-22WdV)iRM+iGUYS+o3PG)V)h|6VH zTvCp$9pX}Ik(--KJQ~xAMxRY$kxgAi@u?FO7M{Ycig2nV0?LPp5DFD@@L(a8A(L9^ z>15|*VX6q?2nP-vq`0gSGd_`q`3;CSt2lIEAH}CbB&K9gKQ9}@iy}ISy|XsRTS>u!KU@= zIaM4auR%V2uN^={Iamg0r;Ngb$0;re5ucJmUcGt*Oq0^$LJl7}Nid@D$H!BzK|ZzO z6=kQ7ao~86hK(AM;QLcz&VT1J72OndG;|U*{1p-ja=Nk#BR+}bfQ2J&GLEU-2&C4I z`+4Oa&8q0lwcYTHKA@tPy#Of?QlD*mS`Zihsu3`lsrrJPfcFaI}NZ zG|-VC<;BHFLTwTf;<0K3s{Wsf{OP+LrZNSm_J z95JOGa2(33DhY`}YI2fGFs~GbQ4{h3uCpEi)9<~v=g36G=e;058K$c_*X*6 ze`NXh8-V~+GUwB`nfd8bI-PqiCyyK;Eu#UGo*0c`RUa@`R#h;6?pGW+TExcPMf4jy zjNyYW;_J`n@Y$yeY0;)7d-m=nH@_jzO`FQ{9~U$6iN|T%ts7-UhcS~fd2-4Nq?H}z zv4@^z>KpHHXx9qvee`LXweLphp%kBtfZLFKl+$R@D#sq+R5GH zpQHB$dDx;^zG4HVCrjwvvpwa7CJ#LRGTGT#l$RD$JF5{-O}L9t@H8Vw+((NxXOWjz zhZfD7a?8Er`DyVFv~8LP-U1^6zbs!v!NF4uzwUB2{W6~!bAF&nyYslPb9)-}>c$td zKjCCq6+5=drLO?wZJmYmG)ox2$K%u8I@ zz7b!%_ZlD0TS;zS9vNxzjJ@YhzW)9@=FXc(UV{c~-LRXXw+`j1Yp(%O?oqcPEd1tc zzL>j+%zC-(+qIQG!^Y72qK-^__%V)49Ch+qFyf{gNpMc_$%h|MTB#{GT*Rcw&ykx| zi;(SO;ljma*4x8?YX|b(><=k(f;{@f6D*qhci#W-bF%9<;>6*-T-s+4!)_eN+>bxt z{dvo2-nuOZcW)r0X=na6czcZT)dk>~->wHQ|%W%vjY9$&dRZiLQB4)kuEtg$)9W9#W z5?7-Z|832x-RM>*ES#CaE& zKsbqMlOMuD+^O_`HF`DTlrU}bWOfIWdHa=#9#jXEp$MKj#Mm+SlhWcMCOmvMse%7X z9mPf|p~{O&`=jg-D9|=28)YbLF|d_^X)2fd5*x(CP(F{Bz>Q)W62Z0R;)saH;UIvH zxW>K;cxpS~S9m8}06rY$qRlO(Kq4L=sSoWbPAM&zhWi=!ZLEKy?f)wOD~kM^i>+JS9F(oE7r>C z9V=yEziVXI$r4$+WVYOL`v^H6iO8XXHPW$LFZp5RR{8FWSQy72nIX zHx8F0;fTC2{sEc!&N~vcLo)rT(elvLnX>u7e(BTwJXyPYj|3y9Wy`vS(!BFEvg=T( zXuDMGa7gT`BQooSNpjDVvm{h`M8=G`PTrjNqf|OtoZw-(ZNPmx}EKWzn2Z~8%$@g<>^rtY`uDj?juaM3 zq^eAw7>!e$!&a!&fZh7OA&t>3sL!`nEO4uovva*wM<>gn)`mNjL(BVTe@R~ky z@N}tEiHO!(M2q_s3Cr?t-jeHY8ZM=x<-5;kNxvIMNU;{NBS8sAf>L~}Q2O=gDc}6M zMiwt!Cf&Q7Cnu^ZWcQ|3(jd(z8xHM}36DM~w_HC+N-KjB3GSA=N8K)O&0Qf{wAhg< zv7IW}w*E)y+4lxHrnSufbh-?=?QS{hXbC$Z(ZO9Zu>Y0v!`jWVdeOHsXkdTYeX3Zh zDvRa*hsMj`n?^~|p>@*v{7YozhQkt$RLM(|o|mCRZ++~+D; zzWjFy*x;mQW}p8#iv0 z)2C1W!>?t_mc_0;apHu`m@z}N_U64rMC-6PPEZc5`9?C*lI4v#OJv>8Ur0uBk_>-f zsuZ8xBmJ-FDt^Q9mfr@SKvcdn8A`dKpb z!*9Inie&LOuS=4ZDNn!hp_~-)+EJhJ%<3BGfAHI%i?=3fEwLKL`pNr{9g)L3HcI3A zO=ZCKx66sDh*XIq%jUl;jZ+ilk*PDKw8p!+PYa8P9cvFqL_|m2`4DRZ?^-7$BDVWC zCnCCXzYM(mB02xcTclh>BJND8(Qc75?yYrLbZDPk+v9xceB~`t6|J{+MB5=bS@63w z%m_%&L1X1;P{h$91qB5%`MD{gV=oz!%927EIqU{`@VQr{Qba_DL?k3yLLxdO>wo)6 z&hOMl8Z>GwuYK^j1VzM_Dmi&*i}dZ?OLBAa<>{wil1dSAbd?0l3uW|(Tcl2A9l7J~ zadPZbsYtj=%1$4XhsTYTy7ls<|Ikr#q`XQT9g$FJkvuZ?PHB)=Uj|%%s~jt}y;iA` zna@v@yqvnyqi0XqvSX)I#@eDvL_)FF{Px>#<&Qu9_=i3HSNY#lv}X&fSg}I>{S+}? z#-L$XScZjZn)u?9xVT+&4j`m)|B7s^n;iCOI?L4RM<$j^)Gf z8`R56AtlbCqM{0|OtdmEOcS4BkzFT~U@(lTYogE|>dXb-i(!zOo=Iv_GQ~wjoGREy z>&~4BB>V7VV@kx$uoH1J!=ji&1mXe=8gc{kSFY#8`OP_W@Hn@%Y|O!(>zFv{S&mnM zS$33?xcV`a3*cp#xzcN;+Z8j4Uw6^9QMapUb>F)TkmL+IEfo1@1H$!^&OZN-6UVpsu`GDwRv&Nu=<440b6 zFx=w>Z6icbhJoKS@JW~r%NFwdE3*g^Px#a+Qk%4M5qXv%x|~D%cd}-~7KYt6ihy6C zw5HP~9XWlf0Lwr$zm!077EPMuV;ZKL>njn6Vu}C>ML2Na5Z5%yMNE_WIkm}3)oj|f z16vG4{P;~bn>s#D(Y0+IR;^x4$hWSgH7AEQ&AZr&T_&33bzgX7C1V@roBh#*s>D|0TV+T2sV}h zrwaG*^u&o26qOTKae~6r0S|8H_OfXx7sDqGN?gV1&71a+on4QVq(po^MTb_+`1OYu za3Vv%^5G~SmgT2o%Uph0{WF!?aSwtGFZ11tKK-$FHT4>vPar8CD_BK5HgRS-r;3Hm zTeouCjW-g}HnxWL-P&<*{}F;AO|#~WF-;T8@Nw!$0VStT@WkU!ks2^Doe0f4cEG~K zz{E5K(Uol8ww))R7*8N29_$D$8@I!(0udjUFAl?0V3+gGj8|E(^cM_YGW)g^(C*@k zUA1kc!8GuaE0KsM4mf$_C?|pz`Hfm&Dw}$_b#b)KkrPE|9K_Kw1t61gQhJR zIOIlp_vy{C!~58=>i`|QT*jDDH`1|PV-_s>f#QhC#HlZn)gYf{`8m~aSX}HTQo){` zTiL$r7!|<~aVe>^YTJR_dRYX3Q1CQs*KOi(;Yku|WzfFE*<{yFzz&!2`)?aKbmSy) zDJgV3yCW^yoz37I`g7^Uow4lGgv(Fz`|m4B@j0B|r5UX|pU-vIUq|Yepjp)#( z6$#?5iP+Hr6=ct@t!&=5kMdIosX&2cRp)JZ_&m2nDA=-s7bj0;>91S3qFFa0KpfGd zU7M2PlRP(hIzxuvNu&H+rcHU47H!+nE-#h4?-)sb+wP3H_fDR9>|x?^>T}OcJ$UJ< z$0;U-xpP0`%{SlXjdwn0{QcMR@kj5o{Xj8uzW9VsKKX(P_dm$=mnSgw#p!I=aftUm z{D4p2`H)A(j^_DSr?X+vH_ZS32j2YPBewmzkmskqz{FRlQ#a0!6^j7=6$SiHE&u-P zV8P`gi^22(3A3-Th}L<{QK3rwI)t*z`FhT`)N9#=`^VhOFTbqhvpEX^g{>vV185Mz zAmU-76(R=O%OI2}_}QaVh(eRA$*3KdkI>d6Bqwp;z!q2T3p|6;HCSVdw%}#4Ce!(X zZhZRLBg}l;BCAOUn&j2v-N`eEPfFv}X;UcLww#Htf8%|`Ky)k>1yCf#`@t^dP~kCB z8fCiIL_+9_(@c405`)K0W5_iZF#Cg#*;oXKU|K%HwhKn~`4dU0mCCMNdr&>k10w7@ zR!q~>+AeiXlsZLufPR(e;zvASyQy4F<48E<9wKp-}#feiTBxYx#urU07EJFyF zRbb=8YGLaS9PQRa(XIvIzCEGuT(Q9}E{*EhsDl&hOfuS?_(u@zVy4TX)1V zO^=JtB~noyuU_5UhO}&y!6$FdV8_7{`rmdAMMn?w%kn>Xe&!q0inADb(@>Pw7|KCA zRUj7P2qNG!;%Jann}Xe2sk99eO+S_qz!1fTmA_L`UdcO?g(+Z}imHkV zcVE}qr6Uq|`Oj}yho9E1A`}jz4cK3Jl&rj_7(O442Ce*P5llnl(m&LMI4KWHrO9iQ z$I1gIh=gt8l!YS@K~Xy~k=&e2UY_+PiAez$y5RFuw0kY4Asjt&l)Q{ufF`+CCJ712 z+&A_Oflx(=;(v1dRp06!P+N82R8soO3}JEN!FB1PGR3YX{rWK!md5Nj z3{^9CRJ-eh9YPT%g5Raci8?_Nc4xlwV-UdI1?f~03MYan%8O1i|C?{9-{wLZou5I(QLNv(hld||j0t0J!l|^WsMJh; z{v~o6G~&%>&8e4?9PMBXQHZYM&6lR|>g**10&cEEo3p#~&c~mSo8~b6*$GU0`x{Ej zEAaaRT-JXW)2H0W@_C;y`jP4Q5)w&BPG#ClFK|{`33I;vinDrLN866ch*r#={WU)= zSi}p@jiyzTT;_cBB^O?M70vQ8nE2pBeDv)Cf?yGuvxh~|Zt-$jqPl$ERh zVDPQu=+vbX@yh0g0oSr^WM6*#Z4(bX@+=o#*qmmy{0ts(I|WA$^U@o0xa7)#T-v=G z?HeVqXw0(|l~htUE&%fHg;)Gl{{L70$24IS!t!NHm^t$u#y>uR6`Qtm?)eu}Co!4e zi39A|xRLseTd{8KMt)xQGuyUp#xyh{9vGL1M-$`2!E!Nf%F74_P<}T$BN~+DW_1CM z8$Tjy-Wg(JmYMZ* zJdAjsLE~mk*|u{#KP~-%^_#c4d3mBpNlW49B}*tPsX!a$^&G`AJWvpDbg8c{f<1;lVKaHC<;oFaAGyBuO^ZVM(3?FqDAHO+^ z*I${%!w-#T?}>6cb-WOt<7PmMmwmVV*Ck}2%+2Ph$Dice`3rgfqt6M3 z!Zc}`Py6<*7(VnyKK}44-hJyswC$%sP9`r+e1P{q_>?^bM;JPM1n*3Lg)cw*jHf2Q zNLJ%ET+pdKmQ*1+?2)Dj7zSr|y@>MTC;4FJYjo<+;ta~0Xa=%~i7&o31N&XYjHyqM zSUZQD>>N@O0*DCTe*HDemoKNdqKtqE>8Z(-mY(Lv#Y@o2?~WsFa@WXP*t~89Pd)V{ z-+#G)9eWO9i6T3vJ_imSWXaD%}4LV)i zm6FmEOndQVX3d((oVnle;P|J&j6<}8q1;T_C^MhymFXI}eFn-(;Fdc^Q?PX%QzlK} z^RK>PYe6AGfU}x5BfDM}qeqWs&ez}Z?z`_&bo@9Cn>1m-zpm`ZRq8fNOUTK z6G5s%0c+N*W%VB` z@CW?7``)|!ylgQSbnA+t94{KG(2j#+#4+jlSJ<&@E!Xw$i{*qtYXWA34VzZ;#pm<5 z=h3Ixw|6`3o7Lm38E>&`-yzCNibzPw^hJ@7n$Fm< zBk_mI>DO-nhbtn?cxNVUTC`-;$dQb?^A76Pt&51sWxe~bdD|9VdFfe99JGS*lP0oq z*>_YH6|!K#uT)lrC^}L|!SzRE}qNJ-+#i|4V!ps@>CZ8u#l3HlYBFOK1C&E z?AW=TQFn}D>5}i5@Wcc7EQ5$+)3y7h96i3DVb}L#{#W0y=g48c{PGKyFI~$clU`)s z?u}$7YCe2-Hf7~59Xra#&=vf&Xd!FXZ{zikKV!|hRbi%l%Z+ayg8*Mr5rv~ zNLhtVMx8p?SftgeO{DA;*p-|vDJ3a01*IT2D~*5?qG10XN`ji)W-SrzP`7R}rc`jG zsF-a9r^%?>0HtjFiSFrJNl6X5r@xYd|D((QOm?txk4PKl)MkM?EBdwlur zcdS{rom$zA>D8?}hLymOn{FZ@Wf2GWZJ}ZA`CQVgAMe%5Vfl*HWal+w`l$QJtDi$j z@d>UUcqM^=AJF9G<#XRXcT+n(C6+~@;?kJ%>YL2|dI9Cf4`Kyc(DuBGY3L-90GP_; zfk*G>%Q;`Mb?a6vGlc=yUO}p5QWXCdBRcy{trEL!v<1-rJBl35o~3M(;%NmF0s zyM;fod+$zC)6y}Ma(R5h!_52oTZ&E;5me`JdGB^4CnWR7hHbR#d@j9vUqt|mbK0~f z)e3k~5(f-}T^AR|M53EwQlYWT=CTQJk=5rv>0?cryEZ`^$chC=tV-nA}y;f z6Q7yDk4sjudHWu&zWx^4p4E)p^aP%o{47=BDpE4Cx$FMNsGXcjo!t6-{MlzLT)ddI z+YWJM-)lIpV`J*q4)DlB53+j0Ru(^p zZYBw78BBX=8sC4vnDQ!{m!>^WmkzC{syNEXTZd3T%Z~}vZ`O)Ig9ejq0TMy502B96 zIfbP3MBaPjd45>Dl)VK7TsiPYI=5*{?OL^X{%^1F-QRzr@Zdh;l9Py!i$nQRd4Bp^ zeD&?u?A%>|u9bxusKvymC-Cs57V8tcS|N0wgST_?B6JLBPugsXl_X`%YX8l^u>Uuuy+O{RtAIH7-kK^0# ze&ERdeMq}@oZqc0Av=tv3`X8Hg8aty*}8on-3JckieA02MAN=&cPdpa{Ftb?y4-j7 zDC*bGBqQxCZoBmsQd5%<(O8xV%HrBVgQ(NAJ)#`4v+6M9hU-Z1#bKxjJ$qeAyO5uM zNiMP21WSu3F4ok_ZcbMH`q-5_u?#oj8#UFngL~>=1aPc445h(vFttV#k2ZbYh=o|F z$Z)e|l?5T&#vvYu1kP&Rf`-{CY}mYp%P(xssj_nVbnQ-3N`Nc6cjful7gKn$oFRAI z$U2qIt)_Qi?z%$npJ02|5Y%=-roE zwNhx;rYXN{{)1!3k0Qzd;t-{1*QOb%rbB6QIT0WpyzqenkC>-L^Tu>+ox_$z#q{fO zDYcTolG=+D5B zoGjRbQx#;^t26j0DTyXc^2x}oPyM`B+&TI-K6q<7pL{u&+wZ=YJBM~gOp}NTU>b@> z^|P?Tm6VhebNFxxVG%lZZkB=kZGY}_C#C8zN zRjM&flZ1o>d_Ex*3Zc-1!y&}5z_bYX{ouIIs0!OeL`X_X!7?FSS&1_IM8Xb&NqoRh zLY##isYEH$%^XLtYVQ1hMFRh$%fH$zRnvU?vp_7~EoU0Y0D21X(h!vrd-6kzx` zt3wxBcj)R-R0)Qa$Tj^3agCUWHt^D~h|kOCj@xfTw4y;yCXTYuqOjuA>D%X8`YO}S z3eyV9Fi5V~kUQ=e?H=D6E^)6Go7#19x$U-*IJSxD84KrKZ~^CCaFNT9FE)l~(o@nI zJfJU*2%;Qv^P2O}*w$_bL?fD}k2<-HxqHkQZ@~veGsL4dMp*$9NLKTZ24$=_C>U9cd`2_W_3OL_8;t0c{rN;9)1+<)uT!CHZ*C`HnvfV zfT@HYS6oGpEBb&ku(hW>;!oi6URQH@uf86!i)P@!8xZ9x)ii9>oV)I74$8z8{?jBT zW^n5*!(uFpja#&#Nvoy^VH62O$$g_y!YT|JH*Z6;7Og#oxoUmwTG2XD09A*7$ z_BLgZoRUUXn#s-sTiCOE4>@KcVKF^$oW$A|VNyA2-~gW)5jT)2#FnAEACLBK5GhxuR8WY|EqZrg>yE?999%1<38Tv0)#F9lciLgBKm+a3|StE%D{raONCd=_=Hvr)>R|KOXr?Uo@_ zR0#pUL84)E=eWlhG3ri+k9>ePXT8JCSGU42%vdEY1my^(kw|uS9TE)1hChDeoJJS( z>*_Vs$vzujyg|SZWv5S5Y9x|gHya~Z#FD=+WZ>oPsEjItdT;G0h4$(fQ{DECi(*9W zrgk?rUjq3Jn_-`Nhsw$z35LbaorPS~?P?mt zPC5meiuP^KR(SoGrTxG1784>#TOvOP|BKWeYgFVPF2( zcmVNdke6MD%Q`n=-}beH?S53AtU}vDM!E--_%A{Xf0h5V@;^cmqf~(UjoVU@9`Mei z9V|~yNm&Mtm%ia*@!UiRLwm;%HOM;!mry$5VTDAZ_&bf*3T1iHZk`H-)*59fH@U>N zQKp5h9V`>dD=PVU`AT+u@F|J4YVpQvf1^|T=8S*%K~`VyMHYPymAM84xbubnJ^63 zD2^(yD8Z9XR563fZEx-Ioq5zuT2N;6WkKmE_nA9t4W(mR9}L0};!WrgH?t)Sd!}g$tVXj#o{EvfV}(F)gn_f)Hy&k1p zUF+D$`sa#>Aoz((sn58_9^kHVPjO}UZp2FvtV|O9X3Y3iI)W%4T5Nne=t(*Ha0~-Q zII891HEUEVjo92%2zz&Ip>wBBgeyyF*rXk!Mhv5QmY>0cuja+Kzot=xe9VBKo_$Bq zsaDAVu8tHdTTvjG=ecpyF!P%`F@z?|RlT|mH!^I8{4jD*RqNY#ZD|zI;d+F4s1xpq#;mH{v5TBgFxJSnG z(wpyaV&^KBE?>onyBiy8r+n07*naRCo)vyRJA|qby%+M z-!b~#&=R#IqfO?um4j;z3a&PWs?k?o`-sGB8m&F!$*YXQ3!@Y52TuY}Tv)o{jTslx zAYKH{tWmq_F;hKYyzzKO`$dy=swLE-u}2-PpJxo#Y~PxOXY8#ds+i#E$vU1Ew4prA zuW~c5&Fc0xyt>uYK{&H--FNv%vS=bgBoblAjveIY=JJoqpS6Q$&z{Ylci!pV*{Nj9 z){X4iyPr^{CNV9GvpaPn)e5p`$#NQ>)qw^XK7L-lhOByxIJbQ(P^E0!wwF!2in#2` z%SrMnjM!1X*M6cw7jgHnVSKgX2#<}wkJ`18Y2LC8Et)sMkH!ub^T*nC96f#-e{wqQ zI-NsyS{&Qgu3%TeVKhF{>*mn0LkE136MX-}FSI)6Vp`_a<3Pb~)@|H^<0x9UYe`1! zG?x6hoU_kAm-^XtDLrz8HJjE_QeH_`b}r|1K9_h^#pZRZ*m}5}3%hn9#V`DQ;V-o5 z)QJZ9xmXTZMwA0js3iI_E6@`0aO2R9W=w-jxKOxJR^w zM_9XY8>cF&NK8uM+zzcs2so@VwvdPYCNXvHZNeL**Po3cRRU1jl%%V%jvp9Ni7aKS4qO80U zUm%{w&05f^StBe%Q?UPVOg1h?!t4ZD^T!|Pq$DT1A_jk&N%Q8-BPS>4FYVy}?=HH;SBs9j_CvK~RP;zjbdajBpaMw*yaW-?4)7`vMSDcI^fQfu zsJg27wD?e_g%Za#>Zqx+ES_epQT<4-p6>rV!{bly^5@}E z!<_MsCu?5d3F#^Y;;?7?Zr*{G}a5s-LJPg->bL=4D2#8q3#X&d%+VZ0elYolObBP(LqD!fW#9{j4iBoO_Q+dh= zUZ6HQ%+GKJ9IY{p|C-bG-)96y-!s}{9wJp!O(L({C}q?IGPD3;K%os+L89`+0q!3) zgkLuA#~}`vpxb2l&HY%vbvM6nEM@Mz_h_D*b%qjzp#aB53}3abwzyf^uA+pAX+}qS z1QCT+7AClnZ~@y} zW5v5`k}|mIj77nJ4pp8Jx^|CRefD~+^ zQh?$yJ$voz9mAS2r^y}5QPn(C+lc8o7dW6ni;0+?TO&4tf!3}g6+I;}#0@amo-~}H z-To705xYpcDBXesht4np-4YdvbY%t&T+b)AmTJ$bHLciavOJkT)R_w7;O%V!qRbjD zIPS5$(x82wbg8%YyD9bV=|(j5(Od4&4tUTasCGc3YfW@E{bdCHXOx;o;J-aP*j-TE z)m>>Xk|NRQl1jal(1s!4QhP4zNJdESm%y@Mg(_fkC@}3c0 zxA;K*CKoAL05Nhx5QgIIUB^)c<&+uDDa`fnaHmqF6m-Bx{s{o>WAl2HyT4@|~jb3#7 zB02)auH^PxhOu(hy6VV5bbBAxQKdGCeQ6yVB>?}>0Q^@Mt+ktI&>Dlnp5Kg!|xh$0){V+_UHDXM~|!M*|R5?_3Xi=Juanj^LF&O{3?bF zx{9=%P;Felg16PqW8o?usk{+5YhO| zs7d0EJyC|6M1ew#INYpTw+>eHR7hMVf|y&bqU(@~%@oHGv^LOMs^=xHktH6GSHy7P zC8p;PY60a#DHFpmVn(jpXUc^hc|D2YM+{$VZB?GJFNXCGCDvSMhT-Zy7>JrB=5AE)LJpf}>2&xY02@ znd>KNOey1+9~aOuHJ^@cT9AlBY1@n9x%G=EHz~pWd%%5$7tygjzu8@;93th%`Qn4u zXnXkp8a2)%&TCDH9#;!Q{ZA#9n~0z+Of>gB@-XpqWToM9)OiM^t0}4w2b3vpA1QD_;?)MAYk;^>V^Nk@M`C@W#2Zpd z5F8W{G;!FD!f!Z49Ko`z*u4bTCNz|yVUtG8{^Bz->t(zBYeW#Sy&#YK{(dDW$409t zC6S3zih`YM`DMjk`rb4MzkuQQGkNkPQtRYl5Jq93J#3ryHVAhdR!3ngy###4HOo~4(;H_ zrN8prtl2cqNhBpsc=Cy-2&86UXpN!7ySs9u?#f4cMiwu=Fon$8nXF#=8T0oj_Q$8qrayr@#t@rp)CO?MP2Rqbv>4QCgl>HchZ z|Bp+} zHlV9DXw6uSVm0vW7b6M{P$tA@@Yv+(vB-ZE4|ztr0m?99^*6i_cnxwD6dF_2pwU+b z;yuS}QTL?hjIfxCn^odYB4r4ssfeBYMC~l^Lxx8jUTy6Nc#-Cqqf=w}MB569foWoG zVi?u!j)y&uItVq#V61Ib)VPZ}qpG@NY83NNiCi_|60!JUG?M4Fk7c_1MGVxd6w$_t zMg>*P22l#5`fgah>eH@h2m@TQb>S}~@ISHq+l@e53zn+n)Awic#Pe@sqDW6mX5h&C z89t~xrs>DfZnaLIJjx??-Nw2NJ4noJ#>3A{=F+npGXKjjdEvR4oT?}#E~PH_j(e1A zuj|RWpXT%MefM$7v52?Q=zqh_jJoGGjN=D+VBE7zdE|e*IG52xkWSFFY$$(q# z1kjr8s}^(Z4a4~8$KPq!FopSF z&1e1(o0;+aSRS}{G)q=*At5=N2cCSAD=+Paa(pO9Ftp~AnJ-fm-<${Tzk^+?f8v2h zrf~B3VQOb)AUX}husM2QGed`srs%|J>NPowNiR;LT>~HClH)va=U84ytHXWw+{~ap z7xDZvFR}2aB^Ze*jJWGTuJ3mNl_w8#+t4u-94e$m>n8LY(4Si$dWoe!E}~=8Y}e;j z8nK0uLxvKclF6*UJwv2$6XU1MqF5(0aKJ#G9y^4g*9~CXz9Q1=x8TXiPjT+qt$6OK ziCoybH&Ex@&!ZRQKM4$M1UI^FBx4@K_ha z%nn^$VO7_vweEGV9GbMen&-znOPN%~&JDlt^ypXFc_5p5HLEgt%tJW&r@5^|8`4ul zOnHASRmzrR!q^G?`s)fxRjkLuPdv%>*EV70PxEu>78sAmVEy@#&Wno|e%b6wlEe6t~wYNcWF_%TeM`y&}4mt*POmpb}rr{E|1{ z`;3CTY&zU{H^YVvCJ;W!Bac4A+D$va%_F03VI&Q%fd{8NsiM7xKpIuX8dxkIP$L&kG~|!O0`LczF0!KAJL#I#ny014%5G zCk8#jeNVm2)pbj8>uq3xfsu?G|2hHXvVZ$3uD+rzHR@L3+nH~& zd&f@3k9m#EojWL3yAdypf0;{bRPnEJ`A5u&{!wG?rKdv^m^rC1~XbBl%cfiMwUvHHcrI2W}|pb`~!OIL6wg zm3S_9RYbAV9{So-g1p0^Ih`7usP?Sm3F<=6+UNzoSz_+tdIw}1W98Gz9Cl6rU9Yby zuJ|Zzq*yC(lp#JhZ80ufKf2cT+_UDm?RevsXuoGWMvG|^*x1U&^1L?^Zwr8nCB8zd zz3Y9en(|-{o@LiN5*zEe#umZW%1acWJ8C@R&CoL?_14 zx8xS}S_$3(PsCVFJy{Hg!~e!A`MdnTQ2ufy&{hg@qZ~c3oBEfxVBDDJICWqbBcFen z`c;!?aB)M#HbDI1B}(wZxUncZ#K*Ij@Z}eC>Dc&D4jws0(>7fgG`KHom;J_LgYKtE z+YKB!c9yharFd`JXXKwe!jsR8q3!k8(6E?`gGMVw!TB>(s(uk~e)bBdcdz5I5pU6{ zU_1PM#k11YYfy`tRm-w|%Qh~n*@V@rR&q)6 z4g^xuczV=785T(8r$s+AYt|gDZr2K|03u$5nsU)tWSu$7*cV^n#vVQC(y=ugR{zG6 z6XqhyrflVkd@yY)3YW1HCNuNv1zhszb)*+B&eJbH&W+bzOPN3cua9|}%wrLze*Ogo z=g;x%s4+CCnM&F6r6D9gLVRGCy_u^8iDNTG7s67elkd+{~n-+qUtS2dwhisG}^ z=FqflM+OcZPU%n*b`nf{>m9I)@%fjt`0}gST+*lkN-2UW%-M5CnLPC~9vL*0YSnA< z{EMUc;EQ?O*`)>leENAh^|+UpI&>xwDz3i~YNHF@5GN{`vAas+LOQ`4?W}y*J;ZPw%VQw(kg|C%nrgHPd0XNAkv-lc`a)DkGmA&v)~eaNYGC zcxd2#lrCKYv0RkIKw>77jIxo!d_qa7y#M)R(wwsl88wMj8~0E%B|z!2Rruh8SyU-u zQzkW=pl6lTkvwwp!;F9PEiNjX%!ubFF?ZIt^tz!QS~ObOxDHgQQ=boKe@8~p!PYsv z`^FnwbHmNNIPPWM`rva$j~>soDHBMx{h$gwMc&)bir}w)9}x8K7T*$>kx>>b4+ClR zsJJWLH^luK_^=S|Tkv!OUgBYG zeXKhYNXUvmFJ4r90*mbh4aPCGngl$^LgA1gl=5x8UYo@?fEo$gvSkZ@m;YYnFINHu zOz6J|DJ3dUzFIZvRW48Gra!QA%NFW2x(XGrQ94H6`5c}bJ(2Ghd`-TaPLq~hKp;kl z)KVE#tyYZ^TuxHt6vt0y;izPSDJ7{`wK~PBBvGSMNsecoqkg)Dp+Yeyy5zJB%2%yK z%@Q#(N~UpW-!9JWTtS1T?P+#RTS_C8DG|cbQE%BO|1bpzDkYijx8B00H5+kSUCfp( zTN!lsKqAo?lU{#^*3nZ(L@ZntB)M2RWlN{RsUxiU?N_=DpF*t$^+^|p)(va0Yv*Q) zSG*pTUV#eLs#2;%ItmzYZ*4BHl86upS|k@MLAg?Cgra!}Lb0;dsaPq4lG-7ff0mKY zzQ~V1EhW_sbH#N%32U=~DL04x`!boka5eLPyql0!fD;XKb)Y!SF0MjhI6#lP`;wL% zBt_?ub!;mxDWsRqphO7=EB^@VmMy3Mn5k5(S%b>OLwqsiC04KBK*UNTP^=tPs#nLt z#f|23Q8|k}yEam(#-&Jl70Q<_W%8I78CS%m?&TM;cgA80!@}lunRM*fj$lCeZRskW zd+}w?Wu4&sxopm!Jx@t*I1JX%0p;R4Q5OERmUf+Pq4AYXu$%)_uap4@+7UkaWIFFp z{Rqj;LRY$yh>M}0NiIRLQmGWzVN}>VwJTV?d?i)uG~lwUno=epbh-9w-gN_D7JGmYNYx8u!Er&H*-Bn1Klm2Z6lu&@YWC6}gTnUbU@=Xn+y2g~v{-jtG* zuU3PKp>kYSyAr2Q><87rxTwTfBLb<#C{?By>145K`A_WFb&Q*C>4WX&pkgjn>r|mw zMrCfhsWNy7QXkxoHWBa^LNK`)MODVsnO%-ur+YDb4&J zeqr^x&3yaADo_!FIRj7-3Fqcugo2LW{yCh;nU%2^J4?1}H0pZ3j?V zumT|p3(uJ*D#7(!Hd6GVCIB`nSc3Lly0Y-;SNLXbIZ}$3pBGtZ@$nx0O$FpR5R6c#xJd8C#|$FhC09b?4_C?j`{FJ>rAG^BXeqJRg_6Nm@< zn7LKrCLZY85Ckjb; zAH0Zd-vVPAW2`Hd6(D4VNYXZf##MrAA{p?(@W%L}4X2?}ph6@iC*#JlKtQ{uf3{^o zG-_CZY%`A4>eOZIbMJCRU6Yqu2$CK!2whi4v8`Zy1JueYVna(fzW(bWBp2?IrsfEi zn9L;!+HotMDZ>B$AJG%}zyDWsn+tR+Pw_~|zW^@EvqWj7imdCz-CYOlfQmB?U0|{L zFR9IcRE4q0{;$@dl(GD25$yj{wZY$)3x+abG5sHnt#1QPNQXyuec`0Xf9VUZ{FiBt z7sFTS6K5y*t^7kkobT~Juu}dm|96)7%>Pw@P|N2I19og$$*(^zWyY*o%v-*hOD}Ih zMo8gi@8$T>V}$J#v=hd46;U^Uwu2rThWNopl!I-1W_rs)D+>z)*f+=+FKj|P5_)_7TfhtYpKEeYkcK+5-ZE=QdOpNHP^GRi;8(l%X%Z#&x&d zPwCVUL0t&37?Hv-Q9?KpG{nRqi_P11ksHROH$$jcA%hy#OEY}%qpVr6mW^BYBii!F ztQ~YDpGZt_lu6x$6{K9*3|1^y$hr+X*?T;jYrA#hlgX1<{^MdknKpxEna8>0(k29) za016H5i&O|=axGjVE5rO-l0?xNKL0)xpFN2?puCcy_LO(j-!-~vJ+=gJC+BL9Kz8k z5==wcNuFz5h^aKHRIf$p1qDgrv{xmED^=PVkxZO5KX zoB8~`sa(;dp;2Oe+4Y4>0;Hr>qFd)Sj2rnF`N5J@uThr}Q3ARUH_-1M*qM5if|q^&%R5OOr0*G7Df}2`+eJV`N2ZgCnz*A=pM6g~}E~0peJKwnCJvSc$!B zm#|^=I#zDT>&B*ye<(|GQmqbZC;AaauDhCRU#%Qq6kW#x)xJT+tlxnbvD zf)@T)im${<9Lpu>!jmjtzLW#U&SUb#3NgSD7l;5cToIyxBLWgeFt2?zoVZK(-za85 z#9OBSW#iVM!)S4c{mZ3-;9v(5mL%8L>Eo6E871L*{C7&M@H{IP&1K=wD=6^Rh9AB9 z`@O2@`|;2Jg6-`0fg$nYTZ4TUvS{xoVaoG)HT@MO+9Wm5V#xLdaDUIxpg=6+j`lNb zncI0vrgvZ0^#besFkp?rA9@T~Xz?(ie%&sAm;b)y0wwUz4-xmw+hR=8k-|boj(nC^ zCQV|<$bZtTMQe(u73aG4E%<)X&)jqW!vrP5jW^uP#EFxrU9&0{sT4~uPU#X!2Gh!mIa|SGRl-83BXDwBclYVDM1=F zX~}zUO<>l?@AAapM>v;Pi0g;$BMHBX0+9eIDJAK6{k2rCQIpPHI$eMFHQa}JlQYc-l0%Kl$hOJxHb7!w!j2l0J zyn-;r%VhA@l*vf60Qx`$zmNy+xtHgjdx=6Pz~h4-V%egvd3fN%Y|1>u{rw;2$_6#K zr`PTLylge&-h7`jY3YfQoypD4qVZ)Hc?yc}rt@Xi0+mdc z>#nD2h2mV(u@%MAQ>j$BDt#X4%cv0}x%Kv5^Y_wjHmGe~I@$_>ddB-%Vj8M$M{axx9I6+O%#?zk7Sr|KX=7lTn(W1x;GCrAvpa z88VEOBw=j6W*_ryyh#L-(x_NA4ci7~rC=u&r)q^Vgp?3SEJ=-ZiOZd}QI_uR`X<0g`Q<}A@jA;*rL z!igE2n^{Y#WRx#QTF6FQsbrKXPl}}w6{1wBViYeH!cHzh<#Odn21BwPC`Orb6)Bb! zLXkx2vgJt*7>h)S;>9RYDjgL{r+oR+glwVyWlb6M$Uhh}YB(>B9!sH4;h9m-Q92p= z-qV|5&pg9{V@I$QWSu_4fdfa4Ql>S>4j(2ruK+=lpO?eogNOcu&oSlE<#^~Z9cJ&g z)pWU`J3p@2$l<-2Tz1LjO#O5YNIpw`m`|gIjVN8F0*?)Piu2jojCg7Yr83G;tKJo? zT(jM?#v9Aszoo6j7evC*D*h`mLUU~Udah`A37>qq05_V?=JgxcbL1?B@Fz;RW&Fq@;t4sq=0QO=&vFY)Xn4ZZwyZ$B%F( zw-86WAQ8@=%i{3i0~|ehf~e!*htnW2@^W)Idi(?@&z!-sJtx07~xk%R-m9D zFNed24{-R&C>@t~es1#T7@ih&WQ1e_GaWTqFAq?3A@@ev!+XwUyc5{U9+N z6}QNkXf5Jub1$u9B90@j_nvkmqO~Jhv^cISjuwe&@!m5RyKY2W(-RSK#r4KSw20$q z5$%YpBc@eaB6)mpT;>H~Bo-yyYNMT-%?BBUVZti-!Ec)d)3G1kc8#VXy`Vn!bp5eRf29W2VK-uRpe~>xipeudgE7 zjf(5U#Pwf$GiJu$5v^lI+UNJvm6&LWiZ-L8JxS2+1@|>W;??Re1+7Kvuy>^+j?R~u ze^>uLuBp?=d{nd(Hm|jaBU+;3diRP;ponAo?YRCOy~^CMXo*QoM07MJ+HvCZ>}oCA z6%i*QTATSdZH$T*$9zW$#SvFx{uqiY+6{|%y?1;Oa~#pG_WJJ)Le$7sR79fjHLk^R z{aG~ExUM$$bi$&wj?YD6-D-(MBC>h&X35UZ{==W8OP9vKo0XL%Z@u+a;`!soMBIpo zn-jUwfddC*%$PAn-q9iw71248xp9f~x~;49>C;zk>)u1= zEnX()y^#?ul9!Vu<32@}Y#aBihZDUl-4o!H+#8|9EVeOq}wu#9T*oEML|w zTOfUU+#nYmDIUtbw;|NYYYwr*0s=4JBDioN1LZs*ROD{I%T{gX%U z@AAL9_|H{(g^f z$L)7=ZL7xgyQ4d`Yt*1d_3G5DUXvO%>hSR3;fCHo1wdJGvQA}%P+l%x+cN38Y-Mn5 z%4@%}g2Yd*Vu(fk6RvG3P&P`L?^p^#mKCSOKzVsly&#u(f?}mmw#TzC{`(FnkDtr3 z{h>2$AYk&Gdg<p3IkDfxj5FQhS=+Smq0fZn*yt&3( zr^-asD&M+g*`Uo>CDu6DaoQH!Bge(89XsgB@`Wg;3%K_F2Ss^&apKJl;vj`589j6$ zS2VhUK94*{o@;wi@-g=8+C_drl$@+HoH=!xgZnah`;FJg%*mUC}k*RB$mxrA5P$!)-9=5w;oq_x`8>1*H9>+B}~q#-3%Gnmn$x5#0}l= zW!F$=0PaP z)~&k;JH`#TYvU4n-h3Sm8#ZFV;E|jz1Xm&~`s#gdyzUwEE{(O2O%4M|kns zXDCrN4ac^<$C=Qm)zyr9<8@wrZ6epTznWXRb)jXGnt$p@{ayagE`ND+uobjHk{B}L zMG7TUWW(_uxXR;h63fFC5ns)Q27(KMpo&H}T|kog2j&0&6GinJwfKJiLT|(J_8*Dy z;pfxAO2bb}Ckh-Nxa?sJq3DK_P+E(EbraEeMadv8Y?LmF1LlH|hs5`kzr7_Q0TT`) zl^7c_bPM9Ou4o8_`8+Xj;#XV5-BPq2el$t@&Ry7;*_o)F;%)X9&PBq3>DQ%-3`Zir ziecV2-?T_%PA;k>;knGjb$NKmP#zpQ5?6WX7p=LXSu=L-%LFUg8&88}bW|b&vuJi( zZ-nC`76-nnZDf-G{z~Dg) z7(5K|jwc{Ecr0w%8%5;{loz{Rv^wR_sCnTZK8m(CK^I~2QW%9x5_5Lp6kO0fEfJIz z#MNRBZd~{|o+9c~im1dL;$xFg9sgjgii}DTjoG7GDSD&dUw7eL|52^~&H*=(6w<|w z z$SI)0BtV4N;~{MZ_)O?&y6N8C7dCYyNz`{$>_)H+=6o%`KFbOem?4oSc(<@$FAMF=`a40mZ*qgZ?i6 zZOUIh_gZ@#Q93}f^6*b_R{AKhNG{*ZTSR_-)PRBE!U+4gqVfk1{UTpB?C075V08>F z`a-aDQ82;if0 zwWqL|?>H3Xo#p!lOUTI!7g1ik1}bBT6EtpIX)2OOSBmm<`FpwLZNNSg|L?Ig4$6Cw zneh`(K`E+K`j{n8@w7r<2fdU}9OhgXPh`N?aMTyqE)D4@u}E z3hX4Xg4oJSNagXjsX#iYWbd9v;kD2NwTWxhc!osZqT|V(pP|DQms2N?^X2EC6Vo1I zS~S}74;ucQ$Jn@j9lH;m`h901u6p|E_`GQs$FuI?39P>08h-;dWd9~Big_al5<*-_ zD4a^6v`Z4M7a-(~i^q#59zm_vjyI-$B%-=-x|KO(BtG|N-SRBL{wYQOPNBoss4LAx`--`#z+`{1h!vp@He>MT zmnb<|2UxgpIW-$L=l$uknfk`_6bopBxm89!mF-2y1k!1H-EF-0?qoV&*M>CLCB1lc zUV3c`FOL~Ttx9E0Ab=7>NUSxu8doJ#q4s6G`p(--dv83Ik|Rw0@Dn!g+|8P`yXbu9 zKlozKbjFPsz~Oy+SifNdB`a3OwUZH2xb5a{TzN?Y&@n`Vr4`z75S7mDcR$2??~J2W zvql6Q2TNQ+ z_cPhL_c&Il1hH6{WGP_oH{VkD`^cF8Xc3fh%z9ETt5z=IuDkD~*FE>Lh$%WR~XWwiVoY$L$H4N?`u}9T8nmKy!zrWM!xV0 zVZd>{O;#0fc+YyC8aa-v^AVqT-rL~4Q>Q*p=9W$DK9)r!p}Co&{eTbOzT#7KD735b z4Lym?S&&#BD}I{K!Bg2@#HovxL~^IN66RTpT=6mj#0q$<|NYFK_YDPr5^WS)rEtCc z!T_#YRPk|%MbEHw`6^DH^GI3as-{tF#3wfu5(>3axXMpv=D8XXZ%A}pX%OYliG`(H z6I1KB1`6QO{Af>2Hc^I}faS7h=MLU{?R5&m5i&Qfq;A!+Y}vCfuFQdp#Ln>Hhwrg$ z%N}B4-gCWZPdqC?*2%prTf2cmyr|&9W88Z4_58eMlaZk!LMjL`Cl()Ke*wmG8z|fJ zz-vz-(%348pT7T+9``)VnVbSMr{48uFV?F4WLp)CuvCZGi+0c_#?@g8^764&8Wk#3B`IiAEG>xEnu5YY?4X6%3b7Ss%a$Zb zITYmQB5=Vm0#PVslN<;T3!lf)LNw+Q444#WwQAL-PMx|W2aEH_19y;r>=0AldWZA* z7S~+chC}OrWWYnuP@vMeyU(4JD-}Sri^jlS0+uH$whaLrM>H|<;0t1rbut?(m_p@? zE~egPm(%yb2N-z&U8EKxH00r6*@P5t_pF?7fi3?BRljW4NB*|Z>q1vy|@gu^jH zp(L!J@lu#afkPzsG(CDfMp~)rJkq~6DFMZSy?a@(U>So3+)KsM)%fb0pLy=d7udOd z4Ih2-DeZ52m=|7tjj6AVVb+xAIDG67g(`{U)MAt^SB5K^HY5<#965Q$xWl!^(hg`p z65p&ACnuMWKmMG~H+Ci^CG@uy@V|Na%jaLTHuxQh0vfRmle?o8O1UV@K@%{_fyA(t zYw|Q=K_H01FGUR}mr6vpiP9huP!UwXGVm_TSj5+)ItSx^GlBCOgA4L+B*ua!4%)U12cVa<)?5_@%OnVL1Y_oM3(?}BEk&z#ZMo*! z_6QKLeQTS8*g;|{$vdq@J(b0vw?q^;1-v<7EbBIGinm$&oQO){icbmZVi5x!1yNXb z&>N>jDk=fOIaxgNkNeoYXAcp;Q2~@P*&+PQyNDTUS3p}fE(Uwpz56X(T)zPUG=kxw z)8dVzQi#&nw#m`#WvAkN_HkZ(VHD@`3UQRln(QJdj2sy19*mN&Vj%fwiF*8bmifNV ztg0NeZF`vx{FyQnj{;o&q8+zb;wCN0Z+HotO(G2Cjnu zj4(U8{2~m!~n-qhR(zSq!3qJTuinBOKBrpVww67V?9JJu+kfC(m_cC<;ju8 zB8G)n0Yn@Ewu_P|Hi|GNmq8#Ym9976OoNN-6Z2YR*&a=X0?mAW>N@P@{Me8fsxotUbjDMaP^A=MeihvEcE@*SG!S(X<`f`fN24U8y zfBY)y!4SmKU}=;tBq!?-Uwtv1*WUh^T_`2)5d zhha}W#`<3uGUfG8IezpY{U3OM`}+^#bWVf@ty|LQvTFP=?^`lz)}U4UHiQeZ2~bEz zsgk&a5IY4|D}uI7a!M*2SFd5s=1gkUtBd5H0UI}v$~9eXqD%_poH$73 z3Kb|`x-!jMwIcYZ0-Y3y<#Em`N|mWVlP1k*)ubg=%9f`~yGH!7@Ei6YIL;4?H&CxZ zL&_$*Y*?{`rEAwy7>n@c#IdB8EWy2fdXt-Tj$k6CPv&-Z?p#Bc>pJk{ zh+)*NSC?=kpX{@TICb(A=W}z>fn*$&%H3J(HTeYE6 zr!IUwcL6aSpfKk0+wzsDSd2q^x6!B1T{Laen(Mn>&%7UgHXF5$lDTyYcinXlEn2nV z<{rIS^2>6s)d@eP;IebW3VL?y!hw^g5sZ6mvl+{cdHyAdmd zPx`BY%w4<5+_i@g!s%oC81P^}I<)V|b1#lVdzQ%K2Y1o4`;D|}(UhUXN04>C5bOZ4 z{Bw*LGK{O6U&F_re2j7nm_BV9*LAv%?zi?}#hOikLw43t20i>JEnBqap8M|O+wbSn zvCFOO*?&B4^-tV@sr-cjpT7(?>lJLyafXW zJi&oOC(tU1O&hjw`uI@-IPA^b%D{dPa80`oy!rYRA|klrkaOk;!-o!`ZM#nNx&I%; za_F~S0}wftJW>KuWx^L?>P*>=Jjj1zjrU%wr;@_Pdv)P zMT>a)+41Cuqr}2tCX9KW8FS_lHL4BqoCg|Sc={>6U-$zKinCcq>2==&Y}~n@uV#Hl zrw;9CcTIbyefk-$VcrAp>fGEs=FXW%ettd>W8Ul;bh*AWw{^XlHS0EFSrCgxnK*U~ zty;99=WRV%wrV3-sn`mZ{_q2Bn{;I0fX9hAuyXY}&SxIDq_Y43AOJ~3K~$e7Ai~;J z%jkJq4?1=1#OGhmAqo`aW-<1~(R8}5Ggr51!;mLOarS(~bAkF)+5U!Wb2j@NYgesA zyI~g2o5_tgbftN-X581eKU;SnB&J=I8{>zC-*RP>D|z_Q$BAjp)(z{pulHTFZ+|Tx ze>#Ig$K_o18OA<0jCO6?a^uZ6Fn#6>Zom6MPG#oJiU8f!{_h6!Ale0r9$=ERLm%bh_Pvh zh+(ojXaW*8im4SOYFVJd9uUIML7uP-8?=CnB|`3*6HJ`&3R6Cs!|nZ^=+t1sLsY;e`eUQQ9L*94H`FZNspVaBj%V~#mbFPvO*Oe z>VFSA*Dhl4pke&HY%@_i%|Hos8g(ve$k=g1Ik{&YqhAkd5B?+)h8`i%bl9wMSrs9m!rB}$aw&fa&ClXH$$D>icX zef{X&y%RG&`k2WdeM7DK7g45CW$HF;%sZ1_;Pk;A41N3w#=bm>oqG=b3Dh?i2nC{4 zk)S?huqUpC5TMunw-e4g!;Lrg;Fop#dGwKgknB1vm@}QPzyFa_=g+fr=^BL@XOtm5*``>U!VaW!U!Okg+V~rtJGA4ekuPxfz@gNv zb`cNU-Glm7Qn|fn4_`V%aNI%OqDj5 zH;^Sum&wOdUXfV z#St?4&Cev}II?cd3fZ(_oxJeWLvsH^gXEm!$SWg;$lD)HlRP&nZ@loR3?KJ~9M8#? z2k*X7dfwYtep)hLUK;VR)VlOq*>m)~gmccwZ_5_T`eolpmup+dOK*QHvBIM=@ZN4R z=Ka~SZqH#kmwiw^nLJt=Ue#V^&YLfeA z-+qt|U3$o_{U_oSBau_Pq;ZXs^8QzgWaGY5QgA*?-XHUX+;LAoS+s7iY}(;3J1uwKew)1U<{R?c&x_^8Yud_;A6H6N zPL}lT*-?7-eL%kdWu^SMaGsnx^s8Lm@j98e;-Ku>dq5%uhveNiUzF=^zFn3sT`Dh( zd{(-2x=FI~bL8VsKbH2bTFcVqzsSaIt7XrDOzC*zZF2C~3CTWlTJG-FMb>8Sl0wm< zB`o3-leiK2Wa3B}^2~FRCtB7l{Ysj4=qd;EMfUH_ly&Qt%U3f$mn$!AC|eF5m!FsX zB3CzVB4-KsBG+EiMkc=h zxqLhKD{0!MqkJ)Uv79`zS*~o}Qr@06TNW<(R$4S~D^HJnNeW%UWHd49+M>G$|3S+VjrdHnG~a%Z21MC%;+{FAA2d(S?yckg~Vc67hwoIN33 zI(L%~-v3yBUc5*;wQD0wH*AxgyLU;pxlZj~O zth_z?AJY552jz$5t7Y`FBcx>IOJwb~9a5NoL~ibKlMH?88CkykH@WAQuJY{5Z%9r! zEYA$MUuG{{DBBP0mm52@lezPMka_dwNb9DT%Y^s7l4#*+>CvH~44*JXHtatw**OJL zlticKpNZEOlC4CeQQ5L(%m0ufMnvTF>C^JoTW^`Fw4pQ+9roxRf)UY&(2H zV&3;7BI4?ph+Amx<7$cd^gV9OP^IVut&Afg;ugl~d?XeY9rMRY#MO?tZdAneXs$%Z z`{X!oQ8F449X0pSuA!3>SH#VeJ-au`w(Z+x>-HV8b^8w4vOQA{o<1WHEgr3tPc7vM zu_Q=t424Qm#G{gO;PfKzdSnFfVec4#HduY8m(G4p;L=XII;IQ>({NN z-OV@Rps>V2J1*OI?`6xD)nsMm6U{csw6z_ga?J)bZ*diM%BM2z-8b2L=onfhQKD2i z8aHji)y=E0VDT>;J9(P=l@*p2&snI+s8EGQjW4BX?IfnnUdFC1+c~#;F*WKpV$hIB z$*?sws#L%@Ed8SJqhtfc)4Bfo>sY;d3)eTU!P>R!=ryD}mX2_E?=IGE*~z(+$2pRl zOraLUoXY@{)?ER|PM+rQ(X&jM{Tby;3KdIQyuWZaN;yO$Ijq~bjZ+7=lAMypv6H!I zY_wQZs91`IwX2}c9cJ#V**x&*NUpn~GwIGX?A?;d`pv6o)T|Z7%U0#e#*HaiA_+@r z7Jkw9pwZaYtDOaH^b!wI+#mz;bse4gFnp|0n;%KDc47;{(W&6(kxUqbW96LdQ z>l(nZ6ms2q=wHm`k-{uy5}+ zDpaaL)GkS_s#QFPq`{RLD5pcCW|uMJ)vw5j3R^eq;OdsGD3$DTIQujU7cSz=sWU_h z3dr1hgpvk=hr-1c6Sm?=gwJQrr&E_+^y+mxA&${_{&Fk@mRrctBL`W!Y(3|W@8Q_- zLLypFT9J}koEkOLDXD{~f^(j$2-f_(oEkOj(zDksR0svwxBn#Xy*ie5AHRrBD#oQ( zwWDSIlH?pc$&ByjlM{^+N;a8U{OD^CY)jC#jo1zJFr*hY0Bi*R{Ba zt(%u|Nt26Nci=S7+}VI&ERS6~cCl^SYEGR#N4^sVFG^ma2qvfS%riqh%%dk=Ue<#u zbuQ+L7FW@}aYI&b*u%1gU*R;V!_H%8nfTrl)T)?*{ZMb7d}Sv059|jbIF7eQ?GRVB zYDL*Jm+h;6WcjL94CvJsaiL^JX{y!8AYF`8I-b`X_&rqC$G~0?W&b}}e0Q+Hrz-GL z>7o3dDlZjY(4(&rV--|>K4H)#8Em14l{|Mgi$M7(V|ny3wcb2i%CE0zq`6ll5j*wQmIPfF9>YXY$G_j#c;;S}6n{7VyQt|> znUsjOFXO)FLjA5@Wqa27-`@}XQ7*d4t0IH_w=4MX0{)U`eSI|0ij zEhU5#bwLLcp!GN?9fF}CX~7`6AfJN#JStSKL@0=f)^nXAE7MW-{+FLIdGZH5^7Kd|XDV~xyS0daS-c2Ji^<3kNFgOT8H+G>z;K;O zB%A*I?u4?JGq~R!6h`L|_PGB7b|Ajt#-dU3@(Rc(SI$(cH5tW|C@jn;tN}adMT7c} z1_z5kkq3>SU5zUSs?Pt%-g$>fQLJtMSKU1`n={KUEU;`KEICRN5LC>FS=#~=T6 zDM?9Q#*e>(xa_u6mu|)5OCl{LB@%asFl@J%=5X#=7LCn*;u7PL0utlBB*tqTI$Td! zX#~xvE7a@tF|uC~UwpiXUL(&UtFRXdJ|Bj|+ZS6Mpnd0J2sg4}%??(tFXOz+ucH3o zLGHX|A}5}A5km(JX6>p~giVF=I0+chR)Qv}YYNh-V_Q2($O_wWfJ(7_?Mm*OF@x); z-cMqvh&6jZjPRMc{Csv+YxMU+HT5JXCgIf$gwRM&Nuud+1y(2kngR(kkr*wQc%>9i!Zy3 z1fSyKE3YKIO-HP{Lui^|C+{c?P187c%mAKy`#p*V45d*^rb9s<@4fac^A;^*%B1Va z*tUn|D>p>KA_Nu^TY-cXc!ayY>^j#9-A;Y*dT5)SL8!To+PcGtxOfthQ$U3AC3*>% zCjPKf$;z}hJWbb8LL%{#k>;gkXA`CrXqrGshka0)POPi$BoW)IS~_uSIua#>!?WhZ z4gQ-|L}EDxU2+{Fdc>(FqTKk%Uq&B7Kw4%tufO#^Qfj!Hx{}y2(uP4mD&jp}q;x@< zw7E9jcx2&53Oi8)e?xh5Q|fYd{bZ~r1JI3pRlCOz$tLj zTfAPI4^@wb^8804Vw>VB?jwO7f=Ca3{@wqEDBO7WqtNQ8{J$l?I|!6EoJPEId_P@#52i~=FY4<;tov~@9t?D06C6v4P28(H z#JPqSB{U4D7ON1p1rQ}|3J2_cz|b6mXQiVX_L;b_QzvH6f0lLYHd2t8O4Xr8I%z&4 zic{byJ_V$Z->HODS5Gmv~TkJc8=#YQmOH zMWSm4Ijz!3O@vq8c!SeV9709KVF;TL3bA)j8E2nyJ^7uBDJp8ux`P4GG?G%1*t2sN zRh1B~C{7tp6u8)Q=z-)`N_<*B!I9)NYIr@b@hI}{%$LyMvf#iB>{xO z8>f?;634bJTj|sx7nNvXDTNf8lhtgpqqK_dy$4g$tvjl|lGUZvHeAvLVG&1Rm!5dE zFtzoSv@hz56$p@%ok~);6`Iw^g16sg)QI7DLw=IHaU{k0So`hQWDY8%Rf3@Jz(K5B z`Yl6>+q3bfAF1|x7}UQv-!5B;t_wV_Le~WSj~m9k8z!@}S~7IZnV@SCcpD9~@{p32 z$0@`6^7!-{NX+g+L2)60!w12e$;in@C*7aoXtq zEO`B|j2b(ff-H+>e+U#*?5!j(znE_QdK22eiNrYjIGvE1%-;Q_l$ReQ(`%8JYMW*R zFmOnJ-v06%)^FNIL8``*Wy={o_9Ap&62decf@c?m{w=eia4CpPiLP{n((r0_;*NbJ%eNU-^v2hI%^m=td|MASW%Es@g*in36V8IFfeV zJJIrNEf3v(FJsQXgyfV2%F4?r>OGi}o_%NzTKu$X3kVOIE~q+KiWTa`j~h1QO-QCs z*J2_IOj=Zyl~K93oV_)>_;S?-jz4WOz58__UVnq7Uwy{#0o_=!^anZ>6_AktLTDI< zt&XIVhovjwkjY3iuR%tu9CmHlMCE~FN!CN8BzpL2`FeWv?n}GY>C_zD!{%N4={0Z& z$(qTk)oV#<)t0V>9RPun7M5x9uSiu@m0bo;X%6s+X3$5WpooApTUWRdY0f)UvEQ(D zfJ@aQoGfrR87&a`mJ2rBL!@#Jb?)C?tA6w+cl@JkBKCkIh|mtW7Dhzm8NV)$%}qHe zL;|D;+pIv!rnyorEd(4$92=q;3sTj;0Kml&BOF~3$~|A<9^UM$k33~Zp8iii@86N; z=4O;qR8>_u{j~f3&vQ|VU;Zu9dN3Jdy>n4ZCuY4`BxQ!lXS)hB2Q zh8cU&4G59QX=j|tZ8K)^@%&e~`tl37?$$fG@1Z$deaRm|=$!M1KhdwxKq?L#Ko?lBw90A6voAbFZeBZXyK5Tv&7R8( zbLWzskX-OwDTkmfU(KZAmz0-k#E1+MwSSb~5q73ZCIHg#3yOuGJZq(4YdOXA$r1bX)y zLj2;7xa7hMh%^0ovhwk2f|5SR&?fyuE<5i6diO5jsfQ*KRyJEAOPP}sc(Pt1A*%QCTWsd@msq_-}j zYp-Ki{>r$V)7l2Fm~)>!oo-2enSyjB7+AH}A5VHBJaFet%z5H}nDsy%C0$CmW%5+wC4`ki znHF9Fx<>;mjM6+wdMCfr`d-JVaee*qBwDKFyIqM|OKYcV)?wH2?56&d-_yKHL zw}zR|zRnZR_rl`~GxwQi={@vh2L%3mvfzycwzop+NC8rl2uy_1Y?>X-$(L0Eg<(?{ zIvY4j!>xI1!!HN6Nej#2c{HTM;pPBA-K9!$66A!EXi`OZMO_?V6F1r4v9s!(KS~=G zDj}WhUE6jjG0>GnQ>LA9?NoTt9Ntp*77zt&_WwrYFfEWs%_hXsAX3Rlh=_C9P0@1h zCnERzmq4Jyaq24HSdi<2KucPYXGj;^67}|oNNJ+Km4BrzzurcH-|uI^f(4QL#a8M0 z=j2GMp}ohro+rz;hC9`3Y!Lsy2m+NtN{MNjv}xPsf9*L(<^Mhr>bF=C|AHuh@F5<* zZz?MfB=PKXvq=O(*oahD60880ZpXoBW+Or*V(Esh&Qusp*!07i0;~{d5YoID%27<3 zLWS#4o&-#Mc*2b+&5Nn|@S1)s-HWN|_^cpO_hKrAZZ!}H1~G(=-|}$YCD(KAxKp|O zkK@pUCnn&?#Etq9Rue%j5h*mhQlhIC(7c#ZL)Q($*veX00W9IeRN%7$g!MR-0D~5U zWg)aA+l?h`H=9lnTXAbxcnK?r6QHReNQp(fortJ{=!8(xi>dptX+=Y52rOk2EJFxX zh%iZZb|PT!6anXNafI=r34v}kVd;s4(eR-lP>=8>fHZ7yEfk?}h^w!@p0odOJ|~SC zjh7Jiw&RNwr1xOjG&M*RahPt2GZjV?f{-#$8u*YP1NN9PP~nh1akUW{{AP zih)GO1f?*A7ZZphfQe1!ZeUZ>Si(mbgE#_M7=$sLHbW>FV9VBRbm;KQpm4*64IF#y zu>jQ6)Ua^jLaw>ynkbmTg%zfKN2P&qVUO)vRn9@twyM}=7zJ)6BnNCMB33=uff{l1 zy6QLO_8*YAJrSx4o+ zFUl#p@ZERc{r;9f0Vp8|Svt}IE&yKVgon^Tk8^+k2t66l(3KnT8x4X*;BW`pl}Dn7 zKY{S1B5+)0Mj`@XZosLI~$Lq!mX&Mj@2n=0wz>wRVI2#NKzySt!9GegHs6w+}h6XkS zv-|CQ&-T7}5t@qpE`%5GAaoIVk#>)rXSpLI3_M3@8n>-B(2h(3EfGy=_=KZ$;!p&MbmAH%T5RyT5Dw9|4ZDN@q^%fiE4coGDHEOeQO7BT5gpW zR}?5|TcA)VY2wv94mr3T7i{Bt8&Jd<9(!~RuM=jk;U*F22xr`Vk>Yv+9Ynk{)dsx;u1jr1926kawehel+&=J!mz0!o#|ml=aKseXU<4>n4Nn{CsI*!_xR|j90>v< z^&4fxW1Znqs~ z#we~6kzf9C5{`2E6a&##B4v zjDaq(Sc2+KzUUmgB5l~n{ zBQqlda9n4xqjQ91g_s=zJBPzba%ZHKhTrY?k={-l9!fKW#)54*`) zbgbQWDCNur+rR^McB^HD@EG36UZ!n0*r)&iAOJ~3K~#&MZD6kG@%-_++pvrzd=7qy z00!X}^b-yrsPp}p5)}4(H=`e_sB6$}bLsv zdQ9bW#|?|JJ1sG5uk*^lI|}OUDxdDOzz=30?uMAdXYK#OZKS0D^?WCVThS(Y9?aUXT8(_lQUo1N`dK zz%ET^xmKOXw%~5h8itWfPEJy!)~u%4r`?Rq)^@;pj7tV*@&7Wga-Zo~6oA^w3M`M0 z^vn!Av8UF^W)Q**huB-uNZZ^Tyt?+YTRGKMh3=5H{sxLdxt4+0cK^Cq3gVMeX`7r1 zN;y>oe&u`aKIJ|J74g_aH;{j>2TB;Erne$B-Tj_pnMz2eU1Cb)K1wMpDbY2}jzRi| zN?+k`Zf5_1eRM4990`+;x?ezGfoh?qrU5-6gY?Asm_9gk7|NYbE~u6u>_7l30@?qb zIG`Viz#uiPH7Ti%g(s3QV&ZSEXWyYFI^?y%tBJq4gI$wa|Ji2ef>!slsP!STzgh}( z;keVW-NV>bJ*p~e2pfsCX_bLtctF|pa)tJH##R_4rRE@F%$~x59LlL8{Wp*}_D31! zaLoZ~gK^}w%e5_<{08&=Kaf~j4S|Kfb`OuteVvh~UcjJE*{s>Po!tClI^?9$SXag7 zZQE%GSY)+nN7tePD$BOBySxJBNuWp19%LjZII({=;)xDtbbd>>w4wy1Dcj}vi+V1a zkf2bQ%~h=4u${c39^_>v6AXqig@<^rK*uD|aG13l_tL&gS5h-loG=p=W0`Z}+N83R z>8uz#qEIMlw?+GV>;Gq?7x~H21yQXN1}SL@X?Wv&HvLUR@400Ig?%Ux76H@1Qj!F( z$I&hBBo?tK@Mlj}5%_3t6~E0)asj=&{Rrh80Niu2!&+cpXX^^f0qge8Vq!UVY#kdo zM)k4wU!Ctq<^M1F-SgQaLCk>Ag>#B^kFo)p>MNLj_hZ!7HbzfVV6SuGS^|Ey3C8+e zelAK;QMR2~vu07(*c5R;+m1Lpw$EL=if9d5=aG?&MYqVkQ&E^`!Ma}(d#MYdfs}kO zZyq0iwuBbT;@w3Hc;n4?BZbcFwI5{P?k(JK>vXDXo9&p!Bl=(i#mWQwsH|`N4H(`P zSbj=(Y^0{q??klyo$laRK^%?u;?vKu>ibnk1cCq3BVvD%;U;$M+)az=xVV01Px!@K z2oPG#5m`ld2_ald5fRIW;bsgA*Y@%&)51pHY~HYrDHCs|F%+b%Y!5eGe;wr&)tK%z z%C6b`($i0|eAN~Jzd%60EXOhyORgbQn5L#0c9oVB!m&UG8+r86huOHZEb@-U&pPS` zkw<}^yFJ)zLK87tjI3kFh85iVm#1k8{8DzS9b377e>t^Hfk-FaEhzc~C!oPDqHJFl z3+MzWT_LnE$~?pyFF(z~556R%oVEx%hA=wlzbvr;kjN(Z^G(`WLoonI07{1W@U7Q* z@bQ;va=s~l_RZg0l(J{5R1z>bynhpq&3=sS<&~6g`H}O-oyDBz7t+#L#iRG%#Tloa z&e`Xm%abp>$mVUEx%>|oF>dUsTz>7XtlhKEVG4CU98T@+h)=+twbBLinp-E@X@jE( zl~f36p{cO_Hz$jH>knUW_8Dh0@2w?N9xUaWtFPvhuYSN(AZ37c-!0|LQ^)bv;;$lf zH^Pl+#jdUG6s@s8(KOKPcx8lgsC$TLL9nYWDJ3zF$bvpnBF|EmGoCss9N>`|w{i27 z=~UL#+jCP{M5Aq8y=1Xr^$PxY$(4NY@fS#?P%a&zl5VMY9PAqN#Apxg$*qpuQ~qsn z0G~Ss$^seWK-n%HedHl78$X^~Cf~*vOTQ!J)NS6pc>}Ybo`*jeLYYCn{`@m;nmn0` z!?kvsmBKC_=@yVYDo5q_k>4EzYOeZlHWqn=YL^HkhYr`-MdE)o8|q(KBnm8xs;Vl& zj%6+uOh}?Z+L5hIz>ynQg#H0Xm-J<+YUv@ z-^9++QUX?Nww{X~BudpYQh}6zx9XR0EG6y*O1Q=MV&2seW+E5LyMO() z_9+mOK+w;jLp4|^%y5YE(%mRaMgf}wgvGuC2dHTZAY&-oB8`$EmVUT^yC0ZIv#{A1 z5l~rKNjMyGJMs@k$%@?AzN>Wl=~xF;m~e9)HT8{HzhvQ5CT7b49=P`&zWjbWrik9l zR1R&2jE;<3^E7%2an5Ct4OjqS8fze2u4`H0Bo-+J(gY=u z%FQtaq=i%xX-bem>S_;CTVEG>wOaJf(Q*GhMM{uO$WSBx<{*uY3d?b`x9L>Ojgu#F z(FNynV9yrbeSZmqMvY_do_#!Z|DAll6GjG77)3^vl#(o91jh(GLb5(-Hu)QG>imOwCwr3Bpu4B)1T*KqQf zL8!(GK6>wMc9&JqzAsc*36U%HS5NO07 zXraEvPm5&|M&JCP(gyhI{f|?{J{XtAsZA`lyBv|_ugc8St(6^Kh35^ z$O_~4H)BeP3^&u#c$gM5Yy;A80KdP5mKHzZaM;mBf5%wxFNzJy9r9+)qWR!1&OP^B zzTa_>lgEvtRlLQY#-70AFU}{dLR44mX8E^ku!7BOUcZJr?|Xs^FT0ZTjC99aB4Yj> zm80_e$?xtCRtSXjQ@Udd->lk9LsJXsDX9z`Hj;vNakc`I76=FgoA~n6kJ)#il8l`8 z3?Dt3tP~HWyLR%!%C*!rG?0*<#mLbo(l$GV>iv6I@y#-->iu}U2@D!Clun(BNY6}U z_=uqxJ|Fefd-?L~WgI-zL}HwezC%aSskj3^735HLHD7(bf|}X}d`W2x8#;u-{JdyJ zt)3O*b`Z#j4G9y`Ix(2;_ z6jN_xW1;ZZRq^GrZ>g#%Bh=D@r93F9XsWB?{l%Zq*wje7{9*To453E8`0!Ke z%l9yBP;dJ7>B`zQ8(Ft*9fmJ~!NW(BpO-LoKh|TNQarVi_V_5ZkvvM6ZjX}C~FJZ*MuDti|dsH3rlbxH-u;D|< zN=;_K;A69;Nn-x?ZYNSJcI|@2=VMl2d zqecuOPK5Yw+1L15=hMAg7km!j5yA$QOP72`>w;p6iVF!hRq)Qo-!bC2(KH_1&We?* zKu@Aq-vRXQ-4!$qQ-ZGPWM!r?_ViPTOG!lFXZwatEdOy0K58kitfdzM%?hz%`7$(Z7E`FD)ii0F)WHV&+N#teN$w{VkDM*f7$C{F~G#}!NC10?wqL!St?HPXD z2vU<1A=tq8-~Ys>t)(O+Cv(PGr;?y4)~x!Tbz8S#B&0L$^fO5C1X=y#IyP=X||Sy)(h*0kBonzftRuwerpUpzxbjiFuZ%wJYqF>Q>x9RI^jRapr9to?2& zw@#hGs`Wd_PPAwVYA91tTUo_pkNkz8FNbl1GYEz)KKkejI(F#D-IK4x3`0$0h+#uV zke6S~yw_f$f0shsSUB5?DTA6(8oy_y5YYhvu?n z+iqIr4PWJ9UNM`GH%zo@~x@R@>&_gpxY(Idr`Xr*sFn3M7 zm02^UF=zHIbSrAZ{r5jWPPZ=PWDe!IxpR1A&QsJiw9vhz2iM{LwkQ^X_7#9!Ixc!&vn4gJ?*0@7%%2!N=2~eL9QYoXd^Z-@uw5)}d)$ z`W!o!ryjo>9fcLLxaW@PJUsnQ9((3_!ZoE#y5SZc|LY=7=-ZAy{RVONga?>)`(;eN zaRP6BvI?O*oN?BfJoNB%k`p|(HBkIEwhy5MC<~T1o-@;4|se2 zA~Xey-~Wg|{OJm6{b7DszLZ%H+)c;~uzt-dZn$|eyY^KOI9$QY&%a20v!BwlRS^UYDPBtXOMuGUuMrJ-Rou9Vt zLeavfpS;hP-)%%G3$yt!iHSZw{P2AqoBKRLWhb9#3WSs_`{X@7Ub37(FvydS-p^ki zeTWvnpP$xk#0+CU!D_+`HeskRci(qE3qJY^DGW4BGSV{1%;`u%VjSOmzL;ySoj}>X z{Ve}>ITLQ2%Kn4C#X!m`Q|I;Jo+doLCEye9Bk(Cxvz1!z7cumZbjRerDV;nd-VaHg8zN zRhRvV9Xob#sOm5~_w2P};ZzvQUrT~VXVuD;-2KpOT7-_!bdnN1WaSo-oYfXAKQBM` z9HsjX(o$Q+;EV6U)WDLYXQh*!(~hJBovj_<2wTW- z6SAd&)Wk$yedRS?c>NuM(&D{0Ugpj_?x40gKy_^c5M=QOi@0sdRB9V+i)PSLeEa1G zJoM0gSVHI1k3V7Zw1)|59&kc1bQNOxlDC+6^9?jM)UkBgGA7?Wi^Gk_sW~iI^d`66at#Y!dV$y8{)j!LyZOsK zkI*9Hc>jZU7~Hdf*|X;I)0(xs_4a%YRyFX_tMi$^U_O2O_d-d#>WUJYZHd)%ZkT!- zUwruvC!RPGLIFIwj<8zTv3VUcAAXDxC!NjPi{3;J)-Y+}RLb@qpla`K{2?!Mo_vyr zr%&Rew?5#y(18peI)J8{ zeaxT#CVd7D8twDiGUtDu;l1}h;M%J%<*Toj z^1)|c+hpllJQHr7%-1Wv;q((n;~-}U0YI>0DFq=~nh*2-*J~L%VhpMAKATQQH#m0m@uX`yHKnB}X|nperA)Z- zHm<&DGAEok94|KIl5lfKV#5TE%2D~9H?IqXbJi0&}{&hUvmXXS6{{ze;Chq zE0!_rq%l~+=1uX%CD8BKku=oRQX5QS>8c+=jmB>Zy7fPv%dfhclSU5Yn4!nAt#mJq z0fUUJ4qS2NmBe$Hv(CGgZF~2Vn`_|4A1NzLn~q(%2st0rGdAG26%_f@me8HhW z0Htp5IchF^385J&GJBdDvd zCruCY(&F#&TXuG-a(~|(GD?b||@Y)tB1OrBl;MhTZNH?1ZwlveD-*H@a*;%Bb5aC*m89Iul z7Ks-2^Yw;}G?^w+fv)P=e_#hcZr#V!yDld+HJ)wjf8@3K?~?k*llXYaa$bDzW7@ZC zhsO+a_`oW3Pa307JDXm)3N2K@yl0-{+^Z*X$+(jkw|fg0oqrDBt+|L=D}h$|UAg+Y zKVzvN{-y>}R0Vqv?8cv-MQu2dzTHcR!?6ImR$38e$g#b7c;1(o61HyIO|Jp{$jFEz ztGFB9lr|I;H}cizAG2}W9#WiaXuDRcL!7HZJoEA*ih2%b#y$7o(QDXNb{JhKG~uIb z&px!ut0yZxk%wRSke~vDMs{8?W5*s#nzAsOciUDw1glnj5AiA7aOZ7gCqP(QJTh$x zPyNrGG@EgZJ?}~ec5h9Jk-(BA?{oei$CB>x;ElMmh2uI@NMTnBiBCwR|FEGn`x_Zn z-N5<{+c|G^0T^)%9CiX{99M+bs^s$X##7K^C<8}~qI35Kra$-?)r}R@DM4H_*_0 zCX3$voVy?S3j+oZ#fLD8|XnTdiMraetn z<&9uT;&czHxsiEK%w@=^QyDyRB>jgT!-Ofb*>_++*@tl~_mSGV16{gy#;~d}!WQT$bnf1h zoD@%F!&h!*nWg{}p=D%#q_8zF=^a6qdk*g|UdH9)$8+wb*K+-YKa(JplU1vbDvUyq)xJH&oeDAJA*zG{7R2iz zwrp8Xb&JmUn{Q!2aVEzO@6YO2zGGKeIS7FsmrVQOdFtP+3(&5QqB69ePbi zXvqv8c`PR$+nMJVujh)X*HT=ZgHOUEGiQScION!G1j%k6hhC$n7+KBC#&|CtEDz|sT=iBP6fnaW))ZYYP7B&L}t zLy*kdKFE6KT`ORcx_0a znWU%269|QgPJD+Jav#M#`q)P^X<=ZYtPpN)nVT$v5D0G^ zXPtLGuPNsn zBu-E$i@Z(+_#5A*bWb%utl7zFCy$}Au9n$%-%D7<(<(WRrkZk0(?S_IV8OQ53Z)^H zG7B%0Vx$F?OOB6*R_PCiG|03f37oAv$Hi-7)`eD>dP=)isdap*0p@D0_`n>_1Emn>f%AB+(2p{*ntw@L8bggiMJ)7^3D-Gxep_ zy#2w~cw{5zoH2%0=_xTzGvUVkM=6G!F^F!f|A`2^@d>0Q3975hs6KdrR2(a*W+!!6 z%0f!ZiGvh`OzGqeC=8*YX+D%@>pX9yZH}!{$_T{@W(yu=Qh&IPhQKy-FfVVd3^uvDrU}pmTSjfNykM` z;PrS32U-ZWG=ofL>F1yFFufwCR6FDPNo!?*L?)3bT__9;9(doGz7i4K|hQ8(~W z`R~Z@9~0sCB5cLtrh6f$+%{T$r|3SCD9LkPf^ltyMw zHk;S}$eAY%MM=e$^8NHVX&Ac1A-u)rs*@osEgmVf$P4#+JqRSh#(L)+cx<35EH^)q zS6_aC5vPpf$_Y2K=F1Ow^6e#fluaEWg@@K{I*^r~%C*;ANls2{bReuj`R4Wbn;Y0y zUQSU#KEm)Id?|Q50;}OLs&yJ#LK2zT+0^W-zyS8wHL}0HnNCGTY+Sn|vW06xM`(g! zqXskmfjLw+#M7luUxd&RQaYS$P6C32oHqIN?$VBzo|wsj%0{m2(UZpNGWPB*3O+#2Fm_d|gU`gB3>(M=QDs0Q9bw3aaS@=A0ge?h{#fBfhAtgPFsdwK) z^WL?rzJ0Du!{_l5Y;Ld*8A3aPrKPxYCq7!f9Mj)|Owie~vyA*sB?t!;TS7x1@dyiD zS&^g^+o`8Hq}m1u9ghlNgz9+rowqpq&(rwB>BsQOYj3l4PYXi#V(5x+Q!Ppg@Fr2v ztrxzIotb>wB$9QTl)|G`LUO9VzUl-NNUxNKV3SGnl3Bn<(r%h5>y)vAG!l03ZNKL_t(~aQiJ2S^U*%l6;C_OS2743}1xi$d{f& ze!I5JnlXii&(37>t$(6l&u(@ilon5~o?YqRvlBO8dJ(s$q~bqR!>IGGqen?0pDNAa zMO4nA+d^PEWJXTg1t7u%T56d&>q)evw!Hn?6a4AQTe)`pRlM-fE!=qHjf63{=YiX~ z@#dT8&?<|)d-frXJcJQXzX3ydd**ALJZcO{K8uOho`WR>cTKyS%!ClZKr>2cbnf1V z^hCw%2dDAe3y*W-&67E6=s*&^f*DgL^2GfHbuAK2hS<7sBV$iHk<{Eg4sI_av!D-# zvfHgYho%2iq;NHq523>Y58TO^aThV+h7jkSbt*g8E@$SWk8$fGFVMcAfc<-RVJVG- z)Ku=6I*DnwPU6CguVCS#`J{Wm=kN*sR!5hka#a3V`Q1UFJ=JaI{ME~rFn!8hG*%y= z+Vn7N#HqCMdGMOGeDlrs^dET=&%E$g%=%LHRyCk>Jp#xgS&X{w#8}(ei%K}0S78fX z=vZN}l!0`Lb4lHU5-!b#ljWv)7;)lQ=D+(jH(&NA+PCk>l5aPV-+cfsopjXYXjj`v zO-Z3=aW)UlTf%#vE+N4qIbqZg?wk264?p+-)E~lBwnME=hg{};@FB;KIn}{IMn+l{qbw~^cRIKa!G!Toskg}H29 zyN+S~in(^uWNyEEHn&ymqQ1EavhwNIcL>e(wdl%@m_zzmx$I+3zIZC1E%}Q6o!cXn zLXS`2)KgF9=~=V*=9?cl^TcCNh6hZ`v1nLIIb&b?jRFjmDis87~EF*=s z+4-DsOfk1!e=UXG1|WpN^;0L%p*Wv&&p(yxuO3gI{>NhIitBHOfG2^<6=`&~$ zr=2~Tt8coQCmwr-(v9D+Yi}h3Pr8U+oeSByZUaIyW8RRUd+%dN_a^e*>#s8Bwb!vd z^TH{4<xVF!UV3n_FD2=r?O?&0gg-b(z&oR&%M5Y*$+H|5vrlt??+dH zf=)fCuUx=wx6YujeQR#Gc!Xo|RP-5q3^{KvV8$(zNJ~y+{hn%O&76s#8lgf!5Ja3^ zOIGQTY8XPE4T%7B8jptTSkzn-TLq?Da5ka9^HZ@E%q5O;qpNh!&qiazZ>8UO1MA z@1922zQajMO6HpDF5>(P$MM9hyI8w)07hynuDtXjF1Yv{W<2yH8@BEtF5aM|_pzKm zb~uHdy7E5@UuEOw^O~ESsZa3YyeG*`hP!UQ ziK@gdJU(kOhbwk7`n0S0%fkIHyuvDhY=M88!FSZn57^LO4 zW!R`=@#%_F#+}cA?)k(ClgFN(M~{K8vSITMa@%#}qRXzNeRe9th8{<=N~Sp&=IqP* z^QVi?B`#RS>F1tHVaK+lW)(8?v01$G#yhlxbP5Z)k(t$wb1oc9`!?C+Wal#X#bC&e^X9Uy8$x0_F#bE3?XHcA{h}Rf4rD|_kSNaSr`@cc)ju42<+V zHf$-URqM8#I_{7765Fuy`_+UM^ckJch+~J)szWChfAA)+&3}u!kU?Q#0foH=vhbsY zys_wW>gpRwYn{uOlSYu4p3DUoo==*rHHw_VUu36%1Z znAe&4Z@tB9Z@j@fZ~m3E%xqp+^bsS5kH8}uXqB78al?8NZ|Hcv$xOU+DwX#?&4$&h z88)yFN{<$XI|=}g%I_&h)DAx4r2oGp781>@VfKvM`D&YD!i4d}VUpjeguI+AG&8`C z?K=>LkM{W;*|KR1hia-39v?Yv+tRhT4drDAF~c4Ti`rrZ8(6vWdy4xE#%yY);^2O| z_vwv?Cbn$eO$mQqOP3Ow4(%tPB~Z{I4-sr+%Z}Yt)*M39bW*b0(yb^T*;3EO%{yso zX+rnLk(Xag$GlVmE%j{JxQF`Y5XA)@$ZwxRS=oNd%lD#rycBlrM(gxM0xiw#*l~c8 zZk_Px7WK7NtlCsczrOuRON_H!QOZwaeI4sImJ*au(xnK?e~2a-PkzUId`hCi4XoR+ znL~9gcy$lC?c0*yu|3ycc|9kO8_OxDjv-WE!`2<89Ip41n3zbfVFjH^I+2y0PU)^)?A^bQ#FPv=cP$|$(Z|7x3aY9O)4OLk zgtVzNloep^lk@oUyR|&~(leyRd+bwv#L{bTOhSPbs^f=MKhnCOC+*tgV5k6<`}eYa z_ddd=#OsTrbC2GnCm8J9x``n16t-{2+Mia@d(dE#e1gMOm2BO$k3e%Xi79Cmb}1n< z5q9p}&E5kw2rQB^TGOj{4?Jd&9XoeZexQo9v{d?bFJ$B9?c^19CNnXf+Cx=r*|7`L zv}luGMEmw_Ay~)i^*ia*wFeoA9_p(qC_hk1r(V7A3gK{`xxgU=n$AyaHqok88X4)S zY~H+$hWdImUmP6@I#JLzi{{2gHf`EQlRrrNf)3<&$m3vHIeW_X5|q%ceFusg4=dz%WM;Qkz4`X<}^zPe}c#oiL*Dm%Rr~!|UKD~O9;xj2L zub^~)1xhK}b*9S7)I z(uH_KvUA%O{6;EWJ9R(>n^?7WJDrM)X_b*0(QV;ym~Gp(@qgHR?>H%nuKoL49cDJ? zUBZ%sWI+T$L69UEFaUxeC?*g@5kW8`N>BtuMZ|!jC<2DtoFigFB!htD95<&4UG@G^ z-7~X*cY5@Gf6sGUevoCSr>nZEy6V(*&bh9dHEW)7ZSu5(l~Uy8<*{V(5=M+15mhk} z9x7`@XqrqyXsp!0R3ROkCNzR8R1k!PgQ*pNiVre>&J5Q6b^u8nO4)!-&u*>x=;KdV zzNwJ+-d)IPHL7@2(o7ia1)wPh)6J`5kpL^ISTdLYvHM?2<3nzqxw%x)JVBug8##Nn;Uu1a z<`EJj+<~rJPXUG*Ny-qM!a$9Y6jCwQo$3{elDl~Mjc!biGTi`ehvSD2@Wxy3kdu?i z?wvb$V!=BsdF3VQRnMY45OD9Hox}dbB(gHnBk^{pd`34O4~U-pEBT}~Bfdup>xoK< zh`^<%LV+tO=Pj0=I_jwxi%1ox{PYypo$$l&GU_YEk%PPV>dQ}=_uN~|dSWImTQ-ll z3jbb1POd9DUa=|`-uIO7#!7+=v2*ig)@|CtqjMKBedbKsw`xQnP{i?L`6y*XZ)ynA zvNA~U$GIsDvCb6{TScWfw@UFiu^+^?Q^kxUQI5Nldn@)r>27*%*n%gQcgpYR>kIPp zC@d<$FfF|KX4yWfR;hxQ0CCEDsAzj*-v{G_M~lo!wCi7Qx`uXT{>}?jT2f4YegV>v zIut;HWm{xrXXCRi94RAf#vg%XDEB{si}a%0KJ?-w|MeRFEhBKr5=M*|q2qYv?|Tuw zE|yYa7$U0R5u-t@grxM?ZpPj?jIVy#N)Q86==i*$*A5`Rw2U>s9%lY?vuIE~`}dzi z>Ka9?1dsRQDb^!>PSWEerK?pGv%bf!s~#Q@A@BF@4;sNN-AA`>UD8=6`I)5q1f z-_4!34k1wm(R$|p_pz+qyLYpA@nXi0AOEKVC;!Rvml62iQDTii3#erD{n-;*Cr2c3 z&UrnlQRW8s0}6LT5+=eGWRDG%J*i!>IAdvv3p8(Bm$#R^#Fm{001HjM;LzywHuSmtVy%08%6Q(W0q8xOC)^%2N=%}9t~y3Y zR63!?Y;^*S0z|6%{ipqBNAKi=r)RB28(!JyhQgv!_U=2%9rxZ% zYj9QGS3Kh96Q0`(HHug?A@=Ow&6XW|nLK3@ty?uhpg4SZH!r`u6zS;9ZzW6&pPzwO z52kKzuA2vV>Z8HQ?Fi$M8k^oH!n-m$z|p%HfYioQr4UR;D3 z8D`_UpZWZopNVSCN>VbbGJM2v5=^hvr?`*H<=u_!+{_wl6Y!m+W%Dfdtqc=99W$n^w{g(e|mzhcR*D zmwxvlO+-R9zFe`{MfXe{vVb6@w2rQlIzjEP@>lt*{O>8kaUA8zSN$j4!5SS2gA*cb zCTerYlcI<)zr_LI$S{`i$Am3P6|0aH&EAY`w#ucDiE5f?fpCxi0XKm_f8D`x1IDf2#d#Hu6UH<(k{=S93PrjHb78p?K_3dFJ0V2GIcXq;>v2%Z<(5OcM3ul7dG!=hsL0xJB3iABJK3mAcpQt~ zYhrpA(GxCi>Y?jG&kvzA!YYJIT@_J+IYoUjhPV{kK`WGU(R1Y5-?_$c_M?rr|5nes;#sU$)OHg4L8X_z`2RDn>!T?eFVoN8@YA*4pelsB_ujX+m> z7m1-f1X-W*Obj>N!$BDiN@+K%5-0a;O!PJ)c7DVl?n*jt{Q_YaCxl=q_dwvq$qDx` z$L|6F`oL$P!y2@9I?9dRi%>JUhY4adk56j*pE6T){eR-V^?U6O27@?`!`7`^|LwN? zt9|lk-djpNmdB1ABR4nqA6)%c`M*@G{|x#UEsk_B3;~XV!a(OU=xI0B7>GG_Diw1&kGfk7&KbYTTicq;OwQL_sqHX$2u-;nAQ~m-VRjy7r0ZO=U?FX~ccDwqo-U)EhoE|W<@GOakbDIt zg$I~4^;t&WF_l_5aZz_|OgmLf`}FUl2%&=@_FobAU<7g{<{6{vE|tgEn>_+USmYlo zVAGlnC}DDF-xlt<<922*{fH*Day4ax3Zi5Yt5*Jq%xXd>Kp4@P03bw&)jxgC=PPzI zdi)sTQ4lO(-cxh9a?D+{Yu*Sy(ls8U@0o~EZjpFKv%9ehjkqE8UxtUsRQBrXjCgmv z!ct%v4xvCXt5$8GydsDY5{1^e)kc(qFv@uA%{Q?!n{n9%=VDRHu5GJ%=&`q$_v8$c zvdzfcCo<}lHmu{#q;^KHi>|gRW_0v>=U~Q+on9q02kXg@^4}k|N)PpSuktRfY#hhF-@jL9 z^k0=%i4(thVoU%2U3Txt4@-n`oDiXqz)^~zF!1?Avg5-cxA8c9?Lea{5TplbcbOrP-xA|V+=hN%da zAf=6ifzL0nO%nr!lobR66-bqUW7t@hiQg1jDI^l3B#=%8fj|W^K8*z7;DjBVuz@d5 z5~wI8B;!z~NxaYJqMZsuSzwr4bK?jqtP}(wWd)&72qzRG7_c-6vrtG`OrSy{jW~ja zMY7Mpq=Ky*SCLe&6~$%cB-l1_wjvx35DFaQ=kdX8fHY^f-K75AY&PkKN zHn9Qalo1Gp2`LL@`H8b_OhOnkNHFN&NDIR-2?R=5xAqtE3yR51QpCmi@CivMSVTBv zBP~C+&!^qtvVvem1(G;~sW9z0${mMf+lQgT1OtVH>{Lw4!mnJ^!!@FU6~!2K9KtjZ z;R;HFCVtz82p1DlCKbv;_-qnwZAJ?TLK)OMtqC7~`6c0mOe_&5TwYAbRRJhf7RnMB zN)o8ZCoKI)!^ZFP;WH(9hj+4d<2p*p%2B34qLs{yCuUO-pMrtZ@`phP3lm}6_ze?F zg$aejI8xvs!LTuXK73MPnj&IhX->8z~xL|bUeO@K1o1FYwg^<2pU&rcsQrX$8^41;$} z0-5*Jo;$fx%2mX&(AS2QzF#B;Hu{7_;&FvOlnD2zE3t^8?Ow0A$$TQlbc`7X6;rj8 z`UAtP++N2CMfgAgFX5l)%_`s55nK|IRFn?Qa$Hb0qZ1Jsv5&=IcYh>9!zt3{JR@dvK86 z*qwm%>K{c+9U}5VRBozgcE+ zsf$y5gt{%xW%A?)@KqdT_EXQW{QI9th>K_Y?n8{abtKme?q3N9LrL~+UPbRdS2FMI zuQ;o54sR}go#kr}GHc3hOrQP;zi!@1QDG5%hg{F#0av&PkU%KO+}Sh8w`w!?_UrlN zouy2lyO1hrK4hQ_R3cIs96xf9d+(h@NpUGhiULe{=n=Y}nMHZ9oO$zJ=A(B%Wk~<7 zv^cE>4?H-BqOxMj!xfx)PFKdst^ z+1({(KmHV1i{54Y=xf=(_G@N7|2nC;r_rn1c?=(P5qFOt&z{2tl$3-SG5QuR=-G`s zZ@-;R7j~!DMHlhf3orBeS6>qdhw;b9^U(A;MCoy73=|QU1Zb0)h8go{MPCWJW z>&%}!lVrbS?1+(cxZ)Zv?R{Znp;k&FRDh{>jUlt~ncOgZ1c!HSrq5M(^5QFtIQZ)~ zytd?Z@=JnbrnMM1vM)og9mRVfRzL zS`F&e$!6@B;XL!)Lbhz(LP&-&;;S)Z>Nt{oGR7!SJn`rwtod~l`||_z?Q<y-j(Y%)j#V}8KsHrv;WgIDyCFM zja-H}QNhlghe*t-PIj^nOpCBIumzw(7=|llX6nPEse&jKbqkv(B6vceVo=a%eNn9S zBtC!`P{}hLb^8KHWfK-A+KI1RBh!6HPzYh8fRF}kV@zq+C?&RMJxtw02$fr}Mz%$y zZLX27g!gg8j`BcD!?j{PTr?agX8+#Zh@`6IR?UhSmm=C2A`B3o9VlGm3x($;ifyeS z6v$GJ9xJ4BT0N;!7m07WW^I<>0n zaX$I<t}I--KU~CCBpeY1gqQ_ug|8n}7bEzI_MLdtiSK7nG8mQH7_Tdj_*~ z57%CM2kW-%q+MnJfh3F|P<))4^%^nx@uw);^D_fSOk>Ta?S%F%XW<*4vFP=s)Xq#~ z-0kBi$U7Q&SpoOu4pXCEH5%5h!N0$ZNemryBLjMLCfPa0U89HN%WlmR_l`nT6f*Lr@vJ_(9yMy#Brc^EPt19Q zv=keuBp-d;in?{H6OFO6Py%iqJB|)#w;|i8VBIG#aOQbExo!MdvMjLuFlp+;2;t-7 zH{ay5&p+erZk9o5F&Nmk zVI8@(YErXaHmB9-!MR<#Q*iVsH{Ez6t2S)bOlNM!q~U~#QxYWv3toDKL&u7k`}_-} zii3=u@F+?`ob6}m(CfM8nxSl3x15QyUgw5eM&NrKN1t%TWnGYw3@E|K+r}Y8 z87tTR#_XrxW@!Jmgbg2kuepxfuI`0jK~{CXSEp=%e;>eP*rf>Oqg9L-M~ek02t zqO{!Mxw-R56om}G>MGuN=M(N4b^#Ob9M5@I-^tJ`E@0(PD_OAMoya~FW9yt?km(mP z>Z<&Mt-qKeh(YiOacui4F7G#z3Df7%_4KOTe)mK48*&qucRQ2K8`tr`q^ayUl24Cb z7c&0V5&Z4d=Xv3kH;GHjWy&Lua7NR*Iu_7<5*dAhNYVC>8M)?^{=rCKpyy^*WEUINDAqcW(+jj1_YZ@c(7|&VlT2a})kkNJs&m?h?N)Lk4 zO^qHj6c|FHT+G_D_$q@=VNf9oi=nu@oGMk*F;T4k=_|&J8qWnI@8PzahLCu2$4CBF zG5;2>VsMn*!9xT!m!MKb+&5t?heBDr{>mI|SDv?$>JuW0REjWA%EY_wN#w=NkX1UAJ!hK6CdTT@?TXV z??pJQGbR7b0AA2AHikl&3M)Q=#FP|rYt^OWnGM*zXB%P5hY}%#C}r=CjodQoR=S^m zF_We|%CV#QKnPQq#KotQoSaOHCbdcQm2<4107V?8kw|iK3RS9SP_t$>g(YP=uAOjX zF*WQ2{7H$_tW}$|q(ll2?q}ELUpb@gIn=6Gourf`t@b1(GU^Qi;qv;$*<9ZLGS>XO zhNAsP*t+#MTDE9N;gKEOJ@yv5_Pmh0?w-hzqlNmcDy+y!P~qUH0LKeUC=dJTcvfpN z(^JXL%)+w3a*A2?&4=_KIFJjvU&7M2-lx1I4A=-|5^q~1#rX)82HCuE8{IGLNk(Qi z)vMK_{b@DXw|fUcD-PjLATcqK#Kd%xQ!;4TtO@aPK6lYKP)dN|!}ceV;J2|%6NG^s zpF~1Z0`Y!>y_;5X>#*zS-n~1sX3Ze4u$Zt?gmEw_XV3OceD~cC4CsF~UAy+;({FyF zthj)E2aaLHXL4?bwxp*fla`)}fxQnBM$A~OJ05j zYu0W6>Od90;o?hsU^!(heeo$Sx%e`!7;p`%H*Ds3Nr(^{*)R;zyb zm0ERcQMYC;8Clioc;=a`{q|GBfeIYkkCl{4dRi7;&Thr=qq`{&hg^MDZxb*;3QV7k zvV0^YCyt6lCH#6N9>E(Ig zqolNuJqPzu7zlIZ$R1Yx^aDSx_?f)J+Zl7)SU&mc7yNbtnF&5tF8_`R<0n%RR9Fe| zC?m$f?EYXV2SbL@@^=d9I1%H_Lu{nd-@28< zTUXG$VSN_9^R>JBh1s)X6DwBy#HQc2yHDpO$bs-O;Jtd4+eRe_DHA13O-}8JC#lGl zZl1lR@1xv@6Iz2BS;mjc-lay(20T1>f$QQ|loc1Sch5eG%F6YemmbO}L1^_S52-Vh za`m&7d-!v;ja?%Z*Cf)O*8oQj9^i0ZnQo`yW}=1N2U1R?E^TCKKGK3CN60TO)A*PQ zV=9R-41(ol>_51hqlFcCB8r-*TSVYRDTDmB;U_M+s0(*Yew;G5AB56|m~?`C_5Mv+MLbw8FMLjB#sKPam6xv^*o=`TeW4x=({*jP=XWz4(!^%)q{r6qInAj4jsm( zT?YX;yk{Gut{X~=7R~5A;9A!2*pEbVeD4-+zN#;0v}(-m@Q#gD59C_P>gOZczyUt1#XV2>>N&n~gyxiTDx1jrvaRzkztRj`D@G!%j$ zufFmsNmU!Nbow;D`+hBNzWohg;Yh=ka}w^NAdyII*eI85I%dysguwAORROrCBn-`Q zCPNPK@d+F`vXig`!%#?Ugb|Y|soehwKqPZ+m+rj%;bdN1;wPnALr$w%gEyXfh=3z_ zW$BybZ(YUo`S0r-L1CbkHvwUyFp2Z~5KaY0j~yd9H&q`Z!w#~vh&#sI&V|D!aZSJO zEME8;Tk-)VF%3Z|Ad!HbV3Uv<&z^mIaMal-9QNfEQ9m&mA;XcABf`-qP%AES;uk1P z3rrKjfuI|>@3@Bd*E-S^r50*`QViNgz1pt(k1t_UdRLRa_ zSJ6JCVMSt^OiR+CV@qCoYbhNya2+83i$4SYqfnoVU znMh?KaqtnwAdC~UCJQf%T}Z+zjA6SD9MdKtHI*hU+VbL}rKI>IO4uaE1*j-Fq*Wur z#k{fP4fYp>ng8li3i9%Kc-pfd3{1l!TprNLIi`)YG|h>^M~#{dIIT)N@4fpe>vrWa zrb8RbwthpSrVW_(!V(%(%LYt*@d>ANA{7;tv1rMAJn-ODYS*m7onvkz94tqX6nXC> zFO-1zgm_F_P*_-ipc;k($94M}Lbx7S z@-{!L`4w4qh_bL2_^XzY#Ayv1(W2Ga96Nf5Jv+9MkyVA}O&ZapaRb(@TSaL_kfx0q zQ?1@cv>B5HEam76cH-n{nr+;Z{sgq zb!B&Q>(-@F!xq#(tuc;rIJ9d6i{E^geMgFDetH`&?>~TKUx`Si5EmJ`tdP%>)di zf@L4S&usJ807RbPG{hN zOE|Q18%y4JgMxBJ+m1cy)x9H0{tABl;!8gGav4RAk8?Y9?{r)+)o|Tiup_eWfT|W^X&Yk+^FqY9nNCXJ@@j|^RMv0t^Jtx(7jY`(3UqQ-Oa*x8AysrAyyp${k~P`Q;~={Md7ZlIrl`lQcekF4Yp^Tza-Y{H^(`{4Xk%vV;E~eMm9TkeZ#gLI|v^>h!SB03V%`@Km4?UJ_85fC>x;+YUEbs^wS$M z;L0nw_l{dBJg^7lgt2WONhz7E+3*|ZwP{LmQ3*=MgJDs%S{2@Z^BroWrcx!bi2m1H z#pp>>NRJmB-o1qtzwPF>)?)}eAwaqdQIH?LU&eqN?&iY}KcH!Ys@gG-oJ3BwY!)wg ziHedEn%7J~8Wx5V?VHT(TsCdm#*Ur4IDF&?mfH<796~A|wQ4jXHObHP8Pgef)nEz_ z9ir>S7t*+XE$URy;@TnCa@*~9B8v{ur9)FP(h`|F<3ajd(uLC-<5vaqPz^B;ccyM#FH?Q!oXAxNjX)xp!dbh zocb_{W3T1YPrs(9EC~4V*?yLP`4N3CZp+#qzUGe6V|nX?kEvfHjY$*lr$}Tl<^J&; z+qat$BW~fLnUB)ESu<@oq9QJ_|JjNbMyOJro;8L0CeEQEE&(%CLP(`yDw9B2DQkaT zMf=`IXj8>cSSgO=PNp%TF*YdFSI_c=P2)d2hjV?!5OgYBg#> zz?Vv^vpZ5Hy^vpiT1k)nhv<--4$@)chP50#bcoKKnv!5;v+}3a96fx9yyNNIcH_;w z`}Ggli3xR+s;r>S!l9rM{QArs~-u;d@-+zS`4eQ|7gYBYdVSIK4 z@4opaM`R}FOum-CEnUh>i{Iz$3(sT5V~=A5N||`iFr*5wXUA4bi}GpF@qA88v9N?- z#dpj2<)@zr2ZQX%FXx`&-MN4Kt*qXzh)c+z=aB=nZdH@Z&%c0j$HMU?@XRxBF#DND z>C>|{Hw?Lo0+B>~ji!X{3@+(X9|MPjyEgOM!d>JSDBk|)JC=X7gmqtk#-Pgvb3BaB zsDJteX3Tqr8~QXs3CG(}So!@oTtDPS_7oQ3^BEMCdCU=jx6gPH0#1lC&uT}jGv;yo zZDV3w_}&Uu%C4Q8sj#bZcIPf+CI&dCOs3D7(jkem@5ViCMPAt=o|Yo@r7?W zaA{k<{Cqjn-*}J)4I6Oz#od`U^%<1Yhm~vBbH(Tfso$Ux11{*q8*`_#al;CJ{Ph4+ zAAO#NjglBWa%a<+Vx19%=_uO30XxWyuxC}C~-ThjY(6k2u3Zh$Pyy??`TT26lWp zojP_R(Y8p-uEp7BwINOjEGvO-ozJ0qZVvUEoyiAF=A#Ps^65vPl8~B;<+F7xp$u>$ zW^UQ>^cgsi8;1|2<2h|WI`r;;C4Dcsm?bYf&)Z+FpmWzQ#2F?R^}U4Z*=ZCUI!wdU z+t9jc1LFM&+&TFXhF#r{k3RT-?^bQ$rs0E0%c;sU3tp#os>PE}Jj1@DrS$B2Hl~@v zHP;WLdCde~Tkssa4wZ26fE$@R{XSNF^92WwlrV4JQ`D>5i1d_fI(0e|(>9SvGPASj z)#E&p6a9Fh+`^Z_ocS-4n{M#w2XAq_G(^27t!UA>9&vzaSUfQ0KH9cx!E^JT=9^WU z>Dr|`>4u4kfnoSah>PQ~+0$rLGn>UPKF`WEYY96FUuqR*Kf8#_x}C>6i(lruU)B(` zvzU1Ac#_O~{`TGn>@S4A1BP(R^?g{h@Fjdn={)xIToMeEMs;e@v3*-WxEY0Uq-8at z_oV}=o}J2BEgKW(xk{t9lIy{;>2Pi*hFmj{!B<{PQoNrU)$4NK19!4|<#L{W?nRoM zc`hv))S-2Yrrdh_ZERY<5r0w|7hT?$w1h-jv^s;=UtdDe;r%=@e<`OmZ$+!7wQ1V! zEJhB$j=#P90t;XNgf3k=6KBI2?K^YVxRHGM&O&}%xdvrtaCWEj$Vy8hCA%I^J~^BG zz3chvn-xr+I)%>Xw!w~1p;z~F$xZ=N2-0)w(4k`|k}OlZ2ECvmB|s#RmR*~3&umVT zDZq%QR{d6d^1%`^5<|SQ@FlkG*oNbn#HVC3>7H9TR8T^XO9wN&{{<|0;UyNm{w`fE z?2Z|iM$d~bq-V#|c;%(%*t&BcDH+wcpnE40<84q5ZMt-2=ylgH>ZTj8mB5J0V*U&B zsh@4K@WuJ8S-+96a*bElT`Lecjv_TVfd?PFo9&x7@Z_B5soLOln$)jDc3KAKb?b>` z7$E#KZrO%*EgE8(@l3e?LHhJ)!;)8D<=~-0eDP@*Ru)$dx{9hvL5>{RM^1JQJ-YP3 zpOB0r44O4-LbJw=FoZ#TQWEEM>_Bo#3el{}FgiChdXNAwdhYL+*n_Z8L5hy;V)5e7 zsnYN)zFWVQ6<@zast<%=fngvGg_0pR)+&ihufBy%o7XUW*g&jc3CUIJvV8R#mVNp* zXVkBS-%u`jw8T&Xq#~?rYBxQXAJ?qqo6ibj1vo zVu~Op`K(?0Bg=pOm02&m!QS25xw2P#zJC8RHg4KUFyxS4y)mzU@Bv@Hw~&GZ+gZPH z7Xe}sFl{s?WM|W^Z7aTi|4nx7+QG_g`#Ga$Ke}~2pXt*k^2B3Psh3*=WD-}89LuI( zS93%E^RZ<)6-sgEgELwE)2C$G<*Zw?kw7^FD@=O!xq*ELx3cubS$z1)JPsE+Tr=!u zrap8(eyf-tmM`OQkwK~S)3w)S%z6A_Cf$8AwjCyfpAOxw;P8QMj2|(GZL5D^=gtkh z_WFAqsW4dj)pu;!^c^|=Vm^BJW6A^I2m>W6Fr8w)|KeK?Q{vfwa6kFQ75IFqB>8+8 z${{5)i*Qhpf3yG$L2`034i*UsDFn+(zzI?sC?_t_j}nlYk^~MMI-EyEFhoX9DhfzU zPb1z4QCeKg!J|barlq5V#7;`VGW}GPd(qUf^lN{9IM`q1|Gi@AxQ}S;g;Waj&m`Y; zU6eve8Z>Us%-N5SB8Z3*NW)^t^*5s247Ra%jK@)7q_8!brz98j>IuRmEEQHt7LPqM zU%T>Z*QVpy?KO&|lDJ{`NE|FI73Q{E$Dj-Yqsi%9*Q_-Xf$h)WuJLyu2~k>jh@ygH zTsQP;cJDpJhu=Ixi>58GL=fQr};NidVMxM|o3)G!l?jYMEdNUht1sZ*x9E^9ZyS3&h!jhH-n zGLE#|gIkzOF1eiEz58jleg#4~FwNRL#odi6@^VEc{5Nu!Uma;2{hga-EwtqaUmDIqm7#uDy0I6Qc0& zes&)?&bMo~a^tAmsh*mINtt&2i?~QclY>Ai3o9vy*>j%3!RIc-7M;5G;@mF1bZi;| zM}eur+<5b?NW+Je4zuSyjWBHtrD%CpM_RV;1VU3pfWj1E23>svgRUNdRC?1e0Mnn! z)kAM&$koGf3=@MOqeqX!!9qz%vu3TBF|!qjIBnZ0MM_!@lP2Bcl1(@?Z_|$EZQGz# zSfasg3UElEPNO!AZ**47S;VGUlg3PaXd=qZIyKyl>C!8%L>U_W9)8nEhTm)v_5#JF zA}Kwdad+JfhL+p|nD&4sWR_BqTdN6=Or8X$meCU;nd-F~bN~I5w9%s!h%kl_>Bf`uU!z)X zQ-X$|VUs4zobd<_0z)ZU&6-Kr5*Rr2yK*QF7N&rV^epbW=bosDp#YCeJfbk7R3yRS zUt8T2!9akLqH>a}*C#zQlh9EE(@;93z|e_SrfKQW3)3cyt>es)_@u&6eq;cQ1TZ61 zFc6Uy5)#KyC{xF-)vZ;Hn%U`W-?5kc;!=vs%W2S}CH^Fvv(9WzMaA13DVAJ+^91q= z1hXC(&x_C0W8&1AoKr!f$(zGVA^) zNsde4^2;vAR2BUAJY^~~XFbBzpMJ!kp*J&i!sVDo98%aALQ*{|4J#0! zurQw^d4r&|;euyRk3hnwfOrhx)x=Mhl1SlVd1XH5xmp-Jc2_k@>SA5U)*Iq;C z?&otx%hs5}0^!pej?jH=11O~zJ7J=vbctj^DFcO#g{I@y!ev^LO#s40m2@j5G8{%I zhnHVmz_r(2Pv;)z)3BEtXcmn2p^7PxP9c( z^ePL_Fc6^CT7-pErk;O>iDBCAd=WZe(vu4mU7A3fN;VH zVk6)5JP{}iCAEgHVWV6U5<`G8Y!HUq=N=8Q1%~AY_!~G5~YW zxLZH1AwrZD9-&>!=G3cGpSrbcQ@3sd>NjY{lg}(5tSp2Xhf*LNi3t(+nQ|mfSh)SD zAROZBFPAZF*eC`L9E|NV7=FX$`Vn11G$fWrs(vu@3A>^fM;8E3SnYSkPvGt>Fv{Wtk- z(+*x-@(wAPspRBTp`x^$akt;f8?Qaj_TM)1^|vbtVc-Zu8$fm(i9Xo$(=rb1KSWV} zDIxTncd)5fuO2B$l7-LD=GTo|_+j;ClG0MCQ@gr0hTJ5TpcBN965G)83NJ(xmo?Bx zqHE`KsGX6>teJC3$;svX^IH%oKFS04-p9m=Q}D+nV%kCW{kD$Z_Uz(7VHpyiJ6;Ou z#E3~s2dSKh`UzGXwHls=Nr?7s&fuZRQ@DH56t3uV8CJNMcJ15n!3Te%ZOdl7_wJ{Z zmIRTmiRmES_d{UDWzg`n1~?VR_~N~{SoZagY}kH~nssVo`~1ZFOpYJi$$|U;HBW1b z6DnZQ%g?d*a6aWOdA*3dd#5S_Wq7GJ`e}|I&8Muwq;}m#$fCU*KYV~=M@m?`VL#ov zccXso9Ar43mA|Z{q(t%7yI)eTNdt20*5kB#b=kCL6%}PAtXjK{j9Rr2aj7(@TZ`XT zt)il&lpj`YCb>pKnl(RzI=N|l^Zp_#0zp3gem(y5TpHw7*JTg*4SndWWBf-0_ zU=yZkM(+)Hfnt{7QK7ooc7_o(0$hF(VVWpukXz?;mj3MnmrEb|$^g(I@Y$Xw9j53DdJ-f%fr6R5>!-X?U%hqia0Q%%7D#-u{jUL1l zaYCSPR5_*6*P{1v{T4z95V15B(j|2jkv5#y;}TY`y9AF*OvVK8NBdnH>7Pa=~zq=lV#`O3Q=)qUAG~CIBuEnAh+E45T1sNz~syh=d)$!F5L$rx-?67ju>uV zh2iOSEq2Oa&LEblVVnuu@=J zu_U(&gyr(>nT#4efl;?jh-@OlMR=pl_MRd7ES^Sev;thzoQR4|r=GLX`C-|W846WQ9e-5O?}Q(JQdK5SzKaL$pUN%QT!|BMNJy(gTB09e zXkuugLK^BrVaTA{RW{P}X(bR-D-7A__Y6QePDIs1I3f1#*u-VM`w$37+IQ;1_19iO zolLelC?-eGKl8~Lwm4j|1At`~d0AVT&VG}~)m;%fUhFm>}ed|~8;B6x* zQ#P$TT+DUDt|2Zyjougc=G!SxF?Qn9JbceEu37OTug;#v)00av{V7zhp5?MexP5Ta zgt3sq2aeS5fD`7H5jS($HAA@gg05WJ<1Fr(Fd8EvhosELT-oPBvf~2WG-@cbrc5I( zy$VGo6-<0|2zFv3cir~@Q=fQ-wcmZr!Td7DOqhr?(ik}4avpx@5pMb60}hv%jD2Jd z8JTss`=-G>c>e=z_+=UUj|I4S^hByBCvw}UL5v@FFC#{crl{aJeFqIDJ0UTKr0B2m z-&}-}N}C`5DXu_Qn#|iEJ)1=eg`k}Bk|JJs>0<^D>PK37l54wfSA?S=aoPPDIu9vS_t(YYFx-O`sjF+&k$c#LWVc$X>!dv|PS>5|0^8+!-I zmW_cRpoiT>G{dNHK3^_dO=_*CoYAmG)D`Axu1cveU9Lg>3TcTyY4{0@mb2F}7f2j8G^c zHD8&d2w8q`+kKLRt?-UJvGm5eJyA`a%7b6I_fOt-l!KPIGqf<774s#{VBxrKHi1SY zPrX(}-_?^ZQA!aCh1jxX3pH!jJmvS-uV2r(=bj5dUS1wcmMme!h?~$_#-)^$l~Y&} zCLC0lK0jHR>6oH|14jx-OUod^4s-Ze5oTg4)zXr{DWbTvoPtuwtyT>~g%L6UR$@%M zB&eg@G;}DRuPfq(7v@s0N;XL;sU##P;!|N%sGPjKQYyk>r0pX;{r_X{y~Cs`wzltI z?cF^&&yYcKmMnq+k)Q-oOd#g0m=zP~V>*gQF()vf2#5-pP*L!Jh$03Qkc>phLl}l( zQg`pF_5M+NcQ@#HUr+FS&-Xmmb@j}2&+gh)t7=!Ry4Std$|p0dC@_*A<-voL9;`qMWaVU&o|;1O&V3ZrEF?WWgswVBNog5T0$ju`sD-%bAE!%9`xI6B+Be8c%l>H_9(V-0TbF*=^uy_AHGBUGBO;1Bds@PXj zN>mHE`FUh#X5iwXy=wOCs~{TlNYBb9Cojj2d!(BE6$dFVFDE^_fb6_{!j8r@9tTPf zaItE$<5u!_`hnB0PVLg6ruzkeo2 zb^P$d52;tL9$mV0`ORnK&+)^Kha~Otkc6H1>-?c4??6{k{(h@`^7Y15%XnbSi;RBqIqDYV#j8_T^P@Py zJKK(+T@sM}RDi&l#KtM&Z^((8+vx5AYT;ih!s3MsNN?7b4&9FB$tV8GLCNHfJ8w-& zj}&3=u8ll1ZajSk^rJ90)v9Un>J7vWFlWx!a1&c+k>sw4%@Z>Qgf zK(zpcsXV~s$rCub|5-F`c!Y15No0kUgjPdPc~I4DH{QrG{rYg~X=hlaJ{VVZ*rp#> zIATPq_A>p0d7L!pTx#VcP`JcpHnh(nir!&!G5KmMa)~2e!5Ao&NS+jk#41EWJQuS+ zb9QXq!p9%X;L=-0uyVy}&L1*_DWA@!Ws}Be5zF6lD|!F@sdOH28SR_bPa1NIl{w+7gz9rBPJ zG8)P%x4y@+liWuRpNEH6WuI+hK$$3uzMV%^MoqeO>4YoE#}pscR8FGaq$&=78(i@l zdf-1)g1CpaLI=W`WaMO$of`@+@YjxP8q~|SM->O^*2}_Gu9aOVo1ENCa&jHCK-vC% zTyxb$eD(cm5C^3U9>Vok45eDqaYIq+)T%|jdNqBMu|gcEz5z~`TSLRlon(5pt$twUSV08|DwYNW*vOm2EE zb?W9Fg80`vBGW$eqNr8Bk-t<4b?P=u42A(wDWqhCsg;o%%m{3B2Z!2qvVxT$z6{l> zRo{M9$H>XANlw1PpmA`?$gfRCp20IwT-TaKjR_G>O{I379Pm7hr%B5!q)t}yc-yHU zCei*wv#q3%S6GYSEQml+QBm-9oYZt`*G~7}1PKvCIBpiTYi0TCpTWfg<)G5CC``+s zu&|bOkaK*3l#@noZW?(7ht2R%8u^8F$X7O{svDf5+;p;YGsw;bjK-)S$IL&+UXM(}7`^ z3Y1IjdiA;S<{QY)$@CRNL7OC#Q(}F@#YHLK8NjiGbR)($xy9qiBVw?RnMJEaIevUT z7Zu-R1&nKzQgLt{hcnJPi%Mn9Mxg!c720UDa(y$jw!AYZk|9>HkLMqKhzHxBK!b)ykb?3d8QXR(hL9+~ zufAfa1f_(_uDOc*nzj7R$H#606PN$f@%v`5{Ktc3TX=2KWR5)H9Ex&WZ2GMv1rUYj z6ZajAMSPS(j7B-uxxg;^wip$tGyXL3_d!Q#{N!HoHfRGb24e)r4g1a+es~$raylC} zs>d@gJVo8wwQz&>i}95lH-TLH*r_tg0+hVwhM%>VQqOrzsz)wvTXKuAnn$;Y1+qQF6;#Z6>@NWhPY z4K0p#|MMk?m=IKMd3{M2_&jO_hZqH1<;MSS|B=9>)3UO-^4jY-_3UyhF<)_O)uJhV zy%=YeR8TiR*CO+W85)#(*!%d8LmLpZQK=-H)(ukCafn!wm9fNqlBop&ZNq9mZbk;T z-aV3o<%fQ+PVL&9e)<`trl!;V*yG7h3uq9;sSt;q;}7XcknP3g?_A`n_$d5Z2!|aG z54*&16R}>Mq&uJ-LT+lJ4Nly?4dKwQ?L11w&!oyp91_IekL)E$H+MJ$Bshe{p%f$~ zT#VPNER!`pq2m=LGfI3a$={3U63{M^)tpm9Qd9>(o9MeCZLrf`9!RBmVE54dd`({V5 zc3Uw*6|-i3z{OYHiWfP+1?QYXK~WK1j_$!1-z_EPI2dKU{v6SK^!CfV{q84dJa%nf z%)o&sQ>Ru#uDoUxnlv0>=Z2MZIkF`+@-jH{>~q;rd=OEoRF&@KnzPTRR$gNsd-fT; z*nXb)%R@A-SC4ibJ1}F;0-{t>x@QxE`}C$}em=c=9K)NF$CKZnJxkW_@=bXL(UrKO z8QiBYHS?PA$>(1(_oGQ1*}g4VwVHC{$iHB!OE{@VCkl!R>2dO4mapG}hr{^ipJTzd z3(%rj`Tds+=+l!r^_z0@$Ooy^8i=ub>uQFaJ%k#yo6@saKdSfd$1C5%F)bTYSabyQ zzgWlJhC;-TefHN+aFSmV5EZYzxtTtj_pb9qIx{|@KYS9_K1}J z!kMS^A+JUwIvqcd?-qW`CFc%d>+XH*+PsSX#~n${x;3d)vo`nsVBc5W=%Kh9y1yDI@P2gQ$bNHE|s6kL*N?Ce4^Q?R~0^Fmc=%hF^CRW%${L zk^ohm`14;b!G>;(L2LaFy^JybOZ=C?h{g?tIicrC3_a%@h73K6p+nDN$dDnlYu}O1 zU5;kJNxex;O+BoRfBq%LD*q<=^$*vhFvj(fs8j|FJd2@2hH}n1=fq#f_vpcCgHNY# z-@fGLWMPcKi~Z~E|07<9j+OCWzh^8DeFa5p9e4II`rp+~`Pb|CJL7$5JLM3W{HX-~ z?<~K{|Ne)YgB=&qF*f|Xg0@|b<$-(e;+IuRd1~}S)XBSpCQX~5{Zm;^ZU#?1{TM2o z!mDq8#>5HJ>HgQ@Y}~w!qmS>$#2YW>t9hSu^?9f9*`goWyloe0X<7Vj-ZXY^UCV=G z#?qlnXIiC35DYOC6?=D4w?Px0nlyuLE5BvbBhPYdk7F@=7IVdQcW~>dQFQIxj{myn z5jL;?8Iis?Dlj}NjM21d--6mT^I5!n6)o$x=ZEjVp?$Yw38iK7(8CY$U^ttZAI;*` ziPP!Wr9I+=kRZvoXfzHb`%8IX)ID_W)}2QmeVFgR{))ejp99KJvu;h^nl=Sj!Tpas z$E2z6anJC6Waa1a_$%Y+-={aVG9!$8;$dblT*u^h-)H~c-8?} zW_?a>emb#Oj4LkLM?p?HL52<+07&|L9v*v!mcMHGgzFV*5)oGJiy``A! zg1Ri2JdM<>6x?tc6DNGY-hKPD_+rr#2A_Kl>({Ix zzh+HZb!bWJI*Jqep3Ii*CEPLUetMsJ8d1l!rYJ{Q?{x9dN;7rp`@Hh%R9<;$JhgHR zx83(Vo`z5;#E4sO<%SV=vhb^~c;(dzoOJT>ILhJV(@x{=F)vaOhP3cbT*tvE#m>#Y z@XYh$_^-b{!VyLJ{AKjB6lJGz_MkQ_S-Fv?#!aDF{TxP*eun2BAHzcr-$R-!zH5~7 zX$BsnAGn9Qja%`>*jI_hs>#jCMr(%)FF2RmMn6PGdMaPd{gg>lKH%k-$5T}u<^0R8 zqE?f}G{`LDjuAI=_X97`xPEQ!y#G<=e$|Ek%~Oa*qP+9TC)CQ%BfGK~Wo&-a%F;4+ zZQajX)88Z8@wn%KG0a_XJZE)p%tH@6K=0GfV$2Iq@XSk7SiNjDiqi-3Q0g{eII+*7!zIZS$O5--2@7GoZ~9mfeV>i!29a>;Ot(nBo%;v+ts z@g6U|_7c$pd-==rljwTV$uw)*iBLfqDI@`Y%6A^)FjVMYD1q61+O%nhZ2JFfQA%5? zi3;Ha)Dk6V4UP)3^cY;%B^He(9GiZlUB9bb?VeV?B4%M37kHxA6`;!6MtSOQ^3H= z+!#YuRn_0+%>G&aXO>Vf8U8blA=Ys~`FybK8VzXPwlzn!YRsB%eqhzorPOcL#`ky? zs>=2=>8kH_x2h3&g{6LZo@%`T)xt2T6O znZuMfa@o0eKdl>v6Wl}Pl37rPBU&`1SuLpX(o{CCUPbA;uV~)!L{2?-82QRjzaWDY z6G<3aeU6$^3bHad_4HF&vgjwyKBh5CmMmfT;EVC1hW9`Cm`~@^jY zHFI!EH!^?L-#F)%C+T=hH?lB%GkYehRxReJp8W{tH=s%LmgMDTfaCD^gB|P$_=~g{ z8_O`Wpoj*wvdQocfDvlcX+qPcb;uP>^x$4zpEQ+k7X5%JujGhMCsHj2r9y;sHNR|H z&#W((uxfKLsbS5I?Yl7f^=RLuh_VXJb+?WnH!F)YQ^CGn%R!}6RIfg@YkGt#HZ%XT z*~VM4W8uHt#~m7Fi5G^Hg4a?_J70 zkC5xwyrqF>l2PS^XOQXVE_O2?n@=yZe zl9HN6qb4nBT3c~^*S74~zK>m-VpOXT{mvUklY&$l)GnZSSJV&n6i=#U&9_D&T9I3$ z5iMIDK`t@M_wC@#H>dLX{CSuI`zdNazy=^zE@`<%)T)t5j*jx|J2Uw9`<1M{#ITqsPe;ljUh))#=Jf8nmJup}gPdxF&_-2{RI}4VC*hNWDCJ`43TvEbeJRP%( zV=Rh_9boe0*Z6Vceja`5S(Ywd!<_kx5oM!4fqn2((?Wz@FfoJDc9LrZLPBbKDxMK+ znmRuTpfBFaIW1aAkF%{eX(uA4#s!Dn#qL*tk`w-z{Q zv~Sjk8E?J8{4c-d{)e9=vf)R@y}uC00fn}nyb40fpp0kpq8bO!vnk$`@(qDi`?>n^ zq15So2G2Zy74N?D4!>v@RG5%)keCp5K#TUx)IoS0Cr$gb`7s z<<(@{+T}JTV?0N*{h4K}_r?0=@jW?%p=YtQEd0-QFKmP%qU_)8>{c!LJ zVV4Q&8M~PVW6G zuT6ayNpXlBj3Hv@ZHy3S3^|Y6ZXS-KB1E-EQSExX^}6u+V}nt~2AOt*)YMc&8)9C}nqgJYe(Tw9M=umGj1t?of&>brney_h ztlPMgr(c}FsxRJS#*cd}lQ85`9f|tiajA&F;4{wTsypr?OIH)ap>Cu4gvH8E1jGsM zo22|Dp5Q}yvPrAW?OZlX zxHnf2c|e7ew7+2YPHy`@rZgm}n1}WKuzDovcd#b7ffDEETNfuO6jMAb_a9PzyQPW# z$NxHPI7I~?`AVvPFibdw9mY@m7fK`&0fE}JYyamWYy3mycWC~af_8%Z!Tu5u*Fqdz0hD8vIRHP3KH(JF z9o3Ch-_2#tj89m$d_j^W;&AZOl4{eaU%x(u;R^10_$f|4^FoTUGN{_WgS_kv za}sE&k);z`V^4!+k=mtH5b;=Av7 zchVblJh~mO6ClcoWnUyrW>#GWpL`6D-ghGh$fa@97C5mgGD9A9>lBfim5q~{4x-6O zfrQ_^^q3|dSrh~jMYmP;)dY*8*V^rhjp8_(Bz03Y+AFDpO&s-@rna(#_V0DDOW#woeWi)hykUnC#kQTi!ljZ z&p#9y|6pdr0R_uOB6^~KCL^&y2LZU9xE3pc))rrrg+!>N?DVLRBI-5(E^BUvwxG_HQaG@UTtZJB{BI1i@f1{wm=20Z9bFPD1Le zFns=I{P__Q??_x6jGzC%I8#9qj99^+lcF)&i+|OAF7bMd*q6lH@+T+oe`E1Oi~T1D zKUnNE+qZ7w{PQm0>g%rKoGY*9_~TEeFe{&qZ5lH9?P;8M`EZIit>vgrUAW$hZFkrWX@-^S-E^IF_lhA$R$57hld{<&E6ebIl1p3uDbqC+O=y1 z9y^{7-+7z%?Yi>Bb1%}MZcUV%&N&xe!Z&~Wl;gVhVfu_YTzlI{PVCx_VS@*8$Edrx z_Kv&g*zqV*wF7u~{>HF-`xYinoJL7$Wqb^rj2s^P>lmg@8qX;M2lK_(-`g+@%H{}h zl*^b$|H|4`%jnpl6W8B%FL{N9gp|U#Av`C8!rWRs_+K~i?$kHw-tAbfyXGcJ%gV^F zRmih1Jj2Q#zoU1Lo?L#_4IGT6GW_bxc;)E_=|6A~^B1k=#+&aXKkRXQ_oH}u@>K45 z;w5Sq6cQ$eNHmcGEEJ|ev$h;_Y%hLUw}#FgTg4Yg72iticq*06;DPvQHAr*gsh!{~NQ57utpLCxGuIvv@HqmJ&xZIXz)Nr z-F71*Zy!a+PJQ`#(=XJnnMbD{$J4ZNefsr0kwK>o!x%$YpmW#b>D0D4gZuU8=3DO~ zB4Lc<;)4tO znaXiJPN46A)9Bs%Bzhfx4CkDEI{CTjoP1J$?tf@3C-myaP1jz?9e3Qy3BCIA;OH?_ zM?IRhJCc`P8po?Ij^mi_-MIa(yV<#?1dlWX2Ul4iWltPDW7}=S!Kjc;W~fp@xhNAM zGrtBSZ@-PVUmZ)o-o5#J{z9~qnY48!nc`F!oD3Xn))0(h*hLqze(h?yw(ra>x7|;T zf*OPzhXJP#;o#mKoP1(0UU>O6j_%Wo%P+f#TW`FP9zA;S>*u=w0MI~GO^ zx^fRQXU<^NhHXFuQBWlcr3?_U!J&iQS=nb%w802Obug}hN*KWP&aV}yq#}p?ZD0O@ zH~u99D(c5v#2zS&5b*+~AZp_jdbS<0c)h+dby%Qzdoy2dhqNqEWe?Zz4sT&nb%%qR z{%<+-t-a6)k*YF2cxwW0OnsLK#1)la3rBoK&{u*2J9ymmn~?LrTNONulf9n*TOyi&mOs2`twls6`29y0W3-sqPI>&k%Vo$lw@9goXc5syL>nU_ zM#N~*MvE2^@r;NO@r;qE5i!9v+W24eL_|we>@`M2v^F9pD#qB)wTVg0coGv4qa&h? zC!UCi7ZWi?w2n!nx>Po9+#tJ)cgTjdE2aC1XUH2Ld?pczNgx^j&Jr_5Vmd0uRErMk z6%p~OM2si4*;+g?5;G#AV`9XJ7$ZhU#1kW0w1}w^5l_VLlV@z-jfwfPG7^hMMf-BI zvJo*_#E20S+}Rk3d7kK?9Y!Rkjl=?3c|m>l|DM=(h>6(#n_z4rqQzLT>X?XVF*iDt{v;;_EC4reGiY3YHj?^7!lE;C6I6Mu_t0;zMTDr8PAuU3B+jI zWMZ}&v3=CO+{I`+$BdP0EcjeUMYI;tIw5cEiD*x>vC~y_RE%i*xA8=DRJ1Xojj{7i zM2tivsK6d1+&Onbv6NoRE_I6Gr=DnT!G5KZDOlf{ZLwV-)nNm@@ zM_zm7CHeZNbrKUT#_W?--+UsC8?=_!-kT$3@!8{vNX*Wf;6_Qa(DR?N#4HPDTr55Z zgE=Sh`l5%lJGdrTCqyUu5nq_%H#4$l#~SI?u92K|*$CP1_d6l5_*3nF6tQ#M=wM|{ zYRex}HgDc6k38~-zaJ$vO|-;|)2<%+psZWx_G-pDUR#YpOJUm;)k*kKiZPm+`&FE#pXBm`80(5 zL$+A-5oNDaX|@Y0IImh;jEZxK6d^x#903o?uhaG*6c?%MI6<-!!1(bO1JipbZbq@p zBn?i8I7cRam<;L0)5j*<5f z@p(Y53K34pVxys7W4Py0)*kEdYOh!@ZxFUq{@ku{Erp-L^k6ArzJ7WIx zB^W|zaq&zFS$PHY?>C5cEnBl|>(9J6?ltN(?!fc+j-+nATFjp_n-4$xjwfGvof?gr z(yUp1A3L)=T|4(QNCez8Y{q7rIVGN(TD1S{DztL^xn)qqKnw;OS5WSfL^q0 zUXKIC8yR`$EsT6}GM(Eu#Z@Wf*Qv|EfrDt&pq_7xw&p@33Zoo9cBer}1e*>p1yICr z2#N7?Hv@5xQv)W3R;g&EY<_oLjS9JVe!gj&gF1qz(lJ1a0;Q`FH-(ruq*96PQ7WE; zwd5#+V>HGjvO~qhC8RXURAU?)T-h;E8#B*j&XUKm5J`XgDM zf0qB&d-E%V()efK1X||lL;o*_)oGGW);>-UM{(>~ zHzr~#M5J1@j#)H9EHWnMfZyKW^reJu$ys zO&kI+{_D_Mk}kFoo<*iiQp*y@asQK8yyrUp*Wr}~xRdxtc27iCi9{>nh@IB{`QL{p z4zK0V+LDV-uH8r2yf~_ukcttbD@AmrM0}($B4SVc(J~QT<)eL`7;RCcO8**j*gXz! zgf`kD&xa32@<9F87ftdP64J9cT^y!4wBF#o5q~avN%e_{HhxQEB2s0MM5E)VtbJO3 zOODBvSllnD-AmxD$s+yL*AmZw{lFxDFOEPMUzA2fS4uGZjWH4xk*E<7eL%#->^Cg9 zD-k175!7$=uiFs++agiPf;&uX{>%2xB(U@(^xGWLpTykt`)NFhR9DHepH|5Jl79pV z^u$P&9N4{1EY1po_e7*W-A9?i>=y>#ijD2L3G-^~&(!wEW)}p06|N2xZ zi)k@BBAb5tTFx5OUvhGC4c4TMyWbRk;%hHb| zKPyAVPI_NC&mat>Rbogq0zMRMmu&qzsmwOu~~q+enprdpOS_*il?Gv(Py z?@7$7l+pK$lyt|H2~#FW-$8?9z`%Yo`oY^IoK_^Sy!EkY6O~cdTqez$x0Yp_x5)z| zuaSmDX_B3tD`#GKm8{)SEXBLl$%*Y6%HWG`k^RwXx&D%&l2xOb{Iq(F%zS6Oq~|t} z*QQJt;~kW_Gp0-D_H8A%s7TJg;%eErYu_R0)*n%R6A2Vgj8`ewUwFQ}^zsC$G)Crs zG)elOajxt&0eWv_?~e6ycAukV{<0Mk(Pc9JnR}#r|BGZ_l_!7uXrf$u^#yYN#n;NU zH~+4{&ySaLFCH%2sw1K$DlyMmTTE<^JaF&BGVqj(#q+A=`M=yD zS6?_x%3_{)6+7hA!KcZ$Yd6T0XC9GJBkz#CF;8}F`$3NDHAuc%8;PUSeaLy83AqLe1!yeL?NPZaV>XBX_RAI6YMplgRfr30xb<>HEmV?6)!j6--U3PV_oe?GR2wTJyLi?tIJvV?GIE`MiV6Bz_ZN&D)1my_=F#P7INaAL6mwGU^{+@ z>wt$66rX%8j!%2`iPr%V85c#I2IDiPeG+m) zRN|wi%C_541fG&6&H_&bC!G`^ECFXup+cF6O7X|qW-@V=kgA1n62m6mCv|AUMBqTl ze&&8QhnO)wQlx#Nye~`9AQi0pc{$sPO9*mUBzdfmz^aIkX7YSH1dQ~riHCjxA5v64 z8W%!K80`laS3a^366|vlc%B~i3aIo7*Uo2clel@<&?#{#95OEt<8b+Mx6V|`Cyd*? zv^atMlzmRbN4!mpFoG*$Ik*8=%m=zdBBUF!sEl&rP7m?tGXA%Vjg0u~D0Tq~r0__v z`5bJ<>*UyTJ_Ae)jvu<(Am{*ekNa-B@pk^6;t)eumvGlDH}T15Uvu7-*V5~xeztAK zppc=EfUtAT@e`8?L{d6{}YB;&V^3@W*A0 zxP2toUVAl1G-`nBfN~wQ8%9hFqa6AT8Opj6dEv?D_;T@TDpBaTqlJCS8n$de+g43^ z_x%qzSh|xX%hypwIM4bh0MHcx^(SKRz?P2eLja>#oPJh(|NS-)Rm&be2(pL zA|poJ&h=MZ&X+SkV){q3sUi)7gX<_<9l?#1f~4SS2%9Jn#tA8Y*|40OZn=$??K*P% ztvB=I7qfX_^fOe-p)>s7Uy`0d@rXtvR7Vd|UR}nLjr(ZWxEblhs8z29B_;dVSB_o( zFzi22LAg%l$d*lTRFrN&a`stS`J6Pdw zKDK$rK+GpwD;20O4%*+bMVYuc+i2^RWyGK`6t7&w^~0}YOUVHniX>1@M9?Nd!WZ$) zw~j&ud3wY_C6e#}p}0BL7|$wNzYgl?4eM_C+co?%E|@ zDLXbS<(5&SDLznTRR{qkzT1P+KslR!Udb=T`|N(5v{`z_phX8XaX&JA&<5)*h;j&0 zyV-k|^V6dFY~NpMY5UsvUXBSea&WaM@I)gHcsj=YBS-S-tl30-6Mi6f(FWramW}p_ z=Ei`DVq*JQvg9ZBR|Kkt<9oXK-}Upz8c#63`OD886Q7;dT&}J1paavUpV~?#Gz=vQ z?Z;>Inb+~(#)wT{<~XcfwT4GVKTK6D%KDW*(z9C!)@<446XxyWE?x=aUmVMVrE7@d zo2vbgH+Fnul$C5_@rpH6VZ)_J)gFdlehFVMU+we#b=EN|-?X2~yNK ze*bK`viMja7-NqRdv=+Kgb{@pg*JXJX>AbEY+k#R zlaBAos!iJv<)R4rah3e=K?rD#crh@7a(z02qY!aX%CXN}vX`b~JdoLXmt2`kD zC$~T;)Dnbzw*57LXEbqV6G^0D3rPP-x^+@9!a-+R`vb1)Xues|Jn+vymtyZ&lAb?Jno4e410Tyg1DTzUTa)X&RL zGSvrO!~)__P_r2q4w<*Zw`4kJQlc0Goke*q8QH-eOCC0n*^BNEIh@RezY^z1Bp z9NU?d^FCq4vX!h{yNv-uFQIko4orCERbG8@JSX<(Mc3weY+dpdvuDj?&0bB{*A*~XmDKIi3e zFSBL)EkE-bJAL4(!Smob_D5~PqkEYPFd2?E}?ZWhrKc~Ffkm{y@GK5@%@jPN) zJkvSaxP((O2ssXjM<~U?=qS;c=dXDh#1M8|8%j(${?e^M#c-9zQ8vY?ZBC5Qe;rGc zR!1`If`N!qG-}!sKgW-E_4_%rl5mG;Z907A;y>;VS`&*-cUl2P!?ZC>%T=-Lkn^ zwIfKZl*b>wp9PB+6Ls)|Pg`D4$N|A6DmF%-qqOxJ^L1#~QFsA><(KLM#awpYS*%&R zjwoQ8rQMoCw@G+ zeS5ZY=bd-3x74OaGblg4oZVI=;5&s}93?1;T27#qG#*&xNIVo#B;=A%Srbs36S7=B z$8|6gK_fnJ>VdM^LB!8@YqUqCstOHc=Va5fXAe>`(yfAGqJRO%r7~iu@GQR!(N@_F z5D|&7;IkP#`|MM;oyH=xojP|QJ2wX}-Z~q0MGH8tix9I&jrJ@G?kHmZ*d#)G1TeVW z6qFxiF*gjZi0%gf`Qv!NaoXag7zB?c`*RDuvMF%%w-W0gO(IVV7m$m;a_~d zpn?!U*gV`iIBJOvljHeFj&l4kDoHX)jCMi^w1~Gq;gb}}!$4Sm?aBK8Dhf9gCLDH& zRaaA89VHw}0Y99FU@*qBYm*8gxEK{MU`-;(vT_NIy|%IOsFIezraS`0(1sUEw9!$D z%8E*2QO$v}GL)l8Nlj8u^2l0$h8Hs^%a6>6RVj4meq=ywL;^B$-7K{K<1#k(a-*DSzU<%(o#|puZqgDGE_Jd@$8|(bsfT?R8BknOzyew0iJs1 zIUacMUQ$#3fg%29i`ee7l(^ARJv>Dt5 zMOu0qN>@@+Qh|`d_H8@K$jBr&D-#tzfXQwy&65Z@ifZsoZqS z)ue@79PKgsuTRjv}1*6O%&9s$K@B^30Z!8LSguaLc9MH#nQH`S@PYNy#D44N)N`UQL`39FFcPfN7jieWdP;n<-Gj- z6a2J#GxeLd=aS1Vr%ByRmi@Sh>C--9>(1Te*RIR(;n&iuY= z&K@?5-aU>*r=@c+Qcf75c*|;Deq{pdx9%f5Gm9bTU&^t^9);^@Hn01c@vptc)}6)V z)vC|A=bXdQo!b)_jd85GY4e(8jD2}LH{SCw_430k`)MU#f47<|FFJ!4UU-JZE7noF zZX+(g>IzykIs&7t6NV^7OlyP~X<{hZy^U91n_0rP=Kug807*naRLG`vtH{a9MQe?# z6uWnB;qk|wV(>I4uu#Wl->T+`5lX(4|kGX5qNE+8ILWzKmLd@{UeWNL=djz+S zxQ6stF>g%$fNjN<^y=N0ONaL1q0tYqZu4H6x9-d(mtH`fT6sic9-=)`5w`xajyEPx zW7C$MoY1!~Lx-GA7$H)+m+=!PvUueN8q}@Lbr+qC7mG0By6ecxbGd!g%`|OTpAX-e z%G}Stq23Wqx#Y?#XjH!@8`iGk%}JBkuwyUnI<%*I_a1z=cn#NFejcernL1@6*^S!L zr+07C2u?BzjNzrR&(g9>SB^R6SgK05Gy2I1Tz1)&?B1}HsZ-x4N-C$Gc{ZmE=!=L& zj76*?(f-nd*lpZn{+wC7`@u(~sVbKLyq8Xc93&QD@}%*6{^fV%71iRrORwOlBb(tk znkC2=ivo< z)#H>wC-BURQ@Q@i;nYqmr&42;WFOU3V!(s}g)6amSYip{|M>(5jUp6GR{%#)VhJKU zx31&vyGBsHetk9J2M!AEbuPIUJcmi_oG^%^&!ee0G?eCZ_?ui8wV z8o4-BaqvI|TDfSYFt~)X@~BxOpUE#g!Pb>uFyxG$6y{{39TzX0LFZO2Y1br=dv3gn zDQ#Qv-Q0z=?9!hWEt~NLArw&*f+37?XmO|1Ih?Ys8FqW^q*4ZsfTh?@gUVrJKv?r<_d7 z#`SpUfrq(x*dWHg@+POAI+Wa8KO~t1Vek`lAFFRF-?_~?bBU?o!x`_eYVCUNd*Wuw z%F2lxET?v@98yxVSo!ltR<2lySF)L^ssp5_y2PTIZJXBf)AFB~{Q5M`Kj%W~=KaTg zX#On!jf!I*<$ztIY*5ZW5F1tqqAU60(;57*dK+h-e<5M1=Hd%3WA*Cw7}r6gh#3gE zX&irC4{o~ld^T@f$&0T|LQ5r|&;N$aTPwKy(n|?dmU8BRzU;4zvUKqZ=FFPIS?8Zk z+lE=(ee2Dv*tiW{QN`B_zNRt~qj>!qzWsg~LoT_VX7zHp`r4b>bHHQghUJ`m>M%-T z=?uHzLRS5>imw)YO-urBxP$?=ettS%eEK2F)^0#_6<>ZnhvF&+70#k-_Y)X?&2VBR zn|R{MrzqDt&P8;^uxZ8jEL**f^6E++9CbT0=Y7p7XPk*Em565--OP*(`VH*Q<>wCK z{kJAC{_T&@62?u<;N&3}FygMeIH6k`W=@^JwYNP;*AseElo#gOtFK|prgfB*7W3h! zUvS2mLm1eippw#5ClhAv-Xh7uj8hXchRCz5ew&j#M-UCmMU zPD&;{d-mbFt1f5Fck_64!fPDF<;TT8uyyNt4px_O*X{QaBg`3t2k_cc5Ayl*bqge z2uSZFl#q~+`Xo;~XYcoqbIz0CIQL#>oVoYC*Tv@vDbI7xKD(^7_S(PoTV}X|B}+ad z4(!>!g-^d)MJTTwdHEfWKJ@+inJhL#V z_AMDlVL48!UCZ3rQ&_pHlyTSJ%#eP^5cK)5g^vM)2Qp>q9gMwv44c-k)XO%;d|}n~2nw@!?-SWW)ty8FBh>{8l52 z|MV8MjS&v*+s%tlzraZ&MseoxeVBjG6uw!#9@`2t?T)E@UmWJjYsOI@Zea2I9}$no z_-4gQcJJBeL|Qc+C8NCX_=C)O^m#^&Ih)D@TNroaog{oAPCQ`<3m$xot!pL2DnZTgIkZnj|B z1M`?V?G|=!TE~ZO4O9^ULIBrlAEg2?lix3~VhxAjL0w&e@{~X^@hdMj#L%BQ->7N(zCTHe7Pecv`j2XZqwD3Hki=8F~iu zW>075rq#^5e?BQKav0FF6S*x~aMNuQ2xSC0c<>OHT{n>_w_V4UjcZxGVJicM_M=0G zuCy-b#qa;{3^`eT-h1b5R)4pN#+nHJW?JFr7vVxSoYN5{3_Lgy7@RZqD)QU3WYmb$ z*wjeX-hEigM|O5=PCW5sMxWA)6{|N>Tv|@Y0;hDB1HX~v7j)u;69+J? zXC`ldyort9ZKiJT654br;@)|)$kG+>zV&B>ooJ@)!1Dz4%ru4%Kb18rH*k92d{(di zmUC`64IyGE8E5OZJ+#Wr;;XHPX^;}>0qb2XkQ8v>P&vEy9ORFS7L%Xjqg%TcytDE_ zl!_trIN@lF{pI`V(Y-sRhiZ_PKTj%J+x%BClN16-cX;Jp=+riG=r5tnY36vD?BQrCbH{Mu8tFdF)v+p3k zf9F#QT4&+28>l?A30rBj@6wH~ZETFlA>MxFHO5bz!SFLqVPKy^eskdktXRF4I04$W zFXZG?hGU2XRwPVbN}RnVJIHC3M}$-g3)o$)a%u-R7CXis!K$UpXy36D*N(rM+<@fJ!7#tOe+Dl+ zcQ;x}27``2o#T6C5Ur|Z@n=h^kB`UjnF!4}Jkn5Tx=zdNY{Y>wV$m9o8+IaopNW(@ z8JRg0b?Zhz)Ux>XC1mHeqqeRVEn$(Cmd>hG-?1f9L1Q?AX$tn1SCEq4g3X(EGbA^U z?7Y?tI<7ArvofgIvd%fOQV`JmWTb=`di;rW&9T|={WiAkJWT%_NqJ>8b02z&Zn)p?L918mcI}_U^=1I))u*?S}8LJ?yRYGjYn@ z+;rD{&X3U=zFfM5(jyUv*2Mt{P}D7(sF6v#4n6qm`>)ZdAdk3m2%v-xS*^S9;;XNs zFx>PQFp*4~J)dc_A9C=tnoF`Jvp85*=2TZwiZK^o&X|iYLux)8`X9l8gS)UaXTA?S z?qt6D@^qx;Z%Uj~I(N@}fIDZI=t7~%C?%yOU`JT|=U1t3ln%MMJIC`{=d*A3X8yGJ zYdZHjmeWoiiccj-$!W*Ci{Ew10&0%#ynfQ1Tz|_{61od}5I(NIE3Fn!Kkq-HwTbVq2=iKp?|7pFT3heEi}oueSo{}OTLK{Lv4 z;b2iiX*tY!@KI*YdlaR)^HwFeXZAcS5kMdaWashfTd$)uBT3|(JP6h_?!9*gsG~_+ zq=I21&*J#e=VA#BAA)(0Jj1*N&*9BeC7c+%t|BaW;z<@f@d9zBAq413QP8<7%U7+z zbNjSpve_@GA^%s!Kr|t1yoxkGrf7dQNhXA7SkjrW=mwqgvZ$-6MwtPWoj?;&K6v{r z{fW6yHdwotrIyE%i!X( zh9h(XW!YdD2%$MUKnW@#sjUl>-=RIOIU+ABop3{hMtoSB-;JEeBu>k7Xq|sH4kvw6 zX0;Fow(aH*D~p8-=JWZt-*M(eS7HYISdqA+G^9XaQB_rj?(>u1rai%+!ByjLC%a=; z8pDS%f~jQZWVqKApgTk#E~LJqjC=2zOkw}y zY2UU3LiZ7k+obulWEngMQ|92{%B#a1+q)mS4pzo{_%Zjn>gu|nz8Aw~uAuAIZsl%2w7AA(9 zb*vB|LR@v@t+f5-+*tEFOOBS-STf z!jjjXBQrHb+x$ENhTyjoZlOo-zKHlvY~@7Wl^5~GiSkHWL*R2QX@a!O3=)>4vZ{_y zS~|gC5U|j(5tc)As2fft3Qc$BSv(OX(imYt#{%*Ty3($7dmbKgCT;Sv5r(8qZiqbx z_F<;yU_z_Y%xKnq$yjfzxq&#l+9yF8w(F^&?PK4Ju4eYKnxIr+?c z@?pAkXzlPzD(~phO;pni2MZ~{l(@K44X?FMGLVBfluCf`W8m<@I>|l`23u=3vX+z> zn$J;lI5=uMkw7<&uJ-iviepK0 z%D>3}QSsI)Ha42jJoMYYP#jdcP!J6_P+MJ1w4s8P+YfNwWuq_?QGBuytFfB(>o?Hz zgfkd@?zyCYwVeI?%TX>VvZ*w@^&||#QNFs4tvjT}PG+1$mmqD0ra4ZdM4$|(mZ{P} zHyylQL5Hqvd1n!&rDfP5gZjnRMJGh=UTO_(N2dRuXGyAfW4X?$M2pKl+#x26QJJt7qM=a)zEY z96xackWgUB7_n%Wt;IDIcIiU8-$bDB`3zEmJ`No`KwVuIOw&e6&+!5wZ9ZSVp8hAC z#+Y+{&4x@r`#<{HIX*Qs6hS()>rQ%5r%Pc0UAuROM1oLeI%Ruf*pW(>e)A23`}HL# zBWRjV$Y-#3^Jek`tw}c|g+05nX~Skt>RZIl?Zq6b)#=~6E2~$o$3`ZzTZIq|IB_U% zPPw0bngJB7dnyzA@c(Z z?alROF0KGgH=5exL01H5y0bnE(ab4wFK3uqv(I=`N6uB7-_mm&MQR(q-&+a7Y`Vx% zE%UZx&Hw5;>Pbq5rZ#9vdZnfuZqMn~lO*)QbzYs%cpvvZVQ5WwZBG~IK8KLJ`I!H_ z1rVGL7SeXf$h~1|_S6D*j;LhAh0v29_W+j8x@y*6!rffZY}lJc3X|gn&HBR`FQ3so z8%9t5-S|OB)cLU~$|!`xSO7nLo%|yI|BK;FCU4i=?AY^PCCOc^WaIjk+;G!m?AlT~ zbv=gTj~_vHnn`XteE64-IsKfAx&Of@7`OIwYQr(w6%;v&RnxF!#GT!;SENN z8c7^KLMgIZwqpFm2|WDt?|AD)lSo4Yty|}jnw8D-8y6@I8 z`m&q({L|0q*R?$;9WAvbmtS)OFFd}0_ug5|jaOZSt@#j%sIxB@I@e!+4G%xLkhR}` zk6m9!+aCQ10wQ4}?Ety0I&krYXLH~5>G)EzNKen?fk)=hwp~XiOqj?Mb7%2VY7SZH zY0R26i8Du>%KW=;=Cuy3x%sBcxqjlU%$xTF*M9K<30vc$tH;x$QwP3Zxe_U(jzLs_ zFzDWQD4jZV;H%F+F5|DbhF;wZxqs@_PCP?Ox(*t`fC1k!{r1WD zWt7yMcHBGbUWBN?z`_(U6zSN)#FiR{bcr{V=fF4_=dZo^JYTNdfUx4UY1f&)-3m$T zn8gQ+-(mc<*HGBC7n5(ehRy5NGvV56@CP%=X_?FXhvqQo)Kj_S@=KXL?M}=qP5S*LmpUQ2w+{xKj-Nv~W zoI!o~2roYW0)6hdlzSRcK_oJgc8lDuw0(bq=P1!MHzpQ zpId(D%=|}V_#ZhwfA4eQa2QPpcJ12rk2Uarm`EvIinL$mb8AM|^lo*Ci zz~@7^t7%O55Jmu>-9StWqMHUjJAxI7Ve0{65-@erO%N(dJgy<7z!Dm!Y2w!nkP+hX zIC0yD;WzQ=7Ag_PiUXR@p};Y~RyOgt!sqj02pcIaYGM+K}0Utq4V#R8(Y(G->qx(z(B(SB8ZR_~`K9Cj;H=xGv zpM8PlE7$Pov(LIE)I>6Nprnfh(iK8Qh(;n?a2px=+FqQnz1=XlKs z5Hu4+6AEdj5Y#l3<&2vWKBQ^lHw+9FrY@?XnL$!?fwF88i5ObQk1q*AaF0k;j6^g- z0zV0Kbi*KI>S$IYG212~4dR+Xy5EFY9r37*G((_km_9$Ih=WWJk4tQ+qjVjg;lm_C z%u)zn2tx=oJ5Hpb7LnQlQ%VwzQS_7)OscUgfzmVa88*_25>MD9Y?wCZS<+gx=Dx|7 z5RF?X-Na`YPBaUNz#<+AV_6Dm1hEa16b-Cs7=r2ev^dI^#4Q7(W-F(keF<}3c!zEs z+7s{@Xr@U(fU+AWTyI)+MM#o|N_KdGjPu;av|aYQHuO$dkbpn2E`$IvGd3AS(F zPC>zsQ(|n~xRGJQh5=AfQNf}`i>RomNJavGnz*M1Nwwz@Be{^2f1pI?e-@?rXASsI zi2^k*Gx}4n`;WBqzv8H=AN1)DfBr}0?|oJ&g=JZ2nwFd&|7a4@{{(3s4IDjsGy?_< z_-}5}FY>Px&*5LOVub^;@S@g2=*>_F{~~ci;SvMg--2K;Kq?$nzt$JZ#&o&CL?DO~ z;Kz%M=$Jl%&y8IoLimF|m$=nL8E(Z`BLzPW-U&U004`wGmqNhh=Mo}-&(si_qVnJ# zo_zKtbYBXGD{BZh*qnUg34Hna2OKJINOBH>qHX)m3>|tbhOY$~qFFd!58=~we5PZ7 zk{r@{Iw9SO2xvx%1H{Be=q7q<0HrhnILFu?-AN#zV@W|!YZm_3`~(6f0St%y7lG#Y zWBOdBCjcD$QNZt!2kQu-lM(c6qLZYe(9!*=1eC&$!!4$1Y3QPf|4aC?@B_Ypj=*Bq zwspMu`Xct##p&FmyTfH@1PSPl!SnE3j$7u#AMz*1JOSuh0G|Q=$hP<6P3&%RhjLiv-J zPhl7g8$O)8tW1Kz0JhLvUgsc&=EE>`5Z=8NC<9+04bwd?F^p8FxynG-4T3=}iG6ag zI$-)jm`V^3O@}iI$MNy`3~Z?o!XW5(nZ9HKT{8%V0$$A0CFS;$8gzLkk!YrlZW?Ua zw2JRH7P}6vbGQ~v&*F@cXAsnd<6z^AGe!Wvq2WVIW<%<}3=E%e$(_B}zKPH@0s%nj zNEbW~LHs&RAbZ^)nBKxY8a6P}(%h4;3`~cU0y|pEAD(-GgVhnDjg9QyUCpd{*J2BU zfZsjF!mB<4pkW3xoSM?f-zfByG#s`?4NWr%`aqgG!Z6W&LDEx0&T&1iGpq;k2ff2s zAHIMO)ARE*AN~}dOENB+ornJ8;?*plK7IN>ah0PTh@_7D88~d3KVH(&{4Y9NKjx_X zR7dHbi5mS>N9iAF+s`F`@7^UPCA|Ln>)dh29m%=!zd;r+Ui{zPgkR*}EQYsSG>

zX8=?GN1_0X6wbf=CWgoT1aMAoo8S{p3Wr0C>qg*kvY0#*;-OE3`+k&;hn;c`(;P&Z z1JYJU86So7Ugv2IoSIgWl+0Yt96g4*a2V4JFtJk+ZF5_&Ib1=)swG(_1V~Rybul2` zeLauQp!tv9Be~FMJk#4`Al)hvLLrp!TvH?l8UkH3m2Pw1=M|fh&5rL?lKj}~8OQyw zQ7+@0aT` zO1mp3DaAV`^RQ6@Z>T-E0B**wNp8n(oM5)(k}C_zZJmxQWf=+F7-L;U6^CHmPach#JGk=wvovE6&{h!xk-dy&sBt6~Jygj06gp=## z$NUh{?3<)R=%VO;P~Oj3&#t~`R^3y&eWGa6G0D+P-q?k&c)AE&ZQ#uzk^KGNZR>v~ zO$_->EogR~q-t*F?;fRhyeXwM;Sm2eox3?m$tx+S9resV-n4(6{rW|Ik^gOCI8h0= z{1))9bO6D@9%x#S4xM|_PP&_7&C>@q(zdBJ(tvNu<7?v>pCy<9QRi9O1_ zauunC!oWsHbB&KD!i_ElQ?eL1XfO)frRMM>fc^uHb<2sk4OPOe!r(O|ECFoR6aU(=|jiP&8y5QGBR3n>ZxZSo3&G7xmmT|xFlnKBptYB zk7ijG;c%F=tPC`q5`dOl7BJ}usTh%H0?Z%*_n0$z$7El5W8*%HvT-sjMKfPSCfm^5 zrASU5Cwxt(&OPbexo4C0RPNKb*A>F63GIP41V>};CDM*i+mOJYnu%X)R)Iu_A8bXM zoCwe95GZU6oQ;x~s^DH-XeeP))cY8^yT463$;lOWv^b9*B^*hh2Q%<#&1)ifn<)40 zz6=Ho9Gc9GY;s+7w~S)5!TTHe;nO4^`tN<WP!P#}d{G|9bqa(Vyg^SE=S*@Fvj!vC$`oh&(kUgqN7-9D!>BCuzp%lBV`4@4Fv%j`Mp#)5fN0 zbMT+Y-^`bvXHI~-_M6RKFJt|vOk3~%KUP*$;O%mowddz+-!Jlu{8z)}<*){w(z5dP?qeo2l>W(qi6v z<2C9V8@*Pz|9iwNu7jimLg^ToN$1Ha4=0m$8ezL7-IAA2?#i87$2NG*odT3((eIz( zgAYCc1ws10#FmP$mww8pOTQ%H8gl0XF-nWKGXA#dlvg(%z0-9a2%#cWRhCj+-{6$F zqp6N6o`F=jkvu0Zif0Z~Qwc(^ZB~qf2TF-V-SJUgc`>^wH?Wxl?Wsep`L15Wsn;n0 zU2hr_S9CY>Q;DEytJmD*Xefl$$fDO? za(Kj~&Ee8RRM$5qM-`lX!co0&)I{~>q{ElyBvd6xR3G5JS+m$zQ{%el%8m5lj+ZlL zx@MwjhBJSaPPnR?KRmaP{iRMndI8)YebGE>)YRU8R=iDG(=NxRrg$qi-f#n-ui8jm zZ8-}UE@b1D-Jm3;`*ySN$;X&I_W}O=(Z@vMF_wS1g!vCXz{8I}$<70Zlk>}4$6i$t zr+l1r9dM^}6$;BmY&UmvoA-3`!IdO@q?D(hdXn$A?g13x`a0^vF}I#@j3X5#JpI%{ zcI`Rf-rsvQX*_piA^DDGzw+K7o9_9;&6`rn-LSdIFz#?@!dqBQ!xc6OJ3(1hn3!zl zJxQD$pYm!pIS2TKM({QNv~)iThiKAeA8X>G zlFFsy!3{n}sXMZl$&;s1QsolO3c$7;!-sM=BJQ}@(p8?aY0kKIQb!=9mNbygC`c#1 zcGQmBOK_41rJ4+;+iOBVV?!MW_7!7G2-i38!TTRj-xx-^{pCa_671NygUYIUk|xF5 zFbTkp@y(LO%zNl@qQc#qD8<*yzT)r^$LX<^aQNT6D4>o*!6ICW79o=kj&Mg$B`e4_ zH_q;y64HrCDRs2Ha3Kqccmw+n9K_b$KP#u&hEq;Vy0g=ZlDkK>3Y3(rSoQ^bcJGGB z5pKF}ET64fk3*U6xgk#9=qNXO>ioW0$^)Joqr7#Q2(xYTW~_wm>KGRia8%=6_=h{L zQrJWy4Sey*5~^zI9G~C^PXE#J!+hYQfBHwo@g*FCu9OqK3?DA#!*}23KzSXzwr%E~ zyYA+Nm*1qJdJlI@n#9CO_pso1kF$K)5;m+~!OCXhaYoj=Ng6`e;luU@U^>{h_hz- zXWV|n}Izct{ zsZnVfg&b(ECXl29u7nWl>f1TmI<@(#WF4dst-{{>q!li94vF>+?j(SDR` z6TH{Yy*Uur2#;@7McKV!4cA_E89jUS=CspB@y@$ThzbE(n6=-0!cCKA(in}QtOgdn z`T_$_9?i}}^$sUuvkEo8L;`=2f2SBfB#Qi3<0*ua2y80K%GkbVKhbE6P%ub`?mfuO z(y@`)%H27|V{F{8j;h*5QZw@??B0XSpib4{a(3+6OEeb42&7TeyEiS;Lxigiv17+J zY8xen>7z?wS6b)hlHEF&u~%J5C=?=IU&-bz+o^7d6EF?h6&BGpFB@IN30K#$b^C7W z8lw38DHL|?Om53;n($-*HsR_rHg4HL&w(e9=7%Fkswh2NOYg3o*|cdLhpTD`rDW2r zsEDkzAW}NT=Fv1pj69V(JsVKOBQ1uGh6%jVr2si`3)Jw!p< z0=DitK>z;z$V~C083wwHQ-9P6rb#BAzH7lrV zh?Aa~M`2Mn(n1CoTyzm>IjvDj60Wac`;NWTg=6IB7tpz|6Pl*5qV;UqzL&Bi^<<=) zbZVujtSDpImtV0zS1_=DFVa&}*t2~%2M!z{l$JxM9zDrQ4bV_m#jc$@sj3T;)he5o zx%pI7)=|{8GXWiTZ{32HmQCAst=)qyk=*%j-?WbOR;|g&&4XAKYrfx2QBf}()Kk(xRY4 z7xLS+MI^%P+Eq;X;R>XkAiY&vx^?SL$n=h^n_`$UQOk-I-_p6)P+DfCkcc+0ZA%Hg zdUYY%7-8#fVF2v>-b+uBBsPPf}BZ z#2RW@wq^?hdlxa`)>~-PKEH`s>R+mzeq4mmQ1M!J?%GRfc@^P(yNO8+DWOwgdoI25 zO3wcEMU)-b&W7*TaqRIYF=fhabn8;UUq5)CiX*i={?ya7?bMNuT{_^oHoC4kXAvq! zX~|xS_gB&wi{T5U)48x4xver0M3J#Nwr$x%MNODMYC478dyt*#L&n2w*|d|2BXx*S zDn&gC>D|8%mtTGX!%jH`VV6_3Z#V1Lu4PFpAHBNgFl5*XTr=*soHYCdq>_Yd%Gk1f z8x2uKR!$qb6crKF5>%D$WADC0G(_S^%^<&XA?@<>nvU}|&)c$Ts3~XF+U<1d)t`b^ z8I%j1l*ReC*+GUWaKf=L1JJ_&(Enj?|O_yGM2*exNwRJn4j~PJAG{LHG zSJARv5#2lHa`-?AyNk<+NkPl}wsh*;!A;Kd;;H|*IQxAM18ae@*t>BfH(WoF6GooR zWmjKE$==<}y7w;DZ{NdRxBi+$tcLQcYV25?PnLYZYk&HHXMg`Z`E4>#9@D(?HqF1t zFY@mbiG6*PmwL+g~&M)ZrBG+<_Iy=8*?(!EZDzgm^5%x)sYPuW8_$ z4F@=F)CEi!dj=o8`zDJPEusJ5V_Cm_Hz}DpEPUc&R(!sMS+k~d+*ub>QCd!8LSz0z z^T`VD=l)r9nfLsQlx_K%>C@-aYuH&-lx*XOmCCaVA14?&z@3xsq9G3L3%l{rr>nSX z+*p1)?oxCGS~9EDCSFy-O;=yW?-qT|alKmc!TW#W`{D=>-7}u=SANNX%0|9hyPbZ= zpUkZjuW=(Z5}|Aszy3U>W>0RLbQP~I{2i~n_ZcS)8N~j*#mKmYArr*HhgtUdUx~#m zmVC92iPP@myi?mDWrBkx`&l2#At%F6ZP`|)&iEaLU5lu$twn^gnSb9zWJ3j0Cf&v{ z#}1{SeJ*7O_cM0l{e1SxU+CAhwKEEu#8Q$SJ9iKhDRk}Bk@X+F%lDks-N^ZuU&57_p3k$7J;rgTk7UH?Q9SX;Yz`c*BQ>)v8#eCXzK0jk zvwaI*ec}<`{%8d~2A)KE$YA`XCt%A6TQ{wvt}KNfUE8o>?YAsg@GQN06|rMq8Ev~1 zF=yr-eEr3zJUVAC$Bz6Jow|3TsF!5s?B{v$x%p%oiUqUp<+O2=$Zgl!!2n8Ei3*Dk zUU?qbx{&K`naH7C-!XpD{VaNWF-LZ8WYvnbl$1x$XU$~Xw7Fz=ZOP23lc|#-GBbi~*?X7==RH6{MvU8Un@F1u-N{T1@X6O3 zxb^nix#ZU)+<2kx+65bxsAk4pH*wZ=bGhM)Q55gl#_V~|@zOK*GVlJ`91iS@b+6T5;EOX z1?3(gswlsI`bpk-|0DVi8A{E;ErjDXntRk3#)(|o+ z8bk<97lf-0@y=_nkl*Ea+71n3+cs;~uHo8ozvYhG#uII5q#+vR&M9}&reiOjeeo&s zx^{3bE}f%(>{_0GkJ}3Z@w@4F@%(FlCSq%3<+S1I$#--6xU>25A0A`ILw_WuBz2JlgHJk_ zCl)?Tj}CcGFfs`-NKjY4jVpe08JA3)&74W+@zjF(Jo(Hkyt3$J?w$20Qc50qa4NIz znZeHDy%-s}oHpiio}D!wVJXV?ZDs1@skCdG!`rXSW$Kh$*|1>`bx}pzu0wg{4-YwO z+-_je%P;W3`>!+SiRZ9OHZpm_WFCF%BS!Xa!6j#(&985n$J~kMaLd>W`Fc}1{*2a~ z_^VOOoj;vWz~{uQe};N;-ocN+Mp}(byZZr#oO~t|r%WZyXP}+jpTWm;W9*Idxa91C zSV)v?xvZ{m*c7po)8anqo zmT9wRkR}scdC_I8T>dFTPB|IjoOlpQP3O|9$0LC*pMTHW?=5A**psM@*bEqUCNuAy zz@DwE8GPLF?3i*pM;at8a@sOu#!OOGHD{kcj;(w5aeOP`g5w3zs7>3#W4LF=okR~8 zGy1}bY+AdCXz4P(-d4uv%f6yzKvG$LBhkj{<_XGp8KEuOwV_v^9;{ink)b_LVfDA) zaO{|C5klv}E3U$}bhdoIjycc&nR;m>F%Zhhg4Lu15|kb~%%9);oM&Hpov!V3*u8NL zqsBgfRD#UxJZ_yl1!+aeZ1n~!R&Hd>NgXkK>5Mw}EG`;xDrU5jD=)o`ekWbXv?(_e zvg2HF$z`lvyPS4~T?w`B#+19Jk(rSKx}b8*g^tltfN;t(*&3X4*<}nH+>eYzn6JZ? z3_AW)CQZAUbY-DgRa|}J4cOApfKNW--KF0$=7KQ@eE9VURaN^~wSF&;KK?WT4UgeC#;ZZrM&60$V!A#Xf1_mvIy} zPrtB;)SS*d`PgIV<`ItEJPU-vGy{zJ^@UirVCRA=yEb`)1zHBlq6JgL5ZwxZY;U4O2O;D4$LbE#Q+sy~~uD#g1Wi#KeU(X{izD?`Qbf!P>I3Itq zg3CvCM!6W!O{>3T`FGoR`>&sq?YCI+r$6$$C+9Hqq+^-+z_au}?hJ08d<#BJV8lu> zR03T|kO_2ufV0jU&8X9dks7Jui?>?w#@ip#Z|c=7`|?YM3>`sgz(^hhJE4pQ%J=Qy z{-@vMnHOJU_;Fo`mv7?yYwtn`#al1GM&I83xq89`O84*Lk{hN|QxE-mcjo=Se#(f` zj$_qVpL6ONCz6#NqA7Fwzbi@-BU*oe2j@Ob0~vh2@(c9C>p1DGaU`q+ShnNH`E;Z( zut?#eao6$OgSVmEhgop{0y1+uvu5*ZT4o0EYHcVtTVJ@F%Zln+TDI%MM<2ey&b3Rq z;)-i|df`wm89j)npIStV&iz>a<_kPB{dS&z^;Iq&J&2D#|BMDb#G7v~rf2Ui=(uzdbVs@$BQq&%e8mRWWqHUFz$kL_}%PB zIQP`SR8&?%dM=CKTu5#4R?Z(glZ{(;(78h%DQ-5ma`CMhZQ9VkPj42#@g|clKY=w{ z572ec2u>M(I(v2>!mli3Z8>Wh@s178EHq`Ldy4{?A&26OmOq8+_7!>vFL#q^x zin9GARGj6XeaNy;m-5%oKB7nOPDda7ddYSF4I7PSS+HQW{Yp6i}px{6uPNDBo91zd?Ez z<~aiC8N@0MpyzgTLEi#RB`7H=X5Hok+&N_?K|O|&HhqQ-q`s<}l#~|ackJj|JR2n? zQW;L6dlg5;8Yta&kes|c1dx}VPV4j_+xPAwrt3tL8H|d6VKTH=8&)p=nC|_CliIo$ zS!rpQ$p|2BR-PcgM>pzfKIC9&6>Ha)aQ29iB zIF#(%M_%i8=z$<;3A%Ub#3%2)jfyuowQfZKQ1t3jz-P-pCu-TGnoTaCljM`iIp_U` zcdnnsp*?$f|1Y01`kE<}6mMtimIK^*_bk%1ILIK!4?NcM^wAX5RF=`YeHY9WXI>9I zrjQ5gt0}LlX2aIKoOSN6-E0pVG=&mQ$u&)A7)nPED z+&O8aV}xxBT{oN!o)T179wv@Sey45@*|&_LyK8C7)}0)vsAkoUVgf2o&n|7zWi5kG z7|g=SkFsk|IUBZ?F#ewTXv#)m{{RT+;zT6~&CLLJ@n22i9aXvjwSP(!;o4eiYa+DF z>q%~YI}(kX(Urn9O*a_~Y-u}sh5!-ebCR5B#MEpwJ&301?xw|YR?t970k%VjrIbSH z0i+Q0>eYoVZCbH@-Fi+NT1ahun6rkDB0W3Em@`k}(La90zOpb^Tz3l_cizLVN1np* zr~QiCrcNWzmRJ@jDL^w3dI0<>SSUA^#QhOGivO3=S=cTx;RU0s8l9Ocvj7n%mbMbnEXbCCKjBjj`je=A}O@Z4H%UjQtNZaw=@ z*rfwAr{BTU>Gv_9Uy*YSDKY*RaSi?=|9^>=1lLOSpS<Ppnw*&(k$t+3fWFBa?%VMT%7kKZyM+plXj)TZhtL&<4z^{HnvubQ-P;fr2%%$ZCQ5S+yJ+I&a%wWBFm%{SM9OyZ5R zzVH}2wQ0qNZ@orV%Um9O{0S!AIhoA#6a)(0Xv&5Jfe;31p&(YYp3;4L0I;P)i;<|W z;IRkqXY@svG5_f&x%A?TKuH(Gtss#=0m0N3Was3vedBr;`7GE|T26MWR%lY9*{)p_ zHbPiV!hoCYpy>j`(9sddh?g;KqNLUo6;|;0<4@7I-yj};>E!0-Iz49wu_6tQldn6WV3rV%F6eXh&xWxhMgt&Qc}rEPosU? zZ2lj6=N%0^Kb@um1Rdx5EZ@9sG-}PPhS~JsAUE!oU=Q%q(d*_ZVDDeV2 z+_dsaf$7Jm3~YCNh)Sea|6|EY2=naIFOXQjF>PBma{a?h7mFD{BAHnQB&Z0#Z1~32 zeER`ECW_*cV)_l}%|o+iGy9Pzc=W-0Db35KRof2ar~7zf&g0n0MYL<#lmz8cieNgl zD%#_kv_W}+M9TRe!NS>O#z5fTFHSVQ0(>N=WKl08h5fsKV%wIVv9u2hXWl>=4*2x~ zM|=UaVW5?O&(TmTWnhSk#z8x=xVHN)0-`arg-8fQ*t_olyUPzzTH1hm>1m`UCG*v1 zE2uhB%g3v}Br!3Wtn7T6G;PkyFV5wO2WRl%;x~Ee)wi+n;qw_NBY=?*#59F%TQ<2d zL_Wf<{z+p{P*g;Msrh8dJ5(O7Wc?32@CE&3=hnkC3@2Dw`4H0p+X)U+fE@+kfZ@mR zWiV(^AM%q;ZomC*tY9)jhxfw{*YM2Tr+DhQ=Lw|N=k7bF^2RHV5u}=%Z<)#V12y;( z{Di9yP;ulig3Xtotzz>}JDK(HQ`|7=I)XtzwrCO)lQ4}4hxhD8+XfLMnZ(pA3}Dyx zUx;85HUUEs#$?>YtNHMq`83YU;{I8Wuw`#K5s71D_(#SDxNMpV2#}DN!Kk6f@adAp z9I32|zDuvY@fzVkB1I)-DD9(uQDg4B<0j5Lr7t&Kdp$e%IZO`@#g>i*di@)Nga71M z{Ld4g$NVntj`|NB1P=Z}#Ni-Y`^oz}a$gAtw{KzXwhG4d9zs?^B9W?HtX=ypjazl$ zg$3{MYM#l@zwX2K1+kRhRcnRa2utU_F1B-jG>RBco47#(F|(EXo++QRSepU*3_6jA zpL&ByS6)H0mM!`4({E|eq9fuN5L`2=lX5MIdg&Q7D@x(+XXmqE(c2`Ons%+q_~6lJ zdF8cN2p!x>#D)Y>WM`%E=7&o;{^VgU9Rw5<w-e#*-au``rR z`*uAE)mGxguOU@@wtNZ4pLG)-eDon5o8+VLVWg(hu1kBKc<2E(Zr(=!j*XlZ$_vpI zgYMnh@$ssqWasCxZ|hbhAqlM%7y)WYp|GHo_GKwtKj|uZ4j4jpjm@ZYMpD+SA$|L` zXY6^SIO*ik5DGDB)Cn{zuFrjw#?ZHaKaLsLm9x%2k2!PhCA9Nr)~ww?UYld+*19df zZuk+?h>@2o!=Qb){#bWC#*0tP;r^$e#WX=_L6o4qDOn}pGwU((#6g^N$|#P%cpCK! z3a}2;k{qbz$+?fvpty|fhr(c*H&OeQdM~~pfN!Qc5 zNeLUb?4?hFkHWkHc5M5RH(q}YvuYoq8conp6f|ta_Dzp*{~fa_D$eHYA#Jb>hh?u@ z->%s6=5XIF)5y=v;O(WKGHdpID0K+5V~%z<7%CdI>y6MT8=5#EcW}Rsj2?Fvm)>wI zh3Sbj?9!ShO>&rd^CWup>rL49GwSrek`PEGNi;7$`5fn+)1L-;3z&HEnY3-+o~K`2 z#D$k!MoCr{QzndJ(&Sq?Tw6uG>^ugv&v$g5h9JHmow{}9)#v81cYh_Vo0l@US8Jw@ z8^!tKXE1KsLj?V9)M|W&4kJizgO*%*_E7G&gB;lXT#dh znKv^~gQ%b4XUF=_xPRvD)T$td z4({aMnfDS5CUKymmIiGGkd~Uo$tMnB`P7Fvp?80Ri3v=fegRo&37mJva8i?l*hT`0 zNm(>+(}vECGnhMb3UeQRfbmnNGve5RG%79R{wY`U&}{})ksv|8$&O9yIOVv(NNOJY z58Jfs+J|5;7~LBDQ!-+S<8>?IWUHER<7J$G;iZhf_&hpv>%_KSw(;(JpD^XF`^YcK zX3I}DwqX)TsK+NohX)2ObO9`2E5UKkuh?n>O_5+y>KGiCsc_ zXZkk$e)5YO(6&=ojvdsWfC&v6HzlW_nEeM1k(`vwph1IZR9Z@DX$ir^6iQ1Pke!oF zNu#Ee6c*66a~H}QH>aYqn)J*ph7BJ^%Vv$}H(($MiD?`%A|F>wsh^< zgCvkfeY$s|q_mhuO`5WQe>pxg zfnx>^q(#%lQwVVgi8fpg9~mv*gN z;x~L`XXn$tO*7JxoLta_C8acL+6`$ zNJ>uUNJS;Nxp_2e+LZLvG@3MRNhnlJhmM^X(6286zaPZUh%-ksbja}p4I#fck9O@l zQdwC;z)&=8(uCsDX0&e8fr7j|I&|nvLV}-2q=x2A%E-^IM}xdHmaYDp^DeuT!mM9spN^fnQe9nxflyXfMuVb!OcX`M zg_JgK%7DQG$V^SaFoevUJleKxM`~gMS@rAFzDp1Cvoi_!{M64Ypjq?A1pEO~($ZEeM** z2_%T-X?I*h&>`M@a}nE)_!xi9cupNMgt3=jPP^tM1OtA$^yp59&K>C9qc5k8IFn1q zUPwW`RC06kXxg?j-Fx@ryz|fFgcAmml9Wh6gA#gl??Q254xKu6p-r21^zGM|UcGxz zSWrY^aS=Uwbfd5!kKVny)3$AU`VJVx+2>!t`R9xz$>;cEw`kvyZk^hbkyekK`~rIS z>Ox`tESHW6L^*XaFu}0+@rNH-`TbtTT{nR?jT?}jl1#(0<_tdWFZAfqgBGpY(ymh% zP8~LktF9bFaZV=f+IFN}yY_VI)R_}cJdq(M4WU<$-n44jl8#-was2S14DQ#Rk_Lqg z7%+eqt=iImz(9KR?m?@T%^7@bFWR>2MDIR*8FtzTjvqXLqTDn}8#km)r=FZ}^2wZk z{#i6C$|vAv_4#KkZ-);b=DY8{rB|Noixojh{g8o}KY4 zMZlj(K|wK18_-WIw9l?YYit=;G$x4s%&PrT%ntz9E-n^OA)Km%z3jU3y_*4EB zqLgCCjvXj*?ZHuv;2#YFwGC3i-P0zqYFCgaAHSDW;#l;FQd7CQECKDA9w6$}5#oykqwzrbZ;f;e&g5>)mCPmKO8V=I^-n=0|yT{)_bP)|$AdI#r0) zMWSTJUYVl`kveBaJxBnDwAkU*^Z0ojrhi<&GA|oMjHnjZENDa%ayi#K6R{Fkf28Vi z>Fa3AfO0b#h?_{yh=L18gAoN%Q4U0xV-LYgTXp2nF4lgrhDp;N;J*9srcB>s;^+YxLf_>2G^gJm>%NPJx&E?Y|Mczj*JYg%{2X}4jN zH$H6lTz3qr-{U9~bR%>C*>*^73-#&!5kjOD=U@K_9M5iH(7Qtp$|n`hR&1FVT+C0ER=CV~aB; zD-Z1E`U#h@a@_`p*-|T%1UYx)NqoIw6U)EZ&!V@UrD;KSbOvx7dR<~+oTzaxb(}MH zV>NX`&^$J8H*1X+Y|;2kNB?EJxvYQF&+Z`e-V0kCbF~?D8@I8m_A+ePaJKEQb>0ml zf>xStU3;WMok#I*eGd2#E zal}TQ7u!IA*qEOAU3orE%3XksDDaKlBc|2xrVf2nO^$-hQPJ^JiI{O0NQ~!7B-)k^ zsPJlF#sHez?mz$Z6EDB~3Kw5-8SUD&bru}KDYpVaW%JfT`&|~+j>afO%Qk{@hKj422PD--E*Oi)3u+ zHhezz{j!zWv*(bKm(O*R#*&_(*t_!=?zrO~cJDvv0#w292RQSBi}*{w-oy{aC`|YK z_@X97A?kDMz9rEVgI>qrG{5$ax;eX*NL>)-wr`AL{2$Y*h`8E+p9@-0F7On`auR>{ z_y-vd7VuJD`f$y@K1ET35?Y1**j_EgPext|oig%BFWg63Qi8*kjExqbJ7?eqnt1fy zDoP%$l!{V{dyvp6kKvLyD-6SQP0-@xq$WPySzIn{_qUF=oI_Y1zsYRew2b6>5vOj- zX`j-DW%L?+GMSm#Tzc7+)K4~}N$cY0C<7G(e(^(Dd1DYfa(e>Tei4XO01H7W zaT5;4=JkJyx%yA}Q~sBtL`0l?zQ!M~1;hoL*dR8xk>E@+Q4kl?e?-q?dZJH zcwj90827u_+8v)3C_eA6lRiq-nJ{8kiHbo#Z+9DAX54m)&&BEejRF?;dCusiXL60f98ENH05;$Tm=JLEeen-cUTVE)jbg2$Z4AS7PnDz2iD?3z!&Y=bLt7|! zH;>_qW@Qavfvy1pIMLwV9UXnANldfsfL%9}fZMmAFpg3RME{jKIO{k6#F|>w{VIwv zb!@VaJHdn24$P5gR$fnUAY!;nRm52k#ZA4Y#MRfu76(UIC>Vube)*Y~UwWB|*G`NA>!Z+K z?C{L$1@mNRqK^9&t*2`w9DQb&hj zB)CAyo8p}s2EaY;0iNG3HNTl)B~G&^#FP?p)Jcjcg#AsFVcfj$X@F35HvrC|2v)d; zN1t5486$>MFDuRMOK;o+a9M<%M@n60v!ip-3ldf2MXiwnh6-cb7M29?`+eB9<>cj! zsfwt(<51B$Sdl93x%Uw|bn4CEfqkR=LJCjArO?Wct&C_umM2Es(1{1wp5DyUR(kF7 z!*}2F##?W5@ih}j@|zBQ$?r5={5A1)@Y0;A|E_=k0eR=0cjEG$|L^2~+(>ITjha#@ zQ(<{XHF6)1lNZ@Z(7W^v{68v2vCMX+J#GOC9wM3#+TZX%r zbhu*`S_>a7S^9U^?ceMD7ZX9EIgD#-YyaKF`BVPI;sc_S+`sBY6{~{9ue`)=qmVO3 zp6o)cSki5AcgCg?z>fNr#eAR~HT*+&-$|nm?HD>@Bmwt@^_Gihj!V1+$jy`L`nNe6 z5))I7u;BUUNhof|iO2LJU_dO}q%#=^0#*&P?zxLLeNLf&pKdPcYn&!79?0NoRg?!m z9iBjE5j5lcR8(yD=dH=Oc1)#kw1e*T?tQ%dJb=Px_tx*ZamE~Od+=d)e7TgZ`)e68 zY#2ee9RG3zWG0fCd(!>T*_ozLq|x`4K#Qtk=h}-FK`NjVPe{t-i$5 zS*SX@`zUDlB<6rtr;Qv~>fAG42XeH=LZbDLU2eE#a=6v1si`@{!q?wr=t(C+dJ2YN zq9ms0lBk~1)6#l3cL1L#53sp9LT$vfvI-m%a3yaoc$q_HAtV2KGJeC`aKs>bY!l-A z(SV^WY`dD3YrdwSv@>;`jp$hO)yah%(|F>JD=$)3@x%HJEPU;C z&Kh?W0lyjDcGYS7=zHO|PYkdA;mc@ZV&Xq{vG$N~^nbz8ti}5&|MP2AXTw^jIR66( zjBZ%f?;ii(%KsI>^ScrqXMSfBc2pnK(FD43=mtV!)dM1oJ^G< zP5{Rz&~nol1r%V1-Br-%oQJ3BihvyfGm(fmj^-fb<>zqsUAK~y6lC?Lula6kCC3jN zMhHm2a$C&6(cgKHBIGXU324Eg;y{r=Ok1fiFq8#$4HyALe1w$)JOfheKmaia8Hxl2 z%8HFa|*b=Q+v;_^|{6%8xPy5vxwb zoW_WPSqC^fWW=ZdS{Z}|{AdiT8vH>l9KR}4+0JuqL6d+s4NPp54uO$~r$;s<;%@Z= zF?UGMZxlx>XXprG)uQ}~M8t=7``r{lQR|ci6H7ya0Z!15lbJ+-unJ-siCE%jg6g11 zx4*F~0S#uFbDn@nwL7ANgav%cz|=J$HV#p`-yL}dVux7w*+(2qZO72zCu10(B!bc! zF@sJIXhpzq+s{nI7TiDpL5mMt5@K;naqFT9*j5O`XFKCZC1NW@5RI~H!ANmA4+Wo& zpzQ$K^{DV+IJ}i;AOXXlfGvWlY-iYu!cuVo4hqoKu7=bXbZVa%M9+0<>(;Go+_;gxef$1@)mK$jRsZfH{3-upiGsj?tvH&t7oM5N@{hmd#FP4S z^`*m^HTx+Rzq1@9Oz-1{GVaQYk*aN+K6(s?D#8RzgW`sbx%P%hv}@Ud88=O#Y3ELy zan3nxSo=Bm+&7yaw(X-~<7Pbk&|Rb_C)e>aLTTQazkvJZJVB-S7;@b4j30XvqAebn z`4BJ9o6i{|PvorOCo=ZZE7`Ya7b@W6nkjd1T-Q5+4J*e&NyQfmHsSjsiJA4rif+m>(=$uYtWSGcil&; zlKOoA?RVUI+nwy*y@QmLEG`>&4aW@X$Fha5G5waQL;}h9O+Uj&ox}MTokPXWos7Hj zKIY7Q4%3F0UV4RhS8nE*zMYsn{vzhT_$<%8`ZiWgHJy4L!<7>zP?WB@_s;uR@b(H4 zg2_y{{u)j^en4!}blb}gRWSRZhk5<&WoYf^;!8(y{9pQV@7)ivYQ-wF3NYlxX zcl=C?4*j_2p1UzCw=wpLoA`0Z9xVGH#RZK>Pfus-FFz9rX(mm*g=3HH&#Gn1xMSws z?60*mOg5}q#^gI6W&fdH$*h-6MNJkl zRzQhqh%5`+KEV6$eZT{Ap5x$=3XU6mEK?^>;)Qw7GxvoTsjP|6xqT-l-ZX{u1kJ72 zUd5_)KNGPuscGrlc;^H3ZC@W#gqNRvnNL6djAI9OVAQZNiK09ZQ8C-Cr(YFM?-?RgbC6lH9%bZToxR^1stydc@xD&cnM4o@<6EP=-R={}>VZpYo^t zUlPY0teh>ix6Aos#W5jiWpL`~^O$)3IO_RAtoh(YK3}(i`{zDIuy!w3Ot_tSX=w~Q zsSWFX-p_OMUZO=|5({5^mWO8D%U$=+LgB;lEDZDLL$m4LcQ8{=8bUy6(t?Rm02psR zedXmB89wY(hK@QLi9|?9sDVHt=Z?FI3r7#7UQiM6Y3{yf7D}borq9VRl)AP`*~vV z8`M|7a{dKZa{j~_4C&FBDbw#`$vqH6a>uAY1!y-yrMz6e?jLP~-1ankS+jJfe9a($W&E8geXXI|vSS&z~@ z*W`{n=P>`3x4G)vzHItsCl_6P8z=Q|NlH=>zi5c2f>Iz6mcRQZA1z(MZTCMwVOAEI z$+bNHL zlW)JB-aR{#8wl~@>P58geH@ofoJei}KK<}@-uvJq?z(?A*$I{0H2pyqEc}4ek81+r zq_c||=iLrf8nF)Y*sR;wu*=V*Pd`Jt-zG89$CPPzlU&e@xzlgs;MQ*$H|Z9#%bJl> zeTe$mxlDif32L@}#)N5em~#JYii1^Le$5?x{>6H_l)=U=yP0(%*m?bnlzJ^C?sUR!Fz!VMFr^UeAnXy2lg-Fpr&^ZwZs<|J{?Et8n} z(Bs@S@j@m|ypFCTE@Ra20qouOGuKRcIgSI+iC}crX`8COTbT3YbDTZ?dU~~KMxv@> z$CmGz`{J8Sm~;zGOS5@+=5+3PG%uLtZ z>za3!8!svfY(b=g*Pnl!cUOGJeGflLZbk~h#1vM&`zFD}WFC3>S*m_o$C#_8GUb7} zv@P**)wQ?t&4z6xms-qu{3*s>e+%7P7V`G|S9#|7mk9WRjKBISveMI|25Ye@nSJLp zb{J&IL=GQe*RGvT1ge;bI8(A# z3R?`!gdiF9vS{4ADNP%dk&>A~PJS+}nl|OYFWad&w3l7`4>07clgVjN!r&7IP%p*L z_Zxpks{nzdBy#feX#o2`1i#s~5qb48IC9u=;?=I1QN&L|Fi2)vki^6w?|$?tja#&( zOXp4$l@!shUvIu%@iC%pPzlt}EhZ-?lhouON;`A~-kK`P;EhGgY1h6hZCW*_q%fP* zpuysWuh4h!F*I#jM$48B>Dnfb6>C1H1`~X#U?J#w-$sF$9~qQ%Q;*P#>b+cc-FSrfYV?8c`bEpaj_VaD;}#c5Q;pyo(5 zYu9|uX=k5JQR9Xbm6V_(2ids!C(ass0}V*#vgt`5yY2}L}qplOf&}`DcRuWV(0l zL}`N({(AheeDT4X{JOs!TbbyH<+^W}vGvHOAQEEfyNl^Da3GCaHlwI8kNTNuSXwX= zQpn3IrbFj;WM-w2l$lOZgKQc%$mYPly;SVmM=+R3x4xYyDlDc!K_RBCF_e!!eR|Qp zZ7Z~BG=6HUYFM-SGyZzU8I(3Gp|r4wjHE>T#C({jLoeb6xM_|34{B>X_n4T*QDbWh zQ!KW9`w@Q`JcuQ$zUJ2-zNAO59z6Z(`yfa7?2|=wY}1sK^m?3oHo8K=iXWlR3yvBSa8oq3wvmahzhKT;Q32yaU&pH!be*yJW2$| z*V@}2cqa+Ajvxryw!JtrYz>wckO^EmOillW-u_e2bcXa@{y9Y(YjHM`>i zVIjiG4`1Po(?_x7%k_A^CJGCskMQ*DnH)Fh7}ox<9m{Y6LZbAiF1Mnk!M17$)f}Wc zVnrQZAcE*x(A8*NL2Yd%RW&u#Shl-1*@#_3sJeoRswxggB3Nidhk*#;P$kvX)l`PV zguJOwB7{RnsI02wNNt#iJ3f&x;ZOxNl@(Ofh6zVa-ytHQBh*w^QXL8ra@)gUYVe}2 zy?g(wt%85bzguD~9nlEUKX^yrZlVlBQC(ewXE;qyOXkqQ!+=96vUh(uDe3jmTA{?* zDQgr}71d6jSfA-=Eww^fHbEmoxTey1;ni;`3!D!oLr0ycW)j-6AafZ zg=@7F!0>}*Th6qs407scP;q!ak#HD*BUP0oBq!rI<~#XUW4n5f3MLk4k(nB#s_KZ7 z+Ds`hePm{3bLij^BH}DgNa{72|H;)0Hb3a%_JT z5f|_qXhS1dC=sl%MPiblgrLd(y?X&0Ln)ND9MEle1h+T~lW7u6OQxo#2FtRXcT+2p zQ!@!wR$;k)S#=~tQc^Oe(ulhNM~SW#h*BgZ1TnNk@1eBcS@caX3{5a43CoHQj#$_N z<%bUAPst!LB?+Garssp2U?M0LL8%C0 z#E8}Z5ph7E25mXM!DtL+6Hz{@2@($1kd~B8MP&_pwr}R9>u#jl@-ybLF`PK4J4@et zpZgwqnv;j0!37tcM_ztr-3MsL-&d(x3}s=6#x(sz3}-$mzM-G#knn}otI7WV#c-!$e-o1q|5HTEH*?_LXKw+7RFrdUjNeGnJPC+8B7q>*&V;qlj6O9TVWa)bg89eA% zrrhzU%g*VJeFc^k=D8=IuQ7s`x*(fdAoQ)FFwE1A~8* zSmLPP8C@B?0b`9)q|^Z{p_b1^=jiCtUC8?P?l z<7La4FzGfLHE&71v^11xLXD+K&e#NFuKeFztFGw^%+3r4Hd5rcB@vk9Zic7vKUTmx{M zn>1wV_;Gyl@h9AJ+XJZN`gHHq4xb2y7;fyW<7ID%lQqGqr;uJhgEgx^X62{fu9y3AU+aRiEzQ$r?Gm)QeJ%d4OV~t zC7U;G;p_`9XYp&V@y^1xm_PpwKKphD1N-*CublB=v$#B#JA$|DQ+JY@|s8#lwUYItPU-5uDvU~-$g!uU5C5)SR z16piCRR_3k{21oUeb&{+{A1#n1S3f85$?L>X8QH*&sEpmOjt~mKM}t_$o_r%2>MNq z9N5RNyUN+KuZkrfzE9PzZ`t|Nx9qFXtX}gapRHPfRa0A+Lr;U)HN5id!<;hoBzpGj z#qht5;Ju|Q328woo67R-+%)NW`t|F_xffi@w?FPgD@CaCAlFTpK=T@=QT!-K9fFu`Z0LWUwHC`H>s$#9e2Pws!5^hNI7Q=Kb0<>JJF?6XS#Ok z&t0>gWZ63lIq{^SeD&S;VA<4GRB-&j6FBSaOPq}?A$D!s%-}%-8TQvRS@YFqG_Yaq zYQ|l1HvRhdrT=lKvUc4Dst)XB(sdIVFrYu@UT_H;w(Y}K!lAuex#*$`=-syuBSxLW z*Xw@(e}I~*3T~M+nSuR};qC_>;Ydvg#A4UBpSgU@MfC2|o6E;dWaqvL=RL*a>r(^} zw*S15%P+Z<{{2tj`T1{PDIZ?se^hfOhO3ngv;4!?dHtoQNKH;ft3-DL;>EfPhxV8A z+UrZWY1$n;@$mf|{^fh-zws_Rckf}=z4tR_!VS!Q;sF|@n>_T`^F%^b+^pRbM<0Fyiy(6zdz_ocpU;cWKgXV$8W#k{Hf(>&f2Kq^eMKZ@V)+9_p;1N> zBhJ2rV|%pZ_Nh0p=))DX?%bEj*ImK058la>&%Vm7x8K3wV|ro`A;D05xoQnlrc9@P z<91wo{SBlVJ_?Eo$*z}+AqL|nO{8&YE>o|Y!0ZPfVc)?cQ4_946Tu>6*Rp!$$BZ3w z4bx`K=8`KerKC|SPCtDVg~3{`A2*I=tG{RL#A%e}C34lJm-6^CZ*crEy$J>a+%#nx z8FH9uH%#Qywd*4 zR%!wXDOogW+>ivrpmV=|^zYf8=@Twx!Jk@_@*Bir3 zptz)n^kjEBQx0I&N+WK01%rZiotbgVO}zKglT4g&4J*F>iT=l*#?9B9!;=rr#8JK}| z8a8Z5vfo6R0ZK}W$gZD?;ZLDuvqoejIZ&pcsDOgPTxXM%mP>KN7NqdUqi? zHQCXuDZmg61GH8oXEfxVd+y-Kj<31?+6l~C@D65b9{1lnjjvaI%+zUjFz~c6 z#pkbpj{K`P7AWfRLA}uKa#7998%+f>CST8;x8Fxa*kH$wN-RsGty<7w_V3xl;UhJOZ6e|)m{UxH(gxJ8mq930 z1A!puN*m4&XpIO!>mW< zVTCQ0EqaBsM_$A)zx>RsyKd&e$LCQmuLw~FHI_|HbuGJh@1e5FWlJy{Hz=%6X?_N~cl^TUpSDvkzX9K`|AueYe#@FKzQ<=M@CC_e zP(uCO94De$KtiLJoMCDnigl^QxUg^T`Rn*Vf*$isN{w;Y21w5ybRj6EoSlJx7qy5F2Y7KeR_2z zyM79%5B&=pzx|$HH*e+ZuQ$=TXLr&wv+35o8^8Xz4hdJXY4eY??bCyl%xwC1ZcF*b zFW9(#9pC*@&fvdZKzddN!;bGxb@^6){B;knzQ2wR-3O4DlS<=Oc_=Hy!2{uF8GnyL z@=y5>5;;n=)<+-ur;66Lh_*y@M6`~GEg}&S(RN70t`@N)qD92gBBHBg=TFNeue6nX z{nG)lMIl5-qkwMC=;Tx>jtlB`o3`(^VpNt=L*iSVSzbMRZ6+TViXGkl13|5s`4Mh;55# zEm}mvTEx~`w6??&E!wUXZAT>HR6?{^VmYlN+6s%me-19{&twrpxh_=MiUcc5##Cfua zHv)86L`TGS%kH$fC1N>0TGu*#XWP;75!PC2B`mhCcCHtvEY9zUXt$rjI#w6255x|O z*0D0!Vmo8g4vS@L326~q+s@b$%PFTF7F%nnv9*ZQMxQCRQwv*;Y6B}Q5$!x*yKSPi zEn)49W36jN>?)@%#fq!D7F%jXq(-#uwwv46B4M$jBVD5Jk}cw1T`Lh0iD-A6>5z!+ zbiCGK3Aw#2+8qqq644>i+IbH{;*3?XYDHTWV(Ch^ZN$BYQ=eKbV(VJ5?TAFQH@37> zUa>@^T5O3(t%zGA%NY+M&Tl&;T3gX}6A6jd&U2jqy`Hp1bd87(i>=+NSeA&kB;vNK zH;>q&Me7<7UE`Fg&b*@~6bi|@b?fBd!Gpj1vwZpT==uBi@0Z!LXN%}cIk4wz>CvKz zbnMVee%!TBe*FAx$w*6+M;9!S?dz9GQEq|U_Q>n9{_}UFSy@v#=h}OvR)GYoWzIZ>DEjqkYE-=mv z{ep3Fr23#dJ8POGr8kzBUVBv@dSH^|WTnfcmyeT0%RiU$h{*P@7E5+&iahxIyRvKj zGRdu%CNrO1A|YFg*yXb6v&E8~m?!gJUmyz>z95-NnKJk7_vJvvKDl(nagv_hTvmL! zMy6jqQgRDh%f~BM$Ty!ZmbBzznKS#P=lh@}xB>DM`hhe z?`_veetMQX|L#&bEF$aIE|ab$xzeyvQ@MD|SZUv}jbsd$Q4@-6RVYy?{<&vI~ zCeOU}o-BTOmefnHFHbI7CKY?uNm*f*Tr_cpgd+##&Pi8El1h-bR&S6>cTW3d>o&Rl zu9;%T&o`kRGXDG_GJeLxa!9;6!4i>QW%)<1$gs1nlS37?qHFib<9Cgho+q9uZ+y5+ zj_KV`j?~nM=-skz`F!c|mow$dPnJl#k}Uc7`yVAFmVEQoDj70puvnGf%PA)fl0{#y zml|!$zRh1r=lW^#*1~6{-GE{8{a?;aDOGzUoC5^1~T&}uuvSU6~3d6QA#iisk0${qC8nlhV2Sx(6Er{4CYz$0L zNzN`<3D~w1Y@!0743r9E>KZ;;{03zW8jzNnN^(jXDan~MZq}AnU#!Jaj_;EapPLE7 z@h-G%jnX!re;~?_G7JKM-}QZWvbQ-JI!hc)lcQ4zU}8GX@+2TC0XuBt_qee!T_U9D=ggU5$T>^SNf0n0=70(+n6n6&U@>C`b3lw3RzyU_ zRYBCnfEmO@5ET@aoYOE&I-$Gj{iCY;oN@Qwyy3@1kRl9uBxu^)Gs_wpiDNS z&NBJV+i6f-kD{X56c!g#qp&93d+kSAMxjK^^p8+D+Q-oW+A#5%I2(*1QCoA7Mw!^k z09^?lABF@l;!H7Tl5gQB7$ zii_%U!RRZf%xJR0i`=_{Fh87brvIrjbP@iHwcNi5fB7f8}TJgHnmNn2~>b96=i$N@QKs1O1c3_UR!t0GMoE0BXiz6cfk>mW3be_34YWf7$fin2rK+e?yO?-U5eFZ3 zBgta7MZFNl=8vxD6OobUc&~|D2Socra2(Hm14}%sp_yl`c|f0&QHuzV>m2XPX?@_St7z5?&dPGvnn~ z2~|phsD5Dy>lMBb+ib1zWY`j;%`6=edNn~nOuCSNM=PQcx)^h$#a8J;n|G(Rz_9`P z(gC3bj_cXM6W~Y@jSV+UwlbX*O}Y_hj%37{7ujn}{7|k52C##nZ*n|ytq8}m0M`xG zt96vPVQyef4z2~kt}E>`e82$mun$bmha{)pZTek!5-AF};_8W9di6ahVGb=q+wD(; z5^*L28Eq0sH3ApMf^X3HxNbaZzvntp8^Zaa?feN5k`(zufM!&OgHl*-7$Jm7Tp{{Z z^f~ZPq`Hbxt8NPh^zF>t`JXfO(Z^`wm5@;qDPksR%w}e4;%K4q9ARdna8Y)?2hxnP zSe|@Jcwj+E9Ie?~vWa*8I-BzC8(6Vv7Zb)EL;IFZY1gtL^Jc$DkCrugW9GBeYt)1; z?K<-1CktuTt|PbJFqX@%p2ROd|3c8E6Iw!`6^Y_T)G18z&g>UxRa8#5E{({Vj2|kM zL(kq_X;wF2%B>SP`p^TI_rcdRY2BW7ZQJrS4odq3+DAGL0)^w{#)o--5{V{Nv6;#D zKET?oRh&L{0E<5Rn08GYvHh1Xx$mhrx#rsIsMnxAy7F^gnlY0;Z5wdtf%`;80CZrc z7n(o?INGrX8Pib>8aAax>t-z7xSNjcI#a850eJOj(XavY-f91>I@aD+qM<}GR0rWw;7nnW%CG@kv-d}4K5(xY=Xyp3g$N%8r|3pu&} zN%ZK^i5H%JkPeL%->lj|T6zTG*m5kdp)&EpA`JbJuF)}fY<#c^_^qpwox9VgO(R}?>OPu}8_C?iyhnrP zUFp=U2^XAv5TAbf4hJ83Fl(2tBvDXAz1nfR2mQ7(v452R{l&m0ozo8dt+Rs#MnVmg zp-%aA*%@y2y+x7J7+>&{7UuVpyQCxN1&2;bCgX51L zgz%CCC|nUxT)#CJTyP%WEO>*9F1m>MAAU?qc_>$)M4UElyK&Q`8~E|-MO-=VI*J;% zDO%^CSCU@CfqcUpvq+GyV6H!hqQL_fw=ZT#4!E_vpY0s)}9+C z-b$DD&A4{_WsJONBy;D?p`yH;8PCt;!t>AL!AGB9(4mKN^xy#~>7faT3m=@A(Ps9m zXxO9!x7>0wPIf1kjr|k5Q-TK{ew^N&+R&~4AdWunNaoLbgP@=eH{W(E?VHr#(vg=i z_w5g8)1@PgY86JyYWV7MMSyk*@bH34=QfuDodyKP~=@5htI;(iIyx=bSS^ z)MmtKXHl|wC8wWy8t;Gh6*t{`FU2(*a@7^1*uCXPPCxZ@-dV7Wt8TcRT17>icJ3L} zty{>sXP(CWQ(xwyk)vo-SYVP2wQu+1-`)W9NBQ4bgi=cX?y@&QCEqV!#@4C=4j9;r zc=&n#I28ZJWV1j3-)F-3@pS03FQ=SyHi?jgROH{Ny1nREyC=TZxK#4pH{atY>(jMe zYozv(PDt7rUa!&qUOxTkV~U%0r%T6Hc*3{0G+W=VZ4%WUrE~jbbrR6rRr*)ghaW~3 zo9HtO0?`OEto!LZ#$9(Ok397p*&S=yvDc?dpYFs(-bO7$(lJ@>5n6}&Zh6nnmsheK zDt^^(Q9X2q4Xb}(_}OE5@S&;f*SiDAAnKFqu*JCcf^?c2t{+dAeg`pp#0XphW5tcs zDRN*>gP~EW)$ zxD(CiQm1(Ap@;cs>1v*S;t`5tPTrUcEt0ajwJfZ5K9(gPFzLMZL!{6V0q{IfmBYIB z>qZW*V*56h{;-~I{rgiG^Kc@-tIQ!FvOJqZMK!>it9cIK2|$e+{> zNhC3pYg8WI6nXC&OA}MAzV@>B=e^Cf*I&yUpMFfe8pXKLp&`Ge%66*+k#DW|dz;li zUca=~WV2a*{P9PcH*fxTzw_<4-*VuA2LiBb*Dhwwn#HKmV*rraWPBrB&=TJ!Hn^lw zIHYh%k|Dq)BP1~tj;cb-I0_f7z|kr8?A%P1@~{GWD6J_qJWG5 zML>a0Ap(a07wx(z4W7sv<^^F_W z1=7&Bm_Qzlt18gaMUlXviXf2qPMkOzNP~fhWVJMXhQd)9w1}C{q{bm-vYZ|h%Cn+ExO`&bS?LMs#I*UUFL=s;(WbFHO$bd4^oW73Z3yD_R ztlvVJcP|oTggKy_`R4;^v@XCG5+$sJDH#Y12W*v+xGs3%=LCR92G_R19@e9c$;`32 zbLY~uX;b?2>GKcg)F0*lZV3&3ixw@y4gZnv3jVD@p$@8eW%{G+Degs|fxV0^MEiy; zRSPreBdbJU{B5@4AvvexIUIk=$<(M@-^2;Y3}!IL&`MOpe>nzx4JvCE2rZE!K&w4W zd-@^j^&CRGwyjAz#vdpQ(G>_~_{aR++;i)Aj=K16+H`7VvKN()kg*6L`1TPlzqY7q zAV35GIG)uCwN6j#`ZAixfaOy|Is{g;QlKrLmo%v0&tz2t;NZ&uTVx|K)7gO7LNRAfdBzAM(u`m z89VM0TD5Fs`btZb5Rtlv)`6{rgRcSC*5eQD|^P2*|V<<4Ba!Na+#;!fXJ6 z4_@5F7m_!mBg`0B;N-Gv<4-*P=;Pee^I2js4@nTkn1yC-ZGk&7h6&N@vH?iD&~N2xaB2a_2p?7PuAuyesN5LN^TZ8gcUu5$tHy0mBfbyreUkOZ`y z52mgXLso3gIoA3d5V<&AnHz|arnEUN@LQBf!$H`XVdI9t4d;UP5JC_Wps_Kd;gvFp zX@Lf*DBHfCvFD$~dtdyBZ^0zeVdRBpQ0CS`$SgugJo40W>^w8iH$cFwk1=rE$ZqP| zB~QCW2*A@C(^)YP+FDgzkRA}=;UK~|XO{?&xhKg`B$fytgU<&+KE;5Xr(Z6S&xDIf%&od7{K=;}At>Mb6E~itEzMOp8NcL1z7*bK}ULq8TEUUj;#E_#8qfO@?Tz}hrRHZ5r znLXTd{q=Ne+k;#0xtndW@bM&!%vvQ+#D~Gm~uqgI!SjqV(A3^6%?djgDCzB>k6x8_z1E*^Vnp%wCTpBV<%9VDr5PVpK|o!$I`QVZ>IkFc`AH`@9$ySQ;*PZ;6Zfk z)|Xjx=8+YquS`CPMw4aRFH0CU88b7|J-bzUttIXh=6EBKQtCw@c;C^)I(uwmgy@qYOD-k-)o!5_Jzn-1x z)TI-bj=PGjC8hY8a;85ri2?ol(xGD)&OG}+e1`gPt z_U+nm(kZ92^yiIa(D<23o_zcv(Zdl9oKR-d%ui&q9{=$(5 z4xoFdjtn~FP(JwVOMD?gSMkxj*&KB6A#~}~juTHgo6V(Z1MmsiH;Jsqzu8h1&R~0p z`kUR-N^UxN6y&+Dg;r|~%BQeybME`|t9cd9i|(b(N{9~*#Xq&dyzZ|K{@RDcjnhCv~r``ro8&NjwP zN(0KJ0D*%@)MM6PKjEt-U-9*l&sn_qOO}4Mh)d5KVZe(;BVlx_s8%OUe%OW*=CBz0 z3=9`%jsTzV9#Lo7ZwiT)!g?w4V3|F)VqrJJFsdqHD2GfkM;MZm3yUyybR!~uvj)0^ zWbt7!;M;=Ke>0K7q`T!T?KV3vgl{VEexdgPX@FqFnrbh#VM!tA6k6wr#O2cJ{a=sx7|Q#X*uQPB}fF5?|P8( zy(y+X@i>kwARadcazVI|8+QE%?!KM<4?2*Ek6wiEGsHZBl!8mH9?$U8PNRMeMa_5> z6K=SkWI-VhPJNndZoGq8k6nil4r3=w;Dn*WX;P?p@tKEMxL`5&Pkw+e7A|1uh_hMv z@jRNu^Iebg!TU=%^Qf-eHfbUo zc2+WF%0tY5_dU)yX$UXQd7W=p{DcycY0p2)Pv0(O%H;d#(!DbUnG_|vc9YSD0Qr>D zPUoEQw@|mJ2HV&Fz$KSo#@VB;q(j>#OuFweYSwMYu*2K3;PcNo<*bW1?BM=1YTU?J z?L@TH0-9Z$Hc^$$N##tIBa?mZzV3f|jk?bK}H^NQoG(hRTvXlvSpvtV;2~O*gZ%G~mHU9^jpK z=5hMz=kmr&Q~2@Q#dyg&Jp23|tX%#z58gM0K3&_ij-6#F?eod}ztVs3 zQJgaL2wr;eWgdCx86Lg&QeJ-H1zvgk6DB|O5G5P8as71@D66WXFkTRW7h~=6DKFX1 z>+?Qf;=PZuPpbwrsO9nCgAcRp$IU$O(8GN3=^{=z;vnAq_(Mv|((K;3+hiGvN_Owq zN@?0h#y$G&H-O9Tno7e4ji?(d??4O9;$_RIQ@0WKOn!t^o#>N7L03m$Pu2oCHu5os&wZ!9E3#3~_ zQOyt(X|z@ZfsgCB6vsWP%1TH}GYbQoA{AQCasVk@(d?WJ|6=EaLZGY#+E`=_z|v8I zjrFwHu2Mo7IAD{WOxsMGt?fGM%|t;>;yRmWK{9fL<-2ziY7pnuju6HuVL}9?jXO{_ ziO+-{SP=Lt2(7KQt#o$u`-OkOg{c#f8#iy^P?MD+hK*$H8in?&9> zs>LQN5yf|;QdMZJDJd!WJNssMZ^Kb*0%2q>=A!!7h+Z5zvi61Ru+F8P+b_#%H>f_^ z^XG(!ga8cxYxwrH9Z^;}*?I#0S!q;%l>d9h{XLRFsu%ODKnoJJ8`7d_F*S9Dw?AFT zz(Gec=;$LT4g!`g{hn85JWcnT#*mT4wCmBIKCNrep`m2dm3OnVbT1hN(#cYlsbule z&D=ftE;@DV96crcQF+g8+p#Mjezln9UHUTQu)#QL3&Ja;ut8l~HLFdbPE%D@$%3WJ zS^fPoc5hwJ#&iSHS%Fe6#kK0tx@i%y@;xm3coBO_(meX)6Qs*Z*tK~JtJiFxdGEHS zso^PD2(<8U3gWcy-j_DD)4VXfGp&2}rr&-YIb{DnY+CgbCB2h;^Ya>RdtxTN8rP&> z=f-^S#w->s{f3lNi^2vi=&^4v_UqY@x88l9?In9@=^59JgQ4{(tlONXE$UNCE1r1r z4O+G9%*kh+M(y}sMyx%C_uhJoVTWCUa+9>{-k+Y`Iz(qmv&2|;jdl@1oLcqj(Y{kh zx;E0h_1+@-9CRQ}+!ES9KaVvlR?@D21Eh8kO46onTb`b?kWUwU$cUjs@I056t=seJ zD{s@|n`Im`iX^ z-(SS)4O`KrJK45*1EmU5@!GWM)RTUFdNBOhfy`O_J>~jjw1}}!mtOSk*By2Gv7C9$ zbCg#p6akJS5jwzE(6CJhy7%o(VZvkLt&gEod-(K|PdRzy7zQ3RkgdzVqgKppve8Tn z7k6ze6_rj6+V$y2?|qVFN`GeYl5e@_hP&9m`#$X7y(MqXe2n=EKQ}QwS{PDpWx@p{ z8Wl+5MRjP_yb(={ldS!65ubm$l&YeZtl#uA8#ivDG*gHlKZm>Sn}R~(5Exlt1%a$Z zt2RC8)4MP28Yh{5#*KXO#Scg&kss4&B0qjN+?uUS zq|kW@OBOT;BgtoIvaIV}I4B&WM@?YsXRb2R(gCmk8#&u!%H*!GyRckP`)BiHZL_>!IV30VfL5XnKJPzRxkU2`{pc1 zD-#o@kSJv=DCx2^=Uz01F8u~ltWr$WlGZJn{!JFLP#USssn=9RQKP7cz%DRJPf}U7 zmmn~~PenBnARwObD2lsOrcyR5+QjV$0R@QyQoc4sf|$+3aUttlx0DVjD=(q2FoEZq zXqjX(NmVKZLJ$a#tc>TK)kCmsO;p;5x`+KIUE_>MX^rDZ5^xK`3G=PCjb)n=J6l~zI$5JL$=-=b9&%C97uj3ETLahIZGoQldyq{tHJ z6u!=yXeezci=-zBgu>S*3pX1#vV14%%c*V&ab+g#~6% zP~Z`Z#i*!CfshEtL-=VPxn~k{zuL^?o3CQ^(goZ(XPI?11^6l;K;p$bJfT4cC*0N`Sqfm-a3Q>uidpKk?3PDFcIF8gJZNHf{;J32}X`Ks@5qb00 z#8~QFV!d@;hhW)!9x@IXm#L1h|9=e>{pafa_W{&8n;0^B^yq&WPap2DCiXR7;U;Hk zHJp|qObz43wY8xBt-kMnrpf+UAlB*#xpb6 zvZIvkJIiTUzad*zu4Kd7Eo|Jhm6F}t*{^SJTC{FS?FP*dN+8?>Et)rH?RU#rw|)!T z_Uxr|pU%8HZw?|=g6BC1N8rW`Nc?qC2$LA0OyWln_$Z|T2O$kHYjN$yG_O~SIZsb# z&6?G`_WDO`OL_F}(h)CILKSB7Q-N<53TfON0Z>#k$@(=b*|cFBYq#uX@Zf{^dF4{R zT)2=mzij2*_ZQN4{{a|TE~A@k`D3G=QXxT!P-qq42*Za*khOLMY+{AP@l3d~76DoY zY~HvQ*OT0E%gxlNQIoH}Sj3i18>!d05fdifN<})w+Km;KKTuG&PHh@Dtj&x+Kgqf^ z8+hf_ci5Xs)3$R5gwRM~qjIz%1y?G-{Tu!_Z8pTJa(-I2oV9D#Fk|-n6gBNc+ZHXU z6U(r3%UX7nR#CQh5Bv7$LgR*wsNJvyDJ2jXV(#z+E~N)bSyv2J-bxerS%lU|8OGQc zKwzvp+6J9FI5LKClXUCSfsba-W#ig){Jdr(-HHKy`_jE*b5^ff&f>2YvvqShWht}iCyNW%Te6)^t2eT4{Z1OR zY)^}JP55fTd&FIh5-!PvhxALBJNsqUY~6{nKuQRWqsrK@dIf9Ot>yg>zoM+NlHR>L z;l>hd+p?KGyY{kY*Dm_>>P_R8EvVVJDPiD}bX}yS7(#9NF{tX+}Z)aC&m3iBKiuvz<#DYaj08O@RE3dus0_(Q# z08)JW?KjMO@6+mY|G!Ye^-yaw7DB6y0nOGeEM1%6Wr&`&jStjXRr@pi2^oKExEF+g z!2U$CWDq47N&Ax*9B2D2+|-&zu-P*Dy|F5d6AHvojqH0=@9|4yzS zqGl>%88aW-xnrrZL|AW;Z(aNS%demP@6{!=Ea!hm2od!~eg_$vGTR@7->H7xf3M=z z?;{W<{_|J$`=k786d6vW-|OWop%JdfNh8iAyJs^epD>(zraVgDL4z24U_Zv3a}Fa% zj%M&t$8p-3XCPI8t5Q5NdS=;Id&+2o-vD4&%224 zzWRjYjy#SDx7J|_=5m6@-;#_6L*(ztFR7oK${Lx-Ni^cP+u z5GI*91P6AtCy;S`=^EpJ69?(x1co#j>5$I)6xM3YwO5U0<$}L5?D!!(`urU3dUP6H zS~W$=04*&~A~A$k#H0o%P8i?Pt#5x+x}1}bJCVEZf0RzWdNJ~%bGiBY>o{fD+0?Du zm{W$Ih!7r55D*VixB$RFKfm@=sH4+%7zw2DwM62WOhYGT!jS_&#O($T3eSMGpn|vO zzQVD`4&&4_FQRSdE*yS9UuL~9lOv8ekqgF*XW#(?=+H8WattYKag7>Wb@e#D`1k`x z3>(3W>96wOV^e6^wgnnNTxU!crZ(?Tiodg6*%P$NRPppol!f zlMzD>Va0b#S+e{mCf$A`e|g~k0`n zhNDvm4Zikltd)y$<0c*qjTDYGd3c<2-npoqYZ*4=IBvQ99!gRwM@k-6-3(5&7IReH2*$pHuUj}p z-J}IQI(6it)6Ze-_?y_1b$I55=UDdn#|%61ILWc*4<3ymv`UW~-W!B`QqDr+Z=hth(W(j0l*;q2R| z8y8=EA)`l*Va>YD=J1nE@%+ped42ACXf)|P+nI9z-K<)-9`O0(e=+Bb(5tVbDR zy^3FZui9-}{MT>i?bn^Pjc9{xkRKYWES<+xbWN z*D6BWBX2%c%x^gml(wn+Dua*-l(r(=+6ScB)9nH(b&5^DET-q-qxtK*@6)GU{TzoG zfeqA^WP^;M8V~|4T+4+e5JDPd5hpx*YZPe=g@qTn6pWaHLdP7G4v=ICi5{{lYvjLB z2tNaEA~MTZm0PP4;Na6$t4S|q2WUc$y1AJ2_>4DZLOBJIr z?w~McMg$p@4rcV zccwWTLZHyn#Yf>%iKYNQaPXWA8qc^Pg-=#HHiOhWUnvZ=1R~0L3*)|p(x9>^$209x zM%pSw&Vdw`=-FftO0ZNl0$=+$B4+9q#ssP~WhFmw!I(*mz4KxEwrYeU>{!Oo$7shT zK;RG{0%^yM0VX~gN7#HnmBmBh3lCoi;tG@$Xk~H*v%*2>07odYB8C(G9hWeJ&%`Tc zNvEnvr?NP%WYMC<+&uAaUVZ0H>L%lOK$zhyEn#aA#88fvxWh-Qy zr3n!?N-8rA`~jU7jeZoL_C;RSd~ z<4EkB^vRMip%N-1o zM!_e*LFh{M?ky!AOR#0r3dT)%oSUXhrDqev!KO4wEf8c)?45QHB7@0eHt^C|zic@C zf0-w6lwEHO02HcTA;t&9CINA+XhWl*_`pVn=q zR+HA$uUUx7nmOq?0tm>YtN3N@CK@$qPVM5N=t>beseikY4}e4X8K$4)b{q}5f@KT8 z;JLTH~97%|r)CXH%G7$}R?szrn6#Egqg1vri(lP=|f`=_vZ>n@v3W;mt# z4%na5PaQ@$S&TxPu#dN!xDXgVC&Q)ZTCf5V+yuEa6B9EAI&$*}?X&W`<;<8qlZtfO zDw)KnQCQ4Hqc5ao^Co!0Y>oyr8D2fJyeUGt5^XJCA(x1*psbizYGeuJ$Gc-y+4nSB3aWVLHz zu>jZAoPO%jWZeX4VSti-cM<`PhXBitZ(q6wth7@o3n#&Hs2M5-15(U09BHx(9W;h| zBF8p{c5p?2p?MHsrS-mC_zBNG`#fo-D9<`veCeh5CEK{|jwjetS`lsbu9x8C)6QVv zzCA1e6lfhL7Z}*@m@cuFB-iNm=4}UtJ1+(zuw%i_Fi-DoUf$%&QYSy#9vdDH?SU28?Nnzi3~&B7IOH>qZvDKG8Z4;j~gf5 z&!CgeXUM_5a7eM_^N%>;l#7`3;6t2shM{(m)y$K554WS##H5AV=3$N8{E84R$s+u> zHj~*TpBe&WggIskyM`MBfXS{l-*eIUpek7S=?Bbs;cYIsVifhGUNO>!XmgmAvKoGl z=7`8|!f#ZB7NA1HWrfP_W%jFc_7MSe2c-yo{n*<$&&ABvrk7(8GZ_N>eaT| zOt}&ENBP$*?yrMde``yi19panSy3WdWW!mTd%jD{eLAyZ`2xIH2*APdN zz)iPYYqnw;GZOMbkch_-!enylyoZWV4M79i1P&|m7qO7gGjFwv_F+-&UQu(Zy*}Gl z_2D_p?q9`B#;rZjqV|ZUD)mUz50Vhh~uIqB?9=Cq97vo&2JBe z`zvSQ(0M=Mdos&<HBf#ZX!q>Jvg+O0I{DuTt7~8$p+9 zgsbFj_bU3#6e+5ox zV){Ylnrr7#{=ffOtC&Qfvz5kL?Kmjy;RljH$7#{J1(#ob1qUBzu*$D!)FTj;1oJDISCU#S67byk4b}WDos=Zh9-hHFdYZb{AAf*7ELW?*78dvyK z`Yv%#BUB0@lQxDiKq~_0|df&EQA4vj;IDv zf4ibJM!GZL%~{X$=+x<)eaWAgI`whNQ)w=|;0yvFE}k(3o{!#u_%iqKV{+=-b8jQs&LN)onu>gS>$$|nxb*|{JDu^=aqLZi1 z4iuu0L{V*$HHt|l6Xwr?BndATT_52M0uTW?4lO|>Ae>)Q9T4a&Qn)z6F&V;yr%z?- z<4YWwq##+FWMMIhWFf`LB*lpW;!#3_2y;>GGsCv3Y8EidEM@yf*uId_h8$)Yiae+y zG1;mSj1nPpe-53A5KIuBm_0nFfMlYOf@A^7WRhe-f@C}%^?-=rQh0AuA4!gDERqM) zL>j%Ch~*69JPgD2!x*Npt=JXP*_kvvY>!u(*E6baHUab2s5;m2)A3S`VpxETQ-fsGt6_aY0^X?4tDj3u z+-2UkjVzxAoxu;P_~D12$YitjQi*hmh$rh(m@J}ZJWin_bL+(KScKM~vaI^%Gfp`C zU}_fE=CGk>Q|7xkPK?s+TbOdsy?pfXr)07jsRujO`Emkx|^o3yTbI%M{mty(1HD_RjVFt zJN9PE^f^>km9gUM_c&xgZyGje$UfZ$^4dpVvT5yl?!NtQK3lZRoOgm0H;*}=#tnP$ z!mQW%am^a;xqULrmi&N9Rq(=I(K6(coTkS*L+O;UC zS(kG!y_xm9%P`LWJcuPS?A`u72kzUJy0r@_D2U@G8Zmz2gFN@d{WNOch9_qHg`*Dc zPw#_|V0R|N=O4a-SJ04&lkQ>JXYbLzO>64atwZDHEx7xk=cq~x6Z@<|hz!fWnoqkX z^||);N7%7rBM0{CK)*r9Q(9iZ>hC`0)S*YytU-NRx9-Zlk3L65*8go4r|r8lHu^NF z$}QY@-!v|~{6@|>?Ia$Zcrgn;ewRJjtg*OjO*Rv-V%1OFGVvC=c5XvpfvO4u7A*Xf zDvFn`E8F9D2<0#B>#z zy_4Pngf3R40-%cRo7b~p$8MW{n|~@YRu2UTm0`=zKd@ojE-ROn z0|#N2p5sUxe<31Eghb;gWhA(w4LsU`O&)=UAY{9@@o*tLQaTSPYK;nfV_CD=bK5tp z4?2jfVrF3t z0i@mX1!4FKI?$0d5X=IH4keVFsEt}17iACxIajv`uL-NJ`TFCxnf&nMRDhu{&|yZd zAW#9C04X#QiOgfv4_&AslnVe~Wzg*9lTY90`4{IzM+~7=l&zaj)EfS%5LAT>9X7a8 z>(CdKV*czIJo(IYs%#%AZMfP3;h5liZN`8Z+9Apft?r>q2E+NM6*?$m{V!`NPi63x zX^qxSwV^2xMjkOl-dd3@-^s1lT*2EPeGzG$hC@MNEJ%?BG6?(KN2xSxe%Z*LlD*M) zqQe$>ha#=29Vq1mgndhFSN4xsmJMli2f472XXFS6Xn|5&TV^ewR>4)gwy#pRuv+hX8#0qPd zi^pHjYjdV?*r5j?vjMJW%^T((yc>VUYPz8o44*X2SBY* zfsYepDA3A;HwY8VA}AnRzL&8VjpUb2J9%>2Q(S!Ja2~n;VSd`QgG%`AjtqjF3twn< z?b^=z?P;2~?g~OsuYQus(w$TWHe>;ac^+q;cL4_;HW32=KMQ$NV5n=B7rG4YzNt&|09S;quZVH^3tr4x2rv z5a39(uHv5CZ{XF}-^PzBnFag3&~l=)6^uOV6yBcy0T~P0gbdvQI$9WnbP2VN&6734 z31ez9D3v9!3xH5QU`SDwBMktv-_vN)8hn8TmOerRmd+$}X&MkKgs~jWd;LYGJ^L&f zh$NW=85|K9@4FP%^{OJWWg#2_AxWc=jvIjz!_AdN5}>qsM}d~n=jbc}DvT5Yw29Hd zuKkK%gD8@N68DkI+7jV_ZC;lON@qQ?RKlo(_sQ zNU2TT15IEi7M`O(+BjCNjOMhpDhd&%76nMh0&$^8`IU^hcoZwX{SG07O(L-^*P#tp z5cnB9$Gm?bLPIj2FzbtKKmWO8K)1WO`{sT{q}s;ZQ8{8jaxZx z_}LtD{9%k6bviq@ZsmtxHZu5xlgO$xSB@LU!jC?~l`-p9wuc1apuHkmb?DB30X?Z- zuLhn{1VI*ua(-O7oGm-EjJbLe#|=4(BM$7wj!j!wwQ4mAft#p9w_ZINdB!jjekI$s z?IKP1K0+Yq;CMCY+^H*X&7Q-aO3fX2+)C$GO*r(ZA-pzwCj0N#i~a}gPfTT)`{FDX ze!hZw?b^`2XBR&H@LkTk_%bdWc?Dm8wus7#6q!sF*=!m|I0(l>Ix!UBEARuWE)u}@ z%^UgVn++`c{%6iP`vN9EG?{eSF1Bph`rB`8c>_@e8tEiZxM(erjtha2{!{hr9yqsJeF8EEF?Wy@%&spQa+gE@3aKVE)yG4+it2_R^`igyW`8BRf&2eAi|^`e-?IEkPU! zsT?(FG6Q>;;7LfNU$1VYY8qN3z}Krj=T7dYPw$@0JZ>CyReM~H7liq#%apd@Mq$guz-mHji`JQdO z_s$Yp0|ur2hj8@KlOWj0M<0L2)}0mjgCV;0>dTa4CX?#c*!11ktp4H)8d`&-<`iSMlH`#t`Uke8p&aVMNgda?_QFh6bD$fuvJroOeEqORSU zdhF5UWTeue6kv@Q%mBgmMxK81Zxj_|GIQFIxSe5^e)t8A&F%E<(~B`f2k_o|@36n2 zje;)SnLhJm5?v{D?Qsyf*(o^1q`9_&r5`P)x~7r70}f{F`0=E;Oxl{O`EdCsY};K! z*B)J%Jn?V>zGj|({#ia;`7u*xp2WcJomsj312$~lNm6z`Q>RR!Fe{m++P%EH^h3() zTFLL)ovsD>G}hH{!imSD6JYuK?~|C_m0(Ld&E94vPCbrfhXZ8MT@%t&x$RHsh z0gubY-km!M`NC}9x*dl{!;zfMsL_L2`quM&@W#8`d;3io&J@m>kQZwMx{juxzOLH3 zwhdV@bt}r6k(!Q6gRPr4(zmETRdr2hPL0&GBpbVIl}Kq04TotG2?eZ8o@wB)3#^nW zm_{S-z48jLzVbd7Tz4ObPZ)(}LQQo!-)!8;p`%ALeB`0@E=*?e^NVN;2DxOxLK3Bk z`)^->O3dbkCm-j-H(utgRh6K0oNhNEzn^xWiOZFQ=5kS1whdtdAyJ^2BqpWe@<6xF z{h2?19)(${1cD9*AJpBB7XEf-L4ZsU7ui`we$+9 zWpz5Jxa{#0&3-B9D1ouY%7(AjF=F&svUA;-5<&|`=vth^s*hgh>-T;9^utdy`Cg<~ z@hK!GCa~+r?-`gofU-UN!I4N-W(H}Ua(H9e`*@q1c;jzRvSv>`DIRxh`2J!4-KPEC z+(1$45tJgYq!$Mtb`%48mr}O#J1)BP3R=wsBJC}lfA$=lYO(N?jA8?L>M zJ@u`$Ha79*;@9zo!)Qt;ze{HZA9^JH`u4+Ys%6f(bJ$YWNT(Ey>#w<-uh;!VDAd5B zMSo*grI*suzGS7P+bL)j1rdU2a{pa-vuxQi`VQ<*qQ`|(wXx@?Z#n+zCp`)WKh0--Tcj-j8{6y|q za0g$1z7B6wHMigS06uY(ot4Hd*Wb*u&%aDa!3Xay;p?y0P+U^XPhWh%J@-6}4~?JJ zujkWMYX}7byuRoeD)+aNUtGYe&pyKZ1rHLEFuOOc<n&R*JHd`O9^evuwp`#AxBs2kzl-uYW?0bd zE)RYC4`A%*krbpS@a)qsaQ#j9keHIfx|JVr+1!h$ZVR&Y`whJG;wz+gDJ3U6pZ2;c z?!5VG8vQ|xU^`DeypXMxwS4l~mn?aEDMr|ewu<;z_r)hX`t)n$7I&qowt_k5%;BeP zJMf!=X$H}-_#-{;LZ!`R7dgo^ZyOz z`2ga4ErFEmuAF(=bgH*)VETkZIsW9?v>Q&#l~Z90o)A)q9SOqFtW>=T4#Ti0tAGem zNQDJHu#_^a`_Lss+152oJ!UeKrkz1~o0D_SKAQnOdocQt?tHxXX@(9S#+A1`Ot)Tr z7&)*H_szeOOXpm{iZ9mVkLdU!0d!4A#EP0FWLZ*}kKS=L!w#9ib1%J%&z(RR2VpIX z!GlIKd|+p;J%1*{hmGTvW#4k}*fI3$+XF+QsvU};VW4y!r_-vwmROm;0wT0El(TT* z!_@o2y!X!Q969AwZhPPfUVr9qoOSY9{O#3`NX_le#pg_;uBsMiMk(i=I)iklPIiii z`ih+_T=+06)@}l&gO*4^aUs&Wo3l@wgF7jYlHz=pzw}p*8h;eu?c4{NPDXwqXPhyU znl0s6F;^CK*p$ctY4hJjG~y5Yf69KBBC21SHDMNXEoI!e{$!W|UVZ2V z1`HX&rB_`n*Ca#OpHi~+=2pn_b8>Xuozvc(R3%JJ-c$`5hF;FAmLy; z{RbXQYhwjt4jawOpZ0Hp zPd<#pmCXDb=8>E1$7g7~wfId&_Bjp1)R{EpB&Lk(VeL<2crhEFi4YEj$V^Y6XK4wY zOMBur>sWa2-He)WELU86HHmr%Oq1&_oJ-fPJ?Yi653ZiYe6VUGdn;?vB4K*=IfyA! zkLQRX#hiHl0_vI#I;ARl_U%V)RVBkm4&%k!-k`;6VunMM^c%#CS(8aKgM9hcW;9(9 z2!~nv!6(eS@n(*iFqXDy;}|gVbUyv`OHP3E|<$V^3s6&kUR);j^z+amHCE z6EUFQfFYbR>r_Vc$z$$~iwKE@6BL{lgduD&e)4e~F?KL{i9yc&^XvTO>hpQ(uMaS2 z}2Chxzs1kDs8D4V{;9;c>N=;3fDGI&HEM)oMc6{#iSZ>O|RKTer7m1Gqr z;A^6^=RveJ*D+{tUzUHmin(WwM;Q@JrSth0pR;rOPR_jgFQmJ}j2tzbZ@>M4WBaG^ z$%;?8{)smj*RMCq^x+Tt(cDQ48ZwlzqX*Hje>X3^_BJ=&^%#>U^hG~yGLug@m$e(W zkgqu@F6qMb8B@vic<_~P<(7b#wcq{3!Ntk!+EdQJ0RuRD##A($HO8_C0l$~5;_l3x zbqeXu891(-$7i3dWa>$?&~+UV1DC@|w~`)|l~vGxz(77&zLF+i0C!pfy0SPPP1WIo z#4IjIsOTt;dR#M;8&am-=IJjRo9IpM09y^8}U2;fD zO=skxqv_wX5T$gKBbCCgJvd@?3(1<`!r~ycQiC>zP$^Ij!az!9CMDf_pedahr<}>5 zhx8;#g}DETXXyOsGpyUVm2s1%ao#1DQIelQpWXx6ytkQvIJx558O%9r7OwU^j5&N9 zMLB7trss0kJ$LZrqQ!W9E>hF;NJ`D&uyLcw%gUyppoqUd{U{GTyokLuEu4D#dCZx6 z8Hvsy#XScy_D~lYX~}p}oQxVbk}kPPq+($TJ6Nj}NHT>z`r|1)2uux=Fbabq!$&fC zdLu`S8;z#9Ir;Rn_+-s?1|Bw(PKhpbN#*{>o+baG=h(h$4~0ctnKb+evNLn&I%Nj) zudiimO@wY;yKu*Ycai(>Q&dzpGw6`f3_0{Dk`hyyf6t>7_Z-4UpRT0QuQ6zFKim$B zi2OIT7);xuJNwi5=im(*Jo3n63_WxL7o2+*iJDMUkWWfVl3hfoz>&g$!NVv>ONny= z9q4*0{rmMHC(!~WnT8;ygN*#{4C>blH#QnuCE#!>lomn~v+3KX54oAiI5a1-&p#I@ z1~0$zGKY*ljLR>(6psTo{kVw-A9{*@BS-Q6$9I$8Da#^LvLE6f!NC7+``w*Dv9~&+ zlr78-7*Jo=Oi@v(6@=1tx^*e!>(4(VY=qIAZcL>i%A~Ms4&jg=Unopig)vo-h-uOq zaFLy!i5q*TDs<#z?UamC4lcg*5?)*UIu~6yo3Z1ka@pDAts)CkvpDL^An&}oh{qPM zVB)yZR8`avG7SX5j2L!g0}Kh#*wl=cSjpzCS?Fej>#n_uf}AvTM?3{aN900DR31r4 zN=hOWj-YUmAfrfF+L>qI1O+13S338pDDdHv+%W+Mox z=~;9x%%!%v98(RmC;aH5Z#{nl(~bu@NK4PcEn)orHVg$2CLC_%@kbW2Wmgrw`jk>t z-%Mdq2-Ad!=|J!xN~bhGgXQgwgbV}IuAMb7@pyEcnn^emjX>HuyqXK;v|tFiow6{3 z?L>k;%FFiBW6~6Ki^T}1sadHsF>%wA>7)9d|4%K3Yvn-xBh=^`)e9 zVMm6`DnIa;p@ahv@CWgSBQ|E# zKs1M)L5ou6*zHyl1L0c^;=d0SrlEl|gK4K<%(T{hdKR)J-D^2m< zl9yxc@7`ww5B_xoC>sbOpyB4U^DpC1=Uc?>3SsfvFN4v>UAJ9FeM=Zj-QMPEj2btY z=igjvCyx~o)8g>cOp_5uPPH8!!I@pc3ya^h=wwX6R7n){ID`it9)^Waj?R{Xh{07i z+(J}NuIG^PJpRmh6jtG%8Rc$N>6|h9a!$M8Qc!mM@7HuY|E*@F?=^cQn4+V*J8{t! zH!|mP-BO3NBWl;&as%iZhS-Q74( zcoGQsd|;YHeC>Sx>2i*lemZl`na-L|ma+Ptw?NlONpKTru^cs*?jbun8)sn;&OQGe zJod}$)b$web2QMdL_@cAMq`zrK-jRRVwbMaBuqkb8V)7w*}k8m!THpdH&9*EN|%B> zD)yCGm=Gl>w-duIUWi6J1aK#~2>MzO!^-In=u^n*XI9hP;w357VEc|8)Phz3v+Jez%%OU;744R|L(d$AHCP zD~gEWK+`qyQ{C*^zLP$Edf~0AV0&3PMcsQ?4aI4tSCnRZ9abrWX+*#XvcGXZAx|oa ziD|eD6GzC8-(Sx+-)~~>jSn&6pj;YT77`AGtl}9v&8RSO=@$2yuE0>1iiZOS$~3Ja zRs)b|v4_HlR*71GDZ++Yu9qd`B!k%k;7TMNU?kAF8kebqLiX*=K@+=TbMZY1bTGN#{rfO zbki0j5~i}MmhO4kDBS3xlj4G4dkcnWq@?7KlakDLt3RgOiDS{4160>Fke8c|+TUi8 zhYPrr0(T;_FT0pC=iJDq4Y^F2brC6UCuTT+VS?`V*wwHG5Jn?_8H!*yBmB6lhT?(! zaUp1tc1*+1j=kk1=ah2o{2Qs=vzJdlcn@o{5x^htqPw$kXd%o{5Wh+w$>~B#gitVm zxDwEHoenDP|NG_5j8;IKb|H}Fh&fL2$xzW8(L4iDa&PM$*J6&9hQf$M2>E@yzvO*Z zeEnl=qo#la*K8!I6A1}^6kwW`MzwA+n8(`G@oL%(1eyj~v{=iME{t+u>Nbip{@@Pe zX_Ro^D(o?pbP!O*Fco6^BOQFK;`j5~3(vECpVw-;0Jtzy3Yj$J2un6l1czqdoo4Ak zTe|^`4l-|BB`SLUxG-+)PvyW+9e1GF1od_|caWb07D2hy*E(WxxJTcq-^3JX7T!|R ztm^#;I+|va-N$IX6r$VQ2yxuEQKEIx?cc>=0^=_c9c)Te$LDre30N|sL?4+2L{~96 z&p7&V72PZesE8F&{{_O<8uNe1#{Ku%e;^%fq8uK^j-SL!*WS$)b763wQf5t^!m_pZ zaP5Vc;WFCr1$8dG_#*UB8DVb=cinb7g&8`VH*e2cCb0Jv+BEc4!}FoPHMbZhMHGyLOV6;-PHn{2S=rZ!nL(cpLLCzk$97b?2NDj^)#DzGdE3mywm^ zq^91-^*7#XO_It)QvqwiQBmGEYobvCnlgCy$;a8bYbWi7ldQ~ix|SZq!B<|-W!K%! zRTrI4cBgC(A2*S+FT99ruDXg#F1(1GtZcgV?8TX9oJs@-3I{GAq}-rP+?vqu;93I`=HDyKFAqO1hEY_Hf?0 z=h3^QfRj%cO_!-592cQ(4F;r99+x=}w=b6qbCmlL^O6LX0qX-0)|1l~?h|-<~8T z!BYBgIUQ`?_&rx$a}DlrGfiy~P8&aoG?yYZNoUbZi#cxUbZYBf;EF3QLq&w3D3Y8y zd$(_9+T$Ou6pP(;93plrJ3y6j=Rn0s@kC1(WS;^=s$k$ zuf{*txCpRyrfAqcN{VGWZ*j+Hzj&th2hy=Ih&I&_iK%57#&627_=o*JXff^J-_J}i zLzv+Zdn)$P(r)0%$e?FY4&KIU_EpuPv;?yA3(3h!qGtD33_JWh9)0R%I_G(Cr=(C^ zSVWQz)iwLj-5xTsv(Umms;X*eYG}ccm`c~u5R}aZ!wp=|ap9H5EIk zuWupjOd&P96UBMCxK)7qx=L#Hw_=K$?EC`qvr=eos->!`nTTPMl9@$eVLpMDW?Fqd zvI+`u8V&3$Yow@i2?_Y9s;Z``Ie>veOH8IuNf8azyJ*wWC@d%-fe39)HPp8m

+o z6A4gVT~2+27f)g;d0o1a8#TpkD26?+K=A>wdToS#Q#qQGL zIawINM#}cJP}Hpl{`xAs5k+234t3>aBy`FmE!ji3-OIMJ2731@B|-O7SGSManr2K= zx%Rp{xc9Cb>D#x5t&?p}*~((WY-??ztgH+J7sZ7+ghGB=O*h5)xwvR26!21Bu^(T1 z1Wk96nw3pqisHDVj^LCVALE3h$D;e{Dc@I1n=gXqNu;=QXHq>1Bh*S|Wi8&8AdaLo zx|MWAf-RJlRS+_Catn*dNl&JxayR>1gD7VL-MSQ$;&Id7Tti)R8+lzyaj7s4<$y?t z*PnTWwPitWxa|g##bAGBErD>DyspKT7)$JN>}Ovx>(3WQv*}e!4w-$XJ9I;qFou53XG;HB9RbomxEBi zD)2C)^g^Op^dkyuv9``?|1B{IMNMo@No69+u;3?_n}&(gem?}=w8of#^*gb(mX(Qt z6V0wJjun82vLi}j>33_kF1y`ty3L$#m?lbhS@06E6?vl3Q8PLxLewF(+GfVNrB+PU zN=lfBX4q-x4o@iRj9a|0x|QZu5uyq}Vk=@R4s@LVt)?IxiLiS0=Zrt%2#6BL+wG4d zNJ2A}{p2(#cWjjjX`_12dWIf(DNC2HrhjRw{c>9*zhFtVSudR#3x6Ai!L}Wn3Hl@U zZ*&YaGP1HLDJrlcbLyALf~fF_ZVKofWWF(S=NR#^eWa~XB+8PL)0LvRc|YalO+zE9#1Ivew>iY3q}bSG!m*TrVC5loTZYXf%Ic><+{>>} zMC=qmR1G)!xq&IVb&N8ot*)Y`x(;mlHWP)@oj|{yrFJ!&Gj0O1j*qH-2q30m$wb-L zh$cfY4C^>eL$jCziAG1_Qy|tfXH{>TO0)aLdd^}?Vp(#7257py1e%2X?d;jLlVI2$ zTY#oCa#MmFanyJgJiCI4hYrIN{R}}x`M5MU7FkSmGL2hc?EceY|BsGQBQ`#xt&aW~ zKk?gje?+xX6n@HgZQ`xBm(eM=fHfPoQ`ICqaLW}m*6cwXiGXGox++S#my({GWTnz# z*RlwFtnm=9yrMu1e9e_S_2eR+f8#@*ePandy5!*|`kq*vnbvp;p^Jdw1WiMz4jUor;Z^J zqFUva6V^d1ZrDzsvOCGNm1vx%VL4-1vWP^VgB|-dZEjE9?09Em(Z;ysMbyNW*#wD; zsM+6*5z3pGG398(`dAs(wQwOe_E$G`8)s%y)2Qf(r{g`Bc-kUtiOl$DRNQA#IEfq> zm&86MdhWPS;-0P84v}U%tA_F<0+iFYD@ex-lE2|~n((A?Ba zR#vwC{@Ze^_PQ2*9#)Sy?H;h^&8V(X2YNfI^Anvfe%W%fV}+n&MT&Qh0X|IaPn3H;sD!IrqZX~_abu_zKvZ|DbRGnA9m ztP=im(>w~Z+;M}rBlNCfQ;A)%rWBEgj~_N{q@ke&u(W~=%}I}g`chI{7<(b2;vUh7 zEt)D31@n^?1EJ;9)1--O_Hr_d=UhlIogdx6s9 zrmLuP7VDtcUBN<#6=`H2>**S>&U$ir|105V?5%KC0H`SRE zBR%%D``NJm2bx;FRw~039J-s)qX#hW&-c==vbt@ng?}KPWVMy(H~SaYi1*G8aC(0BuLDzYKRf@geEZ*P(U(Tzco>D~ zmf4CB*<)P&$@ZbCcpvS5 zwCLSfl5D0W8FqkU+R@n^-4~5ab=cp%o*ek^C^erh9apg^Ff0`fP5rWm#2yp6Zbd<& zuY5Fqf8aAPK|%;lOm(1h`mek_|C>l)U0oe-zWF9|=FGA0@jypKz>WgOD2RPallHb28k^g! zB-B5=q*Vde0fe?f>>|Q<-+jlPy?Zc;O7lbqwMBgr1teQ{X|w46>{?2NY4^6!;_kW{Nm^5 z=LBeOZejr8KpwxpB*&6Tv z4+~mh5|IvGP*V&LBlgZ%{cbtV5vA-j_P;TD6@6uGUQ|P(#Kg*~2p7=BKqCS~P~sq> zoEVyJ^A!GP96)P>Z@~b}=p1C4v3DMObBcsegl!2z6*nIKckjr*+cZr(U=Gy8w4G}U zDHJiK!^y>xkTY$^R!k%I*i2K917`!^Ukl9qGwb=!KaUkd{bB!A_Mds`5ic)3c^^-_ z_%;Fl!D0&bgkY;FNJm1(G!2$7UBxd?n4v3Q3*0Bh7$o0fN69X~4JoEU2EdAtj z!f|N`rR->+JsC-)nH#UZfDcxEMVR>HkcQH9l;-%^ZZ!U`O#X+v{9jr8gwedeo>yLc zm2e=;>i6H^xtA8>k6tZG0R4|FD#Bn-PF4k*<>hQx{V5MFypQHcIHo;oo%X;TPD3+#PB7>&{Kh+A#gLOe*!URXxLAETgZMctu$6{ zWzKn*^7Rip2!LIhp?<%Rga`#&*;QFX2y6Uk z_NJf%pZWiSMNnc(>nUY9*(e|c1TmE&2t*`;!eT*)02VAN`Xqi!rISDG5BsJ4?wG(x z#6*`c)q6IvM;Yv{*hi;?1oE;H@wEqOZfyr3DJ_GfBoCU=PGh5&K+tkb+{r1VrKRF@ zx|w~+T(kr?1_ll@Kx0cAUY~)}>84YsEL&glhUIJm0Ae-MW|fy}II zoVp_DYo)oRiBLqL={ji{nIt86$nBiRpKrT~gcJ{L&HLH8y_WKdN;)MblADo8Bp9Tj z$%kPWq@<;jl$?xCfHtp>7HETX-LdiHSfMpSP8k_7I37Eh7U@q6b~V z_T4oxF z&LAxf``EpsiM{0&coN)XXQ$HI=*903B1(~!(+Rf@&5e!tf)QMvL^3imaB2!ogOCxy zj5&buuB4!d5cK(IYH25EKw4TVX^9&9>l+D%Kof(clvDzt5aDnDJu!vM%uL)EU<7Gs zY{DN1pc)&9m>QZ=w70YnHihK$bX@9}JJ+8FnE!6-SR@u?`rmKK3_IIk(C*#O)~%aq zZV6Ibv5ODhUV@(0mk~Xaxa{J&e6@Zn-Fo$)xuu@3)_%p@%dRCQGnNTJ` z&Td0kB8H!*9(sVAZukqYtXjjU;e&8!%8pj*L{-ccChbkNoHpwe*6#AMVdEw;6BI5L z0cA(O3ELQRhed#H7sZIu<4V{dN|p2P^0GSm#e_(JFTYsL-S^zjk6U+>o{`BJ=bXc= zKmCd96yb{%pYX_YAM^BM_o6ur9{KCzJhONyOW%E)qTCF-fa^aLk^RH|tL=Ap0(FN5 zroySik6(Yz!h76|8$FO?#&l=Fg8Qj$F)+;tW>Ow^-g*s*;YyC3egVZL2jOx;eM^|R zS6s@(aU;0r)?4X$$Pi|pHj9j5J!|i;&{1fVH>p6VvKqikF$bEO;MSE+I9lL8e{;av2J7WkEjIjK@ z57@J#o@vJ(N@-4jzuff%sVO-$*45Hw$PwId-6fg{LlPEfP3?ZMF z*5+1I}tTRq#?3khGLJZHPFmN~xHvRA;k38@w#hrUH`}nb( zeai8;O9qjgRl*%N&13VI%XsgjPpEEEWagCczymk2cgHp^zi2iuzrU1*`Wo)KVLm}u z7Tz|Kl=Mt)x%(De;TmqaZXQ)$C!Vy-_ctv; zc#JlldGrxJ{c;WN^iKHNd|Y|O94c$-dFTDFdHlhf+4;jdF23LjUie@Ixrq_Zo_Q=& zFZnZv4(P_6^Df1aT}oX;3q@UfaP!SKu=c&zcwpf|3I~p%d#{7J>WT|+$2mM=1Q3F} z@ycRedihP#atley>B66{y@VytJ;bt=Ye~(>Wq)HU=U;ve$BgUE-Pd2pH`{!4?wn6q zRV~N=={(M#HH-vhuwm_L?z^XjJ_naFW!fapo_Q9T={cn2WOB)sbNOlQ*Szt{Yb0hD zvcKNX$)}#e%$dg!CX7-plpVXUA~Fh;iINchwkGada2K2RR->onG3D4POc~mVGiIGl zX4gZAv{us+2$I*iD`v2T-Sr0dKDdx!UDH_l`U^bu>`SEQ7UBwcY4$}h1)hBPA@((U zx%tioI2?`+H%atZR5l(;rp3K?_F%T6*Mb%HKG1jlg~dm>E$oaSAs-)p@BtgQY{zKc zOTf_4H79w6T^KfU6k|pVqpoTWET`OVbUZz=cQu! zn|Sx#Lp2eGlf4VZ#~J zzc(&SYASZ|{zogQZfK=v?>-zoX)?(!gY7@A=d&-qqrSNrU3W6fY&vLw!hatm8(7VvXd!Mam%CzaEYF?Ipu!8FSZDi+UbMh$@&{PO9 zgctty9AA9#1(#lUKDE0yuzdMvw6sSk=u*Nl(~c)e6rQkwzonJCZ@-sbJqtN?#u2=> zcqu_gBIo^SGRxmv#?~Fx%sBIGG94k7zPp6IHD2_TG)|a$3?)VRaZ&ewgQF#aiHWHU zbR)!9A1~qd`=8*1b1&l7{=I3~x0S~peVmOutGVyi3(++b4JTS8#50Q)v0=+T-hAgB zI^|?o!_jt@EhpA?^8W)4;U8qt|Ai*Mx0xblpj!SiccxrC|8ChIibyD8$kOK?mUGTM zTPnS6Qrl1`Gfq51Zn}QHlx(tK_x?cgjgKj+5H`b<*w+O3+s?FD{%X6OTV#ssmvOM*Q;4@|R@Fv}sb_ z)GW=dO>*PB>t)u-r$}?iD<{vKDGTqtU%WoA`2G9kmRlFdrB~l7hUt?9x8EXXpEFxR zrYWWwdkEH0@KwnL$B&YQi{6m>kRjo4MBe?|eR9DC=SY>;EA{pJWcu+Z$}KltD|@yq zm$c3UWLsH{Z2$H{$?ZN$c2_q_#kMsvWcZQt&4$h5_czP)k1dc{XPheE?$|BIPM;>N zZM$X3TTe+*PLV8H@}>N+Ws8jHQzARdHp>k+Tq!qRbA@=@TBV_;Tn-sNN+^}X-7DXJzfO)EGfsAwl}mfu zetG4&zse!wj+dI6-E!7(L**~`KPFy(v#eV6flNE;Eb)5F8ft!&{s#|~SKnJMt==Z7+qOz39(AOAUsWs3&CSx#&>+FsQ#7of z*mE`PKSd(;Puxc$A`%f({K0_yxbX*RYHF0Grlw!~tX{o3*4_2>_44SWkBVuAMT|E2 z+x>r*?Bookdo38dHT_t z+$GQ_|$j zt8N!>uubl|{ycHHJ(8K8EJ-e1N)9?yzS^`$0wQ9>=2JsN0^+UTA=4)glY_eENI_bn zXpT;D%Y!e={kL8#9#6X5a^ItJhm;zP<9;y*EgPu1j{8-qLf# zM5%1_%4;t?B&9`Z(m6j{k`t2T^s5#~O~XE!dBiZ$64Iqp_mMJv)|pbXcb$wGIZ6hP zKVJNy8oB7yW2HDJSH9e|Rj$4C9LY>ck-}aFOKy*0^4ZrL>=7azYr?;1d-v>>JMUT` zhS@5iP>qZkIZE!m_hIpeqqBaq?BBOp4jC~)zW?EK`Eu3kGULS4<%%nBlF7%;l3f*b z5->%=hAD;_iH+fZQ}h0>ZOM`)vTohF|8Oh*u;1ED(;8`Cef5?62QYy)$CpxwBLUr^ zqZ<)+Z{JDJzJqWjCy}0!#^^%^v3=tPBx0bPDL6dIBqz8SG5jC`ZB4ZL{WfP@grJ0| zYG|i>&pvn(TqL+%@%31i**m~LoqHZ{yzwH}Ty-@Yf834{5dnLs-McG!@Uf?vbleGCe92t;cFspd0%*SiwN!v8 zh3AXIvQj|?SOqDrL|jfCj|S`4ZlJWZFZl(9BqzD(*QX~twrvN8PDFGx zcPa@9E=!5RjG&azQ6U21h=zd!-QmEYY3RC@9@SiK5pz zz~OM<)S#+t7d?6p;Qz39-tkow>;Hex?4FX|APFf1LMWjZ6%kMnu^}q<-o4jeQLi2B z_lj5%yLhGB5G;raC@O-|q)6`xB?QuwlXG_G_s8s>a}v;NLGSne%=3DoC+FP5D+KuAhb1)2>p()Y=ETML z@Oh>70D63wJ|D>`vG`+R35Zx?;$q2emO}N;ZS35>g^~)Ju7?gJE;fdw1Rs7=(~HF= zC6StviWedb3sJF|u2D^+@HKQ7>r7I|2q+Y`_;t~5f*{ppMZEdOTQtkb=j+8wm^*t0 zu^wHjVRF}-xc~ql07*naR2WFZ!1VY~p%BUzoOQv)tX{jC%l>u+re%|s(UN)JEadY~ zr_-^Zm9DSbe-cnZ3|rBowJ%+7Y)-$+&58j{hF00pXAsDD3xmgbHee@w8z4s`Snkfdj~Wbu-3 zczfc@2vMscu569;DQz1QNzj%Q?<^uMIhhe7{=u9tKjP5CyNBJ{2QA>v8F&JVs_F_> zZ{0(F+d}+?i%_9ROK(oI_!#!?+=-=ZzW(|vULQA(tFF14<}I4x5nu@0VQh*-i8e`- z{FxGV2dh5`B1Q+62!u2VRPMtgKzKYfOHXIXj$(~>XW48iDke2O17Vt2^))(wOnBJ0 zw;E}B@ffCF^reYV5}%={tkk%GLbw@Zj+@Bw4N0Nsf7}Ul=+TL<=6%n-_dm*O&)$yD zYa;ES-YkN(OnCVv^4j(0&Koah@$8Se`-M+Y9s}tysjscnxqYUW(3xRg>0~gYVPis;jmH;@DHY|r%OIf{6=k)Ql+}=wlt?Wa z+Bm4dYuR{YB#>G-kPse^K`>Ab=z#B*c{wcpaTaxTwZz35>?z$xYHF&pNoa6Z7Z4cd zt}yMB0KeY@RtRC+n)Sd11C#;!JYK9|tsa!NNn%neyLT?p5W=?2`mII8 zCN;z7kHNymMx*R2<)KH{wq(Qwm^kiDYJy(69o`MsW3}JPsv^XG*cQ#wnz3@%4xKt- z!{+TfNNL^zY4{LU0D(=&@Sq3+inR0$f^`+tRFxy*J(TaOB`z_Q^yFB2b}V4Zgb&!V zubN9Pzl>Y2yO~+Q;2~$@F=I(eNM_(M$MW!lcQ^{BBqk=7jo-}1BL$|DaT}hFLTGp# zVH1~_OrWxy+I^LX=5c_RgoH$@D@v)W3lQh?Qna%aX-HyYb+nf)!N$~3E5ZOg#QOc% zff8q)=*}^OKu873A}&6TU~M^-rB%pu4`utxsH_VR9~*;D*aU1VLT=!WZzNcf^yV2< ztk?*lAjbpTA}Fz zZ5JKDcA$ME!tkNY82v1}9>Z4H#GnjMl!EF)|2pfGgnG+Di5QfKrES}Ma?=x7yM7h> zD!WrzQ^S$n4<$CvL*GNXQ&&BmlJZ(EzUBssO9I?^%MD}~bm#5|N76G@Lt+`W#4t^S zl-SbLDN@Qt1r=T)@CIwyyQ6}D9m^2|jv+BAo^}Pf%v!LJy?giQN(nzmN&B`fNi-~K zD(i4lmh}26oP(C6X#IMwzv^bZ>20{@zB`DQkXqP@8w$H(*g^h&%_Z!qc%CaSJe#hE z4B*9AMqmrC!ziuesAaH<2X4NNIm@@w=jg#yR8>*$t;MdlQCQR~iES%{sz;bYE4-GI zH7vZ?c(J92JMX!d$45TM-M8LKUfbS`eC%!pAKv{xh5`I436~@B`(sHfx0>>YXih5B~lZpq;rqMIdxDUo_g$lg!vH15AKU8j4&xd7`Rsa7i=?4@|TrA z9U{g8kRIB!Z^xG(OyQlkX7k>Rx%3`%6bt8k%;Xne$ZNO>vjSjgvZP3EHyzvR;|zau6&g~eaa<;SHf*t&Z!m=a|`k3+ig z(OXk_``x+Boxhx;jvdIDQ6ri9<~Tl^{RPuL`ARE5KfBWC6w2tUlz@6$kk-5n1A2F5 z_yt3m_V(LcHT(%uTJ`3Lo?S7iMPX|e5@|V`puSlu3j;-q>~!XRI-QR{n#Tuo7IN&+ z!R*##k~LCM~r`OHsy5+ zTN#8bg~Cs4Y%Eqq2}{0Rz?$_%l+-AK0zyJ7g33%{$gzF-^!=9@{p6F(`C=LWp8OFQ zFD8Pv-FO zlM^}pv@=NbNcs=x$C#Ji0#7=J_3TOC4(Tjj@HxGX?1te_=k${X@%|f+^WqDy@cG;& zy#MhR1h6oK2}1L#gdm(9sdWpj#&qb|i=M4Bxb^&D%y@qWuS}guW=<;-Jr!L0w@aBc zc{+c; z#~g0Ea42uRGnF&`b{~0N`_ZXY9yw`}AC@koXkR4`3X{`|0%0c6x8DHvtoVX|Jv5SO zGr!=|c}qZe5X!a9Yb94Iv{g|GLWY+Xx$U`l$dTNC&3R0n@)jS={DwLeizy^eJ^Bzg z-+l-CLLuisC#b0^=b|%CV#cglgzO+Q-}yH!+xKSOjv8z%?z-t}9(d?Jsw|xyEtSR= z{ngeMVUU>GjF!#4lx$wg@}HlFOv=13KcWP1x6sX|CJHIGC%AU8U5Hx$^(OV5qv`&C zXY;q~hO?%)nsyz!GhynRygv3(e)x74Q$Lu4@Fn6E^=w(Ol-k-__SMz#7zYp{FW3bq%OQW-R;6ADXM#3Z#~%&RXm z?!{3o`sN!x`tS>CEl1J%4Jknf7VXWlgdd+7&(&ui!_4WE*tT~s3JBHL^77ahP_ap5 z=eI}Lio|9uxaf+@xc|=U89DrFR&Cr(Eku$*!eEXEtBy_5B>!2A`|rPh1pFTBU$jF; zM7|OY4_*y2%!H(U`;K_Lu`FM?f|S%m1|Hdm?mZ4+(f5m}sjg-C9d~eOw*qSSZRdqI z-lyB4eJI+to^m3fhvL-GUxHy5jT2v2fvHs;eqF?9gt+_&pjr z!?hj&ix(|s?w1SLU0TK!mtRizE`_u!XiHsPh$TxFliebVv(G*ckbL+3ckHXI=GYTX zC?M6d&??WyLJt^IoS*ydLkVqOg5|w$g>$uB{RwOA)XI zeftj}!RMv2DnR>AU1-rPm71D*GBR4wzHMuI_UJ}Zd>o6H{6L4!JsB}_1kDot1Z!(a zPEDa(x9*q{DywWdckV`Vd<;Qb(z8cTax&71Pe|dr`3s1TkD>Qrhj7fGV_3arBbzpE zwj;Ayd?Wlq$J!?ZF-eIuOV4D{q9q^%-Me>DT{I)@~?b^_sObZ=Oo` z?w!fb&Y(}9zO4LlBdgb}CO5kU{rmSLHz$vkD^_57O^zNkkiLEUv3AXmlyCoek_ zQz%lKH=|p(UMya`j6hu-xBcS|x_9kBa(p7~3p!9yS&VP#M%T`TSb=&{nl+cDQ+L|tu>pL`u9#K|w1@D{9Hl?@05Mc--TR zKw#T~*!V;aKjaWLZr;lBm8;0i%%DTNHdF^}diCr@j7L%%u<72d2T3sob+vV5WoOa3 zOIMCM>PVV3OJ%|0rR>;U%5f(SrAN2U*nt|Fw`f6OVWIO*K`EQ+swz5l?MX(nG(v$o z@FsB7QGJQ?3TmsX$Z6Gv{DO9Pg-&3xESu8OQj(IAqgJMf?B2bbyu3UBYHMp*xpF0k z9@-nj6GMLMR?PqYd!8Tr0^?pEhc6+M)6O`P+(dZg-%~kkz_GMznZl$g(lSpZv&3PAJLaQ_%FTOI7 zqfb1Y-aWgpdCL~YzcG&I$Gk#vN&;CqIgEevZHAmajJ}8WCRAO)xN)!X)U(fn@Nx5< z_i+5cUVQV}CoEX8g)`1NmE<@dV_zE2fD=!kTepsQ6b|E%c86B%+RAOW-%Ihn8fJYq zljoj&h2q`236>S}?3mZdZPkWXpLv4YZ@-J_AI%{%s}8-bTWBepmuU$=ctM*)Z(fRmPIbY3Nzzbtv=i`~5bLk})A#BAr^XBl> z=;v6sVGCKUS~2X*VcdJmE!=(caHdcHfQ+nGTz=_=bZ+0;!Lp3(1;0ni%gR`>VkLe1 z_Qxlk{{VA>Y6#%~I4 zz2jbvI%)vvX{kt;r@6tuKVR0aT}whj0$EvE|CQ%A$)6`e2)1wEevr6>8x*0nKjkuX zxR*Hpv;{ypr_5-#ZG?T*yD@BC;5^-^u)8u0qAbF#Qo@Ne(E&18(&0Z)wvHck zq@EBS$8n;Zw(2%UzKQD0NI(9hIB=;-->-y<^sUPRAzXJc4Hmt~^AGT32Uk$JZeJ03 z8_}ru(f7Fk6PncAqPTbiQ>M;h)~DYyZTfgjsW4o!_n&BIq`U+AZuLLqUh61Gj>}Xj zg>8o@+WI4N=6u1lSxb5Gg=a`li9-=`z>9U6ma@YqZRyZxMS8?lW^`)-hgK_6rKp5X z2aNl`ET8+gL_}Pf+T<2B?nSs{r5wf$haWlID@tkh6X~j4ve7ddK5hRo7S)fq^f^(u zjr$F`#`D=JOQ5aM4l7Axo{ykqVMvJ-4GN2DpEFNI1m@S}v~Jv@hHcsZ^MQUnzzPz+ zLMcVCzMeH}*N~grk^_m$7y?jQTFR6uQ@G};Yn%dt?ApDZlF~9lL4gqyM@~*IaiWGF zH*6z0Gne!@#rjRfBqui`w?#ULDt7PQM^Q-~?F!oyV}MXWgl%F8fi1M_TG+d}{*uf1 z@cUApfBtbYo2Sw&Ba`&>=6IFDs;y-Eu3{=H>%bRBW^OL2euI+Yjg;)IMByPOE|Kh< z7MQ`k{J3r#&02OKGdYopvfXSiE=DO2nOV(=i}kZ%?KZMowZ35jA6Mtoka}tldCe&_Wts0tk{* zQ^`zFY%VS*uVo%pd$+K!EJzR!$!Te{%+5mEL3R~wr=+ZkdecKe>(-coGPZ9oA`k+@ z^b(htLT*kL)R(bkb1_u`8zVNBf;O!Y^)(c2T~Bp|0vf50-AVdGltbOqs%Mx8JV0d6i9|wv3`}Td1y+2-8P;i%e2elQ5~Hy0V&` zrM2YcW@8u-3RJOn-8Qnavq?!#*74Z;=ePgqGGoRJva+(87(@O)7j^KtgQJ&e%TXR8 z%949UcyW%}B*cDYME_-C_!H^WA&+>k%jZfIyh2o?&4KOT#kkT8j1Z69S`&&bhnnD0}m>I%WYQN1*E0-b+xUaDIa?VU1y6;iS zt7`RqLXwo$oTr}}MVG?1Na=0V_QsR_7fgN?#iJU=4U4GUx-JI}fNA(-z3{y9%FB!$ z`yxsSOewH!Nz1%8y#4MZTz+P;Ul|7~Su$zj6h8lQ5qFOGr^8kte&VJBz4`y#_OJrz z{9g*#x2Kq!hu?)Sp&9=i^$2MxaoC{{ciehCbHDsn$GtiC3?6y{_uqRjF{ZD6qO^6_yw=C!43$LWQ($ZV4VPY$I^vTf-KC)jF zBXr|3qyIYa=sM8#|MB-IrA;UhvW|~tyvK+Uqj5XdMiP^l%G>X}O-5SMPt-`!xL)c2 z*ZtHt|LNDC?uAG@e)HxkO)@fa$!MO9B|I8nq;+XO;)yz?IcvlnC5gyO4sqKF21L2BfJR|wCki1 zehj^dNw1GK`5nRZHdv$M^4p*+8(|pOj@9xH^RPN>NjcWFp5j9d>oYw!20@x&fO*uH0K+wjT>N>uD_Z__PehxkU1Vn6X z^Des`y)m&T#rKZ zh8^8cKUJ7*+Y!nj=RMg-N16X=l6JSZ^&@O_FWcC7!tYBquG6n=Ya>fwbP4($DulAJ z5rl-^4D~zK@k%=P$q2viu$7O77m0?xruo>;fj@7jPFJNTMx)I>UEAP3)&$PSm~>QX!-WIq{?h8c;YgAK+)E zwVQb!^}F4`68Oi7QYy?HoSU0_z-t;?0w+(N%(YivtABLX2<4O|T+e}2`^}K(6;->g z_2*!18J~POoo&0zuraiyS=e;z-kGYp5W7lhIO(KgNQsZp%C?}I1vvZ$~ zj=ys)=~B4bP(#bDR?s3d4&9v^UBHme!m6Bn35R7T+@FnNJ4M6;1S--8G#=ImN5R^% zWebxhPv-X9Z+9N=D*igzOYK*`$gy14%~^qdB`5G7CAMuNgkZ*u8BN^5e*tM=2@ES| zzi}XjJ&rak{b(j1-2VV7#w0NznGOR7p=89Bcrzmw0C%fYV1r>a%nNiCK>?ckR{)li_hxvoQ5Z;_0Vr`67pJ_aW2HuVS6Ir; zzBD51j8ncBg)I!%5qEIKvQZ7{7k>0F(*l*y0MX&Dvz>a|VOL$W^YW*~NhopOlDj5~ zu&#QL&$q6-&&g2~F5iM<-xLCgm*{i0{{Mk(Q2#eXtFX!$yGpoV%=(|pz3``73Zh=1 z4s$TVO1ToY9@j!ORA~RlMLEzsmTh5}&RXIeG8~mEJii*KWA5@GBAdIrw0dKc8G7bL zG|Wy`sIcW&hChj@H6;8&IqQu+b%u|*Lg^!n?LHqgU2%BHa%nfEKGcek6W*dZdu8)Nsg>aG7En zDS*HIr2M-j+=hc>6KazG9Wj6ZDMU})`sx}MzyB@+dv&Fxtdu41zfXswjz*xc%?Oo{ zX}BARo&*Z@6MUl)I-`g?GTM^hEQ;ZUHhPjr4P*t|w{B+Z?h-op>P3ucgq1+oE+mx8 z6KuQuLRe1OQlQDc!`DQ|mV|&R=FMBc*1eMRhYi*fUAjOJ+9vt$7hj-z-y_NI)R9=x zIFjl&irZXMqY^4*6J4@uWZU}ra-tVT8P<*?>eJ6f4Mg87KnawL2Eq8x>f>(`5j7@6 z$oaCNg{v_Xh-(KsP@VR-7W`Q&vC`v?C_Z6=Xl2l`1pdYi?7*_W)#sPhQQxGM(g@9& zPy)j_e7V`eKW(XWwaNbt5km0x+izjI5K4|>VM~FH?W`S|+D<6pWUAZR+NN~Ou8u8s z4r)pwZGk1~bx$a%VP()fxVmRF+Mydm8sU>wL{Jc2J91P^vd{{-UXPvJU15W;9IH48 zTOT8AVWFgRs8%LYMIw83GcCPtV`?Q(=p(V^tg%vQ4O6e93aPBHWiWhHR}v*mXKq?f zxemsp(gz$NEF@q#Y#BmnvN+r62i?L@M3ED^bmg>9Dm^=taM+lYBusTDwC&tI?AyYb zVM;_DZhyzvaFn^JQ>QjEpg18gO5-V7(srJ!BJUh@o!#&RC3JgTtzFotKY5@QX~+D(asevRVWJWhu%REMUvJHJp0i-BeXp@WSIybL!G1_zO;h#{(d#7?rB?TW+y4D*|2USZ%qE2yKcV@zb|6diI^p{>j0q@ zA=kvNFLAbfAy~6&1)qMskak_WhLynRG8`>R|Lq(>r5mfEG{%`Bg@fzo;Hf$0ed?+h z`}|mjT{#><9V-?u;;AvO5wI;Tx%ztg_U=WDub!9R7|(-`KYDPc_5og%h-ht5%G)p5 z=^NEZMDG4&)rk79^T>wddtoX#bZpT1r=S4V%dzY@6r?a@Y=pKn(b z2Xpk54L(LcGupc6D&37TgaNrvCMi;s~g^z=5j@Qyn^1WaoUPq7VTPQH43c?5+{TaQ4pdIB~i_G#C@^ z^-&am&f!ETGcsh{*C7axnfdeQ|B7B{lK&sX{Iyz1W6yyA>_C7Qhu=oG!w=)uQKLyt zN}yMVc07IUHQfHyY^3RNZV-<0BmkSV7{%-JzUG9BFC#flGU@ekyf=L|uT7amyr-Ha z-_2+Hu4-({W=HWB0+xXbKrwN+*8E3YABOX3of@k^+zD5E~4@OV6=q@?1H z@z8Hzf4cSQi_h<)zOtNM`%1BeiQ(~+l#)uU&p@hrYO8B0tE?nsgYx*vNJ++L3d&1M zsR;y;hCy;tGh+NELRcUyzW#hZfjY&Jy?aqtR?Izj-N6yZo=HlQ$=&ykVCuV5IAUNQ zo*DlDo3;e#n&;D95#@$&5R>;?Wj`hUmo90)ZyWxpyZ3k8{}E4de={0f(Rd4u{_B9s z-a)R>FS+8U>)|L_2e|&ADb&CFz5|cdUtao8y`ld*;$o&26ttnS)*s2?6yZfs+u)RT z1u9U|RqGnLThURo`h6-6P9|ss^D?XzsA$a~8V?}si2T_x6;Xs$7*t%^3atVQbf}L0 zU6<@A8R1yR1Me04|Ka=@b!G~GR1Gf-8~LNpS7C+MsTYQ}Mk?oq=x%BF#1du2e*gd= z07*naR0ay^uYCiCVIrkLet!ObE?sSzlr+rZS7D7S9G|RQM27>_(Ye!hJuCX>aEXmi z7LD$6$6lCWM>vYI6?LGI4GlX2Sg~Touk48?`Ck{)RyrV5XUG0$g~VO5T-TbREEY_e zNL~3}4j*(3pVZV6lM=^KJq}^a=W|#x<3oB4J0mh!qbyCW3tLfEwvW1+TIy683+H{x z(&cMew0aZ$yCm_$lBHzj_oaMqF;6{qFMDcztlm_`o%amqxPjey_320X^vi{$wC>E{ z6HaFLnw3m{Ya*>Xb!OYv9UL)mFt-f9iRE)XW8CzQc=+k(nefD;%$@%YNx7}qvtu8p zpMNbZ-EPfF+fD=sC)C}-~1%b4}aLM|FwNM240zW8Vc-LF2w>4r!w z$?sMGo1{sawx3Tn5p zG$Tq@_#Ns}LPW3*iTdT&*0iCT>nh&nepe~ntnNtctZ;s8sN6PG-rW;~b}19NDM|r9 zP`yNWhZZ0svD3IA1I~j52e2PB$zMvOd*aiyLcdHQQRr+U0|*pt=exHiQg}pfns@I) zTuL(WiD_gVemL#>9Ky19-X&P7QPdkIp;`FT67YCTc9qnzV@nazZ*cCF7xBsLd03WW z>9WPN?T|xyRyrdedyFy9J;$&Uj^?wupHgcZ?A%q!si$AS=%=4%=!r*DvagIThxF(9 zv16F<+(^EhIgJfPJFzX{1W!X*StTc(aynz5dzR}j9m?BpO{LzpnfdlqimL>pUmeFY z&yFU+l+^6o!^#!QDB4@a{f|7#KSw=8VcYERq^S>9vv|#RTD9wep)A&{T2E4HD&CkF ze10!2nm1?7vL7)#iF7E)W##v?8`^xtAJ5RzBu&yJzel1sc|cjHni4+w_+wUW+6}56 zjSB!enynUO9Tv93uVEpmz$Qcp2!IpiCL#;s?-bjy!zpE>>{^z6_Z?$inMh@Qy~9BB z>-dr(vNlP_S|uIb#Ih}1@3>N6TNbum#kUI<^3j~dzu`&yOT;-|PuZ4LeDc9`iuRO6 z%HGfE;VR??V6kEOd|rR;Mb;JXBIKqBV}n)B#?`BsG;tc`fshla7_poEx=KdOAxddZ zZp*e@2;7K~(h)lp3Ol`(0t*XUC=d#vtf+D|G)}}4>xL!S(V8O4*5Lt~y3n~*Y06b) zS&m*ToeXXwu5qd3P$QVBjVjtCe>sui$?hgI*ax1*jZa~Qln{jFpUt6i%NCBi{Bo?M z1lo6OM}C_EtfWMSTy-Ve7B6DMg82w#han5Fb zbxXfz_2N|&@7_g+b~((PHJ9_xzmk(r9m=~CUdFDkq8_kC45mMk7@rTH83HM>r4OIq zL-U*@65~v&YHKm1p)-ILAUybD67c(dWM?H)S6f3>O^9uqw$gXdiTD!Z@%h1TD5Nsz zJK$K_w#(#t(sgb5Utl@kIGieRvg>e?#&aj_t!UJR5QGHzjq>hX9?Y+(}P_fT71 z{)fHDCTWr;`6I=RZ40q=%~H-e`vSgRw378}R?wk+N1lImDk@mTTazYH(58^2lr(O= z`F2Wn?Btp&uOg*c8u^7in7`=9hAz#6SUYX`3Gn7?uko)Z#%Kz;gHduA)(cPp7JfO4 zN$-A0os&w`-X$^Dd ze8Ix+m$0v@7Np@Ma%n~M&rU>XlK(rRvxB3o%D>Dq<-{t~*7MmbZ_v9>Us4JSsqlKJ zs;R_Ol3Kr?W?j0{y+?PZJ@o{43_1$wkBypjCLVtp-8#4Biw`FwWh_@+eIadgT96Y{ z&zs}lA}OO4nQ1<*Ip+Z`yX-Q~Jo_|e{Cfh+i+4B}SB5?{0n)Z1WaBfvPOybQn3|Hztl9TQ}l$7W$A9gz%A&mdQ(FNAcr|CERo0!)&d#xc7#? zVG8h>UNX~SDBHUY+wM;1uI-sH`y1-2Yp68?>@3;A&|^*m6<|+UC25&?f6!}ek|t@A zKTHImLfX>j9-0jU3zOJ55B>V}qeXTuJGQQ5^r)vu$>_jiqpqi*bvAQ9`;>Ry{)~~2 zJVsWl0t(t>N0gkfV&!C83zw1CMRRl@tCUW%a4lro9cya~l5mj-Btn2Rz?2YD5?dHR z2&pW<2M*rkfq~AQrz(XK+P$ss6DTPV%0eNjF5An$?zxLiWHNZz5PU*FunuVjFijb? z#%i~&n`DBJSdN=gYG*92bJPyEC&DbG!In)83xkS+lW~d@TDfw|35WP88xaa2kXS-u z2#|*EM};C}3k**z7L66;-)5E7NtKeiKrL^)_!Q4Q`!dH~dBss0$L+*rkxYM(*PeZXX|orRU(kUiOIGmcb7Se>BabgXpTW~(-lBbn z4lMq016SWPoMFcv%EE8v@#v$EQ`n^|OV<^1?u8d};c0{T;h!IMrXqPoO?2IVse9A z6&ol0oBFa++73Gt<@10P>@42Hu97kk9`MD|_N0@j+_srb@4XWadC)eqE~mm z|7->uOKK_TbQm(E7|<<`7vGpd-xDt&BQb?GSqUuqdJaFXT*vm38kCuUDI_7=MjATi z#l!=aa1w$w42^U$qOcT(^f&iIg;YKyvhNwBUC15lQM=}n`5_pbc7XdwY%(7I0_OuL5H#yrc*FOFy1j#7>p z*b6(bmmk+|;gF+-929p+lQc<_{5hf=tA4OzJ2zf>0RBJ$zYfjQ(iw8jHI&!;keJw2 zRebj0$86YKM0I5qm3#NGXu&+rKI06gfA}FAwr{1RqLf>&zm8jPyn`*pyCXIicR^HD zd^2+r?OJ6M8|&w=BL_44`xPi^`1Jkp9NxVPDG3Q=X6EzQ=+~*VZ7fyGrloT^y5C{M z`24hJ)tNgVdWm42g{^d)o)rQasAT%Mr|Hr@pJwT~+&OYIrL`786>(WAw54p@`laNh z$8y$%=d!c9nx`JTkId|RR&3b8Etj9mF+%e$%&ct9W;zJJ1VeDgOcJcoH$@0sj01baP&AT>MfM2V&PXG(7#t9$qC7v zdC@HtR|K(zi8Lg(qdyC~j<09E%ORaQk(1q-cR%`q0Gfx}KH)|Dd}{p3?Te(R--AM+?%_f#-?%tW#ax-$By$9VSPYnb)%`;^qw zpsqOI4Y`r8Hk_{P84{@OS$&dTBB zgjlw}_6k3ad!5kA<>VVC@4WC5gzRwoKT4sLplx9{uDJRtZoU2@(vnOB9(o>g5;xv* zBWDde8B_XrZtTl+?%IX--hPXEJIL|J9F0c^`VKgXc5MqVl!X$KBl;aq-~NYzZ6G{p z9CyMgWThpOk>84e0|pXf81(MfpY|O(pp+mrvw%~E9!G*l(r3V6-Wc~9ZvY$)1;>21ctk3E45hA1l! z@YEBdNR2UBw_-W9!4Ulh^=&e`H%XKH4~Zm5sBRy3-h3C6-usecPd$g8J-cGKmMAwH z7y(KW5+1tt8OVqS?&FvNhvHH7#H3_$ShHd=*Is`cyS8rS>Ps&p zfRC$gzKP?997}3a4AKq}6BElR!%pVNL-KiQ)FXVmVgqYeF6M7n-Aurr!TIN%%KXpX zz&b)(MX@W{S+o&vQVYzOIJ_~?rEL!1%$vvN9VK`Z(`nnL9YWM`{GcP)w!Mh0 zo3~T6V-NZ5J0PT&g8bH$Zr^~iswmoBLRMi*LO{p%t*9^E#foLi*s-UEUPlf_QO}{> zTSI**n|AErldo3NzT;tdgiUO+AE82&>)xNi zp6AC>Z)>nqLkMT!TN-HDkW?#0&*M(O1rpYoQ4&QEUqTvpjCdGjIlwW(q-C4#JaB(E zov4B!Jv*OU?zl?_$6{jHU`sgpv|&!Bm5n7OC!IP(!xJbQeChoC+FP)cjoBidf-c<& zDalEvof?h-$!XPv8?WzzQWiUk_h3snA?@;;@j#c}&a-u}ZJ5#t zXx+6nU3zq6#>d~#{%@yI(7rqOkLc+H-U64T1H;s;XL@n(*)Ol!UrFJP2)H+B_vA5(Y4QU+f5Fuzc)ma@L6hPNk7 zVo;$#)n3b6AJ1dex-A5q-9;(I`elpQu(gb5CQah30WApZx{s|zi=5<)|3v@z3q|O- zLuo5yFodve$35-D+o>Rd+6qjsM<-?|3%|!l`MzRm>VpW=gGU%h8~kxGSSmziZ7r4( z`2Btq9!$f7U0)5#B4`CLWAr}jF}0>yT~Uh_vhl}z!3<&~c(JG_7!0tttd_XAB!rY0 z9uGoF>grsVoJj;wrb+&avY!(8b1{J~$fW>;G&z0jEAVtcA3H4z4CxGffiO(Xqv!<2 zVtB!0BHa_P4MO;|>jE6!UXZ4A0+FRNfmEb;)5Nwkl#NCn6xfypLSZ-nwl;Q{22BVs zgf35^FbxQ*5K5yGNm*EU{#`B^q>*-2i0A=BP{llJ+|b&QD(7%o_<6VIXm zB*IAJ+Usv+!t6pr_!lg5B&V`9H~vxBu#RVMMg3`@kWuoh`}2niEg#&GnovuT@` zgs^I9*{%<<20B?zYP*$Q^%cR|8g>-##v7Bwo|4^Elvfc<@*<>xL}Ex2g&v?P zf2v7Q@owV%@nmN-C&pt?R$7W6i^`e`dEr>vw3Q^DT76$F(*%e-9T{02pv zx6&yii+y`4QN++JF^P_?GuX9rE0%)#sv0aCViOGKAmZ{IH>rSsRS7GBVSw_VV-Hb8 zOke_pN21J_FnFNloURc1E4}Esg*PnI7= zPi#g8`EA?s?Xq?3*;gL6wYuILp+G5v!k&lFrbQfg{_Pz4bT44~>}3>o?@On)d2DWx zLHXW&OquclkKb|{UD~HJdc@7F{;C&WFIz>uPzXb_Of?4b{(WObAO2m-nhFJYvk{Dzd~EyzysH(>p0lE1EmSEyf-6x@)|NNFpX z{zP?MfJYyHmb1>gf^*KjipT!-yk_2Tp;_E}B83sA(s47zTxJ~y#L`7#a$t{emrXm2 zdE}bhMWg4?U}8sqEr|xwRN)i3jTi7}!gwN_4g1H9h^S>wpaC}p%CTtT#M#Jj*Xq-# z5KU99Nt)z;O%x`061neR4{^(N=koQek9lL_2jsQwL~eFEC=(kSQw33YP|Cuqs`c!b zenP^7Ab@FEnha1A=i&y$pum@!!)xOwAnNvU@4XMOXw^pAbu2(C10@Zl2;j3q2u#P- z37vZN?w(p5^md zv#G2oM+glE<|?8JSi0l~?tb_gjy?G-Ey5}T)S_08AP zHYc7pUVe^Qv*&|IKq>Ipb%2R2v~|g_O)NZENKBysgS^6CyzuJN3Cs+=X?eaRz_KgF`uTe$r1*D&bFepr}j=3<2N<`+{wUV1T~BgmE1n(uEG<(_o`300w(Z$R|D%r}-sf>RQxD=` z5gtOqi$O44_N<(TZu~L!$e4Bum=;vcWe|S2w(`$qv{g zP4eFnr4+$nkTq-8kei!(z-yK-Urzu2{Q)Q~EoI7-DO`Q^)eZ%&Mt(zRmJr)H3>qrr zuxd!83ZWcNfq`=F(NHb60_v+-`u#k1@2f!x6Odp_a`Fo(?AQ*kXlO??2{{U*p<~yS z19c@Ob!A0NoA^30*#+z^F5-^+M{(W_BlzcCf5$KM`eg~n{j4ms3q=4Hfw~G7E%=VI z@>(!F*uo|#JhaMhN4NH^2@~Ea73K_xH104WkIdzukh#S57g@gtm{r0H+G6YIt36En4uyq`~!=Wrx2$xwU;;gcr*r*7Ds|w$1JMT?7 z?RE_#F1WP7c8m>r%hccN@fhW;a^4qCZ$zH4zs#61gRHD9diCn{>pP`M{%6GX_|Bg{ z-{B5+ELA_39eh9$f}OicSh;#Fmt1-waj`xE!2tE4deU2@Gwh5r`EuSI^0J!KEHw#j zCX2X!B?d}bdUDvB>d1D?e+Gh3po(#0pW^VdF5{?vN8k|$p!u;YS^Dh)UYPbhkKKP8 zUXQIIVoX!hc)J$3@akHNCH+VY7SEf>yfu5c;UBk?MD$wFC{VVM^4Z8R*!Y|Mu4+>K znxskomqmc^H26E>LNOy@9?oZ@(LGKs92I-_^6iAjD3YwMJ0I5I0heo3YVRG5*{fW#Ur{N(V^cK)s=g=|K2-U z@coYC*KWeiu}bO&8V-0Ex!S}}=kXXJCFUD17@pJz0xvv6DDh~X$UjoT{S(|^OT znFeJy?%znM4V>S|(r>v@q_@q?! z?A=GR)MUcLQ%CQD3Q|*5$+*{E=id`1vwPn@vT|~{^X~f?aP*Ow!l0^RAC{#YgPXQI zhEH)Qf@OOde)A2S^^d19yfEsa`aQJ$rEfGj}p*=!G2KDYGeNuSuGuN&XNq1f-;A^4_O&!0-{hk-L#}@JrVpL5qS8 z%>Q8}w(tWcwn9T!!GB<*lcY9p!KYt*4NknCEu2i*MpqupaJeRFk|z1TDW*QGXe;2R zO`E8ztHUr1Y}-akNlHoz&6_v>Nd>V!7(#d@wRJ&^SO-mCnAFu*Q}h4WJMTCts;uvS zZ&ioMIVYGIa?T2pBn!x5LNR9q6%`N=6%&dgi)+|*4VVKcMkI&<5mCVef&|Gk!!S9g z?yjo){!vxkJ%n|4pU3dL&iQ->y1J`woqOumy}x^+&xg+d&9Fe6KdKfGK78I%9$xe) z+xJ&;-=ZaCB*(C8$M-zG=pGv7d`1mA)r_E%8d_5$ufO#+8Ere#zh5tF3YC2I%}z?H zbjFStg0G>L*!U!#dG2{U)%nc4<6(LaAHnE;-BD#d8`r+W^Upm`NJJ8i!a;gQ7e);3 z&ujl&LXW>KBvh5CRwa@aYM~bT^OCfpf%os2y)mpwQ5u<4`pkJRWKrG|DRK@#&HVj}M^+g`t}sh=8QNtc1_L*v!J` zUZPiSE8GTj>e!yfl0!WI{41O`s6XH!j5^*~xr+B!ZRFXf{(`By)R9I#Uw^xkLBr1{ zDKZQPZmya#4G_qNG@>FSa42RV$j%)<^Z4IiV&UDhn6daR3GDDJ(xXY#+X0rtE(dvmUOMo<(2;yljLMyIh;}ht?h2lpPLY^;3X9+)V~xpY0U$ zKLvunHn8|L!O_2Jr>?G!<;$1qmd)U zWwhyVikXW_nn^mV%8FU^&=T5rKZSmsIv_nIta$THu9|)u(OJo;W>P79x+F6>7THu! zZEYjTQBjs3M$2xfg<9y(Oom|~gy6P0bNxUm*gSf&IZ^n5-m%|X!45%AStbZH)4v2R zwvDn%Gbeugn&1!3s|lNbhM}10WQ0UY1u4w5GK!-3HIB_@H%U-iX8uBxH(~L0e98q= z4h8}5vtZ345R^pA7KQ*nFZOkT02J$!uu{PMAJ~QGAI{_TK0Ylsb1DcZS{_uhGnZ+GPpt<>|~mP5>)a}WP~cs8oyK!l#aEx`t1TS_JK=ZjWcw{PF` z_$B*T@TXYcSl~ew7*YwEYyFw~f=tgrOxYi#!vv2UtN%0n0>A#5pIam`Zk zgT+7^GaEFkw&5P(*ASm*oeJciJeFVU=i@Guc990&m}=^Argq2KT00hxROZ;7-a;?L=s}VBg++=FOc!Ty%6$6d8e+1wmL+D)G@_eEiOO z+FX4WiZIYT^(=e)Q%0XLfk+h;Rb}?Pxvc#73zjTc#AAP7j8jo?BT$u4Qj?O{|MPYb z6OmdaFFy4oWkv#vW?xT;(}4jbWp`)A+bcm)XeiuHN&V|wJ8e2KG2!gqR*rDGiHr>M z*F`?wMY@GrsD=L2Bnd3UQb*GaRENu4G>B2zOqb_rxt2q?D%7y_x- zpu}b&ptbb-Fj@fCuzd_Mt2pTzI2|^?wZLew>MFQvC!#+J0JKP2@;1SCX?}x9lz|XZ{@QP@fOZH?-F9u+Hv8evrr`Xth`WjZ@H2B(tMUY`cJ&NHIXTy z^y|@{E$iQ-s!pS>ypE@y{3qq5g*M%X54%;>$mKnp{j@#Z@jXodSzxk5qo_U(*UVekaB{e}aB1n6_F=P-B5`JZp zl(wcQh!I3kg(tgCt?6HgUdi$omU88k*)(YZBP3G#=V1HzSidnpII(Z%zo&v7fMRPQ z%|Mc1Fc|>9cH)0CCu=QFKfZ(;XD_6t-UC)CJ;j!;jiIo+X_++z=u%<`g3PIZ5c2b6 zaVs@Iv%r@`x3C(*@XJ_{5(Uj~52a{x@?x{>&?{zDk$j=aOU` z;)bcyIDguF9=PdD?wvc6S5~Y+Muc&}l~afgb#nbh7qhRRn51_7$n4UCw4_-4MrOZt zG?36)3R^cL&1yr^Jkl+bvyc*D=m=Fspra#@LN#?cdL>)G|B6pG9i~ZxPzMO<1)*9# zf>`%B)-I@9JUFeO6^X;}Vc|v*!K2RR=2azgk}yA!Tu+7E)1JLrGp4KA|EMCt2A!Tz&1;jF~u|!n}Qa z_QkjK8aS2*AH0jq)JWcVZ5fA(>v(zjyQJo3k(JZhZ{CFfsH&^0Brop>nkI0EMUaw_ zPIRb?+VWzK7M0PYgDw;jQ&LDujK`%ac?tNn=?)M~iF8ZP$tF;ymhof|S%$ z^7rl{CNZ7Vv_xtuirJfAPDWY+!dFFUStGi15D^(kdS(V8hJi~p!ID#WC@n6du(*b{ zT{_~cuO$D_K_ZfKNlT8yq1TglxPY2k53cY?(las$4GA&%`yC$pzamrTXCUw*bsx_@ z{ump-+QOXM=dH4h@XN#}wc(a)$6+A2^6IPc$|h#adz^&$45nUrE+DC{DCUm2^Vt65UOJyT5FZfo zJIkO`?Xr<9;7(%QAUOtrj_2-WoCL51FfhSFm)3Wt8%Dqk;_rDgU>i)w{BY9qnv)%GCw1L2#W%mmKVjQ?eqlgRi6HY| ztE7-r{n}S?Y$MHFLhOzPIg+0Q2M7F}jli??Ut@89oaWfDl*P)wRiC<9AMNXrrY0lk zyyN;5#G}2)n$KMEo4?FHW7+r`f40=?Xky!)+GiK9mQ`B40t%%Z%T7Mg?-19le8=Z_Ve-c z9q=KOmSN0)&wum1`k#=gh4b>+>i3v4?;ds^IZCvu;qkf=NNOs|cxmZUA~L%(v2PS! zU9$1Z?>Teac;?T#0#Bolss;~NTzw6hxw$NT{%Mli_U#{n}tFA}$`VgUU z+&JfMZoTe2K6vYOZoA_lDttP+F6n#9X*~Yiv$Tno+&||QmaX0ddOa0&Ue204m47}w z)jtm?ikJNTyO?+DJl1Xg7U?r++om%Q{o_ea>DdvNlqi1LDl|1UvFM&#*qL9$KVMwN z!g=$kXl&&5H(uhVDOa)ea4oOB@-jDFIEkd5BYFMhzwydbe`EH8ukykx|K$6Rmhsw( z5Aim636D);{*ouTXk1rQ11NNmHN5%UQ_NlXGT$HC#{Mmza`ohExqRM2=Fhl{*Pnfq z1&_T>ZDkp%D~xMzxr>``xRg+biY5(|UwU_cLlT(2mPn1J`YIlO_ATyx@FB*H98T*9 zjrmJn;*zOTh;S<)8#r2!Pjyo$Q?8v(QWX63#afmweUYorAIE_MM|t{hFOi$-LMz+P zE34KqabPFjc;gLjd3+gzhIdCQPM&!B1H^UbaNUhFKseC6hgtXePZU*DB2@=t#*arD zO_Y|FkevP=(&;iazIrvUy}q1weNHDSy(1v0xTl~9#VY$IOmHUv#js2nHlJ=#Lg?5wix8*T zmI*kma}*UJOr9hHLmEiT#Wx{6o5c8N+|7HziB}eRf=_{C+3frOY-N(R6OIL%71b{7 zZTlfv-3okTeQ6Nvs(mbnlH-0j@o_Vqz{!{lXkTp@5deVASL0@~kb!Uh-H~-tfX4}B zeS${KbO+KO+1adR`7ihgYS_=V_5U$0@xPqLLfTKry07(x|H=F-K7xi|Kzt`U`$Vw# zUo$4{@gsxJ4jxy*?HSGQD-8_5ur>h_Vb2;{KJ+kU^*+|D-^iP9zJ%KeSQ}hLfaXw;iU7sM8s?uw_fMdbszG|vK6fVXe~Q` z{DGyft)@w{r)9h9u8XMXL>_tUKJ=PG#*P}#SKsF|=k|L@j*4aC#Bp49=_Pb*mrmav z9rRB@NThI4ux}UhXWmPnfy3DL;|?aDb3V^J^9JRW4S>Y)2XfO9m`jx+1w!i7RF#om z<|8e$J&M$bjtjxt*g&II=}PKNlok~d5}iS)D;z~J$jV6IryqAwSXP50B$m{K7z9mp z>fDZs@=6L0=TqBQPkdT3Iw2&)C(=+=ijHY2M{lG!uY@1BZ|9Or&ca^Gm)vs?o!j;# zAwGc%E*g(ebc%Lw=euvVGGWprTrLHN<$DOSPr*}V*VlpXib>$Q%-Y1lJ=FVb*0s=l-7}* z&%m&*Gccpy6#pwD{I@p{K?`VeFi5kblf7QHj!_!*96ofA`X=M}cBBDPL!g_^(n_EJ zyFDodK&t^5zkUU=>Fvx=1n!fvm58~*!RxgqR)Wha(E z^XD4S+F8q!F#Bm2nYZ$dGkhuEvtaAqF@b)Sq;RA2#Fyy z)Qu{AxHJQU2tuNw2y?ql?GgCLnl8ccG_vHbJLuNEHXxKumWo@okJ&=KBx_U}JPrN`jLY1ebXWml7y z-H!0EPz=ouS_sleN{C5FW#YJzRFxj4ZSTHx@7W!s!Nu3y%)Gfb6B*{B&!8Uos!MqF z#h2N+=LmlpKOUE-jGHgNnyx*1Gvn5~@HF|*d_Iie@rerq7eZQdv!#zRaIkm(0qPrd z)~;H?kYU4F_2I{)CdZ;H5}jsgum2DvgkgzlV?@Q_Qt%mG z49nY7^9kH8Ck|CblM06J1nENen3cNRZpE~8={{7f_0OSNN&zoFeEkL2&tAfmsWWJo z9%ELzl1`@0x|5GSS&Q4K<-XfyQd3jRl~ZpeDmAuZ8|V z^qcF~gEfxA&`ofoG+U8^5S9R8nk?+qSfE;pCwt*EQ@RKQx*oWP*_PFY1F9;k*t2^- zs-+nefG`ZxaS(x7oZU)`1L(SjAtk!~`!PEt6O$VFYOC1&(~mT1KK~@8TM>Pxf=^g4 zKF77;j~o*q@KRfGn1v56Ca;c>TVKwBLkFoxV)`eYXhc}x zN1CR7!vORq^7rrLU}0GhP%tN5P4k){O-h93C2!v@3M%UG36oD-Go>iOV-0lOPLClm zPNMaeNV8&t^dayfrG_TJD+$z*F|4HIQX`P~){?ibo8U&8f4Z)jVzUyl8isB)A*@Y` zG{?UHqpp^pckaX^4bz}6h53A?rTr4ZEWarAAemd62YXi|CDOi^mA0a(p^WW2f2JuI znHjnn32(hthMljDzz_{2vsKMN0dGAo{NrI(e)cU*-bNPApU0+eb|3{PmR78`qJp2c z|AZazs#*Q@gYF;`sQpPZ3=^PA18CsuuQssc(PsjDU_M99kZ8I@S}(b@w*bGk=0XVE z;i1IExhO9_#Nqq`ywVkL-7qxEx}ac4(@RYEcU7WDP*s=T0-*$Upn&=A*Oiv?&wsp3 zul_@M@zs|(W5h6|p&=9}Is%_C<4O_sCP*bEDG|jm*th#|?|6W$F`-m>Rda>)<^?bQy zGmQc^eDnb;-d=@AaWQ1{7?PuOmOk|qhwD_PU3(=5cmBwypM1kP7hcZNm!2guG8`1s z+ek&nQ&)vo55W}`gQ{0?XzxA@H4KkX&=m&>2?+=R?K^kpnde_(`P*;u$m5Ghh>pO_ zKKRE<+htm(0O2AwA)PiUVHE7$j#S)~meddx6HSCeK^Ov|M3b17ji@EI5j;t8D)E2a?m%NNb%*a$*ce4&|ZXrQk>b5s8^NfL*(Ga@PZY zW7^F(GyaUzaSI7T1JyxjbUZ!!_2b;L#`FF6-%;a(ORu?!-hBq(Yih*j_2BXN5JK_K z9p-XssStjn5_m22$D!ZB$-*9X28wD9I{!vd8h{UJXh><`^XZ@)V0aL!hG7|^456Cf zOaMmnV0Tquf=0{*O_u^qYhvxH_j%;OhcGmAI`Qcegb!h9l6-(>VD7%82i4&~QB;Jg zqDcY5hZ)LmEk43rz_x7on7OlVq1NNYXYt?=5_A(JXa?9-NKXEKnVJ?Iox-we8VoF5 zn}*a4yqeiVZ+$KI&!5BkjT`X-s47A?0hy_Xz+5QN0UtsLf64(<9=aKoC(LtoX={Nr zbDxkcQ9Hj9|9qt*_4stYJ6YgZwKZCp z34m>_cQ6nXmdxwxYk1ZK*CWK;Gh+YN5-qaWfpL&t>TW^w@}yAgq>GRs1nfp@)wF~ArG&Ad>dFn z0O%kz{FMWQK%%p2>qchGxP=Cv`6@}>Y!fsTOFJkP+x?9egV)ozMgn1CE z#86z;Cd+&;gwRbup*m584@3822w|q;_?62`NSs6^wBouOuA!#5km3CYFlfYIX!5Bz z@FIk%3DUGCgd+?g6jZ6B80M(Oseo)mvGckq!L=RCa@uC|*~g!7@uUm+c-@DD zI5jXNK0_cBa3IY42!T_=8E1^6Q^y3JSa=uhayzr@=R7NVIE3srt*I|R#Q1YBVaUj_ zWMpPAf8HEUJ*6L~o!Xb}Tff2O07bF2&*qr$c^jEEYd-Gi)+~SfExP2!v3Sw_)HeB8 zaL--bFnt!q)e2eJow(?%QB+lw(eLyLbn1{sa&iJu@o_x=!b@Co`L$FxHsM4EL#0>m zKIHA$#-&%^K&Re)NlA-h!pLEqckz{!HF|J4pi8eloO8i2wtn>`BZi+&uYRZS#N$sO zbRD(1S>g{x5(f@7~m##2k5XZC%6Wyr8$L^vE=I%zU1SAI-tdJb*UBe{G2 zJRW=MIeyrGlFxifF!iN8O`BTv1|`R9%&Dn6F0ubam6|9Fa*o_(H& zmpsOpF{3~>^3IAkNXg1Y^EUFyC+pd?=}T&BDtT_{v%L2Da-Mo-DGMKdgkdAc5+9$& z`Ik)QqAM=tqRTF)cb`7=?c0aMgjj4p+hA$|fqy=7{MHZMG*g-y!0*1>%IBYN!Y5($ z*l~2u&Ed-pAMx#X-xD62$k;O{l98N9T~!e)-g}25#kHueFoq5vNv|H=QKgT9g2Q~U zdL0$j_4Mi2pTPtA@$uSs`Ekc?!ef#dcjg3gGsAEgP3+sbodpXPkkPgclP{c1@xh;2 zv+i@sYCN1WXdtJZ(g#mn6`y_h9y|6Fp$R9Qx^-pbn9+nOUcUV7Bfi+O2gMP>pwmyM zPtUFhsdH%WAr?RQSHj{GxpmsL7NPd4I>m2;7Dn(b?Xm&y8d%CRL(o+Y+5Bp zvw8E^eDU@7M8zdCdfY@>rzha8tK_Y>-zUGY6dx*Gd-P@Gut9`4bm}Wh`S8Pa>^oRU zR-5*mHEtxkwr*j=rmyfA4hD}LL%*KgPz@iuw{B(0{eLAZJDbUqCK3}77CagNgNpJZ z-dgc4Mb!(Z68hxfv1cv-u06{SVR3>th2r*_Nc-FH7A|41q6ty(kT+(|@YfX~A_ zufD{#Z@=NJ@neWmnmABW!RaGM;;TQ(tIJk1dh}S*5<*zB_9M3MK7czsii<9oMBbr8 z96WfC^Cq2VDNKFT*A;Q=tb52Wsb#_9N61P~;pov~vNO}ref50(piT zLk(dY#uD$$1JmrUZf6d1nDXgYb*KUj+GYYq&^Uc>^uyNB? z8k)Q$XJ#;R^cb>I+$1C?k<&&q6UX}+`Qo!r`DW`j)W}3Gyyzmd@&kOZW z8bb#5M^ThtaX0HiN(bj(GKKW)j%@yJ2lY*j#HD00ux}TlLYugG)=YYx(v^hdXs(}r zJ?U+`S*mC^JqHbDRzxde!d$5SG%S`$+tSvmkx9Jp#!6PM{)F=K3Y_k6+IH=Z>Ik7< z|3S=~8%AQ7lgQi-%$Rd4JqGq8HYt_Y-hQ9WKkTKUG@p6*JxXL`3?32AxtCo@XhH_{ zN;CrokKm2>Ugy)#zNDh2iO{H6dUxr7Vi;zoe}9;rN?BziT?U@X#r+46m7K(q#rN~x zM_*AE3q$ zpqkH!*q^2gaZTn7i9Nc!- z0!ED-feXwHn57u$f7&3F@CbkABfq=MA4|Y3^c&K@Um5*>i3AGhReZhSV=kEX0GD5J z1sREMgi+73<;%G5uKSpN^HjEf^Eu03dzBYfyieWXgZ%T!=eX#Gnbha+V(#48JoECa zB*+SGnK_rxj7|*g(-Fn#LKA|Jut++0%3sT0p}?%2Ty5klKGIqcv0 zBiCPbDX+f&AyNq^HZGQ)15YD9Di*b|npp_Kf0S6=iI~G+ioXLc(`ZIeAI{T#+-E?syh;d1E(vLHaWTE@BNW`Zoh*^pLrJ4P-4?l=se_fS|`QgcDs%l z4H`aQ1JkD7N^E>Gqb7{OClypQbfJ^kz6-qvk0K{G9z$qE#YEFBB7#?6Sjx{ws+o7= z`RESF?cR%?eNH1aDW0D`d7F=ZDy09&5$N^RJoD^pbnbKt`@Y}G%)1|F_8oWQ@>Qca z6~6iI2iC0qkh3P8hawGB!^_SezUI>}x3hfpdOBuC;s83e>xe+|^@l6DW5FWMy7)5o z@7ToZb)WIlYp<|-`$m?&{5qFhJ&k?aKWEaUOZj;1N;+nRF#Fc|%qed?qcu-x6(dYVc|XVX;dHO{89aIIo)(>m&3u`TbXzJoh*C%EmI}w3a8hgQKW=6 z;&#;Xz~V(5sc|x9cu$^s;t4c8l5;2YM+hBF*FbR-5gAXHjuE{5`b+G|FJ-~JDJZH7 zMOgmBii+($t6-SsYT+O;HHCitPbDEW1HHbQyXMXzzfooM@F6_1a30_7I>hbMC-cG+ zk5DAjnK*VRYgfL*XP<56$;aojcmDy_to)p_Mi1cqx8LI7$6w@<%g)0Q5{knxxPQSS zqEj;IJ9rdMMMeG9*Dfo-$PvcCp`#f%bc|{GwaloB)VO8FObiqp=uDq}J+^1DaKv)j z&@<>i)bxF8D$C=+yJqv%PkHFLKnfIRC}YpPgsIm}X3F&)P2&cZ_8OgjrwyU+z|&2C z&gf3em^&YU(!*Ohcfv$`k?~Yld8za`=yzH#LR2TNxHK-hZ4rI#2k|Q$yo8`@9RS z5v5u(FzJs4QOsoBrYns=5e|eJ#<&URFm{6NzijsGoXHnpN4%%DYRfg(wZ}k3$LgC< z36D|e|T(Ls(qoH2F+XN;ZTuhxRi zhXC7gXyEBXO=|_gc^Cg!(ruyNmi!>FnOW>t)D9Zb08b-tyzmU?UwS3C%$ZJvQAa~f zG56iKhI<};j&sMIidtX5U(UIhk2Y&abN1LFi28jEiM&y~D19dBhtoV&ak* zH25@9LPOa3^?J5{{~b3x@ONS(bjF`KmQO$1%*7X+M|_AWZd1}ay57LUiyvds1($LC z4cAaxyo>eQico|k#3jhd$)U8gnC{&>^7@AFXt2zG9XfSm*pM#7NCW9BCp$ZfvWgn| z^zO-~ANQg;UCe)A33k~kfkYbBtX;F3iIcBl=1o^4kT|55f86&TmruEl3ogD0y=n*} z&Ya4sci&}5pF}(|l(7@eqjOdm6^D!2vGogjoSMtWo3`=z6OYlkOFL8vs%#`VEr~jx zPHeQ`y$wHcq^z0*LlB>w!hnIjNeOY|_Ad>>|Gy#xjWv~Y>d>C9T{@7Om4);aBZNZR zcG(OY+LcJ@LHAV9wtagl%S!3qqa!QUf6mMsF93&1`)*wrae8;6(AXnASh{9Y#zMiT zIPhvdLfsB>Tcy&o<4{5)LYXq<8m3LT1`Ts^l~Ph!R7gx>I?0)le)m*?4?}BW$zxA5 z>7uK+>YB@_FF%D#uDO@ZTXx_wnutlw;+%`mC8S{xt3JAf@4niIvo3)*RojnAj)>?|k?X2Mdl8rGyZl6wja`{YeZBW9Oz%_;KrxOkX^exG>3> zF(cTpej}F+YmXuX!^e%{^d70yH#G6XH@lfUvJWX~X*BqJNTUYt`kyE+Z^F0Ey46!sn7k5_S`;Ka~sS+!;@H_p3{3&syH$BX7c>K-yulj+i_ zEvf102-VW4{puEtKv^vjd?Xy$VGf}B1GG#Ny%Vh8q;4REilRp1a)nzC7*_C-qWIk& z?DmCyPfJ^)Kv0cZ1D89LVWWn!Bd>~9xe44n>P#-YU_4G?ny@9RKkUus1F&3f3{-~$ zoGzR~MO6%3iVL@*Sehfl3La8|fPypdtc3t83OOK^fIgwQ;a2#63shlt{mb(L=l=02 zP--;LJJtV51b2|&@euspn3~}eTpQG8pqb_y>E`ki{`QYOLj)Z*mvjsL*~tOT0pPDq zs!(WZY@)KfnvvbRngd@^@p|g1tg0cqb8kR`OOT$NL|J()A~p^c#d5~gi4F@z^XinA zR+5yQ>Ys>Iy^dW!ZsqO;i|N+84;A$q4NVRBa3FD5{(=CK!n}jjHr2Ch?*Ss6(0|AX zdUfw%#xg1{%lA+xJvp8o`x+@Yu$MVkT}*D@p|nbhrqO5M(XDt^p_&n?Ky6(WhV+ql za4$!kDv>FTfgC-2 zgeIS1!6vhKyAx0hAM01Y%QLUOPq$NtQhM+ZUM&F~vu>#X3_w3L3Q zoP{AJPNAVooucY`PESw5K;n*wAUPq9(t>NytQl@H&4Hw zE~ky-_NnLKR2&FHn)lEeS^MTPo_p_e`ki_z1qDaZr3+n`py~c#2&864McO{0LZS&B zO>r=2#2Ds#;DyH@;UAj99SiQIQ%)vGPz`Ib6bhk{(bU&e&{zjV*!*hv3=ap2DmX7C z8Ab6D8XiVWbPV|i50jIqU^ra(PzZBIk{lb2ueO}xqfKb4oA~53R0%>#^7rmx%9U5r ze&Fe3C5GYk`7jJ~MA+}4L{d>%fiB_jfxQ$6gXGrj=sm0lPKW6aYgmvWCMFuaxSGbw zLhhV%D=}$pNRHB}sH_2mrM*-9=AYWqV(O~u*?%aX+L}6&GFs8EeJA{pjzaR~nz#7J zD=X>U?=*@IAI0O7{-iMG(=*M%%`*Qw0oInsJp0|vTd$#mccP>4=#%L9+SXg)WongLM? zX3&x~$DL5iBb-FUwqnuWpEG0f9D(}AQW{plG5?KPsD)bS|8sI2nrAxjCU))5XW&K2sKP+%5=A%58VQFRp$Jk^ z6F7WeEncq==@96$k)M9rK|)SXZkl-;2lnn^*Y<6oOTsYlmLD-wBM61uPCbZ^+Q|9m zpG{_3GD1oWhf4AO1L%f8RTZ-syOf~&*tugD1%-t?f7iW4iCR8bxdv%yxZMg3^))or zH{fxoM8_o{kqkd$939%{;FKU01*gCQCsrbDR9ucQPU+m5o!h^o{+uypeMoC>`Q10$ z=sWZbuAO!r-+uT8Uq7}AMF<>1p}wXXUDwft;ImIQa@x>gTzTDezFqek|6H*J6)?OW zbfKUK7cQZK5<*5wGCytJfE;rwnow{EXq6hl&-?e&fADbX%S+f-Sj5GhE<-2^imF(Z z2SAZtbg7V0B9Gy}fh{5|8(p3J24|H8*B zo@euO8*vDgP=`uQRV6-M$B+VdY%KYCKj71JROvJgmWqNaG?Kqex`YW6#xwJ#sr>!v z=UBMlcEWUn5Zg>`sN{C+j?<{+%@>z4<=RV$P!uz6MTw+mhfEIryoW~b2MeDy*@l1A5AV7DJh8vJd8MFA|2Xf;5KxG>Oxc=zz_~=i8pXM1P*-Em*i1dRn47C zW)Y!Q^4a#I=+eODa?@B_hp$P)8=@1Jo<&%so8hB}F|=QAG^wMgP8`w<9C4_U?>7Iy z;NfR-<+WGv#p-2je0&v(KZ0DMBQS)(>(l*pW(7W?ToS#pk~&W#;cgcxF-g=FAEc_b zfw&0xaocXxkTBvB5tV|2?g17lFg z?S3k^ck9mnL&aQq{Q@o+KaB9yg#Z0{N=gjFVEy{_&B|#0A{lnXb^v}!Bo0evx^S2! z(a;gnj5$}W)Jr;MppX=1{y~9la;3si{l&3$|yYFS|<`1c;D5rD3 zA)J0{Z%Vg)ixjFgSY0Rz7+M`|d-kJqn~hAn_$qR;l4z5i%;2HJc;U^3+KhyJ z>Yxxp&+eUh{i%O2?Yis8>DZ3zr%ho%pHH}b&J2>$(us~tVCF41U|2Od6=@(0fq@gD z*VCj^Re*mJE)W4-1ERa zXi~+YM03`;lem5U{aiQYS|VbSm@sY(=Us9scQ1aD9Xo%fuB3p0g9k8t#6YU^zCjob zsM3ejLr|QdXoiajM>JPldM=9=-b+&JcBCezam_g+NJ>d&{vCIa9q-^sNf{1RC8NXba&%=0hc-Y4Fs zq^OWnyXDYxzyO|n{dsn5|AwOne)F?hXShNAT6s6iyyj& z#g9C}<}cTgoR~6`33e2D6TJw%0s;dZ*{(5*MmzVIv~`n985zk#e+wv3^t_9Qng287_$f&F>%>1UXJ z(~YF2=W_dv*E4$j5T;x)nN}HD96E5AxpQtLIXMD{qVWE^?^BY0fQqAsXxFPR*%{d! z$@?0iXb2^oOE0^ag%3Z*_nY3w84|)Z*IdoV@4ZQBNg);W8tpr_AtE9aL-(Pm&J#^H z|NT5=X_xEj>To*$gSM@3bVEpgPC)as9kFf7*p9FV1x138CP>tTnZr>P(x0M9O6jlp zYo_8<@n>0-!mLkgfk0^`#g~GUq+~MNkyiWWEdn}2i(_oBF}uD0DgBz@;`fMXt*fiU zFbtZSJoqEMf8~lB|4BdpTRsX33P?{+|F5oXq5qpCq%~S>jo`0Nre`q*8f7H~l$2D{ zs41joq>&aAK}qouN=vKILnFw{%pxW%6mNA61;xdr=j0G7YRN0CAT&0Gq;MB?HDweO z9HmiL36F`UReBnw`3I<|szX;?xFaKJo820R)<|K&LCPu{35kj&J0}}oZ81j*3TW`D zghWJ>+o~0Y*T<2(0@B;&;Gltu(jv;6+_cF|p|Z4)qT*6?si1^Jkd>85bf}Z!{QVSF z)nSB0(Jng+x7I-Z(GqIvJm7GWl9felL^uw^OkpE!mpDTr6c1&k#S|4);MKtu8BJ#E z)`ZD=@(c2)uJM7Q5)~CoW>z|~se*%tOr8^xlSqqJ$U9O6 zscgg@7EN|mCZR6Vq1jx-bacZ*-l4-(SJfk(p~R=AlO7+9)T%jfu!wq(K}>u+>2YrI z3ks;IsYg1)36D)6J3SfMRL%Ya1vD5638|@M#Ya~`7K;%a~}Q{R*p6;fPLLxTn(A>pK@XAmE%P*Pe*aY+>p zcLZtaS;RzyQd?0#VYQd^>}*1$hr{~{h>3|MJ|Pax+eBX8A*vg^DB+Q`%}k}XypWQz zI&>*fL&M0(%pxXK<>-+k94)U!hKA9xRR&J!BmZy#bqyX=my7hQR>Zh{{Jdu`DY;#U zbVFrT4fTzZ%(OVlOA9F~sz8?l5fVmLZX04$owAZb3Jc4SA>riYw#J3V(foX>Ydt8g z5Hho~i3)X_nkPd;_g0gCw2YdXCKN>w5*0^wMk=1#G7c10l9`@@Vltw zBPBkck3D<#keQiz!gIE7-_D>xW*|gaSsBZgEn~`*DHaHn&9rO6KbIXdxmmz3P`qoyYqm>d!N;J!f-`<@E8;wmT0L$;o0&j*0B#XDRU_MLKuc2e~+D%6<|+u^MsX% zS15Mv2ox&`v9u;f1-oXdFt3+ZEeT;pP$__rI(ALn;3NoUb%{XRDn3kCccr<1lb@`l z}d?Frn^h0UMIvyQMF=L6T7362{%xc@K>4Ncbkt0RRVIXR8=)MT(@#YA8-_WR}p zMbMcOwBAf+_IbzV)E8D?gD0Ng`mzDp*s+KKx!4smq_qf`8U<--GMe90T79+`G_#Z# zmJgcGulX?aCJyaCNNrt{snu1$XGmg_Qpn9nML`DjGdO0@;@tvh=F@ceM~;1kUAILA ztdwjRiVum3VrgE2WvQTVdxjwy$=fSGwO z&59>Ze~ZDR(jH}jjDvyt9SVkpCW4pEz}ON&*Vx~i=Ld~Xr2ieUpI^WXXqo%{Z9_0f zXjUiN;#67@p22mr1IeJRchi!E@Q)RNznY2Akwz&~CtpnJpo^G!!xe;MkHEm#w(rL= zdf42zMQF3&04(Dst_Si(4~ed6$F8zAcQr!EWwT`{GrT4NkQwZ<62u!6l5Ypx8)A@H26MErJz8X+ydY-6vj zp;VhARjaH=^R~c#w``#4hc5np+w-t#;y#nOw2^s-bHV)!{lGuu4*tq&b@zQK#*vIz%S5TI~#o69|RJ< z|Ni@=r>D1o!2i!F7zFzB1pZdh!Tx(-O+*Aw0s=cyDgfN1|7}u&0GWR`D{LSV-1xEW z+D8_c^Dm^oHPH5 zE{+^6#t^3eoNh?E^yp1)dI|_}Lhb_mD@dIF<@VUPxn>b}!kmNyW9WFE?F9vaAAp+c zTHtve*Pr7+k##RKm9Lf5!UBLn&@uQ~m`^`=%VGP72Kw7N+JX!Ri z|J>u+4er^$9#eKp$HK?sqZ|qPWWCE$B8cSttELm0(#8siI@wr00iWX7Cx2p2|M$q; z(FAl;5>=~V$IgSqrR0+K|JXb4I4O$lZ$H)DGqZWwU3SSCiITH`C@6?X6cdVqf&oQD zMFc@WxqyI56a-NL0~k>em8e$~^{QkAlpt{lo5Q5;s`roX2}>}%*KqyG@iXo)U0pex zI_aD4MhZ8UGH?ljz(fdz6fP_WmBCPc6fT=NR-iligyH*e8168np~DnLtwGx^Pa}k^ zZdWG??IYY1MI79FlwAjMX@7BRV%!1^oser!c$G!nLr#})M%2G0Z5wTIV~DGXVjywQ zObp?K^Vh;_NkpZ!liLiVZn&e$i)0^aMHmT5i~6O6Gg9P2``7pqmqZhfX6~c_6}Ij^ zOWn@K?}Z(D{;Kwzr++FLr`rzv9U_K@q0LlCLKrP8J2Q2JLR*N9<{|Oe5+Q8-%HMbC z2^>5JVq)Uxd-XLSL>O5%w9XA>~MZ(XY#|0Skws=hRFL3eSbEoNeTO@5NzRTY+*^o(BFToe-(u~K@t<|L+#%LgBP=Zj&?1a&Waf*=om-T=tVH-TLA2gk0LUQzpvk_22dQ4G z7A~P2JZvqp1OSi->7yt&ho7<}buOsv$dxI{)0Ma)MXV?z5fsnH2>u1@=#0(*ge0W4 zmkx%zP7oWv$4$g-M`1bg|Hv+-qW=Cv_J#BGmy;coz=6>EJ1~IYEO}*NnSOF|@{xq> z%+5~sq732rD!@-xb|w!z_$Vh%9^v~vTNyiH1_i}|-?^U7_9ZklU3Wr2gf=osL?Rig zr^&}3f5O-?kD*l5hW&RV5#fJ?5GWbI3KnoGCz~+HpU|Ao**yjNylKq!t~~21}(e+L1At#T2ONI*l|u} z?qc};_jCAUfIhwYa!Jeje70`4?)p3c03ZNKL_t&)Q>V_QMY~R1+2bnGQW8r@-jtLG z8AKz9hP0hTgzYw>l(g}tLvu&UsEexYSYj!g*$65PDeXQs13`R2>98UyqC!_13LQ)6 zNHoX!#bF|qva!^W_61qVFr#W(_Fg3&`J_@74!;Umn1N%Azke8QT3*Sq>^w|_gGX&) zDGSrVO}3Qa(BALqdT|GajeL{><;(!-;Ce?{v{+8tZKoG76?VOaZ8l?XFoyH_Yu1o$ z`eKJOGJQvRVg6M5^ty`6I(ML3*DDx4d^Ecb9LB=Or|aJ1+Wx~REb>us>M#>V-bcSd z!#J8#~D@8g3urCI|O?$+YQDQmB+8&pVSMM~x%CS73YP z1=+RhN2H}FD#~Z?{zI6i{C(Z~m9TALqSPG9kwJ!3V~S|TL$ZJW0k&-3`nMX7Um_uc z?B4PzQ=ghiF@!A&!461!u1(L9HmH5}$xQYgJc^}kJleBSgq=_z^Eq*3H;+x4NnSzm z+3TbPf+BW&y@7|uKS@CVG~>6*f-R6<4(;8>qmPWDcds7YK5ziGc!4Q^dvqlWcM3tzd}*S zp0C$&>kZe^t!o#C41buddyfJ^zTLQndj}1qSC8&od&2-;Td|HJ6c%2NAK1#M2kzsl ztFGeuTkhof*VZDX%a)l5+XfG-h_5%i$DscGx#s%*JiqL%@EX*F6RHLiM1WJ7`?;xS zHzrMy=}=|;~UeVH_MK7|1jg^o)pHh;dB-dEkgoabKQ$88(Ay3aLy z^5t%hAKb$ocihdx6Q&WAe)jMD5BCkanV!9`=GNikIdCH1nKmUa(0@KT7a1*xz{@+Y zzR8M}YZ>61M=g@) zc{)#jA{n-%Mmgaj{w%UUnG_a!$uB5I0;N(?iTAiD$j_#r*l))POHIM!(viUeva)mV znHrifh)*mM`@-^q`MkCNtcQL%I)zM?|%i%bGaQMyzziE%E9i;Bq0F92bX zkdj71jBQvgB`9Sflx?48Xn+~OA1o#(&xfTHiAhPsC&Z(IK60~8;xh%p{bXO5*btlbc(JL?@wC3W>1>xp}z=J(g05 zZiPgz6L0QOzT5pH`+hn?MuJYc zvKb&PaPrmwo+`FeEroHrawKKf6bgvT6(I}zx;DJL4~6(3mJO-?>Agv zqNJDU6CPvo^aYfzRt*)*!IA=@34-1N_8&OFsjOU7&3Kd$h`2Zc0WX-v2oyoXjaN#1 zmPM3BpHqMUB`GeWK(-hO8#?|i(T z=9OJ^x~L`DDuYHB*5<<%ZxaY6aC6T_*p6xzx+>>0olioaN@{8PI_IeUHd3nQX1D?UKgop1Omlm`%MDU zqA2SpHf;EmUbhxfJvqqdAAe5i3xnhoo@7w}>-k}S9@X1);K1hXpu72BV3s1P`2f-^ zV(OF6(SOKLnzn933?{CO1g1=&olq;6lgamFLFo*;#z{K&7kW{t;`T1ThY|xAc zM%+i?4_|Zh?L#QnuoZ#ad`gw8$>aYTkI-YtJh+d!PcNoo*;MYmxf7GejAZ)>owRb* z8F+m+YL|=Qk#SQ%bKx@~wPG#Cj~Z;pSrY=3752B&fP(xJ%$+)k{U>}Bm>_kH$QHO^{j-Y%JESx=;^`Cx2N_sNe_8cW9AqAm=e7^Pr=FOW&Lbhb2YEO^b#Mg+el18JO@sij2ksQ51$QI*ITY7&jh0V6~D7UG<0|m&>`iXbm`Lbb}yKxZ>IR`>& zpv4fMUYQ=(T+i_n$2n2(Z}#rljU-?Pe~!su`Kop7`Qiiax$Q1Ceene+wij~jgy4Z$ z6M68au5@bG5zF!+4Cz>(S-8zCR)6>*CkuRBb6t1hJwfK}{hrS^e#0$&dJyAM2w{Y6 z*mO;D{q5KB@s}I9@Af;W-sn;W-+dR!E{!QOW{~aED4!OGW+>9iRpOefyVK*!PJka% zCJ>WYiI?7amkO!zxJ@s$8aAdwuAifsr^q?+KA(T}6+JGiO8{uru@A4l_8b|SpRMbc zAvA?Blzr(GE`${5noewd3b9Fo&RsgwqjxVVq{U#ft(q;({|ih46(EJZ>k9;hMFkwo zHz`-CI_{8trij54=b>!8hd@>~Znt3j)-TBQ>r9+HiR4%}Qi0H1Af!%s5CRqSvuM^+#FVMYq$!V*q)V*g6AXLk3EKC#gWGTEMlk0mdSBh2<{d7fnl4F7 zDZ|7`Q%TZt7(8SwyZ2{OR@13ks~(R}8A*x;vE~s@oj5_?n@4ipRaX#i6*6)3Fk;ec zGHLQyT>fJ2x#Mm={dg5^F1-X9^ZNT6Xi_$w zfT=U-sp-VVCz0T>A+m&UHgzSDrk~sbAH8oH!p&EAWcA9AcxdEEZn(A;)91ZJQiaAm zG5HZJ|8WN2`7obs+D5M?8Lawn4P$1^r*8F1EPnANRY4%sFU6=boVtvt!>ey7lhP#?^N+{QmJA z%=YojjJwD=v6l~4z0dfkpQA#Vbf(XGfoap{u=s`PtY7^u8EK_$M+qS)I+e}LNl()C z=Am43T^~FuKz8OHW$z5iorMD&lNY{&9!}dQE=)cw+tLY zw|39#mk30H5=aYW`7wiDa`W>DYHsqCflCwIdFP$fZ{5n)VmS7=x)P4V zj)4)Qk(QE-ufU7$jwdc58HJ=llO~wBK}sH*K9zCf9%I~nckKQLs_y`xhpDqGcq~ux@pB?a!o2tqg<_gC{ngWLG|=OC^w- z=cSBWqI3h@rQuRRgy~00Fx)Z3#<-BVMI70`m-d4O5tEomQi7Ydjp}f4-yWKGyaeS0 zl#|L1T#WGX!-1dpXyayf_w0kNy!e9>w=j`P!_s5%#K)89apP8$kV>Hx!mSffE|ez) zJtl^F)hZzJj*^p|$*uz@x%>9v#3#lhVq7$>SChRz9_K_x08dO3spZOJ#Kz$92wciX zZq{KAW}afg)OpN!dMa+|r$U7qXlAg)CZPlNGgq?Agg zZ_mrQdf+3Bo;r*4^i+;-{hV*N?%;-j!-y3{C@H8_|3VCRJeA5NI%-P$V9UwQA^T)5 z?K)k7D=wBe1qXAFp}XU#)2udet{`>mlqJa>E)Ab0ZH=|& zMsw+CmWioQaTmWQ^-DY5a9}W8AHUS*RtoVFsRY8 z9kK6jVCe04adr0|^zG3Kzu_h*VlZ@r1UD4q9bnQE^VzcHTcq@pb-a*3aS)4YzT$jNWuBr+>x*dJ?qW85vx9;Y*d`%T z*?guD2wgbNRtB}})+JWASh;K&>4j}Le5!~Glt4)r3Gp5ZP95a)Z}(HJP9x%6?~#`1 z;;JjJBH;B?vteV5P?UlY?w_>P-k+@egm+eNWYEyNS@FgjEM2mM2Z!ImyonR|;Y5JP zCXOQ~w}1ynJxJy1Ynk)h+w3}UjP#5|r1uzW-g}44x>cxNBAPXC&ATbD z02&E#@uVijvu)?stoi73>Q+c0E;XG}2?p=HynwjwttjyNNl`(9fjqWu+sZA2ZY8mF zX=XqFG2d?AMXN^D!Y)_#=iGM1e-sHqF=7ogcOoP28_d$zm(!?4eQH*#MsdL@=FWVE z3bkufrS=8v{x%!UlS1qE7qej2B!)fw1o6o!bh)e*iMkfK)c>iiI8WyZjL_-zr(p*x zaK*%un3TZ2J>Q|z7JH1q&BFgCosDNp=s468SO!lAxb5*MFDxysd; z^4xRO%<$L~LDPuWEZc)n5S9eS#>F8F!I7W#Q>9WGU=S0VM9}Y}AiJ1yW!>Zz6jA68 zkerwh4h`Y#l1NND#IO-d&~GzKn(hLj;nHkXnyw%&&P9yJ;Mn1VRIiYX&mZ7qZULU8 z6#U*igbdhzi^9P6jC4XnYc3MYROacKQ`!05E}owLJi5rHRr@w}Xa*%g`q=vQXT0*} zD&BniZOW&5=ylCd6gryAji!Q_riqAi6PKJ!TyiPq&YMTgj97F{AvA+{PmE)Uq=#h3 z=t;?3(dBYJ+wd{hb?Zn{Tnqpk)@-EEXHlbaS;YQBl&e&o@iU+1o#&rn!pMhtYT*l% zP4(cxKIH#YbKLXvn@9>5MqC-jKQR$)%wtS_bR>lZUec;vNP1cVmX&X-^<)sVIHa<0 zQ-mfoFg%z-L&L}88hlewD{>xm`=M(%Qo{PHlL36z8HD#j7 zAW~`s5$H(TUv>#or;K31vb9Wm@;{vP!UdWKp(WG#imtr-(MG1sT*{K!kCS(3AB&bP z;`w>ANiJQ1*^3r&LB$M55*dkea(MqwJpAxf+H~s8*oouGh{@-Q^gAFej5I zCr#nIT|W}^#L(f2Yq_|6%P2eAP~HE022eOmzCs6~(d+uY6nG1Ha^g6Oy#W+1YF*fr z@sHh2a!Nc>)0}&CEDc+}Dv2hvKTQ&7 zNejahN6%}oW8l!SqKlG%9VYU4-pB<}zIL?sp@%-1#8o5+#L&K30CUhh_KP zLx$UfFY^H3Zr@GS>Qy-M!&Y|eIYq-Jt(Y@yDvypC#buZE;`s3_`rOnDB_tX_bm_=% zv`~N$Ct`tv_yHEW3KF{0N!++%(;0BhWsDqh4;hIjM~)n1)AoG~9(f_jRpO~!p)`-* zH=LUXT*o(Cc2g*lD3wu%-d#E{b>v_Q9~@77N_mo!Jap^ahVU*SaBlQ53>_q!#zy(3xBBxr@aw zE~j#Xi)mT6Hal0YK-V3_3dd&0G9f9W97p$WXZhmglq;Rie%iB{ZQFN{nqGr| z((x+~WlE=0bYwGcyt0%smCKTtkc2lsi%lCoqCvw31WU09R$!3(nOHJ&@qp3$Ji;jgv}@h zg8`)J+$4pCR2rI*!r+IV;EsnTBZP)j5LDpOg4{V`40nzgPf#ctSM0%wynI{g7|5pc zl|ATt$4D~w|3KTzdXrYBESBz}&1F6LW_wS(ni~U)N2kr=(di3tVpJiOmtdd}pVA4% z0R=|b%D>Z+t!pF{zg+8;h@!j@-hlZenUa$_4pJ9-18sEp+bA0G{T{YPU6E2Yphjhc1p z(Yj@8wr$Uvl}Sezf~qy^(5z`wwr$;tL}$dP(KN1K z8@J&iH7%WDQ_`w=bK*QYCOR#fH=_MTEjV=K1Uq+pM_jCj=FJ-;l!a~>w7a+ihOURz zr6Coi{Z~<3Y*DppHL8>^jWjKMQqiu{Ql&CK9XLqKmMyucT|0!7eEaQYii?YB z*}M^n@g4$}PMeEblbRH3OT08e>x(WTExjyTw`}2LRu)Z~x8SNPI^)tLTek0{)kT-` z!2S1=lHeieD<(A~gSz$VA^@*n(X?q3DwRp6Ld8mK`r-?$K#=B58WFIdUc)AoO-(}+ zk`}F6Q#zv@o4?&mm8#VlHEJZ~Gg2vAwj5?qQYtltisj2X>TnxjK_SV_&EkU(H?Vcb z54332nm)aHk&=`^%_^1oX7e@*d;u=Iyek*CZOhK>+t{{!CoNjGq|+tssamBX)v8os z%a(2UgBC4XwWfFXZYXK;?Y14{n)<0efwdiW?Q=^0cgR~F-}OU;g(_H))j z5&N=`0_p#E&4xm4gy!>a%O_NWbHC-JP);4gF46q#Tfa96A+RiqtgI}OlatSy=ER8; zRH;%0fa2m}cJACsi{{PIG=UHXI8q-QgTwBBO^Zbc-5x2;KnO5|v~AloHwYaeK$DQ4 zeS+I=yp|CUJ;KacGnqAW22VXTi#)GMhf6L-SD}5xi54duCQS%5B?+NV2q8Ik=qE1e zcm@BOI-NxeU!>Xv7jpM~_fV@!IW#l}mB+H>)|#8}h9LsvWF6%CYx**3^cZH$n!}74 z&oE=wLj0D&B^_GZ?2Th;p&@W1kZ2gfsev$@a6iIMr$EyLXtowc6T&ffu=`6X+k#gQ z!)h3I|DZ4g2;oKvBNDGxh0vgM(6sQ>F|Yvwv@mMSU&8Enrl7MtScLL?p$TJy7z9RgV2pG!#+Lvd}ewg@sF;9ym3+ zKThxSvmM=Mn6C3{#_HTDqVqdj`DYueGwW}UmOv`gmRdUiZ3;W6EGP`&;6E!ITTkiW zr=FdWD%r;+%RM_obgupiQPle(^8f)(*k9-EkQ(r`K0YIxfb+$5_KJt|j^I9@UWZ?# za0NmEg6(>p73S(^@~{zmq9OXkXoS@2R1OvtVbYLIFJ`<#i^wOotC|edok7x$gd-qdV6a?W$ zDIFm+GRl;pLisXho1te?)EGziNu)nyR6-H;`M*Iw{qz&dmM!Czzz=o_@~AS{JC;Yd!{1Nw(t*O)8*ZjTI>pFzD8ArU>(PCKmB;$wMfon{7kcs0V>|Klm79Vsj-{Ecsx9On=zW#bB$En69cJM=3kffSHm zSZL4RpXHUJ=d(rm@|92_#0(|y`HK1F`Cv0=6)IFkDO>ucoXd%63W^JhenlR?hE&ww z|62?oKpikx<)j9JIfx|2N zmaLQ@s2Lc_LI~Xn`vHXHhDt*T%lWrq+bRkL(O!Q@M;&mkLhW3Y6bOx^NNazikS+S#&s|EQ1Z2+CkXX)TOh4fb3tmYo6=uNx8?rTbq4}$#8XuB> zhIm5ZI2(o9Y_9{&QI&gNQ{|0VqvNnlo17O%egDsi!~C>d!-n5A*ltI}au1)(dV z<#dBV2n|SuE|St_dKH>;N3r45q_E*Eb*KB3IM+IkY>1)#!alUMaJZMqA+8+gNlK&# zg|6FU6FT_qEOiHdGb9DH!q?!l)+XF1T2!Ba6w%Cn=zGL-`j4RBbapBDEjT0R%3BCQ zW@aWC85t$B{|!u3zLL)4tEyelSxNj2haqwU!Uw!o> zy?b{-*U!Sqho3H)u0*YC5B z9XfP~H{N)I0Rsm7F8Te{6k-Ziu3Y(7SLHnY$y6d(^q+gsM^qaT2%hL8H}u^?1yAwv z(v`I6+>`1R%7pMDqS8ikivEq$(w*@}IGL?pQRK7f^G|4*UX#`h!6QV896&m^^vK3$ z3j_oLqvVDdRl10N9}__lyZ3z0s`o#mZ{IE`$HVT7{s{-7HLwo~8|PCwcoQnD%9B4+ zX32gyn=NJJTUaKA0@kkn2nAf;xeH#ImDq-7yA4XH)<$l2O$_gU1NKoM`f zxr*wI+tH|I6`Nr?XWOIm^b-tb^TzA%(WlRKXY`hBG`WgFgRdn9g%*~1pKA|@8W-#}5b&O2+1u;6sB>?smkx!{ zv1d6rM*jE_s(_UrtfoTMRy3$n0hb8HNQ{Qd5|Q;I&Ne5014I9dE%+5_o%ngWuA{k5 zUz|Tzlc*Kod<|>IBTt-^=ZY2i%cAG-%u~+TM~(Bj_P-DrXZ!*oa~GoQZ9}`ke|IYU z_G{Fc@BjB>AD!3lL7Ju^rNl6dh!p&H%KNV(r4)u?{Bpwc^nZ$+karG)pwu646QHmU zMHK}6fW!&a9RAJTj{Kl}fQ||l@%HOWIhB(|09*Zu41n^3w2*)ulqCq#3(AU;H3UJK zC~24DS70g2&fD^Xl9&jB0K#UkWaQ)rB6nn^EEEAC5H3UF{_6(5V9D}D#CUTvHQo2&ISoq z5lY$5?a0l3=b4?Cr2?Re0g2`0z4raL`SRauky7FVOe9D@Sa!@l3&$}-nf7=9UhMD| z$dJoHsFR98d4XU!KCRtTc0B^he%HbT6;Y#Eq2p7TnAjfN3J}tdP<}KSQojL0Qe1eF zw_bmVyuzYzJA#h%6{l{&&{R|*rB`TTT1clKG|fT^K>#}qmKQL?{c9H*K$%5I8N_m0 zVoHfJi&*{68~k+Wu&uzC_6VX(Ea}V-r9c*g=>_S`f1x1>I#Q&wNrDtg7P0odH`%s* zJAP%iPYUe5RY7~s0VXC;Y>%^&D5u>L&^<8>zVAM|_vqxz$$-5U!li^hmJ{bOG>G9@ zfD{_O;ym7cZ5g@QMfMsLU<%NbJ!&RkDFZ2etpDIW_8mNG_qDQ6n9l0QVPd3X)?mkV zbY`hDRsp2bqI2#}DyrVmT#PD_1Sx(dk0{c09ifScx-=>;W%^Ol4BG=M%R)TE(?+gR zc3VSxlT=nXl^Is?+k0Yk1455NW>a<=XZ1>nloHFb?0Tq3?}c*wtF=An>8~LzBms>6 z{GlWO>Bm=eipR%K;KGItXxh9bZ@#;MysQ&+Xx4yd7cC~>D`v{1NsN1ZI+hvW&`&?o z^NMS!U!y7O*RSW);k^tRa2t*4*XN4MujHGZ2e2$3uPt6ky#_5QSH2#TCQjn@#q(*@ zpea>r)TCjPM!fpQ`yiY@Q4J~lxVDw6S#V2@b z=F`+`+?x9Jo3ZBOHGKW`m$YkhG1aP6q)F2Y8990c?K)h{1vP7N|L{@d`GP26vg7NG zT-K!C%bnHEU9(N+kx|aw|tp6)=Csll19vCAr=JN;7$M%vk0>|0Y?P z$9d@f`>9*M9$hZ$%9r16BPcZ%%zm1Bb?Z^NWBWDTuG|1Y;i> zLA7eNsa3l^>(_nAiQ`8YI_yDe*S>%&y7gr9&RrnAEPZhyjq5d~YSpS-+^#L-$B(0V ztCrNdpeECwnu*VpC>7wf#fxa#ycrGa*JI|)`FM*ZLIw!;oqOGC+Eab zhTr!fwJ)f}WtVm3KbvfIpw(#}9Mp-~qC7a*;w&n3u(o z1BW<#B$EPf&@t@*;b6~3q<6O5t)$F7>W~k85vR%fR774UWD#rEtYqxOY51%Nb7x;P z9ma(y$z+Lsa`I58%M_#Lf((G=BM`Kia-k`tmCwre-sSao*Vq@5NHv{2PnS$abLNrj zZ^<^>Y}B5un^?T~c@Actz!VXlI(l|S%Zim%#LCweGyRDt$;`^b5(4FTFa?W`vwG!9 z=05u}0aGHw40;K!^jA@sX^w8Kvf=tH6$$bb(izz{

3a2&`(S5*bVKnXo;ePC;T zf}jZJsR_+y^i?rR*etJ!bI}xGaSBRkPKgR-1?>=#N})6zB{U~IjpFptIZyvQGNKKP z|BRb}1cc0I>D(vydQUD(mcLHs{@pw_?HL-^pUi?67xM6!8Thh~vVP-#n6=;q^w=WO zD^zC0!uhnUU4v9Bi=np;pk{}w8TrU4K3MS<)1I2o3r`Pc&+a{3+UrK{8gwHWt^!_J z_!JfDw&az`53_6Y=R7)X9<7@;p>DNgo|^L<9wVQZmc7lASKguN*c-6UVb5nv1QhF6 zyul}%w(|6IFHk8lhVtcN`25o?RIS;ZSKoM*)gQjYwCS^$yLc&y%E!R|1Ni95?sROF z!H~NK(QD8sx_7L{dn;D+^>+bu71}HnVXsi(XZx3Hnfu&JJTi4A^(v;36ffAcaRYCx z*~Bx8m!SJ{89QnuT1r_uH?7Y1J9aU9*-9#>3LYCZmL;#Pp#S9^cy;+w_8&b?sY)L9 z{kVrN*A8Uf-1)fTl3BUx13vrkb*4W(m-&lkb71cw2HZ7_&OLikCNYj#+rDAo?RPR{ z#Dm1dyV&;SMy5XTBok*YASEuqz4zQpjfSmhRWX5_yaHZ$^9?c*5=heA+B*eud zk!YG9zb}h#cI;=|v=?dLxFQuwn@oFh8t&98e6(&2@4o*&Gp9dE%jYJr|L|ctU2!!- z@4kU03!Y`!;+I+U=IfYQdl^1zJZ&!TLc+;CELr+8k3BVua`9dspR$lj)oRhHSv<-U z&$9R5rCwQ`w8Ubj{c9R}LIqZ@Uc(0;uIA~d=F;TFxwthADHVFiD_&WAv2G>vm%PQJ zPtW0kGKrK*cC-4!_xa%Soh)4XDl-2RBOZ7Nk(9#4wKCYTa}UpcxRDC+K^}i}B5$u+ z$KCx}5TBaL6ALEL<)S8}#}u&Qr58x9P?v?vpCCmPviY->%zb`26J|e4MhuL4coHtH zfEx$)L>YPsX-kA`>4?V@&#*D$7}&2D>9NIpx_UVePkxq}Gv`pYl$&XfPh~~9Qe1b_ zO&rbg^7O2k)T~~X7v|67-Ul9K$+J&j1oN?k#?ixv7<&64I`kXDgsHO-0WWc}F;QjO zmm;$`m!w(zIG4sfjUoTn3L%d4fq=fLGsM&r7eq zPWvXeVi_JDpFNM>9UGDwo6YARufr0tnCN)W&`b+W74q@t|3-K!u;J6$SkfdTEd{ey z9s2Y!F!Tt^9_k$t5{(HF_3zNbl3&H?&wmv~?}-wHpUi#V^3X%0nX;%p@xg<1yXFpV z8ul2Y2X|!tlhc{?%nRh2(EFyrJao?>#@ux)>of?G?Pb;YWr(I0Bb$TjPc1lkK7*K{+;h zj-<0>xSxSb#8j{lz&v|MoXjY0{1gWizmm^F&yFdb&zmSYDo= zJ%a-U9xlJ3KWS;nc8o<4q#*YwPd+(|1BFTS8+ap$#{Vx)ZzNE3Xuu>O{e`^0@_k~` zt8z()_81{NU}cAiI(F~?D?eCGcA=LJmt9Wt#tqT2@aCW7t+zko(D59awrWj>4()I& z6Dv@}yQ|*k`|tKqzfp58>DZAtkAV#O_+DBd_wHAbKrGl;~R2#vD{^`FsoAyZ5ANi$j8@*FsHgq>OeIoXBuxVAUdQxr{_9B1pUuN}!K z5b_j8f{^V0b{kEbwBh28?MRk>bdkl<#b3~*V^5m5Y>sZ`az&^1y!+l7E@^ZpxHQUE zsY=}{v0UA)Gany5N!hAhsZymnJ9i%-!&eFw^inn>fw$j!i{p8Dyz<7I$l^S#_(}wd zZCjy=RjX6EN;wixNC9yPNu;NzwcJ1Z%TW>{LMI6u0qs@;8Xj-;D@remk zs#2M%sj0Xv#eh2pI^*py(3*~>#Zs+CeX3PYgn~V+dTSX!7Nqd*@)s#AD8ikPh&Sj* z>26XoDp09<4LW!1$ZN}9p<1mPr0YqPPfy@PPBtr7e9VOn+i*#{cEpJ+F70qJAHB1J zPA&Q)j5v~0N>e&bq7`KE&Kt|wmzT_{*OyUPRE&sEA>cRh#2Dxyt%(Mh0d{@6g$|eZ z;Gzy~Nx_Ff7XSIr7qstw0}Y!rBhJdE`{iv|v*r_8*X)O`8&s-Pk$ROpbiTALKO8=Z z1Wc(&NQ$Lm=|qH8gp___OQlk|YDLlw9~+iG%SD%TqDA}Gq^cmp2J~goYcFu+ja{+O zog2S>$c4SM9q(GpRKzF7Q?7I}9@EFhHEU?su_x^>ZBHV8Zn?T6Z-2Ro?l<;Fk4dCb zrK;4bUzO`_>_gW9Q#h653x|XFVc!8P;b!o_{v^i55gln#prbhloF_hs7HwMc#M2XT z=^A(3dJFiy1kp%MODChW2RB}d3$j@-e*tUOzE8H-MUA>GK-V!`9uiBXl3F^67*%M) zV@cuswcQbvD~=0lR%QN{X-uCYxbuPGSZ+5p>NTZmohArPkBT0n9B*S=g()oyG!0D% zJAy#y0G83}KbwjEZ9844Kp!X@uR4g1sp$yaL%9m647~Lg+Fsn6Bm2K+=_{{Or$t9* z&zVkAVgj!(Th70~-OY-1pO8_dDoJUnVHKPvKu87BXR9%_B!sY4)&T`>ArZ<1dSZ-k^^AzNSN2Lhlahgm;e6{AEf z7CMG3#?oT(`vR6osq+a^1_PMR7fzHG8=hVG zA|I^(luthUg5}F!piFu)0?XbzLN+Maw@?d#&@^Ini54he{OE@{o?FE8FD>K#2Oh-G zU7$=966M&lX{W_a6ozdl6bSg8JD>&lu#^ld?{oy3Qdk0%uyE-X(hA^l8R$SD5VQ{` z&A?JJgfky0L)cCbnjw&ubR-xWC_9)&FzB(*`HlZ{{S?|-kQRJ?7kC>Py`4d z5qL0MF50%ai1$~2$VclxW$X6uxo^m=cnk;zt*|;tX%Zz&tdMu4gC#75j^%`uK-Wnw zmCS_6Q}}4@dOqFs1s|_pN37d}P#QtgkxLl10k*B=kmy2TSrSi741rK0Vc-u2k-A}@ z^Ol7&P1{q`&`3@z&A*tP1`w)2j(@cDdbA@qc>H>JcdbX&zFE!-|01F)n$rb@Tt!D)6g@VH#~e12O1Boy92 z0Jq1D$IuYMLaNZ%i_^mN2;4Cq1mKr|&~O=Uf`K4X*=nGGDbZcF&$vLMyWA*Kg0v+P zn!^m(W1}#Ge#cfQqQZ(UPe-8XvD`U)G%HuW$@iPT;<`S)@cO+-T}K5?JKT&2vh;-o ze1Gr+&%W?7GNgVLi`;uHIF(^Im)Hwcb}O+O%oM7qdU2R@GGcUEhxt zYd53CuuuexwwVPq=0IN%C0Le;%#UHZp?EQq#r8;*E zxtjw8MMNUUnf31Lv}@Cz?5r%ZtJY@3=m&82nDoLL`GsX{qgpVEPkzg$XGV!ZIgL|Qg(L~8j=>gKfLx8Hwf&a4k< z)20$w-PW8VQvqEYtk-9wKqJ*ieHn-O>2 zL+;T+qQysfYx?UnX_`Z3W(9ioyn@whHxU)vSkkp|;gRBeo|yO`wQAI(O^det@Z(Q^ zeFXXsE`7@He-@r^eTC&etfX>QCf&PqLOY>Si>(+Xbl;wxY~5SHy%Qhi?%_i?wMi|e zz4;ECwrpqNw?FXAbI)_v$XmF5U?1Lk?_-YVAK|&Do}~Za!Q6Q3EsPm6g1NJ2A>J{* zoHLg}!zVCs;H``rGKd+^J<6V)zwypzUo-svr?~z0J9zey(af3k7Ta?VFzLxx>Dv7g z?i?|UNe_T?b=D$ zitzSpuXEU|!uzkk#MYH_`EvgE5Kbp8DVZO?U(L_!e#281Ic;)yYsLrc*}ae41A8gR z-;Zq@p9l+Ixl$IIkZ(XySXvRrLn)6)aS4RdQQ;8bBty!sl#OMCLdIgGlIeIxTehs6!;DYArrU+rk)E7Juk*SvckUc^?b^qoydxAJKa4`~ zltw8x&d=GRQ61L&w1S`3tl@`sztZOP_H6xqBVW$@hQmjXvSZ6;k|YMMi=!Mv>x8gn z^Do?g@4Xxf-W>+f@RkISf%mQI*rwr<@-OeY2jKwtx@lAX=!AC|Fx{YEx#-9h&Y zE@H|2&-rTBY!-d@9j|@xHSIfeBrJs#AI)RYqJ^woyMZ^Sf54e%b|kZW*yLAPG-+I) zl#uY)V^8w)x(zH_wv1vQ2saQBk60wenxB6qDI=5KmtV%-?Z0v4coF3?Qu*}lH~4Ag z8V>B)O~mzZ(kfzwlLVY0cq1+nE2&H>}^hg@Z?q z6HVp001BWNkletA|##g~5 z=szxvnl-Jlw)SN*_|qC&p?b}2O*JOQR-D5J%yPP`_CYQ{Q`qn{Vr9 z<}PK?rtPV`@Z2LLg%m^YxSQPL`K(*LhNJlrCOq&64@|s|!o$0HXv_o}HfzC)Q=X$J ze?Nbj@G#qd-_GRwAEaF68a(yvbKH67a4J=-NGRk`p<*WYOc=wUt9tSF8?W>8#-04S zdO7!we}E>ZpTlF1J;a_Z8yI@aZR|RfkEbkLJVFXqFaCz7o|#I|t8U_nWvuzIta}QIeZf#tWs8+icNAk8I(WC4= zaFFZd8vX*`MB{V&w3mT8sO|wznA$~t_fQ74eQLn)%IF=^0VhG29 zgZZw{Wpq;h-Ng!&zCR@}#6MY4PCEUEk7LmFmviTBgXq=c0zUlUb9Vl=m&uPk!@!&S z(x^ov#*7`qtdBk>;-+%*ErWRTsr%`D`4z0$x{sIMm_c@$%T*Wmg8Mxa{()SUBrF zj^^i+crfOhvN-RGYq+t`MU1+oAD3KsIdi{Vg-S^wIW=ZdIVm`yR8qBtZKdK`X{1r9-+YIIn^)4k%XvIJ=_wjFtPz}S`Iad2u9zF5b%*o0Z|t2sKXE+W&%c1@U;T*o z9lLT{zdj7T=|+YOAH#s*t^-2;mV7-`0_q1T(le!g_WF+Wtk%swC2j|ZlGLpGM9Jn!E3Khr+J(9 zy!OVceDKQioZr0%WAA%}{DLC9q!g0V(+F#ikhmPlJ;c)Qmg7bQPe5?MN+mh$kfKTu z6-GJLxOLdwG_97zHJ9|_%05@IWcex}1IM-qr9_S5?t}=19UReUD;@2mlMLjvYtN{= zhVjtIpdjtjb;PFh9{Mhw20k6wM8%dY6lqE)*XI(!^0>QtcbCB3-vlFM2A z{g2p+c(|d1GRm11rbE|@x$o}Vd1m}bdYyj((`L-0YmW=)cU3oTy1p-W{bdrPCqB=G z=XSzYnowFQVaEc(C?}cZkf7`;T-CQ9OJ~1N*BUK${hb$$((xTdE7r{ zC=>6#gPU&~N$>0WGGO2>q}iF=b9+DLe(^DR$Bvn!L;px!Sq{p{xQBB(bY$@GQDkOUL)jI$y3b{7TRo4S=UvFVA1|bO ztrpxp_&V+#Ih^iYdvc@%s+6z5s_z$Y$z>OFO2_jlpH+o(Iy7egzHO{pwG!72z-P?y z@5Z%j*}Qct8pV+#NBL^bH{|CZLu=Ua`*zl?S&I&$^5YZGKNticF^=Z#X3hGY)NR^< zemCFDg+0z7#r8nEShm^tn5bqKrIM-Duq78>cpmke)W(q*q2zLO?{NX=pK}(K)6>ln zxL9U`=pzoST=+FZZy&*+A$PN8-9~cr@({}+=2}RoBAt3(%q5qdPkPv9>y|C7T)CEl zh~m<#ucJqgv&l*~8zgKCPh315A$oidD}G!-UU7tn@4uhnca0^clG(F+ACZ_FhpsUS zONekv7X7cil&$MlvTf@w7Jk2hZe6<(PO=z3=_%fP`8l$Zj5#}0KAWDsy3($76JvR| zLR76?hpVr=kdCeDb8OF64jwMR^TMPir_=4+o?LrrHxBIhm2JEBG4q3ux$(xESiflp zhYlSiqBW({eC-{r0c zp5n%SH*!&z*6jIhJzI7j#*-uhgwCbke}|o1i5qXdgBJp&@lrtDM z{(D{RiMUbmw0WM^u83D8;zs;_p~aP`L?Zdp`=U$amvujjt4$r3Xiq#H@!Q(uMaN1^ zTkDvJj*06<{BdH&n(Jxt#1qj)B5qV-!FxTwPkSW^J)lIyJsz*S5)tu4i`Eg*5=-c} zK_4>(ceR*)EJbD{`fVN+5s`>^;+58WP`^4NuGaoIGW8e<`hgquGw4q{T1%v)Sk|ps zE&2I}B|ks^uYMLSS`<&8mzO6~rc4p>3gp;Hdk$}tF?Zc0>6Vgl4^5Prvp<*j zXMHYnR&SL8FBq3vf@wi}5!tu?YiUuZqV&AvD#@zaO5XYWTPYS#Hm+YSKdf3ShjRDG zm0eDghNqq-dm?7eJa%xkoZ0SFIj`?9i4^aYVK-bU>B$vj#g2_K@S5JzD7%3y`DK?B zOR+5a@^z_~ktCO1akYH#>1>(#*_ZP6oMn=K?2yEAH_AKHUy`%WK3ghe)s@e`TOs3z zTrKtMG?aO(f01oJ&yh+MOuf&3_gTp(S3#zKy+V#2-zV2!aiLVLT3zPDPjc2N zEo9riL*lxJKmF$t5`}LI>pDh+w z$7JQAdD60Gw*0d8J2~h4i)7|EDUQD3_j$<6BHEpMJ~pvdNd@D{P--zf!J!YDk#N{mmXU|3K@P?m)w8c%zM<5ejv&%?GIP_{8v zC=byt4h|ZH)()0!-fw9!ZDiv|8wTWGRw=EmXt2cC+e8Q{-~Ut@M|RN`SSGU3^Z^GE zP2i5HF}{(Gtx(Dw?S~Y&p2D${2%;Np6?7+MI8jC6D3dj%EU=S(Z$}dy`Q7}l7(H$R zQP)`5G$HIznAhHZlNJqXgB1etZ~|M2O7;B&1xrkuh$v#NhZ8bK!CGs=wh!U0Ou1|o z1ji)d;GspZm2D^kRT!m|aUS=B^gIm~A!0@O3?Fg}Kd#$`rwq@A!sFbFd-LGE<4|G% zAj06kAlaO3nVg{TaK*y2lkij$Camxg@2_G?sOChk0AD|_kX;bn2MU{nPnTS^{+5|FK25ZiY zi4fvhDBG~TSU@!95(<^JyYkz>w0k)2&!WXLffgdB@7N)8UHhy)zCZDQ%;xh)Q&ouc z%xtdceI8>Un!;5VUqZFC5(*+3TVg=6-{(C)<546OpXbn8Y|COq-LI6iu@JX?3{C99PJv8hox zlOub6W9VHEaLom0lkv)XyfghR7R|50@q%Macb`I<;#uYv~*=KL1j>oZgZNBd_#fSQJ7M8Vi&O zjf`0g%AG;EqfPSbiU{B{9*_U%Wa5xQM|6_Z!vD*1yp(F z6^0M$Pve>uSo7;1Dm7?@ML=1Yc-r&-E6R)+|5=_FW8A1Qbic4CZBJ`MMyQb2UYkne z`t@1-<0c-TK8Z%v!qll(g?lI5$K^fGX3`TcGT@#kDW6@D-q&2kTdz)|hMmt#&%aEE zE`71W<>}n9J+D9aC{`Y1p&{7oOdY=kC9gaO_TAed#q?wCPIy?COlT z`3nAW--9%3-JBo3nL~{_^{HGwrIe~NSddQ2zoo<>V*WIs$N=eB0)@S^b$YT z3V2*?6?eBP&8v1fT8j%7#Olg@bDYU4jEmeIVGijN5s zYGTK0-BPBnmG%P_A2OC7)r&HHAm|aw3ZP4j`jixM{76~}h7>`FaN^vcEPvNgrq7l3 zf3b`YsQ8N6e|EML9F&v6?W0GLUb!kCeKwE0LwQ`*yALfI*ToJUr+Ld9s#HuNIkf^! zTQsF^)eICC%1NhU)ofZduSbeQg?=R{)fQ#xt~wfY>&nl=5`wb`H}%_?mNj zb)kCI3=}1_Iinq!4Kr3xw3Y|xfhUVW8^CQjzS;o}S*(T7o^?j|!;xPS6w zio%nqTDd%x>*es~j2S%s#1wYy+(+B?9XR{k9wb=-%uLx?;{QvmB&yYEM5szdk}z|P zcpgewRLCgLedEV*@5D*WoA)iZjGn-$jk2+c^7IQYF#g_0dGeVTxpDXe23>bK4lxGb zHJbc~Co*>21Dx0E3i{q~As(q*am}^l=H_w#y^}b#!#RwYcpkLG*!Apu!pq&Pq)gRN;C3n$P8GP%lreG>yXYj4Qm_RH`qKLAHDVvZ)@l+U3lsS!%2w6R`16qH%GE(k^ps^zBogLVQJSK{JU)EuL-riV!*j$?&jGb+RcFI5YgxH!BU|?s z@YOeSsavBWVKlaQc)`gEF_Z>vg%NE&d&N$ znIXI5iR3?=XAIC_dtX=yH+4UQfSuO+H zpX5}Tg(PtSNu7@#g9`OKI;jkXu|r*YkEEG_=7J;+U>0%+b6@b?B$ zy-NPNE=#S3_zT)m)~@@J_ugN`OH&{9>myh=`QzdFH#Ay>%eUVy;QQ}?rd!uD|LWaF z*;A09zMuddr650_wZG@m=G4}tI7T5hc`(YKCBgrRv`>I5Y^C`o`z_xD+7|Cm2Icv9KEQ>sXo zj_KgeL@Qt7bN=gdoH6bu`9UTgo|NENA6a$TH|vA}!c#OEg)qsV$Hgd>`xMThxi!%`Nl z%f(L4WWeA%xOKplIF`cG7Pf_<1H>`;1Q0=~2(iLE-h6oq%YOcqnBOc)LFdjLSo8CG zGHNvAg&7}FuX;rs!9W}-18!|F2t&9!hUL52V1=**LYPer$^&t6RLJyhWvB!#WfRdB zj-6znll-Z}5f^L+NFt^^EOE^Vhw=|?#b82uI5;YBJy3|R`~?b~iN&=+D=bS9!bNKZ zmP5>S35617GYK{?|9xwp78|83EKg(E7M_dW4!*&_H-6X_SmNS|!nPcgGTiXECP>7f zDVXvpWf^OtZQM6BF3JiS>%TTGKDO;+WlG3*)rtAr6cf0jtg!D^rBM>YQl;C}V7B>Z zJAj>(e_i>L8AE*Bc~J(}3lK5LbY>m%{N0@mxMsL&fx>Ovd(Q|)On#X&S~T^2ImEa6 zSaDrLdlBR3XS|mDZvrL7ELxszVPTowD)`ngGwF(U@pKH&?7;~8)uDZbQz@I^*crs% zqnaZxEiMW(I7NI5W?WZPD9b3W;s@qyEtGi1;^QP3;w;~SVxkSfKf^Ru9r4hZs4)r9 zW-(x}mWbIoD>E$$2C&$%ED&X&OHiN;Bdo=7R)0T-2WKqjy*H_qVfD`&Q=;lIIc;E=dyF_ZwwyPpAT28 zrbgw;Bx`f*7^n3T(`QZJboum+=NR?q8@%+x65G_m=%mmCZ{+;y^Jj zRpx@PPna+M@MG{6RrdQ6^K-(J%On4y?w?bTa?>juk>M7Jb1S>j$Gl*=9VJ&#uoGOIDb9B5-%1bQ^42pu$c($7O0- z8D&iQWvf)@6h8lc6R1#pArBUF<&RrSh09i~Qa}j{R{I(O)#{ahh z_Y235-iA=fiC2YLFaCShy2R&LzAJ9MFy!ghK>^pdrtNQeyN&QS-eRCGM2lA*=r7C@g zj-Yef9Kx~VjJ@-2HvP7ZdM(;A^v=7eTQ$iHDiv5>N|h0XBm1^6<)yb-{L^nVZ`FeP$J{}3IL54*AMweoFG$O(!_X0T)3Sag zlvr3|`8&g-d_MDIKKN__;j~PK47-DtIgJU+aaJr{&I_--&yk~1Ztvd{OGj9}bP-ov zdpC1$OSwrRybEapSdp$Oy&w=*?I8{EKfmToh%{paHB}znx|| zr*P$^UHoGeA%x3@pO?`0nj0x+y9^pSn$GQ85>_RwS-zZ?UVV+jg_>*n520uGj(CMf zdHMNAS+L|MD%WYw&=I3))vy9TEMCal(?4MEzWrQzNf%O5(^&AuEH2sn3vF6d<+cHr z5Q`jP@LF`MaAU*gm0Q>fmoE!}&bOS1BhM0E*;NA~detDn&7 zlumpy{cYM$9*b6XT(v+&iA0aHYuhf4?cK`6C!c5Vn0u*TtvrjC>n0@A001BWNkllT~tav%7QQ7WZRyDj2}0S`Cos|9mB@* z`ON9mudL{ESua9KsZ4xf2G76p0h7jD{MWlTlWRZNL0J0T*NhuKk%5CpQKLq6YSzeN z?aDPA*nfR5s&d#aA!0WH3YV(c^zxz(!d3O#+ zij{BeOIR*_tJ9nhX0Y+s&5V6;60vA8jum0S?9Z6~<_yN&b1!oiuH=q8NAu;(H}I4X z6fH46|L|iTdH50To%}Sb*KXjpp||tS2k((m@H@lr9Lm)`rbTI)seOY$iSOB=sBCrdiEQ zdUQF9?!9_4?St=l;GswP@U?L)S~#C*L>M>rFVwCQV%d+YXnSTS{xW(Lbt-w39N&)T zxzw*;k26l`!IY<`5-llW{DixC=jEyVv~DvK?j6qyFTKqDlV9NJNn^>blEtv0w{on= zWz4wysL`kuZE7ZyVhi_Ae1M8o>QkXy8vFO|CbfEfzctK(tmr7SXU!rtyE$XW+{xhU zd-L0E{mH49L8&imF$Dz&*|cFR>1h|RZOdjhY}-kLDh>H=(YJ)tGWm7wPdqyLA%>26 zh`rl?Naf31R>C`uVCU`a^{HEPuOpU%!n`4i<&_X*UNg)S&y_RLSnuHS?o z)~q8|Qbo;;FFCXkAYPV=crw)yA+&sSh%p<#QOWL2^j*h1{VE%UlIJk2g zwJX$MNB&WEZ2yr86_VM%Z!fO){=gjW8_z93Vl4e;0lja$i7Wf}B^?ikeAX#VX3gfb zY2T5Qq+}M(oy)lwT}ahXgc&bA&M&`ip^`q#?>lmN;H?QXsgaC!9cIi}PAG`p4J?6T z6sii9t8zT@3p=-Mq~}>3NJ)wE*{3tHGioz$;R=o&$YaaTKe7GbexgcYJ24`WgM2va z8!~I0%Bs~rBW@u_4j*9ij-9Ojau%m|I+yGE-9Y(p2s?Iw9h-h8oL+_Ijp|S_T*Rku ze@Nxp%^7juy=2-Rby9_iQ>W6q?=`q7)oI$gJsmopfn^EPUOWYfAIt-m##Ij0>bB(U zE*Vv^%o{=)HtiE+f5SRhl-bP5ICfc5L23C@qWLeFt(%-4vQtaTxRP^Xxx1 znD;+fK!YZY`EvH>SY8237B8VV2G}7sZ2XlYhYnCNDaxw#zmQY2Jy;fX8aJj!W)+e} zxc9NAF+ne$ADyfzEGS{lSBn@jWIQdK)u3~Smc04)CpV-HQ!&Ft+<8`M?4r1)X&3O8$7kK~qr5 zpG&DxA)O>Vl#UUL7L#A-(z<;&&g|S8O)(vNTu4sShRk_kD_M2xVL84NvZb+X@GKJ# zEILNf@ne+BstO?xE!4}-A{H&7$n|iQW6~;(B|gLm5a5BC08WL4!PZN%73EUG#3IGy z9z00Zx=rcOsT(QYQMz_Jhn$wRSiX2Zlb(8u!MFA!9NNvsb*n+ea4oQ`kPiW48E1Df z5tC>WWvVS3&v#PFD3?r3N+@tW3cV1go^~dUa+-4XIp=VFa(V3I$GCUgJ%qCx(5uVo ztXw>gXv{@y8&4_2v+Vax@o_3G6e2E46|rgK&n#KClCPIuLD+$UV@Ijcw3s^vUPOu& zEc-TKn_vq&l}=}N6Cp^ zPRdC+DJSKBL@e?7f-TGXQ_R{95Kb>oqgIXCxb_E{*2|(<^Bfv9YCy&G6jm--!s@NL z%y?@WAHDrD%YXV6k~2VD4(!@R-r)k$DpsLN^{V9V+D@~E^=Y2dl6np5kd&P4D^X$q zMwRUYI2(|JnClX@6v}g1yK*I`wK;_jojcR&)HZ}uQc!jhh@#-oQDT5jgrHCg@Mzq$ z5liRIC2#j0^78U2I3B@OVdGw_z;cYMcgPAEKRrKkvvKp5B!!b$Hh&)ZdHEbU9wFkG zAPOCK3^XEc3^y7jr&%MOefmj~(lc4Jc_*#fwxuY47fl=1qFJj`Xx!oyGLq9twPF+= z%SAgCXx_9T+c*74y?S-X$!SO9MlGnA9;Qc^Gg$xA3U+SU%ArF?DL5{qSE^3z$UgFR z?KRL)AF#c6G*pVN}`@~Px*-%R5M4e8YJOmbSb#!gByk$=IF znOHyyX=xQGIkcT42ljI?_Xw_5*j_Qm4;^4%ZXTa~wS=tf`ebFK(5y*Kii?lYta)=9 zHElsovqnhlIEDFnTy@nooYwJds?=$WrxoEO8_R*;H*IEL?qQ0fF28M9%dR~KaO1%T zg)CaMkUj&4vUt%#<}aAXlI6>&S4r{nPd^fK(jbygQBg55D-{dGU16= zY1;Y>vdX2?qIC}Wc?W1vqY^neEos!aAvLO$|EG<$lk(pwzCBM|#63c8?jDX6l>ku$ z?FU0?6eTDk1RGEj==fqS-Jdk3J9y!d`oqLIBK_}dw zSd7HGgH(UN2BhrM$~?>G$xXsX!N0G}b&cSat>4l+%KQ#cJBgb+5|hh`7veu!blG?RD^~7F z`BTLlM*hj>Y!ynP{~bfAUcqAUzN@M~`B+m{>q4PyRxE6`R7T5KFYz8EaDXOo2T znH4OQc2S`eZW%J1)r-F2hHLxr@RQGynqic{)7p1n<~#3FP#iJCR}u!T61rV+F_{@* zh7P!yf&B;Z)q-Wj>?9xpp5Tg0M7e~NLU|UJm4u^&DmCje>5<8N{??n^c=Z6Dc;-ba zR;v=!2q4CvNK6Fdl5b{l%Z>dRbn_iJ<*HD-X*+J{+n3Ps9o#gaFMa#n%#07dz#~MP zQ=74O&o(~!Vi7}!44`saF}K`&6W8^$THZo2w19=hvx1`HU$(g4puFu$z_88TutRg!Fj=I66r6c-+1 z;>1UIf971`*lo%|>=fcL+1mIBYAZ~a^Df|`E~hZ=?&0*gwjU2Z`8);3g%0h{pkUu- zZo1(*9(eF!tZ*7g7+ZrQ9=5GeRvN83bS6EP%T3o`$HR|2Ml=SEs#WBHQMc1?K!4`` zxQ&|!-$hok!-(PiS^d*uuD{_1ZW?$Si?P+(?b=YE-LU zl|ENr&i!M@aocSp*!0_Wrat*NU(K0stfPPw6|iXO3Oe>UkJ|O?QNMm8nlx(2WnEe_ zfBt+@%2lIEMVpzQ%_3%{#jz_ZR;oa^?w$DP>!ox*{~}Usp+ooXB;9Q)+guTe`Qheh0_1Wi*jiDYOe3wmjz4Ka^%2n#*Q7!;uY%vk8QuLXY8mE^zT1_ zX|KOcEK>jgeK&~?C%VkzPgD&5mfDwiRTB1(8l-?XUY^R$L;pfS z%=1w{eLTlM&?MtX1W0Kf{>E#Av}MxA3!shClb{hP(MaSFcMiFUN1mQWH0C9!Fr^A= z@T@=3Pye7U{^zB%di*%^pkhxjqKNohC!+i$o?@ud8N^3P?c`(x3%L_{Ao zytFzhI$*K%qK4;IL_E)M;6?+^T#1PmEiq5T^E?rWio^{2VJzStjYdR!p3i41KL2Y( z3=?ny$D`|s_6(D!7FS#m|2;APJ$^bdtdhZx77@=Y7SAp5%aKr~_If^}>)i>Zg4tRTg?qCTxW?fST zE#i415my^_Tkm+BXV=q)e>Ubu%5tpgfT7mUh9q#cicjO~2E4U~J6H$z>6nNY^>gT% zHui$zmL%4W&$X)!U#;kPIxQleE)wm3F!#nxy@?l)>&A1WwU(&3eyas}F&wy_c;b0l zN<5L6r+pr1H{PZtA`;VHyl1$<{hlkLwcjM3h%ONA78wpBM zB=7|Xr8j)TV)Ezb`=tEyMQbgQNJQ4IUHgZ;!GDW8I6freKT+AX;%%u=zMQ=L(Gpp; z=u62eUruhj`vEy};8(fi+|J^J(xhhH1~O*s82Ns|JgHitf|Re6B~4H7EQ{A|Fx=OY z(C6aMj+LEMf|)0Q-d6k9gE^^eA!DMWyX3B02TJ7zo#a4N`}3MVFK9RZ41WaqPt&EN z{)F--ruEs^{W<2ue0gRT*QJ+5N5nh2QQ9=9A{Y0)Q}Rnn=XzJ%_!tP@5ohq#!Ql7* z>ckoNUqcLc@FV_Q6_t{syJg6LYo&bE8gl8iH_O(&2Mss3Ut`)UmY=?#EuGr8kt(&D z$YU?QD2apG80w(^e;ZG&B98!v27VS-aVI}wc8vQR4QAJrJtFG~gdqXxh3 z#~&8+l;bm-_>@OJHkv`qH``{VOpOJQR3W8| z9n^CCpcBK(D{{h$1v3+Zne7Bh5n8)xDBgn4bm})hu$L(3ZH#SHSdv|PQ-gnD6UaYBD zttK7LI+Hq;QrNR?3qLGh%c1oIj!2zx@{|xEaRGEhLu85%)Z^*m^EuLE!%bAw9{L0 zV9U>ZxnMaxF1(CAzpfy!#NxE}XE6V>52@es49+;MCA)rI$DBp0=+yaiV#oHeX2Uk3 zo=vrywK=ED*;KF{l&wKr!V+QK%9SkpX$x1}a3#kNY-i!zZ)wz~BkkMf5IcH+Zx$?N zU+!UQ)NMffGdoc!HQDDB`qz@u!{8{|i!ky2M~O(7ufCYcM{mEuOD|1f^n`mTXIns& zV@D41_)}9Ec^2ctjh4gchI48FYdW_0{4s?!wcE98Q%Y5Hf`C# z7&^K4qbgHzAHm?#j7TI|_(hza*SKw9}UMvi-$ zXPq|*?>AeQli z3pv+)@l!UxD+n%>roMM9eb7yBqkZSaBS*z|YUrae#YAe0ngT z%O?QI`PyIEV-0gxBEW2^l4_c+Or8-#E)OWn0Ck(VB*$+T53CSnE7Cu9v4X=B^PS_f z8I+PCmBQx+u(t+*-v{0G3t$C}abmZRABzc|?Vt#Fi~}%UlS~JP#@h0Ea!r{N59kB~ zsvQTqRl(J=D)dSD*A#^Zx`g*%d!DiPJi(!uCP_*tcGI!MrRc~ZzMVUdCY>&$=^5$7 zw8!r|e&^|@o+SCMn<*|Sq%h_(?TuHdR;LAR&*(_qisk**H%E0sA-gyI#Q1y0QsO!s zca!LU``tV<{yG+X@gbweK1NB{p(Luvs#ceeW`9afHJbrfUBvgR_L5ntJlhT&<$^2v z(Qe9c)8j3LgUhD1%ebxIZTzxpKc1aVa&iVwO?#OudKh*gk$@hs1S@u!`$mtZ`_(t| zOzVlv`FIB7pZ<`}7hcCh6DF``e-WR~`jlzUJ%iL<#_W$@;^Vho;Qp8A^UixyS^UWh zy!+WAiXt{%EX24cp61T0+Z+FEOHewWC0~EZn8_c~x%b8F-mr=X?jFh2V<(f-uqwl@ zxs0uYw*@P?~!)xWgN^a;pw5nsG8|A^42SPdgfvV z^}UMQhK)yA77{r?gSu7l@Ng8=tXY>k$3DoSSs%0MSP3@ZgfqDIhC$fG5U-F%wXz}R z;)+B0?0VR40o#9F&xc=r%S*3LB`Yb6Bbd$UN%^;yQcIw}rpliL8B<0H^k0{Vv1J9$ zIASba@s(Jc!6zzE_QbdFX+zH=%3Py#F&4LwqsK}}E?0pRr<66(Li-AiBF^860?VRm zt)^71B^WZKQma?Y|39!yNuX4fnWFx>{(^S~lzD*#tZMa!RIP6L7OzspMw1vd>|6Tc zYzG0mWKhaL*$FsWRhcZ9kG_A(AK0D*i5uC1at11t^6SZbHp-R~0`d>@8P9*a?LR#s z5g8Ytc5`Lg&1{@+*Jih_#c)Ts*`7f;%6~EtC zP?gWko1luC8uhSIWhnndJn|3k#VJ=ACn<#_5}7j;#?PjNXe>%Wfk(v(m9SL6_FRhB zAGBH^aRnXizdb0|KWogD_NkNdUl55>cw`T+O#28st0s$Pe?fBYS~{I~z0blEFw<&8 zX~asS_l>tO?eUS=dOy!jdYVer8nS5R_teZRM<^H?!JMbTQmHgO?X3UD-h0PMQS9sg z@9LhJoz0PjU0}&M=b$7pfLRnXqQ{6?FrgyhfPfN21Qak3R4`yXMnF+O(vs7XVOhfF zyc4>+et%T=%-}iq`@6|-@8$D)@nUzjr@O1Vy6UOt6CPHq_?)7%r}+Ey1+4#h1Ex8Y zni`XUmdwiRHSAvVHII*Yif_ML#jzAWKmNFfd&bXT!V@odB-Bi$83la$ z$w%zmcYrDL7LlG7%dNwP^X1n+GPwT*#Jeq|Ed&QKq}OlFmHpbWb^9+Al$P@Ss`Yf} z+KXD5aXj|)^PDR4(Vzic;t@D z@y11m-uS=7NS1&USQ_-{FSnt(xQC4acSs!6q;^O zt5!1KtvN(-c@5sUR1#yoXq3>PK^D~&+0^&~h*&oPUnSpsvYL~HJ|4WV695URwMa~c z=x7&ISePNtjl?o4`QfWiIgww;b1%QDHu0tb!5ZFO_y*lC>QBq|&6OIK3^(Vz{ol0+ z#VYZK1cf@xktQQ_Q7wrj!g)?oI2lZKCY=b&B876wB$!q>>nfCCYg2uppj`}nRe4OA z@)Eg)#UUspun77~S@_mceqO&LbbnHs_L`|7afL`d=Q?3168=p@fRGT1Iyd55waa!f z8a0(1J9-4a)G#$SWyQtJnf@{dbI%ZT&TN?>U06#hu&Llnn7Nb@eIbwpYKl0Pdy;@a z$?b((g=LwFIkjw~m@YhTR4=R>e7y?iP_j z?E(wz!0Zr*;8g8(zH1+^p`WYyEFn-?!R(hNvh%NNK55{YF0JJ za&|It+I-4u0-?t(Y=&B5f?3L`+~ZXGf;L;J$_hE)(2{n>UgS_gjpu*seUzpFG6<$} zLmQ}n(iwNAs&^U00#p#WCC|y?%HDMO0Ruz05xN30q4&m_u7r-PENAqik8=I(_woL+k0?BK9McHcRT~6`)X_Z& z)T>>G1h>7)0r=@LpVK z#Ky&8`KwjnjwJ|G`ib$z<8^BUeHHkOAW~{nSJmKld2zd37{MAAzq^>_->qT7w5c?$ zSI73+D36V1xkA&tL?VM_e7)jhKKNoS)22SNk3k*}~{-PKsfq{jFX)lbH1(s!mSQAUrKv-xPxP)Qr zWD10)hpX_5$o15~G)g&oB!?O!h#AHSSf-zyyY_RopvnezCPG-4(o!Wtu;bvQfn}G0 z_*bQ*g+ohP0i>y3E-4&$kJ7r8Hb^uj{JQ3QMm{!z5?>7lVETRR&fZLEO;9Z-(n4su znkYeO>;fVrl`c_HleUn$J(*^&{hkREC*cFE2tT#JLerwuuHTLU6e8?eR{L=mM#NOB zu4kbMOKGRtESDnJOvQpqh0!(PLc@hFOe`Z9a@`BfWH?G&oo46$;~1s_Zz?`fgjigJsRon{nx#{M!v?;gYnkd8CG%!$j|$M7 zR5^QBVwozwGyl|SDt#7M0djV4CaLnjN=_0MiDs)unkn z|I{ds`myW(0l zZQg?=L7I|T6DBZw&a3#OK}~f9_doCe!~QmcvYG&4H{^NycbU+MO-!S9dLn0Y_jCB* zek_+4LnxJVAuNPu$LC66#|k)ak>kYFk(L7p&N(>%mHec1Bme*)07*naR0Vl_`}w!@ z>N|kh^XD<}qP_?#2&NyUer+O69bM>(u?8|T>S9?YJ2!8ktgxKYYD=+gdK5yJ_$rI3 z@N3l0Y($hMxPIt$toZa3KKS4x9=LlLUXPB@)CM*reQ0Sk>(PT&jWQVf^hl(;Ha&aw zz$*lM?+BB z8`mHerTG|!m)PWVFpAi}dnbnGAs{rQ?xAk|`Us$N*Ul_?|9#&7@MFe}e~OrBFHQ#W zUj_&YHLnS&0bY`7WzxJ}G6#2MBTdPf6U8JYClIgeVCe`FsoSVIzLH~(>29yIzB+S38NSsv@$pbLic(CA)U- z=HQ89e3nk19-XP57Dx7$o#f`_laN-6wq3iBnh=XSg3)qZa>CS*zG^o7vYs5bpkDn3 zbnDs$w>Oa+hF(pb%q$Gc&yHW$aXdE(tQHhE4@7o8L z*Q4B?(wW#T5JAdHirA99n}YIc8Z>Q2=Qb^f5*hB+^I8OPkMs*(SV~z_OoO60W^0E?K*d%enxE-xhL)N z5W)yQDGA4NcJk?`g5+o~oxAm*c8Z&ZEn9L$Oar_wjr=nw*zoHX0@9*!vzD}J(;Bzt zx^(Z}4PA3#+6%hN6U7zRTu*Ff3tT{DSuwwE*hFR7X-dm|SXK~CS`?f)%7#tZ z)c7nKG;c+Rwk;7@_$tfz>K{L_H>(yG^z2B3+DUBRx`jhWbMYpo(6wtzmK=3&BSuWG3}Mf#6`Ou$N2B}g8wfwi3e{&CeMz2jM2|d;@SZ{ z@M=0{bZw%eV?Yb2olq!S2{akF{j4nEs^wP6iH{Snv zC0F14DD$Vjz}BDFGIjLBjDPxJw5SB$T)dR)F7Fo#-Ox~*Mya`oP0L{L<%3x}c@CZW z4xwesX1I)MK798rwww|Sx#K>vYB%B0d#>lHNpEu5(A#NTFNwtJrgZ7lj<;q`X2s$K zlmwzkN=inLj_0~-1~cpJuXtrn4~AaRp9?y-;Et;=#^s5@rN@w*lt#Y+JsCdi5|(}O z9xax=jS-c^qhqG<{3ExhWWB#!3YCQ}Es$s)9Q0Nkih6WZ=$w0z#YSH;>Bl2(X?qBvN!Ky@@uaV zMLAO@jlqa-!J@Yop$VOq?Yc2!@CEkPLdA+(mVquMW=#=qFaCr&S?&1li%(gpxk#&1 zmm7v&O_H~YL&px0)uuDL+lje9KL?yQWiFLK5iS%hv_F6iG^^Q}{WE`ibTWPVUO;Mc zG&APB&73Ju@cPRWxcq)M4-LPZ1ABMy#{7@y*5)auOqf7yvpzI!(15D)vn=`iZQlCu z7cL#ppY7Y;qkfxSjCHnSFd#K-T?W%ZYfnYCyYS6p#5THY!8_UeHa<-rb8vFkqh z@s*$D!3SR?sa7pAGSis<#zH2KABju&89iYhgD<-bkE@WX&K<$hFfB=$FGx(Bi<;tM zUK;ZZQz{Yit7kKoEnmjPmt4(=d#_{JM<227 zm%a49s55CvUiRc1X7lcobZ*lMZ?p~~2u3k4j(LGnGoE(M68ZMW9o#ki3A~lNShMF8 z(`HVk{M137d}a)9FId3ZPu^tZ{sMaRy^Okbia2|yiczCR)4WSB0;MNexOf@!7A__; zUf3*V*g21MA#t(x*KDFZ9**qT!17O5@#@P@uzUM9=6m6$B*EzILpGf z-(~D8vuKf2!}tjkXx9BIQe&fO)}j>ZBqN=SXbDIQv-l{JCyZtKqK{~vX7ScrZ_}vL zCDf~v!0{7#R95>~zH}ichd;tKmkm&NCP5f}-k$vmZ7+YE`n3{xapWT$C<@TOdkeN_ zZ^m*pM+m4YFXP0CBLqr|Sorp0o}V(4t_@unQllc^p`t2?2$Zt&^RJow))!pZt2+mC z4zlLQwM-iO5L-5`XXf<9Tztg<-1s?h^e8jm{)pvE-yuFa4Wy*z>{(u)J)g&>zr!_` z55OxVy}NcKGtR@J_urxSzzeaYiNCarQ6rxw)|<==<6k5#AxgP0LxH!y|7-rg!laHM zivE}0#Ioj{IgxjoU{J#omqd$}t%%nvShDN`>NROiodk`Aix!fYUQfvhYN=d%+g-Hn zcRjV@Txd>xH!Ui}z?f(dTZg~Td!Ji!4pLQB11=9~buw|eQn>Pl;WX=XDUH$-$%?&@ zrJsFDoklH4OpN3C2@|-d+D%E`5pKPABuS}hSXvB&hTO*It$X6vqv_PHC36=o;?VJv zRQm!%MMu-TWmDW{5QGbaV%IeQ%S32VB-E~taK|$2_UlNEbE8YiOS9)w9&}MVUPoxL z414%VTJ*V+`Yk%(Mo_m&J7&GRh{MND6EF-kcN7^78WR(pz!NV_<&q%}Qah_D^)l0# zzj!G}bMr7PL3C^aSxuW0ml(}UbCz)HzQdH3RU_P9vYIx>E1VQ6XG{NAFo_gWc^srt zFzPjM5UKT=lUGpA&36o=Ws4?6Y4FU8FOrs-Npw^k4?O-9yZ7f%6%aIT(www-H=48< z{?Oxe8gQ8M3O`Rg@)!-9G(a;ddGf`VDfhWTYE`u|)6}wKQ_8)sx|X(q0129g?v7=| zlTTAnScW;n4+<$dy+Q!4fflZnvGczoe<`V9QcL?RFf}?*#;vI}k*miY0Hn z&IOlT$N0ZLg61#gyOrCJZWp)Sehc5M-^M*d2eNC+X0n>J#O>D5gwA!h3}ImBw$$Y9 zP_=!SwKMB8dh}zo$xNeNv(Fek<^`^} zt|wA+qvJwHaM=}CQdM0@w+p*7@TO-umV1gL2XjbCOXlVquOTBf375+$SE5=ZgaGO1 z*I&M8{pKC4_~J8C6C@Qy<^1}~8fs;v5FMAykQ;_juTDCeOXs+BQKxQQZn^yyYRAM- zoqH6Q6~vSRzu&~|ishk)A11c?EPeY7^+>AT^Hi#t4g5v!wdw(g0H53rSXx*Tz0eyG}iMa?JC%YEE+JJ!4tE^b4LCakV`lRB0K- zq-aR#;=bz%PVRw^z@=~fKG;Pq31>(}3o)|K?Ruoj_6SrJeDMlGq| zNHK#I1*aMH(1WbovJXS(n3{6T54(E=&p$ho9=*~duBraj&1z0&R&({pyczVlC<7rS zd55>tyVn2=cOt>+N<>U5125`|%jLoomqMqmDWOepTHQvZ)op|n76Lz|g?ZdO|H-J?y{P+qJEQBPFZ<7?MtA?)}m9lG#gk+i#XNZd4P*yQ}Xf8PG3xl|aH2xSGEmi%3b zcPStk@R6Ti%thC9Q;80iv==ltSKn|eAAdKF!s91cw{{c#Z+Q^itzlZ>u&9JEt zt5pkKSOfwlei_B^`yQoY);ykn;t{f%wc-9p9;9wsvg$b1B9JDz$Bt0#FJ;dBdBnI3 zG@@wSwj2HXbSFQzgt1ROK}O@&j2Ll0x^Q8cCQ@L_+c{Z!w$n)H2qAFCx=D(Up{lA1 zEQ8d9Sk440kiLBW{`?D^tA3RFG z0sZiL)E_O=i7(aJd+aow`n5sRbiCeZvNAI`v}Y%lbrqVX*uU_^WTGL_g-fXqyQ8U> z7EMj*8T8m_gtXAjN@h--#Lj~iG)j+R+nz&o9wbT0YROGE4B_?h6Y!>HaOeH^(xFW= zJVJrLP`s8qo(nJR&(^h@sc+UJE+LM(sd23NdIfL4_X#QW8gMFSE7a{~7k{xA9;qog zJk8*AQ3-J=8Kfn}0EjBWfZ!+yg2%Kri^=@Mww~2&=8sv5qsVp^zSh#)MOGWV--$!gQpb`DFV23@*#3W2`xnlD3H<>I%iw}6Dy+Dx1}mAtc+ z=-yb`bnHx@3ogJd!(buw4T)U`Mt$muj^eT_uAoiFo=8oz=N?Ie1{rj0+YxVaI#=Fs zBe5=ffk4=RR|~gIS_mOS`R(DmRsbcmZ^4eyjhK&Bms+6~EBI^&isO9joYfJmG*Fcq z{wm{EAcegs*=-NE$gzk_FPzE&8je$6IO9j!ail^qjD#XT?HF{2a3CTvP>2u+6{tG9 zp>C5A$PsLh%lYWP^Y*XJWm&3Tn#2C-`tQ3{FtPANd5BAhX2-7WTz5@xJi>)3bb=y= zzTw7;ukvG2$UQtGxOEiML^6~rSfw*C4mL6OAd8ME*eo#fM1cOxu~TD9u);)Itd z&O6KvLvN*4(^lL+YzQtQ7gL?u^%{UXijhx0L!;WN4wzd5U6?%j^plhp9W-OYpJY2Oan^>R4EF>#O?B+3608vv+Uk`fGKY-B{RX` z$fM&iEdyN_RF{|8g^e{5(~`mPQ=DIb-XN1xMTPji@uVds5@mxf%aRCuV1cDYhq4wW z2KBO1C@w3Zrn&~aDu~=bBO$piS6zGo^Ja`Cvsn{{+<7VtH_Yjt4 z;`94Bdg>%y`d$l~9YGa2)O3lQWBpR}hm@8_QRYTet|6mGZ?GUo+{A zkGY_21~p@+BQ?;X;<#z}eOz((&siczR#ZgGrO7bM{m- zI`-^GdW@Sn|M-%N23^L`+wNlJ@;CWp!$}ZoadPQVwhKlDVrQnMP*HT2yt5_5){n)d zxxmy2mX`3vC!h1;8y_>Edjlqne+`ML-Yd(*2$<-aBq1rDCJogwvXap^ZOZd@*jzP3a+p&jR?Z%C1+PEI8zyFo?t(z0Cn-HjC;_DyNxOEpY zlM>J^Nu$=Cc;TUknLBAb&prJdZ@e>~6t`M1Ecu(hKX3nJj#orlc4Cxc_WJ77gOs=; zmRHS*J%G?MuYT2pPIP=4!|r_;gbT;X>7+bFf`{KaKL5EeiXc9@4#Vz#7*!}fJQGD8 z83KYfFc5Zu{+QU>{O!JnLU-+yOtPzX+Qp0PVp8FW^xTsR)!uL!rid1wlU;VMJ2(8@ zf7M#&GY3#QW#yfg{Z$67N_11g0O9)z{Upvk_P3^mi;>yK|MT;8KKp-4gwHvcZa6@5H z5gGNVflznNF~Y} z%{y-|rb(KM{QP{}!X&j`Lwu!YnehBHn$=5Y_)Qma>#*UxIc)}ey0>BNhArH9*F7Z1 zrlL!UGz~Oe?G)dbHH!^<^O-$!D)F{EwQbLC#4T9L-^YxhUHw>oTECtKod*$=f~zm@ z!|O99QxcWNb4?l}WDrxj&_fHG$xXN3$fM6pV9KPI2$bd#L~`40*AXtAtX5N%!KUGj zP2ig^mT~&nPB#9$iq;)^(7JsWcC1|mK|fKkiL_|hiY1E{ajb1!4jwv8`-=o;@(X!? z(L&Yyl$%kHPG<77nLPaL6pkO=O5^%z?A)@6vt=$` z8}kq`9u28!7{Y_s8_(m9Kg6R?OyH@$iWMt}a;rGwaOrVH zyExhD;vAq8W`-ParP(ZvWtXl}bBE3I$^YQo`>zsY|BX{fp*BGZi`lhB1z5rgl`B%| z!FCP5|4@mrF!Lwu^C-emxo(}mMkoRN$IdMYW%-A)g5|%#Wc>-aMF@dmn0)!=SE}5K zW4~7d^Y7e7%Ti_8s;a8U%*_0KFLvJkQYK8(lz-$7z(RuMLs&KJ+OvnlhY#T=iiy)d zV$qw^=+Y*glSg-O-Cbju@akJ!+$jsUSOR;g%*=po;8m*&IDtKtfU~ z-MaT6B|gTUkW>Knum}k6=i4GxN$25DWAzBL@$#W6vQ1L6fNXWG?8_mz1agdw1<& z-=RF>Qc~&LyF0@4u`PQGr%o4=R<8k_x^^WYO0sMB0ixXTv~1ZBA*(oeAcy>NLHADW zak~I1k!BgE&lIqI#~vyx%XsI*)!cITC~h0v9?d9V%&0L`*Xqc)(GL{w> zos@Wu{Jaw!$g8Ah=hhURInI{tyQ!}7;fYJ8TlbzMcwybzpDC>j5SyGz_pV(@OG-e= z!P#{jh0Rk~K6dZe%Aw)_{rmSPK{u%>JHw_edpLEv2ycv=dd*wWsZC1?au2X^`w{wG zcmap@ZYH)~OPVyOi>NMP^XBd3=NBVfF6y;tMW>bxDLIqN=B<0EuB^r#mq@#=J!z7W z$l22;*tl^kHI|1S-8)b}BZ(c`c5?K{Nn#Vy=+dnRwNj!vk(bBW{0cgEYKJcToXkDO z?t`bfuvahQydFT+UIc@aCl0b}Zw?jJK@yYG=-9a%DM<;qrAf}N?U+$9G;G<57);LQ z9cR;~ZS=b6Qc@G+|4%xFq?81ML2`0(s9(SSzdUBwu3hx$(+7Zpf&!K=UrygXeQnhu z2q_TR^3<($H?TaE;w9TP1S2z1Im{ay@L7<$=7^h2zl?c&B^{*?Ps z;lF<`f(fT-s0?SjP&S}R-3GR{yVU6k@$YS?#HpucIRG;>SN!Ym{~7F6QBe`=*RSWQ ztF8)t_Iuaa{XN@hSt{0Q+xBg=ZQGVEUAp{k*E(;1zB%E4zyA6wLjDmIq9e@2LbrVE z*|L^>M^2HDlER8FzhmF=088ioo$6CNSn>5L4pq3BI(-sJfD0274MRCJ(4{jGn^;1} zLPNvC3RV*E`vDJVZY9bj1o2)kLP#{UaCC$X3{0C&*PP9qP!eYbswAgwmwqtpHHlT&#X`~}TheVTpYJ3$~rj8U*I4%>@ z<0i`O#v^4&E=fIKQ?VhoETI+ho|tOH*$bre3_}8dcIbh6hNj)?s^((YMQ3M0OBFU? z35jy5+hYVm&)}S>AF1MvY%LQUl@&{Zrb&ZzyxSGiEX{PIgOGc(VF!2jhI2?AZ`Od5ZHWSow2S6S{@cI`Prb zS(4*pLV>%QjJzLtPVkJHAT8W>9E#;EveHCguq}H#AAI;J0aKwHX<4MD*X54;?jgEP zIxagqEW9i`Kr7N^6jtjCyG30QP89op`&nrAoeEV(+m4mdal+E|2xt;+7ldTyRK@Fv z$yo~lHFY)3zB5N*!|o3~mNUiGtl#<_@iFntm^zWH+6jE}{dNujIm492oI6Y5J2kaRj)qDf%~*Xxm2vxDKo4ywqtPDs0u zcZ7UQ_|6?kKxaI=)K7v?pQ)HFLXwB7-7e*N3=dGnN=bnfo=~r-J`bwjg$vMBDH!22 zN?la}!t;LM|B6X_1FE}Rq4)H!X3yDa5dZ)n07*naR6>Zq=$)On^LF0;Y9^#5Whl$& zkI)R35>>oIq9OzVX<`aZ#l8s*goYKtR)pLsA{>0|xLg#DP^^i{bk#yju(VXU8wZS7 zG92t2x%jHs7z2shhHegkQ^zS*O^I%4O86&&)sqOzc3o(W`vuj8&>1Yd4FV~`GIL6Q z*9yUfNH>eqQU%c>r*!F*oed>mgzv;*-kj%X+H9ob4$>mdBG0*=4E1QhzM>o5QW?jl z6u6we&_ert=R_(yRyg#TiPI{}zAs_-qO>_J&6Eh;0Y;{+5#vIoV*ECy$~lt)Md6;X z`%Mbl6%}rE=-CSsq+)9=O)+|!4e}kARU{!JL%V}8PvVRRVW$>3M)43e)~a)Mf#_^aR93`hMn^Zzx{meXh<1mWyA4b7NPjB&^r+E zAVVhpjZY#!JNMh?ej{=o`D@UQ|0O2SQJ}$g$NMY!Y25}IG;2fStlC)iSO{ys=nmvo zn^b9n&@l-oT!_elhxn)8|KE-Iw+^v@06VtrVf&sV+;;m=TVM=A51hzh7Re#26Gy&B z&ZWY~igW)E+DL{y8|N^eBJvE5DHR{fRym4n?QauHoXxZPTjYI3-shh)z9N}GM}0`W zpAtv56rB5aG|Tmf^-6hO!0Cg(#(Q#}3H-ldkxZb5_+!AIV?qct%g3khzs2O&-o+1~ z>58n z`o#u54!n$<6cyxi08IENf#Yx!LMZt$3xsJ>Q&omPXxP)2&1%`T@B}jCArY9iyU;mO zAVd1L=VlCs=4(`(jAm=!iqHfju%yX9zWJ7Ua~IghDwnGaT}1&>^*zVQC_rimDeSXU zv2*8ECQg};)KsY&mxDWm<05xJyqz4UDF#g10MOyebTo9kuQW8fzbw#oOdK5q4IMq~ zHjMzQs{J}hi!&$oF#5%*oUL*kZ(0c92pcX68KD`i2`nMVJGh^RAH0XW@-pS^btt?@ zAD#WkRjCEl|B*2CUje0X4y8TaYX-_it;Wo;W5<~_b56tsbg;Kukvi0oFwZ_w#PcHJ zpVLa5eFYc>)isqiEOjX@Q_BXRk*5^cAYE5LFk*XhE~q^V*s74poZ_mh|uPgbk0tlpYqzdaTflAxvD87VC#PickUEx^{{ zj<_HD*;uxopbF>*Q%a-^B8@zjESSx66J}HDmr6>|R_Bp6NRbjulZa>HY|JxA2s4;Xfp z1V;@;+Iv0$=ZqaoVr!o}Z)fBi@&}u6<_4wzjkNGpR&wNE4m-AQW8eP$yDQBc{^`^u!RX72Tc9m15tvs{N(J(CgNHINF@jVR%B9ieOS?#DX0%C(cYUh*CIl zG7flC;6g}Yw>!v|&70W1b5}T#PCDRI3%A3GRdnv%t~G}Z&B{v3ICAJz#8hjAlWb+E zH4(S!01F4G*w8NoWCcPx*H_cMCLKrRZwkT6NWdfP$uUS#!D;^S-H%k6oNM;j31Pbk zCQ$&TMFnJU-a^2z&Vg{Dz^HIo;kk=#=*dTHGD3`v%U8^0EZ?s3z$OM5CIUX@~0&g=O*nw z$1>3D{I`e&^j3SCr$IDy~+OKCn!r35HbqC^@^gaMx|a`1G?c2%=^j zm&>rPqk&n2&`eD18AbX*D$REjwXy&6v67wGV@dlxF)%9fnK z7ZBTIpsfMxJP$C?Z5NLA8yGAiSZS5eV@j|zkG;z`K?XykD+~-#RZC{W9uzYI7N&_JS_S16uCm0&f0H&>fD+pj| zTExam0@ci)JA;wWJVWg|=`?HHm^bIl<(8Z8ps2V4Gib8%+kbH8)DeP#DyB|(iJYUk zbnMBcGB5)1~B zMh#zo^darrwkNA`OU6&0K|m5JO{caA0x(&>`WrIS(wI1T1_9IJ`_GnAKeH~Y*KOtL zM<3*>AvaQKn5_PCIUU-zCZ$e8ZW?wEGEjpI2B@s4q)pQ%T+r`g0z&faBlpuVJ(aAi zEXGfqK}|qlSSF@rF>TUIWTrG@`HC;uy7n9D*UjSduYcjh(S3C3+>>jD-i6Os&WFpE z(4k#xGU{b<-HmrqToDZ4y#0j!jFBaRH!jCqj5R42G8Tb^Y$m0%PEQqe+&?`G!3D< z05=|wD(SL)^D3rJf0MGRYD~?;j5+gZRZDW?)mM=()6wyhoY9D9$N!zqO;g#wZ6mX0 z&L+RSoC+(E`yYOiA(!^R1NJr|$^3>n1z$IbQnCEz7c4Njo{Rp``eqd*@i)Wr6N$~VOdS7-g zOP4I7adH(`-*6XE37I4$CGy&9W7)Pbn`KLuQ{(qx#bq#V;zT+$u8Ui9*h)=dIjT9G zcbEy|UgcQs8MJ6Gqn>{b%Q9KF@@uXcd=*6%HC!`vDEB>Z7tv-RGpD`EhV91))YQ*%;V3JoxP9f)KnfG{X7HvbVmZZ%A!CBKiR84X4JS@=<%7DRfY7t zKbU@ZwSvkb`w8+`2jD#yNdT0FQ8$1A^;v;11pFS5}j%$j(wgD+54&R zNrn!;i#u)`%DUxmF>UVK$hc%QS;N)0JjlIw4kcKT&%8NvS@-KkYJwKYjXN=E{Ae1a zC5Oi|D#KVBC2U-?hL>M|o2ozsRRIr%6_05eoIbXn=~E_iqNswRDvc|yx`7ApznLZT zUghlt^GV96hb7%yeC0LVea~GaYn8k+=S{x(aWhqc8ZN%>RshgIFTWmr@J@dIbO~c; zyoDCukc;~Fr+<@JvNvXP`;9k}n$eUO@4JV)ZyCaSzx+(Y^e9%mF_*7)SMcWaQGE8+ z9A>}&Bc6m*uD^C5*I(L$sncF3@8nsk{LpLgtvr7BASOKhAjRHRy!!HZ5?p{KIk9Ui zOP8(Sm3NkNQP=i(2y*k#tGQ$7oviriWA41~PJ%`a)rGlCp8Nx6eM!uk@gk{S7rOkH z6!-ra6C#KiEath9BU$|3w_G^*Dzu6`wjJGpumZR=K`>xoSvueW;h|B-4qVZ%J>7bA zVbg|eJaIAHaL3KmuUC&c$;lCsxdPperA*@bKe&@!e{g5A97segRLE-QanN5}dX^6uLU={xvF zF28I5KYYKAF^@e?|IMqZ6(5amzf77g!1VFuCm-<5ue(^hPeclY{|6gQ+VgS75weSL6nyJnX_;a(NP-9-hGGX$4=(MC38uwQ;%0?&j8C} z+MGpv`{PGAaL-ksFIS>|biCteuKMg99wOBbBk`Yl50b}XCUcHNp( z*Oah7x0Elx`Iu&P<1nfY^Zv5MJU(_RjWaTsGGhU+yfT}Gb0?#TNLRN+8r965_A)h| zbY6RR5(yp`(XnoR`O2bWx8BTnZ5H{5cX9v7(Oh!*r5xYz9mftGVdkuv1S*Spe9WsH zJzdS=AHE^?R3Y;gyh}n<6bbQuHm==_=__IU#5ojJ`Wg4))0CGSW9fSzaL>pwv~J#j zsWTTaeezTm%zloY`;K$RJ&$npkW28!#)b+thf0x{22~ZMG;Q6Hv6Els^!^Rpa{mN| z-f%VE>H~~=VJ7b^`G9sUGWq6{Wh{7O1`TJ<;ar@Xy!}ZA59q-KeFrhKd2iAZW9`Mw#Brbt0L$Xx#~oujz!%8U4Q-FgXOMYCnf!gT}Xw#;d9m=i|pPa{6_}7DMj=moa7Pqj=<5Hm%!0bV4cjLL7cmK`+;aV; z%>Q&9xp}8pxpFIg`wk>F&c*oYv+!9iQsdmDCMIAUIgJtUG5FfQfv_-z8&7NsV<%1~ zBhih=ETOWhl6^-{Q&dup-&e`ry+=v!+!zDFl~-KNGov3Qksv!(XCnldb|$~HG)yfD zSA0CRQe!BoC_~p=48MDX3ayP;rGA^p@&^qHgtXA4@`BX(tI02|Avrl6w;iV~1h~B} zV!a*$Rn=HR<8*#L)#c?}*tajH=CT=K^~}N{8j^q3emQUF?e{a6qqF;mxPl$CUB6OD zOv_^Jk82n=?F}kVAET_agr>c(MxqlmB{7Lfq}NWQbGv5jIi8PEUBtG{TUq?YZk~Vc zMZCcvE>ASR>ME@GX!MZ#NgyqQeYhvG;T8Ey5G;XVk6UPtp{hF<8%D#^% zR}BHvN3W}gfzYwEXi{p`CM{NS+x3H4`0-c@3W_K!JH#_Dyu_I!`>2v`1`ZpAv;WPBJm{7mr@~>lchv%I1cL;$c#_gGsg))B|4!tDJjVa(}%Eij6-eJ-AD^u(Fw$* zB+|NdW0K-yID0aenv>f|sMDNwJ-SlM<7d#oj(ocE9~9R3IFwh$qrLi&k`hbp)L7iQ z#Ps{vyCa8BzuCn1KW)cjR3TjH6qlBe)}uYOGMyMx+llG~3nK7U`*NlCPA*$7{ikFs(<`*votd3z3h2VRR#71H!lGkBm11doUp1SmRr zjI#wLbnM-a=2QnIpyT!?lb9SwyrJC1rf}npi6P$W#)pA4 zgM_Nk2|>^>KuQc;xDr!HNsdP^FXX`P{d~0PG++GVCp=~)o`i;!mRHifQ@4=zwnA|h zX24QOK0+gC+VN-@xV!=(OvNKm zFrk4NRIzxW_DHOd?yH7B7~brTX>3{&w$OcfWhD zkFUX*?g}TL=RD!_2_a^{3)hH0S8#!*Bd3pX$Bow!tk9B2AHJ7q@6F>>SiAI*V&G_l zC;^g^0;HOXNVu4YVPhx=CMToqFiLC>NZbvOP)-Ex2>FE(PzD{&y^x9(O3|f959+qK zkYLbFxDsW6a&wzS1-SW^UcCJ7Ox}3qRdyUI=B|r66GBKTU6!aeD3zAX#Fw9E+{7uo z`@#DxS+tA|U%o@s455?|jz&=u<(rkCFl^X(ZtK^Nh7Id7;+dh~7=C^{C6TZ@Mn$8n zAO;SRNFkz9Kv{^g$gWhK&p!Kv=Z22v{b{f8&fI0JUb%#()yu@%J#IPsR}QYk2wRKv zv`iY;%3|-%t=MuAmNHNh<ql~GI{hEK6T|XJ zC?i0*tO~sJ%=2_^Uk_7jw1QG)Gf^TQO1+ID09uogk;(Uacj4~!CK0W` zvPe!#p?>qGygKm(s#GoumV*kVl7IXtN;`pC&x zo%h)rRv;Ei8SywWLlX#q6OF{YV1bZH-sw{qC~OrZYPfI_0W*k!30kAXz*GTh)@{o3 zZ!M;JsvCcoloTQ(7>E7v0VskgDWqj2apdSel$_&2;HUtO3V8538iFP&5I`w|vK6!F z*{d6mjhsMgD1cy+nU=w(50f}`;v}x;&%jhcw3Wg+9nYgqt!yTY8ph}e<1tgxsZqB+ z!(W|8-SQ^Nv9S!BP|!vkg<%BT+-EC*pyOG%Xpkb59l`LT`2rZ2MgSZkH7%8*!jnWJ zVN?)ua*MEn$s}1ODM5qW(rhZsv$j{*>H8q3gt=jYE`?JZg zN)S<`rX-VW#8Of40#-@Q%)~GZ&YV7lK^4TYu*Ja8K{85}=aDCF;?8TYAb^cBHAxvk zmd`37;>XKLfSkNSDyIb5{Pk+S->{i!Gv^V?+ry)y-o`XQJA$D?ZpNXZF_LUhQIvL* z27)04D$1GMd{p^NYz2W}2xSB?tpM5s)DBufl2Vemt?%6oc=#_Q+l62yQ7X-4fYvck zX?J6~=z`X~Gyg;O?%q$ihILUYNB3zmLM>rR)EY#0QSO40w(yT~ahUE@L+h!y=#XRxoeQY@`2uz7051^!5foCvA11qPUhs09Sw8r;33|dF`q_FThLPcL-kCr z4Sh?$_1FFO2aBMvm5Ej%3{x2ODTWL(oHuaSiIQf_z3w^{**snEIccqb{tI8L^~S8{NsqF z6bfZpgi_MjvUVdUPxi(%;o$CFoNQQ&+^|71V3>lVeV7$@Q`d$?QhHS`IR9K;8}%sZ zk3EG7Ws+X5Ea#NZ#6^{J-(sRrR)}7`d-LLzw=i{LHO@cxTz)y6OW8(Es8XR8b+b&S zyfT&>?&wF}nIhVDXp45D6rVoE+f%2|sBuFkjh#sQju%t8YBoX3;NZT!oH&uknGy%X z5R{Sxyf}rKnod@Qa?E+_Rg!`!RL@GMLY+o@`^pd&yx)w{sTKu=whN`9d|WX=8I-Ty zfNEJ8yzumc+;#UooXB%%*`fvMX)$mRH(5ahGc}njd-vqIF+(YzWKgj}7NxT)U=zZO zVeokyl`^>P_M5or`s-M@U?DAAwB}3%I-TE=4i}xvBToz`yL=^T)u~MB@~IT7R7z)8 zV(9bF^3-Eb@al^%^5mdCRIOZ|7l#huo_p^kr!Y#pw#`V5_0VsZEkCWmL@5(Lsatua zvJ8_bNnCt!H_8rwnTgLn#$}gZ!Ndu#aqgv^shpZZkBgf!ZuGMl>RI;h*+W5*#;}sO zpz~$idf$`OuU?rJO`C8iC(PAXv}ft!1-vqEJyTwIo~mWiKolv-iZl87?AUpb^pp@e zCysOE$YIQI5n-)74DEP$yx=m?I97o3FYC(4DKmI`$`~%~(wW1ji@DcbDQY3m+x>?Dk|s$6_tM@EevPL*__QjG?j%soNx?&lM73R(Zv zIu&TCSogzrZtY*4)SRspiwSEFDbdh4Ml_b!U880;hxYB{^Q9|E z3TDu?eO;>8smz4o!+4lTk>}`G&sfRnbn4cPdj^lCL5&L3uTzKI5`%6R zG-AY)Pmz~gpJyKLPr7A*GO5|N9i6+J&%nO7GGM?!LP?6L)24AMSMf~GYY1svOIa|J zuH8G6Yz67}@IcCzewPb6Gy?=v{ij+uEX+_DhCV-*P)a6m&7490nN!qm)ShbDnJB9S zOgEF3Kq{gH(=K%FIZh^8Q*QtOAOJ~3K~%uy)7B-V83q9_&CH1fC};$mzm9a5&1`1&jFl`z<7utxo?(AEs4iT@V#~T!On?1F z>eXw;iqAghrkk!}`kT{;Mx#`!P?>6#vZ+zMCjB0~o591zGimf#(n3Rd?5-<$?9l-{ zIb;}j1bq{(uW@ozs2!mN16Qk+l+hpEe5Urg3@Kn z(XnM?%uot#&b@$gX~`&pWLKy}eWC~f?!5Ot%s?9Nygdy&kj71S+yT^zsbW5muTmlE zHgC_;g$sD;)z?|GYBl96)}ndywgin3W5x{Um1#2=_xwmIRH{L<77Ym)5Db{?*|(cD z>(+DerQNx&{~(f*N_b<&Tt>X`4v#-EgtW}kTzyj~3@e4E&0A8jRGLeI7D(aQ(Gz)Q z^eenQWg>U=>BE(sE@9B4dCXbxA>pXaHNCE&dgW{aB~dzE(2BH>MzBarugIw9pJ(dS zH+f;)SklW^r%9vwD3umJA$l=9%1Gwsdj=3HU6ZK3@3@e4!EgMrIE0eU+mH2e=M~r`A60g1X8lA7`$sKpzO0ofc?!TYZ%xuQL z_!5?a8+%_#sWgMm-LGM~Rhsu_&SUw~Pift;6LNWb(lSa>t#Vcj*HDx}l_o9dd*40m z-L{Q>*Imc{!^fF0ejG`b%{d(|AuTCHh3eG^mN*1agi^}WzFl+DgAUajw_@>!^O*d~ zn@kuto@#X))2U+{NDKXTM5C-s9(!&KZ@=+2FHV|(1TyG)#bt<@MDOcwBw(1#{Advc z(U0kL=_Q~vhB62Qf_yM@HUTq*apNb@q<(FJkz{VV^#)#^Gy&6z(x&yfq??LzRclbs zEG7gfWl+9uBOZFVKl9#ykMb32a&g-MjGr=<(G%a~`7sko%}D2}8?PZ?B~i0(W9%|n zuFb>{DxGhRFNd3v=>(4wxJ4SFz|_IsncLFAI+Oj zakQ9o&%Ka7clReNGZjmqdF$4c$}ESW0(8FoG6oGe%_oZ%(yCcq(vp)C#=?J|C>0>B zbT%Vin8b)lFX0kdy39Z(CG0(P09yqJQNp$zTU}L8G^jKN4IR!S&x~=E`0yEi-M*1i z`5K=FQ4FY1u_|4zxs$Ee+=jv;tX<&w05<&wKE}O|JVjI~8dtrX<2lE%jU?HoR zhzv+ZsT58fKg!zgekD|@A`jeiE2*YJ5#;sv=U{uZmY;m_6&OiGMWGc0G*qcxletS4 zBaVqOld(nd^3*B3JoR;=Vqhvi!(DUh0}pfS0|SZTX3tw_ZtL5R+xp%IMi9@3LQtZ7 zw{bICTzH!}mvG`}`uB_}pREcJFoP&7#QB$A&Zn1j0hNSpxZWW{1SMh4>(qq~m-KMs zy3sUi-G+mEx4MU7CyIZfRDZRG{waUTA1g|`NS85G{J2Z_j~t4w?iR!kGLDi2YMDCMB0y=^5Ij& z#5XvhZ7{5uJIMo;`KyIch%D8JVv z-fq}vuZ|`P<&=P7g0j5eJU8gs@qnP+$ST{bpYr075rr_%JsXQLj8^tc?^7N^3W<0@F(X@!l^!&#&8pu64(~ z&l2${Zam=c7~90zQG}uk81mS&M77DN31ecGUN`bD;$7!+E4y<<5yj=3HauIB&t+qH zC5dy)_@g3br}l6F-S$ponTex5s#xE~UFq(y@jvr#llXv$|Ickr5$`Zyc>Upz{(p7c z*4gs+Foyi}(@>-g!WrG35UH@5hHHckNGZK!e}9i1ys<%46qn``ra8khA92nd3X@ zcgu|||8^_3vb=V;==0!Xj2b@JRqjcQa`WTFd}l3qDB&F6wV7+WcIVflXRxgdI(F*D zkde>PqFz-OB_UyTh_eGJly=BHv4b0~y^U|SY)3q%CQPAS$98DoK-p%E0+eJJ`uciOeOq|Ye7qx4{?SK?=pM@LR{)YTuZ&1F&1TS`!LhZ$@R7XFDo}j>%UR(D2{R*x2=3MJ->3!t$r$o~L(bw3K06HN z_XhDlS6pSu|Ic4c;+t3;H%-MRI=D#@DyCfd;4}@g{JkNFb)#`n~DWOu7AOdYhy6#)uyVAzppsbclYqg4@UO z0CdwEM;fKHS8EG@)W!}XzH05Yjndwji23#7>V;2>=#MG!88%|$|35k7(IpK8pXkf~ z6o|3iMDf>@7=mOBv0Z~0WMtLhgU{A^Q_<}?H$K{h-!w>6s3mrRe~ayfYPuuFK@-Kqz!4W{`Yd9%vj(ph zo*=k~SHtn1?=lR<24igD^bTk$@o?fZLnY1-_uANuSN@UCFH8KWZFp_^?;2Ao2Evbr zaSJYftzU6}q{J0rCB$%0jaVH#^Izc;sV?%qM(8}1Q8UbxZ9AU6t445<1@PA1#8F3gd5g$5^# zySM}pOWdqHE(h<~eqFp0 zipJ*{^<(@LZlHc_|Bs1(t=H1NGUnF}#)hTezka>MZyU!OgDz0DiEqS= z+hruS@g`*XqHu&bT{L)B+k_2GY0uUgXI1f!4gT-?H=i1~>kmp?1=>5U#-Ijc{T}O8 zPuWT+%-@iI)Dn2|!{(? zL)_D&KmUA1(OZQ4qnSSzILpe4ODj10~uL&KjqF0!o|_Jzl@WvbxVVz}pYJ zl1sc6Dxnw%61&A{U1@ja&mH6ykrTt-f~N9rpsBR z$qDsK$c{hT=BE=kAHSGq|NSo#A1ipnh7DA%T=`E+;Qw+t%Mu8mU${sVHupgn(z?Q1~0D&8F|x zV*Dg15|y|e__Z;;_KSCt0uMVd-lMVchPR8wHk`!$!&AzM zlACjsC7*AiN3ULF1pFk9L<=&$N|4YpUdg?fBA;)>cU^n-#^1Qa&vwGaKE}1Yp$s=} zR#c4Y&+=TXZh2k$I0wMdDAPX@By47ImeS%|@|6EpfBgAMvTxr^jN}J*905vcR(SCndPqyc^uNDM5+tDZ~LB&juJ95-7BGFbsu~D58SyHQL5dQ8WP@WyO?U zg|7g5j5LBbz7s4^vG@BS3TKD(#}#{ir`(?6=QmPpeevgOme<+UQy3A+Hn1NE3 zJA*y+0awWo3;~e-NC)o<65gs1y%%ikpHNP@x?6R?ijcS?7vlmzfXMsjvKxZ z^(I1M$V{TRVM2bAof1JC0+=Xm#@ZZjj2hw|#~g3^8RA-6wKpdJuJS2`X_`c%5oXVx z<(1iA*W%7@_uu#^m-xs0=GT9_IF2``M5tW3^1r({f6Bj5tk~#HoVkDG=u`@^i&(vM zAv?lVxT<$g(o}o{SKc*o^~{K`ChE5ZjXReUZ8yH%Bd&t^^jHRqX3eK!{U+3E(wrdi z{X;7-6E+k7v?!iy%kX1bAbxs}ol^Y?u8?S$rAt1dYRikLU9&1l7%l}^ten2f?W{(L zJuklKD$jxwcPpH2N%GqX@ZuyzgvE=NaQt{KU3+x<%^Tv@2j3atQ@$zj*gX)Si2eI_ zux9lJZoQ><+@bAjZVLQ3N4FLUyvqq(wef||?-3hcW$=}*m|@c2486_YRjzcrb0p0E zJ=+-b;#4|Z-ix$=c0s|F8E+Bq#zdm>fEMK{b&ez>YQo!e#c+s*k8t1p!?^aIr@7>uI`J-2fN%Lye$Pun zef;_A2SE5XZTCB^3psJ(B&SZD!L|*OGD=aoLPb(T7CM^4?)|68u2PeXkiv=Nv2)Kp z(#upQyIh%A63ZVUgC2b}Zo%`$j8BEc! zkKdFvcIfeAP{Ghf>@<~lc2eT@ll!&r!QgkF`(Mfa{rj0cdo}|H4*ZQW{+}sYyL-># z#f$&lMfp?y#S%AY!GHhg_78{{zBNUNI|6WiiK7w*oKF-CN_v0&*I?1T)0-h5>KIkh(BiWC z+OY*+63t}p>ZQY8zgcK8FboTAN6-inR80MKH!+v^-DmrCVmnqCmoM2(A`!#F@vI6; zY_NUfK@@Zt5#`n2S5+O*F2`^L(@(h}ZifU#35qa|*H&Q<-w_ee1)w5m1z{lS#w8Hr z?GkdcweLl5*Pt897P5dIQCBjQ4QXzgvh5=Chn!~!ffZTf~6Cr_f##_eYmE(fwZ zrhKMm(XQ1MDM3p#L8W%Z58JerKUU&jx|@#ntRxyoS!gQ-2g?PrmI$K5UTwk9Zn%Vl zo2cZrsYa<(F6nYP*Wb{SfO1ee4BE!=#vO*q)-7N2^5lsWMnMz6G*jr)w-5E|WP2r! z0ui*1r%j+VE@!tp?xQGdKYmL)h-k0fU6-%cB`jaEfIIK)$LJR)GiAz)4C>dH7hjl6 zPEnYG{F6NT*yH@P?-aIuhM99e;_e5ZX7`?hC=}xOi7x*{#qDc78Q`S`6MJu?k_loUZL+sk$ zeP-h0f9HGuGq+7Vm$w2XCL#*0<#(_D$9{YpfEzYsV4y|0inB8Q#y#SBjtmS;Z>=B} zhN|$gbhSH99A(A~4dTs-f3%!_{r>y){D14mFyd|Sr~Ka%BW7>|MCMvbUYE{ogl=*!^~XArxD z;ZHn9^;(UoRHYG%7Jh`X9j@)!i;87x^5I9HFze0N82;4#7uXeC}mqbGtJE2s;3amo~G)T&3V zx(!+OxqK=>=`HXvRD2-~? zB|EDMvp)L7Q^?~%;1K1fbzgAqx$P;PU4h2U8nbBm3Ze*xggJWX5Iwqfqk8q4Jo@-k zC~@K#QhLY2KtM%RXO^Ml*lj2Xw#c z296#-9c!q75`NsYjXG6pQ>}J0_U+%#sHYyGa5j>}U}O5AEmXTW+Reg$mqy+dZ7gcVjOX&Y4BKR?VqUu{;C&-^1N^ z-^+qUt5LxIoxADKrVZQn?BJ|fsX&mY7uU|{Y4jrgotp>wJPQ*QC*i4`L z3e6ifpj`Q~oOj-Ne7kWI5lmhjJC>)P9zu!Z=8G#8CGXTxCXRoZ2M0dIzS<0qjim%z;FG1xdHJn5yfyPf+P7)$DmZ3hy2d|G5;w)TWeN-u5%-|2EboB&JC`Q>DA6d#HyWt3J?&znR2W+vqK1#vDER0B z|Gi?${|YN0{Cx+5KjnX?#DjqZHzDK?9s{l`&_;>I42IAsnzwGtthpbuWZrxH@Z~4W zTKF+`q>!I~+QO)prt#^b4>-KsH)+ZEuRBel}t( za0sM`)t}5}z>tXy89j-2-+hDf<V&s^~*m8E98VW=gGIinzW-MC8&BvcCBJcDmMhqW`;}o;(iw)d*_du3^ zzLZPPZy!_t{G2{?gp-H%P^o4UmahJWCkOQ9vB!t9_h=qR4s54W*V{O^^L5OdGZTIM z029ZJ<#g2Mh4C*EOfJo5%fI06yKW^Zq)0NOES@`!m!~gc!qhhz{@g$YKJqwQw;iBz zhi_+-?0Ac&q)soU$0%y)8i+w@Uz9VXK54I4>zopV^ccrmrgXL94!Jvm-n!dE~1Ox*^p z_t(rIIo3A&ZM6+%CHcFMvqE^-F@f0TIS#$Ln7SDNu$?wc##7nR9>Xa8r z2|_^UQ+#?q_YZiIUN`h%<>xCn^vgz;tyoUSOS`jiCW<%pEG^RaNd3UU4H!a1R9eX&Dyc*$BlfvWEKR9i5BPMU~qKbk32JCEVn%L z6tiZ&&-dS~<=J6lDAEpVe%MOKOS-XgdNYn99$NEM&{K z-(Zz(O8XXVNVft6tPm;X(zv3_MJ!+VG0L=1kuxluGm}YEmoVwYSEy7jgryP^ivB?H z4d!S8r-Y*8J9*;qL9G3LGbJS_`E=Q*>^^i9jl=2FhgtgRLT1iiz`E}@5Q&zsb<4Lb zm_L`riZTy@L=oyYvy?{W8ok5N!!$G-cgD1+i!aSMxziHh>D5~D1i zJ&h614d+nqnOMTw-!AFjAxZ%ewr^R_z`;XVu>5PB|Ki>_$dt|2&1>m%*Zq9((Q;Qw z_q`1gVfWVc3>-9=UB`-J-VxVV;`QvQOtBhQfQVLN49LM!32Lq*O*q|AWs|47y^$RwB`xS>zh52l;!|uJu zIDRI=Mqoo9;3@TKpPOBEJXkDiiAIw|G z!Q;nSHE#i1f7#C1v115?PqS^;Q4Z}t#`j-urhE5ZT-N0RGSOI^VE4~I^X-}ye6{u) z-gx&d8rH4MiEUrh;jgk8V<3dc4O4Wx7X{e8&}3R%g081U>EPUaV}?uUJh966L$ z%^MNYhe@6J4R&#u@4onolgAJ9{FsRtb`d!_x%|3oFV}YOM5_*$o(1EfwZaM}Q>jt~ z%BCg}J(iE5pi$E{G-+6$bSKQQJx7@F?mPUvV<#u}ALPK16ZjB7Nr5n%Hhssh+xIhR z(j*Kg%;6KceD}i-mT`tE7`f68T4VbL`*|9(r~h z4J($VYN-(I+I3{h_FaTk3gxn@(7bUAltehEb(j?&KTmPdO>Et@k8>`(h9onHi67pi z+>oka_e1~yAOJ~3K~#mP!=`V(=jxm8r1KS>DW!|4U#ljjl(2d8*R20xGhsr^pFNYq z`*xD`V^i+$cNsHYdx!kfd)V^JHmWshPik@s%5ktT5ec(@|9;+ne=a#E_i#KXhdl@O zk#1Os5uj4#OtQ=nI=mMUl!9G9|3vw$iuAm$C)uXS!}sLT|M5ZG+y5@YBvCoLGR>Mc zq<;4GEWc+cX9^1G)~h#Y?H)KKia5pOo<2o#Mp;ZN;AMom4Atl;wqyxSm#bK57v#ykrt_ z=Zeo3<#@1CW-Pqaai9IgI);v)&bYUxP`h$@Oe4yog)>>bBTA3^?2Q#V@?$58#pRAe`VP$gt*J3yFlK`t-9G>w#+Ex7&0 zo}?t^g6Sx`c5LE>DQ|J~beP-kxSKAWI}(sE1;-CDdcvD*-?NtU8S|G?xmq0_9QYTiRLUZN54$C?J^z1;W%Ez@`^7pt9#H+^ zmO#&ph1L$*wkbM!jJ~(rM8_U?F{JNvj2<(}O?nhJ(+mtSAQ%i_I4+U^|*nO33|G6qYhPKGP_*Yu91uu;FA?$imPjfy``l?h((E zV4mNj*TdTs4`sl1A=8J0+xk#yvd{;L}{Xt z;+UgaD^QjXePg-xG)%;fP_tGIhK!#?>14nRVI_qKnP+3(c|l0nVVl&{G_STE+Mt-2 zX2{)SOijR2h!zTq3h8p$Mcg}hC?O(kRmF35@xZQ%&jDplq{ZV{g> zT}sR5brBINRmkSaaT6(DDu5kTq$F9GmJ7vWJ9d20_x_C~V8mjDT$he%nS?A8B2l8@ z2!TMz%}Q4g2nGI8xEYp?LL4DlY;(hP*U|gdJ|rPT%oHk>OYw62jI%6f zfq;S5Q5czf(`40c#ITWLcyG$fM54CqN;4FZl0vi-<&sM}^Uz}t zVBDnXZve97H*BFQ8~75=AKkG2Af{2$?9uMjQtbMZgNVV_ZVi zt5c0sImOrOzGTbx{akm$eR14zj22#5D=W9W0kx#^xqXjG>({RU6K zktoV^H(3`nzzqb|UcV}>2nK=#yjZTJfQ3ZEUhI~I6$kow;pDm+ujp~#wSI$*{1W+2SHHHY0l44Hf<>J^HGn7htnKGmrnnuT2RU)ExiYrEz=H{>yDHCjxq((u&7f8m%@nyaqt#?wy?#z-p7 z&Ar<3_RAAlv348x-F*iyOqq^Vsu~0OT*mylvw45cLIyrMkT<5!XY9xcj2Zqguf8^w z>CV#2oXw2<>f|5K+>>?~9N}2*o{3;nZT2N+)4i|Od%TGV%i)E|WvvUuJj-J9M znX1(qkeQyw#!WwB6ChktLg{3Mp`(P0&hXXRuh{y_cHVmXU24>>Np^N=^73-2UZ)-z zWiu#WwiK2Mpp-|7>nYJjFi0ppjrCuxXX~%~IdtR%S=Fnu@rU*N^utf=+kcSak|G?5 zpbgMIW}mhxon4uvP#Wvju0te3xbP&UfL|i>S9WFR_Fvhxf3FLy5iKEPLaTO-`Si1oS-*Y@yLRs4$k9{S zflR8_XvpUuy~6GvzvBIQi%G9gg^Y6L`DWcZoJa}b@EJ1Ff&@%3brj2pBVZ*mc@WF; zRdI_43TzvNLG!llDLB55Pv6yWClGC5 z1(Imlp*@Q}S;pbR`w?A2N$w%igHg8q`~z>j{{d%;irrTWlq!=-QE?udH*VsGpSDpH zRTyRxhW4CD${@E;s8Y2KWlEK%T&Yw-rmJw-qA)_GY0|g_zi!*iuDyE^!z3?1myDzU z=d^7?PVOP*FZhU^yAQB)#~v~=GRZl9gpJ?*#4kH`kW{KHrOK9P@%+!&xpOzuK3Gio z+RbTHr#cp4S8)Wip-3;2Lf5MKflub>>#CEqx@v=0^ExiB6 z48Gg+Gd-{Ci83riB~#*9-1pFZT;25|`rdp!n}6L+RFtP|{xRb2kx|xv`58UCbf!s@ zrd)H|0~Fd8h7~05+scy<^yQpZ&1uo9EmvKA zE9=*WVFpAimOL?Sud zc;)3>(e)}e{&En@OyR(`pXh#J7g{!JP5;M7P@rM^rgdD`qZqFI@0=rp8T}y1g0`jP7aetJW1mQjp@|+ zMwWfG8IcH^*RSM;YkJbCSz}tZZpTAUJkQBO4|3f*lp{7v7kohH3(loMqZT~!?0CZZ zpLV_y9kwFqjeD^&Tx4D4vrP1GGM^t+}8VYy0ov#tFKRE>yG{W zylp=t#*gEsTe>mqvA)b(_!&7zb9w)rS=@I2qg>X#2Tu-qkndN13ifGMt@(yq9vQ(E z-LK-w2kv0S?3dZOYa{c%_<=`9zfJFJuHlvE?&teeAF}Jn2}Zs&lgoSE!gal`1N%?;zacRt&@lfs*+C|N3UOJFYdN^Wf(ZoFt5Du zJUx2d$kqdeyfkqHnOWr+HE9YTzV|xkw!fHHr_G{LRw+Q5`Nf@T_2)M^&4me!!#h6LH{A6X;ZHX_uP0r-MV&X&D!;#6poJInrec8MG#HL zE?v0(`l}c+@IfxPvd93;Kr_Fp zRGR^Rd62hW9K*33n;}Dnu=>OI=y6$R`t<3`j=g(9f*2AdV7NKm+KG5hmc+gYp{+Db zOA`dN4iGS0H&OLEP55xutGxHdIJ))d&hET00|pHy%{1u$=z}=nQ*^!TQts|QlzZ?!GrO{P96_ zzNib2KQ)T{qA<0aH0AyG-)G(%uhRLVPCWVSc&gQJ&()pUa^HW{Jm?WN zu9#1c%e%1VyN$d*cLCX@G6Li+gYC#gK>k(dFVU96Oam`DzU*Td6)Tjv2})^Jj2=$MYC4;291dIf*Efb2?o? zZdlW@c|&SdD2G9isO^@aQndzj>vAFeZoG<1I(22=fqkTArqi(bx%9fM19#ta6?fnB z5RpQMsNvdMD%Wq!U+%w?=N}uuHP_xia+xfie)d_COhrIxbTkTLfl3AimT1=ua3AM) zXvxUY<0&XCbm{s2AW?*g6dY#Mh)EncC4BJVXH0u#EXk(p&2Z}>E_;hIQGs->yzO2# zY+BFVclRbmN+?~vHp|zp=i|k5Xj-e9=koS9UmImww7TFDzFf7El}qN*s74j$&He~& zM<_g9NM5dD{*q-p^ThppzhWLsmVUv?<;!?+;&eK8y_Pj!d`g|{RE{1y?j>~rL@=FP z7Jf93cjqkTg=z0Ff9|_{|IO#TJ9Dv{a0c;MN3lpst-zu$*RXWy0vgt;M5USy>E8QB z+O%xWmEF3~s$ngHwh#8tX};g zP3l&`5EId<40_^m7Q8o!gFkI%@w~YdL`xVsbTkKY48Hu~7oK|fcILk~jd$lPb~Cn> z1}UKA^g#v>8bM0A`m9>_9mAjOPbfw^`p*#8+hG_c&0C&Bx2t-Qnihy1>|D`cggJU( z4@v3eNlr<^3M#5qD$Aw~8#r_-7nM<#3fbi_h|sioJx=DHRNmMLf zg~AhukZ?Z7Po1J%wF*Rm8dbB=XA0Q8eK)!J4t1KhMk`I-`js*C8IGJj$%d^5s9L=t zmK7kmbTXEq$<47n2g9Ecg8%0w8ns1h5fKrswRpe&VWLGuoDvaTD2`}x#1YXYBH9)$ zB2f{Eh$D^^ik2cN5fLq6(K_OlO^Zm8h%OY-+PhvvbXY_j(IVn_SNY#*De?Y_f97c0 zeTGvaVmlJmA|)cSd&e(w%_Zl{>AVxMyKK>-#TJpUh_*$vBaZ)UCnAovrO3NZbg^4L zr&uDQrAR~^DG_nbh)7f%+mRA25*0^87fIB8YP{r5iHI&1M{6n4B4N=YPDI3siq^Jh zomfXL5-k*MN5potguOD^+OKJ@Xekz3L_{K@b)jfoEMc*wMBM8|q9RVQ+x}Wh#IKhY zaU2otL`8H|Y!Pwni2FWmyX~U2h?KbFMvG`|i%5ZJUF5cz)?#ash^@uZVF`l1^L`rN&v~9b6roB6DN5Vw~^5d2*(zWaLa_Gbvv9&GY6pGkU z(T+&OE2HB?+_yVn5wEW9C@vPQBVvn4REucs*Tr^6k>mEAt)rqvi`I^aT_i>M2W9WR zALa5ZZjhBPXnDW5jFIutao3+}b!^kA}t8j+A&~IVw^2nYM^H zQ4z@(N5XEu+ELMtEsozkTHJQmMP5Hd#qr)9aYS^~Z5yrKw$oaBf0uau{`ZO2TEgM5 zY}v9!a&mHh_h!oF_+S0CLcR5rLmA#ujlFW=!^4h#r za^UAxQZ=iBjC^f@{Je3Q)T`T2ZW#Q6M4S@Q(cSXWut%j_)i$#8OtBP-NK|ZZEpfck zhed~v$%`Wf$^XaRdB;gnrR)EDs;avu=NX1!fB^={h+tOCi6D!ZGiF6y1Bf}GAc_HV z)-@}bGln&RIiZLMiog&Dm>j#i>b$={PE~gg;=Sv=t9SReynaSzx+|VKbo%2g9jl1{~?^3V(KNUQeWAE5SO zdR10PW$#|{;=3QptXWUVz{(y{+M`m=y!2XGxps}b_T+7nnO-i_?|N7oR(>VrnI&@c ziKol*hAQb@k}k)eHc4tcE%QHnK`JWx$f2j4FR#tMOR}=N$h5m2lI08ElOiWmPB`OI z*%SFMogGiI3f(;}ih(b1K1?#cVhxzlf#`d~we zi`J{U(K2IKPFtcQ8=m3Q&P?1zG$efx3dU(cp z8V7|^Hm)5e>e-}guoVa{C>t$dECf%xDCLVnDI#^W2v#Ayf1vJqUAQrK9C)>yV}yfDh-Fey6(;-JM>-t{y% zVLb7$m4i|?uf6yzPtAVK=L$4z{^@yz+;HP`ax)ZZn0zHu<{&<0T^MDXqJR+iG}abE zBtb77h{=J;?L?&++8pf>wrsRkh~@Z4PMY>CEZgM&g-!N7;2@$gIq()DMp)1Ys>FHg zl_$CDfyWuJ%UCjV(lHWTX#^^(A^%0ufEI;iIf!`JiG+TmMQmx$FIez(U&Rnz80}w$ zrR)UVIbMt_FS>-ER&V5hamTUkc7t)W$7A>3%{%YU!^JYH6XMXlaw{&qbTZjtzY1C@ zLKqn^lYpOL3R^6b&t}XJ9gzqGb zH1LGT?^F8vADTsaMh-by4%IbPtXf$`p@a=*AS&rZ>A>pk|1K7SgH|R*CGmbH{N$!h zS~sj>=8ZSgZ@0s_b@~NNn|dAdSH%$Va3zK-8Y~CL3H$k(itL* z{2$8Bq^;ov+-Mta$Yt5`YKCmL4_ylLX|LbFsU8asW{3uFCEG#CB-IthA}m3S^<$aSr7q6;Lpv22u>YZ3p)5}$P>PuSrhRYpp~o}&uoG}`Qfi#7l#Ru|Mki=(lN;LMNd)~Y_}fnO zpVZgO^6!IC7Bg;t5K%UP28%**?5SsP?5Pt7)KO&9v!q;7hsB<4 z8Gs^*{ZoJNL(#$Sn69gW%-fDAEGYPJ{I*t(xx+-ureGgG9W$}JW!Zj_Vvv&J7cHdB z(5c`_{gE;uDW+AJtip26oNz1?&c2GhwjE4X1X|o2LRJW@7@)9R^S*eVV2LRNLTqet zK@0`Cq?XM3ARA?qo|R8Uc_E*?_Zp|1@-s_U*U_ox5P$G+2&uFLNxH2B+p-xkas>Bv zxtyCWJBOPu)kJY99c+P0qkFef+Se^-)S(l(cJkSDec)NHoqP_rWM|M4Rows7^Yrc2 zB~gg$SsF{)Xs%wtgtIQDy20VDTdw8)yQXr;A!8{m?!pDiVr!jJ`?dhDSIefoe z$?HCl`|iGnI2kAvGw-Br#x}>c@hp{Kfv~VpX@wkp#9>@H<6cJZvpb>8GJ0(_fcIXz zmvc`$ow@ISj84m>rAd(+$w0Jg^3=sM3smvYUYLlL%U{nqlL>#llpe*!xX~!NT?R1W zv{PvMjNW~R^6r=Gd1A_O^vv@ZI^YFK>I4^uGFWiI;aA6_(rJ?&pH5>skZrL%O-&M+t(HV z03ZNKL_t($lXlsBFIPVBu~Gowe|6md?q`#IQt?&dXW|dVQnvo>oqo4zt*NQ0AvZU7v)`{@zn<>hy93bH z*2cnx3mLZUcA#tq3>nDw+YX^q=kE0CGmw#E#BYwVa(1|Sz6-i_7eGVWuzktk~dF9z z+M_~dPCk3>yF2MNhzhaGF1s>xNFNR!u@8N>-j?Az59R9xKT^?e2M+nmzEo~iN$1Yx z3>>;MhmIS=zI*OSm+~(3?!6WJ?|%S$>^_{*!aM?vCG&zR+S=pP)W;Y!WC*=0E9l*; zf^D`Q%6|LoM}B@jqehQntIA3S^{=F;q!U{Y+n(XO>_Ud^(4|KuJM6rJiQG8p?791H zt$jm8Xs{w;J=7jN_ zdeYHouN^C#$?)BFq-WQ18k^&6yTc9)9z1}7{rWI?&>#v6OW5at(Offi3cb1)Q`V`3 z{sRWmrJ|DI!*^lCetR--U@tm#E~EdTp^O=K2)pk*jLb;j>PU{Kzo%z4G&J!2_usS2 zF1rxSpGt(L<|q}Fed$+OfumiTnp){QXlu&L%NRDKA4^xPVfFfY&N+7?gZh@^*s$Af zyU^4eW%-J=oO;IDj2f{wVN2*cU?8DTm@mKlnvtUp6A4A=(W3_?h53B)+2`!M z+n$_s>aj#@he7?fqI2g?e79%`yX`xI2@_5uGX(i1`Sj>n$tR!Br+420oOb$2G0Tt_CI;Ww%EUsDWzDoY86VmV(5;<2P=PcOjrcbHQYMwa+b7q zX2x|_kjbV)y8&bnP$>la23PO-UM^o$TzlMh^~K~5*pY+A{e`FQyA?OBi18K|_X-6S0tJEw|qBFx~s^z_?Mv6Q{TQdq5dqr4@X!DTwu5 zEVJ#@8i5v4k3a@#4IIk z%ZxW79+t8JkH-3Hrd@X2M%U6&cp^Tq2s~lhm(ep5j`rdS&%AMp22mjMHhZpzV_SGiOq4`CQ*eVyc(y&y zHARdbVEJ5!N}-gM(7#nFW03YdY%6fv*=UX7s3dhh@H#BL{t>IHs^aOVpXP!KE=W2} z#Pg4<{CQ5y{VIhgacqpVpomHUP^AFR1KTly7JrgS%n?EAiPi~kdE#%|-^vd`2aA(|*M#MuY2Ukqk-BO@kA==WOAXd>@;VF+-pMQ}jpL~XC zcic@*ehFFW%J*sp0M@+RP0g*e8=^Wtq-O5R3w(SU<6ZPcM1#T46ATRl7;R)r&^k&> zTQgb&@u0k{jLeL%xlbh~M+`rFY<9%LOaMwH6A856$q>&c1{Uz!%WM^;VdFX;d+2XG z_1x<;G`7;UTThOea6TjV-<7;@h-dDd$!9B?xbnKGsQOwiz2bW6o1@IU=^Ao#a}wdl zEw;t}*`~Gj-)jI1Nlf&<3WcAW7kp;0kKw6v4E!=L} zWwD{Ao^}-J%A`LiC4`bJ&4BjP9s9okccu1#AMci zpA4g%fI=V9?W|d`jFnYYXdmQ>ozBMEM&cU6etvOcF{d<$X#)XlJA}eZdXh}yG>%Fc zn@|a`6*NLLIH(|{Csk$YAD{cgC#~)RD$SveAM;$|-icZ+X`0@KiJoWsGG`7QmBge4o zuu2|&^dY`qvYgJHD>(efqv%oI84nxRa|tOZ$WEgzBbTbGmCU~PUTPZah)al!++r@i z>>TEQ{uyt+{2Ep`%pM1fWuM))F^TYP^;~nw#gyb&OuhI-va>Tu%gV%3n!5FCcxLts z{Ia}?t%mNv!G|A0wiD;0_uk^&zkf(mt4n@SXAVE+D7u!H^2_{>`DFf54ms{P(rvJC zQ4;0n@4w~Qm)@eTT^Kof47=_)3=y+BbR@>IWy^T%;m0^-!f`D9X%RZ+^1?IEQ8{=R zg9rBUOALZXB!FkMg%ybM*tm8Tvz~gEH5=>bzwIs@IA$c-jz;1Qy!Of*-urwZ*@Y#X zaP(N(>(}z=Q_m5L2|MgKoDri(nxYjSnky$xPHqm$ad`XnS9$C8Ik;kjoz4LV9>D&4 z@5Z+u&*QZ@bBH+^j5+iuwi(ca+O^AhVfJi(UQtc=9^Du-W-PN_c#ETsI+)HSxh8)y zR>uv~r?Rpk%*@;FB0oQer9Um^+H0rK)^s+??g0c$keRwuvIf?A)R9{x=HKq950gK%H&OG+ivxwMeWs+b# zY&=YXk z3gx3Fdy}L6{t6>WQJ3jB1_i$dQf(HJxXw+^lK^@;<$9CAG59{nT(@sB|-A0aN*iPG#nOlezQuOQ9mEQdZ@yMgIm~q>^+;aU@xK2J zYui{Bv^3Ol+2vQU#~%AqT3kvr9;IKOo}6&}@z~j=0C;HMee3^NX0Wk==DL-fe){QT z<#u7uz4v6=l&kq=>Cap=@eF1^_#pQ^^f)I@yaFqdL&$LmMTDJq8b(8H3zH{bjLI%z z)SzqbXl*o)PxmT=L97jfE|XR>6~MkZZw zIWNEXAm4vKpXX;i&AFFMAtNh;jWxB*dhRv$8?i5?B?Ul?`sGV__0{*8@zl%oA3TsO z+oiI1IgzII+%o$a4mfBOPRPNDwQ$ZEXOodx%=ObRA}cG+_m-MMgJ9VFgV!!w>_5zc zNq+9!xqc`%2=yhW=_Jvz<=2gaq_t^0Q2o%yS2M!+_?V;-204Pa$vP&sTEpUruVnz~x9xpO)>mPKA}9#vIU z{=?o&L3M&`ct8qrW^vhq5C+e9WU zy!F9H3@FPZ-qy&~Q?8}5?;wsn;b?3X$5R>Pl=fu1q1*Vv>}EBYcuxK=wm{f}B@4fx zK{C1Rp@%4S;tVXya8}M&^od*+v(e@oS&Ah zB0gv^t^~O@{wfinv`YmUA{#+Z8fcS zJ_TI{vH$2%X5h!>i@7iR&mR!Qy0sfgi=s75$}4lI zYES2}r=KDtJz^++6p1{oEsnq~_D7gf3fs2XSX)EPb5WuUs8Ml~(jcbzDFJYlLW!50 zSjG3>s30J#{eS)Hdu86MO-s4VKdGL_l+XO|bW)8cHOJToX@1I#R@(O}1_f7M0>Ih< za7*z*DgT}cJX|TqCvp7b*^>EY_@56gA}Bd z+{X{C{-&plz!L~b&uZ$u{R7L#-^e#BDIi&0%&opMh9_z6O4lg*gOycS8h6U%25 zFyUw|UV`*I=~=W02(!#yR$^b1QsW{i;qRdJjD)EH>z3ftYvG6U75E_Chxi?Cbk(X= ziQ=d&_Mc%+Kx3h-|KdgXr<&<_!Ryf09;KnFm9mPSW;JOkN(-}SYFNvLnl|!_N^mUO zC~_$H;O)1VdH192IpRQ~_0`yJyE&|Ywp@SxYd)~?So-64oO1C^Ou7CB`gSg$X59iV zx%7I>R)D6X#wp`jpXL$5ek8LP}#iic(tE-Oqy*+{RkYKIIgg zF8$bNXiuzIJ=#n4b|gK+7NDaoJoe}_)Y%10J@+Is!>ue|x(prZNlOgUY>TreoJMJW z4y(n_VedZ(^rm{ctvEfsP@LEw;t}_ZH-QjTtj0L8+94IR5X+q`6=(|KIL);bOzckpKB&i^jQ@YgMGAa)SAcYb3ZMaSp7 z*+c!0o@;Q_mtTJQckH#r{(mqh2z&flxm6|{Y$KLUJlalHW;We=bmxnY-(!#M`{TB^ z@WZNVMt2>9likEOPkl&J-9boJCYDls@$p=SY(0qMPdu3w-+jn;_dIXbOO{JC+J^R5 z;Fj`mo13_4>NIvAF^=8#+!^9+G}Nx6p|Ob>=buT$t>x+07NC_yI6ap%%cXYhTH4Zc z30Wqo+p)uB<>wM_s%PW!4P=+)^5IttA-#Yur6nfgLn#x&u??M!Ev8VVzO{|K!a~9V zs0e-g4I=ZsWsDlJ2l)jB#L?trr1Sl{Dl)UOxapqTIsJlbc;SU19C^@wcq+7+7ThE! zL|Gsn(e^g-i#t=dZUuF#YstzB^Tyn-NiQs=U*%Tx>z>E_&);Xzz%GboQNMaM-+lQd zcTc^Op*{2Ye*QviOH8u67UFRiRM-@QC|LQ^0$zXf9j4wli`_u*N78*!Tvr#&RR>2B2PCOQ4eO()c1^J{o4v0l*p8@pgSIHZ%yv2a7rRcClTWdX6 z-SQAS?m3dYj5NX_oAiQWPCnsaI#~^zb?ON`{PeR7>RoPtU}DbO;u73q|6B{GZ)|0v z3juADBs@E2kz^JleqZ-Bl2L+I4vD&ez!IQH`}4W-`|a=OyZ&sQnCK-qe=6gfxwZg` z*ocvaOHeH&!^FQjb8wBpx0@7u1VtFXU5)Qo@ry#N0acil(mww4 z6r=;4RRY_YW=U?3opQgw_F!(_0xz-g_@;u*q(4}jM;*{{sbsPO+Jw$UVIph3S6V4M zQC+>o{{VAQm3NdKt_B?joGkpEck6d=uRa`m!PR^e&pVqcGeRkZNz5{n> zK)jAm=e)}~r=LPvQCD`~Z8!Ga{{W`WxSdJooKL*51}~#C3fQV|Pi~*}GW+at0G?Qc zB*qU5f8wKg^BJ^T374LCDOqW7{@F*;y=x~fIQ>j=vTdrXH;|E$NpWcbBX--Gt1dX3 zZsp}%Jo#u`m4+n_ox1kn(1S*D`B|rtS6aZjx)>KsyPa-@g@i4^(|!W5KNe>I@4xme zkG$|EcRunc#g0O$Oor{U2SZ+ekMsU|DrtpXDK4vE+LagJDTv}wR@s;7mrdmC)6S+- z@k3}Uj2n+{W{n?=DHa)7MRY4GW9Ibf+%o+<#vZUY7oRqsoT38O*0yuzq-*I~+=+W` zp3KZ!?_}=RpOBv0g;NgQi_w1>&5SEArJ}TmufF+_BX=A_B)fnfJ$m!%%Wt#G z3!29sdWh;ZYq(>^G{PZ^J@(p#(MO%Y{O>R1+zF=;$?HPj!NZtz*6~v|r%|8@p#Rbd7lCx@%AxrQ5VypuCdn@1$<(9qCG_n~`n^aRD3I;1=6r|0MInwK}oB2w;jvMVnak%W85vb)~!@ z3s;NpzcKu!0n56!Y%B@#zl`FGhr$Ua{|+i6|M+$N+Wdh>0Nuu_)wL{NTf??H3?<|P zMr9>=JAX6A`8#a$FeMn7%$K4yb=50bvUCOIeFo5_xG=F*5(xfTiAeukGjnBXQAH{U zH-#suyr+IR2z;s*571h06ex@mj`(5vMAdo9NN+4alSU{(L?OyCK@Q{q4MKhq;9(vIi4tgUG!KRcbQOo#f0cAA=+&L+H9c!nywwA)ud@OCTVcj~?a|+N}5Z5CwFCQZ$l3XvF@x?==m4^B# z&8;q_owLz#p{}lpc-$o;E1TThJS^pbZl%7ViRM;~wj4?da!?Ybwyqh^GoFjQ!UA&A z!!*{{(WWg*^D?QfsU;(?h*&PuAB0U@lgj4?gya-$DPq+UuPv9A+`()>V*F{tP!#s8#bs|^Y_6YkA z$mOK-F5{>P7jwiu+pyrvd0cVT)hw#2 zBxp|*c+$?JGp}XFZI3bS;U^fi=gx#ldMHyt;J@2DT(x2~Pd`1I$rql7(HsGDXAZ6e ztb5wI0TG=n=<#zlx9|l1XIMv`z)e2tqtQEk$~_9vw3;1ky6YWMt)ZBzhK)%-lRObMnll8VYhFex9^oIbljVbuvh721*L4F~5`QYj(P9#K0X%>(=7Tc}Wo zw6M`M))K}EE4p+_Pw!mZ=|`giT1eb z>*{)lWfpnn{k8q``}MJ6`GpNZ=J>yA@0Jcft5+=Jf(tKZ`O4LFDeb})S6@Tl0sZ}= z3>UP=tIs^kt#{o^yEyE*?;qvS5rm4P#K?4VI<@M9)T%3oFHS+cR zg`6{S3S$mBh>OlY4TWOCw+lG($YaRL$w%2~>^J&AuDW0Xvz~a2C!c(p>iQN+dJN*a zYp8gKPkv!{uDa$bhHg6uCsEV>uiD02?9Z?S2vmM<${#KmqCqLw zyzJPZoTOL@;M1jJE0d37NSJ*fph01we7XWG4=sjN+Ok5R6k20S|5J!u3Boy|{Uq;A zNQMQog2F6(6R8%0uh``?%SGcLPOGb|2(?U~&`1oJp+UfM)B&_4wIF0Z&z8 z$dlwcS^42u&uwPohBde9eBw&Mhh|fQjq;?L}g_GN> z6wWD26#gyxO=Y;uf^?X~)FgJoaiDx++n|at!4DQhixQ;OJ{(G!kyM9pNN`ad_8xpxkzlM;T+Lqz{e{05zBk>j)sE;ZlIYnfrJLE*1WFOM_&o;(SKg{QjyC0*zp@puM{W)^{ zc=}fq^4(XTGJE!mtXp4$la|Mb0}o=<$lbAYoZ3}Y-1Eqz{Iql#k(?s-+Iv3^J)pno zdCEdr8s)|K>hsTe;@KBzYV+7@-;o@6;3(28Ot?@5V_}?VTP^3GdlAh|QCw_LA@gJMOvbVV10FV(Qe%WQfaaFTKJWfB%4tydn-h z{BXA2W)LCkx4e%3$0i!12IJznEnIQw)%57upXoDh=JnYR^1vexbNRK?$#uXcMompM z4?p@W7hW-qZe>MWb>Sr5dT%F&5AMp;tFGqYQ!i%E?fWqOk_))$p2wMX$pk)m>lL1O zb`CABLz@m`wC+7(?J)-R>C2rD{tZz!p>P;%iyd~`gB^F@6YaHg%3r53d)5nFIr%iY z_3qDgH_aq1Ba?^ke2f=fdX+xg^e4wQWZeI9ZM(((RO}ZV_YeR=3rZ^)7u>{_w z;QWXIdcM{NN+na2t(47z88+c4O!+;Pl0p3Zo+Qu;h#wSzN`~1pMl9x`C5=cp$;|~F z2RTVxuOb^4Px%I^2>7Xpy8XH-(@CVkcS%>r} z#6?lt8e`#)KT@}D2)3t*X`3a>R?rfMczd+Na1=b`4I8U@W6oqX>Mxep@*N~#d-4>R%)^T&fD-yOD045SMb%hFR^-UGY9S0ACq|) zBQ2!);^Vm-KJF+QL+NDMnn&-ypBo>2o|BIpO`7is3KlRTu=J;&Xx_MyWh+;)p)H+$ zgDQFJwJPqq<2Jf>%_l1@n@8@upQBGZhP1X?WlBgBIRe)`y+!kJV?pd7DtvPt)U_SluLq7evo~cvL;-UK(Vza9B$QHE_(!BexJrzra{8d?+wjr$7)krs|S<_NBQ=u?_nHG7R7$L=G? za@etxu(juVLE^NvG?E?)(a_LDL0Ku`a0E}ebnn^;*NgMx_dl|F?M8;}uoGBNSXxAG zK|1SKZ{*WOzp(F^(L^kJ%lNRxfE3&l6o>rLW(tzxJoVrmOugw|;$So;%|-ZgsPT?@ z0V49rKDCeP3~;cJ1oOM%i3jfGwYT3Psy)8`^h4%-HJ?}_Mi@+~{<2cMl?0D7#D)-E<@p!M4U;m07gp6Mrdcns-;|Y^-Nk? z+KtSlwtNk$lv@w>^`D3Ki%zg2h%&1|&l7Cb&Wa^pam)#4Qd3vY>J>ln@|<^RiMk0u zVXiF*BL*tr4p8$v& znjK%0$lo>qIFh)>)Th+Z43IYP(FBLIBzet(cIyCll>aQm44NWd0O=x|hxR5o zPtrqYo`WBDL(r}Vx}62{KjHPi&m-n(YB#KmRx9vSK)K^Lu+}8y7Jt=ZTkM}`ia1TRD|zvyx9K%-DD%Ghig(_6j?9Rl zwTJE4h-hplglG-g;-JHh=Buy1;J6cy#qxxrqOQF8_xE}2F-A-`{?n z!F{@e69LOXi(qLNX{%+<>#wr0u8CuhK8BM{IML8-&HIM7m`?QffVMh4Bbzzzyu>ZH z-bhAP0sH@DEXSR262~5UB2Pa41Vuh6dJpKwv}-Qm z$it82)i>vwbO1ZdoEKhT%H>liFUch@7hENP#pfS=%7qt9rm?n)Ze5Cq2U^tsca6Bk z{za@qrM_iZe|%wxvJf3-?ed>kRbA(&)O!Ap`Cj{;DjPH5C8W_TWpp3?q5{D}`(BW> zE0(dLrUtD&zWeljKKW`PvEU9MuiL!FpLXH}LDjS*tKCKo${`3=m zSi0V1uSguF<0e-T&?UYl!ioi7&u7jXuhW*O?$w|n8qf`h28m-r>!w|emb*$2RS3!up9bDU zi34%}{uJUfJzGknl=gF=0(UPyLn9!r&*~2z7H*)&DlshWCbXYjd_9K_U00)&0kT?q z21F@*EoXDD0nKcnA>aX?@7+_PvBVr%lqu^m$=U5J`u0;^dg}wC?Jb;t)=B(*?x*G+ zOaq~GJOT0&8nI}UcG)zoJ~*ESA9Tl9^!<07eByX^-f0JpI_3!8oA(iMKX3E14?g6$ zBafh_xeh_|!TTRF{^YZ$t!qTIHk!}De_Ja3{`V#xv6gz;T7~qiVzLVg2uBolK;Dc| z$yFzKQmL^E|GkwsE%mFp=IU$6DDKIOnKLNsR7zHEDdWZ+LQzRMUCYbZbyz><%zm1e zU;cn@19xHgHWmEs&YPGt@p4vG*OQhOLQ4x;8*TEynGGI}qw!pS(WD%-)@Zk#`lfnx zIK<+genC0u9DV$WRQ9S!DIVGUGV%Y$l)sQPQK^iaJRIc`ZD|0liMPeD9UI3V+XaV= z%xv7YX0teTg{Fp93i9*GOm}c&t+=j6VN+XIOUSVag+rJU4nsn2X6`z)#^30 zx(>yi%jjAVVfoKXX=)Xm^bER{cO@$$ge97|r}1ouk%u2ii=9h*YYQuuE+XEpaBT-7 z5&HM3prv*l>(;CTJCmZ)GCCJ#Ah9N@e*S^)=6_3VQJ4W+m2%{fM_^~>p`@Mm_6Am0 zt)V_@k&{6!GX=uT_>TB_Hs#kDdhDlMZt-@&$Q zL@bmFv(=!jnON4J+zeqw)e;&SqNa^4hfZC)(K$bzpO-A6wH-p4*>vmLm8_6r-HM-B z@XZ&HkwvF2UD;>kD0bL=S0YXbPg+^Grka|XR!GaBTX{LT=??K|6DwD)p{X^F$!z z|LpU)Z0hYCG-5}hjdd*jVF7V3%7U+dWZJarIq%AA$;!*Y^3@Z(EhGCs&y+(>Q7Qd< z74rVq-!SKuS1C(tq&291Ncx!**j_82Gtie|Ls`ij&wy`Gkxsrb7QyDVT6iu~j`D)1; zy7%6SEXSsM_ud?O=ongCo9WV{KM`Buc^YMdjf*0R=e2Xk)SLMDn`KPB=P_FA*Rx)= z(Na^xl~ZSO>IIV+zD*^&@3SLMPP~!tmbY@rwKouPqAXwbGb*cuBgdb_D^EPkoA11j zXdx{lop>zDlAo5sj>9P~&S$|FAMnF>1E_0iLVF%r*@g7z){TXWs@QGMy%;vAKP~Mp zJ-6=fKZHO}`CrFxWoZjb+dw)wIi1;MNDsdJ=uNg6SjHD${y=G2XVPtlmCLIr%1@)B zXCGAK8kR3xMyG--<}X;m*rU#3t8OKPq>1-GoX7BOdh*gMuhW0vHe_amfjCM+#@S(k z;GwKI4UH{`I3Vq`$D_n`9LtN*)Z9wQaS$tlWm!aHZMfQFW6fGZmSq;*;^Dd)SH$FM zLJ|o6>oo5c`xEU?27$qv(|GojKnRcdpMS_z*WX2_PDRw$)>2V9l#4Gs1Keh&Typ~( z8|ul*@5KHGjHdH$gL&<>*IBh@Bg+;oWRC+6A=<;$!W*x@Mdy6zedfX3 zdfUAW+Fq_dmvKZ+}Xcic+eo)^gO*M{&rZBf0J7JNWXeZ>b!#4NHIgfnE0- z!I@{D#fR_A;mH@@=JtmkCN1nkBL%i4KpX4UY~ZRZt|y9xg-2Ukl&fyOgI=W>y!6BX ztw2)01Kd0NZF=_XOI}Vk=be8RUw!%spUiug)isU$vR3oxJ=1XGt{-Z3S^WLCOq%f| zvmU*h&pw{Z4?q4w{kj^Sd;L9T{_PPC+Ghuzne{XcjjjB!U@=FXd@2VYGLAME=Fa<+ zW$Wu1G3qZY`Qj7a{owE1_xO{1{^=*&c++i^bnQXS>eUS0c`yEY&S@-P_$B8~o=(rf zJJC}6GaH&M?zr##K19|wq`*`Ea zmGs@JlKpla$jYA<@V8e!Vd!={vD4PQ$lQGhmtHjkFOrYd-a?C)!Sv}@(zVED{0V1J zP*_S?w=#}BH5Oz?w1a!z_-D3Z^rA9-95aEncF28m<&6i!n zh3A}s*V;&7NpDK>GeN}=C0JeyV&$XpNb_2-1+YWJ9EA||-+L1IoaRJ;2wBBlIQ^W{ zx%1&y7`6XsV&bsfZX=C0Fvj~FL8Fv|i^BFicG-O&F1+Y09)EcrS6uV~4UH{W;S987 zu=~Dy^Xwb*xbm{8Ja+fZto?ZfPds!tx8HUnnK`-K_rTxie!w0klHtc(5R01C>$vN| zr)g}pm^k4iY+Oz{?kM)!eGlf&`-l~~F?8pB$;>Y0 z>~sH0eM2h~C!B`sYWfZw%ww~jrnsUU--Z9@c7p%TeCij$!479}-Stzs;;Jcp`q@Xs zy*Lvuy`1cjV#3799C7>+j2StSgAUw_D=(ag6;7vnMSl(%xer+pkH1bjkC``3=h1K) zX`u+0Uw8}|K`sbkQ-G*E#IjL%y!iZV-gx^xVy&&XRu)%WehHS_#zXhq!8hOiK)dG= zjcLv~?|kwy(z*Y>+xX(s&vCU)tUb_6DVH_!7#L_}*Xf1GI% ziHVM`mg_D)L5@4;8fk5-m&5iOCYRlCyEMkzB-&ml<3^5?dGEg_FTXlV4m)mwY-nnc z##mh9o)#Tz6whrJH`*#+zx|vXHU4zjsI^R;JW(Eae3rDh?Q+ZIC(ETb-z^(OBNYHtUH2a=bLM?5KQH*Zbn3OWEZX2n+-nopT`ZF( zpDz!*__3_`@e?^--i0ekBCE6$4rpM#^v(F12@QNXH1sXcwAzQ)pGJ-Bjn7> zX2{B_#nQh#Tb_M)uC%(YxUMT&$Hntn#f?@=b90sS8M>#u@bXJCf8Gnyd+7eMdi{Et zKksGPYwRhqz9A}Fw@6#VDj9#+VRG7pNm3j4L?kY*+aR9TChyFCLe4tpeAyU_%PHf> z%e(KqEpg8iPrLt*z4MNA-(sq*?Rjq^ZfppbMD#?%sRuoS8XO zo_WgWBmeK_-^tliPLzh0Ei!iGXu0c8_ej>u$;Op)KQ zlZ=^ooILp8Uu4nSPssQqPM0;?lHz%u_U1yzFv9dmHhQPcI=SbZo928t|TMbY?CCDO_E3?q%E12jPHxdwMt8}Ra$d7 z@%?6LO}0oXlNIqj5z``>Y>PA|Q<65}v+%|9jpTe0&kyHHPJAyVskUZmYipC8ZAnRF zvSPeO$)$HnvMnLLG2&%fCDFW9TGLtab1kxc)m%v@T4l|`+0v!9R?htH_0r~f;`>dK zPHmS|I&EiRu2oXWR%uNnq%oC}jOUAISHk?-OM2X-W7-e3OxMx=j-4v>0Q=&$US^ zv0V~vEz+7yNivhQtA)u(Hrpu4wkAom+5XLXMtqU{{P;Ah8unlM^FZNw*~>mGf+W=UOF|Y?4GvizIV7`&;9QF-b`!c1j|VuwzF=f`Y~P zzGN~P$!2rGoqfq=+a%G}D2ZfJ5}AyoeG%iQB$IBIM6ykq5=m*xWF%>P@gyVJY=b0| z+oh$oMVeD-$rvNP81W@5zGTJN6+}ctrcIkBbLPzX1bcG7{3|5X^WJ#l4e4MB6eAz6 z*+3MC6C^I!NV(RQR<>>2&S_)Df)gX6VQ75?t=rf0!TJX3`VA*mR79}@T6|V7p2KxF z{FdgN#_ZgTS3L{_A|jxyW5cKjQ74Xzp>^kWF8JOrm~z^e88f&S$>z1(a`PXU^WI{# zBw4m}JLyywN=-gN#nB3rwQ*IRmnPAiCR$QTQKvZCfw9B-K(?9n+Z!=%3CfA!I8a$z zN<8Y4%z20tp-4IH+@s(cW2t(4!^&0b=skQAG1o=K97c^8#Ps>gS-ZB8R0f8O8isKk z9FwKBaWgmk@)i~>UQDbw#+Gf{NM};GZduTuK^CJHaw3Rlc=W#e*_w5@^=H>n;uz+? z`YgY`<@Y2hCbNATo%U-C*Y5fdZQ`VI(0*;2B z^<7D|wvfwt7;LPjC&1tr6YURX(CgQp-#pN{|Fr+8j*DWL0dpw?UKxrIp z>s}mdZ{QGgRPeMzYipLes<0u3WHO70A|8$7;ZjrEi31Ov$dA5%2|vB|8pe$nNRjFY z@1)wj_RB{h5hAXG>k1eLw2cE)P7$T99ehfaP*M~yKNvwwoT#gD9cyVxY~R4Q&pm^g z^OxZ(7lH(((=WJ~tFHWCN{VAdj7PC!=^_=SxQ@n+Y0LT+DW=$ofpXZsb~#5Mb~sy8 zLdL|X?>meyPB|9Gu`bG3yaXc-h@f>5@wgLMi9MQjtmNFY&*Qy?tMG9UW$>Ib&i~f; zx%$%ci3p$!p0enGh@!YCP8hK(Dnhh8Mu<6}0h}T`uH#WG=Q(JxR>o+|wfLcca*Bu* z#R9gC_7+!{NTdSSF^IBIQ}U^fX>A{;Xp`=u(FhWa5DT;S1!5%;kbt$%Eh6S%+n$e8 zcTmKM7sqXgX%I(fZ(&ec5s5^|)6t=E+$hCv3{<=A+eC;)qC{0la2Uj&ipFtEh`5#p z)%TTUHgpJ}!t&r<`{ln>IzYsPFfkvSC~TsKV;3jS_lXz9DeF|q%2lgzkC+G|tZhtj zOl23kCWQ}{tOnmh92fAJ{^;XWb*<;RE3RVWd$YK4>Pt4vTKgD6$YYxon#-p79d z%R^7U!Bs!|Io&%&aY=FGjkhsk+`)Y9I~Otcg{OIN<~$4#RUVmKHdv6fRiurksI-i# za+l2;R>6b;q%%31(@9DzijlNUU@=&w%?;YDMB9V}RahS5rR9`XMET6=r*rPPXXE1I zXqQrFJNTC4GEAKiF@-Ez@u{uu#FF)!0Kv~CSh03J)pfmal!F`KJ%(a}ryoLIEA3)X zWQ~oGv(Sh(=}0?KVyh*I~3lvdujH!W(oQb`XR5^km7Z4~TcF@lJ9=&@7(96-F z42z3u=VW24FD}H9*1I20K8GyKj}H$Q1%)R-KMj~v!VFjqDxOy; zbntx$p_QLADr|R<4i)m41&(Q>op$J@pXNi11r9HS4is{}bwR_+pG+-KMHt%{EPDB% zc$Gi!wLi*+$%7%oQeHv@x*g&I+R5YXT4>v_HkPCy6dm$8+d-Ni-xhN0W8VMw%coLy zV+{G&vx6NMe2408y_kRBTWr{JF5kH5yIg+b9TewUShwSzAxfnsR<~{WXj`upgg4cDP-z{2bl- z4rOrvdM-Zi8=U;vBf0yodpY@xuhOr+79|-RH=M98zOl=}6A%BDhaY>MKi+c}(TDdE;_ESh9vAjyZux{^w$D{EdsG61?{Aa(;LJ4fN?-!6~Po$kji%jI+)-i%!ur zeR_1p0FOQVI0p>qK{}B{i9>05CnULpg>&Absyqhbf#1f@uDc3VR>ihW8=19z4TA^w zr{AEV%zoz`2EO_V>z6Dg>S|(2(WgfpQ}6yWTUwF~=+%d;C^EQ|mUiX(tA5DsH~)&p z#!W1KdluDQx-hh71*^Afv}>1ltu(&L*$qd+7(XR_001BWNkl8;G3GoQac zcn^+>B9g^%!#JyO3C@Q)+fYe2O2i5H51a@JLj;93*z9nkjG8!^p*O0RMH+IRPgFZ79CF4%YlG`J7#yO?vdB!FG>K;(dxB!8h`wDS9Cym+`N6e6 zVdu8>Y*@K~9W6-?Kkft?w=4#g!H7)|TE2V%U-{|}_{Fb(&!H2CgHpuHEBW3PKjsVP zTtxHEZ5)2kXqGIP!?Uj}D?)?+xMMW6j z$90^J@sa!G9}*EEl}zHeVaikf8w#6sA%C@SoY`IM7Va|ifC&_oo7Z0; zcTITL@Gd^0iWxHUpx~1r+04u0dwT*73TqJFH_q?_#uLubu>J~*W0?O%hlYfdWd*Lr zuKDO3w zn57-YMep+45codCW3@_Ipy-K^hl^_en_b3R;d5v|LJEHeV?vx=t}nz3w||Dd`Fri% zFaODsR|2)xfA6}FOgsaQF5{##zD6e6k8HA)&rSI<n#IE)xQ38!m^EINS53*_9D#`~B$8}xu zpp*M0F9lU+-#R8d6hH9b1Gu`Q;!%JWA_z+eHc}jGCkw4R!PQ0u)qPRndm7)mb%N~x@epO{+U>+H zxRCOb8G|1Y8R8x;>_(x7ZCl5#>&9J?$P97QT0FJw0{oqv9a z1m%Xc4;|_n^1$E(V@C&l-~m|+yscuv>ZpQW<`7&Q6pj>v1yJqVCj?xEbOeyLpBv=_ zo26J6U$FW4N)?_#ev=M+HV3$Qt4{b#eVqI~6&}Vq(c6tbY+WR4$869SVa*GSC++Pr zwxtr3MZTQf9^!wgnEbz)Oq!+3R?@RaPxjO~3l}bA^5n??G&D5u;DZlx<{4)O?$E-Z z2}{&@52*ytB(PNleIG($b)W_e;jucf-n3tWceOa~`q}Q%{?`FZFv{4`NPE30xKPx- z4UN#wUbt56enEaLN}z~Pm}j&bi-Dp?py>FjgI)3Ow5Yv&dIt2y^&5F|`ZO-Q@SAyq zpKWU}DB4vuRNwN}Q6>0RMGWEl2?6O*9aaN&E#>cj)_%McM%S)~pZuP=3!5pxi!Z)N z@7}!`GiJ<(>W}^M?JW_WTziiO@$g**Z>SBY~+oWCy{Z+nrSX4hZJK zDR-al5vpLJBOz4K3Ziy3%LhkWE#!Zr+I?PN?+DHI!GiT6y5+;F)*r?TzqhhGFuCQg z37IfDF6Fxx5q6Q00)@QEw|&oJB2;b#Xx!Pr4cGmQl}pwkM8NpySP3Vdb0(*pe5{2$ zkkE!wuv+A4tM;}162z_s|7nCj-+2d5J@OO~2W6o&;eqcoPWk9=%0PP zrBy-gCT}_{sD*L^XAbSh|!YIqr z5*`sD7&rL`)G=x1V{1mB2(*`I^ixUFw_iR+aj$>meE^IvIF7c+_iAsGc~7#p4X?ne z8nR&IvRR^TG_Z_#Xgow*jEW%Iw+CubHpn#uRc){Fw0|EiA`&j7*+3c8HoGkEc5wox z2ioo3)-|I7v%M&VGAi%>KtgwiwT+p)CGpd}qZW9Or5!b#b<-GJBnT*0Qc#(LAGQl$ z34@b^6REUQ)b?-^4f!qvq4T737<*_O-!q7KxC%CiaMR=O;fiOiAAw~pw6Lns&h>w4 z!QuBBF&dPID9>)ToyRfm8xzn5d|k-Symk5lY)p(jecR1EOg`E7?KfQ9ZT)>vez4g) zfP)G%kyWtOwO`LWr0lA^ksvsR*mo+M=gJN(jdosXODUKC+fv@`mwlCj>ryX7vfzH*3}46gCWMoRHT6VkB#tEIhS+%Y??pxA`hIFiQISv;cnDjFye zR=I8Owh8PP_{PJDS~|UW#37sUZ2yJC!0kjSLtT9hRYftDEM7v^iD6U}6^-C3Aui2i zl_pwL%%s7+c=NqwB(j=fJd!Ak6U9+3o-rR{`3qN4>sr$&RLo&y|2np{-9qoyp1q3pQCiR@YLWI;&e8&kgEB7UH+eg@l+wE^YvG_3ZC&@` z<2c}Z9!kXnlbztYmiyJq`9va7%PyuAN-I3y1et>SF8?io-g`=Dli={D#Y0@k=As{7 zi4IM)p_m*dxtS-PnN7cuhcU8WCsID>NQ|gs5WkJA=aZ8-I8ove2QRymjB$Y?oLH2& z)_Dcu!`UUY(XmUA-#KL$!jc+U^rBXpQv9WX68j0O}aDZR}@5r9V z@_yMbAD3vsNAN)h%AYD&cmDBL$1)11UW4&Hz))9LMtw~Mu6Sr|gO!aI3-zLXL>ol= z`Il+`xAOCr7av0=m!!HssDn6_#bJIbIngz$Y=HiNqot zHK9LcPS)npYt4j1MlfV>Ukks2bg0j#?`86Onkc~!T#TKoI`Ns$9!?}0u?n#Y6l296 z$_VLnga*-!7&+(vK!5A*DH_eN=47wPB^|nMCX-7*LC^a7mlE|t~+`uDA;zA}m;yU*=JSDHs3%P+f( zjcZnO_Lt6~TlZcJ9eoh*%vI;A;sO#{qm?)kfovwaj>aI)D7b9Zdb} z11ws$f}D0hr`fb|8PB}*8rguWe)0Qrxbwb;*wL1;7Su47@ZZ)nx?lcXMO$S`F!=Tr zTD#<*eC5xd9S5}-KXA1Qcp30bfESm>l?0AS;z$xj&br;m;7Afj5@<;y$^(_dkpzyk zp(Tw{IYd0GV2ZG0(K_CHXPyn3_cJ(>B4XNbO>5xF$)Y5UBMDqTjca_0<8j9Juc4D9 zaQrmN_jrHKVpcC-iSay?$>K=L*3Tr-lEy}fWzmwdbu?{gQV`V9-p3Nb+n8V0X}w`Jw>ZHVF#AxF3BQuG3)tP*|B9iN&*+K2e-pQ0`=jcnMrTi#8tGq;X9G$0YL4z>du%u1TOJi6Vn0W5+2u z?9A|~?^4bejvB$R`fAGY8Q!NWr+nrB>O03#zEAJ26&yUI3yz0_b4q;^MKkjnN09k9%A+XG%sj8{ql+#XS^tcIZTKhhC z-f<@bh9AUhGhgMh|NSN}&v=$uv)<+2dmrYp#~)z+c?%GW@oL{^1G9txIS`u=XM!3Q z?)fwr)OYDvu4G7?wtA~|2T@v_p=D>5S#K_2LyKX| zh=GhB)dhzXcu{7)^*)Q%?4+(o7siYj!1L2zq16;)T!&6&E~g$fj;b<)mvdOYVmq(S zUqwqcM{So1jvqgU>Q0Kr7Kc|~pUdio43*WL`NF~ds3;d!Z_M$+E6d2L9FrytWk`=w zToGP>XD#!WZziK1LelnpP!8u&4_*_3^?~l-dmUE={J{h@PxsP>{W~y&D-y-=ellCAiAt@Iwc4 z$RYihx3Z0z9_7q^Z5>NCY$0A=!r8}-;jtO>*_^QMQ-uz!jY2f)bJ(~64DVTvpeQjh zJ}@4x<1oB$6%&T{B2o++R_^4rxgSuZgz7TIMduvJhNR~1>GP?sEM@ZO!BkfYZB0JU zy)=i0oT5wT5{{fWoa#!Uv03r*%r}V(e09nw+A@a6XS`2CBE=CC$I`dfC6V%Z6!C5?&wLp@XRbWwb{)u?syzByf4d_ZD#hn%kXuKoZ7%K z69+SKXg4;zx(?+F%CvwFj3BE{95b^e81cICxXM$^oG=23od&5bNtv6g6gJzqKR zLVkJKsR*83c|9SM*vkF4-@=V|+($z~_`<1Y@uRCRr$=>p04beU<;b*dW!%t%*tnyW z)|^jHqI~C)Z}Pd%9>>?eb_qA#dLyHT_2UQM`W7=^dyCSp1G)K@TRF661j)4UlMBw| zhKsxK+uvP5zux7Xch0xjwxfyqL8JKT4Zq@xNA)5qN!BfXoyxK@CLDGQf0=q07oBtr zeno#Cnsz^T|NO^X`m1|*XTc)Ornk7{k}H|}{st<#^yIFGA7J7E{fPTMTH847ea&?K zC`EzANF|F>S;S=d<#o3ZFYd-KZo8eD@=_En+;{)|+(wq%mkt5&gn&0;!5H76W4 zk)BnhtoQBd?x81MV{IzR&YX*wN+Ob_G_E*!%pjJ{pUiMaWBoIkIqA)C5)dih=WHCX6}1) zIDXQ2RxV!83u`vgqeneQjvvg!vleo|h#@qsU&)Mli^#-lNu_)a8b6TgnBn)ioS{%t%&mO)+vvPtr||JTvPx zyl5v9*&MzRR<2I*>~k||QpI@0c<-GLSTVba?sb)nI$#`27A(SXgvQo3Ui;e{NNFdg z95eYpfzDIMD@ZbY4(co5Kl*_~s1KGCtJ>J={nQx}(ka!VQMVcob{Tti-I0;|# z*1Jn+P7A&`pdDQ0QCD8f>$4Yk~f{H{~xo!u;4;e~CuR|l$R+aPl$-`K%cr^=` zZ6WKFA<8KvndT+bDE72~|K}@#Kt7&ox6cVTwnCo&hoQ+*D84p(3E3zjZfWyy}jT9)FfnWr9mfa|XN9bdZeJ5*MdbIoU%JBU{CN@Av(&GuUx?KM;yeY34VhEBX1B4VzyMoB_4C=-=~=QvsSaQAxE2^ zU|>T7HC;R5W`)Got*qakCgqf4Ob*BOIbhTf#tyASa*%G!5jRH0B_!)&bF&hMn0Mel!A(1>r1?E27$A z@#0l9MJj1tx|-o*`_rwm0@q8DRxx&@T$1^{EX}C~n~V`a;V2QjoX5_z zp(&Xmwx)s4kM2doYKIEfW#O{Tv}7YREZM;L0rixZL|L(7Ij0>ugmk2gH{M&0<9H13 zTTNYUl>P%wz&H@`9EzeYqzix|?eo@DfO(??GN~-v6N;v669@Y~ol0V?TeFVgCyr)p zZZfaDH5bta?I_Zo(Bx^_V#PRG7&&qn6Gm1cfSYkBbp>BM8d|e#*y)jOX=CxS^>po0 z&Z3oD?U)MUOf5@?MvDa^GRELU;-r0-?db?!Q7KE;>|nxSed%26(zkb4)^FWLCMQIq z4!(Fc=1Cx;U}Uda-e0nk)!Q?;<)!S*8jKh^m$~%mUP1rUK1VXHC`HqGXNGl~8p!(4 zCNUavn&J{o@A@((^qfemhB8;t(x#}as-Vb?@%{(P*qAFL8ZD+sTMWhKOpJz91{D$d z)OF>h+4I@v716jM!9l}w4D4RT%A|`C*xq8;VjOTai&kz06$#l0akRq4;295e6fxlE zJkn___cb0yJdE#CQCdn>bth!SW?ZfCWKX-EvI@yRozS&kb`#0bv~?Zt&Rs_DLF2jb zk{^&>GL2jR_%ORG-5Q)SdJmbvnO`~$Et{G7c!o%P^4F~&y`0jCqEeD!=b%zc>`o_vDEOO}yY-AGFk&N%;DoN@e6 z{(Q@CPyukE7V8G~l3SVm_FHU8WV!jaKch*LPA6Htd^K6mpkwVbQe$Yhg3q3GB6r_< z3mZ3Y<)WWm!)J~=mQq)E{+Ve++%{hI5&-<-7eD8JFTawmHC1>Umx5c$h>1sY#+gSG zqnTOHP3O8_+(^@w22xoV7_G+7`4|yk{gP^4YlSd^Ujcjlk=CHoSXUY+yFrqMC2G0*bd5w>F4!$QA zdEWyumKsisPsE90d?A?%Vr`7U_yCTLzJ zjH9(>6>y!<;KiEtJNVNRZ!&IZSI#(bJkLEln{2X$x86V z^r`tjifqPmTscaS z^@J^(cCe+f2mO21(Ys3V>^ocWR2<_=kTLEDhh`y>P7{koakZdK7FP+L=i@7vWow&x z^@UeyiHp}vHYsL zi`iW#0n5kyUm$zUs0=<1_2UnJ&{afYaiUR8Te6kb))wMU%<9|dA@*wOsyk6+>T+wWq|O zM3o|nM^P+_7GcM>on*3xRMw+ZnE)`sV6q9sjo}oPqTM(b{NRU-9^MnJ0T}8isy_k5|XL;hWyP105U-FYtZY)MFv59mdO-V@% z&_v=9nwlH&42X6?N5C!S^sj!MF8zA(m%Hxgic2nJOPg@n#b3cO1|251@h?!H6c}Y= zLQy4@lyznDm_aO<`#Q&;a5$wA2PDIydGl$=C^~oVN#oXy3>-6=$A5eQ*In~tetOmQ zTzTyklodtnTI+=1{`*zI{qo6*2GCmJ8~+nvn=<%b3L!@>m!qarglII%g2g)+KD-P4 z>WUdNpex-vbz;ZXCf00fq@+t%Mh~oGU}r;*^1!|6%I z(3Z~8mPv5PL8BR1Tf|YL2Gh1R&5pJzhbyke&Rl%GEtJu&cG$cKa7(bXn)rw;$4kwXH(bAHjYjp)Bq*%Ln0giEq#$vp^ za3$S)*3hF$Q5DZoR_x-La3SybvRT)DK2g9ZlTTJL%DOhX)l^U(&9ZgP8eBg|Wkn@z zEor*f#TeYJ69cM>aeRZLJzT$$59DG2%c~4CRU&H z@i4r(cr|?n)pJ1aQhJwqbaoV4N7=kJMNw&-LH&EtDQc*%u0VM?(#aG~90vEPVsMvI zbk3)tsgVQ545PYOs4I_BRN2c=d)W34i)W`9Rpqv1zB!~uw4C&@geE+-OWBtZ$ zY+1jCi!Qv7zuY^OC!T$pDW{yt6Vs;g_!EzE%WZ!m=NI9pHLcC9L@PScvwJ7*yZKtq zIrE!5{>&@rqB6E^T*vfhUS#>YZ79b9r;PsndeOFi0q34Eh3{T|4Os>&h_+%yYa9EQ;1f^qKckTCh zW9D>j{?)H}^Yz!ccj{xDdEUhwcf#lB)29bu@RUnU_a6M}m)DWrw1^*Fb{&ZfING6o z+Rc7@{(ku+#kJlgWrNLi;I{mT3J(FF!%zo7;YM71C%PcPdc2OffXy8$*N+Ot!|;u z|5g=tU!jf5YiF&nYjcFMtsrX}r@ zQE}pKgtC$%lra{xRje)0bzCNl8-aEm-v3}7v*#}*=M?eevvc{}q!E1f`0;Gql41Ib zZ_%9b=s&WKgNF@9`!H|eI@axICF%LNC2N^*&;dlEngvUDuwmyi_OyItMbVJ)F$$8# zr_qZL#zi$HGo*~BOI})gq_3>9&*O11K6tg{*A(?}QhMg>0-$d8m^{n62 zKts-AMlM~kmI0Fn^4ZTH!aMVKuyscZYqvCz_BQY)>m15*eO-`8|%GG>ReP2e5qytl9DgJ9q5lBH0u?_tHYLJ5x-1{wyft?NCrlbd_ns4(_2vh> zwQvniq>L|o{$O@Arg(hDn>6`RDhzB-rO9X)BR*({veII-!e*>0gReF7mu)23(!%5e z`!jY-9}=y?3p3wk^|m%75+~_FLk2u?*x4pL`SLub96g4L&YMXzraM05!USX2FVrV* zC;1o2USa|R$e<7)T+4@B-vk%Y#eDzTtEueTl{@Zzk`FeuF!{)18Q7;D#dhlIyVJQO zf*UQTYqu_R>Ez%jKo=A5R6~9D&P0?Y_H)F~C#M8yb3`h;bKhgr`TphCG5zTmaLa2r zcJeqJqLg&1q({#xO0*$cR7P!&9#oc>(0|xaUVQm!etr7`q*G}YEZ=||EymZSoO<3j zn74EziB{o@C!bE&BEwC${E1~BETT(~0mK}ODJaHA1>ELBgqbaF)@-D)Wfh;Fath!6);W|`#JKwEE4lWDTUoqt5yu~Q z2oF8^EI<6-l|1|Gi%?X-(Z^1}i57ACSzl)P(v>_p^Br_)7qY%^?zb;yYeNfXa8|Z2Y6@|W#GtB+pz(nfjOiN0+WW_~DPQ;iOYfB&u48#Y(8DDnTiSs=6Lrb4hVha>C)e zl)Yc}%O@x5m|wjrN-KQhSx{P~_Yipg_e5+mNrzIQqa{Mnjzc<`Boc|*`ydv?HP7(j zbwH6f0mrR^fSS_-JWR0R6_$YDJg7pVa`J)SDugr0a}+5GglL8WiJ8VI9h~4LxW7Y) zb!e2upVJ|~BM>qIs61$aL&!vefS-3mDGOMv6qT_YCmlMJM`pZ1QsQ_9eC;C2#vW?p z7kEku3E+bkNk}s9fU+k?CDx+mOW$xKzS{cDY%%i=hWbx$gT5}%Mc1PK>W3Hl^p zb`JWwJHAfpoJRYZ}x`eSq zdh+Hgud_K5MRW|U9eh8C3Dkmeg23=x7Do&gx6iVX807@@^b7S=I;dxuC8~oyD6qm5 z`aF2<`Db0om=B+Sp5a7n5|ZS98!|!!4AsiI_f_Dk6&(`t*`h6cM_^GE3F>JrM`2%w z9L)-Y7TceuUF6Z%&E+Os=2p9mt>?HWsL;3uaaME~y9d)#S5?qCsN=gyrx z_~3(Fc;SV?ob1RlUf>V*^Yf+fd{n?DZPy+Na4EfH3okzVD62PZv-1%RL>YSESSC#x zPmIECBx*13cimR?uJ482(&zV976ie*dEGNuLZh&4 zrAC@I;pa4tb=t#cd#dG!DYu}m{AbJFpHC16p@hm3d$9TNyRIS#pUzAExhSWwh6V3~;|1+Q z{xOhfY2ptz-^z<`&c{;$pRkVbtxJByA(O`E=T-qh(8<>|gb@Ky;?vgB%8Z$_cz5|G z;<0khJo~GB^DAE<8n}2RUrwPORt$+mGdKV4M&6vW#9pNoqKo*>_kYCX38R8JZ6Huu zI`)Iw!(YxWeY&^n)b4HC!|(I84d^;QEsEdXW!F9~d}>9v`#*)}_%YXNzwDQN5%-T* zoJtrP9Lk4fv;4nw#`cr=!^Au|!7E4M93Iy1A1Uu26~#Zd5Vc?2qrllGA3?|(y0j-e_Q6utgcCmdHrC?+5 z8A^&H^J6ybn}42#b-(ecC=gDSbJOa zKHX6%y7e2(-`<{wQAO4}Acb`?44v5X!B10F)0MxyF$ZuFoIIyfN88dUs;gGjTw{)T4}dz$v(CQDmLWgOHDH4IeR3Qdr4Q7CH zV~&<|k)k@AxfS8I+VhF;>vbZ*3sAhj5jl>*d$n!7@mL~!J7Z|B6_t9u5z`&-Rpugf;!@@vFT+fv+U@ow z49>|B+LHKD@+EGMr=)$s^LIasb}XwN?1N&_dd(F-FTsCNB3qdGje?dFxd(7l!RWvj zA_uuESV=1GBkXTwej}{_d|!J>@#n}0qz?2!veZUATG;0_kt0OhKW<0(i;+;GO-xW5 zyTLgNZ0gKqb;#4X}vVT3DimNeuzfFJ4Em zXbA*(Gxgj0S%IjP-cRoYlj0RmzG?Dh-q})T+cdsXlugSrd3?A=U-d44K}}@-Y1g-& zxC8a{wx8(3gP-2m`6q<`H;BVeT^n0F94FLImEDp;1%~k(Op<`FJiPguBIjplh$c9q z9P%eI0woX9O091Ht*UmHexX$P&!5;ZA`rHA!H^q@03$7!P>voYj}S$0!QosE^Dllc z04}*`irwvXx5^eTC*xo|B8FpXbYi~>Ix1>oTY1%fqyr*UAw^&$7%2tOFzS|ydUQ1i znTV)h;$b$XY3Nu%XVuyEv$)DL%t=qH-OfJ1$MxNt4|IWfOQqFzX_5EwH-JOJfRLe{ zvFLEH55y*j!GXaFg>EGsS?7LLsO^e;shPU%%zssgfE8nP`yIp_rcQmsaHeI7haZ57 z*7Mb|azVuCLTcOZ+$Vdi4z0YltFDW+C=g`!eAp%wDApH6=e<`DMrRE}{iq_}&h7>5a%i5xRdG-dFFz169rFl!66B z#h~|NYn+GeoZe4PkGQET+H*{fL~pJRV&9z!J_Dd6EkRS+`-4KK_JcRnzssl{=42sk zk_&M25g5W!mv_l((}p6+osyh_cE6fzrhdOg#`SdaFIe)xA~|8)jQV@Hy8Sl=rCU13 z7v6fS&184cNMe?r)bl+AgY5uV12WCF$2}|B=Mkus^ti=BJ9bhTk64fM zcU#ifLax!sb`Y3MKkQ1J@n;9Vdhee28(dd%7+yzQG)mG6+O)~7)&v7`L)-foM7z5^ zI}8eT&wK24x94n^jh3lQUMwQrVMN8ki|;+&FI{`a1G}DdeNj^6VYxnMAs8%<_)dIx z|F;S#lx&{yY{2o|Qf9L=UmZU(IloZH%<*S0&0aJ6Hd$|1^!pXItgj%{DA-kpPp})F zZ+p_^H@fzjS@!MQWYt|$^Z5H%uiP$0sNe5wvDBBcT)Xe~5QUGN>zNNpRz{whnp3~k z5{}EP?_7qj?w#zf=X?I0pDz9`;Dr@%xU!yBg@nYt@=Y23v`szo+ahl%>DtxaQsrOV z`HKCxq~Xss_HeQp$Oz9jT|X$k+UUy~CzCPr$o`q@b=8sM-a8a;i&E|SDb{uShTZj7 zpD*TYQON)NDIj7POsAjQu4lSms6SA&?(RK-cvM14|2mZ33%|E~>sK0+*YO|c^5n9-T-hP*F)Jz8BH50}!7$hQ zvyCYkcWWwkZ3n{VSUmBfVH*$6vm|Sc?o9aY_jCrn>1#K_MpK@#m=)drY)<-kJ#7&Q z$V|73{{7Z%)8i!MF^Q&jqeXQjB`gM`<3^ZnbB5bnK4WbjH6177#!|k~R2RL5!%r28 zvhWP%yix)3`^jp|Y#!ghQ{}Rv9Hs5=7v;?6tMO`$nb|6FZWzSaVW`a@`y?^58FaEx zj4wZ;Cw~NC7{(!cuEGuoTl1_&e2`_VCZP?%25gpM@w({;OSL$8)flqt7hpb}JF+bZ zz0tpWYDkc%4UQJr$;iXEhbWoHEF*xpL6Jh77zQ0F;^u&O;Iri_@z));zcv$Szx14e zzuGv^zC9>Ef5GgJPtcPs#Y5^yIeaPlei-nQ$6X9v#{q^Sl>Tr;TfCUBci?V$Jr`A1 zN1B<=ke>wKVt!%C?_ddsF^Yt@6~l13o=?Zu%BH_=zB^ycCIEkW)nB*nIPJgC(XhOF zhr4ohT(Jer zcUs}r^4f#*U#&+eZ~u4z_=|Kq1G+u|q$tPe^*#VwJdYDDYwsqTg&bWSFCyc3#n#p# zw4Tw!14~lRM`yEZnvwsm-_PTF#=sJM;AXyWpgEp93jxC%b{<((6%xdkUlLeh?+5V@ z9d5S_Yy&N_8UykM6G13|1p)!8EYa#a8$H?&A{3Y~DmqwODEOJm!}AJdI-NCGW!F7+ zoAi&xZYSK|SyT&3&3;67C28?5_fM~fHf0&2cDLD{8Z;$d9b;&Ol;A>2Xj~9$NlHOU zB5jfio58*bNDs)b3x5JGs7X>11&5aAP~i&i>ifW5Y==1$?-8rP=AEZ0F(0h_uh|kn zK~poD33Q0O41p6|sx3kJXo--FjJ!aI)LeS+`L*q?^4wyH;r9g6%YlqHFunvo)`AVo z92p2GXdRh?NMiptCm#~y(EnCqkX~5K3goCx0RmyF0?XWnD4F`YDtJf{PGXF7kj~(~ z-kH+>4Nf&Di`#3|JI>D+Uvu zbs2#(0x~3=JS`O3q!YJ(RO?N(Nn!ZS5EaFc3Lou+1koZ-7fhyd`sc4N)A{ow2CpX^ zuH!`)lUkxIbhte455BstFSBG5#X3=Lu4dbDPTr0B$3BDMO&5syKyJJC%=)BKM!Pwo zZ4Hj7$iJqmF>b`hAh8UL%^Lw$kf0TP0RJ77xpe{dJM(-O9tSFk>;`)r2xSh8aY6G4 zlV5+GL3Gxi3VjyfFC4y%Je_1-L@VYS@Jqe}uu;J@Tks;&fNPIhG5haHZ4$KkV zmq>2|>*;W{+8rf)EO_M_g%gHi82&uIWgu&a0~LCw;dBVm!PQs6!YO+8+B!6ZsKC(7 zBalL={h?o)f@TE?;5P2(9}awnoq|NG@}-@V@eL$aY}AFbf7uJH5`dUr0M8^u6sME zWgZaX#`1q)7j7Cg(8`MjGWi7Bp^qvx%N2GLXzk($uv4jTcZGk03WIC3fAB8X>;w$l z4AYKPYvpO#VoP>eZAa{#?ssm?Z@2JnsTvT$tauESC6fm@V=xr1_j8r} z_Y~MATF0dc0RxWZ>ogD?+<-TSxlG`WbBPRx%VUU7Kvx8zn44$zN#yfyDt< z;S}h*9w|eC4k46XX^`Yt3WnRH&}9j`fGQbf<}xV(E9pZZkjZSl7#dxd<;fy<^MzRu zH#|f*n?M|I7R^7eS3Rd$5JJS> z8ZST)yV$gtH-oygHFJkP--`IArTs_7KoN5)lQrhXN}#Za%>}FJwsGdWjIglnJ1(&k z133D>pUvJ5=DciNM^sUy$k;TI^P+1}=)bft(oTAZVYNp$+Xrbv?JyP?LJAs=$phum z2BVq1vyb|+h%zhhJHQ6Nu#a8`*yWsfp79d8o;dAV9PqmR zk$do9lZAYv;XlBYo%3V)X18czpgUhNlEb>Tc~kBFLJD=p+hX;Z?~XaTYjC<}=|e9= zSs8vX-{sP&xWd7+pSanZnbu3E=i;|k!5OpoJ%8L$TFWk<^Xg$9&v-%6i2Qln@*KUL z-uT|(E%D(ox+h+>+4Mg@x75d-?|C+J>W;EeqY!R1h^7#$z;eN#Xm5O{u9*KjGyHIn zDv9yTvVc0cool+AmO0iPj^vBe_EA8NYQkd=uqv!ZOvE(Xi+@JNenH~Lq6(RZ3=0B} z+{+nK#wgWhbSy(R1sR3Sjk^*H3Ka$e5h}!Ps35@#?f2;I+JCs?^;iC-uGmkYDj}sp z8W$-@5%V~hrvnTvySrX&7vkn9*;%OBQmwXFTaO&?76>P&q!4To?zwML4semsBi?;)mIv+-2XKS!F6k~(tp+~B)Ro0`nIj`ECkk_s_ z9{i-4%;x1zm!x-XLuO{dTTXhHJp3%lMkk3 zS=(b_L^#Xv;n!<(X*NDfjL;kI>gr~T#L?%Ol~0Rd!DIfP7huZ|XrlKcfU0E9mGMAq zXLRczkF1#0wLCZs&pW*HnN=`@Vv_ zTU~KUk5G$ES@Z37?km)|c|F@~!K6S1tta+3Sg}{@o#20>m>zIv;gwbD9WK>qlnj)Z z&mFe?`HV};h-#SFYB$D@Yq%vQBuZv>35`q01C+7uGZ9xgO=34dSaV`gE;Yw?b z2UB$}xb1@{=gw>SQIa4EXf!S;0vO zHJdN{@^x`nTdl}l&Js0((B(PA*T15pC6_L{+4Eqlw)DmtI7MZwu*5m!aNoNYYf@Hq#rXSkfW z?S+sGVZO*^xwL|IHT?}&q3$KAE6=X}71QRdK>oor`Q~!&;qW!#Y`u|q-`NVNTGDgc z-Bp~oT-xsf79N#LOlO)@qgGQ;(H?r;;$A4Ur8;l9EHL{H7}^l^emjD1vRH_CYli80 zJr;Mp=9aS5#2Tc-og7OdU+Z$A7Y@@sjQDFckn&T4-1A8Dza`cmkj<7m2>Y%#Bw!|8 zml*}UXl!c#asP2%6kU-lv(hLuC z0$s0G5Zp3BPbma0Ik1^5RkN5fRyTUgILwG z9UL-M`pD1Zbe0r69+kmrh6oXh;&^swV2j206Da$U9r^d)UY8K`ojlXqwAQQd=Q9e* zA*16Vt@rC7S~eC$O*cw&qHXYeJb_3$YaWf!nNiZ;0kk}t?{EmbT%nTXi?t_E_APhf zb9NgM1IDX4vzNUQ8%TP~BiveQ$s*yd*Kv?i**wA37D_sL@CGXBV;oMv{?zB`nZSi}2{x;D#~l#BJoyt_)O$SRyBgcs*<(9RY{ z+kKLKBxK6Tossel-;uY+^HJW630C&4v2|E}MHQFGTliR$@2?;VnFy ztvRV#IZ|o8+zBsyU!l=7G4*tu^_Gk=WW2({%EYNGwwqnz1&UT0-SkfsJ-=sIF;BD- z6*Prm29Wlw2soTN#_NTiE_0~P{J16+tu(_hw;}Kf(&fxz@ z8iOrc6to_;+tOWc>q=74v3D=T@Qu%Xj52yeC4$&{99^#iILA{tK}V}J>TUj%jc7>0 z%tTRa2*%3`KPbtq)`%#1!q$8o!cX%JLQcBeYERk-c}d|a!vPbIVp6i3Ij;%#w{~<$ zDNtG#3n*Yq6Lw-kzMK!A4fT&Qenli`WaymzBeiY)_W+*d+Sg!>#=Kz(i6WMA$PE?i zwT_S~)W0M5eFQ$B2kF3u!*^)UZ_qaR>jprjVWJrP#g5rU2C)ftnxY_mx0F(P%UYn~N-(g@_(I8wJ@Ua7P)UqLF zue%|})3K`~WfRu>^+@~%k0}DU!j+Ish|cAS>q;_G?|89!gTd}^BPUA;4l0by*{Lh6 z=17x_}~_<-dO&K`#&#)P&o!Xw>STEkIiMlZ)|(-$O9b2wX1B_%CozF|Y~ zLvkwgHKnr8W)h!!9H4H09sb?^G`|gl!{8sMTC=-a+f8D^3aB8@BbcTj8LNA}8AOFS z@n%hBIQ2WV4}H88vXrvf{#rQKc9Zmq9H+)yuEOW_YAR9nE z2Y9-Wy{%vxC=f#Xdeou;Zy`RJZ~c+w=h8@OINILCo0chnmELa*2yjI;90`khP4N(m+0-jUp^J@NlR28DHLKdS(g@v4TTC4io^HR8<~ zGO9RSE&)5FblP_e2l=Q;@2R|J;o&m(H6Vr^o!MY14F-$nM`3~yf!O11Y{3ef9wNkN;W<1L8^iAP!l6^Ys*<`;(l=)3#QWfgq73* z9LHRUPnYXaMgJM_y?eqsMBJvw{>x#9CD)~@Q)O`k`lUp2Gdnb*@$q&Z-Te%I*mOM@ z?By3$!zwspHEAz&@#0GxH{+X;-GW=e(G?O24Kab3UP^L8VGV>UhGnZ$u;}l|K*}LC z@3m`!L+hOW`9dAyez7+*p9krcphDQIYv_Dy+DIx}XT0Nd(s z2Z)s&d*U2!S#n0!6suY+vAQQ0`&o0~UxdNP!^yvtBv5=cn=QoT4*ncZ`XCbb;7w^R zk5F(NMG|7iC#3W*lTzCU5`Z8{lf-LO(J5(t+XemZ^8sUJ$ z-v+-_3MGMDz(Xs1{1R1Ap|+xdc{2%)|qaXx;e0zr`UKA3H*l zgy2j>PBppw@Q{Uk36Y26NiY$1khD%|cj9bl@u_C5`2fgmi#_ZzA}AgkZnm;;vvs?|W{=I$^BX=eFtln_b%n+-QVnfLr=|yqsH%sF@t2cI&F>g3F~snL1(RxVP`n!3_ifhKuI= zMVhYXM2KlY#=4|Jg+I&!`O0v(?Y;doRm7CNs&TK%$LdxG;rv{l0%{H~o>1(O+ASEEa2thaH?BwyOdiZsz}?tHq+( zOp}^RUbUIA{D{o^pv5aVg}1~Z#WU?wuii^#Ft3*iS6_pVlR3{!KSI#aYJc|wzB{lD zHyiO*S702Tdve$nrmT_>4ut$+AxZTPQ_{#H9X3TbMeFA6r(>S9I~ipHMv) zSOXabnVDQV|M*(xgBW(5sl|%MwVq3c2+D}2i}|ec&_}>}mfi6c1fJ1FIe&bvO4M}s z%m`Tml@`-YgMsyWa~%J+FY|&apJZ9;4x{G~Ym@mxE;My4#8r3fr19yMFtA)aF+{85 zR!!W^?Bc7oyKby_B)BFt%xQvuAPCu-(dut&HGDHrQ6=&pA!=jhf;OI(jOL? zA@f8eW1j+u{2UsFY_>-`{mCI3xX4LzT)D163lE3(sr&Tv}~$lxFos8WqN*(~6dKJJ;k zC<8MQfBrFZWbYhq*79cXc+rW+9nUo@bJya`XL@E>$aL7@Jf4x&1I+pO22B^(^BV8& zQ-WP^#P9DgmzlEY`CgOJ0lmXv_&qUNHfQ7|s&H{XK=>bSA4Thxru5}{GpF+*29ZM6 z>A@9wK90{L<~%qLmzcqBJO65K{W zHC?YJ6oawLkagSVW4}65aJvLpg?SZKk8c)BESRQ&~e zZl#ovY5H!N+O@bbi@7rj~V(|xkq2lnRpXUjmGc-gvsFV{7CTO4w zgv-@d)dGEB=^9sPC!i1>7eY)D7m@^`eFO6G=&73Wi1cg+qx7o0TmKq6?FnOYu6)N-}@gC7m=fW?|;D}#F_m#=qv78KeefEqh(ve|&^?DEI$bVF=F(P*}s z>yZ5&8A-+A_(GC1V5m0D&J@?LTl#d|%BLe%x5#*G{en!mKHLR@i*_aaI} ze&L<^#@>7~E0rPojP|P898(-69)@@40uuK%X`;&0>-)r%`VNxvh%3fkH$OXf3^`h| zBH6xuXV)BXu92MoAvHg>oLfLc6C!AKt|x>BAb?bKVR7!2#zo1aDk&m@ut-ri{ebC_ zDs-rEDYbdU7gz|8ZdGc{8aw%~c_>2|qVrRPIb622F8M-NWPgX+5z(2`0hH16@g_#)mRNl2HW?hAfHUd^{Ut^#>J<}kuXg> zu3_IkHWrL<am@D*8=Zt9Y z(l!U_z(e&};pNy;l8ViO8ZWPiFItAK;-`-@KI=zr5deI}kn>JAf_o*L;|&fYn7^ba zt0S4tqSB%TpaYg0N`w(=_FP7Es&BU~>e2`&q@QlOs3R;@cP$p=IR0Wf1+d<3`%SxP zz@fQNtO60L_oRh%@NxCtec84m^r)yhQ-$5Ef`=J%V;10g&JFwg7Ll7ZI$L}*TJmde zSsE+BDBsf;k;u}9qI;_yz53y}vEz)MX;~dx;(tvFv){HPvkPJGth@gNH$#?)EfSX4 z_BjbFV)MhXf=kHYD`LT@h;+NLVpNGb(z(WC94QMDRw2P+SIYNnsV@={4LslHDe8n( z0@XIkx)HJGwy0`0*F{*QxFHDU>$v2zu2d<$NIt^%XZj1#tOA${MMaa242RF(( zk!R>hJvE8Og90IY?|lnH(0Lz~);oTkhI{9eVJ<>brTP9;>JBBqvyoL3K=k`%w? zEalaZQ9(l%FxuaAf|s$5dB(s>#`Rm&*cV4c<5bixAR#Fcw8@Oy36vyaqS}! zcR_%Nw;4B(`Ju9!HD~6x8~*`CGsh;~C+>X=&taXDhPz$*@8=IeGZN zg$97Phd>uJ_pyCq=q@q~F~Aa4rrb5r4oU3shpChN_u}doos!6pPOUkGT;uGtAIlRh zFHGORqsq2SJ&2%DixW6q;78{Lvb){tHo_i}#~FDtPw5lzoa1BHJY*8pz^#hJ%XdV< z!Z*)SP{BkkV2~O=8KCd`E!nOI5*67XBo!nW9B*DSr%4cUnji&H!JBC|R8ZoKjzp=m zU9w4+y`U2oQiU2OBC-(dZWJ3|XlZ%eZt**%T&Sq~`cbJts*2;&`VwvA&NQ_Mw z1vT}vF7;28n#BPbv|P?Uz;`o&!xGk1_j63oy_X$IEu%X__o^U?@! z?0MQ+LlTO=R!ces*VSw08ylVn_mgL?JLmFU>Az~dACYl!t<;CmBEVXJpbz?P+KT>e zT`v`J_yA`e_(&wFKY>-~z;mU;MWfa_8p(F=yMe!Vs`W>!Q*m1Sv3BWPZH6la54S^H zEbp|>2>}PIcbW6y*M4OFjWy0sLAOB84b2hIGLi9l09N(+q&2vd#dRMV&^al7C@7D8 zqqIA6YpqDoBuo~gi0G4+wF(Fij&H)o1l=2N`>`pLY*lta66VtX6*jn{JMLx3o3~HD z{*hcR-O`kP)q3iafRz$EQEo04*@vIiyNg#g#Tu7yArrAcv{VC*(sT{g84^xWYInq>urwRw%(i(moS3WGe6S&wz%XJ%VX?1 z;oY0m`#-51zCU{V*{|dxtcXP^jHAg46x`tl(ynTd@r%+oq9HJtnsxjkXeVqY9)l{{ z1j51U*avcO2yjmvd>jxFmk$#WAizNyOdD~Tz8Xq`a6=s235n@WqVT&34hcFy3CRY7 zB%HvjrJ8(jw6wYb`Y3HE18q+VJLadcFVYvc1J!W(&dOrG5;tE-mH0vC5c=~y)YE{H z%6@zS?KfSNq>-q=357vw2%`Anz<8H}ne1^O*<_~kPuOur)gzF&cn~M_;U^p1uHdMVTZ4o%?^Z^<`11_$eG_1K}vE9%ny8O)CZn6chAml zXddOm&AwN)5_vaH6+9y@w}K~gz6fy{CtgVv*v~-dt)EHq_Msc8zN>DFvI?DgaN;kG zBn!F#7(syxZK@wgS#60R{($VohlzK^n4lV*r4T5EJ<3Rf2&w@=pG**#gI9(3+U}+27la( zKRjrF}&zC zzA*VP$PKKK1pV}v58q&W`wJ?X-%U)40|LXZH`0O|Pq-eJHEs_3FeC;zHU=sb$q$6y zz96Oj7K?fT!voMNhUf0q7Q66ZH_An(9RFu4L7vp>>>CYtzOa08{)dh;QDZpjPp9o9 z32(~78&}imlrT@$DQQI((+jWRl1*LP9uvL($QT^-m-IOnU%YO6%iVetL(} zzjH~C$*(_;qV>Rh@dc+;E<-@bZ~zn4F0;4m>zDNQce;R-O^5UOv<^Fbe}nMH>!nGx zR%eJo+QU&HuujIu4T==>9cQjyAM7*Vz$3bg2uNK|M=*WQ=48yuM<^Shn8D^4q*93O zNc8mq#~b!}%LiMsRBip2zkmcsiy6d^dS1bsv73gr+Jll^ia4@lPYohYZkC zKE-a;b6k<(#8@ms(f^maZZ8wNcCYa{_4ZI%K5?m2;0W!?b?_hxczxyAvQ@OCdHDIM>}1i!uO6 z6GQ)nf|l#w4`%FGz#;u`NaTVlDxrwnaV&2h z41)|k2>S7B`_Gt*`Dpn$o#}iVW3p=KYMTXj^NhuyIDXIInF{sGMB?)pZALdNB+58hb3QC7FUf$nm%>4hn0CTN>T^7Xfx~_q@HEt3A ziH6AJJV1`fr4Sz^wObrY&|xwW%;A9k>jyWtD=$(D;v14x$uLXQw_A|LY%u?6jD?oh+Zj*nQSt+B|2?E-vgz+8PWv#2A%NWp#7tC0)urQYyOh}>V8O>nLz~nnqFfvkbUQ< zp+Bep#$l_b)p3wDE%7+{?jo77>3Tctysk44xpT!~4mPRX_@u%a;aj})@G($%J&LVrRpm!=c;zh_YI=9^9F?eY%x+_gN@-Zfj@fc zNcUPM#R zm(xEOp~hY&fcyl8@8^+384fK$v;bBhqTA-wQJS7iDdyqOFe)S^l%$|sl`9YL0cJ9> z$J?A__1BlzucyoN(yNkT=rB&-3ycF(`a{)Fji%60J^38h2AHQ&a9^Uf#@x z&4Xw^eV7fug%H+rzhXr>@m%){L7Wl^Imny6#AnFgL74Z)NIdmHdu}qv1Jbo7_9MUk zoyisS3oy@2+W-sAD8P8GK(WUx#936XhbOXl--%tJix$(yXJqg*d>11Z5BLE)3N zI(|{nA73SZZjlH0AB23-k=(8}b2cR^8Q_70eA>!!`P;j5>6e4xhzIkX$mj15=mR|8 z#3N~4qU#|Tl|b)1rZOOZT#i|24RBW9_KkF z*;I;?T7TmOyn*}(5NdW}q>v%AXtCJ|oq3|rXbGxO#w2gc*eU;w{@0l|_zg8r-6!N3 z17r3+dR`X2Y1?_k=Igb0G@08Op4i}s!X_1x5K2HeEn@XkBf;MfG%{oI z+^|P?8PTj+So~2-({AqOBgEG4Q}4ZEF?+`Ivqq$ z6LD06md#=l&>*y~(-JWssfuS|faRBT;FGcFF!64aBhaf+pAN^aHJY{i)p!vEPf63* zwJwQGYaRTn0{m8zlBC3B*6#)ggiEHs;Imq{J5x@FJ1I3`m=l)SLYqHehW(;&CtvVl zt1WQOE!J?V12#C>_`QXf#s^?S*QO6NSl5eLRh@n}uM9aTE~UzQOrJh6npJD~Aq@W? z#GUK)YIH)j=zR;WgcM|aYC>egpu|G4;sP28DY@EnrMrWPu+_MbYf6kYd|E7O8< z`3_4ITus(rqie;~y0?VvBEd)Axqe)OB4Es}+2Ye<1C_-b^ym-){Co+;$;O(kwqo5h{QTDI zl8~ow+F|!=&EG&lbnUU8YZ=DHWJze~BCES?;f0|qsU{eMwct||GDQpofq}*=4o7c!=B?NTBq0pA zR;gf=lvLFt4c?$$WE8L{Wj;bBv;S65)D0DO^s~+@W2kr|C-$f5PGj5k2%TsDlJP!K zjK$}Tke3R+)CZwb|2NP+ld#mpX-DUi7J)qM_3tsTO#r7re>P@YBIqI6{i@pyhPvk^ zlD=L{rTKevU6fL$HK6~-gJgV&0S2bv27I3}MfhKZ5)3dZDk@59 zYGPvI36cikmYnfIpFK|Uk?XKn6Tmxk2r8^_M4OyDCUIYRmGE~!e%lMm7-loV0K5c@ zvXV|--JH@Nw|dJxHhKy9Z@GZf`OCW$kfs4RaV|6xO@B&4oXUY;2xQ?v>kgDJQS{xz zODo$$Bltc8k7{~HY-y0}Z|0DLDdq{#HQE6gg#+F~vBCtL30%$0l;iXuHBi)9fei%B zR%UYrI$qn}?>2P3#z2i_GlwHKVPm7?hO0MK>R)SV-cLtZeD8+f=ufACePTwAavRH= zE;~6dC1cZtIyjtqGrDG3~b7NyYyVDnVAir&r+!Iex=$nXC+6FJ$)z>QdIxa;TqG@xTHElb_8N4I{HR&I+|hK6edR4cJ;uC?kPYf@%#VnxCn`#bULZw(@&r zF0$=RRnzs%K&58?G0zv_widvEQw1->p#iZ$M6O<*XXm8 z3=+(rJ3N)usQ=XYaPEZHjBMSZH=Bokg&}>gY{M8t?qT;Twe5Lt0^>*7AIY=r?m|fJ z)na^{qL>F+Pkry(h3 zO7zn;SJYJsKn*;e(!41%!Jj|PE+wf<8X_&Z`*%Eb!S5VhI3N_9tbrI!sfCnECz9AiT?l&|tbih# zdF94a4_omoEC*a<@@UhsEW7x`t#I8f?ndu-vEqkffOVhZ5ESf7{QM)ubhTDk9r{$6 zbY4_NPJY{dWC4x$CF+kKOujXB?Z+`@#lvI6M`72mCYS~miS^shxfX1kVY3v?ev4&R zecg3QHF*GlY*Ije+|a;Trs~hNE@CMO6knQmx$!((>q9OzF)pbV z=}!oyqVnV7p>Nymisdl)H$hKFa2?3k_4NM8pd$HP)Q5k4>R#KWj0GE=IsSEn+X0sfke5o3lcRg2F&=*P#zB4$+O0DsH7O~;H z_md0M&_2gy5TC9T1#88wuj9oxz`$4{tMO&9?Q4cvG(2^5*iZb2gln-f zMNp&NaOA05g0{RGy3l%5M$+&*7PjkiIZtw8I^XNrR^6W#)R@&=VnWPVltSLg##b10PDYRYy5AF9X|IFg?!+MWU`KK*<0V9ifh9ZS$JSf)0! z#mh~uJF46))*RJK`a;3Mw{rXN6uz@^VB~az&>zo? z)3l(10z-az8>-W^ts){L&Lm=Ep}z8*4qCQ6pitE>al!5*C*CyMA>iz-@){>Q&W`;3W zi(N?g4dida)kZITfLu<2cRPm+jw8Ju(fKCSmFJCy?bnF#rlSr#TaDg7=Az-dH8Cd(@!rT3^_aOCo{yF7(L%K5a?wk_fD9wCUY=0?e;{8ea0W-)hv!RmVbG}!4qKie zCP{6Te*BrNl@t3O_Z)5o{${%FxpJ4-3hu8QJF;&fT+P@GW&l^Np8&5!Oy3mpRFxbxY{$2q%?BbEx7z?bL4yh^xs~ZiNn))8PaGo87ihsaaFo z?Ni}wv3lsN0W3&xT4%h(D~~T(I(%=kU7E#qKG5>? z)EIE6z{i?HCYw1|Df?SSaXit4x?(vW+^*}94pY*EVzfs>#u~?F!>v!i;aCVSCaaZ* zlukfS7uaT_xy&*pl48VQE)ZNF)A?jRV4Ih#(f3l5?TTYG=b2w54=*RY|Jcx#FD8qn z(9trn7VThV@m^h-f`TG{HMPlhCE(+NhDvq3*muiwRWNMgmGs9Xn4vF7*Mcd(@nrKe z@r9=Wm}xkQll?O~TI^awg_2CQ-ee&hcKo>3VZnRvs}-COFVy=5YOY?!g^8M|(eC>@ zC#zMzKaN?VN+a%)`+2U(!fH6$H}`H#@=uLo8WkoKjrt9@AnG8$9+q%SGzr}GX8)q( z!fM+&5NK_8Zq=J}zSNQwik*bI;@dmY_$}Y6ru6t;A6c8a#f8 zo$xuuPS?6kc1zK3k64Z`yNH^tmNL4dWbHz~C~p}rHhZ#ox!D>mmmFKJI3;=mR_2R! zP0;9aXWnEt%C$T3eBK|6Tur$!D;y@XdgHsgh}K(91$=eke*9IXN@6DKtyUAaMI-7h zhP+#EdLzW}JHpw({~t}~7#?S|e*KseyRmIsO*3&C+h}atw(X>8)Yw)tVUxzTZNGEQ z`M)3M)66x`-ZOizd#&HXn=&lcIe+2N!( z_a2r-B^H+LjJE@~?;>bhDmA)KS_rtFPOB;je>IU{C)B9fxq{7csffplj5|EWlUAkX zMCs%Ly8DxZ>(P}FA0hn4Z2kRp(?$Y8F;5^&S+?E0J#`x9qq$Y|+~J@4IFr7! zBm#h1JPZQaJab7b5Ne8OT_Q&$;cB%QhpR4&Nc^Nd8cDX3!c8wNBw3t|i7Zf)Ooz@f zRO1lgCpuXo#a8Q|K5<}Ocz*ecYi{25A|qG#A3@mJj1Lw6a~|qYmZ+ff4`#SyFHP8v zZ-tmZNh3^Wa;rdy_#9X34k#=hSw1=w$2H~&F=Jp?Mm#{iEK8I!2b*TT(&8(Hnm{NrX{E_-xLa{$Bjt4w)BX>h?D>R&F-j-UkLR9jXJhXjW7u|rey!k z9(f(Dgbb~ZF&C5GxIS<65`njb5G>ZEtBKyrQnbL}zNX`kJ3H^sv-Tw@zOsrZ8^$Se z*fAIZ2Z|Ec9L90&FIQ>^JvQ7$c7J~%j2b{zn@;jbNua{>HjS4~)^0Q=VM76e+2tHh zM0yk^2PE9!Lwwu<_x7bA9v$e>1uzf6=o^`_$-pEsNyOLULolZdD;sCQ_=m(qu{B+1 z7$fov9~1mHz-$c>paOVa-L(*U!tNW-cT7_a(#p#XJgng9mn}9)`=temH45vKzxU;b z72D@4QYah!WbZ^_Pxnv#Zh>a&h2n2<0{?2~G7k+r=V6t;KxEe*${AZ9OnHQ8UufSI zaK&N(<(qh_;rY0(Qo_T~y<_w`j8K`gxhlLTv;S3pkI~__{#&cg+j6-S<1C(;Uf8Hd zE`a9>ZbhbtLV$rJokC>e@=QixGhq*{4T!`DLGKtT7?3FHFFlSch=esZCc7_>`ih8L z1ViHuAwv9#cyG;HsxkTUuSz{)rP=y#l}CX7KP?1apLuBMKx1PBlvsAIt7f6V!_!6} zIwZj3R%1XS3V)J`{QVkQa?uH(RjO7SYkvGoDjlbP3kfTh4?SJljU_$%l}bTW`NWL`3 z%C6&Fb>Lqx2haouVLyLW`Qu5)KW7adUrdq+zUvv5Hwg}gCK+Ei8+7PINkS^$_pflF z(>`>2BqKQeM-!XlfA9b(r#vN!lO5nMEN5l@bhg`ul*QtZVx8pFiBox~=qrSAWMq46 znY;?zm^o-m>Jc_ElMlgl+Y(C}nu(W19ewYr=bXz%D?x|bM!Dphg7y4QneGne%-$b3 z_>f%6_aOh#wgmooe*|oUPHZ~lprG*Bzkz-KSsUM912~FGZ_wvAf7k=EtB_BnN(ub8 zPaI>jB`{pGs3#}G`hiQ6$oc;W3e7v@RZH~6+JBL&AWlTKNl$i3#hwNR+mD z8^B({pA;>6sd33X_)a3q_q!Keg|wf4G{d)SYP1|A?>V@-&IN7ZPNH{zMw$|^NbSWW zwuyfE!=GK|+-#4bDKH^KBbPFWGzcvs@_xe61`aT?C;Gu~W7)41IU|gz!kLFBmD5|Qx!!M>5S*k3S>PEHt%G9V$VDlJKOT<5iqG=)g& ze|k^ulnCm_Ebp{O5w$`nV+&1xncG^_)#U(VLGM`i8=4Is2Tsw7<&FOR=ZNO@P`A>5 zL8?D}wK)Sdz3#S8QxfW|Z?%<1=fw6qbd;`*g#>m0jtIWeHBP|J8w<<6IMjkD)&1{| zQHQ-ifMg2DF4}!?8JrmtOh8-4MyTXvKX-jtIj^U`NWbj(47F;v7tipDo{@HUyQGlA zd)bm`w?$mK!1oGvt(8*<+P1hj$wGppUgEZ`n6`k<02#1EswW_Jr0Y`_e=`&(TF$pk>h)yZcKb(b`>`fxk> z;n7fJ8>)igP?!)Dw9PH)g_-!WCPBdRg!7TmH-K4x#0J@IAmna{uw6$^JOP$SU57#n zM}K&WhXr4OjaUDDXzzyyDY7fn&zD(|pH3;m)rLG7UNM@Te|1^#2e5KAHP4uzCK9$Y z=9FiR|IJOaxq-O4S-t;EaBgzrZiGI&Tmr(#3UI~)Oy?K!ykow{f420Q)=`1zO{P*W zwR_DoNK5vcwe+0K&_>?IJ~%DJr9MvXb)M@!$|g0N6rFZvP{TL91-;sbiI(cK%o!KI zV>)SVJJT`T_!t~CMDnG6=2!5a_3PGVVmZ>WOqk4~sq%Z(i-jmWzQ*rfEwu6C-_PEL z+QJJ$MSF{VYtv~#x3HB*%H)02e8?3z9PGGy6f&56cM589wqnN^QwXb{{0x%1(fK?; zCVBQ6ezHmQIQjP-jE2b$d2MliyF&HP?F_|~4tVI>sA;lV&w_r94--$`oVp6CGn=E} zXRLjy{#4lSH@*~x&xI;idJi%^WO)Jb(8w+UKAqM)?x2Y3C_4hs>kdqGP=2)O`G0w`7patt_NuUW)d)U@VLjt;0 z+iCA(Ts|!0BLDY&oz5yM;6})JF;F^%E4^5pfU- zQm!A7k?l#nc-K4JBlSu4 z%0hGoUWx={*mXXf2zUneIT=@N*mCtB+B+h&Dv{_Gzdh);@5+_V-_31^Dn(n=L1+d(z_%#0_K0c9OrV*kTy1o|f-&gw0xB0Yb-- zy!9$FsDkukoh3dzx_7^XkKOa?PuH|=gqvpzoT$weq0I9${lw0uo6me~x}bQVxfa5Scq^o+FfG4U&K+NcgVK!nT0O2GXY{ zxxyT9ulTM^&K##X8e6WDc5}AckWG5XRJ^o6TcuZqc^SYKZ#~b!Wk+M{>K%qf5>NzI z(8!RWKY%2RZ*0aLHLZxy#2$I@A?VHng+@J z3?!cApU#9^&X*74BUcq!C!mxmLNP%JDtEP9@MWKvx&#>wtQG#d38l_^jcb30!*hLjll{P7Sv36;J-tC7T~;a} z^ziTYj}h)%?`N{N8{tf$zhuwThox+q!bUqZfRrOumH?+RF=?thA^u=(9}_*8e$#gl z+%}dpusv`rEaW*21XU~+yY!y6Wg3dngEj@a*hV%Gc2A~weMmRFw<`2sdjLuY0$^A)H?V3W^FD{i`D4i)&X6}!R=vt;aB`48 zSv@vR!RpvN-)j%!mqx8@=aleLlMiWF#+1wSRSr-|;qau&;h?WS1xTjl8UMIRBxg}3 z&rn|R*RF3;?@uFtn;*)$fCo7 z65$uegFSZpu3hr@f@#TcB(1yCgeF_Pf-l^sR~HqkbPV&g8y*I}u^scAKzZirty70> zHG7fawhJpfZJP;J@q-47ZTW0o2l2@hH&4GcpS@Hh1Q@yrk!jOMVexOy0*ip|IAL1W zBDF+^o{#u~!|HDg5k^x4`CXQL+}3JkHVNWqLXO#q!8>oaLf3tHr4|}R`j1u1-Jb{y zY6H8EB0y^uW-yb9@xe}CGT}mBM!sqa?4g6_$XPTXm@HB1JrFHMka(;2rT_Dub5s-8%{q{pVh`7ib3^$OBX)cp2faEFnRcFBJfCT8nT98O<*vA4Jj zqq5!53*RFQp7YI-DpSL~gtYN2AyeD}f8L~N(bv?=o{!uDiz%93vKaLo_v_`>xh!7G zYQtoK|L+Chsi(H|JipHvV?n`4*6wgeKBg95RFG2Cr!i`*!0WFcsMKwz9}eot9{% zzVFP)2h%0q-VC32T_qK6us1@1E!h=lZ%$#tQM4q|KL7FBPUG0FA z%{+EikTrbg;-|&;9j|e{;0!F2 zOIK#6PIsVHB2z*{CE*_%E${{XGDrR~S4u-k>Wc(YGwTPxvG51Ya|x9W`rqy1U32nfb~`Yv{8kzhPppvWBh znX~wPp5O*1v3yUQ4Na_Z3>DA1p;sG=q*YEFJh<1@YPn@wbr(jU_A<+3I=HJ>{ikSy z{#QG1Cdia*LhIK;t=u|Nn$^lrnl$UhBIA@7SL^v$H;swTbtq_h-(4tl zb^HleczrfMVCvxR#lis=s!l_4*=5V7{4&qHJymlj5mr|%#92!izm|d$C9%%M}cram^Pu(N^RV4FohDRK}%E& z^FI}L!@2oiMmgLsgh1t3h8)+Omw&o*rF7yH^@N;L`5OZcyR{ju)_xHSkLBRG`sE>5rs_c0@F;DTJO-36$po4y z7d3>AA4`yGhX+RZ2&(A6O%SO{6O;1gqs#cbmiznqQps_rUbEca>nh|vAxr<5ToA1V z4HIf`nk|t@Sa8graFv=jh69e)qyHM#6n+(__)#fB3bV?j+nyCK9M1ORYCcnMXG74z zY&Lg2wD$6=ydH(ZN^7~n+_zXqIOo?mUgwt`ZHaIQ?SbJ&X{}B-QmGq&++uA%{e;xW zkki$SzXj_GNJ+J)#Qc_qjv8aQLYYELLe`6+j8>V(Ou6Da<+lK#sJ5Fl&#ib}r`WGA z`rLF-9*F1SiHVsSdDizfb4~W@3rvR7C;W{+by`RXABiY^2IT!Sh0=<1WB#2kg_%f; z>tS-A{HqYpV<6gS4C2;(xIGLuLn4rRs~yjw`3Pcgi5e`b@ z9K_M;dg86TSL^S?MKTwckRWO)@v()KS2IQ+hpo@llI3KYon?1up>zT`g2{RvQ#$fs z5}F1&Tk{2jQ8v`^k(Qt&z5E~qj>Q9D&^4rz2!MgC*tZTukyl;pyyevZ3%Gb1?xA17 zb1Eiz$Vl|~CbuM`?Jc1G8LyEJ!ZF#o2@x%@eb3c^@R4Ow_uto_=oS+Em_+d8a*m~n zgc#*4igrkPb?@XP^q3TQ9SW18XgE@bO4(j zeKtUnAX1De9O3A<^x%w>BNUrFRCyFN(PSZFP>roE4h0JhZl~G_I{#pdyUSvrZX}Ty zKaw#+YU+|Ay{s(L+)YdcU(44ofn|r>G)5;+BVs~z-4Bp8Cl#iZ=3bbA&wV_^IHGmH|LtfbSJp^_(xN zc1#?g;4JBa+YWSkaTD52(c-+QqX2v@MaUctR`b!8^{&TZTLujWvH4PGgw+uz zD5@cvnKla!Ra(EvDdE?pj#Dx(>K43<1kBlK8sXnQyvN5lUfaW(ZK>*g`_;Z2oU_aI z{wQF+p!sKi3HJVBQdau6b`BXTnu^XKC0y=b3udD)Zf9$5siqavb8YIX{#nn^c#1?| zd`hHTdwV9N@+`6@9@!ejbdou5s&i0fJ`{DK8e+0)l}e|qz-G@o7<^}YnB(AI+6OE) zpL@ZtZJeos#;?7>nA&016bV}wpWA|W#5U6`K5#~#k%=@GM2 zWn|1=vzv+dJ+pT$8-G(``lq4W`%(ijSO`^{t+{7au(J5=zIgG6>HPs!Xi1n@n0r5* z48%J07%jFCpKbW0HV~j#t&^qD7bKV-J_yUde0YFpGz(>&2?SbdM%R`(ml|zY1s{k? z3aLs@zfodT)N$HV+z|2K~XeW?Jz0 zRz`jq=4=*fibQavr`zYr`b3HAXeL5-e=bTLi5|MNY_Z&J_sc}~6C@t10aYh{12Rk+ zqlURrg}40Yg=x$A%6Q8=?H~H4N^lNN5UhGUZj_wy`^Hj6JYW%8UMF;36jR~v%q~k# z81fYy_c8%2ospv&B#BmgQ}S{=>RtbG9I$9hzV=A|+$<$#wpKS0#dhJ}B*(rJ z`&||z9K-iZtx7Hj?%4NzL(X=!IRZrx)ihn9?0e(4Hz6+yFTCmGygWH4D}-?*Fi1&6 zf7H8QuNPiP=UPl@!#5q7J*^lgbu3BPFN#d9NFxw-N0Ud$sY^F%)IMt2$7QfJmHE`eWs>wqY!wcJVz@@ zs}9{^@E1J^ISxHB{?PEVjfT=DyD3%+g(TA=o_O6p4`!!9oW38Ek7_as102{bvSc*M z`3WMvacgIDt`{qLMZBn%w-5UG8boM9&oI~F{oI-;W=C;@%N}PGi)fuu1vGv#8H&Qs ze%sDOWp6NqD4p`97zw7CnLl`#+a&}p{ogP;!J#RiMSDQ!K5om|N<^&OUiWlQF%ysG z{mJleU1{edR~}KtkKmM7p1&2~n5$uPN`|3tR`k9JzWXbRT21D+&3s{k_W^t)Sy?VI zEOxDiRQ!yje_6kA=~OM>kYd8^R_03G;X+;?wx16TC>Sdsj8lt4i*+~qyEtF?^8@z$ z!vWnv?tXQqS8kFB2>OQT=7nDYDnllfm{8jlFd0cO;!NiP9(%V+o5puX8SNkCoj?Bm zVx*K_i?td_*5*$+Bv6=%G=JJ_bQ;nbzB?C9B}mHyUwh}O3I^U<;%Ty2c*MtMj8+D{l>(AuKQ z7&S^#B@G_71!;kD7t^Wz^tn4-T!Gwt{ z6mni~+~wC{yXmiv_inH{n(B0h$Pj=~@I@hMvgzaz;WneXRD06-;#Ef$xz!i(M{DJS zLe`Rs@fWBvS9>dZBcz(3lc;QZL)v9i_kj-74qI0M$!-a^`?_-v=telT!!~jockn)V zubYoYXS zUF$O=n5gunFVoQsA0Wi1at?W2&uU2(Dmr&Zh8iL{a+D>AWR;kqBHb%emt*( z<9fA9)eK8%VVPh?42tyzQP6qWf_QrENo0`bndD;p94AHE5O(+`ytEZ8R?W2W2`Ir{ zo7_CpAFWI!G26{@4E+9+XqI&V0 zCfqck*tXxIx_m!#Fo29GWBvA^Pd`J#2H_Nwts^pFz-^RKNqktar^b*Gxr+xnztm)j zYp@1K*;aW)-~ZtsNxrX>(0h3NUJE%f0$o&MM}7g<8o4r(Im|T`;9aD6|I_vn#HL@_ z?`UPg+Ocp|WsDS^$$PDedp>4)*QN=K*YXhXS-jT1yjqtkqKLOepB*j@J8qT01A5#o zeMy?f3JLs*Ss@9hr*FMF@6%wwXrF@S>srPrS&1s`FD>7wso|G0m8rf%dsr?-xW={Zyg5 zH996rraX6Z7rnr03N6bz&*DTnSUKFu-4Zm>5~{tleIB4})gRrK) zwCyq>(YR_~Nxg0T`ci(E{oVeV*pF|Hm>2H~DX1)XB3B@u1+L@0g3Me&n}~Fr&AF!KeY<-yLFyyCQdt@hIL|`7UNsR2C~6g zcFmV#Q2{S?o=n;rL%VUW0b1~SPsm@lh2fAcJ3oX$Rby6R zqk_g7Z1RleAUEf+(Tkd zCxIWT5QQ;}owHuD!N9)V3W*=Z?PU!(6&^RQLy(k8M?UZh{k^7EK zhcKO^BoanZTw*csVP}YEq<(Q@*uy^689#gpg96 zjD$CC-fx;bP`ppD1KA)o^1xJe;}tj zN;6Hjvx5R>)fKu-DGUK8eJDCN<_d$7pROjo2!TvLaF1m2P^$Zq0Wb8&G55O0Ix1xO zenOfUCbWnYlU`IiTPOYiVp@aWBF3-9U((hlx%tpVA#cnMEHh$q)6HKI!Bg?Rw1;$Q zmDG)8=)fp)+fpXu(*t2D>I&6P`(^~L?O-a&>7Z?4n6G^R!!MH_x<15gdg1e@DPfo8 zYDaBC;xL}qP}rf!7gBALA|X~!g_M}92JIulLn~s z@4dpxPHA*RAh3aT>nzE)BS2aydepPcxJX9n<}b~W>f7d9b#eid?Gv;Z!Ld6^Nc|Xd zHwYkU=*N`kXIgHI1w-k_b+3$P#61sT_oUwkU zM1l$CRx>3+TjozWzDw(bdq?@_XQKWKVWbA3Wd6rky|mfmC>3cC!D)+@<}re{>8doMpQ> zw1;N^lY1lbt&*6b_^AbM_+y6gl3hyb?d!*Z^g6|FM4Y_ss8Ldj;g*mKH?lgu+MtkB zSlf+;964<%42U$w5j9{=SYv?6bF^D%VB(b$=C!thBqQLl;pLIHg0A}i?j8BZzsxoc z@VpK`tK=a#{%G!QnygF^tSFo&d;d(VgDITXz=>43g6;)koqr(!c>_3 zAMNaA(5rcoDKBHFK*QvTZ-u!~BHk_lmjjkUEiZdPc*!uXf>OPYYN~_^lCBsjMh)fQ zOLRBrMK`?+SAFe(;KUaX94K`p*%M`-47VY>h&aXQnc*GR!~ni3?V?kZleRyOy;Rri zaCWOrG&Cc7tp)x@H$#Z|Ay|`Quz!PYH&pzS|x0TLpEbdGxHHMHYSt9$o=){WxbYnI;2*c(DF$O8)D9M?6 zF1d1vi|=Ix%6ma38ILi6Y#815nZh_qf^9fUNq!?Lr#` ziaz((bCLO@X#*#XsG{Ht*#(~xGL;p*5R{L|g(CBM5!j)<_gmY*>Z(N_;5GQ?|#0sRJ03*rG;R$ZhSQ% z5TDvdeq-}u&~+y+G@i3q^V@_T`lE87nDZz4K8KF(JD2rJa_2>N0+Km4P1!^qcTNes z(oC5u<3*brdV&8HhID)`MYjs~h5sJ=uMA!`^+*CydGk|J!8U(K(d>Ce8ZDKtL`ZWi zW*e-xPk!4Rpz?C|x7t^*iyf0Ab^7U1)cmt(a4#eLXzuWfecQGU=8ins-fiiZ+3=+v zJ3>yH>79w^7&DE^fyjV0sdew>C=67~1d_d5ho0TF_Lw^Ywn&>=0$??Pq>KzAxXbXV9X{d7(&VIQR$Q^LnI8J~I;pEp1As>DD$wG7W$nE$MNNi>|F;jLp`z}99P3AlGvwI6sFa`UrSvr` zEm35spJz?+|7Z9r$Rwv&@87BOfVWYlGoP(Bb;u`vXIMlznk-tk@!T7;tlVr7j3ZP# zn8J8$u(~yNzGY#ze|zLQU5bEw_rBTpak$!!ApK53E!cXtwRCL?q%utS49pUpK0L{> zFLSAA8Ok0hxZ&bX;Ip65N{pt>_e>6Vv%zA61w|J}moU=^PYA2xlwx%%2pk6;SBPLxDq)aY5MY3H4Pf}z( zc;H&y9j^5My#Utw5wr!~vHH@i5bQufF#|>Rkh-4i?o-X%nY>nKcF~NS@XZ)(bFZuZ zh@XayaFD!HHKTpxLf5n7cNc%NmX=^TTu=J_S~rJ!;*h=k&j>@!BGE?T_V-(Ri%l^pKd($ zgnSfz<6_R?p;^GT)$566uj>+@4$@TR4^@X4bOW%LXYd8L*{`Piz zNhIPJZ5rWz`#eOTC+tes%s}IOc%HEJvtfa?B=F)tcSwvzUYC(obK;Xv{R4adD>BdPA!gEKJkd0i8E9&7P* z9b%ugc1vDIRAJhOZO1D?*h@5vs3-lM4!xj>_VGlJ#d`-z?lc3{>yDMbVN+@l@A|jJ z76tHvIb3eLM~_EBZ`vVnKNODjJ|@UsP%vI;8haas2lp1ubKe~;$34Ly8waVOf}Ap+ zjw5`Z_8;#^*aDHITV^|_jaUxT5`8}SZgK0%mUz%%mU_IfMip~ojRrr{2{ryF8P#!} zUiwEakO=8(P;v{Wz}+(_<3^0lY0NfmirGJp#-+L-E&FV7Y{ms7;7P}csf5=G!_5?H zXlKvM?^Z5~Z0k)43yi9VBB%^RbFYGZD7;pGI|#}(P2;a{i=Z!Htt$8F=s=^0uvRM_ z%y5=TnWbi_WmX}-Qj^4krIv@%=*Md%eJTyA;9?$f3+aCTPNU$a%mRN1bk)q^m0`Ib za~-g>38ZDd&wwc+-H{^b(Xk)jClkP;&T}mnBTK%!{)#GZJG&e%bGcnBs_TVL#3|3^ z!BMTBS*zl9f}P-#^$S2pO|Dp}V#M`yBLO9+bq62UDl5zNay{i^o$$B+6ISjts4Sh@ ziD(hF5(<2;nJx8)O;(oozw`miN(WWwv_YNy~hy)Vy0Or9MyX z%|<^Y)oRjZoVLx`03Gg^(G0>7%)|_()N?-#;G#n5ruZY0gP}(gl9JOwD|xScE)P)1 z0lIyohKj{5offI8Wud`%knrOOP8a_~aG4F|FU1G>T#wLEa=6T%U(WTWrpW1q(|+q^ zPJL0B2JX&m$fc&6{jHbtk(ax7`uo%0JQ)FlVX8=e`Kvq8 zlBCYCtAzuEEB?a8bWtc<`{;6oQATtM%HVH8=e;iWcujksd5>r*@eP z?-&Oi+Tj>Q(oplfXWNXW6wg-1;`4ltR$6K6Gecv#AVLvj#Mi@Xj_0f3g;y5$pFY;# zI4nhcRG6yUoP`8Wyf`o=Q-LW32NR}GeL4t(1L;uIc9@{DnPwkp&|Ky)qer8~vP$;+ zQ5} zy7U{I2Tj^(0;C#jGAeQD9eOXl4mF_jv)cPgWQlhg(w=!9gsw?c;1rB<@LdyCDRC(u zHq_t{8&$tD`*4f+^H2jmCMkNT3#KsokE6tDkVUmC&<9xqul$&U`mfyy0>~`*m zDI%|dyqnJuj66wg95PGp2=uP58N4F#P4rB3g^JA}wMvy7@3>XA@;l$$BpsOycF^cY zHq^88m0^~O$vo<*kcBS#^dH}9m#PD4$yspGQ|l53_K_>xd^4?#bvj6jt+r_JJQ4W> zw6}(`m}VK&sA!CgGjXjdt@K3v;3SVc6^w@=k{iaHhG>VBi2&^WZ=Fr{2063^p1H3D z_zL0(wwjdF5TQ)w3wwyMpKmT-ZTUf|a{W$#=xAAlv=z0=+}hR4V;n~KIY&CCiK2h> z#Twn&YPBj^2gCwb1DP2zit@9~yP>ck^Y&QJ3;#2jaFmmQ98*K1y>3c=uWKk;#oQ9- zFj=)qy|9&go!gzGdNoC*ZD$Qs9L9>%dkVYXc7UQp*&PI8Lk5%G$b=YjEfs)lQnC>` z60VAE#BVubYcq`^=Y4BHn>(LF@3p`+&64a6J`^<(c%!ReGR*Fl!<5e)vw~1LJVw5b z^jwqT2XPE#$c(rX*%}+gK+IMt&=a+~#z9G|BpOQ0e^Ez7!U7*@=NZeBb6oNZRrm(J z62M8|rz*u#1rx!E5Fk4kB|OBfIluj$AteL04o zm+d*yrhbn=7{lGw*YK%ej-yYEL+z8TA%6oxo6CWF5`i*|hYOxCp;3tf2#fAS(Y7H? zO38RrR$3eT+EAT|)=Fj0k!aUSnH>Kpq~k5H%RvPvW9jFsG=~$7WalQo@~koG zD2H#S=~0oh=Og1yIrG;gzP(9wG&z8-B?bAt@95gw!3^V`l<-NN5D3ZiV#dC98kl^F zune5FRvSXpi_O8PM!YuHZ6-mF%MyhQ1EcIrVDxR{*z~yNeS-pwB;+r1jjvGPPXMvVP5cev0XQ-o3uI;<42xCyRgmGQY6T_ta~OWDQvIChlE#wa&zrg&WzX*#Lr zQnLnDi4(cQuLu%A*N0Arn@xfk=5G_AtjzY#@~zn+ZeoUEEGA706eo{Z zb9UAnkEO`-GJh_gZ)WpqylS_-4WLqP-!p4W*mnDM-Vm^6;1?m>N4cRh*`=|fp*q``*HJ*R^Oii5CW>b5#gVKG51L;}t z^^WIVgH3-`7G;FSvv+51NGKGAeLhSSldlty zDCKu`ylcy?B84vJ-A++7A^Z#n||4oGkOx2Lr>a8Xea1C=#V~-nYpr2F^dU4=(*pR=d|rE3-U((CAN zh3E7B;_*y7E$`YBvVg}AcbyOT51r15dv{iQ-}5L@zf7{vO>dR!l5Vff zP0^%Ba+=h!>-in?w|zGuCda9z({-y%O}oOBi`vbEPy_7q!94BZxgER_Sh_6wd0f9V zIwe;E@C<#hd{B=@e<_KG7dd?mVG&C;y*villC29vp`M4IsI4zJ4 z4eoF@)N?0bpRQ1N&3}74F%7avus3tb7D1;Ksu=aPQHYoiTt4@?Fu=>b)FrgbsS29FKSLeQ(a?HHGssAbC~F9U`d6n^=NI+g5V9+%D#~7;8{8jG3q2|sOHm}OSl|SQCj5cj>$hz##M&>Fp+CHpf8Kvh1}t$z1a865 zr{3_rJ*j%`Mho)2Ho4$89+HhH@P+1FdL`dZ=Sr7539icuZnd$;3wsIR83u?R*6EEr z`9;(p7ApRb#)ui_-)`b;b3YJ%JFBik;IN`0;mAV7qS-p4nSuPqL~0BdmLALe@?E=t z&!ifD4QKF>G~iGBDc+2h;dtWr2*(NIl;gxhmm7Lowp+Z66gG^uT>G(n*x*f|owN=}BxnFnL8w+AQ7,+{EZ~ zTBT%lT*4UTc#q|5b9)Hsx*ZvRs^k*wJwS5bbm4QF|I<`5>N2N}_kFg7ab1esMYAvcK#0rONkalH;Q7(*MS^J{P_};ABy^ zs`)?r^fU9Fvd-|r{qIU$Ec;CzmGb11mENdIeko@nJJLQM_E6t6SCWjx)<}Qc_n)e^ zI`7=C@_aG8o9~g3-K)vYT+arvnF#(P(nKgEp0i>!=ezJuu@AtZ-M`1hX^H(D9a(C` z;#*t0ViT0pZjNs>DwSN{hX3YEPlUNPK<kwFfkfmV+Ye7CMhWBa0?4Y|4v02TI(Lmu) zI_j@!#llD=vg5ORI^l7+mHNW(zz(TLA2e+Z-A2LAmvV~qjM1KZWBcUWu@WbK-EJrG zijProqvAv|#8WmjRx{TX1PKKU1CIr9JYJ1lLC#9Nnl3lltqqRyC-!i!<~h8*wG@Wvdpl0qIAFD zE>dIMI#NrGDD70tscG0BCaTtL{Xd${fxEJ3>DqBRwrx8d+qP}nwmY_M+qT`Y*|Dwf z-22||51g^jSYy|!J!{r8_r>vz`UdbUW-YQsg3?VSN?~I!4mjb-*G2X^BQQwlskmRF zOEx8k4?Uz36m?N^sHM>zpk2wUB zR>)xM>&)YO%0(qRIvPP4A@6;}ykZHu;6{!_SO%xU&QQf*{6QMqE31Oa7P>`l7n^@& zd#nOu+VuDwz^Ewy_4@X7N@6I%abls9GGLM^@d1$sb`bUw#Tq|rF+4+2i(?_zg*Zn+ z4=m^$un5giz$l1vRvfqBiOC?Ai-Kr!4i)6XOu6L|4Mvr@7$!oC5FQ}YiL}cB#wA9J zKcot6suV#gStdv-mXFq;5#7#QtlYAPTEL58n^`W;Ieg%Vyn*;C$t*_F;B#QqGO?7w zDxFGKBp#RBH5^nEMO3q5RrB2U_nRBYL3||M-_bCls)yECpO$<$nVb=VDd-S&58&HW zmq0W~mL8oDCW9WInj?`PzHdT0QMH880#S{?SRMX#`$f*@@uGWfg##rbU@0igb0Anf<_8GMcW@GiWMZy zcN&uFeci+;W+sBnR^k8$$7M8Q#oNFjd8MQf6tWiKrexjt-Hwd>Or7T87kLcj;)23HC2h{ymaS};L>D_0Uyo@lP|3#lS9V)z!>aVwre^@T?U=<1E7u_YQ+FmYi=!7ON!J?;HpDEu&Vlr-#F=T9)|%-R7?k^qq6Yxw)Pg}oer4@`RO;MOrpFapCChh zE#YK?K~_`kCq$c?ulq3zz^Q)mHS|DjpDG||_ z!horSFro$;l=L@~S5+g5dXb5v2nn{kqeq_}qb>IOihnA|V<-Yr-}6;|DC$QXf&5!PQF1%m z@Oq-M70oOew))tKDRF*^arlc zvOn2iik(W93KQev(Ui{^)tTi41#!6C6zKjoN+~Xu;*H_{PF4|fn}?61{RKAWN_1Nz zl8u?%s3O_ANk=LpwP{>&iz=!)e;xAPtJy2}S1G%2aAKVp=yVT?s8EVBVf^7A0Y zQw~>t;o}t|kf`JjwYbg{^q3Yf42lVFkel&^>*Ss8)tcY4d~mwM#Bx5V)`%)h{G<@f z#X|i?m!dy$&8otta00Jgu|YwEi;u7Yja=(`&eEeTw&9dx(FRf#cNXX+X+AhLScFr} z>S;Ix@8<45^-cRtpLlSH!tBfWHRtB3mlu^4!euaWj1hyETg8G!=RcYD<@v-!`O0+h zN}A8Nc<*K72A{AkF~GJPsOt}tQEyS;Wr~~BAiU@n*iI@;gPJBFc_z+@K|vtizlGIY z@N~hV;X=*oOkpIZ;Pa84j-N@*qap^WCnD*L+?`(jbRLM zRIh*`pFd)LY?;ag6p?&gD(GtoDRy2C!vuDfr?wV4s_zHS!AJ2#-RRfpK1zkikPj`E zNS`efjnTJR!a=tEr~B#a`pWb8B4!yi85(#O_woPM|E&&6E^I4{cG0GSRQ}85*sera zBI(c*idREQh*#tA;k)bR_KAIW&zeFSG@*;M87O1kM121E4}@)bRfUPRENL)$2#n%& zzeO`td9}va%6VA*+(H>JH}s|0SW|uRNH|7Vhg0Uvm9?5bhYd{?1}=O6WlZGOZ_SN( z*58|}4}*XDO6W5RdRwFDQdA8!*vE)(v+?r&br%9d?WW)zX(N?18I0Kxp;H?7ByfZD z10}%b{k$=B|LlB#39`Z`yyoa?#DJ;Tu8YVDgPzT^m=NEZ3*{A57{7JTwckc%EVI6Y z1)A`>OJyK(O8p~?Rw*IF9UFJ9Y+`I~Y>d)2+mYkC3U-Qoj-n4LSMXOi2uB*v_4q~O z+;fby5*a{9x5Pn%iqcb1==KzQB`%zISYTD)+}h7_zh$+B3upN!z4@0GX}2A9R~-|u zMAVaYnsS~@=>B%SG1sXc48#75Xi&9;9`*Y8MW1&{)Fj<&z*~ZR>OuquG$XK9$y%c+ ziX};U{Gg;{v0)C&ieMt(7|Jc>zWXu7fZ|iXdS592TK)Gb|0(@Sx7y3m*8&L!`{`s* zWD=MkMtPYzx--`&#_}8<)KE$%1`n}zXdVy4n+5CL9$lFJII&i%(=+~ppEMb29o3Le z)?IbRz&8G^hi38#Bo1=h=6I9Ces{o4unyaZXmM4pY9H@HmX_*#BZz3Lhjvg`JP(jXpKrft~u>~4{OR?kTxPfD5NY5n&*3m zmL3r2_ru)hbApu#r2kp{lEBEWnEV7LY75?51IboMw>Om|ASHCQl^@C{Q4L82LL8Vk znojuWtaaOBHG$ll!_5u`i;jAMI1hR zi0fL^{FYVC;(V?LeKR|wUfe&WL|ouJME{KwBXMNf*1z=P+xvQ{jE!?~Ss#)+l6q(T zmS79hXo)x)Fi4@>m0DHXn|Pd}DlyE5I1d5>3UglK36rMpMYKz+Ez0HHNnQ12lM{@c zpu@Ng4f5a0`2+VMPH3-wbM+Z@D-I(Xyx z4fiLtc2rfUt{3!dqXks3F;`Stt+A&QLd0UVg~InEHR+TK*YmRB2%}Auw0};e$>xoV zO`T0aLuJ~o3vR^Gb~X`i4hxkprbRow&*XQDY*?*s7h^e(obnZU@0S<7|38)KfSv7s z+eIu7y_xdH)Ut+-OrT-#B?@n>DmABB9sXs?n_$B4DN9Y>-fGo4L!&WSk)HUVVb@}U zg81~nT=)0|4vZ$5l^Trp_?&)`ZX3D@mqh$y-+wDTG>%Kd@2+Uo8}(=?V1P+}{NkeAaPp+)p0ASZW;(k+ zV00bUt&yGU`?1vFEN*mQtQ145*%~r=&INGVW3gHwhC0r?P9#}Qg0;sQ9p97LY&8dx z6L2-tmCWV)p>hc|_GZ@geFm9u4bAs{oh>!NsAjP@x{Po!3ku{l5?6uKQcrh1RBUyp zn$oZlatX%qeVwgz@XkCvRckaP50Hc*ukz8P(vuyx8XI`ZyOidROszDQII(C~U05=6 zJ#w6YKnfzoPp~%ljBru6+K`b0=X9kd$bH!CwxZSLr|%DiDWW>BH(KIJr`3@n%C_x% zQPNyQ(ag|l*C*4Z{El#QI-)k@$(PFdTmdY9wdWXfAQ_PhvZ3qM4 zX_R&q!rfR+dm!eUyfKj9L}j?I06|l(!la_Ms$?)}HD#Q}|8|NXzow=v6pvd=NrjJ3 zo@jL&0-F~eFO${K7h%)0iCQfuN(1FA;_9TGXst)IJbee)v88J1Pme zf2OzRVtVu0fn&S~-qS@Ml}xVe&BvV8a4<@7wB_9EO3L ztv5q~gCXNFf&|b!)o(rD_q)=&d|0-_FU9jJA>LnbqwllIH`;S=(CH`?30=$8rQ#&8CMW!d|S_8C`$kH`CA?O?B3F+|5#~`NsKbHrX)Ab@B0Vc%z5P z{V|^siV2{j!C*XGR>tyvoM2^NW_h`=Uo);_YNm;LSZ|x^Fgvl8Su4tJ(|e=q^LghC zyK2Drqpmh@|L=Os;VQ-F^@H8xvq5~#cyQlFM?aAMy8o(eTc*^BtZnC=5`pi7c5=aH zQ)hsEm(KjwAWm?*vg2fO$|BW>tC_)MVPi&z{{cNLrDHnRmjbPY{_EqJY^4+wfa+`% z8PF}zzBe46 zwD-+l+ zMx(fG%|55!mE~|v*Bv>t4PqyLcTi}5fp04_nOhj)Lve6!~oA)#zTs z677WBA7-;G4qL%8o6IR!D0=KhsH2aVy6pk{k3BqmpL4V@xZRuP}|2d`WPE+)>Z7&wx&6eX8eVvh32+>o&AuK*8(yz&> zUdX;oZ0nAfld3zE64X?9fsy;OErdncmTHaG+|f+4_op+dhtw3G_dAN^6}G$e)rXF& zKuFBLW5F&cRqE9vCI_(pc2dQ!J2JY7!X1au$_kW!>$r}{0&p}o@9_U75P}8PN4)>j z3awcEa6TIY@6}2axdVmW^Ba(>QnBlJbbnrkbroxgL`QVr9q~HtfMZC+L=-PdX0Z8& z>A0$I3WC$$)A`1Rr#;}nh#Yrd{SLneX`RuZ+y98Y@&3O z-1979^LQi6E`hqi_;$lteyRY4e0=3xi%E&DZQHX;$LERG(n^PFX)c?*&X-4@S&WpC zxHsa}Xm}0(PkJ%!=PTOVM5Oq5>AROCS=+?hsV;Hb?pt!T_IFA2j(@gKt4~#NG(%SE zY(kG44mm)wCvuLT!^ zY}seZ>o|qaa2u3VT3<8y*t1XK^!Jk$lg}kj*=(Cka@VC=n(b1u%4A8b+@wvD%cE|> z_Y?c(dg11@xGzx3k&=vGr(Ml<&(3z8$yr>h*Lb>;M^I5yr`GBv`wI&qWRrSBD&O^7x_JZeHp;zl3EDn;I; zMc=;X;|U0X5tSkA^F3$EVD|I3w2_mn_brjZ2WXW zU>hG@S23iH<$B9ilEu$tsY%oUdr#c#e9J^nWc)J{ks+MPLZ8~BcYIsgJ(bLfSpKUr zB_GSD!T0&7Y?+#@Qmsp=+jT?k|9$JL$#bfU1;|U&Y-mvwVZI;EVV?v~)1|?&wldkc zQ#M_%QkPa{=s(uqyyQQG3(4zLHDJ{;oy3BSuZDnXr+c+>kKS6Nl%{`Nkl|9#){ zVEKP{a~`wt^oyP#;^qDEhu?F`gb8VmoHSQXstPq(g^E<-L@{ZSq@|r*YH2CCrIl4; z9N)XdmOsAS7g2sU}+5cQuQ0Yqc+Q6BO2c+@B6DZ zf6>nXff0#|ZX5jcSu=966GCJPLa~6+2axyVv<8y}=JQtf(J5nLUHqHthI{m~iMtkP6xg%_v_;_R85xmn$%xbC zI-~~}baNUZLtnsoB{rh0=11#%bIwMm?Uu`nugy+<7{JV_MyCt?U4W?rA|yA|ZZ@C4 zqheoGTDelz+=PQq<^{bJ(VqIaCUDw%Wl>pELNy*A0ZGau?94R;V28Iq#BLJh##QLa zI#;t}5h}ooZ8pX{Uq$^}FM_;Ssh&gsJVBRV%OFpWA0=B?ktPQ;>(#Ju$!^yIX^V0; z)oTKlj^ZKdaFo(fdOaHtW%j2D1LxP&l1+|FW?s)Yh7a~5ZCl>l7#%>Owo)998z4C{44-ymEdB^ROmEIu|5qH)+)(~q3OvnVQbgXs z-0Lft2NOb432mb@>-|GfAz|<&R``EfQR|i;pCo_8`xMMmU9qRvNu#G-hUm>4B(&~4F;rD#x^CF-c+nSP6D%sOSqpTr}RIANNRba`Y<~S#tfmo+d6XPD<*k{U{-K?l6 zRj`U;-cq*-4tTA%J&s2#*6bP_wgfqxPuA*fjiG#CP|E18V(hl1Ed~3J8r6o9v-Eq-E;lBI?oV=c9d8)-nch6Z zp)j#|9K3}~Owo}OY$+)z3+;dT!*f(?76rLTrc2-lcDP8kbw!5OznxS-5F9%4MsS4T&}Q^jc8&WF6Ya!G1eI2bIM2s4=;hKhhDgz zi;+C9<9N~doXOq<9*fU37GZ?J5Y(%6hi?>l2a8p;`?KpWEOvd4dmIt>5#IP4@|zD1 z(3JFc(xxL`h~p7|4QAEgVGI>h;V#6h6+2$^|2I8l+r%0^?)?$oy#9>h1IUQ_9eLvZ zU7S^;eZ$ExlaWoQy~dtzqh%f*Zu*_BRAvXmcRVjEs?)iy7=q4p{&{^N`n(T_u{Hye zwx|2v_J$UDwV&55FC6zFC{%Rx#098PbPv8 zB;?h4t_pV10^G?iw1@F`#vR|$C>-y@6`yZSeJn1YOwl{W9QHmBWDvHl;lV&Mne8-` z3=oq882?tPq8ai!{*2)hh{VNSaX#ixbbp`FY;if0`*x}ayj2vx+v)N*e)%e6 zZui&kbsRdEJw^tDmiJCw5$C3air|bA6z;sgBx%y@Ylz(kg>(Rn=kInN&!#)?$lu{G zWjyPiAOEd@_L;Hl`gKJl&GN({$noVs-oW0D9Cx|$$xm~owAzvQdbJ!5I+r@nzka2+ zx!`>vV9ItEgR1L#)4j~~W@Y~UV=0A$4GNPOoJ1 znjJ;y&1zx`sQY)Ya<76Iz2y?S^1)wW>2N4Vp4;XBKD0eio=neI0!37hLg zjgkAJd@sc8Qo|}ZI$33!Y|z{|ypDz9#T>dn&2>#;Vbj^os7rf=E~(tW!T#OGsfC%M@S|RQ<#g=pl*N2v*pZ?KHHK0 z>jhVOQx1>wt(*!SI!rzpXkrv%=l!aQ#KkUY@9cxXaPO8EbE%K6 z$LnS9N&hFTa)Cs%+X+SYS*cuu2%u}c{Uwoa^x5}%##)IHhUbobsB2I0HupS2Lt8Qd zyW+B0?+yb1|I@hfJ<|6g!n#}vYMgJGrWf7IiEugUnkBe!Z>FqD`T4P zfBx%c=xg}WxW(xCG4AnS@b0)IB@S{1pb2+=eNGAFA49A>p8w6;Irfz-!3K;0V7xDT zalCJO7+U`RZN8ZgbY|el13a2VdF@_jzl*O*< z=+;nMOlA{C+s)RorvsNWwb6dQcdLtYi=|c)^K4J_o-TJ%{{4oza^DDwD9KWv=Phqk6bjkW zW?^jz1gydQz~J(lDze=1!}#E``8s|3D!C*adX@YZ;c&TaOjZLRsImD{S)4F9Jdsnm zt9hpI#oQjOhD|*gE(79;6V#^|xXY&1+~^H=u+TUBy548+XMEl$jqU(p1pY+hIL>Gu zd1W1?!TRmzeCINFjU2dwa#`*7rwie<#b*zwxa*!NEWm%wt)jBpj2s9KZ`_;@bfLW( z1dxjFp*I)}4@@A^QkYJM+#R{y%5>Z8V9(eCq!~H`Vy~d*si)fTW;sILc*J6Ofv!A; zb!PIvK`~j(SbIL;@_TC&dc>}0N-*>VBzxump1^fKhI7hrI53BTL&%^5SB=ad(!vs7i-5?zVNfLKaF zt{kEh&Pz5U4sl#x(u(N9(%!)RuA7MvM`KHUrRnO6VDSI!eT2YV1gSVv&HJ&WaM(OA_(G_o>5U% z70qI^b$i=xcD+!WoSeLDwgCV0-^q@>)sO0{yL#WL*H3vT+0j#vk``sDYj;t7vBf|J&WJZEWvt@{bv04YS@Ylmp~W16wUD3 zOAWRrglTe02ny6+5!zji(PGDDF>|sy)IfV13E9n1>^ns<#A9U29I|CqF`G5{O~h8r zU}(<=5GaS{KZ1;64o&-dqKGjxz!1SC&?Pz`Oc9NCTJoN$tMdUxXdyiQ$djeuy)$o3 zN7e<*V&(p3C2PcFG1)fbK=W*rwJPaVn3XM5vJ%CB#r<;!{>bx+&>KF_xJ?58SnfQp zF!(pmVNjZf(k%%;S)_;*2pEvy1&EkG%t3CbYN+YeW;p~V4!Us)hw#mV7%1l*8_rJ6 zS7lJcQYjS*$8oIC7!fM6#CrS`%V8~gG$|=F%9?&+QwUJ0CS22|Fe%z1>(?5x$E;ki zGu*MG>CsQikvPb>n~sWFhQs-)VKQ73cNBAbshf6Y3VnPQ3;C!HPux1&-1gq|)r&Am^;cMzD| z;3)9xaM{e#PuARtfw4x)d7dxot&lfVa5Xh(wDY7$Wg< zK|~_`z$BvN2b!BH#Q_r>Z4~9o-DbN*TD89872j|oW-}GiwzWe`Ow4k?l~H?G54cmD z1V;-CAzAOHoMzyr_7{mF+U|1SJ$6^FGLraDSN0{p8FvTvtuYVj!vKrx+h*Tw@T9R%N@?=AdQvT1Ow zu77)E9JjQVJsjd`1#Zjb^p=9LRM!m&FV}7nSY*SowyMie@)UQfSHKt*H! z&J?P-13I=yMhVi^)`~@8JK@-n8Z=ap^ML2HG%f^V2O(8N3r5>BooweoM%JJifoq#Bl&`yPXTyv> z6j>Dt-}h-Wt`d4D!--T&Po2;HX6x{sw%fji2T_!RH)@Q z24b*D__*mSf6wJ!M#xpA5nY3`dbwH)SlAj7*47Rz@jkenv1 zVSJly5w^)dcg-ixZ;oJhG{G)m97`6CW1dP{KT9F>zYpMnjKH zR)LJBn*DOEkzj1RubcgZY;$MRny9$TUmfR_z+d(>QF&_-5V&rFi z&6{#4!SL8({l=Sc+e@of$)oocLL#kYG*0Xx&Rlw!NiCiTIvRd2wUe2W!7t;%!avp7q^U}pO(7c}Jk z;=y;hZRN zzX!R7zPhy^hXyqMp4r~D+EY5GC$_BSpg=V{5HuXDBuRc|Jn_U`HXzguOEJu%7zxT610RV zFu-l0fFeO)P{3^Vpq0gI=5NW2t;W^4`h?w$`T2UIEe#ctOg#COdE=jkCxvUCdhWO) z&`HoM4J;nuJJ4h%&FJcwH+-P2vvpF)x+9P*ytLEHF>X&LZJ>66c@gp?QeivZt5_H( znEXcnWz|&$ZGCyOGP=tlfhd>GglI~UW1?ZLXH~^t+hJ}vI926q8Uyb!SrTu7IsS=7 zEZLybO#)PmfQq7Gw=Ok$#G`)caGntLSQ`*})GhPu&SYuTYHun$0#RAnx|BUz@2Sl@ zDt|vhL2&!{P-plF#E+;HXkGFc-Iy*3HkLl$hly8Ys&@5D<+qgQ^Zv+@&flCnOAb9` zzH+caK~6Ao=nk4>CN|TcEy%FjHEMM<&dLq;^mp6OgTx1odYfbT#00vrzarQN9f+;R zfp=rT{r{)C_?v&+0QKkie`jOi@EuO`*1Fh{`&2 zMjx3#Cf*j0i47c@Rzfh;Yxo%i8`UqJ0wPF40P$5LM_b|5Mz1Mgs8t|0jKQ z*C*U8a+Z!qxj~N*CDwWhx@xFfCJTdN1ENn?e4olRP4BL$;DiuYA4&+$Y>)z}gf6@g z6E`S696=kcrXLJgi<$DSsh@{?5Sr$+6lkK}^^GUj|2%EEc*#)85EC_-@DVzckR;yW zGGy%9H{dkSKhTT>(+7U-Tre{o$*Yn6mx(QJROL2>bVHXvU<(o=aT$EA`Qdw z2{(RWC70#qoEz)-EEbfnZ6T}0%;bnO$4B>{buIhf{&WaR%YBT)F&c9PA(0)6AW2Sv z9k$#%XxA7%6-|(j+wPGbGNznV~@5RSTknx#M*~AvE=CgbUK+2{wE-- zngy+!J)|u(T^Z?<=NBEYA6%BveA0<-2L6Hq2Sh$`!vG&xsSg8OpDWG0Ts02XqG)Tu zR8Y%m`+il2iN9$@TRdI3U|1rW)QPa%i8+*7I;>J3YqvSUiqNKspI>$U#hbaFV29%C zLXeW{J+8Q@CO`}lcMAkNgms(077w3^YQbf(LlKaLBMgPY^^&_R>Jo*bg(_J0f@djy z1skR|izGpSpvEFK7ZWn(!$^d$j-UbaM>?TyL?)m@))0m%Y}C-aZ2$iADH7C2_Z3El z1{{v-&1#7X1x6>Sz%-1%9h(yZjyx$CdP=eO+>f9eK@TSDW{6Q{iUTeMlWq}>{5n}` z>;-bLTHu0PbbmJlv&RW9l_@xKiK{^E9&*WOI96k|WOXwA79{NNWd>s@8!)rPLKVGO ztQy@eMYJL8!1USIt66gYq00Ue@*Z=ULCL^V%5((laIk%&ZF7LbTyR+k@ug zHi+KGg^tn46;;#-VLy6%JQ&n?IS6iwV3wK4agri7LbzWr#KXApi?RwTx+f(8NT{Rn zKIgAm6GZ+{r-NcySX`mS^nas&0uls^Gx~h*$b8@7Pb;=G1m6!J=w5JT{c5Ij*V+h?(GV4puM>DF-(+``yYkk^E?Bs z%}XabzP|67DVen!%J>)ELDXj~XCQzb z{A4*v-f-Zcq!`SuRh2>@YgAnDJKV3Z6BimM+&3O@uqWUy&s6@S-1W^%dA!Q#6^kCV2WMchQg8^o%`!BW+!3=S)Ov6%Hd-{-ZM zyj&+}id@zl-)H>UX=a9S(0Pt$DC8^laP;D)puvl#&+A^2T#hT`>t!BZ`ufw#^O$6x$zCW zl_BnM-cBw$a9N&E#o~AaNZ@%h`@WBr7mYkF-0dCrUO@rdEQGaP`)olfC|N7CfV>QP z)4|s}z-k6=UGEn~kboP=`LjRS?SMCd<7@F@y5n=n=jVN%^K?S^!e!Z7w;8ba6<>DU z2?JQ>+xpw-Z52EJ-cHxe$vVY#QAbDOANtBpowv-@xH zCYLkpivhAzE~@a(PO}yJ>ce#7*kb@_=gsU|NRG=A0!~&kI`5#nsnl^*Siauy&}^3X z!e&%9eVj-ff2#7YwMM4_{urJ+Gu#svcB}o-yS3d>fFvZ-cfeQ1?+d$1>kCGsc7svR zXe{1T#iHl^?uw2 zJZaNoHt+FlFupsSj>C5vtcFuevAFHHB6$92cK;vx3_?j=-{0=rt_UADef%h61pQY{ zc4d`JlD4jJX?f0U#uPGU_XT6Or~Ljx)T%Rwal8{m;VgJv5;MYo1w~O$F*YmOq9ME+SBId$GPhO0;fb@${y7qmJQ(J&D z!j0qLD9`Ed977>%?#UE?_juX^`okW}oKkZ2Y2lRpiMs6puJ5?rw0>8{Zuc!TXeX)1 zSE#v%!*kD;+l_BK7eWb|rR4p%Fhc#yzdIfGu?14ZsQddy_*ferX()!?Ph@cdcUW;; zez?Pr;T}@GLOA}fb;)UtV~dSrPLBo3si=mlhtXzBgyB@L-J-fj+e4U=WBl`a{I!5@A?isY~Ns&)IK<$FIy!-|H_>BJ&@UQyX5B=bH{z(lSe_L0DNoc-U~zB z3b0@?wEC=Rpk=wkZ)G|Ci5>dPANymNJ?i$oulLp`v>HRk^8Dd;wMPJ()m{d@@0z^; zm3_|>+nnDk86LM=VY2|s>4UrH_20IRkHC+!>{G|*b@hi2_V0d2WrU;FP5WZ`Jp2H% zYx3%BHzbuq^y^MnbmO?J0Y~N0`w#Zr{aDSm`>frqF%o$`VZ@tZlsUcdi_w32TF@eo z(sXF^yFV*dP%Zy4x&u^^uJyQznJ*^%o*!tS@A)Y&5VE6q7#WTHw>nQJHV%#kFi}y* zgW9p6I*f)@z9LE*hN9JeL4ZL6Q0VV|i!f8xMa1Sz{affs&XeN~nz>MKtmy^T#}c8i zlwfb_E{vo?DVy(;rszy@6RFzDCIWoTOdjtAQ#k+dwmtkbxbNI4CVzbU^RqOO^$1WF zyv&0@^{69>6iYT3GKlkz)f$ZGH5dSkDhMLML`Aq1O91F&3dn>7A&-}{(+?lUW^U|A z%ieKbb3J`ux6td;a-JL4KBwAzc~B@6`7{XsY;A_0Sbzgf?}y&j(65HhxA5=oYQ>H`R{Guam@2lroh1YhKE1{QnZx<(dlsFUGJC4dNfK=+q;oSN5>9gB81S`*8eafzFr;i;1Q`1cPpwy z#0*}!HF>QgtJP?Uzv%f|EHt9=Piyy2WZQ&P?%xe3s5Bs_P^$^GRE&+bT5ea;+g?u=YwdixovmhfiD=8VThS*oS-10e>`ktRc09S1 z&vx6>txwixODzOv6}B2}h9u&Rawtf;fr4LN%A7>A&tKr62bIa$e3=95Eaqp6H7sZ} z6iaR1;x~S-1@3$zHJz>%%1vCA+!7>*%h*5XEaCO0$CrL#IYEXYNTdFU zese&y_RXRAho9edm;nWP{rNW8vR1T?PS-yh6lRuV=4he?&CP3*?1_ox5)A8};A*)E zXCxn6nuRDd2I&x$QL2aqA`0pH(WM;@Rn+Nz#b9w$G1BL#7@DdjQNPqsv@l%#s9>=; zqfTlz7_X`bIu2XAGCo&=Q{~4Q6;K&{L%ZMZHMSNcr*)e{WUJEdCztgZOCqOg4ru5` zz*uF;*hZ%=>SBv_{|-4wCMk8RM7L>di5RHV*szN(C@3h@{K>aeGbQ`QDl0f7;B0At zjf#; zs-&P1!p^p{VhKKjCj>%5`z?w!j>$sDY-X8qm0l{RrwH62iRReR^RI;Ok(hv3t)P9l zxP7hv@Q(RBmK%T&BTFjvmEH9t$>8&2t<>HhS=BQhSN&QjMmUQkr=kxE5T@CKXH`_e zD-I;8!4*?iAtkBBAO5uOJzmzFIE>pFZOfB8=$V60N?eJAW?J~Q)IU!~k2G+)WM2Py z3f}$nEM2|b9Ud;`Ho_|VSsJ+u)OMZ@b4(qZBSkGLD)FaB=_zk4nJpArO;OURS%b*8%nW2eKn;ZLoMS4El*jPkQ4|puQHuB8kvm1v;mDKMaY0^iyz}{3BKFg3 zNL1g&o$DlXwOl8RYQ^hhcD%sO%p#5NV(#zX#H#-WVR8tsAQXp<2b32EA zkwi0oQ`~AB8k%ccP_j2eb3A_S7Dd0gy4E*4KTWE{e*Z=caPTbG>tdV2nBG4n!_jE6 zL$UR8Jx(i;PUrVV;`e)jYdWPfJCb$Jx5VxpboTk#UIoCD5+Mn^Q^Kg|%5gFN^a~)_ z@kIRr5I645s~8$w{-URTHRf&w`M^#yKL&$LoU2~UOT&4&T}b&|gG0mkF4roDr%0#P zTV0_8g#CcR3X?ouaXr5T*CMvBeCTub%DH<{7|rJ?F*e&>QLnUFnM~Huzcecjul;&% z_PYVvBeg(q%Rt&~l*)y_z(-j7+F%y zH9{Yc=#-VQh^4xoG`5EtAk>+%R@oXQ+DE=?TtT+CjX*3csg&sFh>=mh# z1nwKtw|g`|1O;%! z!=nnVf0h*ro^&BKg%hhWLzSAH>D#&O5n5(6CR5bkhZBV=H_%MBT9}ctjK^d5#||e- zd;w+EcrH%!rdQ8n2rIQZ!H48d+!>xo3O3-jv6(_}8jS`k5(;Mdb+NLh*&3H$vPjdIMnD)M@lbGYs;&4Lbn=hOAT zqdfWTS9FHY?=NR^f0pp;?GI!snc@oVIh{(;siJk<#K1*u%d{~GMz|@Ks$Wp0L4}=y z*!k^_-Xxrj_K=>Qp(+)MIVCW?#xtWcHX99p^gzR$&P~X7XR;>}jK$ZR%qhGqndoUD z1f`QnEdGJR3e*cV2?0#eT59zAfR}8CVvItvb~}AXm#e|)dUZPEcUE2BXP_sb?_6pb z;_yC4l}@c8tdK%GU#SJ~<3235D=5TSV(%x8;y7F$39VOa2lW%@?u^4b-ZQh-8cu=a z=<{zyj3}|WUoI(1t>CnZTTCWDlGeH%$qp&}B%0{clzZf$d$^kSTbN#$UdrA+8=ZcS z#o`?w-33Q?pNOf|u7_Ek+i0~ULlXGJUv9ymV(9HRm$NDGPYQNmyrkl5SyJJ8*$FZCx-6$^qLZ8kN4qkTSVKZZmOwfD2-jQ^g z(PFikk9d4U$K|Y#lSJV+y7`9nTIVXST*5E};WP8$ifkK|H#ys|-2zY+UCtIW0Aulb z%NeCofav5HiPmvKRxEBo{{I6^L9@Q7gr2>6pkT0Z>t51Z zbs*lOv3LJby7uf&&E#riWgKGiN0Z1e@zeLp{l&s` z|B5O#8}Q2OuaFRBGUMY9`C!7wY}lQ_1CKmH_pTl3+_?)z(Rn`qYzhk(ub^(76jGa{ zSe{pc#-M^EA|{%WVjmw){D`BOr|H_UD@j#qa`N~|29Fp@qk1(dDL6-|^m51Tw-BL9 zcJ16jLQ))+t0wW?FN<^q^+-YHVJ=nu;~*(57uic5hnE z$5TEdBBmmJdS5};b}g9o%?!T!>RT=p`RLrS9lFot$kA-NckO`Ntpz(CfCLJe{q0vA zJndt}iWL+V74rDlvDB_rlbXp@sZueD3Ga_*`@Taw^yKsO>)DB%%p<(=@^gIt)ptZ! zsLV4jzC@G8jp^2|1q?iuKk4%Crze7la`Er;&Ec4qG{ct8LCmpC!bAW>8f=!Pfev#LIevIt)gAK z4%Dh%kyDvR*t+K+oxAnKtNQt6^#&5F)Fw5hp5@~<49=cCM_gRoMZcTE+QDIj5ypQK zeym{hU^y-7S40<9G)%R_R)%fBs@UYdrodEHOxx?BI8GKj)TQXfNa4X$T!EY- zRa(@9ah8xY30gP)HB~%`6kl5=_N|iH2tQEGiI1#U*uY1zrrHTKqrK z4?;o5WtRX*kj0q7gMk|29m3*Nl!k2(N_H*&o;N<8#w#CxPKD@bM*7%@0Re_B!xyq50~~%r!@xwfRWYO~Kyf6_?EFQk zBZU`TTGD@tEJeo+LZC^XwU(rcR9u+SUME6gI^`(R1X+TiXqYIt0+J_|7f@m#QLL~q zR^L%T4;1s8NYg}DGz6waKO;N=N*z`Dt-K3+4ur70jM7x?yk9>E-I@>K3g*%Iv$^@Y z;WX$riihsG6|c0Ye-w#LF=K#`7*fL&Dw>oCX^{s>#cgp#+UrBeQY#f!@!&_;jEsgw zY7IdTsPuu*@Y#=R)+f*aX?;EoXT3=)O#q>x3!BeUmSPIagtnL}eVDj0P;pU;iH2?q zQz}y8^Odr1{{d>$sBzJ6rm$j27-59*cj33HfG=k3Ii9=F*BA2wUdrezZvdL6$?4Ol z?G!wdzsUdury5ZzZV)Ppka+A{9>N2{Wf^rgmzaSEO>?8!#;!{`?^(A)Rj9Tes@o!= zRTWB$^Xbqwow(Q-Vq;^8i;W>BHj#Vo8;w*Wtm{h9q)mn*G!P!! z0xWSBH(>-qs5aA`ZBQzzZ78WAqEMuU2AHZF6l-6E2EuJ?9@}QB@Bpqrk1VffBnm1n zE9;C`UV5JRm>6PXqlt@+B{n9W^t6r?n{I@nSqc>P@mgRGJ)lG&uvAg35UUr|NDwNj zeY+Q6lPY_y_St6jefQl%Tx>jX(Xk}N#1R*rK!*-JkRlRrAtbnM2eoC{DE5q~fESIR ztes`qxDj{=6dKrVwMqtTPDrDe*I#~~goHR^qT+~&iY7WbhHgFklX>!tZ3)|Y$o85N ziYstF)t)be*IF0Ck!SXx31N+ma9i&yt^l89b_uK(O993++}pm?y9uIm4d6ks z&+DWfT&y4{j4;9oiCNhKu9Zj9$~A62rx`c)iUo?)6RGkBA`|lJT~a>`OS6*{xC!KH8G_h z#irMhGGGFgY3-llVF+oA83^E(Z=bL=b}!bO;EC*-)6k z$szW|z9vZ9115yPFf32BEg{UGwI;0(g^3i_gNAgBqVk0ySRS^&(ohIpLjg4$fhC!O zLz!Z!x2WPz`bY-GQR1k>Se4j*6ydh!K-%s;B$y_q(5we7+bFhlxb62HIY#Hf?XQ5e zt}R7SAKUq+xY)PEA3CL!0qx+hCoqgK!uX%Ur3yaEzYZ<>C~vqqe`}idhrEB6`kkGf z9lW>yZH04ET45aw3|ngL(rncV;I=9+?JWUw%8Hv^C>nG+TO8TeIb8J+stt^U#%)ZAx)r&U0XM@ecxf*0dcXLiv+WT)l28IbN>+x zE3vCw`<&a9b7Oa`A6f3_-$R)*Ny)Lj+qq`sNY3XKk#%@K8#ZmnP=3p&`RfzPGJndz z_WyR1g`dLQY`*(p0mVLNoPvgC@S0`kDA;Nl`1j{PfUWC{2wmq+{+aQoUhR@7H=Y4A zO0gHU?XhznIR3oLI-{*4C}Qiz4IIkMw!MNu{Mt7f3LQf);>~gIla-Z&s;K;xSUC45 zzWZ(#rG`UUZ7@ z(+SL)zXYGKJ&-o_NpL@h(7|ur5bYbN#EzaRg296ala`idn-113wY=@(Y?0WB|LFFa zg{8l0W-Q;E<#|&=#Frgnn6klYrzJXI zT;wKJ*8B;*cBmOi$k_vz5RgzgiBUJ*NMwYY)l23xYxZmk?W*e*}gZj)*ECpcTq5tt?H-L{ISo_(DQrIzYOV4rd}X0R=eW#|OBmB5%@ z`eR|*>n3zGgYCRX$L&@)G&qL+6S|8|nQ<=nZrSx^1lDcY?PcdGXtbAYhm$N2=%eE~ z4KL>IvahOqe;Mi^oIU&rs|_m$uGV*C7-(HHuY znVE@Vr3C)nU#|v27Bl&s*J)ZeozYLcfLU^m`Lk!zp?ya>b?nHDS&J~GL1E58Zol;= zQd_nrwM9B(o_T|F`946hV(B7w?%s(XKe^e582#{lG-{U4kZW$^LSbR>wiCD;=^Wa= zk%9d#C#6{$W5&KgQIQY5D3=!>8$+W8t$E><*EyYakgNLlrfH)F47++HyN{m55E{ZL z<>^Nrrb+#_O#JvWjN)wGePn=^6pH1d5qhVML6Kbk=qG;gzQzqiOSW+V{AUOl7sfO#^2tP169glogACId6uZPEyuS<&aGa38zXwq7DrgfX{Y}>t^ z+}v!&KJ_?FnlvJ3(T z&&yc6Yz;mMh$1$vTTcHzmy_1KC2zd?JWoFTH1B`<1Esp)?CF!-dff)^nK4yRQ8J#<{p;MP0%$dI&KX4)Y1b1FDh?eOsY1uTD zr=ED8bA?u3X2IE0{PV`!X`IrADN{aT=lZ4eA25gpP1|zK&9_tP%Vov#MfB|6h4yXR zF=^_zlt>lb&_S^udqV6#iA0(bq#wWU924JtgS51kbi1rSt2S?E!B1atS@-rdYLvo& z{#WqA3op>ILnk`4NoU3nizr5dQOufO7Sg*{SK78~%gnjU&;eiR1%?bA#ZL>CqXP)5 z%3lf@YGv9lf(CgQVT2LJ|8`u;7z}mZ{g$y<{=HDcFf%ig&6_u)DT-1y41BQ%{67(v zQ^E2yjJWY;?!NC)l4IO#-@Kf+#=pyhPdtUH7xLW8uMi)hkXql%Pm5OZ+MDl_oZ#ZU z@$d5TO9ebV_6aWJUZ9{b4-mZh#@poPmGJT8k5LpiUXRE2ZU~e>g1hAH*IuD>$1c2d z-R+c=`f+>R2+hSkk37uq;Uh_kkyMD%dFqMLL_|dK?!?b{{Mpx;{?4N)s>*$19%9gt zYp5D&Fk{MiR{XM=H{Kk_hIMNge(g;xS@a{-D`-{~YoPE!av|pwTQ_dvwaL>l3$l51 z^wZpU?<4&4u2DSm(g!SFvWaW@HsQq=Un29Ik9Wqu%fbZ<89C$%X8!mSdv@Cui#)hh)8*nveLbzXeR;%NKw+wVAE=%YcM1YC-rpMP0P zO08b3UcLlROa<00U&_LtX7m0>(=lBU)T$dt#@6FhtyhmPznn>O9GHb?cw)?GF1vgP zci-QHho2fp)rwJE)uR#f7q4W(M<3x;^11ikN4f6C>zOun3h%!2E;DD%=FYqCuqsTY z<2^G_L#uR}L_U)~`Hc1JwlZthY^48oW_~@Li4!LA!pq}1a`ZS4KJ*Y@%$UKh?YoGMie~aB zud#dGTHYM@7WJDqMmv9yr^k-vimPuTy?F|WaVpz)A7iDaR~hkL$B_Gp$MA_Dd@?x*0_l@^ZDkBPno@FC9l8v4v{hO)Tv#Q zFMs-sx^?UD@>`Gb{nUxfpTCIbUVoFUz3X`WjkoC7qdP|ruH~+OKElm+-9uWFCcOLF z`<5?QDAcG?o#?12`_mjo7-59*{|7FWFLl7VIRNS#i)T*68ylF6N>1x__>qD;r{fIIP*}8cb-%OoM(`W8QcU7Qq%MPT~@z9{M z!abwMaXK#_Me(94l0v6I5rO>Ju3JRC290IApo2U5_eVPlr9-$;$-ZRmS> zA2jVOrs^T4Qbp?4P9#E>PNaEewbzs2Ddf=6Q!JjhfWepDg|2x?NpDAbdZXZ!n`TH7 zp&-3g8$O!$73EES3el40tsjX>TGlF() zzolWr6xy^(p_Oxme2L%V%ykR5vJoi5BS~sKU+<6vJfGj!B!X>N8Es0{vC!Zqy1zb3Div359 zq7zBQDz#|UstqmcC$eb8dd}t-le>K@m1{I&2WYYguP2JHr+!0GZWjA9j*{Fk zo%jf^MbQ#Wp+pFio$J<+-uW`FzVUiuWht6@iXUhEOt-6UrBDB>(EQnKTf2ZSXZ}FL zf82n9ASE@OrZrrQ*wLMX8CjT8U|)SDibR##X5hLPF^UzWm}#2HyD`ox69#BTR%e(WINC zDm7@D+Jva#eL0d-O0zcUG_C38y{U7_J#&G*o7PafNe8aK<1P|~$-y-n*mE)q)g8l| zZ@*+w)dU7awLaHns`~?_BVmLQMi~Eb_@l*azh~54$}qgtapm97%F1H%=FK76!GHIo zwJGhCBN0g3l9&_}6cAOp5O*YO(? zcZ3%MrwW)5*Oo=UAykcjJU)izKQH9IM;>Cv^iE9qU<^Vi7`C%e=tYcw?L~gtn8Uai zA7$5urF<}JFVd8l2vlKJ8cWl_?=NN4t+&&%eP<$l1&n>sORbvKQN_iQ=7k+b6M#Xa z*MrYzk?*=)8ijeKn0`Ns>cSJ_MMvUxyNGaWk@VIyzki&_6<=emt--nNH(UT#VK2G#g(?i`+f;WgT{Xv2)DZ&M-Gs+?Br_UJ{$ z)U4l_2cCYJczG5Tg}5jaUqKc=sbDBBRK-PXbOb(sDWDMN(LgtCLqlRSX4@fBlj0&D z9lBh`L-*f-CW?7NJWWES8mwQk1c?HQMVIGwEBFi@i6ka60@JT!>N;_WN!<15)6|Xy z;WvnnQc=}xP^`6Lx!omxzfMGy*9vL8Y}uVni;g`oBsMRmWeEy<%@h|E z6CGQ_3VI4a6%^#>5nm-fpvj$>5J%pT0!&k&s4iPJ(I7fD8s904PFi)jE&3GzDN*c7 zY>U)Lr?fDi=%^}zuy0a@1pK8X=%$sWYnlcM7L|=-dI?OVX^?jzpNObvs{qHY05=R3 zMX_n%-7YLGW{Kw3&|Dh+QXjtJLL#GM0}oH8;YZ+b021<4rv%0Y>?}el?WftGIY^nk z!U!XbF#fY~F(dBx_WP~e!HXG=Sy@>D51^Ei#Kc60!S-*=q7i_mQn7Lp2X}7Z$e~P* zo;XA6PVLyVW*Nu#>|@84oy=dll3x9#fWsTdQ5B6LhC zi1tKKr%DtHfBJ#L8OJ%Ckwu};u&Q{=1g;D+j~}IR(X!ND(nwCO%E4XRIh>J2PF@j>QX8{){%nlm3uxX5 z3`N1^Re#gscaq$Zp*JguUkYLqlSxjD;`_-{IhK*ZcR#M+tUrPlO&g(N7kEe~Ko~SC zrG4j&iH+je!98RiJ;mY79J=-D!ron*S+{y6hYp=!{-UL{YTp)w=Gfx)nVhl##innu zLas*-?I$s*B5%L_4yMr9z3(W|@fGQoUYj@Hoj}dzooQ6NI(cVKk$2$&k3RYsy?XU! z?b@xx#3Y~;WwU?VMh@)DAijD7N=gdZzjYNZmqw9c5)l)RX_^Q}YeG6Qd*Bob1jC~C zJ2tnAP-00*X~gmU>&QNxiRO)`$k2$4iNw;@u(WrDlqga`kygQvkP?YXWMXA1CC0LE z<8r)i1zav7ViWB)NK7FuH4{%9HL6wNm-!3GJaK|UCr*)XdQc-1Xq(=cpXYr^UVc8V zhy)B%!Q)bq!XRj_N+%P6I*pogaQ9}mu3Amz(PLy}p2igsMbEz7nDE|5Y~8Yx1}W8$ ziZ%Yuda>w`R2rl{z#+tm7v+dc1&^Z91`j@z?C%wTo?A_A_tkX8QH+fmhQ} z)gX(cBC#I2gi4gx#i6a+$vmD-PWE|pGej~_QE8N##@4mV*u7yBd-v?-z0bcTtxInb zA|i=4@;P(z1Vu(@36un(BD`^2cKKy2n=_k(`wnpUSSDw4i!3sB6w32aTGQ;uP!yV^ zw`bqhUs$^EXO0~|&dJtF`DG|0(1!nCiy=k)pf-})vBBaAS@_>ab=s(#C8zQeDK$BX^#7=X^-6)IGqZQHhv zP=&C_2aTXC$zRwlgwPmx^>B*LW-(&OwY>H2N3`wMg>D_%a`&hkx$};@>Dsdo!>_x> zl85uq|)pH}VWp8FpnKEj2Gfe@A&#sl}=#>Tb3FzBiw-1(3DIeR|OGLodU z4I9e{oH%|w{rV1J>6B~L&1 z8a1m|MsvHl|Dng&uwn^Ah74!M_djvN9d}YWA%z`fRwWS#Q5p{iLT0{4?n=P_g`bc6$7~EpAT^?D;on1P5LakH31fH zq}3?DqJfYBr4#A+g`@&R(Xmq}t{c&ZM<02Repe3W$+0g|Q0hY})_hxI?Zw26OWKlh zLP5bKA|{CkA9{eLv%X;9l>@lx*1Oqr=oknuiZsxq&sLF(=H7q(lP$l@XUM>QeDujw z3QRAC8pF*uUCU*in{mgTcW~99t9gIIBuaHZhJr0&Cjc+l^IpGsIyc=gg6AH(pTSoR z;O%$bM@OSe@7`qRmf&%DNvTsKke?}?DrNzgDs8&=W$2ZCcKIf_dL-_Hh#rW}} zVgzUb)4TLy*ucI#{?EI)dDP9+Xx56`{`CMAqT{*eh9S)U_G@x4EqrX>yp~CyenV-gkK)2SrcHXEbz63!V{+`^ex7~#Ei$vu z{R!V!VT2Jz82=ggElQc+3L~F9d9sWLutJ3jv}w}@RaFs&F0EjzVtLD~{G-1zh+@;U zNNH*K;)Ilpz$<4jMV63tXdA8j-pRa0OG&MhV0F&^U)a^GPUSDCm_iANQ<$cSs#x`| z)=k;4+#y26wDo0Gbh}tZbA}FtLC_eo=wK`=Hxm?xzC$AL0~$yxPs)(e4y}q%Ux)3< zu{=AbqM=Hkb$b>Xs_pHPD0UsOX&Gd~VvEBb72!M)2!W73Oxvim^iwrVEG<_6QwaNv zjzy~3V``mG!Eg89k|L9KQHfJ^WZ2rZnjNo~LP19$3>~BRJUh3pV*Doyd3nMIRCY^L zTcO2LlW@ky3Ct^H=F6cgakQ5Ox@{OZMMHM?(LwqxEm)xjCF07!Z_lSYaCYpm64>XF zx;@sarP+)KjC(M=7?R&6bxdI?AzR+WQt}H+&`p6$l<>v$ANYCYcBXy$E^c9)C8BKW zLP>^HQ@6%N2&+#B!15NGSkcX6W?@l?W98>9Xh5?n)J#`L&vmLr&Wx=xtujZNN<8;YZWay4^{%K{$pYY7XlMS zN(?(C!}%0T8CDDlBaATq=WwZ9zR=f~D(Wx{BkLX9qGFQml4g(?IX{y+;IGs6k1 zT5wrk-bnoZ62^^tgHxxnEd$UrFolawow{(%h#`UVXjW#Db-0irXV(aYGelA-K~7(R zZM=w(zL@OXzKzenm`+hqDNf_!;u5*}=9{Qjua2$l>JI6<5)uNnw~CN4a3DhRorF86 z!78+X=7(hWqP0p93D zo_b;o(UESPn$ciQOXyeywSUXJE>}blJXQ<7mSAG?!|d;wJ8u!_rI;d;yYG1rml7Po z^5#MrqHaaAayO-EE0S1YQ7H{fvxsqTzRvF5M@VUwM&G{O5r)D1Ip4Bq@d|Y5aP&cJ zd?JrMKAM<_$bi01Pz$>3SO-Q!C_ydZ!2ZGY6&y7s8zz zdk@)_!U{qtq_=6ubvImVYhstFF$#{6a1neo2pQ{gpa1e}rp!BK`U8&gN?=|^`Ll%) zMi^oI??8Eam(cBhgfp=GHn-bNT3Q+#H*N&LFbpBXgpfSD>n59QYzii-=85=>K~AT7^>+lALId3Q=A!8YTh-iNy35;q&|Ps}V%H-4`h>|2O&*XlF=&qym(p z>pn_K70W*)Oav;X-9F3sy|^*<-*1fwdF{jJ_o3_78d6mkE|=>!`(Cy`Ay0btxr3{? zgpyJnzv;s5cB82Zis?u9=i%2)5MHdjNDWgcxV>I9A^sKv=ht&$``t|w@KIV)h#^(m zW2j;vFf@$_w>w}2mW4wJ9rDogH&$+hJ%M3_5yt-{e$NwFp33E7-aW^gr)kIg-<$eDF?-N*Lb z$7oQm4l$7te{oO32qTOz{&(QFDuMs#zQ2d6RjZPoo*wWBo;h=doSYmK6vcY#l~^~d zzoAlCNFUjmhuL%F1U_+TFQl|-Ov)UKv<)!96-^tdQ*Av5C8G zxru>;hp}eE7Avn)hBi-zw9yGP+P~$WWdJ$|ojXzHC)9`c#~?BM`5Zd9pCZ$=bNqtu zSyj;nGDI#-NCnWWkgSkoW$fmSH{YfRiE)Xm{8=yoAq0~rOk~%-z2p@Z^72bBlaX}_ zT{u)V5-F^_Q$tZPi}QHozJIW3*8z0FZ)ghpDJne2Lk~a6v16zI;+}*NMi^oIXXC$O zYn9(Ow1D@I@&*D_sZxdX^z=ZawU%R|c+J=iuGY;SN+9q=QOw%V{g z$!Y~$UdfRt|^$PSgS@4_?0iV z)`D8V2KhNhcznzwoH~EOmJ}>I2NG#>_BrcDV0|X7N!9&@oIZWZTHT_I(lSU(yI6*9 z!?e~4X2_g4*9-QytWtMi@DKv>a&svuEwTKb!t#(?p9iDtTnnoxBkxQ$rKXiKpc^G2 zeKbSbWgtyI=g$|S8%|&S1PZ1C`#CGd`IP@!jW{&G9^6`HQy5`{5yt;nI3eHv4jhl5 zW9wtBuzKkdUKWCOtx_3qc~|!A+0BAQOOV1%m!5q{ZPo~*=qx|Z znMcO)lNeH=Nz)ee?A?<{w?@r+wW&}s2^Eu)f^#fh^fTM{9V02ZI@gXIMuf*@-_o7X zsLAQ9qx?8$9+_wJNo$o(->wb8SHS!q=Wr@3lTPhh(zR`KW_mR^zPM(?roZ~@|V?Y+PWKWbQD(%98R^$31|UT3)_n%O^VK+;)n0P z;pmw>r0St%^Ol^?$tEKsg9c4na#`O##7B83DavEf;zexVb&$$6>oQ=#Kq|#VaP;6l z7A=@Zc3vsoh$wpZy@JLK>*9%tr(vV|cohX#X(8)ZuHcmy-k?e26ow7xLC*2R%vrdc z+=4ru;nrM~-El#v2hu`?hU4aBwdtv(L~lr3t!>L`R0;f(KX3qRYoXst!ZKp1@Y2TIz z)ut?x)&r7a6EYj7jwvOYrqZB6T_U|I7tWpH=bvVCFf$8W(RAw6jdtzZqDZWB7(V<( z1$;UEGtxU;hQ};so@d_t#q2wLg4o20jJn}kylxjr14XDI;}iTJf@u=Jn*|X@7-59* zzZiyL*fj?KJvfHo!i5V_6cIw=8hqsb%V2#`TOqJYHR{s3(`7WMQ;TE!xAU)mJxrb+ zNpZm$ZochKcJDvT*_>lM^3+TC)M%okTs;5e!%Ut$8J{UxGH(Ifc5KIw!L-SfcyHnq zDkRs&8xiTGvD?HISYA7!^TsQ$vvco0Qd_q~Qx$|T@JoZ_lvG-G?oORLbx{;Ikuk9} ztX-MeUryoKm&fD7gQ;j#Z8~+X~*6zmi7cgn!$2|AS2gJw6@beGf z^3U6DA=hWHa@h*L`RZG$)vU>xjNLpw=5aF5=aY9fn{U3JNrB&wP$iXX)TC9Hel$&K zf|+}oJ8!$4Jx5PbF-~FhV-K@p<4*jgxlH}^Gmf7sqIT_uM0z7p5tyb$-4o1))2Ljz zBCR@gphap+3eM#4{NrQryCSJrtp<@^4=&Y1!+Q0Qr6oM`_!FEj_Hq39NhZEKk+{m0 zaI2*}bmxsMTE2!I+jesAU3U?cRF%rf)hup6(+}<#nzrsh`*vx>sd>CLZXDCTUPMxb zM5ayrkmsKqOR+SV`o-5QUc8bzwd;})8^iwn`OZL&jj2bbF16eu5L<+_{ za0hdite`w?qcbV3bMJ$rIj5_jMG_ZZk;ZkZ zG2_Fxcz@F87>1v(rc7etvW+Cytj)TWOStd;$H>Y#hhcm4oVsCwL})I&QE@cy(3|x1 z*2G5|d_V0&#=bIv*u*3@tXav^Prg8juN1$umU^q<9PY0 zNBC*^Itu+h-XHfmuf92f*u-R9stZ-MJ+px#uF&e?U*~3CDpxa%Fv1Aq{{sGuv^~cV zv@*EMDlz?~5ZE0Mf|~Uk(xYb!;tW4ujenJvt=n_oBli$(6mUGdfC=xs!IKYlB`N^&caFTyD2WViUJxosY9<`skrmc z^WmI1Tz*AAs@14LoVy2~KJYgC4;>+?MeV>)nbqAdqdswn;CF4K-lD17Mam|&z=+XO1R&Cr&i4UsRsKu}m!*LJn$j}=e z;KZ48)KaamvME8A3N`A~qieUO#3T83!rOQv<9Pgu$Eg%kLVk(D%&%wCx!H~QO@+&^ zxSA`vHww;6NIHN3OsSAmxe8r6cOu^7;llpi=zc%_2MwZOofvVDJ!z-E|WMevJkxEf_KK8WhE3*|HVHS4?Kuh!ON? zpURT?KhS^32wFFc<-pd}Y}vJs0eySoxk$pOzf{sJwH1Sh4yC5Ih)HucFyi{*oNHa3 z*`uByE5}E}xF}MZG^61BNm?{dVfm_!+;`hx{KZA2wCv8v8?NQ%kpmbp;&%4z-%nyv zdm;j9e|C`AG>M6gr&EUp)K5x)a|d|w*{8X8+_zji@G^!D?8mLQ+|9wvEE?6TQ^t#B zaYLHas#~82AHAJQicXw6lBtv4WAM;^RIFT;I&~XSSXxZ|diB}6XAh0*RU|sXMg7{f zXxX9}QPEM%pY{>wvd_}4bsJ(`rBtt8oh{ol=#bV7)&497>Q%5zP}5#hrZkZP{H985 zVs)+=c_XsqG~3s&;O7;qXfmt|hGFo{^r;jP%Y=_VAu-Oyz^jLG)v%HHg=&8gg5G#! zAzRn(BfHaIb7po|U6y3ak}Nm5V`GZ3={@uo0wJOI(2F5J=$#M} z5-<<~gc=umLLh`d2qg)aVq;Tn+|_K!>Sf!^ocH&~%5 zoO5Q+cfN1=-gOP5N90kYdbt0AhnYBGG;h7Vm?su4Wb~L(!~laku#iorld=glDqvrS zl6r@1$cF6yf+?l`X)rf-xo>w{RR4tmRw!Uhezq>T3K5{C^^U;D6PWLR*@& z;|B3;n%4FnDr;(j_c11p8BIrXJ$Qn)B6#AL?j2QCfuz%<(heR5Q7O_+g8sC{u=28? z^sLYSgee3_nDU{y__Fhf;&93N7x9aE57VD?{VZeSX9Y(j#cvlr$i&#j9_rUb}1={l5)Hte$Mh&KNZC@ zSpc!7ej_8RYbh?sL!lW}Q%g_lCLiD_3nxgB36o(gWo7Fi0+yvSKw68S#6v4z{#oPF z-@TC=e{>ZuzW55Ce7=(2u3lW@Vvs5z)_z4mGJ`#Ra|=HBgWr!$y(p?c&Kte#tGj-OBq*Kc=C%m9!JYt15%h zep-jJBa9tUN=Ii$5T_VMvPm%26)KZWEyVl!=&aUqfG&Mc8nrBPE&I|Y0r@Ma=h9G!rCu_rnYVhbFaFDM<1WZYp=dU z!}@g;6&DhZCrG=7bi9YZz400c9eo1l{ctYd|Lzf}pyp0daUp%Zy?CBM+lmpR%BilM zz!_(s#YGpK%lT)0pRrZLg3=~3Fwazch9yiOP?=^0naW})C@dwA4nY0-2hc6bFUOH)2vywmf8t3Kg30N8wDLOjZXzMdvbjjtM_k+{fs&*t|QiO%P z{cARe@_grfq>z0M{toxwKaU+}OyYsNeu3i{1dS2}*hGs_1`UHE{JG-B<1Bt>F(;mNA!p6K zko^zX17#VMhM29vO(R~KR3gFJO}z{+uk>kkB^WebaBO7^crK~5gX0;BOG~I3IfB)n ze}Q;uy1F}Q?Kh07tRf0Q=5-iTDiBEBxt_sw()|6y&lo*^E4-e~y#CIIoO8vsTzv6G z>^N&Cwr7ai#T;_f2|W1V-PDvRo>=rd#*UkeWoeH1-f^6F;U%1Z?wRZ`y)Ml00TpP; zhytw<&&6?^Y~dZ{kD;%|0ho-Eb1=Se;boVR?rP<_xfhdk1lM&)BojE{7>Ea2Fvh`n znh9HNPfu$zZJS&097FxuM#haF$C%1|B3?J2tyoRU^Kf0)PsK?mNhW&zG#znBCwl2m zJHhlfq|#}S;J*K+A8Lne$cAjl{)eX2mJ@ToZd<4z^3NXQ>pru;=^slYf{qrk%U=8Q z;y^OdZehM;^#a@7%#9=UqgeNsx4H&cEnfbZR|Ls)yTdx`9!pniXHHthn_C?Bul{0tl`3xUcl3CaVL5$0<=G{fZre?a6!syx> z%7%|-&%O5Nrh699vgQkRoH2&o_TGg9B`Hd0YuM5M5YBffVczj*8^)_?vb zd(N54VaJ}twYT2O$}d(?SX@BeglU|A&Z*e8VO!j^U1*F6IwgO`vhZT24OmJa(Kul@0H{jRdTXvI;R+L;@XR6$Ix`nz0@CFT8^* zFTRye&(?GJ0efRbi?Af^Ya^>7hE+}CsBa(2tyj!t{Fvd?uW8`gn{H=(btM*Q zeBEV#>iSPHejKAAh9^-h9JGpJRFoKouU4${k&o6sQ>CyF9Yc98Q6Q-zXl=;Li!f)m zUHRp_pYhk%r?CEukEs|j6C3axhu2isgy;md=#Uq ztGM~fn;1KG6lZ+@0Dk)Od-=()o@T`df1$0don80dmoZf%(Z&UBXJEZT5s4I%>TTnO z%dbOvTG+HX&NbIwPtB+*zP0zx+;YQJOspHrvgOO!X8L57EPjtg&pbzdOtX4@6DJ&W zGW&dMHh+8THGX)}g^U_iLs>;7r=4*+W2-BJK2gDc{@6~OGM1;FdYY|f&cbLNWMPMC z82%%Sr=uwG@UThi7?l;}-22lTIQz6yS+r;o!z_niKlUgOEqsl?W2nwzMp9KmrXe4lGCyNC(Xwxb}wfVp!oX65qt zxcJ<2c5I z$(5T61aIZ=x_@j(M)ZvIWmguzo`W-Te-w!^)U2x|*)e zO*AxZLR3B#RimgXi_p6MLuT!B8V^3akTJsxuuDo9JEoR=%VJYwGm-o#B^4!T$D_G% zBb~i{*wK6@P8dfl63Hlh_=P?UjT=_b*_9xzV${@BQ#HH{lj>vrh7EKjgprlyj4Usp zzJ3$^y-8FwO5U&v#@ALss+YCvn~5hqDyv3NU0KfNmS$QvwUgFS%7<4_TT@L$88E&~ zn6C*8$^LHEuU}8yl<7q66zkSEP*_pRh~fg;+d6PvsH!T*GyT*z)YH@J63Z`S+}N?? zX`7DCt@I@0j2b%{TjH$W&_a3DX!7Z&eq$$9_Ot^%OHzn{&U z+ZZ!uG~y;%vvwUL#!g^Zo~EU71736()m4>PLMGXDfa7%%h{Do2KR#JUhaK(W5AeDVjGm)85&G$}48f=rNSUd^tChBlV{-IEfA# zH@48#lfu$b%BrduSvj1Dap~#ppsA^ebV@-q#+d3#Y#bUIn@AZ=q^N{(W5!Vwfn;9? z^-Y`TPkQ7Pl`wkrXbPecKgv!5$w38pX?l7#vY|E3*m09+-&jvYbrp_*j!m1HGAie8nLLMxv3dP6;L~J z1fG+kp`n@KwWBD=&nL2l^xz@IkRcngA^T6-|3o`DS209Hd=E+R-nMNl%ld~J!nuEk z@7vnizIhPnyJh`=cO@R8Be(*#F`&FaZ6I*dnI4)qe8Tqoox>}CdW&uA%7S>dAn_xk z7$S)AzbnQ8iL+`neFH%t*EI^FhCByMcHng&}=RFPfdTIWEYi49^sL?+)#!lha(3Fye@OgJW6n~XN5 zgUxLYCfn-CL^@yD>)@7NZDML()T zfJyxZ5xfQVA{a}cJf^+=CX%N*wG70?GWG^H{C+nyhaxOk8{I6PKMM=tkm%!x5vZBeSeL;f`EWocIekzN^*d}T6o_DHE7lq6qJ%HG%+K0n0Z@6~W=l!zu^ z?6?>i{UVryyZwU^J|)fy^0L`^wZqEz?CG$y>R1huG+eSfjHORMOh%Q|?3l-OBNPtg zoo>Q#6KWruBWKnuzH5gt_O7ShV@pI1^+Hj8+idw!EQg76gn{(-mv(z5x57v6rXCH` zZ*JBiPN4um0qhCC+h_6jvZZ0rbnK5L;*M-?EU(J$kK7w{=JcB}%Z)>NB&m$8!!D#S zw~VmvM_My^Z3qx+4`E;Bt4I-xz550ylq`30bNo$P_r?yNe%M;D#J>d}E}jNHr9g6j zmt$wo$9jEGERwcogtCncmG^((yWIOWSWt&CYsxP-gY@9w;JS-vk88KDKA-y|ChsZW z%+Z(dJAWIb9QGRQWFth)zdyT>;-N`*w;Mk{Q#DZLP}DW&AssDhLcXVnz9FS7c-NY~ z-pyHGUyLGP5NV{)Ew)*zIVj1(L4n`EvjLw!lHpHa3;p?oRHI{4B5(JbHR|&DmLS2-B(%gRLv=0Jf;p^fdvcoIt5ZZtLHo~pj)z~71Fc};E? zN_ST)nmFh~_4&e&9X~xfNk2_FINWcO@Zd4qBq2YtBvdGNsinZ^2Zdn~>H^i0z~{)o z9@-)<@G?P2cd#)*_%T@?GxF(pJSW%F(%pi}n;~#mfApHfs*4lR#f|xZ;Z&`EhjAl#<>ogAEd>I6fL;Gxw4cyBn7c99%t589_KZa zVf6Xw&IZ1F%48+JJi3YrK5qD7E506u*3QZ$&d0<6?Vz?t>kKR2>W=VR8C z5bj9}f?izb)L9x6>+N2!TaPM(ha4PMi`K$w^p7{R!)^rL3({kd8?II6fcn5~a2eM8 zBusdqk+ERPQp}6Y^2_QJdiTV%cmOawiej=AwWNM9n@Z6Cs^Wi9ae_`QgO{_S(baZ^ zMzl3&)~fKo$Lw=)V6@#!wk5;}2OcZMT7c~edLT~YtxZRa4)=(71ltE6qSDo~>umD9 zmt_K?9628A8HK3ONjCj)>_BNjT*%yS=)Sr3Ldq@~$M8ta%+aVx6ZaIzoajjt{lNld zyZ#Q!?$W?bJVsBeUo?K;bq0`Z4;dAkvCLT;21wQ$IL1PW8 zWD%BXhq-df&c5g(p5!U|veR+)!bgZwa=;Euy)f1V1dExWy4!*sPY|6d8p-t!9_0x8 z8N!mirkz)YTFawk-~v%(u|pAnLn=o(Wa_-$wSFE?=;dlK`R$=(lSVyLxXoN%dfZF$ z$BJhIq|T9WgpHu%`m6YpgTKFnk?5wS+Hf2qJhtH2N3uv2bY!#O4Gh>9)De9kWh;x9 zL_T}{*;=}ckvL_ffJBw|I%GZvn&SD@LZS^dmMG}-cwS<2Kn$tTbWBMeg`l25A!v5j zC0_x(q0cRX#AnHVWYxw~|9sp3HVK+oYgd4;4@psiQ3jnewMcmc#A%NVk zBFxz91wPDiwv{RyeUGMD^C#{(9Jvn8Qmuo75TT&`(`x$4VrF~W11<(WYh9%l-CF}V zSWsl|N3)$8EN9kYV}#nuhJ0n9K9ha(WlJ%@!D z(5LzYsHYPk5TL0OznUa1}BhV8~QN9>*r026Loq7*?+R7zK69!B8lhBN7Nkq+Efd zHvtzMKd8hv(k4u}B4?|$KW;~GbQ%x*7m}*L5y-(0P{D6i(Es96m`icCL&t@*UkbWz z=L&wEt+%5y6aIeZ)K*C)J#}>an5XLgSTeM=U?lX)bSO?N}O(cbh0-<;$QPP=ZMI zy5`~b>ICPITCKQrIWAT4MWorZES5=mWlt1vM5O0v@oo&*0`E>v^=BN~HmBd7dcpeO zJ2EIZF8KTdPrymDNf$kDFx38K1>LAw?bF@hvG;lEk7I>>*-~oka_KytAp&6E)^~6e zX6+HgA(fE9ru8`hMm~8254j?(ctU5>9#*Q+5V6VT1E2Tak1W?OS##6^eV>+A&p3&( zcFO_RuWpMRjJoZSR8wjD2ku0>{>Fl_x9m$vDw(I44`%(Xr2-vS(FoqBHC}R1W9bF* z`2hm2MX6`!2Wtu}JDbYAlyK$u%rtpCcA-JM(ZWR^V1m;QIVFa{hU?U&;Oj?>cgOzIHe}#$)b|}Vg#R69 z*}T`uk6MGQ?@_?KZoLIz?eJl7VM6*g9Jaj`3;NIn>?@5%ep)p2_C_T_LB--~iVCKJ z%r^*1nBc=x*{WGdT-2Jq9$#p2BDxD*!&B4Hm(XTAb|Bmtqt)Q|sZKA>DDq^{qNMTI z{CHc#>!nG-$h{|cFAao>4HANb1t;M#IBN}perI73;Nx*sXP8KZH9Oi5O4S$nAXedi zM~vVy@{@dBw$srP3Cn6kk47+ae|}h4S%J|Ey^EH&pOUtlNEv-((P1@=Ze6BU%Y&FJ zEpG<>Q^S(KCmN|J&exk9=)k)yx_dUGDR)VlLZzgm(3rmBH5ugQ77K-0tYV@t6xEXs zjGy@EH_Ku&+IsMsCXM@mXkF}imP(CM2T zsG^}MZD>L~Z``0If0Kimt;SYSrzs)Dj+QafxMWSc%@(R^h0C;Ls+@^|oP|YPODhNHEuzVpu-C{APtN_FUQEl1 z$7YO7Q$^NC3eR&^?J6R%@|gj z<@T)QaaeqUQuglR(8&ebTOfeH3xk%Es>A{l`-s9YCw^8KU9NB3+i;$BQX!^3Wn`vp zLmFTLu1go2Tv$~V)9W3r4FJbFwD{K=2IqS4xxgE|m|xIShOmNb8WyH;AW;2oiif3F zXJIgeX)7N?HyiV(wIi;1-}vxYovjdFFn#ogQT@-EpVINw#)CJm&OhZaN(zcG*H5j? z^jNU4h9;VR_Y_3{z0n0UDuq+5>GjU4sBmKrL&xqZUxqmZQHJ(RBk1|_b!nFOMRkwK@&5pXoMrfK{4OU z$vMZ)%+AZU{g-6rgBlT$Ie!#pQcdpo%B%+c&msg`rt#+>$?DW9CjG&S}n4t?(mY>Hn)qa3kg`3ich z%H}gg*kZ;XC&G}-<{KD^*aIGj1gc3CkHDYG4A z>=bw}&+Zjk(f8nsQex=Xk$HCh!sr{Y9!eT$Jv&PzblY>eXkEA84zmZdkS*=xJt(+leU6^u+YOblHhcw7 z-+Dl}@-ru!`@ADg3wUEQY>rH^a@(9)VRJcP&GY>bJL-CrtH&3 zS(+3?eshFLH}b|-iV~-f;j&xiQsDyNhoPl=#N`tDU!3N6?2&QS=}q{1eWt`0&m1e! zIkp4kpK`gP7r*nOH56hd(3TWY46xDUPtI@ig?3%HBefMoPt|p$K?oKkb20So4Bk7M z?;YT0@wAXu2A-{{y0>~Q%r8v|^#LO3xJm?pQ~8aR9U&ew2KEBJG_@UfrfVWT5$XVE zvL77BqLum9x3aaprHTUW#(Uy6p( z-m;!!L7NL`lMsMq(UOc-moU>qtfhY|@s!boWR>SHEJN%AS(f9?S=al5m@pH7|3hu2 zy|bo$r#rc#ns#)MjH29H|LXl#$?xS92Qx0WKQvRodH41mUCjIbP(-z_HIX9WUosJO ztnrr6^Wwt%%v)((4%;&|awZ2dq#?i-d`kEwlqAQUvkLfxI3-}u-1p>~v&?njv10?$ zaR+{Ae8VyFA=sx;EaMfKEYZrH!$|l{L%|6cEi3~lF;H_ zGg4g$Tk+%M`f~GpzI+FGy!+4+{_N82xE;-(-<$_6b@b=z_rwd0E|&t12zZa%KaeV#p+xNa!=JSRh+UY@6D1-yq60;ZoW zB(xIrUFP+DE_hJn`ic)uoJh!6x?dXIpJ<9{@-WA6(b&ibzJ_tpqNXZju9)tRMVJjL znjeZ6Oc#{yikjjR^98$A_!nz=9d%<@Xl{Fn<(`@+77<92`66;ibA{quPx8zT$`a<% zmz!xOB>Oh_pUr(9c8wIAx|P$IjOZ^D{n+!2s-{(F0>DhT27D+GN;@Rl9-jwF# z(DN1p4T*ny^K-L;-ab3u%dc-16O}D$Ux#|G2dZPTW&!$n9bcXucUc4_RG0D_peHsb zNVdIZW~I~fTkP$Pdtzy2lU8e+Q+cn)?y#BTdm4?A4!M6+N-<&INFL-DuJZ81gb(OD4jWz* zCP#3#NN*+8_H1MbC-6kj(2_BewW-F4JDV6^KBv$VcqT1Gx>aiPd5nJUeKr~cAy(b; zL#UX^Yu9O_ykj1oJtnENwkWL(oO_4gSEf>;I1a1OUG6GPa%$m#Qz+E%=IJIs+M$af9h@z$CzSLVI2_7e4X=AX{i=Lv$(%hkDg+2&J{ zl91eK)Yu4Dt-Hswtb$!OE`_Neh3U`3%m}AMhi5@WZlAq`5WC^w?1M}g$CMgRK1J?U z?(yBOzvJa=^R5>iE3yg!;%XgjPaK^f&?hMYxBV}V^W}-P7CVcX zEUvq&uIovjYh>i2=M*SUa8F6IsIkgahD=U>>Q||-6jKhXuFUTD<^0>;HkQ#@8Z{Mp zlf0RW%d$Pe`d_`0=mX-zzj-!gWLOk4*;5OHy9>S>psJ^;*FuozJb-MRR)wB#N8c6r zcH5IzEu`_Z(FC!`up8=?f|b)5kFxZL`_G-q>e|B0ftucV(Do@r6fA{ow~*&rOZR`X z`;G>}<}h5kGK5R<52^7`U()2FT2%gN`$%D?(n-hDjF&0;-e!}@ z3mZ&q=?uY^G`2&ZYQsKot;5&PU+FS{zopH*@>WJ!Xi#ej5|Ap`lhGzpjD>kajVNgx zHVcUKc6M}siR=a3@aF{IsmH~YavH0>32Ywe3y+0D^>f)kmI|{ieww7>p^DRf%eV`>zaD0$e2NOHjQC&mcr8- zC(Hd(Y|H5^3C6y_h9X}5}4=1|Z zo!DWouYcod$IflYw)&z(`aa3}y5GSUsKwMJ5W22gnIMWi5OcK@0f5*wxK!=Q5}`bE zdk3ufSbM_^>E8p)q*>`>k$1b2u_5s~n3%e;mD5&kG7LycOdk)E9h?qVqGi6aj~?h= z2BzAy0>P>2GB!~o(>0}c%X`XgxMkF|ebRZ+i6jk??KZ-1I~b)7JP}EauF=C5Z-3#s zpJz=yGdoxc&HlZS;=K7#m7} z_@+r29Z7Z?EP4Cc)hfk*S=da1{Oh}by@)T5Cg2V&Chvo3%>QdW1?M0Hm+`SKjOV(2 zKRy$p`v1f1?PmYn1)28CbNSxT>g_b`fty2KWKeM)93G;@N%!rc0~092U!tG^nHgJo zv;FE-xWbLWGuc@mVFO{|qu7al>lZllQ`hF`-7i3_JqEUI%U)VB?cv zIqjKj?d+@_Y$y{WDQLM{o7qhzp?)R9RY4XF7NfEx+XgLQYNm47n!~YtTs>FYo?2z+ zJ{PtY=0qja-1keM+)N_`?7XG}$8E+)WPB85N8jc60JpYi1Qt?gEJ!wef8~Mot`~!} zOxgI6V7K1U!ZNh<47X$%iC`S>##9({6(6!f8j#AXz-_U{utRvmU#W#kNs>++eSinH zc%ef<(5MC!EG>e);&B@bWAa3Yw$U!N_Cvch469#+C;3?67kCa+cj3qgRtPP@RIAI# z?la3rUTHWsvG;=u!1I_0Q;Mlswt(>Bm_{J)&+`0CB-(Gu^@3~zy%X&e^KJoI$NF-j zA0tO;)UoGDo`l@3t!e_Egz`4zqg19J*=;6fG-xKErcm18k=-%B2pE#Qv1z%M9Fb@Gv+VVdmpNX1XZ1mZ`{Sl}K*U}D2Myn0?4nCt z2<<>?s5|?Wgrx&Ul+=m+c8U@J4WYp)BA$JsA0@Ruw{* z&1ZDk-D#_T!E0-Z67SJ-#Ao-g?Vm@R0qu0c4w^}VMEuS`m($S_6pHgUOTgth%omD& z2ZL7a^oQ~PZjrk#Nlw277;J2>SRh5n5t|gszBDp2-0KJumvwa!jJZHxypzZws!l>P zBuwZjTkSd^_;{8X(9yO0v)S%xzkayS_}alNu1ntjI%NX9Z(z_a#Z&V8ya2maZL;My zyyhhQ&i_czF)>N66W8JlEOWnKXpVt^(@@2+VO(@t!*kn_iY6`)we`VI5HOf%9*3AMzUA^lZA19~h8!Cfs)6CQQZG=@`X<>2j znwrV;H&2VJ)D?=+-?kb^{%XSwGMCwM^|0sW8LSM;A?4blm?iej)|hPeL{inTL-aKD z=bn0O&+jm|Lkx90uU3Yo_Iuwi_^tE+U#st8%MEdqNX1a=5Egpn1>e`lReyXOY9%x* z&HAdQmGPb2^!$gMov-Hr0}mBuKJGxbkC&(X_jfx4RrK;>OLgr=C~12Qp!3s~2g+>6 zjSS&eQ9gTPX&M`rPwZq@_B+5;D1z7nf@qTtS;*UKG@-)eFKfhpZvZAu9vhAvHJ|&O z3u259WBWU^=cX@8Yp!q($DBZf(WWPbPY+S|Lm3Y(aUaq?{b;h2@K_{rQhU=`9k}X& zLZ6RK>|OA%UQA@`0B*BpFMmu)!~GN;!{j~-3sXTWx3q);Ol@j{1KnK@ud>h+Y*gMi zo%$0VjTI%6hk7-~UQ=end64()lPx*+dYeq?SOb?v?=4yE2=9WZ?W$kn0<9nf6}Cu{^0|F3Zyqr;9JDg(Ts%>lM)NLearm1@f%GbkjXELDnramo%3w+ z+&Q$uQRS=7suWKjOcDn^O_F5tnLsEhZT?I2i;hOX<><`{L)i$E8yaRC!sGCORyZ;k zbOPv%-3$u8VZfR4&y11uPGr3y-yww0UyHJDO%jQ8Bp=3zm;)D;QDd}4Lr>Q)r@4-a zhNx)#BMy%Zhc%O_Z~tK+SSw)Oeqg1es}mKN8joajZgMmJJY(ziJ#hIjS#w7gHYbV3 z(`UNRZ=zE#-RZpQyP5f~*&}ESm}wmbeinTWU5COEbub#YGkpm9)weJ*G;QMU(=CR-`@SsMQ3?GCFSpn9v+|BdL7Y=Y%4QcHaX$pO%=f98y<=hUZ#w;%Sw8(Ig|xb9V};!C!1?d&f}Us_763FXt_Li zC5R30g*=NCRJA2Y^!ekiI|;?DHhC3vHKl{xD%d<9Xpx1j14`%q#e=NZg2Uf_j>Z$r zHBWf_Gr2Xysx+pJrJ)oWVeYz?5}PhWY0nf9@Q(WSw$S~4 z^#nZ{y-=<%WGM~??1BYILr_)FE3NlEHT`(va{*v z=?Cuxb@lY{1UwmmOadvi?Egap5Pq)%m;qO}^O-Kw&$)@am0>9tPdTF`gRvMi3u3J# zPo1t{Sc;zQK1@4_sf)5>Cevtd=ha1&?9w=Vzhb;kmFt==i`6jEF^6Xo%OOasMi};j z8EB`FMdPj^r)dRnQ53AuTuUeQVb>%-p6D*yR-P1Warb}Udg%Ih@Zpp+*`lI5x-FK= zBBrEP^c^bz!sOxd0xm=iXX@-u?25y^88MkCUTPyF7O?Yh8L{M>=va3fLN9osYq{qh zOD-jYG&2ekG*l#1hY|Luz9DI0O+5CaV{>YZvIJH$BCL4SJBUO(i}Ljuf2rVTN`5pl z1Ngmh-6PSAJe37;un1`|rEkjuVdx|AW-$G@!L8vT4doc{KGXe{OL6}`GY zt$u~wvV~wtBu!9`jEod7+6aF>EdC#iEtV*{8|DVW&H0XQX7&cB;0D7{ux+`4MkhCxV!+K@0_nqE;vWkGk5=dUx>1+k6Xfl^O> zB4v?xNYxTQ2h+>v2nQMHrypR$P$J_-=l1U(=MxU9V2G;5Qo;4Y;0jP3;()h78HKI= zq!<>^?j!THl!##$=XrYud3_dfcmzZiBN`lXW^}6+0b?tt6(`o4*@*tw6C{~lA2^24 zVH*5}^td^nwqqw7LHCN6DTv2vr2;L`P7FpzXL$kQ23a#CyB9U@UMzm!E3(Mnrw=>9 zjkN5OKt5{CuAMmBqGvxwnHhwt%h#S~Emb0larkJJY0d?ACj)A=qA+~6Asgf}>H7_o z_;s2(6j(47kmtC+t?K(-RlJ~utiq6$z{s`f^giS*45)fg_V@5}JY&JD@?%U{RoqmC zR6Sczy=%N6ri1&@M?B8N8LP6B>BmxBhpP_NObuU z!N>!Fzzn)QLL%L{RwpftZM2TcI(D4r>kk3_&lh_cQqx2;c4Lu{IF?NUaok)bd@z+A z`aaPn7JJgEmw0C;sM8R~*}x<4x+4(PlXO0mP`%2jv^gdI9y+a%{ei)oEa+MNEsbITDDqt*pn(stslo)$~j#axj*G*2)Mn*(fz7&G|yW7NdG?*;p>Ubs_ z8!3J9auZ303I^}ZH0^18}$2}A%?tObF z(r3iZD}$igt-fdMN|@MbQ<02Cg|%6S5eh;~rz+^F=G1;lVJ53W4elH`k|^Yi=F~xJ zsn(kjsf&>FCFLe=D9G*YT6rQ3zIL1y@@0;nxeQSWTd}IFCNxfuqnc{|k>oA!+@KQV zmn%>n*HOSG7~Izm?J%$U=e75o;Ln~()I`0u`O2G^8D=oo$@!_pE=9rujyZXRxe~4W z`LB_f-4!h4Y`t^7%MXRse|RuODyC%U;20D*?hI@?s57EimKYGkg5sN}HxIP=s~8RS zKYl?L!8W^m^Rk59;ULNm(Uh`?Pv@hir-|V^kw_Jw=N{$K9>poUPZ6PM!IDUcyS+u& z;}>oxU_A~EI)9ymXAv|sX#@v9qV?cMFY5^y6 za2e!0xK;t=I(H-+?wnI3TcF(Co5I}Po9~n?-eo?GzJ7=+^C)df`TYdRS&5?T-3eEuyQ7KUwlxV2HTixTv;)Q7gDGG)rU)b2w4 z(YJV!S4rJBbidnOHAA0ErM=J`g>osvD-v;7b`9Mpx^I$f^?18)1aMq3GBR+2j zj6688pgV#5*^ihcE<0;Y#N{Bev??w@oqOvjluI|qB@$pfT zJdrH@=6~2rG8g%`{Pu9Lj&dX~BtiWH#wvCJ22|;YA6_d{cao^ddzV^y$Dhwz13z|X z!B9%{ZwU3jA%m-ig)9u1Vmmt)au(Wu7daMuTJtrshh%bLMW%IbU{75WbZ^yc4qQgo zeHVF=rW;ncTSJ&@{Mc7^k+4*&vyyK3KP~|JP6>N)fhzt!rT5*gQG@HqaWS}ZP>B+l zs2}o>I=r$~$1vkH?gb6qHd8rf-rcHFNicqJ+Tn^D28uH(ntuP1SR8X*=*Jj(zjgP{ZQc$tVS|D{q(JdHHaxy z8n&@TyBI8=Nv??)8j3?wo3jL|Iz)Mji@aN!wSQ?T|MFaDcF-N$jUXH?mRrQ-aTK)5^JGSf ztMM*u|H^y!el1B?g^fGcbX`6zWB1&^L>Bnqef#-7cm)rbHI^K$Q?(i zYfqCbOm{DgAgJpOk~3@FPb1luQ*fhzxoBcZ9{t;RT6*xw9x0puk2fcG_3;6Q^6y$lhzO!L2jNe5ta#V}z-`-f9$Tu5hsSh|a0pGF zw(Mk!wS&WPr(NBc66Ju~%hKk3hOi?vPL3B@1&|o{&~^OJrHm+((+6bF{!@TR$R$Su zMda(&K{2lpX`g!f05nyE&!D;;2npZH^Q4Z?o}3EsMuOt31*R0m^9LW*5(Dqv2rl}z zfr>foVO4d#nO9o?L8uy{TtdGSF~vNMu?d>o$O+_1iLyK39!kAIM8ejWz&nvM z>^{xxPEySA9v|{=-ygdT_NVN~B73l-%7k+|BD^3Q{cO49^Ea$mTvmhbm-VttE-NqU z?>PgxUY`&v?aiD#ZvTEqumUc$4ShbDwqD0@~feS5Uy`v~;M6#+oN5CI5lvb&lV>BorH z)%x+ftrf0+4b72d-o3v}@sym95 zNHD(pGP~~EFD_r;aeVQutn8v;KOiOLQ}|^r3XTRYmPAX9YS2V#JQ$dy7zv;8?I=)3 zRh11D^A}-w4#&4?Rz5GS-1`rg%1U1qug~u5Cg9WRT%S+$tT)QZtXi+fwYC{agQ3uce>yQc;Ct;v@2)ht z-Tws1=BL+c1XNS*m(T0i4jXi6@l2kk%WRfQDI5gyX0+~)6LWoo5m?TK-jE39$*d;` zn)3Iee@oEPBT!h7p@?uMrf&md3%ip+J|O$e0{e=cxl5@|y+(?>M_0hFV-`&voy>e1 zjJEa>CdV%jtvqPk2t2rfxL*VwiNMgc!zuv5t(R3*8bWJZFr11Y{dW8Sl=5_-*ZTng zF*0~S1tbMhO#Lcs)AHIq$rm zN^7iN$0XiYnPajFio=gAyD)d5dygyImM1q=+O0pKyf$1Aeyf0S@PYJ5B&MrtR2v)s z&ZVlAqcE+lgLEUDKW$n9rNV64YBs+SV|+<+XIakETsD75yzV^WOwcF#y&RS);)(?8 zjcrUM#zG)QF$+gh3#jJg&mfI34&H6 zDIMy|x$A+sDxCXUUzS8)KMdu$tQn+d#l3T3k6q zH0J#tukBLV!8HG|j(~+CM%@<-e_zkhg$5gPDw@@He-RENK=$jlpA;`oa>79%{{~wkv|d)GD&Glv`$Q^5`O`wVMB~x3I z^`>i{w;w#*#KeZrcF0GgIa*WM=7_IT&&2$OUno}bSN$%d_B}z}tWO@l4LG7syqUGG ztvVhpjcoA_?Kbd+Xs+iT*~tG9PiRggqWHkPw)08XcB!^V9TO7qY$fi(EMnF7ftQ_d zw?D7P{o-#B$+7=T-Y4F4E>A)Q%EoL=lM!{Fc0$h)_~+NBQ<_Z{7X9TOHmE)?MFxPG z(c}4HVPEj5v5(OB;X#KH8o*LpUZNmQl|fQ6woLpV$+BsO#dRB#tH+N824x(wiQM0q z`SVGRXG*SDQB1W{E4B-$Y6vnn_<*{#J!a@SP+`22qH6MVCH7msNvmGMvQ?HyiS(_0 zlAS&#{3vx}9l74X8NPo5=F*0~LWAStkinFt)M`zZ_;i@+89t%M`TkKJRq1NlNfD~g z_V#qDlhk}%L0Met4e%UtMmli(STLExs@PSeQ(KnC>+rDLddm0qrsudpt4DvXdN^&D-Xt^;G?lh{cfB z1-E^mwwLcdh0+GWX9 z%t&SoA4;bpevFErkr6)eYXFDisx`a(4Zz_@6d*GB5RLE7Rjp;?Z}RNsZ8obQ_`YF( z)g3?|Uh?P>XB=tEr6$Xv@Gq%1W@#$D@#i_5qz^Mx7@GY3_xcVgcHcH9v%$~gdJW+) zJ}SgY%);rka#8Y@^QAJ?edy4sgx@i251p+ul4snGa#hk3`fGgz*-!T7Mx)@|7jwH? zHWb!t^~mpMe-R!g;f0g4P6N9A< zS>^~Fp-7g(=27bHNfZ!E*?8l>()y%XH=0L%Dr_kO3ND#en0~Kej4%1chB#D~dw;o2 zguV=>gh3%QIRyvX1BW|El`f@)mzEj<2Z`aF0~>C!vlD32$w>gAa02Pg6j;rGPo$?c zdUhrksVNVCZ6LkjPT|n$c~pV3ZLvGY;B)@!+pkKyJ_@PfgEl89oEp1fkhGH$gSIFf7(6$;nL! zX!ZMjs10#Q$U*jBS#GOKs82}{9ys_O_F}1$Ba>L?I;~V8>oVJ-%d^`j|9Y9`dLPia zDoacipb!w#PjGsOXYI; zTfD!9P|A(U*m;9P|5ifYa{CO`DX_)LZ*c8`&t3w^KCNf;_|AIhDEU>E}%0O zo0$<{PdfY1Abqn4bU&bb`=vXzN}38T!CZ8S=iqbN!qdK2ndk>RwIYT5PPvC|MT_l! z%V#w6o;GILD;qb=KB@$mFj$2zF5_Z?4HL(eH%UJS>!rYq#}b9Cx?Ll1y8q-6;W$r> zs@4$+6}ak%lNWzKL8==ckuUb@i_vZ~#p}92pS9jj%}Q01MW!2#>q%9p?aGw=twNs3 z-%@FeIxrwkrhg@yn@_K*ok9j@ig9TB5To7=x%(fsb9qN;44|TUmg&FF2OkhAOpi(} zz!*FP7k(uF`pyAn0$u*&nNyR=V7hWCTW-5Cb@tfHVl^p@@za7&cvdu94cGz;2Nz*+_ryO%O5E z)dwnUV01=6R!PBP+Tp8!wCvZ%hADm?fd90w#?tQXyQlr8)UYNlT}7mEU~woIFLxvu z54Mtg{m@0071PVVc=KFhye2b@(MnsMI7>;fp+L-oj$ps^A5@<17mcX!HtrdFAZY@~k+k}IU7>NN;)6@mVQpm`mqbcgd+kj4HXjOSU+=WpU zW7K|h>dm<;#eoTm?%TI)`?bd8nbURFYDjdYkzOKSYryDgj$s-0HsFzurpaxBH!li} zj_knuFDtY#MNU$2nNyKv?jo-LChK=gbK?jHHHmuDSM&v*GPj!@@Mt20BzlVA-~-8T zLy3^Ef6ArtrvePdD<7CHHu9y;v1fFE_kP&G=1?MmXEk(?56HyZ<2o%%dTjTdE2E9u zK|k3uoJ7YGeW!(h*Y&=)C$j|fbCJ9}zCi0$iQ(oVU#}Mr19qM1(q!D<@@>K)`JF|S zZ3-5in4ySgvan+Ru_jqq*xuI!2$B+bJTHlL7z5W=p=S1-qZMks^46@dk0o(m8QjYtwFKVKc%-(qVZ75vz4kbp8SA` zvq9LJd^tW6e8r7Q<>7aBk+c zL|ktBcPR^S|Mrn6q}Q5X=OMB;-Hp#o42m~;jX_fj-jI%cKO!qJ-#X4`JFelOMUJ4G zp4*uy%eOr5#ZYahaTdzO8e%MiZyE!YTFiPt^kDk>mC z4lV;u-{X^sv)a^kX-7=(`OG(GwT7onKY;34UnF=QWF+wOLOUF>2UZM{LTy;)x)&t( z*K%#<9sZVFs=~)6NlTX)DoPIyvB6=3p14N{{d_ueSu~ccr4bzaTlY4aSlE02$4~dJ z$XzY{v3dsP60!RyL=qRFLy(}vrB1l}>-2ep(-Y!V=IKw5p4aHMNF4HI7KWm%`6PyN za)%j`#5>Afj8nSHjDy$w*I@02%ccb)?jKOr-|P2xq8>`Ogux+H$!W;x6i!4cH1b4I z)+kH`u&9i*FbgF1Hv?J-)@oh!V(RFy8M-ZElx9%qEfLeO ziMX6_5V@U3qMP^?h?k2oG7--ZwrzBhQ}6d&r+z_QReP^B=Nx0+Bm2^!L_r7Va3ua9j+>Fi^3Ktn zfbQsgw1VX|&f;vXl2njhUpfzh9*HC<0`Sro55u0X20+1L(p&5m0t2=XrR;ldbQpR} z(b#ixrKfS!wVnnwpRTtvzCr5?6?bDg3pEuv*B9r2l&rdPmt`?oj}BzdT;`QFT5N_J zs_Rd-3^E+21M|0>kJ06F*+NpYYcshIojAS$S+L%(2Pe#jYXLohJaHS3&!@Ky{_DOB z=bI6__JpHkxWgBo21sx3)rdO~g|4y|&Ry>1v}oarbNPfTHi$E2xL!@E zDDcVO84O?e<0l(#;EH^z@5w!G#V(BiZng9x$J1&zuKwlyc(+732208E`P{D6=PQ8e zO4v_Xz_1s4;zl*eKf!-!Uo4x^oXPv6X%9$nQ!xeZqt{iiH~6#3S^EJf=Rg7MVUg3v z*%I|l3M!+8>xF%|&Qd~?`tEFEP{_OUo_a^PvFT~!d&WK`H5>_=;e7nf_0;@$dUSvn zR-;}=-oRdfnS|ddMtAGr#n7lCxNmJWARYJY>jpC_6GBAhofquw){kao1O69jYM2T| zJTX&QIRY@O6<8z`l(O8&cdP5UAMWng9qo0th6ndYKiUQ_S(y+_0~<56jC5*6+6DMk zX*o`kh!GDt5nUKtf(gkTIzB5BjRLqE z%?vCOEB$4JIFTfhv|r^odq^CtLE3Q>t{jduE^x&l31twMml%m;PxS>yCglpsXs<&% zog!Wq)3_L_%auR-myT3}JSs71rU){!u$-C67*tzUWD#0;({^rPVEGboaQqUn0~$qH zcC!@O9uzDnZqY;_S*a{xac>Rsmk4%f7y<+YuqXxyaA;CsNxza&=>A^e@m;^FJ@nzP z{SFkn^k^bSHvKpwl=~5xF#QTcAnGSiXtR)_bIno^D=Il{garxhapn&ej_?v8u;R-E zCJ`DW;eom(9V8|y$n(Njv8@L@I=s~CiJ}HK;aF7HG!Z=8jD*=#6kzSI$WmUaonIKWEv(LXEAZtW+WWacXL&-*=N>o;X*pBEC ze-n*3$4LSYFILV!nLt9>>`;(O;Znt-#PG=3SGWHR1^@2E zYg@A_JRx_HJ?jVzO#sYMuBhLGGP z{k|@flgF}@;`0(F<`Z-U+81#@$M_2s?4Q;P6wDCCOZJO|$)u%VyBZi83k$3#Z9n9k zs#fv8#hM=k12WP1`n+BL{#3(Q#COI&ywa?yBB%Y0$@}>2nM?Fy2@kZL;yFOn zczf7k&$hUmWRm7yR)Q2h=jRwBjRZr@7q}PK^#okD8lHKK`KYS47T7DVZ(;3CU{t31 zng+ICNIvuQTDo8$RfKn4=9Uzy0<&MPhEvf(StUmMZ?;%x*?w1_8cCn~reoK|s5O~k z?{#GQIwo=GVt+$LFp%mgCCx0;zaGBt(|hXqAGT*x_`q#nedx8#1I@mbQ1`kIbM}z; zx%lY9Zz8_yjz=0LngbN&OAsRXaa&D7F%Kb|n+^hY!zy`;XbmkLX4MOIavwyY1-pWZ zgWx+bSlS6ZiB%S=*~9C4x8wRGENbJ@jQR_9p{)7G=uC*tQzfV$yIPOfAM7*1swAmU ze83A#_|+QY19JF(1B7+MXP6Oh(B6W+N0BR}#gEg5tX-SyqNITY1{ zlkF;Cj!;NQ(S`LWG{q6p@K<<0id~MJu&`x4YaIwZ*&--Rsfd+u4u&e;DGl3mX_vIs zKu)f1^?#yK(0_#m2=wlrC8jZfig_qt0)3!pgAj-Hd42c+r#cQEae3mH3NXBE2Bj~G z6p30G*^(XG>*5jnEu$cgN$vVrUvS90qR#Rb_qfyW8w|`9aTm2<)`*N0@_`3l{*j!J z(fZs}ks&n`z>l&Q#|o9#vV_;awdKjxlC%0&-pT*O?j%Q$fgwBz5yDEJL1)#|*F=Yv z5T-f@H4d;fCTe>6Ta+HYSVg9cRKIC#+yOM`hx4Gzs5f`Ppa2gRcDe2{SU>?XiR9_! zzN06h*@fM#z_x@Y(`fwe%o1-VaY~IbOMM&fSl#Lu2&?m`^s%cUQRIvXc$^7xUY%ewSI_@d0K29?HC$vbU#gFw$YQXf3iRaP z?b)g``~14=4Q78q58P1jV?dPePQ_-qGIjD{h?a?<^hU)W|ztp z|G-vN(Ymc9j0ywbe?0Sm-G047)Zs8EPxYuYDdL%Z-t-DEH+ZBXyI_=d7mXx`j(T$F zlO5SN5sbO~jrk;;fR(`YY@p@jjX5pI7gn~inli7a8k;^CAUM4{UKO;|DkUj6s=}^OK#2UKd=Zd7lErpnge#UK2%F#S~A#TIbc)LzpFrO^X!j`W0%EyT7~+tiESR(K0Y=J$|@8FE^wRVV$Q@Gnswq0g#*ek>p?lOo>gA&pDjQ zs&!`YZi0NtZhDT#zm#Uu>2=5HsOB41^HR>d+_<=4PI{}oca-Yk^D9`rLp}KUHw-T0 zRAD|2de4!;e~m@hi5mh161jLl|a>y$ObGLkyF77S(b%i=934KS98 zF3hFN&tcATz+iBjB+Wg0)psZoDVk`?avXi8(`j2!jK#c}ZyGo`@yHvoXacPwq|TiPd~9)a5eQ?f+@`)x5F#`l=4$U)7@tK0pKjIj zx{wanm&&+qyvRhP`+m9_C=mAlPxOF)tI)ch4cxuu3s(-kf6Y2IVp7ZWBJ}Go1Fbt* z$2={}1p$oY`^Nwvgr(n?@BZ^NwnbFq+yhVJDV@G+OyLGRsiy`xvcgdzOkk7=gruB; z8BiQyUJ;%~FRXejM=~RFnPLXg)X2qZ^E(i(j;|CWTmGb&h&U6?^*y56+T5v_cOy0H za5pa04!!pRommmsK8ta1H>(NVw_OqZqYsX9u=}ZZ1FEdpYd<&w|7-=CdICEMdjN}C zt4uF#%(jAwLHM9lZ1eRm=|=@z{X^Xntd3_&;rjmA_0wKyQHcCQg|Z*_Ym2Ph%4)$N zG7m1E-&qw{EKe#oy|>8m7HRub5z{v5j-&FVSWI^)60sfeWwa|QH(Fv76Kn0aL`I^< zFgf*tUI|8D^+)rR7OE=ggELQQTi%QEdK{)u1^(;>B%{I`?^8d%44Q`g$-*IZN1x)d zv}cbb185kgj>qb&jpkn*{luqh90d9Qkg&yvueLjrd~Wcj=O*h9t~(#85H9;|yqp9) zcAOwH;Jb6RXaC4$+5MvV`^WA)mySjpg_zO=(PP_-F(e{>Z+*R9iNL8JNs4TsVO*ds zK^k#;dT)~9`22K-to=8fq*uP^E@o8XuFw~>yZ2wjp7))Io_`m(Ja9VR z!2mc!)|0*u^~9v<#n&M=mnT)pZJwODL1PRWe;{E|4IALh%p6M)te+EFo-vy^g4Awz z!Q5Za%P)B65)C()7>Y_6=Sm7WOn3DZ;^#GCOra1Mn=8s-{TiJbkvN?3Lg0*M*I@@!GeWa1`k!Bx zKY!%BkDTI9Qh}2fwoJA>K0U+X{}-0#JL==WKl*s{{EN$i;*93t3505Ax@V#c^Q=Id$HsiEmx z+TePl6FVZ`8<8I*e3|B~K`g!x<)mf}so*UYtSaGHlHO`S~6;<_1mv<`K|;LY{^U}GoIrvm>^n7gUKg=HBfUFHuH79dn)S@ zr$j>uBPkv^N{Sj zz-d=5XC0jZ>topeglX{W2>z##?v#wvz=J+6oBjCXvi{&aOR?E<9cRFd+n4pnCcEu? zEEM{6vC3@H666n1s=TublD5XcfOt$4)!!(;Zf0*bzKUadUKfV9n1{0<}UodU=%}BZ?umhW5v+m#2bXqTmhQ<>XZl)Bl%B7EG zDz{u#_4yv3C5u@Gdvr7|>6I zCc8<4JQO3$2BYQrTq>%Q^YcZn1`9}3O8Mi1AWC@)f)0Iv8!zT#%F~0o2;chmKNm}8<%Y*d?>lPL+ka;(lB`WqGSU)7Y|OuH)<+YV4)>{D`x+1dpp;UxNe(E?E!iBAMSPpLk5&=U>@lgf4wPrW^%@_Q6?5cg1HhTq1 z6b94%;Ck&od(g#v&t&3321;V)q~ZZSKooR*?bg46KzSLJKylfHs5Jyhgj=)SZ#Wc? zWGlp7Nf{mWk!|Mi1c9v4e+6wLJdywFBZjX7CcdLzZ~8qi6b5!8t6esssE-U^wsf>fvOT57sJjL-M;5ZK|?@wVC(aUlnF^)a9WCu+{-yP zCoI;fqtfA#EEGF$cePk6$KbH5L~=RuQDzKJrYn)t4+Vi@r>4o`4HkQEZ?stE%A}DE zHx*#2Rv4IQ)M(2ZNeirFYhP`;Fj4F(p5K*&ki*v~v0QiO4*#}^n7giVcjda}^M2wf z2*P~c>tCroGAA?zB$)F(T=+a)uO?U!;LEO$+tujxA?vCad)JQS?w0U+#C9fMq|wEn zq6ZQqlLP~mrj{=MmQNX3=I+&DF`W7e4wv6>eq3vW!`h0$t?vzfFYtv9C$c4XGJgej z<*f&eyHKM%Gq2y5A_88N+HbS@Xf``^Fhx&$Jf6ip-)bZGS!FQ&{ML)lr!pE&E|7A3 z&}wu>H-bY+u3q%%7lL@X9Y+tD+0WQbN7m>lvKt==n}p_t-r}?(>18+@=sb0OGMO)@ zF_}GKr_*oF`PT%7@$-b5R*SMyqc2X~;Ts168I;W9(BvMsamDYM+4SH$W4Qq~*yxC2 zt<>)1ve9BMbBrdgCDV2-IPnp8zEqt)H2(!~7Km#%ps*`Ch{c%4{mw3BDw7|RanAFl z2#5Iv72{pOURcN^H*$}fyV%JN4eUUS+l4QIM4a4tb?~^}d9I0&JGNg^uQAtQB)T9H z*7N?&SE`<7i1{PePi1jE;u<|~&ToS@Xq%2;dXdWZSv+eZ~St-HuzaT zTl86&6x;D^{_%99kYoPLv}J7)CC*K)R=b`EsM3{Nz3sZ(>_;7T10wbFC$p!!&-})r zXu^{HAY>S?`{5`OH7a;E0hPa{bT+$vs0uKNIk`25mH6XHg);TLm;}iczkBHLWB@Te zc~Wf1r;vDJxOnXcyX8&;$2c@J85TzQp?a_`59~lvsk%%_&y@M?%yx^VN2=vLx&Qc2Uz-3HgsUjmn9oXI*j9lN}kY_IY+FPvO z5F*lc3N7%vJq9J;yv#Ns#Cd-%yBwxCCa@xNKUTE!GR63uO#?63&kj1?%jzD z+n>yib4q{SulP6Ec=b>Hq3at4gsGy+c9)Da7b(cegCeg36UivT9it~3WG9(Yh0`Xa z14%laQPfpLjxf+rkSXHl-n9n+`YGAOAP?qrqJ426@POlZ0=~5SiFB1(oiJ5mBv6$` zot(XWejO7!aVZ>$39N8W3Q@l!*H7_FD%zFB=?&?1a-JD!RCpL|m`{zT3S5tz`dk&wmmxmGv)n?5_RMFO8tK5UV!sO+UR zXjL7@(9N67u?4pXtHm3+DouGY?lLZ!#hf)65@af)AR{FVgiF{^cEEHfx!M7H@{M=& z@dZ|K@idwEO3-;=7-ykZ^NG*nY$H`?nY>z~W^Xyce=qo3lW4$bfTdr1o1t*ii@(!& zh{~LgCreFej0q$9VL?TVNQ?76l|PQ+AGQed3U%{;)9v?5s*FNJ zz-HkMY5mG5MbTN`XM?^UU)CFW^FfO?>Z2{d=we87%kwH$+jercx|$cXU@AIL)hPVl z&xb+K9(RM1^^VVG8O>jJ%B8wfCNzu<1rmoR7KwP{M34Oj{%>aJ*RvNw1_~T$)hnf{ zufVyRy_~4GeK|g(dI^g8q<@uf27@vft4aI?^8#K6ZT}l460Y@C?Z45s;-i-yee1)2 zRlqaRFD%eF9rPnKu{@4VP#4-|u&y^5k-uY)a<$wN#rW%sui9f;dZB8IXp9Ien4jD& z&R$AYsm0(#NkeT?;9-z~p;qeh2er~>II-|Xm}qyVO7x&0&bDL_>FG$^3Sctd#xSn` zxg^5IURRTmKVJLeXId~tNlBaY#oOj2TrZHjSi)<^>pH~d7H8Kwu{^fcodMu-P}4D# z88u5>ZT6;|z+cW4yXj`LIY?Ps6NRJB0U?*Y-&K=r$iYD7{5rFor z{l^r3^ntX+as?oslCzP+Ow@9^xrOq3rwlEj#S`qv+Pe#AgO}yHd~;u|wFTvEwk4-& zk2R@ZTCH}5NSMLs1FDsjyOQG$87MU1nhExE?-T5vk0n$xwMy|xcYW?=KS>mI>PqNn z3_ISr7Bk9=)v7S1W2#)Nx^_$C_>(Wzv$;BUNrY?TuZiU&v(qHMCM0nr(p*I+1A*t9 zR#JN9Ul}J0rN`K8_M1uG&(;?Y$j8t4O!7!w6R!(KA)e1+r`o;dsKeysWZ2}UcstYM zTX+hlCysah#0=d}EHeVHdN^!$(egmDV82t$o&Svy#9Lq{>XHF0HaxtG8IEUj$j&l& zGWzWC$-%xGtq#LB^?b5M%Ax8uoF8VG%727mSzBpV_1JR}4Sj-8AZM=m1GASe7t5XO zU|d)&H=5vUH(ZOPQ_8iZf=T2w%#qcrSBQm>FIQ_wXsc7-VKtO$z2$M(Y$mu*-7LNq z!c4CO<=hPf*58k%tb&)8INYis$GKX?jD#HNmsbr{oXAGFG>_{%2JGItF@Z1;-=4DmIO3w{GU?0 z4bYO(4Uf{h4cVeuom57Nd1>Px?3aFJ1^-iMc`m9P*4P#3CTZ5PC^Q zegF++Qi>#S7~iDM=moa^?&H&?Qn{K~QQ#TN%|?9~tWRfI=o=(NLpod)8SKSx+oZ+Z#)w&{MgfQpv3@WjgE7dUE%-;?KvqE{R{Ehm$! z5@KDK6PhYPK$32KA298&g|gFOKF?Xp9s-;}y5!Nai@N@;UO|<`vC$PMwCNadSY!N-&CM13)@%XG7zihE89Rm)zZx z>wH`%FyRO{v!bu^KzIr^E9sl{I1p7xr6GlSvyqOMd1>b$LPeWWX5OxSnI1bmArU9O zGF04A5c0aL_CrMGiUkr;Fe>%JF6DyGg5^L~Qb-&ysN`~VW~5AxVnCwOJnq*+q0k-= zM@v>*$T6(EEdckQec7y+#lwuQOD4-Tu(<;Mq>TgrtWAB7+_KKJ=ibh|tMw+9yw3p& zH*G)lVb=NLddndaNXTQ?YlVaijOb_HbWH`}{&M@J)8jO!%QpL9*7F-^CUqKDX42?y zn|caMa_7Tk(X8(+THhzY?v2N`Jls_PunmU)U$+v8Bs92R>Q&O#DjVwvwLx?f~C5zF`dWZv|0Qv5N&YDsi{L#+KS4(-slorp0p9H1;=%|_Q9cK z;RuA%O=wc`=|gs_@cVxuDH=)qU@_r)l6@R-C!X75j|XBLjxLxplFq!{(y9xC7iLM{ zxwH5l*VH&}xFw(~;X1EWXjX0e69xFazLV~Kb*dRScR6w|0m|DWV?cj#y#PhKl=FOl zl2(wK_v^*DY=Zo8i1l;F^9%A5E=z7ffd1qfuH=DMnv_&kwAsK!nc(At%`Fmi#xD)- zJl0vuu`V-M&(oOUDep&mYY2HTltGl--9E%ci0$c)s05{I8J6^_8A1Dwe9ruUbWB-U zsp{oS3-g(BVfL7WU9ST4%Z2w}JKbdK>vG<|KtvsKhQ^3{wOXCooAbT0X8qs7j}i&H z6957}M*EM>Cuv%es^IIDM-}OX12IHwHp4=L+nEIUK?ef8tQ9+K0+zVZuiwrrFSSJ` z1V0r@lhNN0u*)1A@4WWTW^=5&e_+e4k&JLM63R5bn4+~=`Rw}=QIsiUGO?US`p<@8Zx+5aO5CsnKvCBI0P!h zzLnrb_2)oXVs!YCu*Ti{rm&Kpvq*I#Odybox0=Q=MBz=$4NhXgvK_U3)zs=+vR-nG zBE+RDQE7Dqj&!qar@ZVv;MZdPOSP|1gY@M0sY5*OsCha@%6k-6xY?#RG2|m_M-U-4(}B> zPP2i>JZvI*CO!}>dEdJ6@U2e;>TQN&WrXz`(73S6dbeBJ1TCF?Wj<)_a5P|Bql>vV zSIzPUWsDJ;a9HcqTgc& z(Zv5J0QA`gpw9q?xFQY4!_j@asK47IsR%QJMu9Cp>iN`>QbomJYH{{8K1M8gJNC&i ziGRI&>klv-q|E*ywduwvEED_HiQxlDF)+w55J$?Gb@u85F0X|=oKS8LXZ%Y-q3$FoRP z>xCq(>fPimtTJn8F-SM}yRvf^OL`(n`_Rx|zlbmT(h9m(ZSDb6JMcxVKW$gKk|jAZ z6Z+o~gqbNz@I)1=uDSq@oEfEJl{B3JYOPE2(*|**Mc=SRv zjA+2>M3d({W2yv+_n%ZE=1LgRaJWL9v0&cuswm{<8zCbshOtMCg1bQN;UrNinAKK#7!a*C7iVRN9EEoNJp{Ihy_1uBh#Zs%*pzpdZ>_ZBJ*uglk zP(TK)=-(ad6@W5aWydg8tJFwq?gHQ|`$K9Jh=iE9u^|srr>V_>_>dw7P_a~Ro{by! zsIS2c$4R0qwi?qsJ8cBUTm>Hjlbneidb?U1W-dZmLZC!_B5IUC;^+F;9!X)~Jg&k5 z_+Pg()4i-|2l{@wPVqC=Z)yb9qr81G&&P4V;!+Qacay~>@kb11V+L+yIKfRO_vlPP6HGKExBDyEr;d&mDP zeHFg+t`19mF%BW{XV6cqDzggLZw_c*=9HN48DqOZh)L+yKjdtOQS2~0P6|4!kc7=< zB@>6;x(II44-2JKtuEH=Oq*5Am9F^5c#S=*im5yri!tlBV>?Qt%k!!rE;twXqf-Z-Yz~ux_>_>j3`iO z)8FTbpr3xkfxpyleWRHQI7t^S0^YnJ%l z>a`foKZAfCm}hrA)vMB9bvmRSj!ORL*n~X zUK*gbwMG&QuFl&isNml);m9tD83ey3);M?>=I%DG-K2aF__5&T-!tZcO1oF|ZX2B@ zS~NrD7_i(E z9;wx8JopKu+X&(GUz>hrg#t}QexCBA*gt!b=VLi0R=~jQE>Z-i0kn1u26>MV@A2go zcUeVALd4Y?bjN9$ryo0+s_n$|l_zR<_*RS(R}>oiv^=R-&wp!Ip8IaQZc>?qwT|-n zM&MTs{{D%T6YQ_}i^a^FrfX#F$uy?EqMqBNNOL8XIS7e}Doh;K&n6x=`(@rWHX7nH zvHRTnBC&blm2BM0LQ`Hp;In@k>~%2$;@e*{iwr)%@TYd`-bJR1}m@T-~ zqosII=RI)B?wgQr1geZl4Ngf(C+P5PUi1inHFGnmJmb^QBEVsw6@*m`aiRY?5f&A9 z{Z88q(Mo8`cs+~ryOI;{BlJOq!Gxkg<`-ea-4sW;_<_TV67;2~={Z64uYS9^Mf^UbjS+nN zF36?+Pl~R%p5+3ey#xEUi;Dub@xF9xS)GEtq1u$!d*$#Hcbb7lxZaf&vxe8KKPzsb zim27~K;b9`rYl9jqLHDZ8l&VLT^14V)aBwqRPsEgWKcrNt`o_5iTB)_LB1h4w=e%N zW6MGQnJOfX4iQ13rZswfnMTWye4<>SNN<)8SpC!oMfl;H7*WM{0@4lVc78)by}^l4 zQ6@*T`{+^bOC3Nbc>LkcWRPlnwh(z2hnfHOCg4Y$@>E1Z(79c?-y}1sI|kiATivABf@2_OTyW>97ZUi``VEGy0S1%FbM9#9 z|9b)K7C>vXx|boFaGut1*n)M@4!rL9h_LkecWfnD5!t2G?SF1>2;CZ472qFb9=xU96 z(nC)Ub(@uw8V0+yHY<8a#Us)|rFI275opJ=exqa>^$L^K=1O($G)HOR^PClzGe-&q zWe)MOW2j2($xtKYFnb)7P}27r?cRJ7Y%i=Jq-mYjBJszOBU6H3%NOuy=`acoE4l91 zIwh&1!Yj-Id7r>RsZ~!`^C1^e5Swjv7PCPmWaUeRliU`{)Z?au*@l%)IP<`BQ%Nn){ozpH{&lj?2Dygx;kM92P z0~Q@9isg7b_(Jr35Et%ZU)XBYQ+lrS0GQ~ZPW~BEw57Be6w%c|Drx%_<&~OE83m`% z5qaFjPCK{g80WX+)!|$|r_j2*jrn3}KZL9G@snDg2Iz%46N`)G>L?mU4Q`g}!976`Kxk-E96&B11x9 z)q3f4qm9p;s}ic;e-I|<#AbrI&2T2YxMC+QEiK9oQ#7&OW=6`3KtP=U)WMz3W$~Io z`@8$5X&|z5Pb$~*>7JeELhNR(elW^-%JRAWp1avfY9gU8UkQ`sXG#e09^|>7zJ&hM z6Zm!|SjKJJ8=7hL<+bTda2)KOP(tY{_%-5E#q))(u1zVxn4 z?VR%y7geA@^~yScz>sL5HPXK9@JAa%qKhGFp!o=c1B(j@At9APfvA*{vZpGEZ0z`~ ze0*y)dklDe{kim;eU3U^?(7xWFg2Ht`W#pF@9Qmt!Y860m())CwdoMSRULroZo4zq z+rA@8j=<~x6_#O$C%GDQicE+Z0}r*|!A%cYROM;^6eE|-hi_;LGAbi$m7X_nN6UC1 z#DuKw9_mz5VEpAE8QH{UDEFQ`C>i2y+)@sJf^-cZR4C; ztvcPR5JeulL?YqvP}(pt6>Byc+~v(|k)iAP=5JE3kM{eb3<3t>UP${+k=5v8q6(AA zh8oTh=HBD5Qs#D|`fkAJTEHI>5gmFA-!JYQ5Bzeo%{IRGGbvL&68V^HW8?u8^cuZ) zR7C!NZ1c?i{yGn&imF=lZ; z>bn1HEBMo^!~Fb69qWH0j*^m`#cT$H%TagOlE3Zw^f#cv_Z-I9UXYHO}zzKX$Sj^DUboy`fuzw6ix(Rx-KE5G+ zU(Qd-OqVEmXwqX-!Thy40!1Ma?=M1MqvBerC+eqd9ONk~3aQ7Xnc1c)M-^!`9&R>o zo%h2)GkIMIJa+g&cm?9kVoq7@HrRNcxl=-PS6o)NJ&;qhBYJTIPD-Q~&$cQMA=|zt zOiD%^N5CAOq&&}dP>A_x2v_#xZKO0x1A_K_VLD#Zo<~_0QiZ{vb$wCbyY!{8RJ|DyggAp!+JZ_-mh9 z=&{sr{%P8N;(x?DVbBrTT(VSAZN~CHtX+Bm>?_?xXn)y2pSquq#MXDIlGpr5{1ik0 zKBI;~s*K2_LPHPRA%HP>`ny~(&1Lpm9_{=v9LD3bI8^qHoE&;2I3#=DrelU5c)nyHDh3y7N zeI;+*d}aNzijPx4DZ_Vdh<(Q8R2^CU*JBT_jKbq~ZcU-bEP!#M1=2G3SHG|EzTX}J z?RE$ToXh0StCXyQBn%v|>MWeMBxYOty9!1)I^iwTvT6eVg>Y>&ep=V_`Z!8VRa(Ru zM?U)~t8nF|C@uw;+~)=LIDwLz8aa%`h4C+uy4ff-zc(O*wa;`s*Gz?i^_V79qlx) zheR}0Xp=Cw)nYODCna5Jk6zF&AFWIX8b{F{G>1K}obcjeL#c#iOmGi~#`Ri6B7LJT z261~qi&u)RjC=jz-o8E>A>R-H;wyF^iAN=cFVdHPBmDi#rcxBgkcjD+-T( zqnVyA6uQ$ati*c$vpOiIYeq0?G#kgm!*`5eH8rhLC3V7EoGZvr8fcH<=<+Y3P$jLU zI@~iNPfRz+$qgU%G=8FLccoHV7+8si4&M61O-yfXw*0pa;2MdyGi{?9x-~!~9ykOx z|1qBu+3QfwL(0y?BK&N}6m90iv&-V#kMFW{v5TXNBco@>r&XKy>&H7TKTA<47sR~R z&$-KRd=tPYl+#v=&HLaVsX6KSx_nCPPKj&|nu=1}e3m zFx6qbU!sxcJ+xXsI7oUkvT~yoTlS^{NrGdKV^;&KDD7;YO#D!l=PZ}P8cDy zmlAE5t`GyKUWiV8Ua6*rcls8EI`$-ngfS6MPQeftnyU7ZH=k342|uDNk-CO#t|b=b zNTEU8iv2lOl`_y}=hHB~JtVBuZlsT6z9IMRi-GGwaGV_cK?zRH!X-5A{(LESx!FzG)c+Z7I*yrl=Tr8VHhX8r zV~gkbO0<-A)kBfKZ>-Vo0u1&1=8hZuKK*qNWk4!WT*vZ6nMH+YkOnaJ|03bS29ZBW zpPqvU697H|{3ODA)R#fXKp5X0X!iI5vE76|Sy2Ez2+bb?ULc3MKyklq)4sxLk;1aJ z^CjCx2_zJ)F5M7KC*)c!`?x!$#LnmG@cKN#X_g*wj*K&=%WbhzvjP}*)vte|mG{i$ zgs5EMGkVj$J1)0}ghpo4bMJdIGCqzYt3Og#j1B%l*YUD7<6&v=b-vPv(b&Ye!&C?| zwIQxIv%#tKTE`ApB|DIXBCiM&(dcO{$yRR}UfCczUUsMV-!)$Cv zO8z$Q<6>~9*ec_I1GKYqv)5~0yLPKNc{QL-mRz(iEhkG(N162V*b)&=ao6K|qpRzE z=gG(ZMB$A=L?$#_Y|_W{RvM@e5ebVFd8R9rM@Enq) z3}si^&2jp%qhP3rkjggmAc$uAkQV2r+A3!F}ZsA?HagneP;n38Z=_0 z?6XX?=xoe;KuBS;m#C!1*Ar_av-HqN*+Pkn?2e}yTlI=-vBmA;yjG|PQif8DY=r($ ziX#8`iy9V!?I6#4pLpmhs=? z-QC^WrEwe{xARdYUm?oKx-ilB_;i{2=c46mBmKPqVN{e;E_0!vRpt56&`457fue!C z=m84qIK8FVV2`h{tzc{Og-T|IthEdu_j}y$-9qB?%GR^_GJNWLe`D0-FUJZv*(EJ@LV-v-{8v;MD zD~Cphll12@d;W=dyW5G!?ke_r!()3NA1~GCNS`Nx(tWrypCV$5$kcA+vOckVyq+2N zc#3P;%tCcol0j2byWY;HWu93sT%I_tr)kb}wF~@3^~q#C_4$C~iP*qC&vn`Hdb-@j zm4$L{x?Jd7v?3cKPfpF0ODT^VpPC?}Ck+dx2rFHl7;+e$@39haYes1_V-ug&SqSLQ zTB^?zKV8&O=A{iOJ%YnQM^gcaZrSWsa$i@r4-YsCm7=u&zO`U<+fOep9SRk6P?(hk zoN+OeQVJAP$;WH-3nbnl22BF$zgzmL-G@#K}@KC>$)bg6+D)_Md^Kr({vbabEKk)l>_h2KZ?sTFkL~cYGdzim3FcD*|uDoQAYgaBWJW}RpC<-Ru``GUr0O-nH?8R1546@&8Dww_r5g&kg}_F#m}DVd=g0U3HINol3K1QDbphL9430SOTarH3H}B!-~{ zq`RdA21c48{_{M~`n~JDKb*Dpm$T2>XPt9j*R}6`Ut!O%`l?fpy5@o`IHJD;4Ed2> z%oH!;sVo~j)(WusEBj|lTv9@?L)F)x#WbIqG>*x=O_Pc@2&)A&CZb*5>%Cv^E@uwI z(ms|5!%srEt@iTEL89lMejbH1RZ>c#^C;9L1V9gEl;I(7Rb7*&l!43)H4VQ=fac;p z2GMtosnC^_g6u4;Qiawo!#r0Z5tvVOXod6g-}nl>RFt?-(d~V&)Gt3HQ6CG9_oO2s zEC8ib$V<2wx%n;1BCE(C)9)*&&_1=8Utm%t4tSY#N7`x!DH6>z_mF$GIY|DX70X$? zVUp@;x1QFt_Q&1D;{9DS^@rw`E_7f`AaOE{nV}uA=dcPZYfRi}!~7W&MNq=ozWo~N zY&LvF^I;{IM@}bWuD+($=J0bJO(JyDF7N$Mvm+G%+6DEiR7w6~-6zo<44l$$MM4wt zAnvpk#E$qN0X?rjFQW)5*^1~inHy}z&mA4OpJ^>9(8m*B)jc6%-8gM>tz75;zt8}V zN`U9tK&0?B>;Yz0iW}XYvt*sk5shy0Jm6HPgo=yhdSyG31<_QrU2} zI#mu}!nbJPC8bQl#7tHkZ?S)r7^p12`_QkjzJ(gOKa{@tJ>#bDAcbyob{fK6BxuBq z)U8BUafR!;?#IvZZrgB_dB>gDkMf;n;THKkoBRcED?h0MU~g+D?* zmbvN4#~@RUmCL2br#(%iu2;Od?|YmF`yL99fn9BFes>93Q#+H87C%Hdso2cGxUS-J zB8bCh^JGggp-|*YN7K3-<%`T~TRT?fi^sWDWZ53YiDGTvN#LpvI|aB7GJ<)25;OJI z{Yn2ylDXyfK;-JCJ@6n#0kEg(#J9Fsh7>-wwPk;{iK4$Bz&*^8V1yp{t)0B3oq(Ts>>)r`T_A44)Zs^*PYI+cLhrn(xo3aW$!+eM$zZ?1){e)X+}RGG zJaeF@F_6{M+2xzgO!LkvHTxN08eTkCjUp@Ui|Y$GnYta$Qa#DT;Fl>;3e#@mWGY*k zet9!@_6zX&eu`=n?bpeO_b3AHHqBqO6oC&}v|T7XEJtRX^EZ5gcpBJ;DWKoV9uH6L z&nKN^R8UYzucO0bT76JnU14-ePIYuPa z%Bql1bbST$)t#pUYiguHw_Vkv5UzB3VyUEh%X9Dql_VLVOR9bbrnE9Z|GogxeL(?X zrQ{x_T>69Ap{%d@YcA$$NvM3aB4eS2-FTC{b^6r=uCk~XmHZ%K?xLZ~^k6+0!;Du6 za4oe$=V3*us~(@(`HVxobW`TtjE#+lQ&F!sve*o!lHY!9 z2OxhW|C16PJh(OQGon79RLu%#{!>Il5?|J!pV4FpEb%Bcj#CMK4PTl6o=(UPesq=X zSrfd=pq}#P6Qp=iQNa3o4HUJv)R;qV8DI)nQ2183n3yIbdzXdybu=rRD|<3#fo!q8 zPCrJw0{l5cYt5Crb8&~gGjxt{DhdA%ehWs(j9&N1+9Fl5ZT&_5}JCq>4Q;E_}o{t~O0 zBs3&SZ{elQkB$|#5?}%?+=-{sjHL=gF1jPs#}&{M)xS8S1=}jr=pY(VhiZ|-A|+bO zfxo_Z{%XLSy}~vX5z)MqfH~$U$_fYw3Oi0B0N*MqP>hW3ks8`jw0MIlNMtH+f2oRz z%U}vklcCfdIuoK*4o{!D{vjxx*?{sND##3xz$lml>T~8^ASr{yw~f(wn(-DzEd|zW z@R~*TkhA)*5zaU0Ht5|WhDLh504zI*^!iaG0n~(#>1cwe&B8#(#y~J8cYdDD#F$T7{?&mhc9{KXTcCJD zq3<;96I*KV$}>)Bl|5+{uJAtL$p6+mKP40r{Coj5l&rhkgvl-sM6bKjO(od(=k6?= zEjTDmDyA(+y zm|UwWl%pf!YFQGKX^d|^b1H^0T-bWy>X6&69 z^1Xq%4N~TlpG*`mXdE>|?*OPs{-#(s2S-scrKt}JWrBy)J z5ZT@&l(32&5?dQ1>aa~^N1VB+5^}xq)x)guZQ2-KD4|t{LgRCljhfI_*;Cmz%a#vi zpFg_}1}vO(fTm2G5-Gl0C>*x6#=lG681Bt43EqwIu&R&V>S^nZPos%6C406MB<*~L z?)$@Y#H8fJ)~%tf^=&zEv@jn`(_Nz=-{f{U>EMLI?Ddrg9j5lWjD<42whrbr;0lqX z7Ytkad849yb1}glA{#7scX(gdO{Q@7W)<#*;Zjct{j_=;7+s)pU^|uh!F9BW!H@Sx zf8s{F$XaPlE9O|!^cDeA$&j)R&L0VVZKGVre)>V`!C?>{9wnugs?g zFd=g}G-dnzA&uuyT+TtE?}yDqrcm-_;mhPqrSrs3U(YtD2-VZl4RZK@N|dR;Jsq#d zGCx-QYdUq?8tESMd<56m*KugU{0iBF-tVZ>?sDVZNI(nLw=;~ubindS$ED9Eo0^|cZ!m3<%Emk z^@{bUaP&Qk_H!z3bZee?RZ}b}VSab(h0@;(K5?dr!n?Q<1lxt(Y6AoFVe6FkpKBZL zGL;c3Zh34yp@)x{4I+!SAvpa;+0GDA(^VW|4W)gI+LOiA`j^S?Ojh4J(D~REQ$N46 z0GxMlTvSxiCar__4|zk@_v9+9Ya_q#Mwuhlo;BC;+bz{m&bA)#+xNEjkJ@i6U^_ls zN$s({{8RMi)b-!w8ZN8%!!s9OUMPF%I{5EZk^XmhxHH4;xww97kdnA!Ue7z+JWJ)2 z26E8|J6RjU7>FL~T{5>UC<)m91;_7rdLQ*^K8*%*0&$%MPwEsa`A&{r#(yR0R|e99 z-IBgUlIJvt?F>RgYMU6tUPb=>+!YZ;XmvZCy~S#WZFoLw`Di=jl0$5a0H4t04MCl5 z2w0BU6;tPG(O2C`Kr?RGH&Qt`ZREUaoB?k+7rE=bqvBRcCIf?1&_DU(Cf=fn^Kh7{ zapVq8R?ZY3;g(!1FiivG`#*IFGrQs*Nq!Tf(DK^A_n0V2E`X=VuTzghR5ppJJ#v5s zhy1~qXGejT#TZq0HJvCY8O{XWAq#G9+Ul&c0S&7VUe}$SI)MRh<#a?#AV8^V=_j(d z{a58P;V-Z7uHubz`3nP=mC--8gu*OZlFhzG_AK5vD5Ylsh!P7tdb+vs?O%d?EFb3NG-19 z;(P1yUTs~T%#zDCbSnbd!AUZh?0C*|*SyB#!6MmCPQP_sWm%gR_U-X)BMa zEWPH=I_`L@M8${8-fP9cf8$Ck_szTvv5ey7Cto4`AE!Lt?O1`2(0x~f^xm_6UkUH& zkMV#Xx^*C`IbJEw)MXf`17R&}%L4}iI2#L|o6(S?_)s-o<4Y`rH3rC+SR8}F5a&ue z5RE*(7D=N@ei^3=;UsyDL{93dkkYJupelQ}u0g3{(L7q?XR<^FLc;52avfW-?5eoIk$z>vWBExRlv{yUdFER}yr1zafagRJRWQ5{w=H zsv&K|tbjjAGXv(x#goZ!2_YKPP`|#vAhSm@{P@h{%A&vnARx+-5rqK0wwYlsqM~9@ zgBdno$1q^D`uz`<5*U}m?pnGO(W&`hSDJ#;9?Cy8Myc`FRjUJeEG6Snzq~h1B|CV79%u=VJFyJ!qGrIS z7a(5OlR86B#+WaM3=MF*WnmLYKyZdVNJ{JoVzOGrm7&mx7w`W(ly|2Tzk%}=7wQ`d;+v@b-pcTW5t3BFi z0l1rq_r(SyEFPl+NiR$Cv)!_}g3egnp;cx7O6( z9oF5{d*F0~god0>HW~|v2ilcF0uJW7+tLh^?*TjX-9jWxO$2C{nMQKE1!rC_*!6vP z{@aO~HgE8!SE^k6Ib}`w?OWMO=e(EQ-{VmNoe@xQD2~bAH`lVNH3kpguXfZ9QFY}hKwD_SDkEs^4GD#toD;9HaYT`))C6T z^dl-QP3#eVCWz9z5#m#h)q*6v8}Oh1QPJ#;hHX(>zMu0~XGluRdy&9#G&N_BId z?|P5eCX_L7wV2QKnQ<)h5kp!Q)lk)b&P;=!QnLMhk94Y{sbMaVY=&rxQYVy=f=f#A zqiv@35Nt#I;xa+YW2QC5araa$MEdc+apR`i8l|71_gVeBxpYEgj5!;KQsnm-=R=h0 zhl~uJ+a-mpqkS5up-;LdB2Td6bA={v*Hkoirhf2=HaKC2e@Fhr1`pe{pdBEb%bYsgQw-r%gc`wBLgc>e2GViOY6L+vJhj25QyHd z!eHraX>aw4=VCkK0u`3+sY}s9x2NiVZB0U9gc}^H41O%?YIKlVrk^p!eH# za>wZDSX1c5&+HTO=Q>y#+xcTwkvOL$L}_LQlJCP;ctBUcT>Xw_wN2ikRsyBsO=5nS zg<6>H9q26iOp_Pr)e%X5zw2Ad2&(M6gvs_7UtDIJMfJX=)w4>C)=%Tj)q6owhCM&Z zI^Pj@9#%JFV3+q_No-RvtKDQ&%$0yHpYDAPt{!(CFB2dmZ5D`G=vl&Z}&K74Wd zEm@%-X2ac?LtPEp7C03l& zkjZ8{jLc_}+7m;J8P$N|_x<_?zI9J26kCNXnX~aPr6_S`G=JP-1Ij`&y%ytA;<4kNEAI08Lw0akMK8|BLizK zkn}%CK2h^7!>fVF1JIZ6` zW2nBoc_$S@rbETkl|3wp{{(sGb1*eDoujPQ%a&c8T{e=stN}SJR+0@!O-K&hAUR^2 zp}yYrfypmuGs#k~hq6(4EqWGp5TqbU@f7~~*WEPd{?%Ctr{Ltkn{nCqBYcn;?H~Bf zG=|)-OX|VxJ_b)bj`|~H@{Y7f%@fx;pX<~+`MW>L>p#xQ%od*A?h*$FUU_1~BK`r) zG1(tGa78vpfT$$Xk_kc3G(8G**OXSz`da_Y)3`mzQ`V4A>2q9auhE`VTP% zUSY002RjdgIj0T?t#56FR}OFuT8S0H&#*SzTmL-)M#KKrM&SG)oBjXI({k7dA`JfD zE%Gi{cM0D7ZxnhF{Qr$~WjB^O|F;AW!WC}`M;v + + + + + + + Time + + + + + + timer_callback + + + + + + timer_callback + + + + + + prev_ekf + + + + + + latest_ekf + + + + + + ekf(ignored) + + + + + 1 sec + + + + + + ekf(ignored) + + + + + + ekf(ignored) + + + + ... + + + + About ekf + + + + + + Time + + + + + + timer_callback + + + + + + timer_callback + + + + + + prev_ekf + + + + + + latest_ekf + + + + + + twist + + + + + 1 sec + + + + + + twist + + + + + + twist + + + + ... + + + + About twist + + + + + + twist + (ignored) + + + diff --git a/localization/pose_instability_detector/package.xml b/localization/pose_instability_detector/package.xml new file mode 100644 index 0000000000000..9f38cf6e00262 --- /dev/null +++ b/localization/pose_instability_detector/package.xml @@ -0,0 +1,34 @@ + + + + pose_instability_detector + 0.1.0 + The pose_instability_detector package + Yamato Ando + Kento Yabuuchi + Masahiro Sakamoto + Taiki Yamada + Ryu Yamamoto + Shintaro Sakoda + Apache License 2.0 + Shintaro Sakoda + + ament_cmake_auto + autoware_cmake + + diagnostic_msgs + geometry_msgs + nav_msgs + rclcpp + tf2 + tf2_geometry_msgs + tier4_autoware_utils + tier4_debug_msgs + + ament_cmake_cppcheck + ament_lint_auto + + + ament_cmake + + diff --git a/localization/pose_instability_detector/schema/pose_instability_detector.schema.json b/localization/pose_instability_detector/schema/pose_instability_detector.schema.json new file mode 100644 index 0000000000000..b45b43102444d --- /dev/null +++ b/localization/pose_instability_detector/schema/pose_instability_detector.schema.json @@ -0,0 +1,75 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Pose Instability Detector Nodes", + "type": "object", + "definitions": { + "pose_instability_detector_node": { + "type": "object", + "properties": { + "interval_sec": { + "type": "number", + "default": 1.0, + "exclusiveMinimum": 0, + "description": "The interval of timer_callback in seconds." + }, + "threshold_diff_position_x": { + "type": "number", + "default": 1.0, + "minimum": 0.0, + "description": "The threshold of diff_position x (m)." + }, + "threshold_diff_position_y": { + "type": "number", + "default": 1.0, + "minimum": 0.0, + "description": "The threshold of diff_position y (m)." + }, + "threshold_diff_position_z": { + "type": "number", + "default": 1.0, + "minimum": 0.0, + "description": "The threshold of diff_position z (m)." + }, + "threshold_diff_angle_x": { + "type": "number", + "default": 1.0, + "minimum": 0.0, + "description": "The threshold of diff_angle x (rad)." + }, + "threshold_diff_angle_y": { + "type": "number", + "default": 1.0, + "minimum": 0.0, + "description": "The threshold of diff_angle y (rad)." + }, + "threshold_diff_angle_z": { + "type": "number", + "default": 1.0, + "minimum": 0.0, + "description": "The threshold of diff_angle z (rad)." + } + }, + "required": [ + "interval_sec", + "threshold_diff_position_x", + "threshold_diff_position_y", + "threshold_diff_position_z", + "threshold_diff_angle_x", + "threshold_diff_angle_y", + "threshold_diff_angle_z" + ] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/pose_instability_detector_node" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} diff --git a/localization/pose_instability_detector/src/main.cpp b/localization/pose_instability_detector/src/main.cpp new file mode 100644 index 0000000000000..34e679e86730f --- /dev/null +++ b/localization/pose_instability_detector/src/main.cpp @@ -0,0 +1,26 @@ +// Copyright 2023- Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "pose_instability_detector.hpp" + +#include + +int main(int argc, char ** argv) +{ + rclcpp::init(argc, argv); + auto pose_instability_detector = std::make_shared(); + rclcpp::spin(pose_instability_detector); + rclcpp::shutdown(); + return 0; +} diff --git a/localization/pose_instability_detector/src/pose_instability_detector.cpp b/localization/pose_instability_detector/src/pose_instability_detector.cpp new file mode 100644 index 0000000000000..afb7d6e007db2 --- /dev/null +++ b/localization/pose_instability_detector/src/pose_instability_detector.cpp @@ -0,0 +1,176 @@ +// Copyright 2023- Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "pose_instability_detector.hpp" + +#include "tier4_autoware_utils/geometry/geometry.hpp" + +#include + +#include + +#include + +PoseInstabilityDetector::PoseInstabilityDetector(const rclcpp::NodeOptions & options) +: Node("pose_instability_detector", options), + threshold_diff_position_x_(this->declare_parameter("threshold_diff_position_x")), + threshold_diff_position_y_(this->declare_parameter("threshold_diff_position_y")), + threshold_diff_position_z_(this->declare_parameter("threshold_diff_position_z")), + threshold_diff_angle_x_(this->declare_parameter("threshold_diff_angle_x")), + threshold_diff_angle_y_(this->declare_parameter("threshold_diff_angle_y")), + threshold_diff_angle_z_(this->declare_parameter("threshold_diff_angle_z")) +{ + odometry_sub_ = this->create_subscription( + "~/input/odometry", 10, + std::bind(&PoseInstabilityDetector::callback_odometry, this, std::placeholders::_1)); + + twist_sub_ = this->create_subscription( + "~/input/twist", 10, + std::bind(&PoseInstabilityDetector::callback_twist, this, std::placeholders::_1)); + + const double interval_sec = this->declare_parameter("interval_sec"); + timer_ = rclcpp::create_timer( + this, this->get_clock(), std::chrono::duration(interval_sec), + std::bind(&PoseInstabilityDetector::callback_timer, this)); + + diff_pose_pub_ = this->create_publisher("~/debug/diff_pose", 10); + diagnostics_pub_ = this->create_publisher("/diagnostics", 10); +} + +void PoseInstabilityDetector::callback_odometry(Odometry::ConstSharedPtr odometry_msg_ptr) +{ + latest_odometry_ = *odometry_msg_ptr; +} + +void PoseInstabilityDetector::callback_twist( + TwistWithCovarianceStamped::ConstSharedPtr twist_msg_ptr) +{ + twist_buffer_.push_back(*twist_msg_ptr); +} + +void PoseInstabilityDetector::callback_timer() +{ + if (latest_odometry_ == std::nullopt) { + return; + } + if (prev_odometry_ == std::nullopt) { + prev_odometry_ = latest_odometry_; + return; + } + + auto quat_to_rpy = [](const Quaternion & quat) { + tf2::Quaternion tf2_quat(quat.x, quat.y, quat.z, quat.w); + tf2::Matrix3x3 mat(tf2_quat); + double roll{}; + double pitch{}; + double yaw{}; + mat.getRPY(roll, pitch, yaw); + return std::make_tuple(roll, pitch, yaw); + }; + + Pose pose = prev_odometry_->pose.pose; + rclcpp::Time prev_time = rclcpp::Time(prev_odometry_->header.stamp); + for (const TwistWithCovarianceStamped & twist_with_cov : twist_buffer_) { + const Twist twist = twist_with_cov.twist.twist; + + const rclcpp::Time curr_time = rclcpp::Time(twist_with_cov.header.stamp); + if (curr_time > latest_odometry_->header.stamp) { + break; + } + + const rclcpp::Duration time_diff = curr_time - prev_time; + const double time_diff_sec = time_diff.seconds(); + if (time_diff_sec < 0.0) { + continue; + } + + // quat to rpy + auto [ang_x, ang_y, ang_z] = quat_to_rpy(pose.orientation); + + // rpy update + ang_x += twist.angular.x * time_diff_sec; + ang_y += twist.angular.y * time_diff_sec; + ang_z += twist.angular.z * time_diff_sec; + tf2::Quaternion quat; + quat.setRPY(ang_x, ang_y, ang_z); + + // Convert twist to world frame + tf2::Vector3 linear_velocity(twist.linear.x, twist.linear.y, twist.linear.z); + linear_velocity = tf2::quatRotate(quat, linear_velocity); + + // update + pose.position.x += linear_velocity.x() * time_diff_sec; + pose.position.y += linear_velocity.y() * time_diff_sec; + pose.position.z += linear_velocity.z() * time_diff_sec; + pose.orientation.x = quat.x(); + pose.orientation.y = quat.y(); + pose.orientation.z = quat.z(); + pose.orientation.w = quat.w(); + prev_time = curr_time; + } + + // compare pose and latest_odometry_ + const Pose latest_ekf_pose = latest_odometry_->pose.pose; + const Pose ekf_to_odom = tier4_autoware_utils::inverseTransformPose(pose, latest_ekf_pose); + const geometry_msgs::msg::Point pos = ekf_to_odom.position; + const auto [ang_x, ang_y, ang_z] = quat_to_rpy(ekf_to_odom.orientation); + const std::vector values = {pos.x, pos.y, pos.z, ang_x, ang_y, ang_z}; + + const rclcpp::Time stamp = latest_odometry_->header.stamp; + + // publish diff_pose for debug + PoseStamped diff_pose; + diff_pose.header = latest_odometry_->header; + diff_pose.pose = ekf_to_odom; + diff_pose_pub_->publish(diff_pose); + + const std::vector thresholds = {threshold_diff_position_x_, threshold_diff_position_y_, + threshold_diff_position_z_, threshold_diff_angle_x_, + threshold_diff_angle_y_, threshold_diff_angle_z_}; + + const std::vector labels = {"diff_position_x", "diff_position_y", "diff_position_z", + "diff_angle_x", "diff_angle_y", "diff_angle_z"}; + + // publish diagnostics + DiagnosticStatus status; + status.name = "localization: pose_instability_detector"; + status.hardware_id = this->get_name(); + bool all_ok = true; + + for (size_t i = 0; i < values.size(); ++i) { + const bool ok = (std::abs(values[i]) < thresholds[i]); + all_ok &= ok; + diagnostic_msgs::msg::KeyValue kv; + kv.key = labels[i] + ":threshold"; + kv.value = std::to_string(thresholds[i]); + status.values.push_back(kv); + kv.key = labels[i] + ":value"; + kv.value = std::to_string(values[i]); + status.values.push_back(kv); + kv.key = labels[i] + ":status"; + kv.value = (ok ? "OK" : "WARN"); + status.values.push_back(kv); + } + status.level = (all_ok ? DiagnosticStatus::OK : DiagnosticStatus::WARN); + status.message = (all_ok ? "OK" : "WARN"); + + DiagnosticArray diagnostics; + diagnostics.header.stamp = stamp; + diagnostics.status.emplace_back(status); + diagnostics_pub_->publish(diagnostics); + + // prepare for next loop + prev_odometry_ = latest_odometry_; + twist_buffer_.clear(); +} diff --git a/localization/pose_instability_detector/src/pose_instability_detector.hpp b/localization/pose_instability_detector/src/pose_instability_detector.hpp new file mode 100644 index 0000000000000..761a10b7a6bf7 --- /dev/null +++ b/localization/pose_instability_detector/src/pose_instability_detector.hpp @@ -0,0 +1,70 @@ +// Copyright 2023- Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef POSE_INSTABILITY_DETECTOR_HPP_ +#define POSE_INSTABILITY_DETECTOR_HPP_ + +#include + +#include +#include +#include +#include + +#include + +class PoseInstabilityDetector : public rclcpp::Node +{ + using Quaternion = geometry_msgs::msg::Quaternion; + using Twist = geometry_msgs::msg::Twist; + using TwistWithCovarianceStamped = geometry_msgs::msg::TwistWithCovarianceStamped; + using Pose = geometry_msgs::msg::Pose; + using PoseStamped = geometry_msgs::msg::PoseStamped; + using Odometry = nav_msgs::msg::Odometry; + using KeyValue = diagnostic_msgs::msg::KeyValue; + using DiagnosticStatus = diagnostic_msgs::msg::DiagnosticStatus; + using DiagnosticArray = diagnostic_msgs::msg::DiagnosticArray; + +public: + explicit PoseInstabilityDetector(const rclcpp::NodeOptions & options = rclcpp::NodeOptions()); + +private: + void callback_odometry(Odometry::ConstSharedPtr odometry_msg_ptr); + void callback_twist(TwistWithCovarianceStamped::ConstSharedPtr twist_msg_ptr); + void callback_timer(); + + // subscribers and timer + rclcpp::Subscription::SharedPtr odometry_sub_; + rclcpp::Subscription::SharedPtr twist_sub_; + rclcpp::TimerBase::SharedPtr timer_; + + // publisher + rclcpp::Publisher::SharedPtr diff_pose_pub_; + rclcpp::Publisher::SharedPtr diagnostics_pub_; + + // parameters + const double threshold_diff_position_x_; + const double threshold_diff_position_y_; + const double threshold_diff_position_z_; + const double threshold_diff_angle_x_; + const double threshold_diff_angle_y_; + const double threshold_diff_angle_z_; + + // variables + std::optional latest_odometry_ = std::nullopt; + std::optional prev_odometry_ = std::nullopt; + std::vector twist_buffer_; +}; + +#endif // POSE_INSTABILITY_DETECTOR_HPP_ diff --git a/localization/pose_instability_detector/test/test.cpp b/localization/pose_instability_detector/test/test.cpp new file mode 100644 index 0000000000000..4747582cdd163 --- /dev/null +++ b/localization/pose_instability_detector/test/test.cpp @@ -0,0 +1,168 @@ +// Copyright 2023- Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "../src/pose_instability_detector.hpp" +#include "test_message_helper_node.hpp" + +#include + +#include +#include + +#include +#include +#include + +class TestPoseInstabilityDetector : public ::testing::Test +{ + using TwistWithCovarianceStamped = geometry_msgs::msg::TwistWithCovarianceStamped; + using Odometry = nav_msgs::msg::Odometry; + using DiagnosticStatus = diagnostic_msgs::msg::DiagnosticStatus; + using DiagnosticArray = diagnostic_msgs::msg::DiagnosticArray; + +protected: + void SetUp() override + { + const std::string yaml_path = + "../../install/pose_instability_detector/share/pose_instability_detector/config/" + "pose_instability_detector.param.yaml"; + + rcl_params_t * params_st = rcl_yaml_node_struct_init(rcl_get_default_allocator()); + if (!rcl_parse_yaml_file(yaml_path.c_str(), params_st)) { + std::cerr << "Failed to parse yaml file : " << yaml_path << std::endl; + std::exit(1); + } + + const rclcpp::ParameterMap param_map = rclcpp::parameter_map_from(params_st, ""); + rclcpp::NodeOptions node_options; + for (const auto & param_pair : param_map) { + for (const auto & param : param_pair.second) { + node_options.parameter_overrides().push_back(param); + } + } + + subject_ = std::make_shared(node_options); + executor_.add_node(subject_); + + helper_ = std::make_shared(); + executor_.add_node(helper_); + + rcl_yaml_node_struct_fini(params_st); + } + + void TearDown() override + { + executor_.remove_node(subject_); + executor_.remove_node(helper_); + } + + rclcpp::executors::SingleThreadedExecutor executor_; + std::shared_ptr subject_; + std::shared_ptr helper_; +}; + +TEST_F(TestPoseInstabilityDetector, output_ok_when_twist_matches_odometry) // NOLINT +{ + // send the first odometry message (start x = 10) + builtin_interfaces::msg::Time timestamp{}; + timestamp.sec = 0; + timestamp.nanosec = 0; + helper_->send_odometry_message(timestamp, 10.0, 0.0, 0.0); + + // process the above message (by timer_callback) + helper_->received_diagnostic_array_flag = false; + while (!helper_->received_diagnostic_array_flag) { + executor_.spin_some(); + std::this_thread::sleep_for(std::chrono::milliseconds(10)); + } + + // send the twist message1 (move 1m in x direction) + timestamp.sec = 0; + timestamp.nanosec = 5e8; + helper_->send_twist_message(timestamp, 2.0, 0.0, 0.0); + + // send the twist message2 (move 1m in x direction) + timestamp.sec = 1; + timestamp.nanosec = 0; + helper_->send_twist_message(timestamp, 2.0, 0.0, 0.0); + + // send the second odometry message (finish x = 12) + timestamp.sec = 2; + timestamp.nanosec = 0; + helper_->send_odometry_message(timestamp, 12.0, 0.0, 0.0); + + // process the above messages (by timer_callback) + helper_->received_diagnostic_array_flag = false; + while (!helper_->received_diagnostic_array_flag) { + executor_.spin_some(); + std::this_thread::sleep_for(std::chrono::milliseconds(10)); + } + + // check result + const diagnostic_msgs::msg::DiagnosticStatus & diagnostic_status = + helper_->received_diagnostic_array.status[0]; + EXPECT_TRUE(diagnostic_status.level == diagnostic_msgs::msg::DiagnosticStatus::OK); +} + +TEST_F(TestPoseInstabilityDetector, output_warn_when_twist_is_too_small) // NOLINT +{ + // send the first odometry message (start x = 10) + builtin_interfaces::msg::Time timestamp{}; + timestamp.sec = 0; + timestamp.nanosec = 0; + helper_->send_odometry_message(timestamp, 10.0, 0.0, 0.0); + + // process the above message (by timer_callback) + helper_->received_diagnostic_array_flag = false; + while (!helper_->received_diagnostic_array_flag) { + executor_.spin_some(); + std::this_thread::sleep_for(std::chrono::milliseconds(10)); + } + + // send the twist message1 (move 0.1m in x direction) + timestamp.sec = 0; + timestamp.nanosec = 5e8; + helper_->send_twist_message(timestamp, 0.2, 0.0, 0.0); + + // send the twist message2 (move 0.1m in x direction) + timestamp.sec = 1; + timestamp.nanosec = 0; + helper_->send_twist_message(timestamp, 0.2, 0.0, 0.0); + + // send the second odometry message (finish x = 12) + timestamp.sec = 2; + timestamp.nanosec = 0; + helper_->send_odometry_message(timestamp, 12.0, 0.0, 0.0); + + // process the above messages (by timer_callback) + helper_->received_diagnostic_array_flag = false; + while (!helper_->received_diagnostic_array_flag) { + executor_.spin_some(); + std::this_thread::sleep_for(std::chrono::milliseconds(10)); + } + + // check result + const diagnostic_msgs::msg::DiagnosticStatus & diagnostic_status = + helper_->received_diagnostic_array.status[0]; + EXPECT_TRUE(diagnostic_status.level == diagnostic_msgs::msg::DiagnosticStatus::WARN); +} + +int main(int argc, char ** argv) +{ + rclcpp::init(argc, argv); + ::testing::InitGoogleTest(&argc, argv); + int result = RUN_ALL_TESTS(); + rclcpp::shutdown(); + return result; +} diff --git a/localization/pose_instability_detector/test/test_message_helper_node.hpp b/localization/pose_instability_detector/test/test_message_helper_node.hpp new file mode 100644 index 0000000000000..51444f9736b02 --- /dev/null +++ b/localization/pose_instability_detector/test/test_message_helper_node.hpp @@ -0,0 +1,80 @@ +// Copyright 2023- Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef TEST_MESSAGE_HELPER_NODE_HPP_ +#define TEST_MESSAGE_HELPER_NODE_HPP_ + +#include + +#include +#include +#include + +class TestMessageHelperNode : public rclcpp::Node +{ + using TwistWithCovarianceStamped = geometry_msgs::msg::TwistWithCovarianceStamped; + using Odometry = nav_msgs::msg::Odometry; + using DiagnosticStatus = diagnostic_msgs::msg::DiagnosticStatus; + using DiagnosticArray = diagnostic_msgs::msg::DiagnosticArray; + +public: + TestMessageHelperNode() : Node("test_message_helper_node") + { + odometry_publisher_ = + this->create_publisher("/pose_instability_detector/input/odometry", 10); + twist_publisher_ = this->create_publisher( + "/pose_instability_detector/input/twist", 10); + diagnostic_subscriber_ = this->create_subscription( + "/diagnostics", 10, + std::bind(&TestMessageHelperNode::callback_diagnostics, this, std::placeholders::_1)); + } + + void send_odometry_message( + const builtin_interfaces::msg::Time timestamp, const double x, const double y, const double z) + { + Odometry message{}; + message.header.stamp = timestamp; + message.pose.pose.position.x = x; + message.pose.pose.position.y = y; + message.pose.pose.position.z = z; + odometry_publisher_->publish(message); + } + + void send_twist_message( + const builtin_interfaces::msg::Time timestamp, const double x, const double y, const double z) + { + TwistWithCovarianceStamped message{}; + message.header.stamp = timestamp; + message.twist.twist.linear.x = x; + message.twist.twist.linear.y = y; + message.twist.twist.linear.z = z; + twist_publisher_->publish(message); + } + + void callback_diagnostics(const DiagnosticArray::ConstSharedPtr msg) + { + received_diagnostic_array = *msg; + received_diagnostic_array_flag = true; + } + + DiagnosticArray received_diagnostic_array; + bool received_diagnostic_array_flag = false; + +private: + rclcpp::Publisher::SharedPtr odometry_publisher_; + rclcpp::Publisher::SharedPtr twist_publisher_; + rclcpp::Subscription::SharedPtr diagnostic_subscriber_; +}; + +#endif // TEST_MESSAGE_HELPER_NODE_HPP_ From 017aed4f8888a8cae468ae04e214356e0dd0192f Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Wed, 15 Nov 2023 13:29:22 +0900 Subject: [PATCH 191/202] fix(drivable_area_expansion): fix bug when reusing previous path points (#5586) Signed-off-by: Maxime CLEMENT --- .../drivable_area_expansion.cpp | 12 +++++++++++- 1 file changed, 11 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/src/utils/drivable_area_expansion/drivable_area_expansion.cpp b/planning/behavior_path_planner/src/utils/drivable_area_expansion/drivable_area_expansion.cpp index 3008f98331c92..ebc1f686865a6 100644 --- a/planning/behavior_path_planner/src/utils/drivable_area_expansion/drivable_area_expansion.cpp +++ b/planning/behavior_path_planner/src/utils/drivable_area_expansion/drivable_area_expansion.cpp @@ -53,7 +53,17 @@ void reuse_previous_poses( prev_poses, 0, ego_point) < 0.0; const auto ego_is_far = !prev_poses.empty() && tier4_autoware_utils::calcDistance2d(ego_point, prev_poses.front()) < 0.0; - if (!ego_is_behind && !ego_is_far && prev_poses.size() > 1) { + // make sure the reused points are not behind the current original drivable area + LineString2d left_bound; + LineString2d right_bound; + for (const auto & p : path.left_bound) left_bound.push_back(convert_point(p)); + for (const auto & p : path.right_bound) right_bound.push_back(convert_point(p)); + LineString2d prev_poses_ls; + for (const auto & p : prev_poses) prev_poses_ls.push_back(convert_point(p.position)); + auto prev_poses_across_bounds = boost::geometry::intersects(left_bound, prev_poses_ls) || + boost::geometry::intersects(right_bound, prev_poses_ls); + + if (!ego_is_behind && !ego_is_far && prev_poses.size() > 1 && !prev_poses_across_bounds) { const auto first_idx = motion_utils::findNearestSegmentIndex(prev_poses, path.points.front().point.pose); const auto deviation = From b5d6c51c26a7ee2597f85dd6fe3c04e75d13414b Mon Sep 17 00:00:00 2001 From: Kento Yabuuchi Date: Wed, 15 Nov 2023 16:23:03 +0900 Subject: [PATCH 192/202] refactor(pose_instability_detector, ar_tag_based_localizer): specify file path using get_package_share_directory (#5588) * use get_package_share_directory Signed-off-by: Kento Yabuuchi * use get_package_share_directory in pose_instability_detector Signed-off-by: Kento Yabuuchi --------- Signed-off-by: Kento Yabuuchi --- .../ar_tag_based_localizer/package.xml | 1 + .../ar_tag_based_localizer/test/test.cpp | 5 +++-- localization/pose_instability_detector/package.xml | 1 + localization/pose_instability_detector/test/test.cpp | 5 +++-- 4 files changed, 8 insertions(+), 4 deletions(-) diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml b/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml index 24b737c309016..7e83220dadf2a 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml @@ -13,6 +13,7 @@ ament_cmake autoware_cmake + ament_index_cpp aruco cv_bridge diagnostic_msgs diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/test/test.cpp b/localization/landmark_based_localizer/ar_tag_based_localizer/test/test.cpp index 6b302ee6bc862..1b44327fd9e8b 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/test/test.cpp +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/test/test.cpp @@ -14,6 +14,7 @@ #include "../src/ar_tag_based_localizer.hpp" +#include #include #include @@ -29,8 +30,8 @@ class TestArTagBasedLocalizer : public ::testing::Test void SetUp() override { const std::string yaml_path = - "../../install/ar_tag_based_localizer/share/ar_tag_based_localizer/config/" - "ar_tag_based_localizer.param.yaml"; + ament_index_cpp::get_package_share_directory("ar_tag_based_localizer") + + "/config/ar_tag_based_localizer.param.yaml"; rcl_params_t * params_st = rcl_yaml_node_struct_init(rcl_get_default_allocator()); if (!rcl_parse_yaml_file(yaml_path.c_str(), params_st)) { diff --git a/localization/pose_instability_detector/package.xml b/localization/pose_instability_detector/package.xml index 9f38cf6e00262..7774407a7990d 100644 --- a/localization/pose_instability_detector/package.xml +++ b/localization/pose_instability_detector/package.xml @@ -16,6 +16,7 @@ ament_cmake_auto autoware_cmake + ament_index_cpp diagnostic_msgs geometry_msgs nav_msgs diff --git a/localization/pose_instability_detector/test/test.cpp b/localization/pose_instability_detector/test/test.cpp index 4747582cdd163..5ea03859d7731 100644 --- a/localization/pose_instability_detector/test/test.cpp +++ b/localization/pose_instability_detector/test/test.cpp @@ -15,6 +15,7 @@ #include "../src/pose_instability_detector.hpp" #include "test_message_helper_node.hpp" +#include #include #include @@ -35,8 +36,8 @@ class TestPoseInstabilityDetector : public ::testing::Test void SetUp() override { const std::string yaml_path = - "../../install/pose_instability_detector/share/pose_instability_detector/config/" - "pose_instability_detector.param.yaml"; + ament_index_cpp::get_package_share_directory("pose_instability_detector") + + "/config/pose_instability_detector.param.yaml"; rcl_params_t * params_st = rcl_yaml_node_struct_init(rcl_get_default_allocator()); if (!rcl_parse_yaml_file(yaml_path.c_str(), params_st)) { From a76d360c33febe2277fd674198123e4d92eedd59 Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Wed, 15 Nov 2023 23:41:49 +0900 Subject: [PATCH 193/202] fix(detected_object_validation): add 3d pointcloud based validator (#5327) * fix: add 3d validation bind function Signed-off-by: badai-nguyen * fix: check validation point within shape Signed-off-by: badai-nguyen * fix: add 2d validator option param Signed-off-by: badai-nguyen * chore: refactor Signed-off-by: badai-nguyen * chore: refactor Signed-off-by: badai-nguyen * Revert "chore: refactor" This reverts commit e3cbf6cb524a34ad3b693a8c0eaa1680e3141f72. * chore: update docs and param file Signed-off-by: badai-nguyen * refactor: change to abstract class Signed-off-by: badai-nguyen * chore: add maintainer Signed-off-by: badai-nguyen --------- Signed-off-by: badai-nguyen --- ...acle_pointcloud_based_validator.param.yaml | 2 + .../debugger.hpp | 13 +- .../obstacle_pointcloud_based_validator.hpp | 88 +++- .../obstacle-pointcloud-based-validator.md | 1 + .../detected_object_validation/package.xml | 1 + .../obstacle_pointcloud_based_validator.cpp | 377 ++++++++++++------ 6 files changed, 344 insertions(+), 138 deletions(-) diff --git a/perception/detected_object_validation/config/obstacle_pointcloud_based_validator.param.yaml b/perception/detected_object_validation/config/obstacle_pointcloud_based_validator.param.yaml index 745a0fd6591a9..f7a27a52bfa8a 100644 --- a/perception/detected_object_validation/config/obstacle_pointcloud_based_validator.param.yaml +++ b/perception/detected_object_validation/config/obstacle_pointcloud_based_validator.param.yaml @@ -11,3 +11,5 @@ min_points_and_distance_ratio: #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN [800.0, 800.0, 800.0, 800.0, 800.0, 800.0, 800.0, 800.0] + + using_2d_validator: false diff --git a/perception/detected_object_validation/include/obstacle_pointcloud_based_validator/debugger.hpp b/perception/detected_object_validation/include/obstacle_pointcloud_based_validator/debugger.hpp index 9ef1f75427b65..6597475ae297e 100644 --- a/perception/detected_object_validation/include/obstacle_pointcloud_based_validator/debugger.hpp +++ b/perception/detected_object_validation/include/obstacle_pointcloud_based_validator/debugger.hpp @@ -71,11 +71,18 @@ class Debugger void addNeighborPointcloud(const pcl::PointCloud::Ptr & input) { pcl::PointCloud::Ptr input_xyz = toXYZ(input); - for (const auto & point : *input_xyz) { - neighbor_pointcloud_->push_back(point); - } + addNeighborPointcloud(input_xyz); } + void addNeighborPointcloud(const pcl::PointCloud::Ptr & input) + { + if (!input->empty()) { + neighbor_pointcloud_->reserve(neighbor_pointcloud_->size() + input->size()); + for (const auto & point : *input) { + neighbor_pointcloud_->push_back(point); + } + } + } void addPointcloudWithinPolygon(const pcl::PointCloud::Ptr & input) { // pcl::PointCloud::Ptr input_xyz = toXYZ(input); diff --git a/perception/detected_object_validation/include/obstacle_pointcloud_based_validator/obstacle_pointcloud_based_validator.hpp b/perception/detected_object_validation/include/obstacle_pointcloud_based_validator/obstacle_pointcloud_based_validator.hpp index 5819302664907..e7df2c409b18f 100644 --- a/perception/detected_object_validation/include/obstacle_pointcloud_based_validator/obstacle_pointcloud_based_validator.hpp +++ b/perception/detected_object_validation/include/obstacle_pointcloud_based_validator/obstacle_pointcloud_based_validator.hpp @@ -25,8 +25,13 @@ #include #include #include +#include +#include #include #include +#include +#include +#include #include #include @@ -35,12 +40,88 @@ #include namespace obstacle_pointcloud_based_validator { + struct PointsNumThresholdParam { std::vector min_points_num; std::vector max_points_num; std::vector min_points_and_distance_ratio; }; + +class Validator +{ +private: + PointsNumThresholdParam points_num_threshold_param_; + +protected: + pcl::PointCloud::Ptr cropped_pointcloud_; + +public: + explicit Validator(PointsNumThresholdParam & points_num_threshold_param); + inline pcl::PointCloud::Ptr getDebugPointCloudWithinObject() + { + return cropped_pointcloud_; + } + + virtual bool setKdtreeInputCloud( + const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_pointcloud) = 0; + virtual bool validate_object( + const autoware_auto_perception_msgs::msg::DetectedObject & transformed_object) = 0; + virtual std::optional getMaxRadius( + const autoware_auto_perception_msgs::msg::DetectedObject & object) = 0; + size_t getThresholdPointCloud(const autoware_auto_perception_msgs::msg::DetectedObject & object); + virtual pcl::PointCloud::Ptr getDebugNeighborPointCloud() = 0; +}; + +class Validator2D : public Validator +{ +private: + pcl::PointCloud::Ptr obstacle_pointcloud_; + pcl::PointCloud::Ptr neighbor_pointcloud_; + pcl::search::Search::Ptr kdtree_; + +public: + explicit Validator2D(PointsNumThresholdParam & points_num_threshold_param); + + pcl::PointCloud::Ptr convertToXYZ( + const pcl::PointCloud::Ptr & pointcloud_xy); + inline pcl::PointCloud::Ptr getDebugNeighborPointCloud() + { + return convertToXYZ(neighbor_pointcloud_); + } + + bool setKdtreeInputCloud(const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_cloud); + bool validate_object( + const autoware_auto_perception_msgs::msg::DetectedObject & transformed_object); + std::optional getMaxRadius( + const autoware_auto_perception_msgs::msg::DetectedObject & object); + std::optional getPointCloudWithinObject( + const autoware_auto_perception_msgs::msg::DetectedObject & object, + const pcl::PointCloud::Ptr neighbor_pointcloud); +}; +class Validator3D : public Validator +{ +private: + pcl::PointCloud::Ptr obstacle_pointcloud_; + pcl::PointCloud::Ptr neighbor_pointcloud_; + pcl::search::Search::Ptr kdtree_; + +public: + explicit Validator3D(PointsNumThresholdParam & points_num_threshold_param); + inline pcl::PointCloud::Ptr getDebugNeighborPointCloud() + { + return neighbor_pointcloud_; + } + bool setKdtreeInputCloud(const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_cloud); + bool validate_object( + const autoware_auto_perception_msgs::msg::DetectedObject & transformed_object); + std::optional getMaxRadius( + const autoware_auto_perception_msgs::msg::DetectedObject & object); + std::optional getPointCloudWithinObject( + const autoware_auto_perception_msgs::msg::DetectedObject & object, + const pcl::PointCloud::Ptr neighbor_pointcloud); +}; + class ObstaclePointCloudBasedValidator : public rclcpp::Node { public: @@ -61,16 +142,13 @@ class ObstaclePointCloudBasedValidator : public rclcpp::Node PointsNumThresholdParam points_num_threshold_param_; std::shared_ptr debugger_; + bool using_2d_validator_; + std::unique_ptr validator_; private: void onObjectsAndObstaclePointCloud( const autoware_auto_perception_msgs::msg::DetectedObjects::ConstSharedPtr & input_objects, const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_obstacle_pointcloud); - std::optional getPointCloudNumWithinPolygon( - const autoware_auto_perception_msgs::msg::DetectedObject & object, - const pcl::PointCloud::Ptr pointcloud); - std::optional getMaxRadius( - const autoware_auto_perception_msgs::msg::DetectedObject & object); }; } // namespace obstacle_pointcloud_based_validator diff --git a/perception/detected_object_validation/obstacle-pointcloud-based-validator.md b/perception/detected_object_validation/obstacle-pointcloud-based-validator.md index dd67aab3db0c9..36b3815e7e689 100644 --- a/perception/detected_object_validation/obstacle-pointcloud-based-validator.md +++ b/perception/detected_object_validation/obstacle-pointcloud-based-validator.md @@ -28,6 +28,7 @@ In the debug image above, the red DetectedObject is the validated object. The bl | Name | Type | Description | | ------------------------------- | ----- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| `using_2d_validator` | bool | The xy-plane projected (2D) obstacle point clouds will be used for validation | | `min_points_num` | int | The minimum number of obstacle point clouds in DetectedObjects | | `max_points_num` | int | The max number of obstacle point clouds in DetectedObjects | | `min_points_and_distance_ratio` | float | Threshold value of the number of point clouds per object when the distance from baselink is 1m, because the number of point clouds varies with the distance from baselink. | diff --git a/perception/detected_object_validation/package.xml b/perception/detected_object_validation/package.xml index e19b2b1c399b2..31bb633294748 100644 --- a/perception/detected_object_validation/package.xml +++ b/perception/detected_object_validation/package.xml @@ -6,6 +6,7 @@ The ROS 2 detected_object_validation package Yukihiro Saito Shunsuke Miura + badai nguyen Apache License 2.0 ament_cmake_auto diff --git a/perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp b/perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp index 47640c9332e4d..3249581513dd9 100644 --- a/perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp +++ b/perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp @@ -19,12 +19,6 @@ #include -#include -#include -#include -#include -#include - #ifdef ROS_DISTRO_GALACTIC #include #else @@ -35,44 +29,247 @@ #include #include -namespace +namespace obstacle_pointcloud_based_validator { -inline pcl::PointXY toPCL(const double x, const double y) +namespace bg = boost::geometry; +using Shape = autoware_auto_perception_msgs::msg::Shape; +using Polygon2d = tier4_autoware_utils::Polygon2d; + +Validator::Validator(PointsNumThresholdParam & points_num_threshold_param) { - pcl::PointXY pcl_point; - pcl_point.x = x; - pcl_point.y = y; - return pcl_point; + points_num_threshold_param_.min_points_num = points_num_threshold_param.min_points_num; + points_num_threshold_param_.max_points_num = points_num_threshold_param.max_points_num; + points_num_threshold_param_.min_points_and_distance_ratio = + points_num_threshold_param.min_points_and_distance_ratio; } -inline pcl::PointXY toPCL(const geometry_msgs::msg::Point & point) +size_t Validator::getThresholdPointCloud( + const autoware_auto_perception_msgs::msg::DetectedObject & object) { - return toPCL(point.x, point.y); + const auto object_label_id = object.classification.front().label; + const auto object_distance = std::hypot( + object.kinematics.pose_with_covariance.pose.position.x, + object.kinematics.pose_with_covariance.pose.position.y); + size_t threshold_pc = std::clamp( + static_cast( + points_num_threshold_param_.min_points_and_distance_ratio.at(object_label_id) / + object_distance + + 0.5f), + static_cast(points_num_threshold_param_.min_points_num.at(object_label_id)), + static_cast(points_num_threshold_param_.max_points_num.at(object_label_id))); + return threshold_pc; } -inline pcl::PointXYZ toXYZ(const pcl::PointXY & point) +Validator2D::Validator2D(PointsNumThresholdParam & points_num_threshold_param) +: Validator(points_num_threshold_param) { - return pcl::PointXYZ(point.x, point.y, 0.0); } -inline pcl::PointCloud::Ptr toXYZ( - const pcl::PointCloud::Ptr & pointcloud) +bool Validator2D::setKdtreeInputCloud( + const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_cloud) +{ + obstacle_pointcloud_.reset(new pcl::PointCloud); + pcl::fromROSMsg(*input_cloud, *obstacle_pointcloud_); + if (obstacle_pointcloud_->empty()) { + return false; + } + + kdtree_ = pcl::make_shared>(false); + kdtree_->setInputCloud(obstacle_pointcloud_); + + return true; +} +pcl::PointCloud::Ptr Validator2D::convertToXYZ( + const pcl::PointCloud::Ptr & pointcloud_xy) { pcl::PointCloud::Ptr pointcloud_xyz(new pcl::PointCloud); - pointcloud_xyz->reserve(pointcloud->size()); - for (const auto & point : *pointcloud) { - pointcloud_xyz->push_back(toXYZ(point)); + pointcloud_xyz->reserve(pointcloud_xy->size()); + for (const auto & point : *pointcloud_xy) { + pointcloud_xyz->push_back(pcl::PointXYZ(point.x, point.y, 0.0)); } return pointcloud_xyz; } -} // namespace +std::optional Validator2D::getPointCloudWithinObject( + const autoware_auto_perception_msgs::msg::DetectedObject & object, + const pcl::PointCloud::Ptr pointcloud) +{ + std::vector vertices_array; + pcl::Vertices vertices; + Polygon2d poly2d = + tier4_autoware_utils::toPolygon2d(object.kinematics.pose_with_covariance.pose, object.shape); + if (bg::is_empty(poly2d)) return std::nullopt; -namespace obstacle_pointcloud_based_validator + pcl::PointCloud::Ptr poly3d(new pcl::PointCloud); + + for (size_t i = 0; i < poly2d.outer().size(); ++i) { + vertices.vertices.emplace_back(i); + vertices_array.emplace_back(vertices); + poly3d->emplace_back(poly2d.outer().at(i).x(), poly2d.outer().at(i).y(), 0.0); + } + cropped_pointcloud_.reset(new pcl::PointCloud); + pcl::CropHull cropper; // don't be implemented PointXY by PCL + cropper.setInputCloud(convertToXYZ(pointcloud)); + cropper.setDim(2); + cropper.setHullIndices(vertices_array); + cropper.setHullCloud(poly3d); + cropper.setCropOutside(true); + cropper.filter(*cropped_pointcloud_); + return cropped_pointcloud_->size(); +} + +bool Validator2D::validate_object( + const autoware_auto_perception_msgs::msg::DetectedObject & transformed_object) { -namespace bg = boost::geometry; -using Shape = autoware_auto_perception_msgs::msg::Shape; -using Polygon2d = tier4_autoware_utils::Polygon2d; + // get neighbor_pointcloud of object + neighbor_pointcloud_.reset(new pcl::PointCloud); + std::vector indices; + std::vector distances; + const auto search_radius = getMaxRadius(transformed_object); + if (!search_radius) { + return false; + } + kdtree_->radiusSearch( + pcl::PointXY( + transformed_object.kinematics.pose_with_covariance.pose.position.x, + transformed_object.kinematics.pose_with_covariance.pose.position.y), + search_radius.value(), indices, distances); + for (const auto & index : indices) { + neighbor_pointcloud_->push_back(obstacle_pointcloud_->at(index)); + } + const auto num = getPointCloudWithinObject(transformed_object, neighbor_pointcloud_); + if (!num) return true; + + size_t threshold_pointcloud_num = getThresholdPointCloud(transformed_object); + if (num.value() > threshold_pointcloud_num) { + return true; + } + return false; // remove object +} + +std::optional Validator2D::getMaxRadius( + const autoware_auto_perception_msgs::msg::DetectedObject & object) +{ + if (object.shape.type == Shape::BOUNDING_BOX || object.shape.type == Shape::CYLINDER) { + return std::hypot(object.shape.dimensions.x * 0.5f, object.shape.dimensions.y * 0.5f); + } else if (object.shape.type == Shape::POLYGON) { + float max_dist = 0.0; + for (const auto & point : object.shape.footprint.points) { + const float dist = std::hypot(point.x, point.y); + max_dist = max_dist < dist ? dist : max_dist; + } + return max_dist; + } else { + return std::nullopt; + } +} + +Validator3D::Validator3D(PointsNumThresholdParam & points_num_threshold_param) +: Validator(points_num_threshold_param) +{ +} +bool Validator3D::setKdtreeInputCloud( + const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_cloud) +{ + obstacle_pointcloud_.reset(new pcl::PointCloud); + pcl::fromROSMsg(*input_cloud, *obstacle_pointcloud_); + if (obstacle_pointcloud_->empty()) { + return false; + } + // setup kdtree_ + kdtree_ = pcl::make_shared>(false); + kdtree_->setInputCloud(obstacle_pointcloud_); + return true; +} +std::optional Validator3D::getMaxRadius( + const autoware_auto_perception_msgs::msg::DetectedObject & object) +{ + if (object.shape.type == Shape::BOUNDING_BOX || object.shape.type == Shape::CYLINDER) { + auto square_radius = (object.shape.dimensions.x * 0.5f) * (object.shape.dimensions.x * 0.5f) + + (object.shape.dimensions.y * 0.5f) * (object.shape.dimensions.y * 0.5f) + + (object.shape.dimensions.z * 0.5f) * (object.shape.dimensions.z * 0.5f); + return std::sqrt(square_radius); + } else if (object.shape.type == Shape::POLYGON) { + float max_dist = 0.0; + for (const auto & point : object.shape.footprint.points) { + const float dist = std::hypot(point.x, point.y); + max_dist = max_dist < dist ? dist : max_dist; + } + return std::hypot(max_dist, object.shape.dimensions.z * 0.5f); + } else { + return std::nullopt; + } +} + +std::optional Validator3D::getPointCloudWithinObject( + const autoware_auto_perception_msgs::msg::DetectedObject & object, + const pcl::PointCloud::Ptr neighbor_pointcloud) +{ + std::vector vertices_array; + pcl::Vertices vertices; + auto const & object_position = object.kinematics.pose_with_covariance.pose.position; + auto const object_height = object.shape.dimensions.x; + auto z_min = object_position.z - object_height / 2.0f; + auto z_max = object_position.z + object_height / 2.0f; + Polygon2d poly2d = + tier4_autoware_utils::toPolygon2d(object.kinematics.pose_with_covariance.pose, object.shape); + if (bg::is_empty(poly2d)) return std::nullopt; + + pcl::PointCloud::Ptr poly3d(new pcl::PointCloud); + for (size_t i = 0; i < poly2d.outer().size(); ++i) { + vertices.vertices.emplace_back(i); + vertices_array.emplace_back(vertices); + poly3d->emplace_back(poly2d.outer().at(i).x(), poly2d.outer().at(i).y(), 0.0); + } + + pcl::PointCloud::Ptr cropped_pointcloud_2d(new pcl::PointCloud); + pcl::CropHull cropper; + cropper.setInputCloud(neighbor_pointcloud); + cropper.setDim(2); + cropper.setHullIndices(vertices_array); + cropper.setHullCloud(poly3d); + cropper.setCropOutside(true); + cropper.filter(*cropped_pointcloud_2d); + + cropped_pointcloud_.reset(new pcl::PointCloud); + cropped_pointcloud_->reserve(cropped_pointcloud_2d->size()); + for (const auto & point : *cropped_pointcloud_2d) { + if (point.z > z_min && point.z < z_max) { + cropped_pointcloud_->push_back(point); + } + } + return cropped_pointcloud_->size(); +} + +bool Validator3D::validate_object( + const autoware_auto_perception_msgs::msg::DetectedObject & transformed_object) +{ + neighbor_pointcloud_.reset(new pcl::PointCloud); + std::vector indices; + std::vector distances; + const auto search_radius = getMaxRadius(transformed_object); + if (!search_radius) { + return false; + } + kdtree_->radiusSearch( + pcl::PointXYZ( + transformed_object.kinematics.pose_with_covariance.pose.position.x, + transformed_object.kinematics.pose_with_covariance.pose.position.y, + transformed_object.kinematics.pose_with_covariance.pose.position.z), + search_radius.value(), indices, distances); + for (const auto & index : indices) { + neighbor_pointcloud_->push_back(obstacle_pointcloud_->at(index)); + } + + const auto num = getPointCloudWithinObject(transformed_object, neighbor_pointcloud_); + if (!num) return true; + + size_t threshold_pointcloud_num = getThresholdPointCloud(transformed_object); + if (num.value() > threshold_pointcloud_num) { + return true; + } + return false; // remove object +} ObstaclePointCloudBasedValidator::ObstaclePointCloudBasedValidator( const rclcpp::NodeOptions & node_options) @@ -85,13 +282,6 @@ ObstaclePointCloudBasedValidator::ObstaclePointCloudBasedValidator( tf_listener_(tf_buffer_), sync_(SyncPolicy(10), objects_sub_, obstacle_pointcloud_sub_) { - using std::placeholders::_1; - using std::placeholders::_2; - sync_.registerCallback( - std::bind(&ObstaclePointCloudBasedValidator::onObjectsAndObstaclePointCloud, this, _1, _2)); - objects_pub_ = create_publisher( - "~/output/objects", rclcpp::QoS{1}); - points_num_threshold_param_.min_points_num = declare_parameter>("min_points_num"); points_num_threshold_param_.max_points_num = @@ -99,10 +289,25 @@ ObstaclePointCloudBasedValidator::ObstaclePointCloudBasedValidator( points_num_threshold_param_.min_points_and_distance_ratio = declare_parameter>("min_points_and_distance_ratio"); + using_2d_validator_ = declare_parameter("using_2d_validator"); + + using std::placeholders::_1; + using std::placeholders::_2; + + sync_.registerCallback( + std::bind(&ObstaclePointCloudBasedValidator::onObjectsAndObstaclePointCloud, this, _1, _2)); + if (using_2d_validator_) { + validator_ = std::make_unique(points_num_threshold_param_); + } else { + validator_ = std::make_unique(points_num_threshold_param_); + } + + objects_pub_ = create_publisher( + "~/output/objects", rclcpp::QoS{1}); + const bool enable_debugger = declare_parameter("enable_debugger", false); if (enable_debugger) debugger_ = std::make_shared(this); } - void ObstaclePointCloudBasedValidator::onObjectsAndObstaclePointCloud( const autoware_auto_perception_msgs::msg::DetectedObjects::ConstSharedPtr & input_objects, const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_obstacle_pointcloud) @@ -119,61 +324,23 @@ void ObstaclePointCloudBasedValidator::onObjectsAndObstaclePointCloud( // objects_pub_->publish(*input_objects); return; } - - // Convert to PCL - pcl::PointCloud::Ptr obstacle_pointcloud(new pcl::PointCloud); - pcl::fromROSMsg(*input_obstacle_pointcloud, *obstacle_pointcloud); - if (obstacle_pointcloud->empty()) { + if (!validator_->setKdtreeInputCloud(input_obstacle_pointcloud)) { RCLCPP_WARN_THROTTLE(this->get_logger(), *this->get_clock(), 5, "cannot receive pointcloud"); - // objects_pub_->publish(*input_objects); return; } - // Create Kd-tree to search neighbor pointcloud to reduce cost. - pcl::search::Search::Ptr kdtree = - pcl::make_shared>(false); - kdtree->setInputCloud(obstacle_pointcloud); - for (size_t i = 0; i < transformed_objects.objects.size(); ++i) { const auto & transformed_object = transformed_objects.objects.at(i); - const auto object_label_id = transformed_object.classification.front().label; const auto & object = input_objects->objects.at(i); - const auto & transformed_object_position = - transformed_object.kinematics.pose_with_covariance.pose.position; - const auto search_radius = getMaxRadius(transformed_object); - if (!search_radius) { - output.objects.push_back(object); - continue; - } - - // Search neighbor pointcloud to reduce cost. - pcl::PointCloud::Ptr neighbor_pointcloud(new pcl::PointCloud); - std::vector indices; - std::vector distances; - kdtree->radiusSearch( - toPCL(transformed_object_position), search_radius.value(), indices, distances); - for (const auto & index : indices) { - neighbor_pointcloud->push_back(obstacle_pointcloud->at(index)); + const auto validated = validator_->validate_object(transformed_object); + if (debugger_) { + debugger_->addNeighborPointcloud(validator_->getDebugNeighborPointCloud()); + debugger_->addPointcloudWithinPolygon(validator_->getDebugPointCloudWithinObject()); } - if (debugger_) debugger_->addNeighborPointcloud(neighbor_pointcloud); - - // Filter object that have few pointcloud in them. - // TODO(badai-nguyen) add 3d validator option - const auto num = getPointCloudNumWithinPolygon(transformed_object, neighbor_pointcloud); - const auto object_distance = - std::hypot(transformed_object_position.x, transformed_object_position.y); - size_t min_pointcloud_num = std::clamp( - static_cast( - points_num_threshold_param_.min_points_and_distance_ratio.at(object_label_id) / - object_distance + - 0.5f), - static_cast(points_num_threshold_param_.min_points_num.at(object_label_id)), - static_cast(points_num_threshold_param_.max_points_num.at(object_label_id))); - if (num) { - (min_pointcloud_num <= num.value()) ? output.objects.push_back(object) - : removed_objects.objects.push_back(object); - } else { + if (validated) { output.objects.push_back(object); + } else { + removed_objects.objects.push_back(object); } } @@ -185,56 +352,6 @@ void ObstaclePointCloudBasedValidator::onObjectsAndObstaclePointCloud( } } -std::optional ObstaclePointCloudBasedValidator::getPointCloudNumWithinPolygon( - const autoware_auto_perception_msgs::msg::DetectedObject & object, - const pcl::PointCloud::Ptr pointcloud) -{ - pcl::PointCloud::Ptr cropped_pointcloud(new pcl::PointCloud); - std::vector vertices_array; - pcl::Vertices vertices; - - Polygon2d poly2d = - tier4_autoware_utils::toPolygon2d(object.kinematics.pose_with_covariance.pose, object.shape); - if (bg::is_empty(poly2d)) return std::nullopt; - - pcl::PointCloud::Ptr poly3d(new pcl::PointCloud); - - for (size_t i = 0; i < poly2d.outer().size(); ++i) { - vertices.vertices.emplace_back(i); - vertices_array.emplace_back(vertices); - poly3d->emplace_back(poly2d.outer().at(i).x(), poly2d.outer().at(i).y(), 0.0); - } - - pcl::CropHull cropper; // don't be implemented PointXY by PCL - cropper.setInputCloud(toXYZ(pointcloud)); - cropper.setDim(2); - cropper.setHullIndices(vertices_array); - cropper.setHullCloud(poly3d); - cropper.setCropOutside(true); - cropper.filter(*cropped_pointcloud); - - if (debugger_) debugger_->addPointcloudWithinPolygon(cropped_pointcloud); - return cropped_pointcloud->size(); -} - -std::optional ObstaclePointCloudBasedValidator::getMaxRadius( - const autoware_auto_perception_msgs::msg::DetectedObject & object) -{ - if (object.shape.type == Shape::BOUNDING_BOX || object.shape.type == Shape::CYLINDER) { - return std::hypot(object.shape.dimensions.x * 0.5f, object.shape.dimensions.y * 0.5f); - } else if (object.shape.type == Shape::POLYGON) { - float max_dist = 0.0; - for (const auto & point : object.shape.footprint.points) { - const float dist = std::hypot(point.x, point.y); - max_dist = max_dist < dist ? dist : max_dist; - } - return max_dist; - } else { - RCLCPP_WARN_THROTTLE(this->get_logger(), *this->get_clock(), 5000, "unknown shape type"); - return std::nullopt; - } -} - } // namespace obstacle_pointcloud_based_validator #include From fa5d7dbb417f62e6944a296dc36da1ffa5336f99 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 16 Nov 2023 00:09:19 +0900 Subject: [PATCH 194/202] fix(goal_planner): fix detection_polygons visualiztion (#5596) --- .../src/scene_module/goal_planner/goal_planner_module.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index 84b4032cde4ad..6b363f206204c 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -1752,16 +1752,16 @@ void GoalPlannerModule::setDebugData() "map", rclcpp::Clock{RCL_ROS_TIME}.now(), "detection_polygons", 0, Marker::LINE_LIST, tier4_autoware_utils::createMarkerScale(0.01, 0.0, 0.0), tier4_autoware_utils::createMarkerColor(0.0, 0.0, 1.0, 0.999)); - + const double ego_z = planner_data_->self_odometry->pose.pose.position.z; for (const auto & ego_polygon : debug_data_.ego_polygons_expanded) { for (size_t ep_idx = 0; ep_idx < ego_polygon.outer().size(); ++ep_idx) { const auto & current_point = ego_polygon.outer().at(ep_idx); const auto & next_point = ego_polygon.outer().at((ep_idx + 1) % ego_polygon.outer().size()); marker.points.push_back( - tier4_autoware_utils::createPoint(current_point.x(), current_point.y(), 0.0)); + tier4_autoware_utils::createPoint(current_point.x(), current_point.y(), ego_z)); marker.points.push_back( - tier4_autoware_utils::createPoint(next_point.x(), next_point.y(), 0.0)); + tier4_autoware_utils::createPoint(next_point.x(), next_point.y(), ego_z)); } } debug_marker_.markers.push_back(marker); From 540622106037d5100db22fb859250226d16177bb Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Wed, 15 Nov 2023 18:10:28 +0300 Subject: [PATCH 195/202] ci(sync-files): remove stale label pre-commands (#5597) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .github/sync-files.yaml | 2 -- 1 file changed, 2 deletions(-) diff --git a/.github/sync-files.yaml b/.github/sync-files.yaml index 4d316b9fb2481..5b60a371abd93 100644 --- a/.github/sync-files.yaml +++ b/.github/sync-files.yaml @@ -12,8 +12,6 @@ - source: .github/PULL_REQUEST_TEMPLATE/standard-change.md - source: .github/dependabot.yaml - source: .github/stale.yml - pre-commands: | - sd "staleLabel: stale" "staleLabel: status:stale" {source} - source: .github/workflows/cancel-previous-workflows.yaml - source: .github/workflows/github-release.yaml - source: .github/workflows/pre-commit.yaml From 7fb4b68e9ed268bea07d3f5aef8f7e4b6e5f0de7 Mon Sep 17 00:00:00 2001 From: Tomohito ANDO Date: Thu, 16 Nov 2023 00:21:30 +0900 Subject: [PATCH 196/202] chore(run_out): add maintainer (#5598) Signed-off-by: Tomohito Ando --- planning/behavior_velocity_run_out_module/package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/planning/behavior_velocity_run_out_module/package.xml b/planning/behavior_velocity_run_out_module/package.xml index fb3c49bb750a6..7bd27fca3407c 100644 --- a/planning/behavior_velocity_run_out_module/package.xml +++ b/planning/behavior_velocity_run_out_module/package.xml @@ -9,6 +9,7 @@ Makoto Kurihara Tomoya Kimura Shumpei Wakabayashi + Takayuki Murooka Apache License 2.0 From 2a1ad67b12f89f8e6b10995616b37890581cec98 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 16 Nov 2023 03:54:21 +0900 Subject: [PATCH 197/202] fix(goal_planner): fix extending current lanes (#5595) * fix(goal_planner): fix extending current lanes Signed-off-by: kosuke55 * fix build error Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 --- .../goal_planner/goal_planner_module.cpp | 22 ++++++++++--------- 1 file changed, 12 insertions(+), 10 deletions(-) diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index 6b363f206204c..a0a84adfcf6f8 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -1064,9 +1064,10 @@ PathWithLaneId GoalPlannerModule::generateStopPath() const const double current_vel = planner_data_->self_odometry->twist.twist.linear.x; const double pull_over_velocity = parameters_->pull_over_velocity; - const auto current_lanes = utils::getExtendedCurrentLanes( - planner_data_, common_parameters.backward_path_length, std::numeric_limits::max(), - /*forward_only_in_route*/ true); + const lanelet::ConstLanelets current_lanes = utils::getExtendedCurrentLanes( + planner_data_, parameters_->backward_goal_search_length, + parameters_->forward_goal_search_length, + /*forward_only_in_route*/ false); if (current_lanes.empty()) { return PathWithLaneId{}; @@ -1152,9 +1153,10 @@ PathWithLaneId GoalPlannerModule::generateFeasibleStopPath() const const auto & common_parameters = planner_data_->parameters; // generate stop reference path - const auto current_lanes = utils::getExtendedCurrentLanes( - planner_data_, common_parameters.backward_path_length, std::numeric_limits::max(), - /*forward_only_in_route*/ true); + const lanelet::ConstLanelets current_lanes = utils::getExtendedCurrentLanes( + planner_data_, parameters_->backward_goal_search_length, + parameters_->forward_goal_search_length, + /*forward_only_in_route*/ false); const auto s_current = lanelet::utils::getArcCoordinates(current_lanes, current_pose).length; const double s_start = std::max(0.0, s_current - common_parameters.backward_path_length); const double s_end = s_current + common_parameters.forward_path_length; @@ -1621,10 +1623,10 @@ bool GoalPlannerModule::isSafePath() const planner_data_->self_odometry->twist.twist.linear.y); const auto & dynamic_object = planner_data_->dynamic_object; const auto & route_handler = planner_data_->route_handler; - const double backward_path_length = planner_data_->parameters.backward_path_length; - const auto current_lanes = utils::getExtendedCurrentLanes( - planner_data_, backward_path_length, std::numeric_limits::max(), - /*forward_only_in_route*/ true); + const lanelet::ConstLanelets current_lanes = utils::getExtendedCurrentLanes( + planner_data_, parameters_->backward_goal_search_length, + parameters_->forward_goal_search_length, + /*forward_only_in_route*/ false); const auto pull_over_lanes = goal_planner_utils::getPullOverLanes( *route_handler, left_side_parking_, parameters_->backward_goal_search_length, parameters_->forward_goal_search_length); From 7c6666051157d2f26572144296700eb1238f4f08 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 16 Nov 2023 09:27:35 +0900 Subject: [PATCH 198/202] fix(geo_pose_projector): fix -Werror=deprecated-declarations (#5599) Signed-off-by: satoshi-ota --- localization/geo_pose_projector/src/geo_pose_projector.cpp | 5 +++-- localization/geo_pose_projector/src/geo_pose_projector.hpp | 2 +- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/localization/geo_pose_projector/src/geo_pose_projector.cpp b/localization/geo_pose_projector/src/geo_pose_projector.cpp index 6d5308b929b25..d147888bb743b 100644 --- a/localization/geo_pose_projector/src/geo_pose_projector.cpp +++ b/localization/geo_pose_projector/src/geo_pose_projector.cpp @@ -36,7 +36,8 @@ GeoPoseProjector::GeoPoseProjector() // Subscribe to geo_pose topic geo_pose_sub_ = create_subscription( - "input_geo_pose", 10, [this](const GeoPoseWithCovariance::SharedPtr msg) { on_geo_pose(msg); }); + "input_geo_pose", 10, + [this](const GeoPoseWithCovariance::ConstSharedPtr msg) { on_geo_pose(msg); }); // Publish pose topic pose_pub_ = create_publisher("output_pose", 10); @@ -49,7 +50,7 @@ GeoPoseProjector::GeoPoseProjector() } } -void GeoPoseProjector::on_geo_pose(const GeoPoseWithCovariance::SharedPtr msg) +void GeoPoseProjector::on_geo_pose(const GeoPoseWithCovariance::ConstSharedPtr msg) { if (!projector_info_) { RCLCPP_WARN_THROTTLE( diff --git a/localization/geo_pose_projector/src/geo_pose_projector.hpp b/localization/geo_pose_projector/src/geo_pose_projector.hpp index b24b976b1eb61..b0611fec36984 100644 --- a/localization/geo_pose_projector/src/geo_pose_projector.hpp +++ b/localization/geo_pose_projector/src/geo_pose_projector.hpp @@ -39,7 +39,7 @@ class GeoPoseProjector : public rclcpp::Node GeoPoseProjector(); private: - void on_geo_pose(const GeoPoseWithCovariance::SharedPtr msg); + void on_geo_pose(const GeoPoseWithCovariance::ConstSharedPtr msg); component_interface_utils::Subscription::SharedPtr sub_map_projector_info_; rclcpp::Subscription::SharedPtr geo_pose_sub_; From 12739923ff05fe6cc18ff37e596fdd4ffa8764d9 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 16 Nov 2023 11:03:59 +0900 Subject: [PATCH 199/202] refactor(goal_planner): refactor select path (#5559) Signed-off-by: kosuke55 --- .../goal_planner/goal_planner_module.hpp | 36 ++++- .../goal_planner/goal_planner_module.cpp | 135 +++++++++--------- 2 files changed, 100 insertions(+), 71 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp index 2e95ca82735fb..d647caeabbc44 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp @@ -168,20 +168,39 @@ class ThreadSafeData return false; } - void set_pull_over_path(const PullOverPath & value) + void set_pull_over_path(const PullOverPath & path) { const std::lock_guard lock(mutex_); - pull_over_path_ = std::make_shared(value); + pull_over_path_ = std::make_shared(path); + if (path.type != PullOverPlannerType::NONE && path.type != PullOverPlannerType::FREESPACE) { + lane_parking_pull_over_path_ = std::make_shared(path); + } + last_path_update_time_ = clock_->now(); } - void set_pull_over_path(const std::shared_ptr & value) + void set_pull_over_path(const std::shared_ptr & path) { const std::lock_guard lock(mutex_); - pull_over_path_ = value; + pull_over_path_ = path; + if (path->type != PullOverPlannerType::NONE && path->type != PullOverPlannerType::FREESPACE) { + lane_parking_pull_over_path_ = path; + } last_path_update_time_ = clock_->now(); } + template + void set(Args... args) + { + std::lock_guard lock(mutex_); + (..., set(args)); + } + void set(const GoalCandidates & arg) { set_goal_candidates(arg); } + void set(const std::vector & arg) { set_pull_over_path_candidates(arg); } + void set(const std::shared_ptr & arg) { set_pull_over_path(arg); } + void set(const PullOverPath & arg) { set_pull_over_path(arg); } + void set(const GoalCandidate & arg) { set_modified_goal_pose(arg); } + void clearPullOverPath() { const std::lock_guard lock(mutex_); @@ -221,6 +240,7 @@ class ThreadSafeData } DEFINE_GETTER_WITH_MUTEX(std::shared_ptr, pull_over_path) + DEFINE_GETTER_WITH_MUTEX(std::shared_ptr, lane_parking_pull_over_path) DEFINE_GETTER_WITH_MUTEX(std::optional, last_path_update_time) DEFINE_GETTER_WITH_MUTEX(std::optional, last_path_idx_increment_time) @@ -231,6 +251,7 @@ class ThreadSafeData private: std::shared_ptr pull_over_path_{nullptr}; + std::shared_ptr lane_parking_pull_over_path_{nullptr}; std::vector pull_over_path_candidates_; GoalCandidates goal_candidates_{}; std::optional modified_goal_pose_; @@ -394,6 +415,7 @@ class GoalPlannerModule : public SceneModuleInterface void generateGoalCandidates(); // stop or decelerate + void deceleratePath(PullOverPath & pull_over_path) const; void decelerateForTurnSignal(const Pose & stop_pose, PathWithLaneId & path) const; void decelerateBeforeSearchStart( const Pose & search_start_offset_pose, PathWithLaneId & path) const; @@ -428,13 +450,15 @@ class GoalPlannerModule : public SceneModuleInterface // freespace parking bool planFreespacePath(); - void returnToLaneParking(); + bool canReturnToLaneParking(); // plan pull over path BehaviorModuleOutput planPullOver(); BehaviorModuleOutput planPullOverAsOutput(); BehaviorModuleOutput planPullOverAsCandidate(); - void selectSafePullOverPath(); + std::optional> selectPullOverPath( + const std::vector & pull_over_path_candidates, + const GoalCandidates & goal_candidates) const; std::vector sortPullOverPathCandidatesByGoalPriority( const std::vector & pull_over_path_candidates, const GoalCandidates & goal_candidates) const; diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index a0a84adfcf6f8..ba846efbb0a50 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -54,7 +54,7 @@ namespace behavior_path_planner GoalPlannerModule::GoalPlannerModule( const std::string & name, rclcpp::Node & node, const std::shared_ptr & parameters, - const std::unordered_map > & rtc_interface_ptr_map) + const std::unordered_map> & rtc_interface_ptr_map) : SceneModuleInterface{name, node, rtc_interface_ptr_map}, parameters_{parameters}, vehicle_info_{vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo()}, @@ -518,20 +518,20 @@ bool GoalPlannerModule::planFreespacePath() return false; } -void GoalPlannerModule::returnToLaneParking() +bool GoalPlannerModule::canReturnToLaneParking() { // return only before starting free space parking if (!isStopped()) { - return; + return false; } - if (!status_.get_lane_parking_pull_over_path()) { - return; + if (!thread_safe_data_.get_lane_parking_pull_over_path()) { + return false; } - const PathWithLaneId path = status_.get_lane_parking_pull_over_path()->getFullPath(); + const PathWithLaneId path = thread_safe_data_.get_lane_parking_pull_over_path()->getFullPath(); if (checkCollision(path)) { - return; + return false; } const Point & current_point = planner_data_->self_odometry->pose.pose.position; @@ -539,11 +539,10 @@ void GoalPlannerModule::returnToLaneParking() const bool is_close_to_path = std::abs(motion_utils::calcLateralOffset(path.points, current_point)) < th_distance; if (!is_close_to_path) { - return; + return false; } - thread_safe_data_.set_pull_over_path(status_.get_lane_parking_pull_over_path()); - RCLCPP_INFO(getLogger(), "return to lane parking"); + return true; } void GoalPlannerModule::generateGoalCandidates() @@ -619,23 +618,10 @@ std::vector GoalPlannerModule::sortPullOverPathCandidatesByGoalPri return sorted_pull_over_path_candidates; } -void GoalPlannerModule::selectSafePullOverPath() +std::optional> GoalPlannerModule::selectPullOverPath( + const std::vector & pull_over_path_candidates, + const GoalCandidates & goal_candidates) const { - // select safe lane pull over path from candidates - std::vector pull_over_path_candidates{}; - GoalCandidates goal_candidates{}; - { - const std::lock_guard lock(mutex_); - goal_searcher_->setPlannerData(planner_data_); - goal_candidates = thread_safe_data_.get_goal_candidates(); - goal_searcher_->update(goal_candidates); - thread_safe_data_.set_goal_candidates(goal_candidates); - thread_safe_data_.set_pull_over_path_candidates(sortPullOverPathCandidatesByGoalPriority( - thread_safe_data_.get_pull_over_path_candidates(), thread_safe_data_.get_goal_candidates())); - pull_over_path_candidates = thread_safe_data_.get_pull_over_path_candidates(); - thread_safe_data_.clearPullOverPath(); - } - for (const auto & pull_over_path : pull_over_path_candidates) { // check if goal is safe const auto goal_candidate_it = std::find_if( @@ -654,42 +640,10 @@ void GoalPlannerModule::selectSafePullOverPath() continue; } - // found safe pull over path - { - const std::lock_guard lock(mutex_); - thread_safe_data_.set_pull_over_path(pull_over_path); - thread_safe_data_.set_modified_goal_pose(*goal_candidate_it); - status_.set_lane_parking_pull_over_path(thread_safe_data_.get_pull_over_path()); - } - break; + return std::make_pair(pull_over_path, *goal_candidate_it); } - if (!thread_safe_data_.foundPullOverPath()) { - return; - } - - // decelerate before the search area start - const auto decel_pose = calcLongitudinalOffsetPose( - thread_safe_data_.get_pull_over_path()->getFullPath().points, - status_.get_closest_goal_candidate_pose().position, -approximate_pull_over_distance_); - auto & first_path = thread_safe_data_.get_pull_over_path()->partial_paths.front(); - if (decel_pose) { - decelerateBeforeSearchStart(*decel_pose, first_path); - return; - } - - // if already passed the search start offset pose, set pull_over_velocity to first_path. - const auto min_decel_distance = calcFeasibleDecelDistance( - planner_data_, parameters_->maximum_deceleration, parameters_->maximum_jerk, - parameters_->pull_over_velocity); - for (auto & p : first_path.points) { - const double distance_from_ego = calcSignedArcLengthFromEgo(first_path, p.point.pose); - if (min_decel_distance && distance_from_ego < *min_decel_distance) { - continue; - } - p.point.longitudinal_velocity_mps = std::min( - p.point.longitudinal_velocity_mps, static_cast(parameters_->pull_over_velocity)); - } + return {}; } std::vector GoalPlannerModule::generateDrivableLanes() const @@ -847,7 +801,7 @@ void GoalPlannerModule::updateSteeringFactor( } // NOTE: Once this function returns true, it will continue to return true thereafter. Because -// selectSafePullOverPath() will not select new path. +// selectPullOverPath() will not select new path. bool GoalPlannerModule::hasDecidedPath() const { // if path is not safe, not decided @@ -928,8 +882,31 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput() if (!hasDecidedPath() && needPathUpdate(1.0 /*path_update_duration*/)) { // if the final path is not decided and enough time has passed since last path update, // select safe path from lane parking pull over path candidates - // and set it to thread_safe_data_.get_pull_over_path() - selectSafePullOverPath(); + // and set it to thread_safe_data_ + + thread_safe_data_.clearPullOverPath(); + + // update goal candidates + goal_searcher_->setPlannerData(planner_data_); + auto goal_candidates = thread_safe_data_.get_goal_candidates(); + goal_searcher_->update(goal_candidates); + + // update pull over path candidates + const auto pull_over_path_candidates = sortPullOverPathCandidatesByGoalPriority( + thread_safe_data_.get_pull_over_path_candidates(), goal_candidates); + + // select pull over path which is safe against static objects and get it's goal + const auto path_and_goal_opt = selectPullOverPath(pull_over_path_candidates, goal_candidates); + + // update thread_safe_data_ + if (path_and_goal_opt) { + auto [pull_over_path, modified_goal] = *path_and_goal_opt; + deceleratePath(pull_over_path); + thread_safe_data_.set( + goal_candidates, pull_over_path_candidates, pull_over_path, modified_goal); + } else { + thread_safe_data_.set(goal_candidates, pull_over_path_candidates); + } } // set output and status @@ -937,8 +914,10 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput() setOutput(output); // return to lane parking if it is possible - if (thread_safe_data_.getPullOverPlannerType() == PullOverPlannerType::FREESPACE) { - returnToLaneParking(); + if ( + thread_safe_data_.getPullOverPlannerType() == PullOverPlannerType::FREESPACE && + canReturnToLaneParking()) { + thread_safe_data_.set_pull_over_path(thread_safe_data_.get_lane_parking_pull_over_path()); } // For debug @@ -1450,6 +1429,32 @@ double GoalPlannerModule::calcSignedArcLengthFromEgo( path.points, current_pose.position, ego_idx, pose.position, target_idx); } +void GoalPlannerModule::deceleratePath(PullOverPath & pull_over_path) const +{ + // decelerate before the search area start + const auto decel_pose = calcLongitudinalOffsetPose( + pull_over_path.getFullPath().points, status_.get_closest_goal_candidate_pose().position, + -approximate_pull_over_distance_); + auto & first_path = pull_over_path.partial_paths.front(); + if (decel_pose) { + decelerateBeforeSearchStart(*decel_pose, first_path); + return; + } + + // if already passed the search start offset pose, set pull_over_velocity to first_path. + const auto min_decel_distance = calcFeasibleDecelDistance( + planner_data_, parameters_->maximum_deceleration, parameters_->maximum_jerk, + parameters_->pull_over_velocity); + for (auto & p : first_path.points) { + const double distance_from_ego = calcSignedArcLengthFromEgo(first_path, p.point.pose); + if (min_decel_distance && distance_from_ego < *min_decel_distance) { + continue; + } + p.point.longitudinal_velocity_mps = std::min( + p.point.longitudinal_velocity_mps, static_cast(parameters_->pull_over_velocity)); + } +} + void GoalPlannerModule::decelerateForTurnSignal(const Pose & stop_pose, PathWithLaneId & path) const { const double time = planner_data_->parameters.turn_signal_search_time; From 3876716d123e8da5607ed11ebd015475f6a98cc1 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 16 Nov 2023 11:48:38 +0900 Subject: [PATCH 200/202] feat(lane_departure_checker): better cubstones's search (#5582) * feat(lane_departure_checker): better cubstones's search Signed-off-by: Takayuki Murooka * update Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../lane_departure_checker.hpp | 15 ++- .../lane_departure_checker.cpp | 114 +++++++++--------- 2 files changed, 65 insertions(+), 64 deletions(-) diff --git a/control/lane_departure_checker/include/lane_departure_checker/lane_departure_checker.hpp b/control/lane_departure_checker/include/lane_departure_checker/lane_departure_checker.hpp index c77503106e485..dc55576640133 100644 --- a/control/lane_departure_checker/include/lane_departure_checker/lane_departure_checker.hpp +++ b/control/lane_departure_checker/include/lane_departure_checker/lane_departure_checker.hpp @@ -29,6 +29,7 @@ #include #include +#include #include #include @@ -46,7 +47,9 @@ using autoware_auto_planning_msgs::msg::TrajectoryPoint; using autoware_planning_msgs::msg::LaneletRoute; using tier4_autoware_utils::LinearRing2d; using tier4_autoware_utils::PoseDeviation; +using tier4_autoware_utils::Segment2d; using TrajectoryPoints = std::vector; +typedef boost::geometry::index::rtree> SegmentRtree; struct Param { @@ -137,13 +140,15 @@ class LaneDepartureChecker const lanelet::ConstLanelets & candidate_lanelets, const std::vector & vehicle_footprints); + double calcMaxSearchLengthForBoundaries(const Trajectory & trajectory) const; + + static SegmentRtree extractUncrossableBoundaries( + const lanelet::LaneletMap & lanelet_map, const geometry_msgs::msg::Point & ego_point, + const double max_search_length, const std::vector & boundary_types_to_detect); + static bool willCrossBoundary( - const lanelet::ConstLanelets & candidate_lanelets, const std::vector & vehicle_footprints, - const std::vector & boundary_types_to_detects); - - static bool isCrossingRoadBorder( - const lanelet::BasicLineString2d & road_border, const std::vector & footprints); + const SegmentRtree & uncrossable_segments); }; } // namespace lane_departure_checker diff --git a/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp b/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp index 9d413b2bf0a70..5bd0fcace9909 100644 --- a/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp +++ b/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp @@ -30,7 +30,9 @@ #include #include +using motion_utils::calcArcLength; using tier4_autoware_utils::LinearRing2d; +using tier4_autoware_utils::LineString2d; using tier4_autoware_utils::MultiPoint2d; using tier4_autoware_utils::Point2d; @@ -41,15 +43,6 @@ using autoware_auto_planning_msgs::msg::TrajectoryPoint; using TrajectoryPoints = std::vector; using geometry_msgs::msg::Point; -Point fromVector2dToMsg(const Eigen::Vector2d & point) -{ - Point msg{}; - msg.x = point.x(); - msg.y = point.y(); - msg.z = 0.0; - return msg; -} - double calcBrakingDistance( const double abs_velocity, const double max_deceleration, const double delay_time) { @@ -67,27 +60,6 @@ bool isInAnyLane(const lanelet::ConstLanelets & candidate_lanelets, const Point2 return false; } -bool isCrossingWithBoundary( - const lanelet::BasicLineString2d & boundary, const std::vector & footprints) -{ - for (auto & footprint : footprints) { - for (size_t i = 0; i < footprint.size() - 1; ++i) { - auto footprint1 = footprint.at(i).to_3d(); - auto footprint2 = footprint.at(i + 1).to_3d(); - for (size_t i = 0; i < boundary.size() - 1; ++i) { - auto boundary1 = boundary.at(i); - auto boundary2 = boundary.at(i + 1); - if (tier4_autoware_utils::intersect( - tier4_autoware_utils::toMsg(footprint1), tier4_autoware_utils::toMsg(footprint2), - fromVector2dToMsg(boundary1), fromVector2dToMsg(boundary2))) { - return true; - } - } - } - } - return false; -} - LinearRing2d createHullFromFootprints(const std::vector & footprints) { MultiPoint2d combined; @@ -172,8 +144,12 @@ Output LaneDepartureChecker::update(const Input & input) output.is_out_of_lane = isOutOfLane(output.candidate_lanelets, output.vehicle_footprints.front()); output.processing_time_map["isOutOfLane"] = stop_watch.toc(true); - output.will_cross_boundary = willCrossBoundary( - output.candidate_lanelets, output.vehicle_footprints, input.boundary_types_to_detect); + const double max_search_length_for_boundaries = + calcMaxSearchLengthForBoundaries(*input.predicted_trajectory); + const auto uncrossable_boundaries = extractUncrossableBoundaries( + *input.lanelet_map, input.predicted_trajectory->points.front().pose.position, + max_search_length_for_boundaries, input.boundary_types_to_detect); + output.will_cross_boundary = willCrossBoundary(output.vehicle_footprints, uncrossable_boundaries); output.processing_time_map["willCrossBoundary"] = stop_watch.toc(true); return output; @@ -334,38 +310,58 @@ bool LaneDepartureChecker::isOutOfLane( return false; } -bool LaneDepartureChecker::willCrossBoundary( - const lanelet::ConstLanelets & candidate_lanelets, - const std::vector & vehicle_footprints, - const std::vector & boundary_types_to_detect) +double LaneDepartureChecker::calcMaxSearchLengthForBoundaries(const Trajectory & trajectory) const { - for (const auto & candidate_lanelet : candidate_lanelets) { - const std::string r_type = - candidate_lanelet.rightBound().attributeOr(lanelet::AttributeName::Type, "none"); - if ( - std::find(boundary_types_to_detect.begin(), boundary_types_to_detect.end(), r_type) != - boundary_types_to_detect.end()) { - if (isCrossingWithBoundary( - candidate_lanelet.rightBound2d().basicLineString(), vehicle_footprints)) { - // std::cerr << "The crossed road_border's line string id: " - // << candidate_lanelet.rightBound().id() << std::endl; - return true; + const double max_ego_lon_length = std::max( + std::abs(vehicle_info_ptr_->max_longitudinal_offset_m), + std::abs(vehicle_info_ptr_->min_longitudinal_offset_m)); + const double max_ego_lat_length = std::max( + std::abs(vehicle_info_ptr_->max_lateral_offset_m), + std::abs(vehicle_info_ptr_->min_lateral_offset_m)); + const double max_ego_search_length = std::hypot(max_ego_lon_length, max_ego_lat_length); + return calcArcLength(trajectory.points) + max_ego_search_length; +} + +SegmentRtree LaneDepartureChecker::extractUncrossableBoundaries( + const lanelet::LaneletMap & lanelet_map, const geometry_msgs::msg::Point & ego_point, + const double max_search_length, const std::vector & boundary_types_to_detect) +{ + const auto has_types = + [](const lanelet::ConstLineString3d & ls, const std::vector & types) { + constexpr auto no_type = ""; + const auto type = ls.attributeOr(lanelet::AttributeName::Type, no_type); + return (type != no_type && std::find(types.begin(), types.end(), type) != types.end()); + }; + + SegmentRtree uncrossable_segments_in_range; + LineString2d line; + const auto ego_p = Point2d{ego_point.x, ego_point.y}; + for (const auto & ls : lanelet_map.lineStringLayer) { + if (has_types(ls, boundary_types_to_detect)) { + line.clear(); + for (const auto & p : ls) line.push_back(Point2d{p.x(), p.y()}); + for (auto segment_idx = 0LU; segment_idx + 1 < line.size(); ++segment_idx) { + const Segment2d segment = {line[segment_idx], line[segment_idx + 1]}; + if (boost::geometry::distance(segment, ego_p) < max_search_length) { + uncrossable_segments_in_range.insert(segment); + } } } - const std::string l_type = - candidate_lanelet.leftBound().attributeOr(lanelet::AttributeName::Type, "none"); - if ( - std::find(boundary_types_to_detect.begin(), boundary_types_to_detect.end(), l_type) != - boundary_types_to_detect.end()) { - if (isCrossingWithBoundary( - candidate_lanelet.leftBound2d().basicLineString(), vehicle_footprints)) { - // std::cerr << "The crossed road_border's line string id: " - // << candidate_lanelet.leftBound().id() << std::endl; - return true; - } + } + return uncrossable_segments_in_range; +} + +bool LaneDepartureChecker::willCrossBoundary( + const std::vector & vehicle_footprints, const SegmentRtree & uncrossable_segments) +{ + for (const auto & footprint : vehicle_footprints) { + std::vector intersection_result; + uncrossable_segments.query( + boost::geometry::index::intersects(footprint), std::back_inserter(intersection_result)); + if (!intersection_result.empty()) { + return true; } } return false; } - } // namespace lane_departure_checker From 86858e5d2185cda186e3923e0008d71528147729 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Thu, 16 Nov 2023 12:10:23 +0900 Subject: [PATCH 201/202] build(tier4_perception_launch): add tracking_object_merger (#5602) Signed-off-by: kminoda --- launch/tier4_perception_launch/package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/launch/tier4_perception_launch/package.xml b/launch/tier4_perception_launch/package.xml index 336588891d9b2..7e6ba83747a8b 100644 --- a/launch/tier4_perception_launch/package.xml +++ b/launch/tier4_perception_launch/package.xml @@ -39,6 +39,7 @@ shape_estimation tensorrt_yolo topic_tools + tracking_object_merger traffic_light_arbiter traffic_light_classifier traffic_light_fine_detector From 854319ea15cdd09d7d8f339791eca785747610fe Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 16 Nov 2023 15:15:14 +0900 Subject: [PATCH 202/202] fix(avoidance): fix avoidance exit condition (#5592) Signed-off-by: satoshi-ota --- .../src/scene_module/avoidance/avoidance_module.cpp | 13 +++++++++++++ 1 file changed, 13 insertions(+) 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 2d85f8cbe3224..46dfd93d83432 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 @@ -222,6 +222,19 @@ bool AvoidanceModule::canTransitSuccessState() const bool has_base_offset = std::abs(path_shifter_.getBaseOffset()) > parameters_->lateral_avoid_check_threshold; + // If the vehicle is on the shift line, keep RUNNING. + { + const size_t idx = planner_data_->findEgoIndex(path_shifter_.getReferencePath().points); + const auto within = [](const auto & line, const size_t idx) { + return line.start_idx < idx && idx < line.end_idx; + }; + for (const auto & shift_line : path_shifter_.getShiftLines()) { + if (within(shift_line, idx)) { + return false; + } + } + } + // Nothing to do. -> EXIT. if (!has_avoidance_target) { if (!has_shift_point && !has_base_offset) {